diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index b7d654f..3b1d0e2 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -1,49 +1,49 @@ -name: CI - -on: - push: - branches: [ main ] - pull_request: - branches: [ main ] - -jobs: - build: - - runs-on: ubuntu-20.04 - - steps: - - uses: actions/checkout@v3 - - name: install - run: | - sudo apt-get update - sudo apt-get install -y g++-7 clang-8 ninja-build python3-pip libboost-python-dev libtiff5-dev libjpeg-dev libgeos-dev - - name: clone vanilla Carla - run: | - git clone https://github.com/carla-simulator/carla --depth 1 -b 0.9.13 - - name: DReyeVR install - run: | - make install CARLA=carla - - name: DReyeVR check - run: | - make check CARLA=carla - - name: get Python requirements - working-directory: ./carla - run: | - pip3 install -q --user setuptools - pip3 install -q --user -r PythonAPI/test/requirements.txt - pip3 install -q --user -r PythonAPI/carla/requirements.txt - - name: Initial Carla setup - working-directory: ./carla - run: make setup - - name: Build LibCarla - working-directory: ./carla - run: make LibCarla - - name: Build Carla PythonAPI - working-directory: ./carla - run: make PythonAPI - - name: Build Carla examples - working-directory: ./carla - run: make examples - - name: Run Carla Unit tests - working-directory: ./carla - run: make check ARGS="--all --gtest_args=--gtest_filter=-*_mt" +name: CI + +on: + push: + branches: [ main ] + pull_request: + branches: [ main ] + +jobs: + build: + + runs-on: ubuntu-20.04 + + steps: + - uses: actions/checkout@v3 + - name: install + run: | + sudo apt-get update + sudo apt-get install -y g++-7 clang-8 ninja-build python3-pip libboost-python-dev libtiff5-dev libjpeg-dev libgeos-dev + - name: clone vanilla Carla + run: | + git clone https://github.com/carla-simulator/carla --depth 1 -b 0.9.13 + - name: DReyeVR install + run: | + make install CARLA=carla + - name: DReyeVR check + run: | + make check CARLA=carla + - name: get Python requirements + working-directory: ./carla + run: | + pip3 install -q --user setuptools + pip3 install -q --user -r PythonAPI/test/requirements.txt + pip3 install -q --user -r PythonAPI/carla/requirements.txt + - name: Initial Carla setup + working-directory: ./carla + run: make setup + - name: Build LibCarla + working-directory: ./carla + run: make LibCarla + - name: Build Carla PythonAPI + working-directory: ./carla + run: make PythonAPI + - name: Build Carla examples + working-directory: ./carla + run: make examples + - name: Run Carla Unit tests + working-directory: ./carla + run: make check ARGS="--all --gtest_args=--gtest_filter=-*_mt" diff --git a/.gitignore b/.gitignore index 705165c..5560699 100644 --- a/.gitignore +++ b/.gitignore @@ -1,12 +1,213 @@ -.vscode/ -cache/ -Backups* -Scripts/__pycache__ -Tools/Diagnostics/python/data/ -Tools/Diagnostics/results/ -Tools/LOD/WindowsLODs/ -Tools/LOD/WindowsLODs.zip -Tools/LOD/LinuxLODs/ -Tools/LOD/LinuxLODs.zip -Tools/LOD/OriginalLODs/ -Tools/LOD/OriginalLODs.zip \ No newline at end of file +### Python ### +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py,cover +.hypothesis/ +.pytest_cache/ +cover/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +.pybuilder/ +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +# For a library or package, you might want to ignore these files since the code is +# intended to run in multiple environments; otherwise, check them in: +# .python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# poetry +# Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +# https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control +#poetry.lock + +# pdm +# Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control. +#pdm.lock +# pdm stores project-wide configurations in .pdm.toml, but it is recommended to not include it +# in version control. +# https://pdm.fming.dev/#use-with-ide +.pdm.toml + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# SageMath parsed files +*.sage.py + +# Environments +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# pytype static type analyzer +.pytype/ + +# Cython debug symbols +cython_debug/ + +# PyCharm +# JetBrains specific template is maintained in a separate JetBrains.gitignore that can +# be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore +# and can be added to the global gitignore or merged into this file. For a more nuclear +# option (not recommended) you can uncomment the following to ignore the entire idea folder. +#.idea/ + +### Python Patch ### +# Poetry local configuration file - https://python-poetry.org/docs/configuration/#local-configuration +poetry.toml + +# ruff +.ruff_cache/ + +# LSP config files +pyrightconfig.json + +### Windows ### +# Windows thumbnail cache files +Thumbs.db +Thumbs.db:encryptable +ehthumbs.db +ehthumbs_vista.db + +# Dump file +*.stackdump + +# Folder config file +[Dd]esktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msix +*.msm +*.msp + +# Windows shortcuts +*.lnk +.vscode/ +cache/ +Backups* +Scripts/__pycache__ +Tools/Diagnostics/python/data/ +Tools/Diagnostics/results/ +Tools/LOD/WindowsLODs/ +Tools/LOD/WindowsLODs.zip +Tools/LOD/LinuxLODs/ +Tools/LOD/LinuxLODs.zip +Tools/LOD/OriginalLODs/ +Tools/LOD/OriginalLODs.zip +*.png +*.pdf +*.mkv +*/plots/ \ No newline at end of file diff --git a/CHANGELOG.md b/CHANGELOG.md index 61bcf50..c2c34fa 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,51 +1,51 @@ -## DReyeVR 0.2.1 -- Adding smart (weak) pointers for the major DReyeVR class connections to ensure better pointer validity before dereference. Helps with detecting dangling (freed, but not-null) pointers which happens commonly during map changes and would otherwise crash the replay system. -- Adding PythonAPI startup function (namely a custom `__init__.py` script that is loaded when using `DReyeVR_utils.py`) -- Fix bug with shaders not being cooked in package mode -- Fine-tune ego-vehicle mirrors according to vehicle chassis -- Adding threshold for manual takeover of logitech inputs. Logitech wheel actuation follows autopilot otherwise. -- Disabling shadows for wheel face buttons -- Adding autopilot light indicator - -## DReyeVR 0.2.0 -- Add face button indicators on the steering wheel -- Revamping `ConfigFile` class rather than a static `ReadConfigFile` helper function -- Adding Config-file check as part of the tracked DReyeVRData, gives you a warning if your loaded ConfigFile is different from the one that was used during recording (so you can match your replay config with that which was recorded) -- Adding per-vehicle configuration files in `Content/DReyeVR/EgoVehicle` that can be selected via parameters. Allows parameterization of all EgoVehicle components, magic numbers (ex. location of camera, mirrors, engine), sound files, mirror meshes, steering wheel types, and enable/disable these on a highly granular basis -- Revamp EgoVehicle input controls to use parent (ACarlaWheeledVehicle) controls and flush -- Disabling (turning invisible) default Carla spectator in map -- Added tutorial for custom EgoVehicle - -## DReyeVR 0.1.3 -- Fix bug where other non-ego Autopilto vehicles ignored the EgoVehicle and would routinely crash into it -- Fix bug where some EgoVehicle attributes were missing, notably `"number_of_wheels"` - -## DReyeVR 0.1.2 -- Update documentation to refer to CarlaUnreal UE4 fork rather than HarpLab fork -- Apply patches for installation of zlib (broken link) and xerces (broken link & `-Dtranscoder=windows` flag) and PythonAPI -- Fix crash on BeginPlay when EgoVehicle blueprint is already present in map (before world start) -- Prefer building PythonAPI with `python` rather than Windows built-in `py -3` (good if using conda) but fallback if `python` is not available - -## DReyeVR 0.1.1 -- Update documentation, add developer-centric in-depth documentation -- Adding missing includes for TrafficSign RoadInfoSignal in SignComponent -- Replacing `DReyeVRData.inl` with `DReyeVRData.cpp` and corresponding virtual classes -- Add GitHub workflow for installing DReyeVR atop Carla and building LibCarla/PythonAPI (not CarlaUE4 which requires UnrealEngine) -- Fix bug where disabling mirrors causes a crash since the BP_model3 blueprint would be broken on construction -- Fix bug where replays would spawn another EgoVehicle/EgoSensor in the world (following the Carla spec) which caused multiple overlapping EgoVehicles to be in the world at once. Now we enforced in the Factory function that they are singletons -- Fix bug with replay interpolation not following our EgoVehicle by ticking the pose reenactment in the Carla tick rather than EgoVehicle::Tick -- Fix bug with spectator being reenacted by Carla, preferring to use our own ASpectator -- Automatically possess spectator pawn when EgoVehicle is destroyed. Can re-spawn EgoVehicle by pressing 1. - -## DReyeVR 0.1.0 -- Replace existing `LevelScript` (`ADReyeVRLevel`) with `GameMode` (`ADReyeVRGameMode`). This allows us to not need to carry the (large) map blueprint files (ue4 binary) and we can use the vanilla Carla maps without modification. By default we spawn the EgoVehicle in the first of the recommended Carla locations, but this default behavior can be changed in the PythonAPI. For instance, you can delay spawning the EgoVehicle until via PythonAPI where you can specify the spawn transform. Existing functionality is preserved using `find_ego_vehicle` and `find_ego_sensor` which spawn the DReyeVR EgoVehicle if it does not exist in the world. -- Added `ADReyeVRFactory` as the Carla-esque spawning and registry functionality so the `EgoVehicle` and `EgoSensor` are spawned with the same "Factory" mechanisms as existing Carla vehicles/sensors/props/etc. -- Renamed DReyeVR-specific actors to be addressible in PythonAPI as `"harplab.dreyevr_$X.$id"` such as `"harplab.dreyevr_vehicle.model3"` and `"harplab.dreyevr_sensor.ego_sensor"`. Avoids conflicts with existing Carla PythonAPI scripts that may filter on `"vehicle.*"`. -- Moved all blueprint (`.uasset`) content out of the Carla content (which is now entirely untouched, no need to re-update) to a separate Content folder that lies in `/Game/Content/DReyeVR/` (renamed to support future DReyeVR blueprint changes without relying on Carla content). -- Adding check that SRanipal is within one of our recommended supported versions: `1.3.1.1`, `1.3.2.0`, & `1.3.3.0`. Also provided links in the documentation to download these versions. Additionally included a workaround for the old `patch-sranipal` which is now no longer needed. -- Added custom `LogDReyeVR` macros (`LOG`, `LOG_WARN`, `LOG_ERROR`) for improved logging with attached file, function, and line number to the message. Done in precompilation to avoid runtime performance overhead. -- Improved `make check` to ensure that a 1:1 file correspondence exists between Carla dest and DReyeVR source, and that all files have equal content. -- Improved vehicle dash with blinking turn signal and fixed bugs with inconsistent gear indicator. -- Fixed bugs and inconsistencies with replayer media control and special actions such as toggling reverse/turn signals in replay. -- Enabled cooking for `Town06` and `Town07` in package/shipping mode. +## DReyeVR 0.2.1 +- Adding smart (weak) pointers for the major DReyeVR class connections to ensure better pointer validity before dereference. Helps with detecting dangling (freed, but not-null) pointers which happens commonly during map changes and would otherwise crash the replay system. +- Adding PythonAPI startup function (namely a custom `__init__.py` script that is loaded when using `DReyeVR_utils.py`) +- Fix bug with shaders not being cooked in package mode +- Fine-tune ego-vehicle mirrors according to vehicle chassis +- Adding threshold for manual takeover of logitech inputs. Logitech wheel actuation follows autopilot otherwise. +- Disabling shadows for wheel face buttons +- Adding autopilot light indicator + +## DReyeVR 0.2.0 +- Add face button indicators on the steering wheel +- Revamping `ConfigFile` class rather than a static `ReadConfigFile` helper function +- Adding Config-file check as part of the tracked DReyeVRData, gives you a warning if your loaded ConfigFile is different from the one that was used during recording (so you can match your replay config with that which was recorded) +- Adding per-vehicle configuration files in `Content/DReyeVR/EgoVehicle` that can be selected via parameters. Allows parameterization of all EgoVehicle components, magic numbers (ex. location of camera, mirrors, engine), sound files, mirror meshes, steering wheel types, and enable/disable these on a highly granular basis +- Revamp EgoVehicle input controls to use parent (ACarlaWheeledVehicle) controls and flush +- Disabling (turning invisible) default Carla spectator in map +- Added tutorial for custom EgoVehicle + +## DReyeVR 0.1.3 +- Fix bug where other non-ego Autopilto vehicles ignored the EgoVehicle and would routinely crash into it +- Fix bug where some EgoVehicle attributes were missing, notably `"number_of_wheels"` + +## DReyeVR 0.1.2 +- Update documentation to refer to CarlaUnreal UE4 fork rather than HarpLab fork +- Apply patches for installation of zlib (broken link) and xerces (broken link & `-Dtranscoder=windows` flag) and PythonAPI +- Fix crash on BeginPlay when EgoVehicle blueprint is already present in map (before world start) +- Prefer building PythonAPI with `python` rather than Windows built-in `py -3` (good if using conda) but fallback if `python` is not available + +## DReyeVR 0.1.1 +- Update documentation, add developer-centric in-depth documentation +- Adding missing includes for TrafficSign RoadInfoSignal in SignComponent +- Replacing `DReyeVRData.inl` with `DReyeVRData.cpp` and corresponding virtual classes +- Add GitHub workflow for installing DReyeVR atop Carla and building LibCarla/PythonAPI (not CarlaUE4 which requires UnrealEngine) +- Fix bug where disabling mirrors causes a crash since the BP_model3 blueprint would be broken on construction +- Fix bug where replays would spawn another EgoVehicle/EgoSensor in the world (following the Carla spec) which caused multiple overlapping EgoVehicles to be in the world at once. Now we enforced in the Factory function that they are singletons +- Fix bug with replay interpolation not following our EgoVehicle by ticking the pose reenactment in the Carla tick rather than EgoVehicle::Tick +- Fix bug with spectator being reenacted by Carla, preferring to use our own ASpectator +- Automatically possess spectator pawn when EgoVehicle is destroyed. Can re-spawn EgoVehicle by pressing 1. + +## DReyeVR 0.1.0 +- Replace existing `LevelScript` (`ADReyeVRLevel`) with `GameMode` (`ADReyeVRGameMode`). This allows us to not need to carry the (large) map blueprint files (ue4 binary) and we can use the vanilla Carla maps without modification. By default we spawn the EgoVehicle in the first of the recommended Carla locations, but this default behavior can be changed in the PythonAPI. For instance, you can delay spawning the EgoVehicle until via PythonAPI where you can specify the spawn transform. Existing functionality is preserved using `find_ego_vehicle` and `find_ego_sensor` which spawn the DReyeVR EgoVehicle if it does not exist in the world. +- Added `ADReyeVRFactory` as the Carla-esque spawning and registry functionality so the `EgoVehicle` and `EgoSensor` are spawned with the same "Factory" mechanisms as existing Carla vehicles/sensors/props/etc. +- Renamed DReyeVR-specific actors to be addressible in PythonAPI as `"harplab.dreyevr_$X.$id"` such as `"harplab.dreyevr_vehicle.model3"` and `"harplab.dreyevr_sensor.ego_sensor"`. Avoids conflicts with existing Carla PythonAPI scripts that may filter on `"vehicle.*"`. +- Moved all blueprint (`.uasset`) content out of the Carla content (which is now entirely untouched, no need to re-update) to a separate Content folder that lies in `/Game/Content/DReyeVR/` (renamed to support future DReyeVR blueprint changes without relying on Carla content). +- Adding check that SRanipal is within one of our recommended supported versions: `1.3.1.1`, `1.3.2.0`, & `1.3.3.0`. Also provided links in the documentation to download these versions. Additionally included a workaround for the old `patch-sranipal` which is now no longer needed. +- Added custom `LogDReyeVR` macros (`LOG`, `LOG_WARN`, `LOG_ERROR`) for improved logging with attached file, function, and line number to the message. Done in precompilation to avoid runtime performance overhead. +- Improved `make check` to ensure that a 1:1 file correspondence exists between Carla dest and DReyeVR source, and that all files have equal content. +- Improved vehicle dash with blinking turn signal and fixed bugs with inconsistent gear indicator. +- Fixed bugs and inconsistencies with replayer media control and special actions such as toggling reverse/turn signals in replay. +- Enabled cooking for `Town06` and `Town07` in package/shipping mode. - Updated documentation and config file \ No newline at end of file diff --git a/Carla/Actor/DReyeVRCustomActor.cpp b/Carla/Actor/DReyeVRCustomActor.cpp index a872754..fa2e6f1 100644 --- a/Carla/Actor/DReyeVRCustomActor.cpp +++ b/Carla/Actor/DReyeVRCustomActor.cpp @@ -1,179 +1,179 @@ -#include "DReyeVRCustomActor.h" -#include "Carla/Game/CarlaStatics.h" // GetEpisode -#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor::bIsReplaying -#include "Materials/MaterialInstance.h" // UMaterialInstance -#include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic -#include "UObject/UObjectGlobals.h" // LoadObject, NewObject - -#include - -// HACK: assuming you have no more than 10 unique material instances on a single static mesh -// this is what is used to broadacast the single DynamicMat instance to all material slots in the SM -// and calls SetMaterial which grows an internal array (of pointers) to match the index: -// https://docs.unrealengine.com/4.26/en-US/API/Runtime/Engine/Components/UMeshComponent/SetMaterial/ -#define MAX_POSSIBLE_MATERIALS 10 - -std::unordered_map ADReyeVRCustomActor::ActiveCustomActors = {}; -int ADReyeVRCustomActor::AllMeshCount = 0; - -ADReyeVRCustomActor *ADReyeVRCustomActor::CreateNew(const FString &SM_Path, const FString &Mat_Path, UWorld *World, - const FString &Name) -{ - check(World != nullptr); - FActorSpawnParameters SpawnInfo; - SpawnInfo.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; - ADReyeVRCustomActor *Actor = - World->SpawnActor(FVector::ZeroVector, FRotator::ZeroRotator, SpawnInfo); - Actor->Initialize(Name); - - if (Actor->AssignSM(SM_Path, World)) - { - Actor->Internals.MeshPath = SM_Path; - Actor->AssignMat(Mat_Path); - } - - return Actor; -} - -ADReyeVRCustomActor::ADReyeVRCustomActor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) -{ - PrimaryActorTick.bCanEverTick = true; - PrimaryActorTick.TickGroup = TG_PrePhysics; - - // turning off physics interaction - this->SetActorEnableCollision(false); - - // done in child class - Internals.Location = this->GetActorLocation(); - Internals.Rotation = this->GetActorRotation(); - Internals.Scale3D = this->GetActorScale3D(); -} - -bool ADReyeVRCustomActor::AssignSM(const FString &Path, UWorld *World) -{ - UStaticMesh *SM = LoadObject(nullptr, *Path); - ensure(SM != nullptr); - ensure(World != nullptr); - if (SM && World) - { - // Using static AllMeshCount to create a unique component name every time - FName MeshName(*("Mesh" + FString::FromInt(ADReyeVRCustomActor::AllMeshCount))); - ActorMesh = NewObject(this, MeshName); - ensure(ActorMesh != nullptr); - ActorMesh->SetupAttachment(this->GetRootComponent()); - this->SetRootComponent(ActorMesh); - ActorMesh->SetStaticMesh(SM); - ActorMesh->SetVisibility(false); - ActorMesh->SetCollisionEnabled(ECollisionEnabled::NoCollision); - ActorMesh->RegisterComponentWithWorld(World); - this->AddInstanceComponent(ActorMesh); - } - else - { - DReyeVR_LOG_ERROR("Unable to create static mesh: %s", *Path); - return false; - } - ADReyeVRCustomActor::AllMeshCount++; - return true; -} - -void ADReyeVRCustomActor::AssignMat(const FString &MaterialPath) -{ - // MaterialPath should be one of {MAT_OPAQUE, MAT_TRANSLUCENT} to receive params - UMaterial *Material = LoadObject(nullptr, *MaterialPath); - ensure(Material != nullptr); - - // create sole dynamic material - DynamicMat = UMaterialInstanceDynamic::Create(Material, this); - MaterialParams.Apply(DynamicMat); // apply the parameters to this dynamic material - MaterialParams.MaterialPath = MaterialPath; // for now does not change over time - - if (DynamicMat != nullptr && ActorMesh != nullptr) - for (int i = 0; i < MAX_POSSIBLE_MATERIALS; i++) - ActorMesh->SetMaterial(i, DynamicMat); - else - DReyeVR_LOG_ERROR("Unable to access material asset: %s", *MaterialPath) -} - -void ADReyeVRCustomActor::Initialize(const FString &Name) -{ - Internals.Name = Name; - ADReyeVRCustomActor::ActiveCustomActors[TCHAR_TO_UTF8(*Name)] = this; -} - -void ADReyeVRCustomActor::BeginPlay() -{ - Super::BeginPlay(); -} - -void ADReyeVRCustomActor::BeginDestroy() -{ - this->Deactivate(); // remove from global static table - Super::BeginDestroy(); -} - -void ADReyeVRCustomActor::Deactivate() -{ - const std::string s = TCHAR_TO_UTF8(*Internals.Name); - if (ADReyeVRCustomActor::ActiveCustomActors.find(s) != ADReyeVRCustomActor::ActiveCustomActors.end()) - { - ADReyeVRCustomActor::ActiveCustomActors.erase(s); - } - this->SetActorHiddenInGame(true); - if (ActorMesh) - ActorMesh->SetVisibility(false); - this->SetActorTickEnabled(false); - this->bIsActive = false; -} - -void ADReyeVRCustomActor::Activate() -{ - const std::string s = TCHAR_TO_UTF8(*Internals.Name); - if (ADReyeVRCustomActor::ActiveCustomActors.find(s) == ADReyeVRCustomActor::ActiveCustomActors.end()) - ADReyeVRCustomActor::ActiveCustomActors[s] = this; - else - ensure(ADReyeVRCustomActor::ActiveCustomActors[s] == this); - this->SetActorHiddenInGame(false); - if (ActorMesh) - ActorMesh->SetVisibility(true); - this->SetActorTickEnabled(true); - this->bIsActive = true; -} - -void ADReyeVRCustomActor::Tick(float DeltaSeconds) -{ - if (ADReyeVRSensor::bIsReplaying) - { - // update world state with internals - this->SetActorLocation(Internals.Location); - this->SetActorRotation(Internals.Rotation); - this->SetActorScale3D(Internals.Scale3D); - this->MaterialParams = Internals.MaterialParams; - } - else - { - // update internals with world state - Internals.Location = this->GetActorLocation(); - Internals.Rotation = this->GetActorRotation(); - Internals.Scale3D = this->GetActorScale3D(); - Internals.MaterialParams = MaterialParams; - } - UpdateMaterial(); - /// TODO: use other string? -} - -void ADReyeVRCustomActor::UpdateMaterial() -{ - // update the materials according to the params - MaterialParams.Apply(DynamicMat); -} - -void ADReyeVRCustomActor::SetInternals(const DReyeVR::CustomActorData &InData) -{ - Internals = InData; -} - -const DReyeVR::CustomActorData &ADReyeVRCustomActor::GetInternals() const -{ - return Internals; +#include "DReyeVRCustomActor.h" +#include "Carla/Game/CarlaStatics.h" // GetEpisode +#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor::bIsReplaying +#include "Materials/MaterialInstance.h" // UMaterialInstance +#include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic +#include "UObject/UObjectGlobals.h" // LoadObject, NewObject + +#include + +// HACK: assuming you have no more than 10 unique material instances on a single static mesh +// this is what is used to broadacast the single DynamicMat instance to all material slots in the SM +// and calls SetMaterial which grows an internal array (of pointers) to match the index: +// https://docs.unrealengine.com/4.26/en-US/API/Runtime/Engine/Components/UMeshComponent/SetMaterial/ +#define MAX_POSSIBLE_MATERIALS 10 + +std::unordered_map ADReyeVRCustomActor::ActiveCustomActors = {}; +int ADReyeVRCustomActor::AllMeshCount = 0; + +ADReyeVRCustomActor *ADReyeVRCustomActor::CreateNew(const FString &SM_Path, const FString &Mat_Path, UWorld *World, + const FString &Name) +{ + check(World != nullptr); + FActorSpawnParameters SpawnInfo; + SpawnInfo.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + ADReyeVRCustomActor *Actor = + World->SpawnActor(FVector::ZeroVector, FRotator::ZeroRotator, SpawnInfo); + Actor->Initialize(Name); + + if (Actor->AssignSM(SM_Path, World)) + { + Actor->Internals.MeshPath = SM_Path; + Actor->AssignMat(Mat_Path); + } + + return Actor; +} + +ADReyeVRCustomActor::ADReyeVRCustomActor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +{ + PrimaryActorTick.bCanEverTick = true; + PrimaryActorTick.TickGroup = TG_PrePhysics; + + // turning off physics interaction + this->SetActorEnableCollision(false); + + // done in child class + Internals.Location = this->GetActorLocation(); + Internals.Rotation = this->GetActorRotation(); + Internals.Scale3D = this->GetActorScale3D(); +} + +bool ADReyeVRCustomActor::AssignSM(const FString &Path, UWorld *World) +{ + UStaticMesh *SM = LoadObject(nullptr, *Path); + ensure(SM != nullptr); + ensure(World != nullptr); + if (SM && World) + { + // Using static AllMeshCount to create a unique component name every time + FName MeshName(*("Mesh" + FString::FromInt(ADReyeVRCustomActor::AllMeshCount))); + ActorMesh = NewObject(this, MeshName); + ensure(ActorMesh != nullptr); + ActorMesh->SetupAttachment(this->GetRootComponent()); + this->SetRootComponent(ActorMesh); + ActorMesh->SetStaticMesh(SM); + ActorMesh->SetVisibility(false); + ActorMesh->SetCollisionEnabled(ECollisionEnabled::NoCollision); + ActorMesh->RegisterComponentWithWorld(World); + this->AddInstanceComponent(ActorMesh); + } + else + { + DReyeVR_LOG_ERROR("Unable to create static mesh: %s", *Path); + return false; + } + ADReyeVRCustomActor::AllMeshCount++; + return true; +} + +void ADReyeVRCustomActor::AssignMat(const FString &MaterialPath) +{ + // MaterialPath should be one of {MAT_OPAQUE, MAT_TRANSLUCENT} to receive params + UMaterial *Material = LoadObject(nullptr, *MaterialPath); + ensure(Material != nullptr); + + // create sole dynamic material + DynamicMat = UMaterialInstanceDynamic::Create(Material, this); + MaterialParams.Apply(DynamicMat); // apply the parameters to this dynamic material + MaterialParams.MaterialPath = MaterialPath; // for now does not change over time + + if (DynamicMat != nullptr && ActorMesh != nullptr) + for (int i = 0; i < MAX_POSSIBLE_MATERIALS; i++) + ActorMesh->SetMaterial(i, DynamicMat); + else + DReyeVR_LOG_ERROR("Unable to access material asset: %s", *MaterialPath) +} + +void ADReyeVRCustomActor::Initialize(const FString &Name) +{ + Internals.Name = Name; + ADReyeVRCustomActor::ActiveCustomActors[TCHAR_TO_UTF8(*Name)] = this; +} + +void ADReyeVRCustomActor::BeginPlay() +{ + Super::BeginPlay(); +} + +void ADReyeVRCustomActor::BeginDestroy() +{ + this->Deactivate(); // remove from global static table + Super::BeginDestroy(); +} + +void ADReyeVRCustomActor::Deactivate() +{ + const std::string s = TCHAR_TO_UTF8(*Internals.Name); + if (ADReyeVRCustomActor::ActiveCustomActors.find(s) != ADReyeVRCustomActor::ActiveCustomActors.end()) + { + ADReyeVRCustomActor::ActiveCustomActors.erase(s); + } + this->SetActorHiddenInGame(true); + if (ActorMesh) + ActorMesh->SetVisibility(false); + this->SetActorTickEnabled(false); + this->bIsActive = false; +} + +void ADReyeVRCustomActor::Activate() +{ + const std::string s = TCHAR_TO_UTF8(*Internals.Name); + if (ADReyeVRCustomActor::ActiveCustomActors.find(s) == ADReyeVRCustomActor::ActiveCustomActors.end()) + ADReyeVRCustomActor::ActiveCustomActors[s] = this; + else + ensure(ADReyeVRCustomActor::ActiveCustomActors[s] == this); + this->SetActorHiddenInGame(false); + if (ActorMesh) + ActorMesh->SetVisibility(true); + this->SetActorTickEnabled(true); + this->bIsActive = true; +} + +void ADReyeVRCustomActor::Tick(float DeltaSeconds) +{ + if (ADReyeVRSensor::bIsReplaying) + { + // update world state with internals + this->SetActorLocation(Internals.Location); + this->SetActorRotation(Internals.Rotation); + this->SetActorScale3D(Internals.Scale3D); + this->MaterialParams = Internals.MaterialParams; + } + else + { + // update internals with world state + Internals.Location = this->GetActorLocation(); + Internals.Rotation = this->GetActorRotation(); + Internals.Scale3D = this->GetActorScale3D(); + Internals.MaterialParams = MaterialParams; + } + UpdateMaterial(); + /// TODO: use other string? +} + +void ADReyeVRCustomActor::UpdateMaterial() +{ + // update the materials according to the params + MaterialParams.Apply(DynamicMat); +} + +void ADReyeVRCustomActor::SetInternals(const DReyeVR::CustomActorData &InData) +{ + Internals = InData; +} + +const DReyeVR::CustomActorData &ADReyeVRCustomActor::GetInternals() const +{ + return Internals; } \ No newline at end of file diff --git a/Carla/Actor/DReyeVRCustomActor.h b/Carla/Actor/DReyeVRCustomActor.h index 1302e70..df29dbf 100644 --- a/Carla/Actor/DReyeVRCustomActor.h +++ b/Carla/Actor/DReyeVRCustomActor.h @@ -1,86 +1,86 @@ -#pragma once - -#include "Carla/Sensor/DReyeVRData.h" // DReyeVR namespace -#include "GameFramework/Actor.h" // AActor - -#include // std::unordered_map -#include // std::pair -#include // std::vector - -#include "DReyeVRCustomActor.generated.h" - -// define some paths to common custom actor types -#define MAT_OPAQUE "Material'/Game/DReyeVR/Custom/OpaqueParamMaterial.OpaqueParamMaterial'" -#define MAT_TRANSLUCENT "Material'/Game/DReyeVR/Custom/TranslucentParamMaterial.TranslucentParamMaterial'" -#define SM_SPHERE "StaticMesh'/Engine/BasicShapes/Sphere.Sphere'" -#define SM_CUBE "StaticMesh'/Engine/BasicShapes/Cube.Cube'" -#define SM_CONE "StaticMesh'/Engine/BasicShapes/Cone.Cone'" -// add more custom static meshes here! they don't need to be BasicShapes - -UCLASS() -class CARLA_API ADReyeVRCustomActor : public AActor // abstract class -{ - GENERATED_BODY() - - public: - ADReyeVRCustomActor(const FObjectInitializer &ObjectInitializer); - ~ADReyeVRCustomActor() = default; - - /// factory function to create a new instance of a given type - static ADReyeVRCustomActor *CreateNew(const FString &SM_Path, const FString &Mat_Path, UWorld *World, - const FString &Name); - - virtual void Tick(float DeltaSeconds) override; - - void Activate(); - void Deactivate(); - bool IsActive() const - { - return bIsActive; - } - - void SetActorRecordEnabled(const bool bEnabled) - { - bShouldRecord = bEnabled; - } - - const bool GetShouldRecord() const - { - return bShouldRecord; - } - - void Initialize(const FString &Name); - - void SetInternals(const DReyeVR::CustomActorData &In); - - const DReyeVR::CustomActorData &GetInternals() const; - - static std::unordered_map ActiveCustomActors; - - inline class UStaticMeshComponent *GetMesh() - { - return ActorMesh; - } - - // function to dynamically change the material params of the object at runtime - void AssignMat(const FString &Path); - void UpdateMaterial(); - struct DReyeVR::CustomActorData::MaterialParamsStruct MaterialParams; - - private: - void BeginPlay() override; - void BeginDestroy() override; - bool bIsActive = false; // initially deactivated - bool bShouldRecord = true; // should record in the Carla Recorder/Replayer - - bool AssignSM(const FString &Path, UWorld *World); - - class DReyeVR::CustomActorData Internals; - - UPROPERTY(EditAnywhere, Category = "Mesh") - class UStaticMeshComponent *ActorMesh = nullptr; - static int AllMeshCount; - - UPROPERTY(EditAnywhere, Category = "Materials") - class UMaterialInstanceDynamic *DynamicMat = nullptr; +#pragma once + +#include "Carla/Sensor/DReyeVRData.h" // DReyeVR namespace +#include "GameFramework/Actor.h" // AActor + +#include // std::unordered_map +#include // std::pair +#include // std::vector + +#include "DReyeVRCustomActor.generated.h" + +// define some paths to common custom actor types +#define MAT_OPAQUE "Material'/Game/DReyeVR/Custom/OpaqueParamMaterial.OpaqueParamMaterial'" +#define MAT_TRANSLUCENT "Material'/Game/DReyeVR/Custom/TranslucentParamMaterial.TranslucentParamMaterial'" +#define SM_SPHERE "StaticMesh'/Engine/BasicShapes/Sphere.Sphere'" +#define SM_CUBE "StaticMesh'/Engine/BasicShapes/Cube.Cube'" +#define SM_CONE "StaticMesh'/Engine/BasicShapes/Cone.Cone'" +// add more custom static meshes here! they don't need to be BasicShapes + +UCLASS() +class CARLA_API ADReyeVRCustomActor : public AActor // abstract class +{ + GENERATED_BODY() + + public: + ADReyeVRCustomActor(const FObjectInitializer &ObjectInitializer); + ~ADReyeVRCustomActor() = default; + + /// factory function to create a new instance of a given type + static ADReyeVRCustomActor *CreateNew(const FString &SM_Path, const FString &Mat_Path, UWorld *World, + const FString &Name); + + virtual void Tick(float DeltaSeconds) override; + + void Activate(); + void Deactivate(); + bool IsActive() const + { + return bIsActive; + } + + void SetActorRecordEnabled(const bool bEnabled) + { + bShouldRecord = bEnabled; + } + + const bool GetShouldRecord() const + { + return bShouldRecord; + } + + void Initialize(const FString &Name); + + void SetInternals(const DReyeVR::CustomActorData &In); + + const DReyeVR::CustomActorData &GetInternals() const; + + static std::unordered_map ActiveCustomActors; + + inline class UStaticMeshComponent *GetMesh() + { + return ActorMesh; + } + + // function to dynamically change the material params of the object at runtime + void AssignMat(const FString &Path); + void UpdateMaterial(); + struct DReyeVR::CustomActorData::MaterialParamsStruct MaterialParams; + + private: + void BeginPlay() override; + void BeginDestroy() override; + bool bIsActive = false; // initially deactivated + bool bShouldRecord = true; // should record in the Carla Recorder/Replayer + + bool AssignSM(const FString &Path, UWorld *World); + + class DReyeVR::CustomActorData Internals; + + UPROPERTY(EditAnywhere, Category = "Mesh") + class UStaticMeshComponent *ActorMesh = nullptr; + static int AllMeshCount; + + UPROPERTY(EditAnywhere, Category = "Materials") + class UMaterialInstanceDynamic *DynamicMat = nullptr; }; \ No newline at end of file diff --git a/Carla/Carla.h b/Carla/Carla.h index 317a95d..a6023d3 100644 --- a/Carla/Carla.h +++ b/Carla/Carla.h @@ -1,85 +1,85 @@ -// Copyright 1998-2017 Epic Games, Inc. All Rights Reserved. - -// This file is included before any other file in every compile unit within the -// plugin. -#pragma once - - -#include "Util/NonCopyable.h" -#include "Logging/LogMacros.h" -#include "Modules/ModuleInterface.h" - -DECLARE_LOG_CATEGORY_EXTERN(LogCarla, Log, All); -DECLARE_LOG_CATEGORY_EXTERN(LogCarlaServer, Log, All); - -// DisplayName, GroupName, Third param is always Advanced. -// DECLARE_STATS_GROUP(TEXT("Carla"), STATGROUP_Carla, STATCAT_Advanced); -DECLARE_STATS_GROUP(TEXT("CarlaSensor"), STATGROUP_CarlaSensor, STATCAT_Advanced); - -//DECLARE_MEMORY_STAT(TEXT("CARLAMEMORY"), STATGROUP_CARLAMEMORY, STATCAT_Advanced) - -DECLARE_CYCLE_STAT(TEXT("Read RT"), STAT_CarlaSensorReadRT, STATGROUP_CarlaSensor); -DECLARE_CYCLE_STAT(TEXT("Copy Text"), STAT_CarlaSensorCopyText, STATGROUP_CarlaSensor); -DECLARE_CYCLE_STAT(TEXT("Buffer Copy"), STAT_CarlaSensorBufferCopy, STATGROUP_CarlaSensor); -DECLARE_CYCLE_STAT(TEXT("Stream Send"), STAT_CarlaSensorStreamSend, STATGROUP_CarlaSensor); - -// Options to compile with extra debug log. -#if WITH_EDITOR -// #define CARLA_AI_VEHICLES_EXTRA_LOG -// #define CARLA_AI_WALKERS_EXTRA_LOG -// #define CARLA_ROAD_GENERATOR_EXTRA_LOG -// #define CARLA_SERVER_EXTRA_LOG -// #define CARLA_TAGGER_EXTRA_LOG -// #define CARLA_WEATHER_EXTRA_LOG -#endif // WITH_EDITOR - -class FCarlaModule : public IModuleInterface -{ - void RegisterSettings(); - void UnregisterSettings(); - bool HandleSettingsSaved(); - void LoadChronoDll(); - -public: - - /** IModuleInterface implementation */ - virtual void StartupModule() override; - virtual void ShutdownModule() override; - -}; - -/////////////////////////////////////////////////////////////////////////////// -//////////////////////DReyeVR logging from CarlaUE4.h////////////////////////// -/////////////////////////////////////////////////////////////////////////////// - -// fancy logging that includes [filename::function:line] prefix -#ifndef __DReyeVR_LOG - -/// TODO: remove duplicate code! (Also defined in CarlaUE4.h) -constexpr inline const char *file_name_only(const char *path) -{ - // note since this is a constexpr function, it gets evaluated at compile time rather - // than runtime so there is no runtime performance overhead! -#ifdef _WIN32 - constexpr char os_sep = '\\'; -#else - constexpr char os_sep = '/'; -#endif - const char *filename_start = path; - while (*path) - { - if (*path++ == os_sep) // keep searching until found last os sep - filename_start = path; - } - return filename_start; // includes extension -} - - -#define __DReyeVR_LOG(msg, verbosity, ...) \ - UE_LOG(LogCarla, verbosity, TEXT("[%s::%s:%d] %s"), UTF8_TO_TCHAR(file_name_only(__FILE__)), \ - UTF8_TO_TCHAR(__func__), __LINE__, *FString::Printf(TEXT(msg), ##__VA_ARGS__)); -#endif - -#define DReyeVR_LOG(msg, ...) __DReyeVR_LOG(msg, Log, ##__VA_ARGS__); -#define DReyeVR_LOG_WARN(msg, ...) __DReyeVR_LOG(msg, Warning, ##__VA_ARGS__); +// Copyright 1998-2017 Epic Games, Inc. All Rights Reserved. + +// This file is included before any other file in every compile unit within the +// plugin. +#pragma once + + +#include "Util/NonCopyable.h" +#include "Logging/LogMacros.h" +#include "Modules/ModuleInterface.h" + +DECLARE_LOG_CATEGORY_EXTERN(LogCarla, Log, All); +DECLARE_LOG_CATEGORY_EXTERN(LogCarlaServer, Log, All); + +// DisplayName, GroupName, Third param is always Advanced. +// DECLARE_STATS_GROUP(TEXT("Carla"), STATGROUP_Carla, STATCAT_Advanced); +DECLARE_STATS_GROUP(TEXT("CarlaSensor"), STATGROUP_CarlaSensor, STATCAT_Advanced); + +//DECLARE_MEMORY_STAT(TEXT("CARLAMEMORY"), STATGROUP_CARLAMEMORY, STATCAT_Advanced) + +DECLARE_CYCLE_STAT(TEXT("Read RT"), STAT_CarlaSensorReadRT, STATGROUP_CarlaSensor); +DECLARE_CYCLE_STAT(TEXT("Copy Text"), STAT_CarlaSensorCopyText, STATGROUP_CarlaSensor); +DECLARE_CYCLE_STAT(TEXT("Buffer Copy"), STAT_CarlaSensorBufferCopy, STATGROUP_CarlaSensor); +DECLARE_CYCLE_STAT(TEXT("Stream Send"), STAT_CarlaSensorStreamSend, STATGROUP_CarlaSensor); + +// Options to compile with extra debug log. +#if WITH_EDITOR +// #define CARLA_AI_VEHICLES_EXTRA_LOG +// #define CARLA_AI_WALKERS_EXTRA_LOG +// #define CARLA_ROAD_GENERATOR_EXTRA_LOG +// #define CARLA_SERVER_EXTRA_LOG +// #define CARLA_TAGGER_EXTRA_LOG +// #define CARLA_WEATHER_EXTRA_LOG +#endif // WITH_EDITOR + +class FCarlaModule : public IModuleInterface +{ + void RegisterSettings(); + void UnregisterSettings(); + bool HandleSettingsSaved(); + void LoadChronoDll(); + +public: + + /** IModuleInterface implementation */ + virtual void StartupModule() override; + virtual void ShutdownModule() override; + +}; + +/////////////////////////////////////////////////////////////////////////////// +//////////////////////DReyeVR logging from CarlaUE4.h////////////////////////// +/////////////////////////////////////////////////////////////////////////////// + +// fancy logging that includes [filename::function:line] prefix +#ifndef __DReyeVR_LOG + +/// TODO: remove duplicate code! (Also defined in CarlaUE4.h) +constexpr inline const char *file_name_only(const char *path) +{ + // note since this is a constexpr function, it gets evaluated at compile time rather + // than runtime so there is no runtime performance overhead! +#ifdef _WIN32 + constexpr char os_sep = '\\'; +#else + constexpr char os_sep = '/'; +#endif + const char *filename_start = path; + while (*path) + { + if (*path++ == os_sep) // keep searching until found last os sep + filename_start = path; + } + return filename_start; // includes extension +} + + +#define __DReyeVR_LOG(msg, verbosity, ...) \ + UE_LOG(LogCarla, verbosity, TEXT("[%s::%s:%d] %s"), UTF8_TO_TCHAR(file_name_only(__FILE__)), \ + UTF8_TO_TCHAR(__func__), __LINE__, *FString::Printf(TEXT(msg), ##__VA_ARGS__)); +#endif + +#define DReyeVR_LOG(msg, ...) __DReyeVR_LOG(msg, Log, ##__VA_ARGS__); +#define DReyeVR_LOG_WARN(msg, ...) __DReyeVR_LOG(msg, Warning, ##__VA_ARGS__); #define DReyeVR_LOG_ERROR(msg, ...) __DReyeVR_LOG(msg, Error, ##__VA_ARGS__); \ No newline at end of file diff --git a/Carla/Game/CarlaGameModeBase.h b/Carla/Game/CarlaGameModeBase.h index f02d621..70e3dc2 100644 --- a/Carla/Game/CarlaGameModeBase.h +++ b/Carla/Game/CarlaGameModeBase.h @@ -1,194 +1,194 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "CoreMinimal.h" -#include "GameFramework/GameModeBase.h" - -#include -#include -#include -#include -#include - -#include "Carla/Actor/CarlaActorFactory.h" -#include "Carla/Game/CarlaEpisode.h" -#include "Carla/Game/CarlaGameInstance.h" -#include "Carla/Game/TaggerDelegate.h" -#include "Carla/OpenDrive/OpenDrive.h" -#include "Carla/Recorder/CarlaRecorder.h" -#include "Carla/Sensor/SceneCaptureSensor.h" -#include "Carla/Settings/CarlaSettingsDelegate.h" -#include "Carla/Traffic/TrafficLightManager.h" -#include "Carla/Util/ObjectRegister.h" -#include "Carla/Weather/Weather.h" -#include "MapGen/LargeMapManager.h" - -#include "CarlaGameModeBase.generated.h" - -/// Base class for the CARLA Game Mode. -UCLASS(HideCategories=(ActorTick)) -class CARLA_API ACarlaGameModeBase : public AGameModeBase -{ - GENERATED_BODY() - -public: - - ACarlaGameModeBase(const FObjectInitializer& ObjectInitializer); - - const UCarlaEpisode &GetCarlaEpisode() const - { - check(Episode != nullptr); - return *Episode; - } - - const boost::optional& GetMap() const { - return Map; - } - - const FString GetFullMapPath() const; - - // get path relative to Content folder - const FString GetRelativeMapPath() const; - - UFUNCTION(Exec, Category = "CARLA Game Mode") - void DebugShowSignals(bool enable); - - UFUNCTION(BlueprintCallable, Category = "CARLA Game Mode") - ATrafficLightManager* GetTrafficLightManager(); - - UFUNCTION(Category = "Carla Game Mode", BlueprintCallable) - const TArray& GetSpawnPointsTransforms() const{ - return SpawnPointsTransforms; - } - - UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) - TArray GetAllBBsOfLevel(uint8 TagQueried = 0xFF) const; - - UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) - TArray GetEnvironmentObjects(uint8 QueriedTag = 0xFF) const - { - return ObjectRegister->GetEnvironmentObjects(QueriedTag); - } - - void EnableEnvironmentObjects(const TSet& EnvObjectIds, bool Enable); - - void EnableOverlapEvents(); - - void CheckForEmptyMeshes(); - - UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) - void LoadMapLayer(int32 MapLayers); - - UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) - void UnLoadMapLayer(int32 MapLayers); - - UFUNCTION(Category = "Carla Game Mode") - ULevel* GetULevelFromName(FString LevelName); - - UFUNCTION(BlueprintCallable, Category = "Carla Game Mode") - void OnLoadStreamLevel(); - - UFUNCTION(BlueprintCallable, Category = "Carla Game Mode") - void OnUnloadStreamLevel(); - - ALargeMapManager* GetLMManager() const { - return LMManager; - } - - AActor* FindActorByName(const FString& ActorName); - - UTexture2D* CreateUETexture(const carla::rpc::TextureColor& Texture); - UTexture2D* CreateUETexture(const carla::rpc::TextureFloatColor& Texture); - - void ApplyTextureToActor( - AActor* Actor, - UTexture2D* Texture, - const carla::rpc::MaterialParameter& TextureParam); - - TArray GetNamesOfAllActors(); - -protected: - - void InitGame(const FString &MapName, const FString &Options, FString &ErrorMessage) override; - - void RestartPlayer(AController *NewPlayer) override; - - void BeginPlay() override; - - void EndPlay(const EEndPlayReason::Type EndPlayReason) override; - - void Tick(float DeltaSeconds) override; - - /// The class of Weather to spawn. - UPROPERTY(Category = "CARLA Game Mode", EditAnywhere) - TSubclassOf WeatherClass; - - /// List of actor spawners that will be used to define and spawn the actors - /// available in game. - UPROPERTY(Category = "CARLA Game Mode", EditAnywhere) - TSet> ActorFactories; - -private: - - void SpawnActorFactories(); - - void StoreSpawnPoints(); - - void GenerateSpawnPoints(); - - void ParseOpenDrive(); - - void RegisterEnvironmentObjects(); - - void ConvertMapLayerMaskToMapNames(int32 MapLayer, TArray& OutLevelNames); - - void OnEpisodeSettingsChanged(const FEpisodeSettings &Settings); - - UPROPERTY() - UCarlaGameInstance *GameInstance = nullptr; - - UPROPERTY() - UTaggerDelegate *TaggerDelegate = nullptr; - - UPROPERTY() - UCarlaSettingsDelegate *CarlaSettingsDelegate = nullptr; - - UPROPERTY() - UCarlaEpisode *Episode = nullptr; - - UPROPERTY() - ACarlaRecorder *Recorder = nullptr; - - UPROPERTY() - UObjectRegister* ObjectRegister = nullptr; - - UPROPERTY() - TArray SpawnPointsTransforms; - - UPROPERTY() - TArray ActorFactoryInstances; - - UPROPERTY() - ATrafficLightManager* TrafficLightManager = nullptr; - - ALargeMapManager* LMManager = nullptr; - - FDelegateHandle OnEpisodeSettingsChangeHandle; - - boost::optional Map; - - int PendingLevelsToLoad = 0; - int PendingLevelsToUnLoad = 0; - - bool ReadyToRegisterObjects = false; - - // We keep a global uuid to allow the load/unload layer methods to be called - // in the same tick - int32 LatentInfoUUID = 0; - -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "CoreMinimal.h" +#include "GameFramework/GameModeBase.h" + +#include +#include +#include +#include +#include + +#include "Carla/Actor/CarlaActorFactory.h" +#include "Carla/Game/CarlaEpisode.h" +#include "Carla/Game/CarlaGameInstance.h" +#include "Carla/Game/TaggerDelegate.h" +#include "Carla/OpenDrive/OpenDrive.h" +#include "Carla/Recorder/CarlaRecorder.h" +#include "Carla/Sensor/SceneCaptureSensor.h" +#include "Carla/Settings/CarlaSettingsDelegate.h" +#include "Carla/Traffic/TrafficLightManager.h" +#include "Carla/Util/ObjectRegister.h" +#include "Carla/Weather/Weather.h" +#include "MapGen/LargeMapManager.h" + +#include "CarlaGameModeBase.generated.h" + +/// Base class for the CARLA Game Mode. +UCLASS(HideCategories=(ActorTick)) +class CARLA_API ACarlaGameModeBase : public AGameModeBase +{ + GENERATED_BODY() + +public: + + ACarlaGameModeBase(const FObjectInitializer& ObjectInitializer); + + const UCarlaEpisode &GetCarlaEpisode() const + { + check(Episode != nullptr); + return *Episode; + } + + const boost::optional& GetMap() const { + return Map; + } + + const FString GetFullMapPath() const; + + // get path relative to Content folder + const FString GetRelativeMapPath() const; + + UFUNCTION(Exec, Category = "CARLA Game Mode") + void DebugShowSignals(bool enable); + + UFUNCTION(BlueprintCallable, Category = "CARLA Game Mode") + ATrafficLightManager* GetTrafficLightManager(); + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable) + const TArray& GetSpawnPointsTransforms() const{ + return SpawnPointsTransforms; + } + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + TArray GetAllBBsOfLevel(uint8 TagQueried = 0xFF) const; + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + TArray GetEnvironmentObjects(uint8 QueriedTag = 0xFF) const + { + return ObjectRegister->GetEnvironmentObjects(QueriedTag); + } + + void EnableEnvironmentObjects(const TSet& EnvObjectIds, bool Enable); + + void EnableOverlapEvents(); + + void CheckForEmptyMeshes(); + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + void LoadMapLayer(int32 MapLayers); + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + void UnLoadMapLayer(int32 MapLayers); + + UFUNCTION(Category = "Carla Game Mode") + ULevel* GetULevelFromName(FString LevelName); + + UFUNCTION(BlueprintCallable, Category = "Carla Game Mode") + void OnLoadStreamLevel(); + + UFUNCTION(BlueprintCallable, Category = "Carla Game Mode") + void OnUnloadStreamLevel(); + + ALargeMapManager* GetLMManager() const { + return LMManager; + } + + AActor* FindActorByName(const FString& ActorName); + + UTexture2D* CreateUETexture(const carla::rpc::TextureColor& Texture); + UTexture2D* CreateUETexture(const carla::rpc::TextureFloatColor& Texture); + + void ApplyTextureToActor( + AActor* Actor, + UTexture2D* Texture, + const carla::rpc::MaterialParameter& TextureParam); + + TArray GetNamesOfAllActors(); + +protected: + + void InitGame(const FString &MapName, const FString &Options, FString &ErrorMessage) override; + + void RestartPlayer(AController *NewPlayer) override; + + void BeginPlay() override; + + void EndPlay(const EEndPlayReason::Type EndPlayReason) override; + + void Tick(float DeltaSeconds) override; + + /// The class of Weather to spawn. + UPROPERTY(Category = "CARLA Game Mode", EditAnywhere) + TSubclassOf WeatherClass; + + /// List of actor spawners that will be used to define and spawn the actors + /// available in game. + UPROPERTY(Category = "CARLA Game Mode", EditAnywhere) + TSet> ActorFactories; + +private: + + void SpawnActorFactories(); + + void StoreSpawnPoints(); + + void GenerateSpawnPoints(); + + void ParseOpenDrive(); + + void RegisterEnvironmentObjects(); + + void ConvertMapLayerMaskToMapNames(int32 MapLayer, TArray& OutLevelNames); + + void OnEpisodeSettingsChanged(const FEpisodeSettings &Settings); + + UPROPERTY() + UCarlaGameInstance *GameInstance = nullptr; + + UPROPERTY() + UTaggerDelegate *TaggerDelegate = nullptr; + + UPROPERTY() + UCarlaSettingsDelegate *CarlaSettingsDelegate = nullptr; + + UPROPERTY() + UCarlaEpisode *Episode = nullptr; + + UPROPERTY() + ACarlaRecorder *Recorder = nullptr; + + UPROPERTY() + UObjectRegister* ObjectRegister = nullptr; + + UPROPERTY() + TArray SpawnPointsTransforms; + + UPROPERTY() + TArray ActorFactoryInstances; + + UPROPERTY() + ATrafficLightManager* TrafficLightManager = nullptr; + + ALargeMapManager* LMManager = nullptr; + + FDelegateHandle OnEpisodeSettingsChangeHandle; + + boost::optional Map; + + int PendingLevelsToLoad = 0; + int PendingLevelsToUnLoad = 0; + + bool ReadyToRegisterObjects = false; + + // We keep a global uuid to allow the load/unload layer methods to be called + // in the same tick + int32 LatentInfoUUID = 0; + +}; diff --git a/Carla/Recorder/CarlaRecorder.cpp b/Carla/Recorder/CarlaRecorder.cpp index 4fdbada..7c989b8 100644 --- a/Carla/Recorder/CarlaRecorder.cpp +++ b/Carla/Recorder/CarlaRecorder.cpp @@ -1,741 +1,741 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "Carla.h" -#include "Carla/Actor/ActorDescription.h" -#include "Carla/Walker/WalkerControl.h" -#include "Carla/Walker/WalkerController.h" -#include "Carla/Weather/Weather.h" - -#include -#include "carla/rpc/VehicleLightState.h" -#include - -#include "CarlaRecorder.h" -#include "CarlaReplayerHelper.h" - -// DReyeVR include -#include "Carla/Actor/DReyeVRCustomActor.h" -#include "Carla/Game/CarlaStatics.h" -#include "Carla/Lights/CarlaLightSubsystem.h" -#include "Carla/Sensor/DReyeVRSensor.h" -#include "DReyeVRRecorder.h" - -#include -#include - -ACarlaRecorder::ACarlaRecorder(void) -{ - PrimaryActorTick.TickGroup = TG_PrePhysics; - Disable(); -} - -ACarlaRecorder::ACarlaRecorder(const FObjectInitializer &ObjectInitializer) - : Super(ObjectInitializer) -{ - PrimaryActorTick.TickGroup = TG_PrePhysics; - Disable(); -} - -std::string ACarlaRecorder::ShowFileInfo(std::string Name, bool bShowAll) -{ - return Query.QueryInfo(Name, bShowAll); -} - -std::string ACarlaRecorder::ShowFileCollisions(std::string Name, char Type1, char Type2) -{ - return Query.QueryCollisions(Name, Type1, Type2); -} - -std::string ACarlaRecorder::ShowFileActorsBlocked(std::string Name, double MinTime, double MinDistance) -{ - return Query.QueryBlocked(Name, MinTime, MinDistance); -} - -std::string ACarlaRecorder::ReplayFile(std::string Name, double TimeStart, double Duration, - uint32_t FollowId, bool ReplaySensors) -{ - Stop(); - return Replayer.ReplayFile(Name, TimeStart, Duration, FollowId, ReplaySensors); -} - -void ACarlaRecorder::SetReplayerTimeFactor(double TimeFactor) -{ - Replayer.SetTimeFactor(TimeFactor); -} - -void ACarlaRecorder::SetReplayerIgnoreHero(bool IgnoreHero) -{ - Replayer.SetIgnoreHero(IgnoreHero); -} - -void ACarlaRecorder::StopReplayer(bool KeepActors) -{ - Replayer.Stop(KeepActors); -} - -void ACarlaRecorder::Ticking(float DeltaSeconds) -{ - TRACE_CPUPROFILER_EVENT_SCOPE(ACarlaRecorder::Ticking); - Super::Tick(DeltaSeconds); - - if (!Episode) - return; - - // check if recording - if (Enabled) - { - PlatformTime.UpdateTime(); - const FActorRegistry &Registry = Episode->GetActorRegistry(); - - // Skip the spectator actor - FCarlaActor* CarlaSpectator = Episode->FindCarlaActor(Episode->GetSpectatorPawn()); - - // through all actors in registry - for (auto It = Registry.begin(); It != Registry.end(); ++It) - { - FCarlaActor* View = It.Value().Get(); - - if (CarlaSpectator && (View->GetActor() == CarlaSpectator->GetActor())) - continue; // don't record the spectator - - switch (View->GetActorType()) - { - // save the transform for props - case FCarlaActor::ActorType::Other: - AddActorPosition(View); - break; - - // save the transform of all vehicles - case FCarlaActor::ActorType::Vehicle: - AddActorPosition(View); - AddVehicleAnimation(View); - AddVehicleLight(View); - if (bAdditionalData) - { - AddActorKinematics(View); - } - break; - - // save the transform of all walkers - case FCarlaActor::ActorType::Walker: - AddActorPosition(View); - AddWalkerAnimation(View); - if (bAdditionalData) - { - AddActorKinematics(View); - } - break; - - // save the state of each traffic light - case FCarlaActor::ActorType::TrafficLight: - AddTrafficLightState(View); - break; - } - } - // Add the DReyeVR data - AddDReyeVRData(); - - // write all data for this frame - Write(DeltaSeconds); - } - else if (Episode->GetReplayer()->IsEnabled()) - { - // replayer - Episode->GetReplayer()->Tick(DeltaSeconds); - } -} - -void ACarlaRecorder::Enable(void) -{ - PrimaryActorTick.bCanEverTick = true; - Enabled = true; -} - -void ACarlaRecorder::Disable(void) -{ - PrimaryActorTick.bCanEverTick = false; - Enabled = false; -} - -void ACarlaRecorder::AddActorPosition(FCarlaActor *CarlaActor) -{ - check(CarlaActor != nullptr); - - FTransform Transform = CarlaActor->GetActorGlobalTransform(); - // get position of the vehicle - AddPosition(CarlaRecorderPosition - { - CarlaActor->GetActorId(), - Transform.GetLocation(), - Transform.GetRotation().Euler() - }); -} - -void ACarlaRecorder::AddVehicleAnimation(FCarlaActor *CarlaActor) -{ - check(CarlaActor != nullptr); - - if (CarlaActor->IsPendingKill()) - { - return; - } - - FVehicleControl Control; - CarlaActor->GetVehicleControl(Control); - - // save - CarlaRecorderAnimVehicle Record; - Record.DatabaseId = CarlaActor->GetActorId(); - Record.Steering = Control.Steer; - Record.Throttle = Control.Throttle; - Record.Brake = Control.Brake; - Record.bHandbrake = Control.bHandBrake; - Record.Gear = Control.Gear; - AddAnimVehicle(Record); -} - -void ACarlaRecorder::AddWalkerAnimation(FCarlaActor *CarlaActor) -{ - check(CarlaActor != nullptr); - - if (!CarlaActor->IsPendingKill()) - { - FWalkerControl Control; - CarlaActor->GetWalkerControl(Control); - AddAnimWalker(CarlaRecorderAnimWalker - { - CarlaActor->GetActorId(), - Control.Speed - }); - } -} - -void ACarlaRecorder::AddTrafficLightState(FCarlaActor *CarlaActor) -{ - check(CarlaActor != nullptr); - - ETrafficLightState LightState = CarlaActor->GetTrafficLightState(); - UTrafficLightController* Controller = CarlaActor->GetTrafficLightController(); - if (Controller) - { - ATrafficLightGroup* Group = Controller->GetGroup(); - if (Group) - { - AddState(CarlaRecorderStateTrafficLight - { - CarlaActor->GetActorId(), - Group->IsFrozen(), - Controller->GetElapsedTime(), - static_cast(LightState) - }); - } - } -} - -void ACarlaRecorder::AddVehicleLight(FCarlaActor *CarlaActor) -{ - check(CarlaActor != nullptr); - - FVehicleLightState LightState; - CarlaActor->GetVehicleLightState(LightState); - CarlaRecorderLightVehicle LightVehicle; - LightVehicle.DatabaseId = CarlaActor->GetActorId(); - LightVehicle.State = carla::rpc::VehicleLightState(LightState).light_state; - AddLightVehicle(LightVehicle); -} - -void ACarlaRecorder::AddActorKinematics(FCarlaActor *CarlaActor) -{ - check(CarlaActor != nullptr); - - FVector Velocity, AngularVelocity; - constexpr float TO_METERS = 1e-2; - Velocity = TO_METERS* CarlaActor->GetActorVelocity(); - AngularVelocity = CarlaActor->GetActorAngularVelocity(); - CarlaRecorderKinematics Kinematic = - { - CarlaActor->GetActorId(), - Velocity, - AngularVelocity - }; - AddKinematics(Kinematic); -} -void ACarlaRecorder::AddActorBoundingBox(FCarlaActor *CarlaActor) -{ - check(CarlaActor != nullptr); - - const auto &Box = CarlaActor->GetActorInfo()->BoundingBox; - CarlaRecorderActorBoundingBox BoundingBox = - { - CarlaActor->GetActorId(), - {Box.Origin, Box.Extent} - }; - - AddBoundingBox(BoundingBox); -} - -void ACarlaRecorder::AddDReyeVRData() -{ - static bool bAddedConfigFile; - if (!bAddedConfigFile) { - // add DReyeVR config files (only once at the beginning of recording) - DReyeVRConfigFileData.Add(ADReyeVRSensor::ConfigFile); - bAddedConfigFile = true; - } - - // Add the latest instance of the DReyeVR snapshot to our data - DReyeVRAggData.Add(DReyeVRDataRecorder(ADReyeVRSensor::Data)); - - for (auto &ActiveCAs : ADReyeVRCustomActor::ActiveCustomActors) - { - ADReyeVRCustomActor *CustomActor = ActiveCAs.second; - if (CustomActor != nullptr && CustomActor->IsActive() && CustomActor->GetShouldRecord()) - { - DReyeVRCustomActorData.Add(DReyeVRDataRecorder(&(CustomActor->GetInternals()))); - } - } -} - -void ACarlaRecorder::AddTriggerVolume(const ATrafficSignBase &TrafficSign) -{ - if (bAdditionalData) - { - TArray Triggers = TrafficSign.GetTriggerVolumes(); - if(!Triggers.Num()) - { - return; - } - UBoxComponent* Trigger = Triggers.Top(); - auto VolumeOrigin = Trigger->GetComponentLocation(); - auto VolumeExtent = Trigger->GetScaledBoxExtent(); - CarlaRecorderActorBoundingBox TriggerVolume = - { - Episode->GetActorRegistry().FindCarlaActor(&TrafficSign)->GetActorId(), - {VolumeOrigin, VolumeExtent} - }; - TriggerVolumes.Add(TriggerVolume); - } -} - -void ACarlaRecorder::AddPhysicsControl(const ACarlaWheeledVehicle& Vehicle) -{ - if (bAdditionalData) - { - CarlaRecorderPhysicsControl Control; - Control.DatabaseId = Episode->GetActorRegistry().FindCarlaActor(&Vehicle)->GetActorId(); - Control.VehiclePhysicsControl = Vehicle.GetVehiclePhysicsControl(); - PhysicsControls.Add(Control); - } -} - -void ACarlaRecorder::AddTrafficLightTime(const ATrafficLightBase& TrafficLight) -{ - if (bAdditionalData) - { - auto DatabaseId = Episode->GetActorRegistry().FindCarlaActor(&TrafficLight)->GetActorId(); - CarlaRecorderTrafficLightTime TrafficLightTime{ - DatabaseId, - TrafficLight.GetGreenTime(), - TrafficLight.GetYellowTime(), - TrafficLight.GetRedTime() - }; - TrafficLightTimes.Add(TrafficLightTime); - } -} - -void ACarlaRecorder::AddWeather(const FWeatherParameters& WeatherParams) -{ - CarlaRecorderWeather Weather; - Weather.Params = WeatherParams; - Weathers.Add(Weather); -} - -std::string ACarlaRecorder::Start(std::string Name, FString MapName, bool AdditionalData) -{ - // stop replayer if any in course - if (Replayer.IsEnabled()) - Replayer.Stop(); - - // stop recording - Stop(); - - // reset collisions Id - NextCollisionId = 0; - - // get the final path + filename - std::string Filename = GetRecorderFilename(Name); - - // binary file - File.open(Filename, std::ios::binary); - if (!File.is_open()) - { - return ""; - } - - // save info - Info.Version = 1; - Info.Magic = TEXT("CARLA_RECORDER"); - Info.Date = std::time(0); - Info.Mapfile = MapName; - - // write general info - Info.Write(File); - - Frames.Reset(); - PlatformTime.SetStartTime(); - - Enable(); - - bAdditionalData = AdditionalData; - - // add all existing actors - AddExistingActors(); - - // add current weather for start of recording - AddStartingWeather(); - - return std::string(Filename); -} - -void ACarlaRecorder::Stop(void) -{ - Disable(); - - if (File) - { - File.close(); - } - - Clear(); -} - -void ACarlaRecorder::Clear(void) -{ - EventsAdd.Clear(); - EventsDel.Clear(); - EventsParent.Clear(); - Collisions.Clear(); - Positions.Clear(); - States.Clear(); - Vehicles.Clear(); - Walkers.Clear(); - LightVehicles.Clear(); - LightScenes.Clear(); - Kinematics.Clear(); - BoundingBoxes.Clear(); - TriggerVolumes.Clear(); - PhysicsControls.Clear(); - TrafficLightTimes.Clear(); - DReyeVRAggData.Clear(); - DReyeVRCustomActorData.Clear(); - DReyeVRConfigFileData.Clear(); - Weathers.Clear(); -} - -void ACarlaRecorder::Write(double DeltaSeconds) -{ - // update this frame data - Frames.SetFrame(DeltaSeconds); - - // start - Frames.WriteStart(File); - - // events - EventsAdd.Write(File); - EventsDel.Write(File); - EventsParent.Write(File); - Collisions.Write(File); - - // positions and states - Positions.Write(File); - States.Write(File); - - // animations - Vehicles.Write(File); - Walkers.Write(File); - LightVehicles.Write(File); - LightScenes.Write(File); - - // additional info - if (bAdditionalData) - { - Kinematics.Write(File); - BoundingBoxes.Write(File); - TriggerVolumes.Write(File); - PlatformTime.Write(File); - PhysicsControls.Write(File); - TrafficLightTimes.Write(File); - } - // custom DReyeVR data - DReyeVRAggData.Write(File); - - // custom DReyeVR Actor data write - DReyeVRCustomActorData.Write(File); - - // only write this once (at the beginning) - static bool bWroteConfigFile = false; - if (!bWroteConfigFile) { - // DReyeVR configuration/parameters - DReyeVRConfigFileData.Write(File); - bWroteConfigFile = true; - } - - // weather state - Weathers.Write(File); - - // end - Frames.WriteEnd(File); - - Clear(); -} - -void ACarlaRecorder::AddPosition(const CarlaRecorderPosition &Position) -{ - if (Enabled) - { - Positions.Add(Position); - } -} - -void ACarlaRecorder::AddEvent(const CarlaRecorderEventAdd &Event) -{ - if (Enabled) - { - EventsAdd.Add(std::move(Event)); - } -} - -void ACarlaRecorder::AddEvent(const CarlaRecorderEventDel &Event) -{ - if (Enabled) - { - EventsDel.Add(std::move(Event)); - } -} - -void ACarlaRecorder::AddEvent(const CarlaRecorderEventParent &Event) -{ - if (Enabled) - { - EventsParent.Add(std::move(Event)); - } -} - -void ACarlaRecorder::AddCollision(AActor *Actor1, AActor *Actor2) -{ - if (Enabled) - { - CarlaRecorderCollision Collision; - - // some inits - Collision.Id = NextCollisionId++; - Collision.IsActor1Hero = false; - Collision.IsActor2Hero = false; - - // check actor 1 - FCarlaActor *FoundActor1 = Episode->GetActorRegistry().FindCarlaActor(Actor1); - if (FoundActor1 != nullptr) { - if (FoundActor1->GetActorInfo() != nullptr) - { - auto Role = FoundActor1->GetActorInfo()->Description.Variations.Find("role_name"); - if (Role != nullptr) - Collision.IsActor1Hero = (Role->Value == "hero"); - } - Collision.DatabaseId1 = FoundActor1->GetActorId(); - } - else { - Collision.DatabaseId1 = uint32_t(-1); // actor1 is not a registered Carla actor - } - - // check actor 2 - FCarlaActor *FoundActor2 = Episode->GetActorRegistry().FindCarlaActor(Actor2); - if (FoundActor2 != nullptr) { - if (FoundActor2->GetActorInfo() != nullptr) - { - auto Role = FoundActor2->GetActorInfo()->Description.Variations.Find("role_name"); - if (Role != nullptr) - Collision.IsActor2Hero = (Role->Value == "hero"); - } - Collision.DatabaseId2 = FoundActor2->GetActorId(); - } - else { - Collision.DatabaseId2 = uint32_t(-1); // actor2 is not a registered Carla actor - } - - Collisions.Add(std::move(Collision)); - } -} - -void ACarlaRecorder::AddState(const CarlaRecorderStateTrafficLight &State) -{ - if (Enabled) - { - States.Add(State); - } -} - -void ACarlaRecorder::AddAnimVehicle(const CarlaRecorderAnimVehicle &Vehicle) -{ - if (Enabled) - { - Vehicles.Add(Vehicle); - } -} - -void ACarlaRecorder::AddAnimWalker(const CarlaRecorderAnimWalker &Walker) -{ - if (Enabled) - { - Walkers.Add(Walker); - } -} - -void ACarlaRecorder::AddLightVehicle(const CarlaRecorderLightVehicle &LightVehicle) -{ - if (Enabled) - { - LightVehicles.Add(LightVehicle); - } -} - -void ACarlaRecorder::AddEventLightSceneChanged(const UCarlaLight* Light) -{ - if (Enabled) - { - CarlaRecorderLightScene LightScene = - { - Light->GetId(), - Light->GetLightIntensity(), - Light->GetLightColor(), - Light->GetLightOn(), - static_cast(Light->GetLightType()) - }; - - LightScenes.Add(LightScene); - } -} - -void ACarlaRecorder::AddKinematics(const CarlaRecorderKinematics &ActorKinematics) -{ - if (Enabled) - { - Kinematics.Add(ActorKinematics); - } -} - -void ACarlaRecorder::AddBoundingBox(const CarlaRecorderActorBoundingBox &ActorBoundingBox) -{ - if (Enabled) - { - BoundingBoxes.Add(ActorBoundingBox); - } -} - -void ACarlaRecorder::AddExistingActors(void) -{ - // registring all existing actors in first frame - FActorRegistry Registry = Episode->GetActorRegistry(); - for (auto& It : Registry) - { - const FCarlaActor* CarlaActor = It.Value.Get(); - if (CarlaActor != nullptr) - { - // create event - CreateRecorderEventAdd( - CarlaActor->GetActorId(), - static_cast(CarlaActor->GetActorType()), - CarlaActor->GetActorGlobalTransform(), - CarlaActor->GetActorInfo()->Description); - } - } - - UWorld *World = GetWorld(); - if(World) - { - UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem(); - const auto& Lights = CarlaLightSubsystem->GetLights(); - for (const auto& LightPair : Lights) - { - UCarlaLight* Light = LightPair.Value; - AddEventLightSceneChanged(Light); - } - } - -} - -void ACarlaRecorder::AddStartingWeather(void) -{ - AWeather *Weather = AWeather::FindWeatherInstance(Episode->GetWorld()); - if (Weather) - { - AddWeather(Weather->GetCurrentWeather()); - } -} - -void ACarlaRecorder::CreateRecorderEventAdd( - uint32_t DatabaseId, - uint8_t Type, - const FTransform &Transform, - FActorDescription ActorDescription) -{ - CarlaRecorderActorDescription Description; - Description.UId = ActorDescription.UId; - Description.Id = ActorDescription.Id; - - // attributes - Description.Attributes.reserve(ActorDescription.Variations.Num()); - for (const auto &item : ActorDescription.Variations) - { - CarlaRecorderActorAttribute Attr; - Attr.Type = static_cast(item.Value.Type); - Attr.Id = item.Value.Id; - Attr.Value = item.Value.Value; - // check for empty attributes - if (!Attr.Id.IsEmpty()) - { - Description.Attributes.emplace_back(std::move(Attr)); - } - } - - // recorder event - CarlaRecorderEventAdd RecEvent - { - DatabaseId, - Type, - Transform.GetTranslation(), - Transform.GetRotation().Euler(), - std::move(Description) - }; - AddEvent(std::move(RecEvent)); - - FCarlaActor* CarlaActor = Episode->FindCarlaActor(DatabaseId); - // Other events related to spawning actors - // check if it is a vehicle to get initial physics control - ACarlaWheeledVehicle* Vehicle = Cast(CarlaActor->GetActor()); - if (Vehicle) - { - AddPhysicsControl(*Vehicle); - } - - ATrafficLightBase* TrafficLight = Cast(CarlaActor->GetActor()); - if (TrafficLight) - { - AddTrafficLightTime(*TrafficLight); - } - - ATrafficSignBase* TrafficSign = Cast(CarlaActor->GetActor()); - if (TrafficSign) - { - // Trigger volume in global coordinates - AddTriggerVolume(*TrafficSign); - } - else - { - // Bounding box in local coordinates - AddActorBoundingBox(CarlaActor); - } +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Carla.h" +#include "Carla/Actor/ActorDescription.h" +#include "Carla/Walker/WalkerControl.h" +#include "Carla/Walker/WalkerController.h" +#include "Carla/Weather/Weather.h" + +#include +#include "carla/rpc/VehicleLightState.h" +#include + +#include "CarlaRecorder.h" +#include "CarlaReplayerHelper.h" + +// DReyeVR include +#include "Carla/Actor/DReyeVRCustomActor.h" +#include "Carla/Game/CarlaStatics.h" +#include "Carla/Lights/CarlaLightSubsystem.h" +#include "Carla/Sensor/DReyeVRSensor.h" +#include "DReyeVRRecorder.h" + +#include +#include + +ACarlaRecorder::ACarlaRecorder(void) +{ + PrimaryActorTick.TickGroup = TG_PrePhysics; + Disable(); +} + +ACarlaRecorder::ACarlaRecorder(const FObjectInitializer &ObjectInitializer) + : Super(ObjectInitializer) +{ + PrimaryActorTick.TickGroup = TG_PrePhysics; + Disable(); +} + +std::string ACarlaRecorder::ShowFileInfo(std::string Name, bool bShowAll) +{ + return Query.QueryInfo(Name, bShowAll); +} + +std::string ACarlaRecorder::ShowFileCollisions(std::string Name, char Type1, char Type2) +{ + return Query.QueryCollisions(Name, Type1, Type2); +} + +std::string ACarlaRecorder::ShowFileActorsBlocked(std::string Name, double MinTime, double MinDistance) +{ + return Query.QueryBlocked(Name, MinTime, MinDistance); +} + +std::string ACarlaRecorder::ReplayFile(std::string Name, double TimeStart, double Duration, + uint32_t FollowId, bool ReplaySensors) +{ + Stop(); + return Replayer.ReplayFile(Name, TimeStart, Duration, FollowId, ReplaySensors); +} + +void ACarlaRecorder::SetReplayerTimeFactor(double TimeFactor) +{ + Replayer.SetTimeFactor(TimeFactor); +} + +void ACarlaRecorder::SetReplayerIgnoreHero(bool IgnoreHero) +{ + Replayer.SetIgnoreHero(IgnoreHero); +} + +void ACarlaRecorder::StopReplayer(bool KeepActors) +{ + Replayer.Stop(KeepActors); +} + +void ACarlaRecorder::Ticking(float DeltaSeconds) +{ + TRACE_CPUPROFILER_EVENT_SCOPE(ACarlaRecorder::Ticking); + Super::Tick(DeltaSeconds); + + if (!Episode) + return; + + // check if recording + if (Enabled) + { + PlatformTime.UpdateTime(); + const FActorRegistry &Registry = Episode->GetActorRegistry(); + + // Skip the spectator actor + FCarlaActor* CarlaSpectator = Episode->FindCarlaActor(Episode->GetSpectatorPawn()); + + // through all actors in registry + for (auto It = Registry.begin(); It != Registry.end(); ++It) + { + FCarlaActor* View = It.Value().Get(); + + if (CarlaSpectator && (View->GetActor() == CarlaSpectator->GetActor())) + continue; // don't record the spectator + + switch (View->GetActorType()) + { + // save the transform for props + case FCarlaActor::ActorType::Other: + AddActorPosition(View); + break; + + // save the transform of all vehicles + case FCarlaActor::ActorType::Vehicle: + AddActorPosition(View); + AddVehicleAnimation(View); + AddVehicleLight(View); + if (bAdditionalData) + { + AddActorKinematics(View); + } + break; + + // save the transform of all walkers + case FCarlaActor::ActorType::Walker: + AddActorPosition(View); + AddWalkerAnimation(View); + if (bAdditionalData) + { + AddActorKinematics(View); + } + break; + + // save the state of each traffic light + case FCarlaActor::ActorType::TrafficLight: + AddTrafficLightState(View); + break; + } + } + // Add the DReyeVR data + AddDReyeVRData(); + + // write all data for this frame + Write(DeltaSeconds); + } + else if (Episode->GetReplayer()->IsEnabled()) + { + // replayer + Episode->GetReplayer()->Tick(DeltaSeconds); + } +} + +void ACarlaRecorder::Enable(void) +{ + PrimaryActorTick.bCanEverTick = true; + Enabled = true; +} + +void ACarlaRecorder::Disable(void) +{ + PrimaryActorTick.bCanEverTick = false; + Enabled = false; +} + +void ACarlaRecorder::AddActorPosition(FCarlaActor *CarlaActor) +{ + check(CarlaActor != nullptr); + + FTransform Transform = CarlaActor->GetActorGlobalTransform(); + // get position of the vehicle + AddPosition(CarlaRecorderPosition + { + CarlaActor->GetActorId(), + Transform.GetLocation(), + Transform.GetRotation().Euler() + }); +} + +void ACarlaRecorder::AddVehicleAnimation(FCarlaActor *CarlaActor) +{ + check(CarlaActor != nullptr); + + if (CarlaActor->IsPendingKill()) + { + return; + } + + FVehicleControl Control; + CarlaActor->GetVehicleControl(Control); + + // save + CarlaRecorderAnimVehicle Record; + Record.DatabaseId = CarlaActor->GetActorId(); + Record.Steering = Control.Steer; + Record.Throttle = Control.Throttle; + Record.Brake = Control.Brake; + Record.bHandbrake = Control.bHandBrake; + Record.Gear = Control.Gear; + AddAnimVehicle(Record); +} + +void ACarlaRecorder::AddWalkerAnimation(FCarlaActor *CarlaActor) +{ + check(CarlaActor != nullptr); + + if (!CarlaActor->IsPendingKill()) + { + FWalkerControl Control; + CarlaActor->GetWalkerControl(Control); + AddAnimWalker(CarlaRecorderAnimWalker + { + CarlaActor->GetActorId(), + Control.Speed + }); + } +} + +void ACarlaRecorder::AddTrafficLightState(FCarlaActor *CarlaActor) +{ + check(CarlaActor != nullptr); + + ETrafficLightState LightState = CarlaActor->GetTrafficLightState(); + UTrafficLightController* Controller = CarlaActor->GetTrafficLightController(); + if (Controller) + { + ATrafficLightGroup* Group = Controller->GetGroup(); + if (Group) + { + AddState(CarlaRecorderStateTrafficLight + { + CarlaActor->GetActorId(), + Group->IsFrozen(), + Controller->GetElapsedTime(), + static_cast(LightState) + }); + } + } +} + +void ACarlaRecorder::AddVehicleLight(FCarlaActor *CarlaActor) +{ + check(CarlaActor != nullptr); + + FVehicleLightState LightState; + CarlaActor->GetVehicleLightState(LightState); + CarlaRecorderLightVehicle LightVehicle; + LightVehicle.DatabaseId = CarlaActor->GetActorId(); + LightVehicle.State = carla::rpc::VehicleLightState(LightState).light_state; + AddLightVehicle(LightVehicle); +} + +void ACarlaRecorder::AddActorKinematics(FCarlaActor *CarlaActor) +{ + check(CarlaActor != nullptr); + + FVector Velocity, AngularVelocity; + constexpr float TO_METERS = 1e-2; + Velocity = TO_METERS* CarlaActor->GetActorVelocity(); + AngularVelocity = CarlaActor->GetActorAngularVelocity(); + CarlaRecorderKinematics Kinematic = + { + CarlaActor->GetActorId(), + Velocity, + AngularVelocity + }; + AddKinematics(Kinematic); +} +void ACarlaRecorder::AddActorBoundingBox(FCarlaActor *CarlaActor) +{ + check(CarlaActor != nullptr); + + const auto &Box = CarlaActor->GetActorInfo()->BoundingBox; + CarlaRecorderActorBoundingBox BoundingBox = + { + CarlaActor->GetActorId(), + {Box.Origin, Box.Extent} + }; + + AddBoundingBox(BoundingBox); +} + +void ACarlaRecorder::AddDReyeVRData() +{ + static bool bAddedConfigFile; + if (!bAddedConfigFile) { + // add DReyeVR config files (only once at the beginning of recording) + DReyeVRConfigFileData.Add(ADReyeVRSensor::ConfigFile); + bAddedConfigFile = true; + } + + // Add the latest instance of the DReyeVR snapshot to our data + DReyeVRAggData.Add(DReyeVRDataRecorder(ADReyeVRSensor::Data)); + + for (auto &ActiveCAs : ADReyeVRCustomActor::ActiveCustomActors) + { + ADReyeVRCustomActor *CustomActor = ActiveCAs.second; + if (CustomActor != nullptr && CustomActor->IsActive() && CustomActor->GetShouldRecord()) + { + DReyeVRCustomActorData.Add(DReyeVRDataRecorder(&(CustomActor->GetInternals()))); + } + } +} + +void ACarlaRecorder::AddTriggerVolume(const ATrafficSignBase &TrafficSign) +{ + if (bAdditionalData) + { + TArray Triggers = TrafficSign.GetTriggerVolumes(); + if(!Triggers.Num()) + { + return; + } + UBoxComponent* Trigger = Triggers.Top(); + auto VolumeOrigin = Trigger->GetComponentLocation(); + auto VolumeExtent = Trigger->GetScaledBoxExtent(); + CarlaRecorderActorBoundingBox TriggerVolume = + { + Episode->GetActorRegistry().FindCarlaActor(&TrafficSign)->GetActorId(), + {VolumeOrigin, VolumeExtent} + }; + TriggerVolumes.Add(TriggerVolume); + } +} + +void ACarlaRecorder::AddPhysicsControl(const ACarlaWheeledVehicle& Vehicle) +{ + if (bAdditionalData) + { + CarlaRecorderPhysicsControl Control; + Control.DatabaseId = Episode->GetActorRegistry().FindCarlaActor(&Vehicle)->GetActorId(); + Control.VehiclePhysicsControl = Vehicle.GetVehiclePhysicsControl(); + PhysicsControls.Add(Control); + } +} + +void ACarlaRecorder::AddTrafficLightTime(const ATrafficLightBase& TrafficLight) +{ + if (bAdditionalData) + { + auto DatabaseId = Episode->GetActorRegistry().FindCarlaActor(&TrafficLight)->GetActorId(); + CarlaRecorderTrafficLightTime TrafficLightTime{ + DatabaseId, + TrafficLight.GetGreenTime(), + TrafficLight.GetYellowTime(), + TrafficLight.GetRedTime() + }; + TrafficLightTimes.Add(TrafficLightTime); + } +} + +void ACarlaRecorder::AddWeather(const FWeatherParameters& WeatherParams) +{ + CarlaRecorderWeather Weather; + Weather.Params = WeatherParams; + Weathers.Add(Weather); +} + +std::string ACarlaRecorder::Start(std::string Name, FString MapName, bool AdditionalData) +{ + // stop replayer if any in course + if (Replayer.IsEnabled()) + Replayer.Stop(); + + // stop recording + Stop(); + + // reset collisions Id + NextCollisionId = 0; + + // get the final path + filename + std::string Filename = GetRecorderFilename(Name); + + // binary file + File.open(Filename, std::ios::binary); + if (!File.is_open()) + { + return ""; + } + + // save info + Info.Version = 1; + Info.Magic = TEXT("CARLA_RECORDER"); + Info.Date = std::time(0); + Info.Mapfile = MapName; + + // write general info + Info.Write(File); + + Frames.Reset(); + PlatformTime.SetStartTime(); + + Enable(); + + bAdditionalData = AdditionalData; + + // add all existing actors + AddExistingActors(); + + // add current weather for start of recording + AddStartingWeather(); + + return std::string(Filename); +} + +void ACarlaRecorder::Stop(void) +{ + Disable(); + + if (File) + { + File.close(); + } + + Clear(); +} + +void ACarlaRecorder::Clear(void) +{ + EventsAdd.Clear(); + EventsDel.Clear(); + EventsParent.Clear(); + Collisions.Clear(); + Positions.Clear(); + States.Clear(); + Vehicles.Clear(); + Walkers.Clear(); + LightVehicles.Clear(); + LightScenes.Clear(); + Kinematics.Clear(); + BoundingBoxes.Clear(); + TriggerVolumes.Clear(); + PhysicsControls.Clear(); + TrafficLightTimes.Clear(); + DReyeVRAggData.Clear(); + DReyeVRCustomActorData.Clear(); + DReyeVRConfigFileData.Clear(); + Weathers.Clear(); +} + +void ACarlaRecorder::Write(double DeltaSeconds) +{ + // update this frame data + Frames.SetFrame(DeltaSeconds); + + // start + Frames.WriteStart(File); + + // events + EventsAdd.Write(File); + EventsDel.Write(File); + EventsParent.Write(File); + Collisions.Write(File); + + // positions and states + Positions.Write(File); + States.Write(File); + + // animations + Vehicles.Write(File); + Walkers.Write(File); + LightVehicles.Write(File); + LightScenes.Write(File); + + // additional info + if (bAdditionalData) + { + Kinematics.Write(File); + BoundingBoxes.Write(File); + TriggerVolumes.Write(File); + PlatformTime.Write(File); + PhysicsControls.Write(File); + TrafficLightTimes.Write(File); + } + // custom DReyeVR data + DReyeVRAggData.Write(File); + + // custom DReyeVR Actor data write + DReyeVRCustomActorData.Write(File); + + // only write this once (at the beginning) + static bool bWroteConfigFile = false; + if (!bWroteConfigFile) { + // DReyeVR configuration/parameters + DReyeVRConfigFileData.Write(File); + bWroteConfigFile = true; + } + + // weather state + Weathers.Write(File); + + // end + Frames.WriteEnd(File); + + Clear(); +} + +void ACarlaRecorder::AddPosition(const CarlaRecorderPosition &Position) +{ + if (Enabled) + { + Positions.Add(Position); + } +} + +void ACarlaRecorder::AddEvent(const CarlaRecorderEventAdd &Event) +{ + if (Enabled) + { + EventsAdd.Add(std::move(Event)); + } +} + +void ACarlaRecorder::AddEvent(const CarlaRecorderEventDel &Event) +{ + if (Enabled) + { + EventsDel.Add(std::move(Event)); + } +} + +void ACarlaRecorder::AddEvent(const CarlaRecorderEventParent &Event) +{ + if (Enabled) + { + EventsParent.Add(std::move(Event)); + } +} + +void ACarlaRecorder::AddCollision(AActor *Actor1, AActor *Actor2) +{ + if (Enabled) + { + CarlaRecorderCollision Collision; + + // some inits + Collision.Id = NextCollisionId++; + Collision.IsActor1Hero = false; + Collision.IsActor2Hero = false; + + // check actor 1 + FCarlaActor *FoundActor1 = Episode->GetActorRegistry().FindCarlaActor(Actor1); + if (FoundActor1 != nullptr) { + if (FoundActor1->GetActorInfo() != nullptr) + { + auto Role = FoundActor1->GetActorInfo()->Description.Variations.Find("role_name"); + if (Role != nullptr) + Collision.IsActor1Hero = (Role->Value == "hero"); + } + Collision.DatabaseId1 = FoundActor1->GetActorId(); + } + else { + Collision.DatabaseId1 = uint32_t(-1); // actor1 is not a registered Carla actor + } + + // check actor 2 + FCarlaActor *FoundActor2 = Episode->GetActorRegistry().FindCarlaActor(Actor2); + if (FoundActor2 != nullptr) { + if (FoundActor2->GetActorInfo() != nullptr) + { + auto Role = FoundActor2->GetActorInfo()->Description.Variations.Find("role_name"); + if (Role != nullptr) + Collision.IsActor2Hero = (Role->Value == "hero"); + } + Collision.DatabaseId2 = FoundActor2->GetActorId(); + } + else { + Collision.DatabaseId2 = uint32_t(-1); // actor2 is not a registered Carla actor + } + + Collisions.Add(std::move(Collision)); + } +} + +void ACarlaRecorder::AddState(const CarlaRecorderStateTrafficLight &State) +{ + if (Enabled) + { + States.Add(State); + } +} + +void ACarlaRecorder::AddAnimVehicle(const CarlaRecorderAnimVehicle &Vehicle) +{ + if (Enabled) + { + Vehicles.Add(Vehicle); + } +} + +void ACarlaRecorder::AddAnimWalker(const CarlaRecorderAnimWalker &Walker) +{ + if (Enabled) + { + Walkers.Add(Walker); + } +} + +void ACarlaRecorder::AddLightVehicle(const CarlaRecorderLightVehicle &LightVehicle) +{ + if (Enabled) + { + LightVehicles.Add(LightVehicle); + } +} + +void ACarlaRecorder::AddEventLightSceneChanged(const UCarlaLight* Light) +{ + if (Enabled) + { + CarlaRecorderLightScene LightScene = + { + Light->GetId(), + Light->GetLightIntensity(), + Light->GetLightColor(), + Light->GetLightOn(), + static_cast(Light->GetLightType()) + }; + + LightScenes.Add(LightScene); + } +} + +void ACarlaRecorder::AddKinematics(const CarlaRecorderKinematics &ActorKinematics) +{ + if (Enabled) + { + Kinematics.Add(ActorKinematics); + } +} + +void ACarlaRecorder::AddBoundingBox(const CarlaRecorderActorBoundingBox &ActorBoundingBox) +{ + if (Enabled) + { + BoundingBoxes.Add(ActorBoundingBox); + } +} + +void ACarlaRecorder::AddExistingActors(void) +{ + // registring all existing actors in first frame + FActorRegistry Registry = Episode->GetActorRegistry(); + for (auto& It : Registry) + { + const FCarlaActor* CarlaActor = It.Value.Get(); + if (CarlaActor != nullptr) + { + // create event + CreateRecorderEventAdd( + CarlaActor->GetActorId(), + static_cast(CarlaActor->GetActorType()), + CarlaActor->GetActorGlobalTransform(), + CarlaActor->GetActorInfo()->Description); + } + } + + UWorld *World = GetWorld(); + if(World) + { + UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem(); + const auto& Lights = CarlaLightSubsystem->GetLights(); + for (const auto& LightPair : Lights) + { + UCarlaLight* Light = LightPair.Value; + AddEventLightSceneChanged(Light); + } + } + +} + +void ACarlaRecorder::AddStartingWeather(void) +{ + AWeather *Weather = AWeather::FindWeatherInstance(Episode->GetWorld()); + if (Weather) + { + AddWeather(Weather->GetCurrentWeather()); + } +} + +void ACarlaRecorder::CreateRecorderEventAdd( + uint32_t DatabaseId, + uint8_t Type, + const FTransform &Transform, + FActorDescription ActorDescription) +{ + CarlaRecorderActorDescription Description; + Description.UId = ActorDescription.UId; + Description.Id = ActorDescription.Id; + + // attributes + Description.Attributes.reserve(ActorDescription.Variations.Num()); + for (const auto &item : ActorDescription.Variations) + { + CarlaRecorderActorAttribute Attr; + Attr.Type = static_cast(item.Value.Type); + Attr.Id = item.Value.Id; + Attr.Value = item.Value.Value; + // check for empty attributes + if (!Attr.Id.IsEmpty()) + { + Description.Attributes.emplace_back(std::move(Attr)); + } + } + + // recorder event + CarlaRecorderEventAdd RecEvent + { + DatabaseId, + Type, + Transform.GetTranslation(), + Transform.GetRotation().Euler(), + std::move(Description) + }; + AddEvent(std::move(RecEvent)); + + FCarlaActor* CarlaActor = Episode->FindCarlaActor(DatabaseId); + // Other events related to spawning actors + // check if it is a vehicle to get initial physics control + ACarlaWheeledVehicle* Vehicle = Cast(CarlaActor->GetActor()); + if (Vehicle) + { + AddPhysicsControl(*Vehicle); + } + + ATrafficLightBase* TrafficLight = Cast(CarlaActor->GetActor()); + if (TrafficLight) + { + AddTrafficLightTime(*TrafficLight); + } + + ATrafficSignBase* TrafficSign = Cast(CarlaActor->GetActor()); + if (TrafficSign) + { + // Trigger volume in global coordinates + AddTriggerVolume(*TrafficSign); + } + else + { + // Bounding box in local coordinates + AddActorBoundingBox(CarlaActor); + } } \ No newline at end of file diff --git a/Carla/Recorder/CarlaRecorder.h b/Carla/Recorder/CarlaRecorder.h index 621b170..138c6bf 100644 --- a/Carla/Recorder/CarlaRecorder.h +++ b/Carla/Recorder/CarlaRecorder.h @@ -1,228 +1,228 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -// #include "GameFramework/Actor.h" -#include - -#include "Carla/Actor/ActorDescription.h" - -#include "CarlaRecorderTraficLightTime.h" -#include "CarlaRecorderPhysicsControl.h" -#include "CarlaRecorderPlatformTime.h" -#include "CarlaRecorderBoundingBox.h" -#include "CarlaRecorderKinematics.h" -#include "CarlaRecorderLightScene.h" -#include "CarlaRecorderLightVehicle.h" -#include "CarlaRecorderAnimVehicle.h" -#include "CarlaRecorderAnimWalker.h" -#include "CarlaRecorderCollision.h" -#include "CarlaRecorderEventAdd.h" -#include "CarlaRecorderEventDel.h" -#include "CarlaRecorderEventParent.h" -#include "CarlaRecorderFrames.h" -#include "CarlaRecorderInfo.h" -#include "CarlaRecorderPosition.h" -#include "CarlaRecorderQuery.h" -#include "CarlaRecorderState.h" -#include "CarlaRecorderWeather.h" -#include "CarlaReplayer.h" - -// DReyeVR includes -#include "DReyeVRRecorder.h" -#include "Carla/Sensor/DReyeVRData.h" - -#include "CarlaRecorder.generated.h" - -class AActor; -class UCarlaEpisode; -class ACarlaWheeledVehicle; -class UCarlaLight; -class ATrafficSignBase; -class ATrafficLightBase; - -#define DREYEVR_PACKET_ID 139 -#define DREYEVR_CUSTOM_ACTOR_PACKET_ID 140 -#define DREYEVR_CONFIG_FILE_PACKET_ID 141 - -enum class CarlaRecorderPacketId : uint8_t -{ - FrameStart = 0, - FrameEnd, - EventAdd, - EventDel, - EventParent, - Collision, - Position, - State, - AnimVehicle, - AnimWalker, - VehicleLight, - SceneLight, - Kinematics, - BoundingBox, - PlatformTime, - PhysicsControl, - TrafficLightTime, - TriggerVolume, - Weather, - // "We suggest to use id over 100 for user custom packets, because this list will keep growing in the future" - DReyeVR = DREYEVR_PACKET_ID, // our custom DReyeVR packet (for raw sensor data) - DReyeVRCustomActor = DREYEVR_CUSTOM_ACTOR_PACKET_ID, // custom DReyeVR actors (not raw sensor data) - DReyeVRConfigFile = DREYEVR_CONFIG_FILE_PACKET_ID // DReyeVR configuration files (parameters) -}; - -/// Recorder for the simulation -UCLASS() -class CARLA_API ACarlaRecorder : public AActor -{ - GENERATED_BODY() - -public: - - ACarlaRecorder(void); - ACarlaRecorder(const FObjectInitializer &InObjectInitializer); - - // enable / disable - bool IsEnabled(void) - { - return Enabled; - } - void Enable(void); - - void Disable(void); - - // start / stop - std::string Start(std::string Name, FString MapName, bool AdditionalData = false); - - void Stop(void); - - void Clear(void); - - void Write(double DeltaSeconds); - - // events - void AddEvent(const CarlaRecorderEventAdd &Event); - - void AddEvent(const CarlaRecorderEventDel &Event); - - void AddEvent(const CarlaRecorderEventParent &Event); - - void AddCollision(AActor *Actor1, AActor *Actor2); - - void AddPosition(const CarlaRecorderPosition &Position); - - void AddState(const CarlaRecorderStateTrafficLight &State); - - void AddAnimVehicle(const CarlaRecorderAnimVehicle &Vehicle); - - void AddAnimWalker(const CarlaRecorderAnimWalker &Walker); - - void AddLightVehicle(const CarlaRecorderLightVehicle &LightVehicle); - - void AddEventLightSceneChanged(const UCarlaLight* Light); - - void AddKinematics(const CarlaRecorderKinematics &ActorKinematics); - - void AddBoundingBox(const CarlaRecorderActorBoundingBox &ActorBoundingBox); - - void AddTriggerVolume(const ATrafficSignBase &TrafficSign); - - void AddPhysicsControl(const ACarlaWheeledVehicle& Vehicle); - - void AddTrafficLightTime(const ATrafficLightBase& TrafficLight); - - void AddWeather(const FWeatherParameters& WeatherParams); - - // set episode - void SetEpisode(UCarlaEpisode *ThisEpisode) - { - Episode = ThisEpisode; - Replayer.SetEpisode(ThisEpisode); - } - - void CreateRecorderEventAdd( - uint32_t DatabaseId, - uint8_t Type, - const FTransform &Transform, - FActorDescription ActorDescription); - - // replayer - CarlaReplayer *GetReplayer(void) - { - return &Replayer; - } - - // queries - std::string ShowFileInfo(std::string Name, bool bShowAll = false); - std::string ShowFileCollisions(std::string Name, char Type1, char Type2); - std::string ShowFileActorsBlocked(std::string Name, double MinTime = 30, double MinDistance = 10); - - // replayer - std::string ReplayFile(std::string Name, double TimeStart, double Duration, - uint32_t FollowId, bool ReplaySensors); - void SetReplayerTimeFactor(double TimeFactor); - void SetReplayerIgnoreHero(bool IgnoreHero); - void StopReplayer(bool KeepActors = false); - - void Ticking(float DeltaSeconds); - -private: - - bool Enabled; // enabled or not - - // enabling this records additional data (kinematics, bounding boxes, etc) - bool bAdditionalData = false; - - uint32_t NextCollisionId = 0; - - // files - std::ofstream File; - - UCarlaEpisode *Episode = nullptr; - - // structures - CarlaRecorderInfo Info; - CarlaRecorderFrames Frames; - CarlaRecorderEventsAdd EventsAdd; - CarlaRecorderEventsDel EventsDel; - CarlaRecorderEventsParent EventsParent; - CarlaRecorderCollisions Collisions; - CarlaRecorderPositions Positions; - CarlaRecorderStates States; - CarlaRecorderAnimVehicles Vehicles; - CarlaRecorderAnimWalkers Walkers; - CarlaRecorderLightVehicles LightVehicles; - CarlaRecorderLightScenes LightScenes; - CarlaRecorderActorsKinematics Kinematics; - CarlaRecorderActorBoundingBoxes BoundingBoxes; - CarlaRecorderActorTriggerVolumes TriggerVolumes; - CarlaRecorderPlatformTime PlatformTime; - CarlaRecorderPhysicsControls PhysicsControls; - CarlaRecorderTrafficLightTimes TrafficLightTimes; - CarlaRecorderWeathers Weathers; - DReyeVRDataRecorders DReyeVRAggData; - DReyeVRDataRecorders DReyeVRCustomActorData; - DReyeVRDataRecorders DReyeVRConfigFileData; - - // replayer - CarlaReplayer Replayer; - - // query tools - CarlaRecorderQuery Query; - - void AddExistingActors(void); - void AddStartingWeather(void); - void AddActorPosition(FCarlaActor *CarlaActor); - void AddWalkerAnimation(FCarlaActor *CarlaActor); - void AddVehicleAnimation(FCarlaActor *CarlaActor); - void AddTrafficLightState(FCarlaActor *CarlaActor); - void AddVehicleLight(FCarlaActor *CarlaActor); - void AddActorKinematics(FCarlaActor *CarlaActor); - void AddActorBoundingBox(FCarlaActor *CarlaActor); - void AddDReyeVRData(); -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +// #include "GameFramework/Actor.h" +#include + +#include "Carla/Actor/ActorDescription.h" + +#include "CarlaRecorderTraficLightTime.h" +#include "CarlaRecorderPhysicsControl.h" +#include "CarlaRecorderPlatformTime.h" +#include "CarlaRecorderBoundingBox.h" +#include "CarlaRecorderKinematics.h" +#include "CarlaRecorderLightScene.h" +#include "CarlaRecorderLightVehicle.h" +#include "CarlaRecorderAnimVehicle.h" +#include "CarlaRecorderAnimWalker.h" +#include "CarlaRecorderCollision.h" +#include "CarlaRecorderEventAdd.h" +#include "CarlaRecorderEventDel.h" +#include "CarlaRecorderEventParent.h" +#include "CarlaRecorderFrames.h" +#include "CarlaRecorderInfo.h" +#include "CarlaRecorderPosition.h" +#include "CarlaRecorderQuery.h" +#include "CarlaRecorderState.h" +#include "CarlaRecorderWeather.h" +#include "CarlaReplayer.h" + +// DReyeVR includes +#include "DReyeVRRecorder.h" +#include "Carla/Sensor/DReyeVRData.h" + +#include "CarlaRecorder.generated.h" + +class AActor; +class UCarlaEpisode; +class ACarlaWheeledVehicle; +class UCarlaLight; +class ATrafficSignBase; +class ATrafficLightBase; + +#define DREYEVR_PACKET_ID 139 +#define DREYEVR_CUSTOM_ACTOR_PACKET_ID 140 +#define DREYEVR_CONFIG_FILE_PACKET_ID 141 + +enum class CarlaRecorderPacketId : uint8_t +{ + FrameStart = 0, + FrameEnd, + EventAdd, + EventDel, + EventParent, + Collision, + Position, + State, + AnimVehicle, + AnimWalker, + VehicleLight, + SceneLight, + Kinematics, + BoundingBox, + PlatformTime, + PhysicsControl, + TrafficLightTime, + TriggerVolume, + Weather, + // "We suggest to use id over 100 for user custom packets, because this list will keep growing in the future" + DReyeVR = DREYEVR_PACKET_ID, // our custom DReyeVR packet (for raw sensor data) + DReyeVRCustomActor = DREYEVR_CUSTOM_ACTOR_PACKET_ID, // custom DReyeVR actors (not raw sensor data) + DReyeVRConfigFile = DREYEVR_CONFIG_FILE_PACKET_ID // DReyeVR configuration files (parameters) +}; + +/// Recorder for the simulation +UCLASS() +class CARLA_API ACarlaRecorder : public AActor +{ + GENERATED_BODY() + +public: + + ACarlaRecorder(void); + ACarlaRecorder(const FObjectInitializer &InObjectInitializer); + + // enable / disable + bool IsEnabled(void) + { + return Enabled; + } + void Enable(void); + + void Disable(void); + + // start / stop + std::string Start(std::string Name, FString MapName, bool AdditionalData = false); + + void Stop(void); + + void Clear(void); + + void Write(double DeltaSeconds); + + // events + void AddEvent(const CarlaRecorderEventAdd &Event); + + void AddEvent(const CarlaRecorderEventDel &Event); + + void AddEvent(const CarlaRecorderEventParent &Event); + + void AddCollision(AActor *Actor1, AActor *Actor2); + + void AddPosition(const CarlaRecorderPosition &Position); + + void AddState(const CarlaRecorderStateTrafficLight &State); + + void AddAnimVehicle(const CarlaRecorderAnimVehicle &Vehicle); + + void AddAnimWalker(const CarlaRecorderAnimWalker &Walker); + + void AddLightVehicle(const CarlaRecorderLightVehicle &LightVehicle); + + void AddEventLightSceneChanged(const UCarlaLight* Light); + + void AddKinematics(const CarlaRecorderKinematics &ActorKinematics); + + void AddBoundingBox(const CarlaRecorderActorBoundingBox &ActorBoundingBox); + + void AddTriggerVolume(const ATrafficSignBase &TrafficSign); + + void AddPhysicsControl(const ACarlaWheeledVehicle& Vehicle); + + void AddTrafficLightTime(const ATrafficLightBase& TrafficLight); + + void AddWeather(const FWeatherParameters& WeatherParams); + + // set episode + void SetEpisode(UCarlaEpisode *ThisEpisode) + { + Episode = ThisEpisode; + Replayer.SetEpisode(ThisEpisode); + } + + void CreateRecorderEventAdd( + uint32_t DatabaseId, + uint8_t Type, + const FTransform &Transform, + FActorDescription ActorDescription); + + // replayer + CarlaReplayer *GetReplayer(void) + { + return &Replayer; + } + + // queries + std::string ShowFileInfo(std::string Name, bool bShowAll = false); + std::string ShowFileCollisions(std::string Name, char Type1, char Type2); + std::string ShowFileActorsBlocked(std::string Name, double MinTime = 30, double MinDistance = 10); + + // replayer + std::string ReplayFile(std::string Name, double TimeStart, double Duration, + uint32_t FollowId, bool ReplaySensors); + void SetReplayerTimeFactor(double TimeFactor); + void SetReplayerIgnoreHero(bool IgnoreHero); + void StopReplayer(bool KeepActors = false); + + void Ticking(float DeltaSeconds); + +private: + + bool Enabled; // enabled or not + + // enabling this records additional data (kinematics, bounding boxes, etc) + bool bAdditionalData = false; + + uint32_t NextCollisionId = 0; + + // files + std::ofstream File; + + UCarlaEpisode *Episode = nullptr; + + // structures + CarlaRecorderInfo Info; + CarlaRecorderFrames Frames; + CarlaRecorderEventsAdd EventsAdd; + CarlaRecorderEventsDel EventsDel; + CarlaRecorderEventsParent EventsParent; + CarlaRecorderCollisions Collisions; + CarlaRecorderPositions Positions; + CarlaRecorderStates States; + CarlaRecorderAnimVehicles Vehicles; + CarlaRecorderAnimWalkers Walkers; + CarlaRecorderLightVehicles LightVehicles; + CarlaRecorderLightScenes LightScenes; + CarlaRecorderActorsKinematics Kinematics; + CarlaRecorderActorBoundingBoxes BoundingBoxes; + CarlaRecorderActorTriggerVolumes TriggerVolumes; + CarlaRecorderPlatformTime PlatformTime; + CarlaRecorderPhysicsControls PhysicsControls; + CarlaRecorderTrafficLightTimes TrafficLightTimes; + CarlaRecorderWeathers Weathers; + DReyeVRDataRecorders DReyeVRAggData; + DReyeVRDataRecorders DReyeVRCustomActorData; + DReyeVRDataRecorders DReyeVRConfigFileData; + + // replayer + CarlaReplayer Replayer; + + // query tools + CarlaRecorderQuery Query; + + void AddExistingActors(void); + void AddStartingWeather(void); + void AddActorPosition(FCarlaActor *CarlaActor); + void AddWalkerAnimation(FCarlaActor *CarlaActor); + void AddVehicleAnimation(FCarlaActor *CarlaActor); + void AddTrafficLightState(FCarlaActor *CarlaActor); + void AddVehicleLight(FCarlaActor *CarlaActor); + void AddActorKinematics(FCarlaActor *CarlaActor); + void AddActorBoundingBox(FCarlaActor *CarlaActor); + void AddDReyeVRData(); +}; diff --git a/Carla/Recorder/CarlaRecorderHelpers.cpp b/Carla/Recorder/CarlaRecorderHelpers.cpp index 8cf3982..4fb9799 100644 --- a/Carla/Recorder/CarlaRecorderHelpers.cpp +++ b/Carla/Recorder/CarlaRecorderHelpers.cpp @@ -1,147 +1,147 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include - -#include "UnrealString.h" -#include "CarlaRecorderHelpers.h" - -// create a temporal buffer to convert from and to FString and bytes -static std::vector CarlaRecorderHelperBuffer; - -// get the final path + filename -std::string GetRecorderFilename(std::string Filename) -{ - std::string Filename2; - - // check if a relative path was specified - if (Filename.find("\\") != std::string::npos || Filename.find("/") != std::string::npos || Filename.find(":") != std::string::npos) - Filename2 = Filename; - else - { - FString Path = FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir()); - Filename2 = TCHAR_TO_UTF8(*Path) + Filename; - } - - return Filename2; -} - -// ------ -// write -// ------ - -// write binary data from FVector -void WriteFVector(std::ofstream &OutFile, const FVector &InObj) -{ - WriteValue(OutFile, InObj.X); - WriteValue(OutFile, InObj.Y); - WriteValue(OutFile, InObj.Z); -} - -// write binary data from FRotator -void WriteFRotator(std::ofstream &OutFile, const FRotator &InObj) -{ - WriteValue(OutFile, InObj.Pitch); - WriteValue(OutFile, InObj.Roll); - WriteValue(OutFile, InObj.Yaw); -} - -// write binary data from FVector2D -void WriteFVector2D(std::ofstream &OutFile, const FVector2D &InObj) -{ - WriteValue(OutFile, InObj.X); - WriteValue(OutFile, InObj.Y); -} - -// write binary data to FLinearColor -void WriteFLinearColor(std::ofstream &InFile, const FLinearColor &InObj) -{ - WriteValue(InFile, InObj.A); - WriteValue(InFile, InObj.B); - WriteValue(InFile, InObj.G); - WriteValue(InFile, InObj.R); -} - -// write binary data from FTransform -// void WriteFTransform(std::ofstream &OutFile, const FTransform &InObj){ -// WriteFVector(OutFile, InObj.GetTranslation()); -// WriteFVector(OutFile, InObj.GetRotation().Euler()); -// } - -// write binary data from FString (length + text) -void WriteFString(std::ofstream &OutFile, const FString &InObj) -{ - // encode the string to UTF8 to know the final length - FTCHARToUTF8 EncodedString(*InObj); - int16_t Length = EncodedString.Length(); - // write - WriteValue(OutFile, Length); - OutFile.write(reinterpret_cast(TCHAR_TO_UTF8(*InObj)), Length); -} - -// ----- -// read -// ----- - -// read binary data to FVector -void ReadFVector(std::ifstream &InFile, FVector &OutObj) -{ - ReadValue(InFile, OutObj.X); - ReadValue(InFile, OutObj.Y); - ReadValue(InFile, OutObj.Z); -} - -// read binary data to FRotator -void ReadFRotator(std::ifstream &InFile, FRotator &OutObj) -{ - ReadValue(InFile, OutObj.Pitch); - ReadValue(InFile, OutObj.Roll); - ReadValue(InFile, OutObj.Yaw); -} - -// read binary data to FVector2D -void ReadFVector2D(std::ifstream &InFile, FVector2D &OutObj) -{ - ReadValue(InFile, OutObj.X); - ReadValue(InFile, OutObj.Y); -} - -// read binary data to FLinearColor -void ReadFLinearColor(std::ifstream &InFile, FLinearColor &OutObj) -{ - ReadValue(InFile, OutObj.A); - ReadValue(InFile, OutObj.B); - ReadValue(InFile, OutObj.G); - ReadValue(InFile, OutObj.R); -} - -// read binary data to FTransform -// void ReadFTransform(std::ifstream &InFile, FTransform &OutObj){ -// FVector Vec; -// ReadFVector(InFile, Vec); -// OutObj.SetTranslation(Vec); -// ReadFVector(InFile, Vec); -// OutObj.GetRotation().MakeFromEuler(Vec); -// } - -// read binary data to FString (length + text) -void ReadFString(std::ifstream &InFile, FString &OutObj) -{ - uint16_t Length; - ReadValue(InFile, Length); - // make room in vector buffer - if (CarlaRecorderHelperBuffer.capacity() < Length + 1) - { - CarlaRecorderHelperBuffer.reserve(Length + 1); - } - CarlaRecorderHelperBuffer.clear(); - // initialize the vector space with 0 - CarlaRecorderHelperBuffer.resize(Length + 1); - // read - InFile.read(reinterpret_cast(CarlaRecorderHelperBuffer.data()), Length); - // convert from UTF8 to FString - OutObj = FString(UTF8_TO_TCHAR(CarlaRecorderHelperBuffer.data())); -} +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include + +#include "UnrealString.h" +#include "CarlaRecorderHelpers.h" + +// create a temporal buffer to convert from and to FString and bytes +static std::vector CarlaRecorderHelperBuffer; + +// get the final path + filename +std::string GetRecorderFilename(std::string Filename) +{ + std::string Filename2; + + // check if a relative path was specified + if (Filename.find("\\") != std::string::npos || Filename.find("/") != std::string::npos || Filename.find(":") != std::string::npos) + Filename2 = Filename; + else + { + FString Path = FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir()); + Filename2 = TCHAR_TO_UTF8(*Path) + Filename; + } + + return Filename2; +} + +// ------ +// write +// ------ + +// write binary data from FVector +void WriteFVector(std::ofstream &OutFile, const FVector &InObj) +{ + WriteValue(OutFile, InObj.X); + WriteValue(OutFile, InObj.Y); + WriteValue(OutFile, InObj.Z); +} + +// write binary data from FRotator +void WriteFRotator(std::ofstream &OutFile, const FRotator &InObj) +{ + WriteValue(OutFile, InObj.Pitch); + WriteValue(OutFile, InObj.Roll); + WriteValue(OutFile, InObj.Yaw); +} + +// write binary data from FVector2D +void WriteFVector2D(std::ofstream &OutFile, const FVector2D &InObj) +{ + WriteValue(OutFile, InObj.X); + WriteValue(OutFile, InObj.Y); +} + +// write binary data to FLinearColor +void WriteFLinearColor(std::ofstream &InFile, const FLinearColor &InObj) +{ + WriteValue(InFile, InObj.A); + WriteValue(InFile, InObj.B); + WriteValue(InFile, InObj.G); + WriteValue(InFile, InObj.R); +} + +// write binary data from FTransform +// void WriteFTransform(std::ofstream &OutFile, const FTransform &InObj){ +// WriteFVector(OutFile, InObj.GetTranslation()); +// WriteFVector(OutFile, InObj.GetRotation().Euler()); +// } + +// write binary data from FString (length + text) +void WriteFString(std::ofstream &OutFile, const FString &InObj) +{ + // encode the string to UTF8 to know the final length + FTCHARToUTF8 EncodedString(*InObj); + int16_t Length = EncodedString.Length(); + // write + WriteValue(OutFile, Length); + OutFile.write(reinterpret_cast(TCHAR_TO_UTF8(*InObj)), Length); +} + +// ----- +// read +// ----- + +// read binary data to FVector +void ReadFVector(std::ifstream &InFile, FVector &OutObj) +{ + ReadValue(InFile, OutObj.X); + ReadValue(InFile, OutObj.Y); + ReadValue(InFile, OutObj.Z); +} + +// read binary data to FRotator +void ReadFRotator(std::ifstream &InFile, FRotator &OutObj) +{ + ReadValue(InFile, OutObj.Pitch); + ReadValue(InFile, OutObj.Roll); + ReadValue(InFile, OutObj.Yaw); +} + +// read binary data to FVector2D +void ReadFVector2D(std::ifstream &InFile, FVector2D &OutObj) +{ + ReadValue(InFile, OutObj.X); + ReadValue(InFile, OutObj.Y); +} + +// read binary data to FLinearColor +void ReadFLinearColor(std::ifstream &InFile, FLinearColor &OutObj) +{ + ReadValue(InFile, OutObj.A); + ReadValue(InFile, OutObj.B); + ReadValue(InFile, OutObj.G); + ReadValue(InFile, OutObj.R); +} + +// read binary data to FTransform +// void ReadFTransform(std::ifstream &InFile, FTransform &OutObj){ +// FVector Vec; +// ReadFVector(InFile, Vec); +// OutObj.SetTranslation(Vec); +// ReadFVector(InFile, Vec); +// OutObj.GetRotation().MakeFromEuler(Vec); +// } + +// read binary data to FString (length + text) +void ReadFString(std::ifstream &InFile, FString &OutObj) +{ + uint16_t Length; + ReadValue(InFile, Length); + // make room in vector buffer + if (CarlaRecorderHelperBuffer.capacity() < Length + 1) + { + CarlaRecorderHelperBuffer.reserve(Length + 1); + } + CarlaRecorderHelperBuffer.clear(); + // initialize the vector space with 0 + CarlaRecorderHelperBuffer.resize(Length + 1); + // read + InFile.read(reinterpret_cast(CarlaRecorderHelperBuffer.data()), Length); + // convert from UTF8 to FString + OutObj = FString(UTF8_TO_TCHAR(CarlaRecorderHelperBuffer.data())); +} diff --git a/Carla/Recorder/CarlaRecorderHelpers.h b/Carla/Recorder/CarlaRecorderHelpers.h index 4253435..0120937 100644 --- a/Carla/Recorder/CarlaRecorderHelpers.h +++ b/Carla/Recorder/CarlaRecorderHelpers.h @@ -1,118 +1,118 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include - -// get the final path + filename -std::string GetRecorderFilename(std::string Filename); - -// --------- -// recorder -// --------- - -// write binary data (using sizeof()) -template -void WriteValue(std::ofstream &OutFile, const T &InObj) -{ - OutFile.write(reinterpret_cast(&InObj), sizeof(T)); -} - -template -void WriteStdVector(std::ofstream &OutFile, const std::vector &InVec) -{ - WriteValue(OutFile, InVec.size()); - for (const auto& InObj : InVec) - { - WriteValue(OutFile, InObj); - } -} - -template -void WriteTArray(std::ofstream &OutFile, const TArray &InVec) -{ - WriteValue(OutFile, InVec.Num()); - for (const auto& InObj : InVec) - { - WriteValue(OutFile, InObj); - } -} - -// write binary data from FVector -void WriteFVector(std::ofstream &OutFile, const FVector &InObj); - -// write binary data from FRotator -void WriteFRotator(std::ofstream &OutFile, const FRotator &InObj); - -// write binary data from FVector2D -void WriteFVector2D(std::ofstream &OutFile, const FVector2D &InObj); - -// write binary data from FLinearColor -void WriteFLinearColor(std::ofstream &OutFile, const FLinearColor &InObj); - -// write binary data from FTransform -// void WriteFTransform(std::ofstream &OutFile, const FTransform &InObj); -// write binary data from FString (length + text) -void WriteFString(std::ofstream &OutFile, const FString &InObj); - -// --------- -// replayer -// --------- - -// read binary data (using sizeof()) -template -void ReadValue(std::ifstream &InFile, T &OutObj) -{ - InFile.read(reinterpret_cast(&OutObj), sizeof(T)); -} - -template -void ReadStdVector(std::ifstream &InFile, std::vector &OutVec) -{ - uint32_t VecSize; - ReadValue(InFile, VecSize); - OutVec.clear(); - for (uint32_t i = 0; i < VecSize; ++i) - { - T InObj; - ReadValue(InFile, InObj); - OutVec.push_back(InObj); - } -} - -template -void ReadTArray(std::ifstream &InFile, TArray &OutVec) -{ - uint32_t VecSize; - ReadValue(InFile, VecSize); - OutVec.Empty(); - for (uint32_t i = 0; i < VecSize; ++i) - { - T InObj; - ReadValue(InFile, InObj); - OutVec.Add(InObj); - } -} - -// read binary data from FVector -void ReadFVector(std::ifstream &InFile, FVector &OutObj); - -// read binary data from FRotator -void ReadFRotator(std::ifstream &InFile, FRotator &OutObj); - -// read binary data from FVector2D -void ReadFVector2D(std::ifstream &InFile, FVector2D &OutObj); - -// read binary data from FLinearColor -void ReadFLinearColor(std::ifstream &OutFile, FLinearColor &OutObj); - - -// read binary data from FTransform -// void ReadTransform(std::ifstream &InFile, FTransform &OutObj); -// read binary data from FString (length + text) -void ReadFString(std::ifstream &InFile, FString &OutObj); +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +// get the final path + filename +std::string GetRecorderFilename(std::string Filename); + +// --------- +// recorder +// --------- + +// write binary data (using sizeof()) +template +void WriteValue(std::ofstream &OutFile, const T &InObj) +{ + OutFile.write(reinterpret_cast(&InObj), sizeof(T)); +} + +template +void WriteStdVector(std::ofstream &OutFile, const std::vector &InVec) +{ + WriteValue(OutFile, InVec.size()); + for (const auto& InObj : InVec) + { + WriteValue(OutFile, InObj); + } +} + +template +void WriteTArray(std::ofstream &OutFile, const TArray &InVec) +{ + WriteValue(OutFile, InVec.Num()); + for (const auto& InObj : InVec) + { + WriteValue(OutFile, InObj); + } +} + +// write binary data from FVector +void WriteFVector(std::ofstream &OutFile, const FVector &InObj); + +// write binary data from FRotator +void WriteFRotator(std::ofstream &OutFile, const FRotator &InObj); + +// write binary data from FVector2D +void WriteFVector2D(std::ofstream &OutFile, const FVector2D &InObj); + +// write binary data from FLinearColor +void WriteFLinearColor(std::ofstream &OutFile, const FLinearColor &InObj); + +// write binary data from FTransform +// void WriteFTransform(std::ofstream &OutFile, const FTransform &InObj); +// write binary data from FString (length + text) +void WriteFString(std::ofstream &OutFile, const FString &InObj); + +// --------- +// replayer +// --------- + +// read binary data (using sizeof()) +template +void ReadValue(std::ifstream &InFile, T &OutObj) +{ + InFile.read(reinterpret_cast(&OutObj), sizeof(T)); +} + +template +void ReadStdVector(std::ifstream &InFile, std::vector &OutVec) +{ + uint32_t VecSize; + ReadValue(InFile, VecSize); + OutVec.clear(); + for (uint32_t i = 0; i < VecSize; ++i) + { + T InObj; + ReadValue(InFile, InObj); + OutVec.push_back(InObj); + } +} + +template +void ReadTArray(std::ifstream &InFile, TArray &OutVec) +{ + uint32_t VecSize; + ReadValue(InFile, VecSize); + OutVec.Empty(); + for (uint32_t i = 0; i < VecSize; ++i) + { + T InObj; + ReadValue(InFile, InObj); + OutVec.Add(InObj); + } +} + +// read binary data from FVector +void ReadFVector(std::ifstream &InFile, FVector &OutObj); + +// read binary data from FRotator +void ReadFRotator(std::ifstream &InFile, FRotator &OutObj); + +// read binary data from FVector2D +void ReadFVector2D(std::ifstream &InFile, FVector2D &OutObj); + +// read binary data from FLinearColor +void ReadFLinearColor(std::ifstream &OutFile, FLinearColor &OutObj); + + +// read binary data from FTransform +// void ReadTransform(std::ifstream &InFile, FTransform &OutObj); +// read binary data from FString (length + text) +void ReadFString(std::ifstream &InFile, FString &OutObj); diff --git a/Carla/Recorder/CarlaRecorderQuery.cpp b/Carla/Recorder/CarlaRecorderQuery.cpp index 17b7cef..801eb32 100644 --- a/Carla/Recorder/CarlaRecorderQuery.cpp +++ b/Carla/Recorder/CarlaRecorderQuery.cpp @@ -1,994 +1,994 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaRecorderHelpers.h" - -#include -#include -#include - -#include -#include -#include -#include - -inline bool CarlaRecorderQuery::ReadHeader(void) -{ - if (File.eof()) - { - return false; - } - - ReadValue(File, Header.Id); - ReadValue(File, Header.Size); - - return true; -} - -inline void CarlaRecorderQuery::SkipPacket(void) -{ - File.seekg(Header.Size, std::ios::cur); -} - -inline bool CarlaRecorderQuery::CheckFileInfo(std::stringstream &Info) -{ - // read Info - RecInfo.Read(File); - - // check magic string - if (RecInfo.Magic != "CARLA_RECORDER") - { - Info << "File is not a CARLA recorder" << std::endl; - return false; - } - - // show general Info - Info << "Version: " << RecInfo.Version << std::endl; - Info << "Map: " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl; - tm *TimeInfo = localtime(&RecInfo.Date); - char DateStr[100]; - strftime(DateStr, sizeof(DateStr), "%x %X", TimeInfo); - Info << "Date: " << DateStr << std::endl << std::endl; - - return true; -} - -std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll) -{ - std::stringstream Info; - - // get the final path + filename - std::string Filename2 = GetRecorderFilename(Filename); - - // try to open - File.open(Filename2, std::ios::binary); - if (!File.is_open()) - { - Info << "File " << Filename2 << " not found on server\n"; - return Info.str(); - } - - uint16_t i, Total; - bool bFramePrinted = false; - - // lambda for repeating task - auto PrintFrame = [this](std::stringstream &Info) - { - Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n"; - }; - - if (!CheckFileInfo(Info)) - return Info.str(); - - // parse only frames - while (File) - { - - // get header - if (!ReadHeader()) - { - break; - } - - // check for a frame packet - switch (Header.Id) - { - // frame - case static_cast(CarlaRecorderPacketId::FrameStart): - Frame.Read(File); - if (bShowAll) - { - PrintFrame(Info); - bFramePrinted = true; - } - else - bFramePrinted = false; - break; - - // events add - case static_cast(CarlaRecorderPacketId::EventAdd): - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - for (i = 0; i < Total; ++i) - { - // add - EventAdd.Read(File); - Info << " Create " << EventAdd.DatabaseId << ": " << TCHAR_TO_UTF8(*EventAdd.Description.Id) << - " (" << - static_cast(EventAdd.Type) << ") at (" << EventAdd.Location.X << ", " << - EventAdd.Location.Y << ", " << EventAdd.Location.Z << ")" << std::endl; - for (auto &Att : EventAdd.Description.Attributes) - { - Info << " " << TCHAR_TO_UTF8(*Att.Id) << " = " << TCHAR_TO_UTF8(*Att.Value) << std::endl; - } - } - break; - - // events del - case static_cast(CarlaRecorderPacketId::EventDel): - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - for (i = 0; i < Total; ++i) - { - EventDel.Read(File); - Info << " Destroy " << EventDel.DatabaseId << "\n"; - } - break; - - // events parenting - case static_cast(CarlaRecorderPacketId::EventParent): - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - for (i = 0; i < Total; ++i) - { - EventParent.Read(File); - Info << " Parenting " << EventParent.DatabaseId << " with " << EventParent.DatabaseIdParent << - " (parent)\n"; - } - break; - - // collisions - case static_cast(CarlaRecorderPacketId::Collision): - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - for (i = 0; i < Total; ++i) - { - Collision.Read(File); - Info << " Collision id " << Collision.Id << " between " << Collision.DatabaseId1; - if (Collision.IsActor1Hero) - Info << " (hero) "; - Info << " with " << Collision.DatabaseId2; - if (Collision.IsActor2Hero) - Info << " (hero) "; - Info << std::endl; - } - break; - - // positions - case static_cast(CarlaRecorderPacketId::Position): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Positions: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - Position.Read(File); - Info << " Id: " << Position.DatabaseId << " Location: (" << Position.Location.X << ", " << Position.Location.Y << ", " << Position.Location.Z << ") Rotation (" << Position.Rotation.X << ", " << Position.Rotation.Y << ", " << Position.Rotation.Z << ")" << std::endl; - } - } - else - SkipPacket(); - break; - - // traffic light - case static_cast(CarlaRecorderPacketId::State): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " State traffic lights: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - StateTraffic.Read(File); - Info << " Id: " << StateTraffic.DatabaseId << " state: " << static_cast(0x30 + StateTraffic.State) << " frozen: " << - StateTraffic.IsFrozen << " elapsedTime: " << StateTraffic.ElapsedTime << std::endl; - } - } - else - SkipPacket(); - break; - - // vehicle animations - case static_cast(CarlaRecorderPacketId::AnimVehicle): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Vehicle animations: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - Vehicle.Read(File); - Info << " Id: " << Vehicle.DatabaseId << " Steering: " << Vehicle.Steering << " Throttle: " << Vehicle.Throttle << " Brake " << Vehicle.Brake << " Handbrake: " << Vehicle.bHandbrake << " Gear: " << Vehicle.Gear << std::endl; - } - } - else - SkipPacket(); - break; - - // walker animations - case static_cast(CarlaRecorderPacketId::AnimWalker): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Walker animations: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - Walker.Read(File); - Info << " Id: " << Walker.DatabaseId << " speed: " << Walker.Speed << std::endl; - } - } - else - SkipPacket(); - break; - - // vehicle light animations - case static_cast(CarlaRecorderPacketId::VehicleLight): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Vehicle light animations: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - LightVehicle.Read(File); - - carla::rpc::VehicleLightState LightState(LightVehicle.State); - FVehicleLightState State(LightState); - std::string enabled_lights_list; - if (State.Position) - enabled_lights_list += "Position "; - if (State.LowBeam) - enabled_lights_list += "LowBeam "; - if (State.HighBeam) - enabled_lights_list += "HighBeam "; - if (State.Brake) - enabled_lights_list += "Brake "; - if (State.RightBlinker) - enabled_lights_list += "RightBlinker "; - if (State.LeftBlinker) - enabled_lights_list += "LeftBlinker "; - if (State.Reverse) - enabled_lights_list += "Reverse "; - if (State.Interior) - enabled_lights_list += "Interior "; - if (State.Fog) - enabled_lights_list += "Fog "; - if (State.Special1) - enabled_lights_list += "Special1 "; - if (State.Special2) - enabled_lights_list += "Special2 "; - - if (enabled_lights_list.size()) - { - Info << " Id: " << LightVehicle.DatabaseId << " " << - enabled_lights_list.substr(0, enabled_lights_list.size() - 1) << std::endl; - } - else - { - Info << " Id: " << LightVehicle.DatabaseId << " None" << std::endl; - } - } - } - else - SkipPacket(); - break; - - // scene light animations - case static_cast(CarlaRecorderPacketId::SceneLight): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Scene light changes: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - LightScene.Read(File); - Info << " Id: " << LightScene.LightId << " enabled: " << (LightScene.bOn ? "True" : "False") - << " intensity: " << LightScene.Intensity - << " RGB_color: (" << LightScene.Color.R << ", " << LightScene.Color.G << ", " << LightScene.Color.B << ")" - << std::endl; - } - } - else - SkipPacket(); - break; - - // dynamic actor kinematics - case static_cast(CarlaRecorderPacketId::Kinematics): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Dynamic actors: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - Kinematics.Read(File); - Info << " Id: " << Kinematics.DatabaseId << " linear_velocity: (" - << Kinematics.LinearVelocity.X << ", " << Kinematics.LinearVelocity.Y << ", " << Kinematics.LinearVelocity.Z << ")" - << " angular_velocity: (" - << Kinematics.AngularVelocity.X << ", " << Kinematics.AngularVelocity.Y << ", " << Kinematics.AngularVelocity.Z << ")" - << std::endl; - } - } - else - SkipPacket(); - break; - - // actors bounding boxes - case static_cast(CarlaRecorderPacketId::BoundingBox): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Actor bounding boxes: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - ActorBoundingBox.Read(File); - Info << " Id: " << ActorBoundingBox.DatabaseId << " origin: (" - << ActorBoundingBox.BoundingBox.Origin.X << ", " - << ActorBoundingBox.BoundingBox.Origin.Y << ", " - << ActorBoundingBox.BoundingBox.Origin.Z << ")" - << " extension: (" - << ActorBoundingBox.BoundingBox.Extension.X << ", " - << ActorBoundingBox.BoundingBox.Extension.Y << ", " - << ActorBoundingBox.BoundingBox.Extension.Z << ")" - << std::endl; - } - } - else - SkipPacket(); - break; - - // actors trigger volumes - case static_cast(CarlaRecorderPacketId::TriggerVolume): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " Actor trigger volumes: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - ActorBoundingBox.Read(File); - Info << " Id: " << ActorBoundingBox.DatabaseId << " origin: (" - << ActorBoundingBox.BoundingBox.Origin.X << ", " - << ActorBoundingBox.BoundingBox.Origin.Y << ", " - << ActorBoundingBox.BoundingBox.Origin.Z << ")" - << " extension: (" - << ActorBoundingBox.BoundingBox.Extension.X << ", " - << ActorBoundingBox.BoundingBox.Extension.Y << ", " - << ActorBoundingBox.BoundingBox.Extension.Z << ")" - << std::endl; - } - } - else - SkipPacket(); - break; - - // Platform time - case static_cast(CarlaRecorderPacketId::PlatformTime): - if (bShowAll) - { - if (!bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - - PlatformTime.Read(File); - Info << " Current platform time: " << PlatformTime.Time << std::endl; - } - else - SkipPacket(); - break; - - case static_cast(CarlaRecorderPacketId::PhysicsControl): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - - Info << " Physics Control events: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - PhysicsControl.Read(File); - carla::rpc::VehiclePhysicsControl Control(PhysicsControl.VehiclePhysicsControl); - Info << " Id: " << PhysicsControl.DatabaseId << std::endl - << " max_rpm = " << Control.max_rpm << std::endl - << " MOI = " << Control.moi << std::endl - << " damping_rate_full_throttle = " << Control.damping_rate_full_throttle << std::endl - << " damping_rate_zero_throttle_clutch_engaged = " << Control.damping_rate_zero_throttle_clutch_engaged << std::endl - << " damping_rate_zero_throttle_clutch_disengaged = " << Control.damping_rate_zero_throttle_clutch_disengaged << std::endl - << " use_gear_auto_box = " << (Control.use_gear_autobox ? "true" : "false") << std::endl - << " gear_switch_time = " << Control.gear_switch_time << std::endl - << " clutch_strength = " << Control.clutch_strength << std::endl - << " final_ratio = " << Control.final_ratio << std::endl - << " mass = " << Control.mass << std::endl - << " drag_coefficient = " << Control.drag_coefficient << std::endl - << " center_of_mass = " << "(" << Control.center_of_mass.x << ", " << Control.center_of_mass.y << ", " << Control.center_of_mass.z << ")" << std::endl; - Info << " torque_curve ="; - for (auto& vec : Control.torque_curve) - { - Info << " (" << vec.x << ", " << vec.y << ")"; - } - Info << std::endl; - Info << " steering_curve ="; - for (auto& vec : Control.steering_curve) - { - Info << " (" << vec.x << ", " << vec.y << ")"; - } - Info << std::endl; - Info << " forward_gears:" << std::endl; - uint32_t count = 0; - for (auto& Gear : Control.forward_gears) - { - Info << " gear " << count << ": ratio " << Gear.ratio - << " down_ratio " << Gear.down_ratio - << " up_ratio " << Gear.up_ratio << std::endl; - ++count; - } - Info << " wheels:" << std::endl; - count = 0; - for (auto& Wheel : Control.wheels) - { - Info << " wheel " << count << ": tire_friction " << Wheel.tire_friction - << " damping_rate " << Wheel.damping_rate - << " max_steer_angle " << Wheel.max_steer_angle - << " radius " << Wheel.radius - << " max_brake_torque " << Wheel.max_brake_torque - << " max_handbrake_torque " << Wheel.max_handbrake_torque - << " position " << "(" << Wheel.position.x << ", " << Wheel.position.y << ", " << Wheel.position.z << ")" - << std::endl; - ++count; - } - } - } - else - SkipPacket(); - break; - - case static_cast(CarlaRecorderPacketId::TrafficLightTime): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - - Info << " Traffic Light time events: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - TrafficLightTime.Read(File); - Info << " Id: " << TrafficLightTime.DatabaseId - << " green_time: " << TrafficLightTime.GreenTime - << " yellow_time: " << TrafficLightTime.YellowTime - << " red_time: " << TrafficLightTime.RedTime - << std::endl; - } - } - else - SkipPacket(); - break; - - case static_cast(CarlaRecorderPacketId::Weather): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - - Info << " Weather events: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - Weather.Read(File); - Info << " " << Weather.Print() << std::endl; - } - } - else - SkipPacket(); - break; - - // DReyeVR data - case static_cast(CarlaRecorderPacketId::DReyeVR): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " DReyeVR sensor data: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - DReyeVRAggDataInstance.Read(File); - Info << DReyeVRAggDataInstance.Print() << std::endl; - } - } - else - SkipPacket(); - break; - - // DReyeVR data - case static_cast(CarlaRecorderPacketId::DReyeVRCustomActor): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " DReyeVR custom actor data: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - DReyeVRCustomActorDataInstance.Read(File); - Info << DReyeVRCustomActorDataInstance.Print() << std::endl; - } - } - else - SkipPacket(); - break; - - // DReyeVR data (ConfigFileData) - case static_cast(CarlaRecorderPacketId::DReyeVRConfigFile): - if (bShowAll) - { - ReadValue(File, Total); - if (Total > 0 && !bFramePrinted) - { - PrintFrame(Info); - bFramePrinted = true; - } - Info << " DReyeVR config files: " << Total << std::endl; - for (i = 0; i < Total; ++i) - { - DReyeVRConfigFileDataInstance.Read(File); - Info << DReyeVRConfigFileDataInstance.Print() << std::endl; - } - } - else - SkipPacket(); - break; - // frame end - case static_cast(CarlaRecorderPacketId::FrameEnd): - // do nothing, it is empty - break; - - default: - SkipPacket(); - break; - } - } - - Info << "\nFrames: " << Frame.Id << "\n"; - Info << "Duration: " << Frame.Elapsed << " seconds\n"; - - File.close(); - - return Info.str(); -} - -std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Category1, char Category2) -{ - std::stringstream Info; - - // get the final path + filename - std::string Filename2 = GetRecorderFilename(Filename); - - // try to open - File.open(Filename2, std::ios::binary); - if (!File.is_open()) - { - Info << "File " << Filename2 << " not found on server\n"; - return Info.str(); - } - - if (!CheckFileInfo(Info)) - return Info.str(); - - // other, vehicle, walkers, trafficLight, hero, any - char Categories[] = { 'o', 'v', 'w', 't', 'h', 'a' }; - uint16_t i, Total; - struct ReplayerActorInfo - { - uint8_t Type; - FString Id; - }; - std::unordered_map Actors; - struct PairHash - { - std::size_t operator()(const std::pair& P) const - { - std::size_t hash = P.first; - hash <<= 32; - hash += P.second; - return hash; - } - }; - std::unordered_set, PairHash > oldCollisions, newCollisions; - - // header - Info << std::setw(8) << "Time"; - Info << " " << std::setw(6) << "Types"; - Info << " " << std::setw(6) << std::right << "Id"; - Info << " " << std::setw(35) << std::left << "Actor 1"; - Info << " " << std::setw(6) << std::right << "Id"; - Info << " " << std::setw(35) << std::left << "Actor 2"; - Info << std::endl; - - // parse only frames - while (File) - { - - // get header - if (!ReadHeader()) - { - break; - } - - // check for a frame packet - switch (Header.Id) - { - // frame - case static_cast(CarlaRecorderPacketId::FrameStart): - Frame.Read(File); - // exchange sets of collisions (to know when a collision is new or continue from previous frame) - oldCollisions = std::move(newCollisions); - newCollisions.clear(); - break; - - // events add - case static_cast(CarlaRecorderPacketId::EventAdd): - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - // add - EventAdd.Read(File); - Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id }; - } - break; - - // events del - case static_cast(CarlaRecorderPacketId::EventDel): - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - EventDel.Read(File); - Actors.erase(EventAdd.DatabaseId); - } - break; - - // events parenting - case static_cast(CarlaRecorderPacketId::EventParent): - SkipPacket(); - break; - - // collisions - case static_cast(CarlaRecorderPacketId::Collision): - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - Collision.Read(File); - - int Valid = 0; - - // get categories for both actors - uint8_t Type1, Type2; - if (Collision.DatabaseId1 != uint32_t(-1)) - Type1 = Categories[Actors[Collision.DatabaseId1].Type]; - else - Type1 = 'o'; // other non-actor object - - if (Collision.DatabaseId2 != uint32_t(-1)) - Type2 = Categories[Actors[Collision.DatabaseId2].Type]; - else - Type2 = 'o'; // other non-actor object - - // filter actor 1 - if (Category1 == 'a') - ++Valid; - else if (Category1 == Type1) - ++Valid; - else if (Category1 == 'h' && Collision.IsActor1Hero) - ++Valid; - - // filter actor 2 - if (Category2 == 'a') - ++Valid; - else if (Category2 == Type2) - ++Valid; - else if (Category2 == 'h' && Collision.IsActor2Hero) - ++Valid; - - // only show if both actors has passed the filter - if (Valid == 2) - { - // check if we need to show as a starting collision or it is a continuation one - auto collisionPair = std::make_pair(Collision.DatabaseId1, Collision.DatabaseId2); - if (oldCollisions.count(collisionPair) == 0) - { - Info << std::setw(8) << std::setprecision(0) << std::right << std::fixed << Frame.Elapsed; - Info << " " << " " << Type1 << " " << Type2 << " "; - Info << " " << std::setw(6) << std::right << Collision.DatabaseId1; - Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId1].Id); - Info << " " << std::setw(6) << std::right << Collision.DatabaseId2; - Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId2].Id); - Info << std::endl; - } - // save current collision - newCollisions.insert(collisionPair); - } - } - break; - - case static_cast(CarlaRecorderPacketId::Position): - SkipPacket(); - break; - - case static_cast(CarlaRecorderPacketId::State): - SkipPacket(); - break; - - // frame end - case static_cast(CarlaRecorderPacketId::FrameEnd): - // do nothing, it is empty - break; - - default: - SkipPacket(); - break; - } - } - - Info << "\nFrames: " << Frame.Id << "\n"; - Info << "Duration: " << Frame.Elapsed << " seconds\n"; - - File.close(); - - return Info.str(); -} - -std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTime, double MinDistance) -{ - std::stringstream Info; - - // get the final path + filename - std::string Filename2 = GetRecorderFilename(Filename); - - // try to open - File.open(Filename2, std::ios::binary); - if (!File.is_open()) - { - Info << "File " << Filename2 << " not found on server\n"; - return Info.str(); - } - - if (!CheckFileInfo(Info)) - return Info.str(); - - // other, vehicle, walkers, trafficLight, hero, any - uint16_t i, Total; - struct ReplayerActorInfo - { - uint8_t Type; - FString Id; - FVector LastPosition; - double Time; - double Duration; - }; - std::unordered_map Actors; - // to be able to sort the results by the duration of each actor (decreasing order) - std::multimap> Results; - - // header - Info << std::setw(8) << "Time"; - Info << " " << std::setw(6) << "Id"; - Info << " " << std::setw(35) << std::left << "Actor"; - Info << " " << std::setw(10) << std::right << "Duration"; - Info << std::endl; - - // parse only frames - while (File) - { - - // get header - if (!ReadHeader()) - { - break; - } - - // check for a frame packet - switch (Header.Id) - { - // frame - case static_cast(CarlaRecorderPacketId::FrameStart): - Frame.Read(File); - break; - - // events add - case static_cast(CarlaRecorderPacketId::EventAdd): - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - // add - EventAdd.Read(File); - Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id, FVector(0, 0, 0), 0.0, 0.0 }; - } - break; - - // events del - case static_cast(CarlaRecorderPacketId::EventDel): - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - EventDel.Read(File); - Actors.erase(EventAdd.DatabaseId); - } - break; - - // events parenting - case static_cast(CarlaRecorderPacketId::EventParent): - SkipPacket(); - break; - - // collisions - case static_cast(CarlaRecorderPacketId::Collision): - SkipPacket(); - break; - - // positions - case static_cast(CarlaRecorderPacketId::Position): - // read all positions - ReadValue(File, Total); - for (i=0; i= MinTime) - { - std::stringstream Result; - Result << std::setw(8) << std::setprecision(0) << std::fixed << Actors[Position.DatabaseId].Time; - Result << " " << std::setw(6) << Position.DatabaseId; - Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Position.DatabaseId].Id); - Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actors[Position.DatabaseId].Duration; - Result << std::endl; - Results.insert(std::make_pair(Actors[Position.DatabaseId].Duration, Result.str())); - } - // actor moving - Actors[Position.DatabaseId].Duration = 0; - Actors[Position.DatabaseId].LastPosition = Position.Location; - } - } - break; - - // traffic light - case static_cast(CarlaRecorderPacketId::State): - SkipPacket(); - break; - - // frame end - case static_cast(CarlaRecorderPacketId::FrameEnd): - // do nothing, it is empty - break; - - default: - SkipPacket(); - break; - } - } - - // show actors stopped that were not moving again - for (auto &Actor : Actors) - { - // check to show info - if (Actor.second.Duration >= MinTime) - { - std::stringstream Result; - Result << std::setw(8) << std::setprecision(0) << std::fixed << Actor.second.Time; - Result << " " << std::setw(6) << Actor.first; - Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actor.second.Id); - Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actor.second.Duration; - Result << std::endl; - Results.insert(std::make_pair(Actor.second.Duration, Result.str())); - } - } - - // show the result - for (auto &Result : Results) - { - Info << Result.second; - } - - Info << "\nFrames: " << Frame.Id << "\n"; - Info << "Duration: " << Frame.Elapsed << " seconds\n"; - - File.close(); - - return Info.str(); -} +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "CarlaRecorderHelpers.h" + +#include +#include +#include + +#include +#include +#include +#include + +inline bool CarlaRecorderQuery::ReadHeader(void) +{ + if (File.eof()) + { + return false; + } + + ReadValue(File, Header.Id); + ReadValue(File, Header.Size); + + return true; +} + +inline void CarlaRecorderQuery::SkipPacket(void) +{ + File.seekg(Header.Size, std::ios::cur); +} + +inline bool CarlaRecorderQuery::CheckFileInfo(std::stringstream &Info) +{ + // read Info + RecInfo.Read(File); + + // check magic string + if (RecInfo.Magic != "CARLA_RECORDER") + { + Info << "File is not a CARLA recorder" << std::endl; + return false; + } + + // show general Info + Info << "Version: " << RecInfo.Version << std::endl; + Info << "Map: " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl; + tm *TimeInfo = localtime(&RecInfo.Date); + char DateStr[100]; + strftime(DateStr, sizeof(DateStr), "%x %X", TimeInfo); + Info << "Date: " << DateStr << std::endl << std::endl; + + return true; +} + +std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll) +{ + std::stringstream Info; + + // get the final path + filename + std::string Filename2 = GetRecorderFilename(Filename); + + // try to open + File.open(Filename2, std::ios::binary); + if (!File.is_open()) + { + Info << "File " << Filename2 << " not found on server\n"; + return Info.str(); + } + + uint16_t i, Total; + bool bFramePrinted = false; + + // lambda for repeating task + auto PrintFrame = [this](std::stringstream &Info) + { + Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n"; + }; + + if (!CheckFileInfo(Info)) + return Info.str(); + + // parse only frames + while (File) + { + + // get header + if (!ReadHeader()) + { + break; + } + + // check for a frame packet + switch (Header.Id) + { + // frame + case static_cast(CarlaRecorderPacketId::FrameStart): + Frame.Read(File); + if (bShowAll) + { + PrintFrame(Info); + bFramePrinted = true; + } + else + bFramePrinted = false; + break; + + // events add + case static_cast(CarlaRecorderPacketId::EventAdd): + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + for (i = 0; i < Total; ++i) + { + // add + EventAdd.Read(File); + Info << " Create " << EventAdd.DatabaseId << ": " << TCHAR_TO_UTF8(*EventAdd.Description.Id) << + " (" << + static_cast(EventAdd.Type) << ") at (" << EventAdd.Location.X << ", " << + EventAdd.Location.Y << ", " << EventAdd.Location.Z << ")" << std::endl; + for (auto &Att : EventAdd.Description.Attributes) + { + Info << " " << TCHAR_TO_UTF8(*Att.Id) << " = " << TCHAR_TO_UTF8(*Att.Value) << std::endl; + } + } + break; + + // events del + case static_cast(CarlaRecorderPacketId::EventDel): + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + for (i = 0; i < Total; ++i) + { + EventDel.Read(File); + Info << " Destroy " << EventDel.DatabaseId << "\n"; + } + break; + + // events parenting + case static_cast(CarlaRecorderPacketId::EventParent): + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + for (i = 0; i < Total; ++i) + { + EventParent.Read(File); + Info << " Parenting " << EventParent.DatabaseId << " with " << EventParent.DatabaseIdParent << + " (parent)\n"; + } + break; + + // collisions + case static_cast(CarlaRecorderPacketId::Collision): + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + for (i = 0; i < Total; ++i) + { + Collision.Read(File); + Info << " Collision id " << Collision.Id << " between " << Collision.DatabaseId1; + if (Collision.IsActor1Hero) + Info << " (hero) "; + Info << " with " << Collision.DatabaseId2; + if (Collision.IsActor2Hero) + Info << " (hero) "; + Info << std::endl; + } + break; + + // positions + case static_cast(CarlaRecorderPacketId::Position): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Positions: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + Position.Read(File); + Info << " Id: " << Position.DatabaseId << " Location: (" << Position.Location.X << ", " << Position.Location.Y << ", " << Position.Location.Z << ") Rotation (" << Position.Rotation.X << ", " << Position.Rotation.Y << ", " << Position.Rotation.Z << ")" << std::endl; + } + } + else + SkipPacket(); + break; + + // traffic light + case static_cast(CarlaRecorderPacketId::State): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " State traffic lights: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + StateTraffic.Read(File); + Info << " Id: " << StateTraffic.DatabaseId << " state: " << static_cast(0x30 + StateTraffic.State) << " frozen: " << + StateTraffic.IsFrozen << " elapsedTime: " << StateTraffic.ElapsedTime << std::endl; + } + } + else + SkipPacket(); + break; + + // vehicle animations + case static_cast(CarlaRecorderPacketId::AnimVehicle): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Vehicle animations: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + Vehicle.Read(File); + Info << " Id: " << Vehicle.DatabaseId << " Steering: " << Vehicle.Steering << " Throttle: " << Vehicle.Throttle << " Brake " << Vehicle.Brake << " Handbrake: " << Vehicle.bHandbrake << " Gear: " << Vehicle.Gear << std::endl; + } + } + else + SkipPacket(); + break; + + // walker animations + case static_cast(CarlaRecorderPacketId::AnimWalker): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Walker animations: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + Walker.Read(File); + Info << " Id: " << Walker.DatabaseId << " speed: " << Walker.Speed << std::endl; + } + } + else + SkipPacket(); + break; + + // vehicle light animations + case static_cast(CarlaRecorderPacketId::VehicleLight): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Vehicle light animations: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + LightVehicle.Read(File); + + carla::rpc::VehicleLightState LightState(LightVehicle.State); + FVehicleLightState State(LightState); + std::string enabled_lights_list; + if (State.Position) + enabled_lights_list += "Position "; + if (State.LowBeam) + enabled_lights_list += "LowBeam "; + if (State.HighBeam) + enabled_lights_list += "HighBeam "; + if (State.Brake) + enabled_lights_list += "Brake "; + if (State.RightBlinker) + enabled_lights_list += "RightBlinker "; + if (State.LeftBlinker) + enabled_lights_list += "LeftBlinker "; + if (State.Reverse) + enabled_lights_list += "Reverse "; + if (State.Interior) + enabled_lights_list += "Interior "; + if (State.Fog) + enabled_lights_list += "Fog "; + if (State.Special1) + enabled_lights_list += "Special1 "; + if (State.Special2) + enabled_lights_list += "Special2 "; + + if (enabled_lights_list.size()) + { + Info << " Id: " << LightVehicle.DatabaseId << " " << + enabled_lights_list.substr(0, enabled_lights_list.size() - 1) << std::endl; + } + else + { + Info << " Id: " << LightVehicle.DatabaseId << " None" << std::endl; + } + } + } + else + SkipPacket(); + break; + + // scene light animations + case static_cast(CarlaRecorderPacketId::SceneLight): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Scene light changes: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + LightScene.Read(File); + Info << " Id: " << LightScene.LightId << " enabled: " << (LightScene.bOn ? "True" : "False") + << " intensity: " << LightScene.Intensity + << " RGB_color: (" << LightScene.Color.R << ", " << LightScene.Color.G << ", " << LightScene.Color.B << ")" + << std::endl; + } + } + else + SkipPacket(); + break; + + // dynamic actor kinematics + case static_cast(CarlaRecorderPacketId::Kinematics): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Dynamic actors: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + Kinematics.Read(File); + Info << " Id: " << Kinematics.DatabaseId << " linear_velocity: (" + << Kinematics.LinearVelocity.X << ", " << Kinematics.LinearVelocity.Y << ", " << Kinematics.LinearVelocity.Z << ")" + << " angular_velocity: (" + << Kinematics.AngularVelocity.X << ", " << Kinematics.AngularVelocity.Y << ", " << Kinematics.AngularVelocity.Z << ")" + << std::endl; + } + } + else + SkipPacket(); + break; + + // actors bounding boxes + case static_cast(CarlaRecorderPacketId::BoundingBox): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Actor bounding boxes: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + ActorBoundingBox.Read(File); + Info << " Id: " << ActorBoundingBox.DatabaseId << " origin: (" + << ActorBoundingBox.BoundingBox.Origin.X << ", " + << ActorBoundingBox.BoundingBox.Origin.Y << ", " + << ActorBoundingBox.BoundingBox.Origin.Z << ")" + << " extension: (" + << ActorBoundingBox.BoundingBox.Extension.X << ", " + << ActorBoundingBox.BoundingBox.Extension.Y << ", " + << ActorBoundingBox.BoundingBox.Extension.Z << ")" + << std::endl; + } + } + else + SkipPacket(); + break; + + // actors trigger volumes + case static_cast(CarlaRecorderPacketId::TriggerVolume): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " Actor trigger volumes: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + ActorBoundingBox.Read(File); + Info << " Id: " << ActorBoundingBox.DatabaseId << " origin: (" + << ActorBoundingBox.BoundingBox.Origin.X << ", " + << ActorBoundingBox.BoundingBox.Origin.Y << ", " + << ActorBoundingBox.BoundingBox.Origin.Z << ")" + << " extension: (" + << ActorBoundingBox.BoundingBox.Extension.X << ", " + << ActorBoundingBox.BoundingBox.Extension.Y << ", " + << ActorBoundingBox.BoundingBox.Extension.Z << ")" + << std::endl; + } + } + else + SkipPacket(); + break; + + // Platform time + case static_cast(CarlaRecorderPacketId::PlatformTime): + if (bShowAll) + { + if (!bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + + PlatformTime.Read(File); + Info << " Current platform time: " << PlatformTime.Time << std::endl; + } + else + SkipPacket(); + break; + + case static_cast(CarlaRecorderPacketId::PhysicsControl): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + + Info << " Physics Control events: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + PhysicsControl.Read(File); + carla::rpc::VehiclePhysicsControl Control(PhysicsControl.VehiclePhysicsControl); + Info << " Id: " << PhysicsControl.DatabaseId << std::endl + << " max_rpm = " << Control.max_rpm << std::endl + << " MOI = " << Control.moi << std::endl + << " damping_rate_full_throttle = " << Control.damping_rate_full_throttle << std::endl + << " damping_rate_zero_throttle_clutch_engaged = " << Control.damping_rate_zero_throttle_clutch_engaged << std::endl + << " damping_rate_zero_throttle_clutch_disengaged = " << Control.damping_rate_zero_throttle_clutch_disengaged << std::endl + << " use_gear_auto_box = " << (Control.use_gear_autobox ? "true" : "false") << std::endl + << " gear_switch_time = " << Control.gear_switch_time << std::endl + << " clutch_strength = " << Control.clutch_strength << std::endl + << " final_ratio = " << Control.final_ratio << std::endl + << " mass = " << Control.mass << std::endl + << " drag_coefficient = " << Control.drag_coefficient << std::endl + << " center_of_mass = " << "(" << Control.center_of_mass.x << ", " << Control.center_of_mass.y << ", " << Control.center_of_mass.z << ")" << std::endl; + Info << " torque_curve ="; + for (auto& vec : Control.torque_curve) + { + Info << " (" << vec.x << ", " << vec.y << ")"; + } + Info << std::endl; + Info << " steering_curve ="; + for (auto& vec : Control.steering_curve) + { + Info << " (" << vec.x << ", " << vec.y << ")"; + } + Info << std::endl; + Info << " forward_gears:" << std::endl; + uint32_t count = 0; + for (auto& Gear : Control.forward_gears) + { + Info << " gear " << count << ": ratio " << Gear.ratio + << " down_ratio " << Gear.down_ratio + << " up_ratio " << Gear.up_ratio << std::endl; + ++count; + } + Info << " wheels:" << std::endl; + count = 0; + for (auto& Wheel : Control.wheels) + { + Info << " wheel " << count << ": tire_friction " << Wheel.tire_friction + << " damping_rate " << Wheel.damping_rate + << " max_steer_angle " << Wheel.max_steer_angle + << " radius " << Wheel.radius + << " max_brake_torque " << Wheel.max_brake_torque + << " max_handbrake_torque " << Wheel.max_handbrake_torque + << " position " << "(" << Wheel.position.x << ", " << Wheel.position.y << ", " << Wheel.position.z << ")" + << std::endl; + ++count; + } + } + } + else + SkipPacket(); + break; + + case static_cast(CarlaRecorderPacketId::TrafficLightTime): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + + Info << " Traffic Light time events: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + TrafficLightTime.Read(File); + Info << " Id: " << TrafficLightTime.DatabaseId + << " green_time: " << TrafficLightTime.GreenTime + << " yellow_time: " << TrafficLightTime.YellowTime + << " red_time: " << TrafficLightTime.RedTime + << std::endl; + } + } + else + SkipPacket(); + break; + + case static_cast(CarlaRecorderPacketId::Weather): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + + Info << " Weather events: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + Weather.Read(File); + Info << " " << Weather.Print() << std::endl; + } + } + else + SkipPacket(); + break; + + // DReyeVR data + case static_cast(CarlaRecorderPacketId::DReyeVR): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " DReyeVR sensor data: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + DReyeVRAggDataInstance.Read(File); + Info << DReyeVRAggDataInstance.Print() << std::endl; + } + } + else + SkipPacket(); + break; + + // DReyeVR data + case static_cast(CarlaRecorderPacketId::DReyeVRCustomActor): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " DReyeVR custom actor data: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + DReyeVRCustomActorDataInstance.Read(File); + Info << DReyeVRCustomActorDataInstance.Print() << std::endl; + } + } + else + SkipPacket(); + break; + + // DReyeVR data (ConfigFileData) + case static_cast(CarlaRecorderPacketId::DReyeVRConfigFile): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " DReyeVR config files: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + DReyeVRConfigFileDataInstance.Read(File); + Info << DReyeVRConfigFileDataInstance.Print() << std::endl; + } + } + else + SkipPacket(); + break; + // frame end + case static_cast(CarlaRecorderPacketId::FrameEnd): + // do nothing, it is empty + break; + + default: + SkipPacket(); + break; + } + } + + Info << "\nFrames: " << Frame.Id << "\n"; + Info << "Duration: " << Frame.Elapsed << " seconds\n"; + + File.close(); + + return Info.str(); +} + +std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Category1, char Category2) +{ + std::stringstream Info; + + // get the final path + filename + std::string Filename2 = GetRecorderFilename(Filename); + + // try to open + File.open(Filename2, std::ios::binary); + if (!File.is_open()) + { + Info << "File " << Filename2 << " not found on server\n"; + return Info.str(); + } + + if (!CheckFileInfo(Info)) + return Info.str(); + + // other, vehicle, walkers, trafficLight, hero, any + char Categories[] = { 'o', 'v', 'w', 't', 'h', 'a' }; + uint16_t i, Total; + struct ReplayerActorInfo + { + uint8_t Type; + FString Id; + }; + std::unordered_map Actors; + struct PairHash + { + std::size_t operator()(const std::pair& P) const + { + std::size_t hash = P.first; + hash <<= 32; + hash += P.second; + return hash; + } + }; + std::unordered_set, PairHash > oldCollisions, newCollisions; + + // header + Info << std::setw(8) << "Time"; + Info << " " << std::setw(6) << "Types"; + Info << " " << std::setw(6) << std::right << "Id"; + Info << " " << std::setw(35) << std::left << "Actor 1"; + Info << " " << std::setw(6) << std::right << "Id"; + Info << " " << std::setw(35) << std::left << "Actor 2"; + Info << std::endl; + + // parse only frames + while (File) + { + + // get header + if (!ReadHeader()) + { + break; + } + + // check for a frame packet + switch (Header.Id) + { + // frame + case static_cast(CarlaRecorderPacketId::FrameStart): + Frame.Read(File); + // exchange sets of collisions (to know when a collision is new or continue from previous frame) + oldCollisions = std::move(newCollisions); + newCollisions.clear(); + break; + + // events add + case static_cast(CarlaRecorderPacketId::EventAdd): + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + // add + EventAdd.Read(File); + Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id }; + } + break; + + // events del + case static_cast(CarlaRecorderPacketId::EventDel): + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + EventDel.Read(File); + Actors.erase(EventAdd.DatabaseId); + } + break; + + // events parenting + case static_cast(CarlaRecorderPacketId::EventParent): + SkipPacket(); + break; + + // collisions + case static_cast(CarlaRecorderPacketId::Collision): + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + Collision.Read(File); + + int Valid = 0; + + // get categories for both actors + uint8_t Type1, Type2; + if (Collision.DatabaseId1 != uint32_t(-1)) + Type1 = Categories[Actors[Collision.DatabaseId1].Type]; + else + Type1 = 'o'; // other non-actor object + + if (Collision.DatabaseId2 != uint32_t(-1)) + Type2 = Categories[Actors[Collision.DatabaseId2].Type]; + else + Type2 = 'o'; // other non-actor object + + // filter actor 1 + if (Category1 == 'a') + ++Valid; + else if (Category1 == Type1) + ++Valid; + else if (Category1 == 'h' && Collision.IsActor1Hero) + ++Valid; + + // filter actor 2 + if (Category2 == 'a') + ++Valid; + else if (Category2 == Type2) + ++Valid; + else if (Category2 == 'h' && Collision.IsActor2Hero) + ++Valid; + + // only show if both actors has passed the filter + if (Valid == 2) + { + // check if we need to show as a starting collision or it is a continuation one + auto collisionPair = std::make_pair(Collision.DatabaseId1, Collision.DatabaseId2); + if (oldCollisions.count(collisionPair) == 0) + { + Info << std::setw(8) << std::setprecision(0) << std::right << std::fixed << Frame.Elapsed; + Info << " " << " " << Type1 << " " << Type2 << " "; + Info << " " << std::setw(6) << std::right << Collision.DatabaseId1; + Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId1].Id); + Info << " " << std::setw(6) << std::right << Collision.DatabaseId2; + Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId2].Id); + Info << std::endl; + } + // save current collision + newCollisions.insert(collisionPair); + } + } + break; + + case static_cast(CarlaRecorderPacketId::Position): + SkipPacket(); + break; + + case static_cast(CarlaRecorderPacketId::State): + SkipPacket(); + break; + + // frame end + case static_cast(CarlaRecorderPacketId::FrameEnd): + // do nothing, it is empty + break; + + default: + SkipPacket(); + break; + } + } + + Info << "\nFrames: " << Frame.Id << "\n"; + Info << "Duration: " << Frame.Elapsed << " seconds\n"; + + File.close(); + + return Info.str(); +} + +std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTime, double MinDistance) +{ + std::stringstream Info; + + // get the final path + filename + std::string Filename2 = GetRecorderFilename(Filename); + + // try to open + File.open(Filename2, std::ios::binary); + if (!File.is_open()) + { + Info << "File " << Filename2 << " not found on server\n"; + return Info.str(); + } + + if (!CheckFileInfo(Info)) + return Info.str(); + + // other, vehicle, walkers, trafficLight, hero, any + uint16_t i, Total; + struct ReplayerActorInfo + { + uint8_t Type; + FString Id; + FVector LastPosition; + double Time; + double Duration; + }; + std::unordered_map Actors; + // to be able to sort the results by the duration of each actor (decreasing order) + std::multimap> Results; + + // header + Info << std::setw(8) << "Time"; + Info << " " << std::setw(6) << "Id"; + Info << " " << std::setw(35) << std::left << "Actor"; + Info << " " << std::setw(10) << std::right << "Duration"; + Info << std::endl; + + // parse only frames + while (File) + { + + // get header + if (!ReadHeader()) + { + break; + } + + // check for a frame packet + switch (Header.Id) + { + // frame + case static_cast(CarlaRecorderPacketId::FrameStart): + Frame.Read(File); + break; + + // events add + case static_cast(CarlaRecorderPacketId::EventAdd): + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + // add + EventAdd.Read(File); + Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id, FVector(0, 0, 0), 0.0, 0.0 }; + } + break; + + // events del + case static_cast(CarlaRecorderPacketId::EventDel): + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + EventDel.Read(File); + Actors.erase(EventAdd.DatabaseId); + } + break; + + // events parenting + case static_cast(CarlaRecorderPacketId::EventParent): + SkipPacket(); + break; + + // collisions + case static_cast(CarlaRecorderPacketId::Collision): + SkipPacket(); + break; + + // positions + case static_cast(CarlaRecorderPacketId::Position): + // read all positions + ReadValue(File, Total); + for (i=0; i= MinTime) + { + std::stringstream Result; + Result << std::setw(8) << std::setprecision(0) << std::fixed << Actors[Position.DatabaseId].Time; + Result << " " << std::setw(6) << Position.DatabaseId; + Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Position.DatabaseId].Id); + Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actors[Position.DatabaseId].Duration; + Result << std::endl; + Results.insert(std::make_pair(Actors[Position.DatabaseId].Duration, Result.str())); + } + // actor moving + Actors[Position.DatabaseId].Duration = 0; + Actors[Position.DatabaseId].LastPosition = Position.Location; + } + } + break; + + // traffic light + case static_cast(CarlaRecorderPacketId::State): + SkipPacket(); + break; + + // frame end + case static_cast(CarlaRecorderPacketId::FrameEnd): + // do nothing, it is empty + break; + + default: + SkipPacket(); + break; + } + } + + // show actors stopped that were not moving again + for (auto &Actor : Actors) + { + // check to show info + if (Actor.second.Duration >= MinTime) + { + std::stringstream Result; + Result << std::setw(8) << std::setprecision(0) << std::fixed << Actor.second.Time; + Result << " " << std::setw(6) << Actor.first; + Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actor.second.Id); + Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actor.second.Duration; + Result << std::endl; + Results.insert(std::make_pair(Actor.second.Duration, Result.str())); + } + } + + // show the result + for (auto &Result : Results) + { + Info << Result.second; + } + + Info << "\nFrames: " << Frame.Id << "\n"; + Info << "Duration: " << Frame.Elapsed << " seconds\n"; + + File.close(); + + return Info.str(); +} diff --git a/Carla/Recorder/CarlaRecorderQuery.h b/Carla/Recorder/CarlaRecorderQuery.h index 96974c6..98682be 100644 --- a/Carla/Recorder/CarlaRecorderQuery.h +++ b/Carla/Recorder/CarlaRecorderQuery.h @@ -1,85 +1,85 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "CarlaRecorderTraficLightTime.h" -#include "CarlaRecorderPhysicsControl.h" -#include "CarlaRecorderPlatformTime.h" -#include "CarlaRecorderBoundingBox.h" -#include "CarlaRecorderKinematics.h" -#include "CarlaRecorderLightScene.h" -#include "CarlaRecorderLightVehicle.h" -#include "CarlaRecorderAnimWalker.h" -#include "CarlaRecorderCollision.h" -#include "CarlaRecorderEventAdd.h" -#include "CarlaRecorderEventDel.h" -#include "CarlaRecorderEventParent.h" -#include "CarlaRecorderFrames.h" -#include "CarlaRecorderInfo.h" -#include "CarlaRecorderPosition.h" -#include "CarlaRecorderState.h" -#include "CarlaRecorderWeather.h" -#include "DReyeVRRecorder.h" - -class CarlaRecorderQuery -{ - - #pragma pack(push, 1) - struct Header - { - char Id; - uint32_t Size; - }; - #pragma pack(pop) - -public: - - // get general info - std::string QueryInfo(std::string Filename, bool bShowAll = false); - // get info about collisions - std::string QueryCollisions(std::string Filename, char Category1 = 'a', char Category2 = 'a'); - // get info about blocked actors - std::string QueryBlocked(std::string Filename, double MinTime = 30, double MinDistance = 10); - -private: - - std::ifstream File; - Header Header; - CarlaRecorderInfo RecInfo; - CarlaRecorderFrame Frame; - CarlaRecorderEventAdd EventAdd; - CarlaRecorderEventDel EventDel; - CarlaRecorderEventParent EventParent; - CarlaRecorderPosition Position; - CarlaRecorderCollision Collision; - CarlaRecorderStateTrafficLight StateTraffic; - CarlaRecorderAnimVehicle Vehicle; - CarlaRecorderAnimWalker Walker; - CarlaRecorderLightVehicle LightVehicle; - CarlaRecorderLightScene LightScene; - CarlaRecorderKinematics Kinematics; - CarlaRecorderActorBoundingBox ActorBoundingBox; - CarlaRecorderPlatformTime PlatformTime; - CarlaRecorderPhysicsControl PhysicsControl; - CarlaRecorderTrafficLightTime TrafficLightTime; - CarlaRecorderWeather Weather; - // custom DReyeVR packets - DReyeVRDataRecorder DReyeVRAggDataInstance; - DReyeVRDataRecorder DReyeVRCustomActorDataInstance; - DReyeVRDataRecorder DReyeVRConfigFileDataInstance; - - // read next header packet - bool ReadHeader(void); - - // skip current packet - void SkipPacket(void); - - // read the start info structure and check the magic string - bool CheckFileInfo(std::stringstream &Info); -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "CarlaRecorderTraficLightTime.h" +#include "CarlaRecorderPhysicsControl.h" +#include "CarlaRecorderPlatformTime.h" +#include "CarlaRecorderBoundingBox.h" +#include "CarlaRecorderKinematics.h" +#include "CarlaRecorderLightScene.h" +#include "CarlaRecorderLightVehicle.h" +#include "CarlaRecorderAnimWalker.h" +#include "CarlaRecorderCollision.h" +#include "CarlaRecorderEventAdd.h" +#include "CarlaRecorderEventDel.h" +#include "CarlaRecorderEventParent.h" +#include "CarlaRecorderFrames.h" +#include "CarlaRecorderInfo.h" +#include "CarlaRecorderPosition.h" +#include "CarlaRecorderState.h" +#include "CarlaRecorderWeather.h" +#include "DReyeVRRecorder.h" + +class CarlaRecorderQuery +{ + + #pragma pack(push, 1) + struct Header + { + char Id; + uint32_t Size; + }; + #pragma pack(pop) + +public: + + // get general info + std::string QueryInfo(std::string Filename, bool bShowAll = false); + // get info about collisions + std::string QueryCollisions(std::string Filename, char Category1 = 'a', char Category2 = 'a'); + // get info about blocked actors + std::string QueryBlocked(std::string Filename, double MinTime = 30, double MinDistance = 10); + +private: + + std::ifstream File; + Header Header; + CarlaRecorderInfo RecInfo; + CarlaRecorderFrame Frame; + CarlaRecorderEventAdd EventAdd; + CarlaRecorderEventDel EventDel; + CarlaRecorderEventParent EventParent; + CarlaRecorderPosition Position; + CarlaRecorderCollision Collision; + CarlaRecorderStateTrafficLight StateTraffic; + CarlaRecorderAnimVehicle Vehicle; + CarlaRecorderAnimWalker Walker; + CarlaRecorderLightVehicle LightVehicle; + CarlaRecorderLightScene LightScene; + CarlaRecorderKinematics Kinematics; + CarlaRecorderActorBoundingBox ActorBoundingBox; + CarlaRecorderPlatformTime PlatformTime; + CarlaRecorderPhysicsControl PhysicsControl; + CarlaRecorderTrafficLightTime TrafficLightTime; + CarlaRecorderWeather Weather; + // custom DReyeVR packets + DReyeVRDataRecorder DReyeVRAggDataInstance; + DReyeVRDataRecorder DReyeVRCustomActorDataInstance; + DReyeVRDataRecorder DReyeVRConfigFileDataInstance; + + // read next header packet + bool ReadHeader(void); + + // skip current packet + void SkipPacket(void); + + // read the start info structure and check the magic string + bool CheckFileInfo(std::stringstream &Info); +}; diff --git a/Carla/Recorder/CarlaRecorderWeather.cpp b/Carla/Recorder/CarlaRecorderWeather.cpp index a820226..31535e1 100644 --- a/Carla/Recorder/CarlaRecorderWeather.cpp +++ b/Carla/Recorder/CarlaRecorderWeather.cpp @@ -1,89 +1,89 @@ -// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaRecorderWeather.h" -#include "CarlaRecorder.h" -#include "CarlaRecorderHelpers.h" - - -void CarlaRecorderWeather::Write(std::ofstream &OutFile) const -{ - WriteValue(OutFile, this->Params.Cloudiness); - WriteValue(OutFile, this->Params.Precipitation); - WriteValue(OutFile, this->Params.PrecipitationDeposits); - WriteValue(OutFile, this->Params.WindIntensity); - WriteValue(OutFile, this->Params.SunAzimuthAngle); - WriteValue(OutFile, this->Params.SunAltitudeAngle); - WriteValue(OutFile, this->Params.FogDensity); - WriteValue(OutFile, this->Params.FogDistance); - WriteValue(OutFile, this->Params.FogFalloff); - WriteValue(OutFile, this->Params.Wetness); - WriteValue(OutFile, this->Params.ScatteringIntensity); - WriteValue(OutFile, this->Params.MieScatteringScale); - WriteValue(OutFile, this->Params.RayleighScatteringScale); -} - -void CarlaRecorderWeather::Read(std::ifstream &InFile) -{ - ReadValue(InFile, this->Params.Cloudiness); - ReadValue(InFile, this->Params.Precipitation); - ReadValue(InFile, this->Params.PrecipitationDeposits); - ReadValue(InFile, this->Params.WindIntensity); - ReadValue(InFile, this->Params.SunAzimuthAngle); - ReadValue(InFile, this->Params.SunAltitudeAngle); - ReadValue(InFile, this->Params.FogDensity); - ReadValue(InFile, this->Params.FogDistance); - ReadValue(InFile, this->Params.FogFalloff); - ReadValue(InFile, this->Params.Wetness); - ReadValue(InFile, this->Params.ScatteringIntensity); - ReadValue(InFile, this->Params.MieScatteringScale); - ReadValue(InFile, this->Params.RayleighScatteringScale); -} - -std::string CarlaRecorderWeather::Print() const -{ - std::ostringstream oss; - oss << TCHAR_TO_UTF8(*Params.ToString()); - return oss.str(); -} - -// --------------------------------------------- - -void CarlaRecorderWeathers::Clear(void) -{ - Weathers.clear(); -} - -void CarlaRecorderWeathers::Add(const CarlaRecorderWeather &Weather) -{ - Weathers.push_back(Weather); -} - -void CarlaRecorderWeathers::Write(std::ofstream &OutFile) const -{ - if (Weathers.size() == 0) - { - return; - } - // write the packet id - WriteValue(OutFile, static_cast(CarlaRecorderPacketId::Weather)); - - std::streampos PosStart = OutFile.tellp(); - - // write a dummy packet size - uint32_t Total = 2 + Weathers.size() * sizeof(CarlaRecorderWeather); - WriteValue(OutFile, Total); - - // write total records - Total = Weathers.size(); - WriteValue(OutFile, Total); - - for (auto& Weather : Weathers) - { - Weather.Write(OutFile); - } - -} +// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "CarlaRecorderWeather.h" +#include "CarlaRecorder.h" +#include "CarlaRecorderHelpers.h" + + +void CarlaRecorderWeather::Write(std::ofstream &OutFile) const +{ + WriteValue(OutFile, this->Params.Cloudiness); + WriteValue(OutFile, this->Params.Precipitation); + WriteValue(OutFile, this->Params.PrecipitationDeposits); + WriteValue(OutFile, this->Params.WindIntensity); + WriteValue(OutFile, this->Params.SunAzimuthAngle); + WriteValue(OutFile, this->Params.SunAltitudeAngle); + WriteValue(OutFile, this->Params.FogDensity); + WriteValue(OutFile, this->Params.FogDistance); + WriteValue(OutFile, this->Params.FogFalloff); + WriteValue(OutFile, this->Params.Wetness); + WriteValue(OutFile, this->Params.ScatteringIntensity); + WriteValue(OutFile, this->Params.MieScatteringScale); + WriteValue(OutFile, this->Params.RayleighScatteringScale); +} + +void CarlaRecorderWeather::Read(std::ifstream &InFile) +{ + ReadValue(InFile, this->Params.Cloudiness); + ReadValue(InFile, this->Params.Precipitation); + ReadValue(InFile, this->Params.PrecipitationDeposits); + ReadValue(InFile, this->Params.WindIntensity); + ReadValue(InFile, this->Params.SunAzimuthAngle); + ReadValue(InFile, this->Params.SunAltitudeAngle); + ReadValue(InFile, this->Params.FogDensity); + ReadValue(InFile, this->Params.FogDistance); + ReadValue(InFile, this->Params.FogFalloff); + ReadValue(InFile, this->Params.Wetness); + ReadValue(InFile, this->Params.ScatteringIntensity); + ReadValue(InFile, this->Params.MieScatteringScale); + ReadValue(InFile, this->Params.RayleighScatteringScale); +} + +std::string CarlaRecorderWeather::Print() const +{ + std::ostringstream oss; + oss << TCHAR_TO_UTF8(*Params.ToString()); + return oss.str(); +} + +// --------------------------------------------- + +void CarlaRecorderWeathers::Clear(void) +{ + Weathers.clear(); +} + +void CarlaRecorderWeathers::Add(const CarlaRecorderWeather &Weather) +{ + Weathers.push_back(Weather); +} + +void CarlaRecorderWeathers::Write(std::ofstream &OutFile) const +{ + if (Weathers.size() == 0) + { + return; + } + // write the packet id + WriteValue(OutFile, static_cast(CarlaRecorderPacketId::Weather)); + + std::streampos PosStart = OutFile.tellp(); + + // write a dummy packet size + uint32_t Total = 2 + Weathers.size() * sizeof(CarlaRecorderWeather); + WriteValue(OutFile, Total); + + // write total records + Total = Weathers.size(); + WriteValue(OutFile, Total); + + for (auto& Weather : Weathers) + { + Weather.Write(OutFile); + } + +} diff --git a/Carla/Recorder/CarlaRecorderWeather.h b/Carla/Recorder/CarlaRecorderWeather.h index e892ad2..b3f79a5 100644 --- a/Carla/Recorder/CarlaRecorderWeather.h +++ b/Carla/Recorder/CarlaRecorderWeather.h @@ -1,40 +1,40 @@ -// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include -#include "Carla/Weather/WeatherParameters.h" - -#pragma pack(push, 1) -struct CarlaRecorderWeather -{ - - FWeatherParameters Params; - - void Read(std::ifstream &InFile); - - void Write(std::ofstream &OutFile) const; - - std::string Print() const; -}; -#pragma pack(pop) - -struct CarlaRecorderWeathers -{ -public: - - void Add(const CarlaRecorderWeather &InObj); - - void Clear(void); - - void Write(std::ofstream &OutFile) const; - -private: - - std::vector Weathers; -}; +// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include "Carla/Weather/WeatherParameters.h" + +#pragma pack(push, 1) +struct CarlaRecorderWeather +{ + + FWeatherParameters Params; + + void Read(std::ifstream &InFile); + + void Write(std::ofstream &OutFile) const; + + std::string Print() const; +}; +#pragma pack(pop) + +struct CarlaRecorderWeathers +{ +public: + + void Add(const CarlaRecorderWeather &InObj); + + void Clear(void); + + void Write(std::ofstream &OutFile) const; + +private: + + std::vector Weathers; +}; diff --git a/Carla/Recorder/CarlaReplayer.cpp b/Carla/Recorder/CarlaReplayer.cpp index 0a03451..bcb44c2 100644 --- a/Carla/Recorder/CarlaReplayer.cpp +++ b/Carla/Recorder/CarlaReplayer.cpp @@ -1,931 +1,931 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaReplayer.h" -#include "CarlaRecorder.h" -#include "Carla/Game/CarlaEpisode.h" - -// DReyeVR include -#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor::ActiveCustomActors -#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor - -#include -#include - -// structure to save replaying info when need to load a new map (static member by now) -CarlaReplayer::PlayAfterLoadMap CarlaReplayer::Autoplay { false, "", "", 0.0, 0.0, 0, 1.0, false }; - -void CarlaReplayer::Stop(bool bKeepActors) -{ - if (Enabled) - { - Enabled = false; - - // destroy actors if event was recorded? - if (!bKeepActors) - { - ProcessToTime(TotalTime, false); - } - - // callback - Helper.ProcessReplayerFinish(bKeepActors, IgnoreHero, IsHeroMap); - - // turn off DReyeVR replay - if (GetEgoSensor()) - GetEgoSensor()->StopReplaying(); - } - - File.close(); -} - -bool CarlaReplayer::ReadHeader() -{ - if (File.eof()) - { - return false; - } - - ReadValue(File, Header.Id); - ReadValue(File, Header.Size); - - return true; -} - -void CarlaReplayer::SkipPacket(void) -{ - File.seekg(Header.Size, std::ios::cur); -} - -void CarlaReplayer::Rewind(void) -{ - CurrentTime = 0.0f; - TotalTime = 0.0f; - TimeToStop = 0.0f; - - File.clear(); - File.seekg(0, std::ios::beg); - - // mark as header as invalid to force reload a new one next time - Frame.Elapsed = -1.0f; - Frame.DurationThis = 0.0f; - - MappedId.clear(); - IsHeroMap.clear(); - - // read geneal Info - RecInfo.Read(File); -} - -// read last frame in File and return the Total time recorded -double CarlaReplayer::GetTotalTime(void) -{ - std::streampos Current = File.tellg(); - - // parse only frames - while (File) - { - // get header - if (!ReadHeader()) - { - break; - } - - // check for a frame packet - switch (Header.Id) - { - case static_cast(CarlaRecorderPacketId::FrameStart): - Frame.Read(File); - break; - default: - SkipPacket(); - break; - } - } - - File.clear(); - File.seekg(Current, std::ios::beg); - return Frame.Elapsed; -} - -// Read all the frames and collect their start times -void CarlaReplayer::GetFrameStartTimes() -{ - std::streampos Current = File.tellg(); - - while (File) - { - if (!ReadHeader()) - { - break; - } - - switch (Header.Id) - { - case static_cast(CarlaRecorderPacketId::FrameStart): - Frame.Read(File); - FrameStartTimes.push_back(Frame.Elapsed); // add this time to the global container - break; - default: - SkipPacket(); - break; - } - } - - File.clear(); - File.seekg(Current, std::ios::beg); // return to original position -} - -std::string CarlaReplayer::ReplayFile(std::string Filename, double TimeStart, double Duration, - uint32_t ThisFollowId, bool ReplaySensors) -{ - std::stringstream Info; - std::string s; - - // Capture params in case we restart from the media controls (use same params) - LastReplay.Filename = Filename; - LastReplay.TimeStart = TimeStart; - LastReplay.Duration = Duration; - LastReplay.ThisFollowId = ThisFollowId; - - // check to stop if we are replaying another - if (Enabled) - { - Stop(); - } - - // get the final path + filename - std::string Filename2 = GetRecorderFilename(Filename); - - Info << "Replaying File: " << Filename2 << std::endl; - - // try to open - File.open(Filename2, std::ios::binary); - if (!File.is_open()) - { - Info << "File " << Filename2 << " not found on server\n"; - Stop(); - return Info.str(); - } - - // from start - Rewind(); - - // check to load map if different - if (Episode->GetMapName() != RecInfo.Mapfile) - { - if (!Episode->LoadNewEpisode(RecInfo.Mapfile)) - { - Info << "Could not load mapfile " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl; - Stop(); - return Info.str(); - } - Info << "Loading map " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl; - Info << "Replayer will start after map is loaded..." << std::endl; - - // prepare autoplay after map is loaded - Autoplay.Enabled = true; - Autoplay.Filename = Filename2; - Autoplay.Mapfile = RecInfo.Mapfile; - Autoplay.TimeStart = TimeStart; - Autoplay.Duration = Duration; - Autoplay.FollowId = ThisFollowId; - Autoplay.TimeFactor = TimeFactor; - Autoplay.ReplaySensors = ReplaySensors; - } - - // get Total time of recorder - TotalTime = GetTotalTime(); - Info << "Total time recorded: " << TotalTime << std::endl; - - // set time to start replayer - if (TimeStart < 0.0f) - { - TimeStart = TotalTime + TimeStart; - if (TimeStart < 0.0f) - TimeStart = 0.0f; - } - - // set time to stop replayer - if (Duration > 0.0f) - TimeToStop = TimeStart + Duration; - else - TimeToStop = TotalTime; - - Info << "Replaying from " << TimeStart << " s - " << TimeToStop << " s (" << TotalTime << " s) at " << - std::setprecision(1) << std::fixed << TimeFactor << "x" << std::endl; - - // set the follow Id - FollowId = ThisFollowId; - - bReplaySensors = ReplaySensors; - // if we don't need to load a new map, then start - if (!Autoplay.Enabled) - { - Helper.RemoveStaticProps(); - // process all events until the time - ProcessToTime(TimeStart, true); - // mark as enabled - Enabled = true; - } - - return Info.str(); -} - -void CarlaReplayer::CheckPlayAfterMapLoaded(void) -{ - - // check if the autoplay is enabled (means waiting until map is loaded) - if (!Autoplay.Enabled) - return; - - // disable - Autoplay.Enabled = false; - - // check to stop if we are replaying another - if (Enabled) - { - Stop(); - } - - // try to open - File.open(Autoplay.Filename, std::ios::binary); - if (!File.is_open()) - { - return; - } - - // from start - Rewind(); - - // get Total time of recorder - TotalTime = GetTotalTime(); - - // set time to start replayer - double TimeStart = Autoplay.TimeStart; - if (TimeStart < 0.0f) - { - TimeStart = TotalTime + Autoplay.TimeStart; - if (TimeStart < 0.0f) - TimeStart = 0.0f; - } - - // set time to stop replayer - if (Autoplay.Duration > 0.0f) - TimeToStop = TimeStart + Autoplay.Duration; - else - TimeToStop = TotalTime; - - // set the follow Id - FollowId = Autoplay.FollowId; - - bReplaySensors = Autoplay.ReplaySensors; - - // apply time factor - TimeFactor = Autoplay.TimeFactor; - - Helper.RemoveStaticProps(); - - // process all events until the time - ProcessToTime(TimeStart, true); - - // mark as enabled - Enabled = true; -} - -class ADReyeVRSensor *CarlaReplayer::GetEgoSensor() -{ - if (EgoSensor.IsValid()) { - return EgoSensor.Get(); - } - // not tracked yet, lets find the EgoSensor - if (Episode == nullptr) { - DReyeVR_LOG_ERROR("No Replayer Episode available!"); - return nullptr; - } - EgoSensor = ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld()); - if (!EgoSensor.IsValid()) { - DReyeVR_LOG_ERROR("No EgoSensor available!"); - return nullptr; - } - return EgoSensor.Get(); -} - -template<> -void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) -{ - uint16_t Total; - // read number of DReyeVR entries - ReadValue(File, Total); // read number of events - check(Total == 1); // should be only one Agg data - for (uint16_t i = 0; i < Total; ++i) - { - struct DReyeVRDataRecorder Instance; - Instance.Read(File); - Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); - } -} - -template<> -void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) -{ - uint16_t Total; - // read number of DReyeVR entries - ReadValue(File, Total); // read number of events - check(Total == 1); // should be only one ConfigFile data - for (uint16_t i = 0; i < Total; ++i) - { - struct DReyeVRDataRecorder Instance; - Instance.Read(File); - Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); - } -} - -template<> -void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) -{ - uint16_t Total; - ReadValue(File, Total); // read number of events - CustomActorsVisited.clear(); - for (uint16_t i = 0; i < Total; ++i) - { - struct DReyeVRDataRecorder Instance; - Instance.Read(File); - Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); - auto Name = Instance.GetUniqueName(); - CustomActorsVisited.insert(Name); // to track lifetime - } - - for (auto It = ADReyeVRCustomActor::ActiveCustomActors.begin(); It != ADReyeVRCustomActor::ActiveCustomActors.end();){ - const std::string &ActiveActorName = It->first; - if (CustomActorsVisited.find(ActiveActorName) == CustomActorsVisited.end()) // currently alive actor who was not visited... time to disable - { - // now this has to be garbage collected - auto Next = std::next(It, 1); // iterator following the last removed element - It->second->Deactivate(); - It = Next; - } - else - { - ++It; // increment iterator if not erased - } - } -} - -void CarlaReplayer::ProcessToTime(double Time, bool IsFirstTime) -{ - double Per = 0.0f; - double NewTime = CurrentTime + Time; - bool bFrameFound = false; - bool bExitAtNextFrame = false; - bool bExitLoop = false; - - // check if we are in the right frame - if (NewTime >= Frame.Elapsed && NewTime < Frame.Elapsed + Frame.DurationThis) - { - Per = (NewTime - Frame.Elapsed) / Frame.DurationThis; - bFrameFound = true; - bExitLoop = true; - } - - // process all frames until time we want or end - while (!File.eof() && !bExitLoop) - { - // get header - ReadHeader(); - - // check for a frame packet - switch (Header.Id) - { - // frame - case static_cast(CarlaRecorderPacketId::FrameStart): - // only read if we are not in the right frame - Frame.Read(File); - // check if target time is in this frame - if (NewTime < Frame.Elapsed + Frame.DurationThis) - { - Per = (NewTime - Frame.Elapsed) / Frame.DurationThis; - bFrameFound = true; - } - break; - - // events add - case static_cast(CarlaRecorderPacketId::EventAdd): - ProcessEventsAdd(); - break; - - // events del - case static_cast(CarlaRecorderPacketId::EventDel): - ProcessEventsDel(); - break; - - // events parent - case static_cast(CarlaRecorderPacketId::EventParent): - ProcessEventsParent(); - break; - - // collisions - case static_cast(CarlaRecorderPacketId::Collision): - SkipPacket(); - break; - - // positions - case static_cast(CarlaRecorderPacketId::Position): - if (bFrameFound) - ProcessPositions(IsFirstTime); - else - SkipPacket(); - break; - - // states - case static_cast(CarlaRecorderPacketId::State): - if (bFrameFound) - ProcessStates(); - else - SkipPacket(); - break; - - // vehicle animation - case static_cast(CarlaRecorderPacketId::AnimVehicle): - if (bFrameFound) - ProcessAnimVehicle(); - else - SkipPacket(); - break; - - // walker animation - case static_cast(CarlaRecorderPacketId::AnimWalker): - if (bFrameFound) - ProcessAnimWalker(); - else - SkipPacket(); - break; - - // vehicle light animation - case static_cast(CarlaRecorderPacketId::VehicleLight): - if (bFrameFound) - ProcessLightVehicle(); - else - SkipPacket(); - break; - - // scene lights animation - case static_cast(CarlaRecorderPacketId::SceneLight): - if (bFrameFound) - ProcessLightScene(); - else - SkipPacket(); - break; - - // weather state - case static_cast(CarlaRecorderPacketId::Weather): - ProcessWeather(); - break; - - // DReyeVR ego sensor data - case static_cast(CarlaRecorderPacketId::DReyeVR): - if (bFrameFound) - ProcessDReyeVR(Per, Time); - else - SkipPacket(); - break; - - // DReyeVR custom actor data - case static_cast(CarlaRecorderPacketId::DReyeVRCustomActor): - if (bFrameFound) - ProcessDReyeVR(Per, Time); - else - SkipPacket(); - break; - - // DReyeVR config file data - case static_cast(CarlaRecorderPacketId::DReyeVRConfigFile): - if (bFrameFound) - ProcessDReyeVR(Per, Time); - else - SkipPacket(); - break; - - // frame end - case static_cast(CarlaRecorderPacketId::FrameEnd): - if (bFrameFound) - bExitLoop = true; - break; - - // unknown packet, just skip - default: - // skip packet - SkipPacket(); - break; - - } - } - - // update all positions - if (Enabled && bFrameFound) - { - UpdatePositions(Per, Time); - } - - // save current time - CurrentTime = NewTime; - - // stop replay? - if (CurrentTime >= TimeToStop) - { - // keep actors in scene and let them continue with autopilot - Stop(true); - } -} - -void CarlaReplayer::ProcessEventsAdd(void) -{ - uint16_t i, Total; - CarlaRecorderEventAdd EventAdd; - - // process creation events - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - EventAdd.Read(File); - - // auto Result = CallbackEventAdd( - auto Result = Helper.ProcessReplayerEventAdd( - EventAdd.Location, - EventAdd.Rotation, - EventAdd.Description, - EventAdd.DatabaseId, - IgnoreHero, - bReplaySensors); - - switch (Result.first) - { - // actor not created - case 0: - UE_LOG(LogCarla, Log, TEXT("actor could not be created")); - break; - - // actor created but with different id - case 1: - // mapping id (recorded Id is a new Id in replayer) - MappedId[EventAdd.DatabaseId] = Result.second; - break; - - // actor reused from existing - case 2: - // mapping id (say desired Id is mapped to what) - MappedId[EventAdd.DatabaseId] = Result.second; - break; - } - - // check to mark if actor is a hero vehicle or not - if (Result.first > 0) - { - // init - IsHeroMap[Result.second] = false; - for (const auto &Item : EventAdd.Description.Attributes) - { - if (Item.Id == "role_name" && Item.Value == "hero") - { - // mark as hero - IsHeroMap[Result.second] = true; - break; - } - } - } - } -} - -void CarlaReplayer::ProcessEventsDel(void) -{ - uint16_t i, Total; - CarlaRecorderEventDel EventDel; - - // process destroy events - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - EventDel.Read(File); - Helper.ProcessReplayerEventDel(MappedId[EventDel.DatabaseId]); - MappedId.erase(EventDel.DatabaseId); - } -} - -void CarlaReplayer::ProcessEventsParent(void) -{ - uint16_t i, Total; - CarlaRecorderEventParent EventParent; - std::stringstream Info; - - // process parenting events - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - EventParent.Read(File); - Helper.ProcessReplayerEventParent(MappedId[EventParent.DatabaseId], MappedId[EventParent.DatabaseIdParent]); - } -} - -void CarlaReplayer::ProcessStates(void) -{ - uint16_t i, Total; - CarlaRecorderStateTrafficLight StateTrafficLight; - std::stringstream Info; - - // read Total traffic light states - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - StateTrafficLight.Read(File); - - StateTrafficLight.DatabaseId = MappedId[StateTrafficLight.DatabaseId]; - if (!Helper.ProcessReplayerStateTrafficLight(StateTrafficLight)) - { - UE_LOG(LogCarla, - Log, - TEXT("callback state traffic light %d called but didn't work"), - StateTrafficLight.DatabaseId); - } - } -} - -void CarlaReplayer::ProcessAnimVehicle(void) -{ - uint16_t i, Total; - CarlaRecorderAnimVehicle Vehicle; - std::stringstream Info; - - // read Total Vehicles - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - Vehicle.Read(File); - Vehicle.DatabaseId = MappedId[Vehicle.DatabaseId]; - // check if ignore this actor - if (!(IgnoreHero && IsHeroMap[Vehicle.DatabaseId])) - { - Helper.ProcessReplayerAnimVehicle(Vehicle); - } - } -} - -void CarlaReplayer::ProcessAnimWalker(void) -{ - uint16_t i, Total; - CarlaRecorderAnimWalker Walker; - std::stringstream Info; - - // read Total walkers - ReadValue(File, Total); - for (i = 0; i < Total; ++i) - { - Walker.Read(File); - Walker.DatabaseId = MappedId[Walker.DatabaseId]; - // check if ignore this actor - if (!(IgnoreHero && IsHeroMap[Walker.DatabaseId])) - { - Helper.ProcessReplayerAnimWalker(Walker); - } - } -} - -void CarlaReplayer::ProcessLightVehicle(void) -{ - uint16_t Total; - CarlaRecorderLightVehicle LightVehicle; - - // read Total walkers - ReadValue(File, Total); - for (uint16_t i = 0; i < Total; ++i) - { - LightVehicle.Read(File); - LightVehicle.DatabaseId = MappedId[LightVehicle.DatabaseId]; - // check if ignore this actor - if (!(IgnoreHero && IsHeroMap[LightVehicle.DatabaseId])) - { - Helper.ProcessReplayerLightVehicle(LightVehicle); - } - } -} - -void CarlaReplayer::ProcessLightScene(void) -{ - uint16_t Total; - CarlaRecorderLightScene LightScene; - - // read Total light events - ReadValue(File, Total); - for (uint16_t i = 0; i < Total; ++i) - { - LightScene.Read(File); - Helper.ProcessReplayerLightScene(LightScene); - } -} - -void CarlaReplayer::ProcessWeather(void) -{ - uint16_t Total; - CarlaRecorderWeather Weather; - - // read Total light events - ReadValue(File, Total); - for (uint16_t i = 0; i < Total; ++i) - { - Weather.Read(File); - Helper.ProcessReplayerWeather(Weather); - } -} - -void CarlaReplayer::ProcessPositions(bool IsFirstTime) -{ - uint16_t i, Total; - - // save current as previous - PrevPos = std::move(CurrPos); - - // read all positions - ReadValue(File, Total); - CurrPos.clear(); - CurrPos.reserve(Total); - for (i = 0; i < Total; ++i) - { - CarlaRecorderPosition Pos; - Pos.Read(File); - // assign mapped Id - auto NewId = MappedId.find(Pos.DatabaseId); - if (NewId != MappedId.end()) - { - Pos.DatabaseId = NewId->second; - } - else - UE_LOG(LogCarla, Log, TEXT("Actor not found when trying to move from replayer (id. %d)"), Pos.DatabaseId); - CurrPos.push_back(std::move(Pos)); - } - - // check to copy positions the first time - if (IsFirstTime) - { - PrevPos.clear(); - } -} - -void CarlaReplayer::UpdatePositions(double Per, double DeltaTime) -{ - unsigned int i; - uint32_t NewFollowId = 0; - std::unordered_map TempMap; - - // map the id of all previous positions to its index - for (i = 0; i < PrevPos.size(); ++i) - { - TempMap[PrevPos[i].DatabaseId] = i; - } - - // get the Id of the actor to follow - if (FollowId != 0) - { - auto NewId = MappedId.find(FollowId); - if (NewId != MappedId.end()) - { - NewFollowId = NewId->second; - } - } - - // go through each actor and update - for (auto &Pos : CurrPos) - { - // check if ignore this actor - if (!(IgnoreHero && IsHeroMap[Pos.DatabaseId])) - { - // check if exist a previous position - auto Result = TempMap.find(Pos.DatabaseId); - if (Result != TempMap.end()) - { - // check if time factor is high - if (TimeFactor >= 2.0) - // assign first position - InterpolatePosition(PrevPos[Result->second], Pos, 0.0, DeltaTime); - else - // interpolate - InterpolatePosition(PrevPos[Result->second], Pos, Per, DeltaTime); - } - else - { - // assign last position (we don't have previous one) - InterpolatePosition(Pos, Pos, 0.0, DeltaTime); - } - } - - // move the camera to follow this actor if required - if (NewFollowId != 0) - { - if (NewFollowId == Pos.DatabaseId) - Helper.SetCameraPosition(NewFollowId, FVector(-1000, 0, 500), FQuat::MakeFromEuler({0, -25, 0})); - } - } -} - -// interpolate a position (transform, velocity...) -void CarlaReplayer::InterpolatePosition( - const CarlaRecorderPosition &Pos1, - const CarlaRecorderPosition &Pos2, - double Per, - double DeltaTime) -{ - // call the callback - Helper.ProcessReplayerPosition(Pos1, Pos2, Per, DeltaTime); -} - -// tick for the replayer -void CarlaReplayer::Tick(float Delta) -{ - TRACE_CPUPROFILER_EVENT_SCOPE(CarlaReplayer::Tick); - // check if there are events to process (and unpaused) - if (Enabled && !Paused) - { - if (bReplaySync) - { - ProcessFrameByFrame(); - } - else // typical usage (replay as fast as possible with interpolation) - { - ProcessToTime(Delta * TimeFactor, false); - } - } -} - -void CarlaReplayer::ProcessFrameByFrame() -{ - // get the times to process if needed - if (FrameStartTimes.size() == 0) - { - GetFrameStartTimes(); - ensure(FrameStartTimes.size() > 0); - } - - // process to those times - ensure(SyncCurrentFrameId < FrameStartTimes.size()); - double LastTime = 0.f; - if (SyncCurrentFrameId > 0) - LastTime = FrameStartTimes[SyncCurrentFrameId - 1]; - ProcessToTime(FrameStartTimes[SyncCurrentFrameId] - LastTime, (SyncCurrentFrameId == 0)); - if (GetEgoSensor()) // take screenshot of this frame - GetEgoSensor()->TakeScreenshot(); - // progress to the next frame - if (SyncCurrentFrameId < FrameStartTimes.size() - 1) - SyncCurrentFrameId++; - else - Stop(); -} - -void CarlaReplayer::Restart() -{ - // Use same params as they were initially - ReplayFile(LastReplay.Filename, LastReplay.TimeStart, - LastReplay.Duration, LastReplay.ThisFollowId); -} - -void CarlaReplayer::Advance(const float Amnt) -{ - // check out of bounds - const double DesiredTime = CurrentTime + Amnt; - if (DesiredTime < 0 || DesiredTime > TotalTime || DesiredTime > TimeToStop) - { - return; - } - - // ignore if 0 - if (Amnt == 0) - { - return; - } - // forward in time (easy) - else if (Amnt > 0) - { - /// TODO: verify that this correctly places all actors - // else can use the Restart+ProcessToTime hack similar to backwards - ProcessToTime(Amnt, false); - } - // backwards in time (harder) - else - { - // // amnt is unit of time (timestep) for replay - // UE_LOG(LogTemp, Log, TEXT("Want to go back to: %.4f from"), DesiredTime, CurrentTime); - // int NumAmnts = ((CurrentTime - Frame.Elapsed) / (-Amnt)) + 1; - // // duration is unit of time (timestep) for recordings - // int NumDurations = (NumAmnts * (-Amnt)) / Frame.DurationThis; - // UE_LOG(LogTemp, Log, TEXT("With a duration of %.4f, this'll take %d prevs"), Frame.DurationThis, NumDurations); - // for (size_t i = 0; i < NumDurations; i++) - // { - // PrevPacket(); // go backwards in the file - // } - // UE_LOG(LogTemp, Log, TEXT("Now the time is: %.3f"), Frame.Elapsed); - // // back to negative - // ProcessToTime(Amnt, false); - Stop(true); // stops the replaying while keeping actors (dosen't destroy & respawn) - Restart(); - ProcessToTime(DesiredTime, true); - } +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "CarlaReplayer.h" +#include "CarlaRecorder.h" +#include "Carla/Game/CarlaEpisode.h" + +// DReyeVR include +#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor::ActiveCustomActors +#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor + +#include +#include + +// structure to save replaying info when need to load a new map (static member by now) +CarlaReplayer::PlayAfterLoadMap CarlaReplayer::Autoplay { false, "", "", 0.0, 0.0, 0, 1.0, false }; + +void CarlaReplayer::Stop(bool bKeepActors) +{ + if (Enabled) + { + Enabled = false; + + // destroy actors if event was recorded? + if (!bKeepActors) + { + ProcessToTime(TotalTime, false); + } + + // callback + Helper.ProcessReplayerFinish(bKeepActors, IgnoreHero, IsHeroMap); + + // turn off DReyeVR replay + if (GetEgoSensor()) + GetEgoSensor()->StopReplaying(); + } + + File.close(); +} + +bool CarlaReplayer::ReadHeader() +{ + if (File.eof()) + { + return false; + } + + ReadValue(File, Header.Id); + ReadValue(File, Header.Size); + + return true; +} + +void CarlaReplayer::SkipPacket(void) +{ + File.seekg(Header.Size, std::ios::cur); +} + +void CarlaReplayer::Rewind(void) +{ + CurrentTime = 0.0f; + TotalTime = 0.0f; + TimeToStop = 0.0f; + + File.clear(); + File.seekg(0, std::ios::beg); + + // mark as header as invalid to force reload a new one next time + Frame.Elapsed = -1.0f; + Frame.DurationThis = 0.0f; + + MappedId.clear(); + IsHeroMap.clear(); + + // read geneal Info + RecInfo.Read(File); +} + +// read last frame in File and return the Total time recorded +double CarlaReplayer::GetTotalTime(void) +{ + std::streampos Current = File.tellg(); + + // parse only frames + while (File) + { + // get header + if (!ReadHeader()) + { + break; + } + + // check for a frame packet + switch (Header.Id) + { + case static_cast(CarlaRecorderPacketId::FrameStart): + Frame.Read(File); + break; + default: + SkipPacket(); + break; + } + } + + File.clear(); + File.seekg(Current, std::ios::beg); + return Frame.Elapsed; +} + +// Read all the frames and collect their start times +void CarlaReplayer::GetFrameStartTimes() +{ + std::streampos Current = File.tellg(); + + while (File) + { + if (!ReadHeader()) + { + break; + } + + switch (Header.Id) + { + case static_cast(CarlaRecorderPacketId::FrameStart): + Frame.Read(File); + FrameStartTimes.push_back(Frame.Elapsed); // add this time to the global container + break; + default: + SkipPacket(); + break; + } + } + + File.clear(); + File.seekg(Current, std::ios::beg); // return to original position +} + +std::string CarlaReplayer::ReplayFile(std::string Filename, double TimeStart, double Duration, + uint32_t ThisFollowId, bool ReplaySensors) +{ + std::stringstream Info; + std::string s; + + // Capture params in case we restart from the media controls (use same params) + LastReplay.Filename = Filename; + LastReplay.TimeStart = TimeStart; + LastReplay.Duration = Duration; + LastReplay.ThisFollowId = ThisFollowId; + + // check to stop if we are replaying another + if (Enabled) + { + Stop(); + } + + // get the final path + filename + std::string Filename2 = GetRecorderFilename(Filename); + + Info << "Replaying File: " << Filename2 << std::endl; + + // try to open + File.open(Filename2, std::ios::binary); + if (!File.is_open()) + { + Info << "File " << Filename2 << " not found on server\n"; + Stop(); + return Info.str(); + } + + // from start + Rewind(); + + // check to load map if different + if (Episode->GetMapName() != RecInfo.Mapfile) + { + if (!Episode->LoadNewEpisode(RecInfo.Mapfile)) + { + Info << "Could not load mapfile " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl; + Stop(); + return Info.str(); + } + Info << "Loading map " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl; + Info << "Replayer will start after map is loaded..." << std::endl; + + // prepare autoplay after map is loaded + Autoplay.Enabled = true; + Autoplay.Filename = Filename2; + Autoplay.Mapfile = RecInfo.Mapfile; + Autoplay.TimeStart = TimeStart; + Autoplay.Duration = Duration; + Autoplay.FollowId = ThisFollowId; + Autoplay.TimeFactor = TimeFactor; + Autoplay.ReplaySensors = ReplaySensors; + } + + // get Total time of recorder + TotalTime = GetTotalTime(); + Info << "Total time recorded: " << TotalTime << std::endl; + + // set time to start replayer + if (TimeStart < 0.0f) + { + TimeStart = TotalTime + TimeStart; + if (TimeStart < 0.0f) + TimeStart = 0.0f; + } + + // set time to stop replayer + if (Duration > 0.0f) + TimeToStop = TimeStart + Duration; + else + TimeToStop = TotalTime; + + Info << "Replaying from " << TimeStart << " s - " << TimeToStop << " s (" << TotalTime << " s) at " << + std::setprecision(1) << std::fixed << TimeFactor << "x" << std::endl; + + // set the follow Id + FollowId = ThisFollowId; + + bReplaySensors = ReplaySensors; + // if we don't need to load a new map, then start + if (!Autoplay.Enabled) + { + Helper.RemoveStaticProps(); + // process all events until the time + ProcessToTime(TimeStart, true); + // mark as enabled + Enabled = true; + } + + return Info.str(); +} + +void CarlaReplayer::CheckPlayAfterMapLoaded(void) +{ + + // check if the autoplay is enabled (means waiting until map is loaded) + if (!Autoplay.Enabled) + return; + + // disable + Autoplay.Enabled = false; + + // check to stop if we are replaying another + if (Enabled) + { + Stop(); + } + + // try to open + File.open(Autoplay.Filename, std::ios::binary); + if (!File.is_open()) + { + return; + } + + // from start + Rewind(); + + // get Total time of recorder + TotalTime = GetTotalTime(); + + // set time to start replayer + double TimeStart = Autoplay.TimeStart; + if (TimeStart < 0.0f) + { + TimeStart = TotalTime + Autoplay.TimeStart; + if (TimeStart < 0.0f) + TimeStart = 0.0f; + } + + // set time to stop replayer + if (Autoplay.Duration > 0.0f) + TimeToStop = TimeStart + Autoplay.Duration; + else + TimeToStop = TotalTime; + + // set the follow Id + FollowId = Autoplay.FollowId; + + bReplaySensors = Autoplay.ReplaySensors; + + // apply time factor + TimeFactor = Autoplay.TimeFactor; + + Helper.RemoveStaticProps(); + + // process all events until the time + ProcessToTime(TimeStart, true); + + // mark as enabled + Enabled = true; +} + +class ADReyeVRSensor *CarlaReplayer::GetEgoSensor() +{ + if (EgoSensor.IsValid()) { + return EgoSensor.Get(); + } + // not tracked yet, lets find the EgoSensor + if (Episode == nullptr) { + DReyeVR_LOG_ERROR("No Replayer Episode available!"); + return nullptr; + } + EgoSensor = ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld()); + if (!EgoSensor.IsValid()) { + DReyeVR_LOG_ERROR("No EgoSensor available!"); + return nullptr; + } + return EgoSensor.Get(); +} + +template<> +void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) +{ + uint16_t Total; + // read number of DReyeVR entries + ReadValue(File, Total); // read number of events + check(Total == 1); // should be only one Agg data + for (uint16_t i = 0; i < Total; ++i) + { + struct DReyeVRDataRecorder Instance; + Instance.Read(File); + Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); + } +} + +template<> +void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) +{ + uint16_t Total; + // read number of DReyeVR entries + ReadValue(File, Total); // read number of events + check(Total == 1); // should be only one ConfigFile data + for (uint16_t i = 0; i < Total; ++i) + { + struct DReyeVRDataRecorder Instance; + Instance.Read(File); + Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); + } +} + +template<> +void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) +{ + uint16_t Total; + ReadValue(File, Total); // read number of events + CustomActorsVisited.clear(); + for (uint16_t i = 0; i < Total; ++i) + { + struct DReyeVRDataRecorder Instance; + Instance.Read(File); + Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); + auto Name = Instance.GetUniqueName(); + CustomActorsVisited.insert(Name); // to track lifetime + } + + for (auto It = ADReyeVRCustomActor::ActiveCustomActors.begin(); It != ADReyeVRCustomActor::ActiveCustomActors.end();){ + const std::string &ActiveActorName = It->first; + if (CustomActorsVisited.find(ActiveActorName) == CustomActorsVisited.end()) // currently alive actor who was not visited... time to disable + { + // now this has to be garbage collected + auto Next = std::next(It, 1); // iterator following the last removed element + It->second->Deactivate(); + It = Next; + } + else + { + ++It; // increment iterator if not erased + } + } +} + +void CarlaReplayer::ProcessToTime(double Time, bool IsFirstTime) +{ + double Per = 0.0f; + double NewTime = CurrentTime + Time; + bool bFrameFound = false; + bool bExitAtNextFrame = false; + bool bExitLoop = false; + + // check if we are in the right frame + if (NewTime >= Frame.Elapsed && NewTime < Frame.Elapsed + Frame.DurationThis) + { + Per = (NewTime - Frame.Elapsed) / Frame.DurationThis; + bFrameFound = true; + bExitLoop = true; + } + + // process all frames until time we want or end + while (!File.eof() && !bExitLoop) + { + // get header + ReadHeader(); + + // check for a frame packet + switch (Header.Id) + { + // frame + case static_cast(CarlaRecorderPacketId::FrameStart): + // only read if we are not in the right frame + Frame.Read(File); + // check if target time is in this frame + if (NewTime < Frame.Elapsed + Frame.DurationThis) + { + Per = (NewTime - Frame.Elapsed) / Frame.DurationThis; + bFrameFound = true; + } + break; + + // events add + case static_cast(CarlaRecorderPacketId::EventAdd): + ProcessEventsAdd(); + break; + + // events del + case static_cast(CarlaRecorderPacketId::EventDel): + ProcessEventsDel(); + break; + + // events parent + case static_cast(CarlaRecorderPacketId::EventParent): + ProcessEventsParent(); + break; + + // collisions + case static_cast(CarlaRecorderPacketId::Collision): + SkipPacket(); + break; + + // positions + case static_cast(CarlaRecorderPacketId::Position): + if (bFrameFound) + ProcessPositions(IsFirstTime); + else + SkipPacket(); + break; + + // states + case static_cast(CarlaRecorderPacketId::State): + if (bFrameFound) + ProcessStates(); + else + SkipPacket(); + break; + + // vehicle animation + case static_cast(CarlaRecorderPacketId::AnimVehicle): + if (bFrameFound) + ProcessAnimVehicle(); + else + SkipPacket(); + break; + + // walker animation + case static_cast(CarlaRecorderPacketId::AnimWalker): + if (bFrameFound) + ProcessAnimWalker(); + else + SkipPacket(); + break; + + // vehicle light animation + case static_cast(CarlaRecorderPacketId::VehicleLight): + if (bFrameFound) + ProcessLightVehicle(); + else + SkipPacket(); + break; + + // scene lights animation + case static_cast(CarlaRecorderPacketId::SceneLight): + if (bFrameFound) + ProcessLightScene(); + else + SkipPacket(); + break; + + // weather state + case static_cast(CarlaRecorderPacketId::Weather): + ProcessWeather(); + break; + + // DReyeVR ego sensor data + case static_cast(CarlaRecorderPacketId::DReyeVR): + if (bFrameFound) + ProcessDReyeVR(Per, Time); + else + SkipPacket(); + break; + + // DReyeVR custom actor data + case static_cast(CarlaRecorderPacketId::DReyeVRCustomActor): + if (bFrameFound) + ProcessDReyeVR(Per, Time); + else + SkipPacket(); + break; + + // DReyeVR config file data + case static_cast(CarlaRecorderPacketId::DReyeVRConfigFile): + if (bFrameFound) + ProcessDReyeVR(Per, Time); + else + SkipPacket(); + break; + + // frame end + case static_cast(CarlaRecorderPacketId::FrameEnd): + if (bFrameFound) + bExitLoop = true; + break; + + // unknown packet, just skip + default: + // skip packet + SkipPacket(); + break; + + } + } + + // update all positions + if (Enabled && bFrameFound) + { + UpdatePositions(Per, Time); + } + + // save current time + CurrentTime = NewTime; + + // stop replay? + if (CurrentTime >= TimeToStop) + { + // keep actors in scene and let them continue with autopilot + Stop(true); + } +} + +void CarlaReplayer::ProcessEventsAdd(void) +{ + uint16_t i, Total; + CarlaRecorderEventAdd EventAdd; + + // process creation events + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + EventAdd.Read(File); + + // auto Result = CallbackEventAdd( + auto Result = Helper.ProcessReplayerEventAdd( + EventAdd.Location, + EventAdd.Rotation, + EventAdd.Description, + EventAdd.DatabaseId, + IgnoreHero, + bReplaySensors); + + switch (Result.first) + { + // actor not created + case 0: + UE_LOG(LogCarla, Log, TEXT("actor could not be created")); + break; + + // actor created but with different id + case 1: + // mapping id (recorded Id is a new Id in replayer) + MappedId[EventAdd.DatabaseId] = Result.second; + break; + + // actor reused from existing + case 2: + // mapping id (say desired Id is mapped to what) + MappedId[EventAdd.DatabaseId] = Result.second; + break; + } + + // check to mark if actor is a hero vehicle or not + if (Result.first > 0) + { + // init + IsHeroMap[Result.second] = false; + for (const auto &Item : EventAdd.Description.Attributes) + { + if (Item.Id == "role_name" && Item.Value == "hero") + { + // mark as hero + IsHeroMap[Result.second] = true; + break; + } + } + } + } +} + +void CarlaReplayer::ProcessEventsDel(void) +{ + uint16_t i, Total; + CarlaRecorderEventDel EventDel; + + // process destroy events + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + EventDel.Read(File); + Helper.ProcessReplayerEventDel(MappedId[EventDel.DatabaseId]); + MappedId.erase(EventDel.DatabaseId); + } +} + +void CarlaReplayer::ProcessEventsParent(void) +{ + uint16_t i, Total; + CarlaRecorderEventParent EventParent; + std::stringstream Info; + + // process parenting events + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + EventParent.Read(File); + Helper.ProcessReplayerEventParent(MappedId[EventParent.DatabaseId], MappedId[EventParent.DatabaseIdParent]); + } +} + +void CarlaReplayer::ProcessStates(void) +{ + uint16_t i, Total; + CarlaRecorderStateTrafficLight StateTrafficLight; + std::stringstream Info; + + // read Total traffic light states + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + StateTrafficLight.Read(File); + + StateTrafficLight.DatabaseId = MappedId[StateTrafficLight.DatabaseId]; + if (!Helper.ProcessReplayerStateTrafficLight(StateTrafficLight)) + { + UE_LOG(LogCarla, + Log, + TEXT("callback state traffic light %d called but didn't work"), + StateTrafficLight.DatabaseId); + } + } +} + +void CarlaReplayer::ProcessAnimVehicle(void) +{ + uint16_t i, Total; + CarlaRecorderAnimVehicle Vehicle; + std::stringstream Info; + + // read Total Vehicles + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + Vehicle.Read(File); + Vehicle.DatabaseId = MappedId[Vehicle.DatabaseId]; + // check if ignore this actor + if (!(IgnoreHero && IsHeroMap[Vehicle.DatabaseId])) + { + Helper.ProcessReplayerAnimVehicle(Vehicle); + } + } +} + +void CarlaReplayer::ProcessAnimWalker(void) +{ + uint16_t i, Total; + CarlaRecorderAnimWalker Walker; + std::stringstream Info; + + // read Total walkers + ReadValue(File, Total); + for (i = 0; i < Total; ++i) + { + Walker.Read(File); + Walker.DatabaseId = MappedId[Walker.DatabaseId]; + // check if ignore this actor + if (!(IgnoreHero && IsHeroMap[Walker.DatabaseId])) + { + Helper.ProcessReplayerAnimWalker(Walker); + } + } +} + +void CarlaReplayer::ProcessLightVehicle(void) +{ + uint16_t Total; + CarlaRecorderLightVehicle LightVehicle; + + // read Total walkers + ReadValue(File, Total); + for (uint16_t i = 0; i < Total; ++i) + { + LightVehicle.Read(File); + LightVehicle.DatabaseId = MappedId[LightVehicle.DatabaseId]; + // check if ignore this actor + if (!(IgnoreHero && IsHeroMap[LightVehicle.DatabaseId])) + { + Helper.ProcessReplayerLightVehicle(LightVehicle); + } + } +} + +void CarlaReplayer::ProcessLightScene(void) +{ + uint16_t Total; + CarlaRecorderLightScene LightScene; + + // read Total light events + ReadValue(File, Total); + for (uint16_t i = 0; i < Total; ++i) + { + LightScene.Read(File); + Helper.ProcessReplayerLightScene(LightScene); + } +} + +void CarlaReplayer::ProcessWeather(void) +{ + uint16_t Total; + CarlaRecorderWeather Weather; + + // read Total light events + ReadValue(File, Total); + for (uint16_t i = 0; i < Total; ++i) + { + Weather.Read(File); + Helper.ProcessReplayerWeather(Weather); + } +} + +void CarlaReplayer::ProcessPositions(bool IsFirstTime) +{ + uint16_t i, Total; + + // save current as previous + PrevPos = std::move(CurrPos); + + // read all positions + ReadValue(File, Total); + CurrPos.clear(); + CurrPos.reserve(Total); + for (i = 0; i < Total; ++i) + { + CarlaRecorderPosition Pos; + Pos.Read(File); + // assign mapped Id + auto NewId = MappedId.find(Pos.DatabaseId); + if (NewId != MappedId.end()) + { + Pos.DatabaseId = NewId->second; + } + else + UE_LOG(LogCarla, Log, TEXT("Actor not found when trying to move from replayer (id. %d)"), Pos.DatabaseId); + CurrPos.push_back(std::move(Pos)); + } + + // check to copy positions the first time + if (IsFirstTime) + { + PrevPos.clear(); + } +} + +void CarlaReplayer::UpdatePositions(double Per, double DeltaTime) +{ + unsigned int i; + uint32_t NewFollowId = 0; + std::unordered_map TempMap; + + // map the id of all previous positions to its index + for (i = 0; i < PrevPos.size(); ++i) + { + TempMap[PrevPos[i].DatabaseId] = i; + } + + // get the Id of the actor to follow + if (FollowId != 0) + { + auto NewId = MappedId.find(FollowId); + if (NewId != MappedId.end()) + { + NewFollowId = NewId->second; + } + } + + // go through each actor and update + for (auto &Pos : CurrPos) + { + // check if ignore this actor + if (!(IgnoreHero && IsHeroMap[Pos.DatabaseId])) + { + // check if exist a previous position + auto Result = TempMap.find(Pos.DatabaseId); + if (Result != TempMap.end()) + { + // check if time factor is high + if (TimeFactor >= 2.0) + // assign first position + InterpolatePosition(PrevPos[Result->second], Pos, 0.0, DeltaTime); + else + // interpolate + InterpolatePosition(PrevPos[Result->second], Pos, Per, DeltaTime); + } + else + { + // assign last position (we don't have previous one) + InterpolatePosition(Pos, Pos, 0.0, DeltaTime); + } + } + + // move the camera to follow this actor if required + if (NewFollowId != 0) + { + if (NewFollowId == Pos.DatabaseId) + Helper.SetCameraPosition(NewFollowId, FVector(-1000, 0, 500), FQuat::MakeFromEuler({0, -25, 0})); + } + } +} + +// interpolate a position (transform, velocity...) +void CarlaReplayer::InterpolatePosition( + const CarlaRecorderPosition &Pos1, + const CarlaRecorderPosition &Pos2, + double Per, + double DeltaTime) +{ + // call the callback + Helper.ProcessReplayerPosition(Pos1, Pos2, Per, DeltaTime); +} + +// tick for the replayer +void CarlaReplayer::Tick(float Delta) +{ + TRACE_CPUPROFILER_EVENT_SCOPE(CarlaReplayer::Tick); + // check if there are events to process (and unpaused) + if (Enabled && !Paused) + { + if (bReplaySync) + { + ProcessFrameByFrame(); + } + else // typical usage (replay as fast as possible with interpolation) + { + ProcessToTime(Delta * TimeFactor, false); + } + } +} + +void CarlaReplayer::ProcessFrameByFrame() +{ + // get the times to process if needed + if (FrameStartTimes.size() == 0) + { + GetFrameStartTimes(); + ensure(FrameStartTimes.size() > 0); + } + + // process to those times + ensure(SyncCurrentFrameId < FrameStartTimes.size()); + double LastTime = 0.f; + if (SyncCurrentFrameId > 0) + LastTime = FrameStartTimes[SyncCurrentFrameId - 1]; + ProcessToTime(FrameStartTimes[SyncCurrentFrameId] - LastTime, (SyncCurrentFrameId == 0)); + if (GetEgoSensor()) // take screenshot of this frame + GetEgoSensor()->TakeScreenshot(); + // progress to the next frame + if (SyncCurrentFrameId < FrameStartTimes.size() - 1) + SyncCurrentFrameId++; + else + Stop(); +} + +void CarlaReplayer::Restart() +{ + // Use same params as they were initially + ReplayFile(LastReplay.Filename, LastReplay.TimeStart, + LastReplay.Duration, LastReplay.ThisFollowId); +} + +void CarlaReplayer::Advance(const float Amnt) +{ + // check out of bounds + const double DesiredTime = CurrentTime + Amnt; + if (DesiredTime < 0 || DesiredTime > TotalTime || DesiredTime > TimeToStop) + { + return; + } + + // ignore if 0 + if (Amnt == 0) + { + return; + } + // forward in time (easy) + else if (Amnt > 0) + { + /// TODO: verify that this correctly places all actors + // else can use the Restart+ProcessToTime hack similar to backwards + ProcessToTime(Amnt, false); + } + // backwards in time (harder) + else + { + // // amnt is unit of time (timestep) for replay + // UE_LOG(LogTemp, Log, TEXT("Want to go back to: %.4f from"), DesiredTime, CurrentTime); + // int NumAmnts = ((CurrentTime - Frame.Elapsed) / (-Amnt)) + 1; + // // duration is unit of time (timestep) for recordings + // int NumDurations = (NumAmnts * (-Amnt)) / Frame.DurationThis; + // UE_LOG(LogTemp, Log, TEXT("With a duration of %.4f, this'll take %d prevs"), Frame.DurationThis, NumDurations); + // for (size_t i = 0; i < NumDurations; i++) + // { + // PrevPacket(); // go backwards in the file + // } + // UE_LOG(LogTemp, Log, TEXT("Now the time is: %.3f"), Frame.Elapsed); + // // back to negative + // ProcessToTime(Amnt, false); + Stop(true); // stops the replaying while keeping actors (dosen't destroy & respawn) + Restart(); + ProcessToTime(DesiredTime, true); + } } \ No newline at end of file diff --git a/Carla/Recorder/CarlaReplayer.h b/Carla/Recorder/CarlaReplayer.h index 0331b8c..bdf3cc2 100644 --- a/Carla/Recorder/CarlaReplayer.h +++ b/Carla/Recorder/CarlaReplayer.h @@ -1,197 +1,197 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include -#include -#include -#include - -#include -#include "CarlaRecorderInfo.h" -#include "CarlaRecorderFrames.h" -#include "CarlaRecorderEventAdd.h" -#include "CarlaRecorderEventDel.h" -#include "CarlaRecorderEventParent.h" -#include "CarlaRecorderCollision.h" -#include "CarlaRecorderPosition.h" -#include "CarlaRecorderState.h" -#include "CarlaRecorderHelpers.h" -#include "CarlaReplayerHelper.h" - -class UCarlaEpisode; - -class CARLA_API CarlaReplayer -{ - #pragma pack(push, 1) - struct Header - { - char Id; - uint32_t Size; - }; - #pragma pack(pop) - -public: - struct PlayAfterLoadMap - { - bool Enabled; - std::string Filename; - FString Mapfile; - double TimeStart; - double Duration; - uint32_t FollowId; - double TimeFactor; - bool ReplaySensors; - }; - - static PlayAfterLoadMap Autoplay; - - CarlaReplayer() {}; - ~CarlaReplayer() { Stop(); }; - - std::string ReplayFile(std::string Filename, double TimeStart = 0.0f, double Duration = 0.0f, - uint32_t FollowId = 0, bool ReplaySensors = false); - - // void Start(void); - void Stop(bool KeepActors = false); - - void Enable(void); - - void Disable(void); - - bool IsEnabled(void) - { - return Enabled; - } - - // set episode - void SetEpisode(UCarlaEpisode *ThisEpisode) - { - Episode = ThisEpisode; - Helper.SetEpisode(ThisEpisode); - } - - // playback speed (time factor) - void SetTimeFactor(double NewTimeFactor) - { - TimeFactor = NewTimeFactor; - } - - // set ignore hero - void SetIgnoreHero(bool InIgnoreHero) - { - IgnoreHero = InIgnoreHero; - } - - // check if after a map is loaded, we need to replay - void CheckPlayAfterMapLoaded(void); - - // tick for the replayer - void Tick(float Time); - - // DReyeVR replayer functions - void PlayPause() - { - Paused = !Paused; - } - - void Restart(); // calls ReplayFile which is implemented in .cpp - - void Advance(const float Amnt); // long function implemented in .cpp file - - void SetSyncMode(bool bSyncModeIn) - { - bReplaySync = bSyncModeIn; - } - -private: - - bool Enabled; - bool bReplaySensors = false; - bool Paused = false; - UCarlaEpisode *Episode = nullptr; - // binary file reader - std::ifstream File; - Header Header; - CarlaRecorderInfo RecInfo; - CarlaRecorderFrame Frame; - // positions (to be able to interpolate) - std::vector CurrPos; - std::vector PrevPos; - // mapping id - std::unordered_map MappedId; - // times - double CurrentTime; - double TimeToStop; - double TotalTime; - // helper - CarlaReplayerHelper Helper; - // follow camera - uint32_t FollowId; - // speed (time factor) - double TimeFactor { 1.0 }; - // ignore hero vehicles - bool IgnoreHero { false }; - std::unordered_map IsHeroMap; - - // utils - bool ReadHeader(); - - void SkipPacket(); - - double GetTotalTime(void); - - void Rewind(void); - - // processing packets - void ProcessToTime(double Time, bool IsFirstTime = false); - - void ProcessEventsAdd(void); - void ProcessEventsDel(void); - void ProcessEventsParent(void); - - void ProcessPositions(bool IsFirstTime = false); - - void ProcessStates(void); - - void ProcessAnimVehicle(void); - void ProcessAnimWalker(void); - - void ProcessLightVehicle(void); - void ProcessLightScene(void); - - void ProcessWeather(void); - - // DReyeVR recordings - template - void ProcessDReyeVR(double Per, double DeltaTime); - std::unordered_set CustomActorsVisited = {}; - class ADReyeVRSensor *GetEgoSensor(); // (safe) getter for EgoSensor - TWeakObjectPtr EgoSensor; - - // For restarting the recording with the same params - struct LastReplayStruct - { - std::string Filename = "None"; - double TimeStart = 0; - double Duration = 0; - uint32_t ThisFollowId = 0; - }; - LastReplayStruct LastReplay; - - bool bReplaySync = false; - std::vector FrameStartTimes; - size_t SyncCurrentFrameId = 0; - void GetFrameStartTimes(); - void ProcessFrameByFrame(); - - // positions - void UpdatePositions(double Per, double DeltaTime); - - void InterpolatePosition(const CarlaRecorderPosition &Start, const CarlaRecorderPosition &End, double Per, double DeltaTime); -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include +#include +#include + +#include +#include "CarlaRecorderInfo.h" +#include "CarlaRecorderFrames.h" +#include "CarlaRecorderEventAdd.h" +#include "CarlaRecorderEventDel.h" +#include "CarlaRecorderEventParent.h" +#include "CarlaRecorderCollision.h" +#include "CarlaRecorderPosition.h" +#include "CarlaRecorderState.h" +#include "CarlaRecorderHelpers.h" +#include "CarlaReplayerHelper.h" + +class UCarlaEpisode; + +class CARLA_API CarlaReplayer +{ + #pragma pack(push, 1) + struct Header + { + char Id; + uint32_t Size; + }; + #pragma pack(pop) + +public: + struct PlayAfterLoadMap + { + bool Enabled; + std::string Filename; + FString Mapfile; + double TimeStart; + double Duration; + uint32_t FollowId; + double TimeFactor; + bool ReplaySensors; + }; + + static PlayAfterLoadMap Autoplay; + + CarlaReplayer() {}; + ~CarlaReplayer() { Stop(); }; + + std::string ReplayFile(std::string Filename, double TimeStart = 0.0f, double Duration = 0.0f, + uint32_t FollowId = 0, bool ReplaySensors = false); + + // void Start(void); + void Stop(bool KeepActors = false); + + void Enable(void); + + void Disable(void); + + bool IsEnabled(void) + { + return Enabled; + } + + // set episode + void SetEpisode(UCarlaEpisode *ThisEpisode) + { + Episode = ThisEpisode; + Helper.SetEpisode(ThisEpisode); + } + + // playback speed (time factor) + void SetTimeFactor(double NewTimeFactor) + { + TimeFactor = NewTimeFactor; + } + + // set ignore hero + void SetIgnoreHero(bool InIgnoreHero) + { + IgnoreHero = InIgnoreHero; + } + + // check if after a map is loaded, we need to replay + void CheckPlayAfterMapLoaded(void); + + // tick for the replayer + void Tick(float Time); + + // DReyeVR replayer functions + void PlayPause() + { + Paused = !Paused; + } + + void Restart(); // calls ReplayFile which is implemented in .cpp + + void Advance(const float Amnt); // long function implemented in .cpp file + + void SetSyncMode(bool bSyncModeIn) + { + bReplaySync = bSyncModeIn; + } + +private: + + bool Enabled; + bool bReplaySensors = false; + bool Paused = false; + UCarlaEpisode *Episode = nullptr; + // binary file reader + std::ifstream File; + Header Header; + CarlaRecorderInfo RecInfo; + CarlaRecorderFrame Frame; + // positions (to be able to interpolate) + std::vector CurrPos; + std::vector PrevPos; + // mapping id + std::unordered_map MappedId; + // times + double CurrentTime; + double TimeToStop; + double TotalTime; + // helper + CarlaReplayerHelper Helper; + // follow camera + uint32_t FollowId; + // speed (time factor) + double TimeFactor { 1.0 }; + // ignore hero vehicles + bool IgnoreHero { false }; + std::unordered_map IsHeroMap; + + // utils + bool ReadHeader(); + + void SkipPacket(); + + double GetTotalTime(void); + + void Rewind(void); + + // processing packets + void ProcessToTime(double Time, bool IsFirstTime = false); + + void ProcessEventsAdd(void); + void ProcessEventsDel(void); + void ProcessEventsParent(void); + + void ProcessPositions(bool IsFirstTime = false); + + void ProcessStates(void); + + void ProcessAnimVehicle(void); + void ProcessAnimWalker(void); + + void ProcessLightVehicle(void); + void ProcessLightScene(void); + + void ProcessWeather(void); + + // DReyeVR recordings + template + void ProcessDReyeVR(double Per, double DeltaTime); + std::unordered_set CustomActorsVisited = {}; + class ADReyeVRSensor *GetEgoSensor(); // (safe) getter for EgoSensor + TWeakObjectPtr EgoSensor; + + // For restarting the recording with the same params + struct LastReplayStruct + { + std::string Filename = "None"; + double TimeStart = 0; + double Duration = 0; + uint32_t ThisFollowId = 0; + }; + LastReplayStruct LastReplay; + + bool bReplaySync = false; + std::vector FrameStartTimes; + size_t SyncCurrentFrameId = 0; + void GetFrameStartTimes(); + void ProcessFrameByFrame(); + + // positions + void UpdatePositions(double Per, double DeltaTime); + + void InterpolatePosition(const CarlaRecorderPosition &Start, const CarlaRecorderPosition &End, double Per, double DeltaTime); +}; diff --git a/Carla/Recorder/CarlaReplayerHelper.cpp b/Carla/Recorder/CarlaReplayerHelper.cpp index 82afabb..b895c31 100644 --- a/Carla/Recorder/CarlaReplayerHelper.cpp +++ b/Carla/Recorder/CarlaReplayerHelper.cpp @@ -1,534 +1,534 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "Carla.h" -#include "Carla/Recorder/CarlaReplayerHelper.h" - -#include "Carla/Actor/ActorDescription.h" -#include "Carla/Actor/CarlaActor.h" -#include "Carla/Vehicle/WheeledVehicleAIController.h" -#include "Carla/Walker/WalkerControl.h" -#include "Carla/Walker/WalkerController.h" -#include "Carla/Lights/CarlaLight.h" -#include "Carla/Lights/CarlaLightSubsystem.h" -#include "Carla/Actor/ActorSpawnResult.h" -#include "Carla/Game/CarlaEpisode.h" -#include "Carla/Traffic/TrafficSignBase.h" -#include "Carla/Traffic/TrafficLightBase.h" -#include "Carla/Vehicle/CarlaWheeledVehicle.h" -#include "Engine/StaticMeshActor.h" -#include "Carla/Game/CarlaStatics.h" -#include "Carla/MapGen/LargeMapManager.h" -#include "Carla/Weather/Weather.h" - -// DReyeVR include -#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor - -#include -#include -#include - - -#include "EngineUtils.h" - -// create or reuse an actor for replaying -std::pairCarlaReplayerHelper::TryToCreateReplayerActor( - FVector &Location, - FVector &Rotation, - FActorDescription &ActorDesc, - uint32_t DesiredId, - bool SpawnSensors) -{ - check(Episode != nullptr); - - // check type of actor we need - if (ActorDesc.Id.StartsWith("traffic.")) - { - FCarlaActor* CarlaActor = FindTrafficLightAt(Location); - if (CarlaActor != nullptr) - { - // reuse that actor - return std::pair(2, CarlaActor); - } - else - { - // actor not found - UE_LOG(LogCarla, Log, TEXT("TrafficLight not found")); - return std::pair(0, nullptr); - } - } - else if (SpawnSensors || !ActorDesc.Id.StartsWith("sensor.")) - { - // check if an actor of that type already exist with same id - if (Episode->GetActorRegistry().Contains(DesiredId)) - { - auto* CarlaActor = Episode->FindCarlaActor(DesiredId); - const FActorDescription *desc = &CarlaActor->GetActorInfo()->Description; - if (desc->Id == ActorDesc.Id) - { - // we don't need to create, actor of same type already exist - // relocate - FRotator Rot = FRotator::MakeFromEuler(Rotation); - FTransform Trans2(Rot, Location, FVector(1, 1, 1)); - CarlaActor->SetActorGlobalTransform(Trans2); - return std::pair(2, CarlaActor); - } - } - // create the transform - FRotator Rot = FRotator::MakeFromEuler(Rotation); - FTransform Trans(Rot, FVector(0, 0, 100000), FVector(1, 1, 1)); - // create as new actor - TPair Result = Episode->SpawnActorWithInfo(Trans, ActorDesc, DesiredId); - if (Result.Key == EActorSpawnResultStatus::Success) - { - // relocate - FTransform Trans2(Rot, Location, FVector(1, 1, 1)); - Result.Value->SetActorGlobalTransform(Trans2); - ALargeMapManager * LargeMapManager = UCarlaStatics::GetLargeMapManager(Episode->GetWorld()); - if (LargeMapManager) - { - LargeMapManager->OnActorSpawned(*Result.Value); - } - return std::pair(1, Result.Value); - } - else - { - UE_LOG(LogCarla, Log, TEXT("Actor could't be created by replayer")); - return std::pair(0, Result.Value); - } - } - else - { - // actor ignored - return std::pair(0, nullptr); - } -} - -FCarlaActor *CarlaReplayerHelper::FindTrafficLightAt(FVector Location) -{ - check(Episode != nullptr); - auto World = Episode->GetWorld(); - check(World != nullptr); - - // get its position (truncated as int's) - int x = static_cast(Location.X); - int y = static_cast(Location.Y); - int z = static_cast(Location.Z); - - const FActorRegistry &Registry = Episode->GetActorRegistry(); - // through all actors in registry - for (auto It = Registry.begin(); It != Registry.end(); ++It) - { - FCarlaActor* CarlaActor = It.Value().Get(); - if(CarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficLight) - { - FVector vec = CarlaActor->GetActorGlobalLocation(); - int x2 = static_cast(vec.X); - int y2 = static_cast(vec.Y); - int z2 = static_cast(vec.Z); - if ((x2 == x) && (y2 == y) && (z2 == z)) - { - // actor found - return CarlaActor; - } - } - } - // actor not found - return nullptr; -} - -// enable / disable physics for an actor -bool CarlaReplayerHelper::SetActorSimulatePhysics(FCarlaActor* CarlaActor, bool bEnabled) -{ - if (!CarlaActor) - { - return false; - } - ECarlaServerResponse Response = - CarlaActor->SetActorSimulatePhysics(bEnabled); - if (Response != ECarlaServerResponse::Success) - { - return false; - } - return true; -} - -// enable / disable autopilot for an actor -bool CarlaReplayerHelper::SetActorAutopilot(FCarlaActor* CarlaActor, bool bEnabled, bool bKeepState) -{ - if (!CarlaActor) - { - return false; - } - ECarlaServerResponse Response = - CarlaActor->SetActorAutopilot(bEnabled, bKeepState); - if (Response != ECarlaServerResponse::Success) - { - return false; - } - return true; -} - -// replay event for creating actor -std::pair CarlaReplayerHelper::ProcessReplayerEventAdd( - FVector Location, - FVector Rotation, - CarlaRecorderActorDescription Description, - uint32_t DesiredId, - bool bIgnoreHero, - bool ReplaySensors) -{ - check(Episode != nullptr); - FActorDescription ActorDesc; - bool IsHero = false; - - // prepare actor description - ActorDesc.UId = Description.UId; - ActorDesc.Id = Description.Id; - for (const auto &Item : Description.Attributes) - { - FActorAttribute Attr; - Attr.Type = static_cast(Item.Type); - Attr.Id = Item.Id; - Attr.Value = Item.Value; - ActorDesc.Variations.Add(Attr.Id, std::move(Attr)); - // check for hero - if (Item.Id == "role_name" && Item.Value == "hero") - IsHero = true; - } - - auto result = TryToCreateReplayerActor( - Location, - Rotation, - ActorDesc, - DesiredId, - ReplaySensors); - - if (result.first != 0) - { - // disable physics and autopilot on vehicles - if (result.second->GetActorType() == FCarlaActor::ActorType::Vehicle) - { - // ignore hero ? - if (!(bIgnoreHero && IsHero)) - { - // disable physics - SetActorSimulatePhysics(result.second, false); - // disable autopilot - SetActorAutopilot(result.second, false, false); - } - else - { - // reenable physics just in case - SetActorSimulatePhysics(result.second, true); - } - } - return std::make_pair(result.first, result.second->GetActorId()); - } - return std::make_pair(result.first, 0); -} - -// replay event for removing actor -bool CarlaReplayerHelper::ProcessReplayerEventDel(uint32_t DatabaseId) -{ - check(Episode != nullptr); - FCarlaActor* CarlaActor = Episode->FindCarlaActor(DatabaseId); - if (CarlaActor == nullptr) - { - UE_LOG(LogCarla, Log, TEXT("Actor %d not found to destroy"), DatabaseId); - return false; - } - Episode->DestroyActor(CarlaActor->GetActorId()); - return true; -} - -// replay event for parenting actors -bool CarlaReplayerHelper::ProcessReplayerEventParent(uint32_t ChildId, uint32_t ParentId) -{ - check(Episode != nullptr); - FCarlaActor * Child = Episode->FindCarlaActor(ChildId); - FCarlaActor * Parent = Episode->FindCarlaActor(ParentId); - if(!Child) - { - UE_LOG(LogCarla, Log, TEXT("Parenting Child actors not found")); - return false; - } - if(!Parent) - { - UE_LOG(LogCarla, Log, TEXT("Parenting Parent actors not found")); - return false; - } - Child->SetParent(ParentId); - Child->SetAttachmentType(carla::rpc::AttachmentType::Rigid); - Parent->AddChildren(Child->GetActorId()); - if(!Parent->IsDormant()) - { - if(!Child->IsDormant()) - { - Episode->AttachActors( - Child->GetActor(), - Parent->GetActor(), - static_cast(carla::rpc::AttachmentType::Rigid)); - } - } - else - { - Episode->PutActorToSleep(Child->GetActorId()); - } - return true; -} - -// reposition actors -bool CarlaReplayerHelper::ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime) -{ - check(Episode != nullptr); - FCarlaActor* CarlaActor = Episode->FindCarlaActor(Pos1.DatabaseId); - FVector Location; - FRotator Rotation; - if(CarlaActor) - { - // check to assign first position or interpolate between both - if (Per == 0.0) - { - // assign position 1 - Location = FVector(Pos1.Location); - Rotation = FRotator::MakeFromEuler(Pos1.Rotation); - } - else - { - // interpolate positions - Location = FMath::Lerp(FVector(Pos1.Location), FVector(Pos2.Location), Per); - Rotation = FMath::Lerp(FRotator::MakeFromEuler(Pos1.Rotation), FRotator::MakeFromEuler(Pos2.Rotation), Per); - } - // set new transform - FTransform Trans(Rotation, Location, FVector(1, 1, 1)); - - if (CarlaActor->GetActorInfo()->Description.Id.StartsWith("harplab.dreyevr_vehicle.")) - { - // our DReyeVR vehicle does not get applied its transform here but rather in its ReplayTick() - // method so that everything that the EgoVehicle ticks can be synchronized (e.x. camera position, wheels, etc.) - return true; - } - - CarlaActor->SetActorGlobalTransform(Trans, ETeleportType::None); - return true; - } - return false; -} - -// reposition the camera -bool CarlaReplayerHelper::SetCameraPosition(uint32_t Id, FVector Offset, FQuat Rotation) -{ - check(Episode != nullptr); - - // get the actor to follow - FCarlaActor* CarlaActor = Episode->FindCarlaActor(Id); - if (!CarlaActor) - return false; - // get specator pawn - APawn *Spectator = Episode->GetSpectatorPawn(); - if (!Spectator) - return false; - - FCarlaActor* CarlaSpectator = Episode->FindCarlaActor(Spectator); - if (!CarlaSpectator) - return false; - - FTransform ActorTransform = CarlaActor->GetActorGlobalTransform(); - // set the new position - FQuat ActorRot = ActorTransform.GetRotation(); - FVector Pos = ActorTransform.GetTranslation() + (ActorRot.RotateVector(Offset)); - CarlaSpectator->SetActorGlobalTransform(FTransform(ActorRot * Rotation, Pos, FVector(1,1,1))); - - return true; -} - -bool CarlaReplayerHelper::ProcessReplayerStateTrafficLight(CarlaRecorderStateTrafficLight State) -{ - check(Episode != nullptr); - FCarlaActor* CarlaActor = Episode->FindCarlaActor(State.DatabaseId); - if(CarlaActor) - { - CarlaActor->SetTrafficLightState(static_cast(State.State)); - UTrafficLightController* Controller = CarlaActor->GetTrafficLightController(); - if(Controller) - { - Controller->SetElapsedTime(State.ElapsedTime); - ATrafficLightGroup* Group = Controller->GetGroup(); - if (Group) - { - Group->SetFrozenGroup(State.IsFrozen); - } - } - return true; - } - return false; -} - -// set the animation for Vehicles -void CarlaReplayerHelper::ProcessReplayerAnimVehicle(CarlaRecorderAnimVehicle Vehicle) -{ - check(Episode != nullptr); - FCarlaActor *CarlaActor = Episode->FindCarlaActor(Vehicle.DatabaseId); - if (CarlaActor) - { - FVehicleControl Control; - Control.Throttle = Vehicle.Throttle; - Control.Steer = Vehicle.Steering; - Control.Brake = Vehicle.Brake; - Control.bHandBrake = Vehicle.bHandbrake; - Control.bReverse = (Vehicle.Gear < 0); - Control.Gear = Vehicle.Gear; - Control.bManualGearShift = false; - CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); - } -} - -// set the lights for vehicles -void CarlaReplayerHelper::ProcessReplayerLightVehicle(CarlaRecorderLightVehicle LightVehicle) -{ - check(Episode != nullptr); - FCarlaActor * CarlaActor = Episode->FindCarlaActor(LightVehicle.DatabaseId); - if (CarlaActor) - { - carla::rpc::VehicleLightState LightState(LightVehicle.State); - CarlaActor->SetVehicleLightState(FVehicleLightState(LightState)); - } -} - -void CarlaReplayerHelper::ProcessReplayerLightScene(CarlaRecorderLightScene LightScene) -{ - check(Episode != nullptr); - UWorld* World = Episode->GetWorld(); - if(World) - { - UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem(); - if (!CarlaLightSubsystem) - { - return; - } - auto* CarlaLight = CarlaLightSubsystem->GetLight(LightScene.LightId); - if (CarlaLight) - { - CarlaLight->SetLightIntensity(LightScene.Intensity); - CarlaLight->SetLightColor(LightScene.Color); - CarlaLight->SetLightOn(LightScene.bOn); - CarlaLight->SetLightType(static_cast(LightScene.Type)); - } - } -} - -void CarlaReplayerHelper::ProcessReplayerWeather(const CarlaRecorderWeather &RecordedWeather) -{ - check(Episode != nullptr); - AWeather *Weather = AWeather::FindWeatherInstance(Episode->GetWorld()); - if (Weather) - { - Weather->ApplyWeather(RecordedWeather.Params); - } -} - -// set the animation for walkers -void CarlaReplayerHelper::ProcessReplayerAnimWalker(CarlaRecorderAnimWalker Walker) -{ - SetWalkerSpeed(Walker.DatabaseId, Walker.Speed); -} - -// replay finish -bool CarlaReplayerHelper::ProcessReplayerFinish(bool bApplyAutopilot, bool bIgnoreHero, std::unordered_map &IsHero) -{ - // set autopilot and physics to all AI vehicles - const FActorRegistry& Registry = Episode->GetActorRegistry(); - for (auto& It : Registry) - { - FCarlaActor* CarlaActor = It.Value.Get(); - - // enable physics only on vehicles - switch (CarlaActor->GetActorType()) - { - - // vehicles - case FCarlaActor::ActorType::Vehicle: - // check for hero - if (!(bIgnoreHero && IsHero[CarlaActor->GetActorId()])) - { - // stop all vehicles - SetActorSimulatePhysics(CarlaActor, true); - SetActorVelocity(CarlaActor, FVector(0, 0, 0)); - FVehicleControl Control; - Control.Throttle = 0.0f; - Control.Steer = 0.0f; - Control.Brake = 0.0f; - Control.bHandBrake = false; - Control.bReverse = false; - Control.Gear = 1; - Control.bManualGearShift = false; - CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); - } - break; - - // walkers - case FCarlaActor::ActorType::Walker: - // stop walker - SetWalkerSpeed(CarlaActor->GetActorId(), 0.0f); - break; - } - } - return true; -} - -template -void CarlaReplayerHelper::ProcessReplayerDReyeVR(ADReyeVRSensor *EgoSensor, const T &Data, const double Per) -{ - if (EgoSensor == nullptr) { // try getting and assigning the new EgoSensor - EgoSensor = ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld()); - } - if (EgoSensor == nullptr) { // still null?? throw an error - DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); - return; - } - EgoSensor->UpdateData(Data, Per); -} - -void CarlaReplayerHelper::SetActorVelocity(FCarlaActor *CarlaActor, FVector Velocity) -{ - if (!CarlaActor) - { - return; - } - CarlaActor->SetActorTargetVelocity(Velocity); -} - -// set the animation speed for walkers -void CarlaReplayerHelper::SetWalkerSpeed(uint32_t ActorId, float Speed) -{ - check(Episode != nullptr); - FCarlaActor * CarlaActor = Episode->FindCarlaActor(ActorId); - if (!CarlaActor) - { - return; - } - FWalkerControl Control; - Control.Speed = Speed; - CarlaActor->ApplyControlToWalker(Control); -} - -void CarlaReplayerHelper::RemoveStaticProps() -{ - check(Episode != nullptr); - auto World = Episode->GetWorld(); - for (TActorIterator It(World); It; ++It) - { - auto Actor = *It; - check(Actor != nullptr); - auto MeshComponent = Actor->GetStaticMeshComponent(); - check(MeshComponent != nullptr); - if (MeshComponent->Mobility == EComponentMobility::Movable) - { - Actor->Destroy(); - } - } -} +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Carla.h" +#include "Carla/Recorder/CarlaReplayerHelper.h" + +#include "Carla/Actor/ActorDescription.h" +#include "Carla/Actor/CarlaActor.h" +#include "Carla/Vehicle/WheeledVehicleAIController.h" +#include "Carla/Walker/WalkerControl.h" +#include "Carla/Walker/WalkerController.h" +#include "Carla/Lights/CarlaLight.h" +#include "Carla/Lights/CarlaLightSubsystem.h" +#include "Carla/Actor/ActorSpawnResult.h" +#include "Carla/Game/CarlaEpisode.h" +#include "Carla/Traffic/TrafficSignBase.h" +#include "Carla/Traffic/TrafficLightBase.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include "Engine/StaticMeshActor.h" +#include "Carla/Game/CarlaStatics.h" +#include "Carla/MapGen/LargeMapManager.h" +#include "Carla/Weather/Weather.h" + +// DReyeVR include +#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor + +#include +#include +#include + + +#include "EngineUtils.h" + +// create or reuse an actor for replaying +std::pairCarlaReplayerHelper::TryToCreateReplayerActor( + FVector &Location, + FVector &Rotation, + FActorDescription &ActorDesc, + uint32_t DesiredId, + bool SpawnSensors) +{ + check(Episode != nullptr); + + // check type of actor we need + if (ActorDesc.Id.StartsWith("traffic.")) + { + FCarlaActor* CarlaActor = FindTrafficLightAt(Location); + if (CarlaActor != nullptr) + { + // reuse that actor + return std::pair(2, CarlaActor); + } + else + { + // actor not found + UE_LOG(LogCarla, Log, TEXT("TrafficLight not found")); + return std::pair(0, nullptr); + } + } + else if (SpawnSensors || !ActorDesc.Id.StartsWith("sensor.")) + { + // check if an actor of that type already exist with same id + if (Episode->GetActorRegistry().Contains(DesiredId)) + { + auto* CarlaActor = Episode->FindCarlaActor(DesiredId); + const FActorDescription *desc = &CarlaActor->GetActorInfo()->Description; + if (desc->Id == ActorDesc.Id) + { + // we don't need to create, actor of same type already exist + // relocate + FRotator Rot = FRotator::MakeFromEuler(Rotation); + FTransform Trans2(Rot, Location, FVector(1, 1, 1)); + CarlaActor->SetActorGlobalTransform(Trans2); + return std::pair(2, CarlaActor); + } + } + // create the transform + FRotator Rot = FRotator::MakeFromEuler(Rotation); + FTransform Trans(Rot, FVector(0, 0, 100000), FVector(1, 1, 1)); + // create as new actor + TPair Result = Episode->SpawnActorWithInfo(Trans, ActorDesc, DesiredId); + if (Result.Key == EActorSpawnResultStatus::Success) + { + // relocate + FTransform Trans2(Rot, Location, FVector(1, 1, 1)); + Result.Value->SetActorGlobalTransform(Trans2); + ALargeMapManager * LargeMapManager = UCarlaStatics::GetLargeMapManager(Episode->GetWorld()); + if (LargeMapManager) + { + LargeMapManager->OnActorSpawned(*Result.Value); + } + return std::pair(1, Result.Value); + } + else + { + UE_LOG(LogCarla, Log, TEXT("Actor could't be created by replayer")); + return std::pair(0, Result.Value); + } + } + else + { + // actor ignored + return std::pair(0, nullptr); + } +} + +FCarlaActor *CarlaReplayerHelper::FindTrafficLightAt(FVector Location) +{ + check(Episode != nullptr); + auto World = Episode->GetWorld(); + check(World != nullptr); + + // get its position (truncated as int's) + int x = static_cast(Location.X); + int y = static_cast(Location.Y); + int z = static_cast(Location.Z); + + const FActorRegistry &Registry = Episode->GetActorRegistry(); + // through all actors in registry + for (auto It = Registry.begin(); It != Registry.end(); ++It) + { + FCarlaActor* CarlaActor = It.Value().Get(); + if(CarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficLight) + { + FVector vec = CarlaActor->GetActorGlobalLocation(); + int x2 = static_cast(vec.X); + int y2 = static_cast(vec.Y); + int z2 = static_cast(vec.Z); + if ((x2 == x) && (y2 == y) && (z2 == z)) + { + // actor found + return CarlaActor; + } + } + } + // actor not found + return nullptr; +} + +// enable / disable physics for an actor +bool CarlaReplayerHelper::SetActorSimulatePhysics(FCarlaActor* CarlaActor, bool bEnabled) +{ + if (!CarlaActor) + { + return false; + } + ECarlaServerResponse Response = + CarlaActor->SetActorSimulatePhysics(bEnabled); + if (Response != ECarlaServerResponse::Success) + { + return false; + } + return true; +} + +// enable / disable autopilot for an actor +bool CarlaReplayerHelper::SetActorAutopilot(FCarlaActor* CarlaActor, bool bEnabled, bool bKeepState) +{ + if (!CarlaActor) + { + return false; + } + ECarlaServerResponse Response = + CarlaActor->SetActorAutopilot(bEnabled, bKeepState); + if (Response != ECarlaServerResponse::Success) + { + return false; + } + return true; +} + +// replay event for creating actor +std::pair CarlaReplayerHelper::ProcessReplayerEventAdd( + FVector Location, + FVector Rotation, + CarlaRecorderActorDescription Description, + uint32_t DesiredId, + bool bIgnoreHero, + bool ReplaySensors) +{ + check(Episode != nullptr); + FActorDescription ActorDesc; + bool IsHero = false; + + // prepare actor description + ActorDesc.UId = Description.UId; + ActorDesc.Id = Description.Id; + for (const auto &Item : Description.Attributes) + { + FActorAttribute Attr; + Attr.Type = static_cast(Item.Type); + Attr.Id = Item.Id; + Attr.Value = Item.Value; + ActorDesc.Variations.Add(Attr.Id, std::move(Attr)); + // check for hero + if (Item.Id == "role_name" && Item.Value == "hero") + IsHero = true; + } + + auto result = TryToCreateReplayerActor( + Location, + Rotation, + ActorDesc, + DesiredId, + ReplaySensors); + + if (result.first != 0) + { + // disable physics and autopilot on vehicles + if (result.second->GetActorType() == FCarlaActor::ActorType::Vehicle) + { + // ignore hero ? + if (!(bIgnoreHero && IsHero)) + { + // disable physics + SetActorSimulatePhysics(result.second, false); + // disable autopilot + SetActorAutopilot(result.second, false, false); + } + else + { + // reenable physics just in case + SetActorSimulatePhysics(result.second, true); + } + } + return std::make_pair(result.first, result.second->GetActorId()); + } + return std::make_pair(result.first, 0); +} + +// replay event for removing actor +bool CarlaReplayerHelper::ProcessReplayerEventDel(uint32_t DatabaseId) +{ + check(Episode != nullptr); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(DatabaseId); + if (CarlaActor == nullptr) + { + UE_LOG(LogCarla, Log, TEXT("Actor %d not found to destroy"), DatabaseId); + return false; + } + Episode->DestroyActor(CarlaActor->GetActorId()); + return true; +} + +// replay event for parenting actors +bool CarlaReplayerHelper::ProcessReplayerEventParent(uint32_t ChildId, uint32_t ParentId) +{ + check(Episode != nullptr); + FCarlaActor * Child = Episode->FindCarlaActor(ChildId); + FCarlaActor * Parent = Episode->FindCarlaActor(ParentId); + if(!Child) + { + UE_LOG(LogCarla, Log, TEXT("Parenting Child actors not found")); + return false; + } + if(!Parent) + { + UE_LOG(LogCarla, Log, TEXT("Parenting Parent actors not found")); + return false; + } + Child->SetParent(ParentId); + Child->SetAttachmentType(carla::rpc::AttachmentType::Rigid); + Parent->AddChildren(Child->GetActorId()); + if(!Parent->IsDormant()) + { + if(!Child->IsDormant()) + { + Episode->AttachActors( + Child->GetActor(), + Parent->GetActor(), + static_cast(carla::rpc::AttachmentType::Rigid)); + } + } + else + { + Episode->PutActorToSleep(Child->GetActorId()); + } + return true; +} + +// reposition actors +bool CarlaReplayerHelper::ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime) +{ + check(Episode != nullptr); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(Pos1.DatabaseId); + FVector Location; + FRotator Rotation; + if(CarlaActor) + { + // check to assign first position or interpolate between both + if (Per == 0.0) + { + // assign position 1 + Location = FVector(Pos1.Location); + Rotation = FRotator::MakeFromEuler(Pos1.Rotation); + } + else + { + // interpolate positions + Location = FMath::Lerp(FVector(Pos1.Location), FVector(Pos2.Location), Per); + Rotation = FMath::Lerp(FRotator::MakeFromEuler(Pos1.Rotation), FRotator::MakeFromEuler(Pos2.Rotation), Per); + } + // set new transform + FTransform Trans(Rotation, Location, FVector(1, 1, 1)); + + if (CarlaActor->GetActorInfo()->Description.Id.StartsWith("harplab.dreyevr_vehicle.")) + { + // our DReyeVR vehicle does not get applied its transform here but rather in its ReplayTick() + // method so that everything that the EgoVehicle ticks can be synchronized (e.x. camera position, wheels, etc.) + return true; + } + + CarlaActor->SetActorGlobalTransform(Trans, ETeleportType::None); + return true; + } + return false; +} + +// reposition the camera +bool CarlaReplayerHelper::SetCameraPosition(uint32_t Id, FVector Offset, FQuat Rotation) +{ + check(Episode != nullptr); + + // get the actor to follow + FCarlaActor* CarlaActor = Episode->FindCarlaActor(Id); + if (!CarlaActor) + return false; + // get specator pawn + APawn *Spectator = Episode->GetSpectatorPawn(); + if (!Spectator) + return false; + + FCarlaActor* CarlaSpectator = Episode->FindCarlaActor(Spectator); + if (!CarlaSpectator) + return false; + + FTransform ActorTransform = CarlaActor->GetActorGlobalTransform(); + // set the new position + FQuat ActorRot = ActorTransform.GetRotation(); + FVector Pos = ActorTransform.GetTranslation() + (ActorRot.RotateVector(Offset)); + CarlaSpectator->SetActorGlobalTransform(FTransform(ActorRot * Rotation, Pos, FVector(1,1,1))); + + return true; +} + +bool CarlaReplayerHelper::ProcessReplayerStateTrafficLight(CarlaRecorderStateTrafficLight State) +{ + check(Episode != nullptr); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(State.DatabaseId); + if(CarlaActor) + { + CarlaActor->SetTrafficLightState(static_cast(State.State)); + UTrafficLightController* Controller = CarlaActor->GetTrafficLightController(); + if(Controller) + { + Controller->SetElapsedTime(State.ElapsedTime); + ATrafficLightGroup* Group = Controller->GetGroup(); + if (Group) + { + Group->SetFrozenGroup(State.IsFrozen); + } + } + return true; + } + return false; +} + +// set the animation for Vehicles +void CarlaReplayerHelper::ProcessReplayerAnimVehicle(CarlaRecorderAnimVehicle Vehicle) +{ + check(Episode != nullptr); + FCarlaActor *CarlaActor = Episode->FindCarlaActor(Vehicle.DatabaseId); + if (CarlaActor) + { + FVehicleControl Control; + Control.Throttle = Vehicle.Throttle; + Control.Steer = Vehicle.Steering; + Control.Brake = Vehicle.Brake; + Control.bHandBrake = Vehicle.bHandbrake; + Control.bReverse = (Vehicle.Gear < 0); + Control.Gear = Vehicle.Gear; + Control.bManualGearShift = false; + CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); + } +} + +// set the lights for vehicles +void CarlaReplayerHelper::ProcessReplayerLightVehicle(CarlaRecorderLightVehicle LightVehicle) +{ + check(Episode != nullptr); + FCarlaActor * CarlaActor = Episode->FindCarlaActor(LightVehicle.DatabaseId); + if (CarlaActor) + { + carla::rpc::VehicleLightState LightState(LightVehicle.State); + CarlaActor->SetVehicleLightState(FVehicleLightState(LightState)); + } +} + +void CarlaReplayerHelper::ProcessReplayerLightScene(CarlaRecorderLightScene LightScene) +{ + check(Episode != nullptr); + UWorld* World = Episode->GetWorld(); + if(World) + { + UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem(); + if (!CarlaLightSubsystem) + { + return; + } + auto* CarlaLight = CarlaLightSubsystem->GetLight(LightScene.LightId); + if (CarlaLight) + { + CarlaLight->SetLightIntensity(LightScene.Intensity); + CarlaLight->SetLightColor(LightScene.Color); + CarlaLight->SetLightOn(LightScene.bOn); + CarlaLight->SetLightType(static_cast(LightScene.Type)); + } + } +} + +void CarlaReplayerHelper::ProcessReplayerWeather(const CarlaRecorderWeather &RecordedWeather) +{ + check(Episode != nullptr); + AWeather *Weather = AWeather::FindWeatherInstance(Episode->GetWorld()); + if (Weather) + { + Weather->ApplyWeather(RecordedWeather.Params); + } +} + +// set the animation for walkers +void CarlaReplayerHelper::ProcessReplayerAnimWalker(CarlaRecorderAnimWalker Walker) +{ + SetWalkerSpeed(Walker.DatabaseId, Walker.Speed); +} + +// replay finish +bool CarlaReplayerHelper::ProcessReplayerFinish(bool bApplyAutopilot, bool bIgnoreHero, std::unordered_map &IsHero) +{ + // set autopilot and physics to all AI vehicles + const FActorRegistry& Registry = Episode->GetActorRegistry(); + for (auto& It : Registry) + { + FCarlaActor* CarlaActor = It.Value.Get(); + + // enable physics only on vehicles + switch (CarlaActor->GetActorType()) + { + + // vehicles + case FCarlaActor::ActorType::Vehicle: + // check for hero + if (!(bIgnoreHero && IsHero[CarlaActor->GetActorId()])) + { + // stop all vehicles + SetActorSimulatePhysics(CarlaActor, true); + SetActorVelocity(CarlaActor, FVector(0, 0, 0)); + FVehicleControl Control; + Control.Throttle = 0.0f; + Control.Steer = 0.0f; + Control.Brake = 0.0f; + Control.bHandBrake = false; + Control.bReverse = false; + Control.Gear = 1; + Control.bManualGearShift = false; + CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); + } + break; + + // walkers + case FCarlaActor::ActorType::Walker: + // stop walker + SetWalkerSpeed(CarlaActor->GetActorId(), 0.0f); + break; + } + } + return true; +} + +template +void CarlaReplayerHelper::ProcessReplayerDReyeVR(ADReyeVRSensor *EgoSensor, const T &Data, const double Per) +{ + if (EgoSensor == nullptr) { // try getting and assigning the new EgoSensor + EgoSensor = ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld()); + } + if (EgoSensor == nullptr) { // still null?? throw an error + DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); + return; + } + EgoSensor->UpdateData(Data, Per); +} + +void CarlaReplayerHelper::SetActorVelocity(FCarlaActor *CarlaActor, FVector Velocity) +{ + if (!CarlaActor) + { + return; + } + CarlaActor->SetActorTargetVelocity(Velocity); +} + +// set the animation speed for walkers +void CarlaReplayerHelper::SetWalkerSpeed(uint32_t ActorId, float Speed) +{ + check(Episode != nullptr); + FCarlaActor * CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return; + } + FWalkerControl Control; + Control.Speed = Speed; + CarlaActor->ApplyControlToWalker(Control); +} + +void CarlaReplayerHelper::RemoveStaticProps() +{ + check(Episode != nullptr); + auto World = Episode->GetWorld(); + for (TActorIterator It(World); It; ++It) + { + auto Actor = *It; + check(Actor != nullptr); + auto MeshComponent = Actor->GetStaticMeshComponent(); + check(MeshComponent != nullptr); + if (MeshComponent->Mobility == EComponentMobility::Movable) + { + Actor->Destroy(); + } + } +} diff --git a/Carla/Recorder/CarlaReplayerHelper.h b/Carla/Recorder/CarlaReplayerHelper.h index b4695f4..4cd2d96 100644 --- a/Carla/Recorder/CarlaReplayerHelper.h +++ b/Carla/Recorder/CarlaReplayerHelper.h @@ -1,110 +1,110 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "CarlaRecorderEventAdd.h" -#include "CarlaRecorderPosition.h" -#include "CarlaRecorderState.h" -#include "CarlaRecorderAnimWalker.h" -#include "CarlaRecorderAnimVehicle.h" -#include "CarlaRecorderLightVehicle.h" -#include "CarlaRecorderLightScene.h" -#include "CarlaRecorderWeather.h" - -// DReyeVR includes -#include "DReyeVRRecorder.h" - -#include - -class UCarlaEpisode; -class FCarlaActor; -struct FActorDescription; -class ADReyeVRSensor; // fwd for DReyeVR (avoid header conflict) - -class CarlaReplayerHelper -{ - -public: - - // set the episode to use - void SetEpisode(UCarlaEpisode *ThisEpisode) - { - Episode = ThisEpisode; - } - - // replay event for creating actor - std::pair ProcessReplayerEventAdd( - FVector Location, - FVector Rotation, - CarlaRecorderActorDescription Description, - uint32_t DesiredId, - bool bIgnoreHero, - bool ReplaySensors); - - // replay event for removing actor - bool ProcessReplayerEventDel(uint32_t DatabaseId); - - // replay event for parenting actors - bool ProcessReplayerEventParent(uint32_t ChildId, uint32_t ParentId); - - // reposition actors - bool ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime); - - // replay event for traffic light state - bool ProcessReplayerStateTrafficLight(CarlaRecorderStateTrafficLight State); - - // set the animation for Vehicles - void ProcessReplayerAnimVehicle(CarlaRecorderAnimVehicle Vehicle); - - // set the animation for walkers - void ProcessReplayerAnimWalker(CarlaRecorderAnimWalker Walker); - - // set the vehicle light - void ProcessReplayerLightVehicle(CarlaRecorderLightVehicle LightVehicle); - - // set scene lights - void ProcessReplayerLightScene(CarlaRecorderLightScene LightScene); - - // set weather - void ProcessReplayerWeather(const CarlaRecorderWeather &RecordedWeather); - - // replay finish - bool ProcessReplayerFinish(bool bApplyAutopilot, bool bIgnoreHero, std::unordered_map &IsHero); - - // update the DReyeVR ego sensor and custom types - template - void ProcessReplayerDReyeVR(ADReyeVRSensor *EgoSensor, const T &Data, const double Per); - - // set the camera position to follow an actor - bool SetCameraPosition(uint32_t Id, FVector Offset, FQuat Rotation); - - // set the velocity of the actor - void SetActorVelocity(FCarlaActor *CarlaActor, FVector Velocity); - - // set the animation speed for walkers - void SetWalkerSpeed(uint32_t ActorId, float Speed); - - void RemoveStaticProps(); - -private: - - UCarlaEpisode *Episode {nullptr}; - - std::pairTryToCreateReplayerActor( - FVector &Location, - FVector &Rotation, - FActorDescription &ActorDesc, - uint32_t DesiredId, - bool SpawnSensors); - - FCarlaActor* FindTrafficLightAt(FVector Location); - - // enable / disable physics for an actor - bool SetActorSimulatePhysics(FCarlaActor *CarlaActor, bool bEnabled); - // enable / disable autopilot for an actor - bool SetActorAutopilot(FCarlaActor *CarlaActor, bool bEnabled, bool bKeepState = false); -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "CarlaRecorderEventAdd.h" +#include "CarlaRecorderPosition.h" +#include "CarlaRecorderState.h" +#include "CarlaRecorderAnimWalker.h" +#include "CarlaRecorderAnimVehicle.h" +#include "CarlaRecorderLightVehicle.h" +#include "CarlaRecorderLightScene.h" +#include "CarlaRecorderWeather.h" + +// DReyeVR includes +#include "DReyeVRRecorder.h" + +#include + +class UCarlaEpisode; +class FCarlaActor; +struct FActorDescription; +class ADReyeVRSensor; // fwd for DReyeVR (avoid header conflict) + +class CarlaReplayerHelper +{ + +public: + + // set the episode to use + void SetEpisode(UCarlaEpisode *ThisEpisode) + { + Episode = ThisEpisode; + } + + // replay event for creating actor + std::pair ProcessReplayerEventAdd( + FVector Location, + FVector Rotation, + CarlaRecorderActorDescription Description, + uint32_t DesiredId, + bool bIgnoreHero, + bool ReplaySensors); + + // replay event for removing actor + bool ProcessReplayerEventDel(uint32_t DatabaseId); + + // replay event for parenting actors + bool ProcessReplayerEventParent(uint32_t ChildId, uint32_t ParentId); + + // reposition actors + bool ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime); + + // replay event for traffic light state + bool ProcessReplayerStateTrafficLight(CarlaRecorderStateTrafficLight State); + + // set the animation for Vehicles + void ProcessReplayerAnimVehicle(CarlaRecorderAnimVehicle Vehicle); + + // set the animation for walkers + void ProcessReplayerAnimWalker(CarlaRecorderAnimWalker Walker); + + // set the vehicle light + void ProcessReplayerLightVehicle(CarlaRecorderLightVehicle LightVehicle); + + // set scene lights + void ProcessReplayerLightScene(CarlaRecorderLightScene LightScene); + + // set weather + void ProcessReplayerWeather(const CarlaRecorderWeather &RecordedWeather); + + // replay finish + bool ProcessReplayerFinish(bool bApplyAutopilot, bool bIgnoreHero, std::unordered_map &IsHero); + + // update the DReyeVR ego sensor and custom types + template + void ProcessReplayerDReyeVR(ADReyeVRSensor *EgoSensor, const T &Data, const double Per); + + // set the camera position to follow an actor + bool SetCameraPosition(uint32_t Id, FVector Offset, FQuat Rotation); + + // set the velocity of the actor + void SetActorVelocity(FCarlaActor *CarlaActor, FVector Velocity); + + // set the animation speed for walkers + void SetWalkerSpeed(uint32_t ActorId, float Speed); + + void RemoveStaticProps(); + +private: + + UCarlaEpisode *Episode {nullptr}; + + std::pairTryToCreateReplayerActor( + FVector &Location, + FVector &Rotation, + FActorDescription &ActorDesc, + uint32_t DesiredId, + bool SpawnSensors); + + FCarlaActor* FindTrafficLightAt(FVector Location); + + // enable / disable physics for an actor + bool SetActorSimulatePhysics(FCarlaActor *CarlaActor, bool bEnabled); + // enable / disable autopilot for an actor + bool SetActorAutopilot(FCarlaActor *CarlaActor, bool bEnabled, bool bKeepState = false); +}; diff --git a/Carla/Recorder/DReyeVRRecorder.h b/Carla/Recorder/DReyeVRRecorder.h index 0328c37..9cff757 100644 --- a/Carla/Recorder/DReyeVRRecorder.h +++ b/Carla/Recorder/DReyeVRRecorder.h @@ -1,81 +1,81 @@ -#pragma once - -#include -#include -// DReyeVR include -#include "Carla/Sensor/DReyeVRData.h" - -// custom DReyeVR recorder data type for sensor recordings and custom actors - -#pragma pack(push, 1) -template struct DReyeVRDataRecorder -{ - DReyeVRDataRecorder() = default; - DReyeVRDataRecorder(const T *DataIn) - { - Data = (*DataIn); - } - T Data; - void Read(std::ifstream &InFile) - { - Data.Read(InFile); - } - void Write(std::ofstream &OutFile) const - { - Data.Write(OutFile); - } - std::string GetUniqueName() const - { - return Data.GetUniqueName(); - } - std::string Print() const - { - std::ostringstream oss; - oss << TCHAR_TO_UTF8(*Data.ToString()); - return oss.str(); - } -}; -#pragma pack(pop) - -template class DReyeVRDataRecorders -{ - - public: - void Add(const DReyeVRDataRecorder &NewData) - { - AllData.push_back(NewData); - } - void Clear(void) - { - AllData.clear(); - } - void Write(std::ofstream &OutFile) - { - // write the packet id - WriteValue(OutFile, static_cast(PacketId)); - std::streampos PosStart = OutFile.tellp(); - - // write a dummy packet size - uint32_t Total = 0; - WriteValue(OutFile, Total); - - // write total records - Total = AllData.size(); - WriteValue(OutFile, Total); - - for (auto &Snapshot : AllData) - Snapshot.Write(OutFile); - - // write the real packet size - std::streampos PosEnd = OutFile.tellp(); - Total = PosEnd - PosStart - sizeof(uint32_t); - OutFile.seekp(PosStart, std::ios::beg); - WriteValue(OutFile, Total); - OutFile.seekp(PosEnd, std::ios::beg); - } - - private: - // using a vector as a queue that holds everything, gets written and flushed on every tick - std::vector> AllData; - uint8_t PacketId = N; -}; +#pragma once + +#include +#include +// DReyeVR include +#include "Carla/Sensor/DReyeVRData.h" + +// custom DReyeVR recorder data type for sensor recordings and custom actors + +#pragma pack(push, 1) +template struct DReyeVRDataRecorder +{ + DReyeVRDataRecorder() = default; + DReyeVRDataRecorder(const T *DataIn) + { + Data = (*DataIn); + } + T Data; + void Read(std::ifstream &InFile) + { + Data.Read(InFile); + } + void Write(std::ofstream &OutFile) const + { + Data.Write(OutFile); + } + std::string GetUniqueName() const + { + return Data.GetUniqueName(); + } + std::string Print() const + { + std::ostringstream oss; + oss << TCHAR_TO_UTF8(*Data.ToString()); + return oss.str(); + } +}; +#pragma pack(pop) + +template class DReyeVRDataRecorders +{ + + public: + void Add(const DReyeVRDataRecorder &NewData) + { + AllData.push_back(NewData); + } + void Clear(void) + { + AllData.clear(); + } + void Write(std::ofstream &OutFile) + { + // write the packet id + WriteValue(OutFile, static_cast(PacketId)); + std::streampos PosStart = OutFile.tellp(); + + // write a dummy packet size + uint32_t Total = 0; + WriteValue(OutFile, Total); + + // write total records + Total = AllData.size(); + WriteValue(OutFile, Total); + + for (auto &Snapshot : AllData) + Snapshot.Write(OutFile); + + // write the real packet size + std::streampos PosEnd = OutFile.tellp(); + Total = PosEnd - PosStart - sizeof(uint32_t); + OutFile.seekp(PosStart, std::ios::beg); + WriteValue(OutFile, Total); + OutFile.seekp(PosEnd, std::ios::beg); + } + + private: + // using a vector as a queue that holds everything, gets written and flushed on every tick + std::vector> AllData; + uint8_t PacketId = N; +}; diff --git a/Carla/Sensor/DReyeVRData.cpp b/Carla/Sensor/DReyeVRData.cpp index b14845e..d252171 100644 --- a/Carla/Sensor/DReyeVRData.cpp +++ b/Carla/Sensor/DReyeVRData.cpp @@ -1,640 +1,640 @@ -#include -#include - -namespace DReyeVR -{ - -/// ========================================== /// -/// ----------------:EYEDATA:----------------- /// -/// ========================================== /// - -void EyeData::Read(std::ifstream &InFile) -{ - ReadFVector(InFile, GazeDir); - ReadFVector(InFile, GazeOrigin); - ReadValue(InFile, GazeValid); -} - -void EyeData::Write(std::ofstream &OutFile) const -{ - WriteFVector(OutFile, GazeDir); - WriteFVector(OutFile, GazeOrigin); - WriteValue(OutFile, GazeValid); -} - -FString EyeData::ToString() const -{ - FString Print; - Print += FString::Printf(TEXT("GazeDir:%s,"), *GazeDir.ToString()); - Print += FString::Printf(TEXT("GazeOrigin:%s,"), *GazeOrigin.ToString()); - Print += FString::Printf(TEXT("GazeValid:%d,"), GazeValid); - return Print; -} - -/// ========================================== /// -/// ------------:COMBINEDEYEDATA:------------- /// -/// ========================================== /// - -void CombinedEyeData::Read(std::ifstream &InFile) -{ - EyeData::Read(InFile); - ReadValue(InFile, Vergence); -} - -void CombinedEyeData::Write(std::ofstream &OutFile) const -{ - EyeData::Write(OutFile); - WriteValue(OutFile, Vergence); -} - -FString CombinedEyeData::ToString() const -{ - FString Print = EyeData::ToString(); - Print += FString::Printf(TEXT("GazeVergence:%.4f,"), Vergence); - return Print; -} - -/// ========================================== /// -/// -------------:SINGLEEYEDATA:-------------- /// -/// ========================================== /// - -void SingleEyeData::Read(std::ifstream &InFile) -{ - EyeData::Read(InFile); - ReadValue(InFile, EyeOpenness); - ReadValue(InFile, EyeOpennessValid); - ReadValue(InFile, PupilDiameter); - ReadFVector2D(InFile, PupilPosition); - ReadValue(InFile, PupilPositionValid); -} - -void SingleEyeData::Write(std::ofstream &OutFile) const -{ - EyeData::Write(OutFile); - WriteValue(OutFile, EyeOpenness); - WriteValue(OutFile, EyeOpennessValid); - WriteValue(OutFile, PupilDiameter); - WriteFVector2D(OutFile, PupilPosition); - WriteValue(OutFile, PupilPositionValid); -} - -FString SingleEyeData::ToString() const -{ - FString Print = EyeData::ToString(); - Print += FString::Printf(TEXT("EyeOpenness:%.4f,"), EyeOpenness); - Print += FString::Printf(TEXT("EyeOpennessValid:%d,"), EyeOpennessValid); - Print += FString::Printf(TEXT("PupilDiameter:%.4f,"), PupilDiameter); - Print += FString::Printf(TEXT("PupilPosition:%s,"), *PupilPosition.ToString()); - Print += FString::Printf(TEXT("PupilPositionValid:%d,"), PupilPositionValid); - return Print; -} - -/// ========================================== /// -/// --------------:EGOVARIABLES:-------------- /// -/// ========================================== /// - -void EgoVariables::Read(std::ifstream &InFile) -{ - ReadFVector(InFile, CameraLocation); - ReadFRotator(InFile, CameraRotation); - ReadFVector(InFile, CameraLocationAbs); - ReadFRotator(InFile, CameraRotationAbs); - ReadFVector(InFile, VehicleLocation); - ReadFRotator(InFile, VehicleRotation); - ReadValue(InFile, Velocity); -} - -void EgoVariables::Write(std::ofstream &OutFile) const -{ - WriteFVector(OutFile, CameraLocation); - WriteFRotator(OutFile, CameraRotation); - WriteFVector(OutFile, CameraLocationAbs); - WriteFRotator(OutFile, CameraRotationAbs); - WriteFVector(OutFile, VehicleLocation); - WriteFRotator(OutFile, VehicleRotation); - WriteValue(OutFile, Velocity); -} - -FString EgoVariables::ToString() const -{ - FString Print; - Print += FString::Printf(TEXT("VehicleLoc:%s,"), *VehicleLocation.ToString()); - Print += FString::Printf(TEXT("VehicleRot:%s,"), *VehicleRotation.ToString()); - Print += FString::Printf(TEXT("VehicleVel:%.4f,"), Velocity); - Print += FString::Printf(TEXT("CameraLoc:%s,"), *CameraLocation.ToString()); - Print += FString::Printf(TEXT("CameraRot:%s,"), *CameraRotation.ToString()); - Print += FString::Printf(TEXT("CameraLocAbs:%s,"), *CameraLocationAbs.ToString()); - Print += FString::Printf(TEXT("CameraRotAbs:%s,"), *CameraRotationAbs.ToString()); - return Print; -} - -/// ========================================== /// -/// --------------:USERINPUTS:---------------- /// -/// ========================================== /// - -void UserInputs::Read(std::ifstream &InFile) -{ - ReadValue(InFile, Throttle); - ReadValue(InFile, Steering); - ReadValue(InFile, Brake); - ReadValue(InFile, ToggledReverse); - ReadValue(InFile, TurnSignalLeft); - ReadValue(InFile, TurnSignalRight); - ReadValue(InFile, HoldHandbrake); -} - -void UserInputs::Write(std::ofstream &OutFile) const -{ - WriteValue(OutFile, Throttle); - WriteValue(OutFile, Steering); - WriteValue(OutFile, Brake); - WriteValue(OutFile, ToggledReverse); - WriteValue(OutFile, TurnSignalLeft); - WriteValue(OutFile, TurnSignalRight); - WriteValue(OutFile, HoldHandbrake); -} - -FString UserInputs::ToString() const -{ - FString Print; - Print += FString::Printf(TEXT("Throttle:%.4f,"), Throttle); - Print += FString::Printf(TEXT("Steering:%.4f,"), Steering); - Print += FString::Printf(TEXT("Brake:%.4f,"), Brake); - Print += FString::Printf(TEXT("ToggledReverse:%d,"), ToggledReverse); - Print += FString::Printf(TEXT("TurnSignalLeft:%d,"), TurnSignalLeft); - Print += FString::Printf(TEXT("TurnSignalRight:%d,"), TurnSignalRight); - Print += FString::Printf(TEXT("HoldHandbrake:%d,"), HoldHandbrake); - return Print; -} - -/// ========================================== /// -/// ---------------:FOCUSINFO:---------------- /// -/// ========================================== /// - -void FocusInfo::Read(std::ifstream &InFile) -{ - ReadFString(InFile, ActorNameTag); - ReadValue(InFile, bDidHit); - ReadFVector(InFile, HitPoint); - ReadFVector(InFile, Normal); - ReadValue(InFile, Distance); -} - -void FocusInfo::Write(std::ofstream &OutFile) const -{ - WriteFString(OutFile, ActorNameTag); - WriteValue(OutFile, bDidHit); - WriteFVector(OutFile, HitPoint); - WriteFVector(OutFile, Normal); - WriteValue(OutFile, Distance); -} - -FString FocusInfo::ToString() const -{ - FString Print; - Print += FString::Printf(TEXT("Hit:%d,"), bDidHit); - Print += FString::Printf(TEXT("Distance:%.4f,"), Distance); - Print += FString::Printf(TEXT("HitPoint:%s,"), *HitPoint.ToString()); - Print += FString::Printf(TEXT("HitNormal:%s,"), *Normal.ToString()); - Print += FString::Printf(TEXT("ActorName:%s,"), *ActorNameTag); - return Print; -} - -/// ========================================== /// -/// ---------------:EYETRACKER:--------------- /// -/// ========================================== /// - -void EyeTracker::Read(std::ifstream &InFile) -{ - ReadValue(InFile, TimestampDevice); - ReadValue(InFile, FrameSequence); - Combined.Read(InFile); - Left.Read(InFile); - Right.Read(InFile); -} - -void EyeTracker::Write(std::ofstream &OutFile) const -{ - WriteValue(OutFile, TimestampDevice); - WriteValue(OutFile, FrameSequence); - Combined.Write(OutFile); - Left.Write(OutFile); - Right.Write(OutFile); -} - -FString EyeTracker::ToString() const -{ - FString Print; - Print += FString::Printf(TEXT("TimestampDevice:%ld,"), long(TimestampDevice)); - Print += FString::Printf(TEXT("FrameSequence:%ld,"), long(FrameSequence)); - Print += FString::Printf(TEXT("COMBINED:{%s},"), *Combined.ToString()); - Print += FString::Printf(TEXT("LEFT:{%s},"), *Left.ToString()); - Print += FString::Printf(TEXT("RIGHT:{%s},"), *Right.ToString()); - return Print; -} - -/// ========================================== /// -/// ------------:CONFIGFILEDATA:-------------- /// -/// ========================================== /// - -void ConfigFileData::Set(const std::string &Contents) -{ - StringContents = FString(Contents.c_str()); -} - -void ConfigFileData::Read(std::ifstream &InFile) -{ - ReadFString(InFile, StringContents); -} - -void ConfigFileData::Write(std::ofstream &OutFile) const -{ - WriteFString(OutFile, StringContents); -} - -FString ConfigFileData::ToString() const -{ - return StringContents; -} - -/// ========================================== /// -/// -------------:AGGREGATEDATA:-------------- /// -/// ========================================== /// - -int64_t AggregateData::GetTimestampCarla() const -{ - return TimestampCarlaUE4; -} - -int64_t AggregateData::GetTimestampDevice() const -{ - return EyeTrackerData.TimestampDevice; -} - -int64_t AggregateData::GetFrameSequence() const -{ - return EyeTrackerData.FrameSequence; -} - -float AggregateData::GetGazeVergence() const -{ - return EyeTrackerData.Combined.Vergence; // in cm (default UE4 units) -} - -const FVector &AggregateData::GetGazeDir(DReyeVR::Gaze Index) const -{ - switch (Index) - { - case DReyeVR::Gaze::LEFT: - return EyeTrackerData.Left.GazeDir; - case DReyeVR::Gaze::RIGHT: - return EyeTrackerData.Right.GazeDir; - case DReyeVR::Gaze::COMBINED: - return EyeTrackerData.Combined.GazeDir; - default: // need a default case for MSVC >:( - return EyeTrackerData.Combined.GazeDir; - } -} - -const FVector &AggregateData::GetGazeOrigin(DReyeVR::Gaze Index) const -{ - switch (Index) - { - case DReyeVR::Gaze::LEFT: - return EyeTrackerData.Left.GazeOrigin; - case DReyeVR::Gaze::RIGHT: - return EyeTrackerData.Right.GazeOrigin; - case DReyeVR::Gaze::COMBINED: - return EyeTrackerData.Combined.GazeOrigin; - default: // need a default case for MSVC >:( - return EyeTrackerData.Combined.GazeOrigin; - } -} - -bool AggregateData::GetGazeValidity(DReyeVR::Gaze Index) const -{ - switch (Index) - { - case DReyeVR::Gaze::LEFT: - return EyeTrackerData.Left.GazeValid; - case DReyeVR::Gaze::RIGHT: - return EyeTrackerData.Right.GazeValid; - case DReyeVR::Gaze::COMBINED: - return EyeTrackerData.Combined.GazeValid; - default: // need a default case for MSVC >:( - return EyeTrackerData.Combined.GazeValid; - } -} - -float AggregateData::GetEyeOpenness(DReyeVR::Eye Index) const // returns eye openness as a percentage [0,1] -{ - switch (Index) - { - case DReyeVR::Eye::LEFT: - return EyeTrackerData.Left.EyeOpenness; - case DReyeVR::Eye::RIGHT: - return EyeTrackerData.Right.EyeOpenness; - default: // need a default case for MSVC >:( - return EyeTrackerData.Right.EyeOpenness; - } -} - -bool AggregateData::GetEyeOpennessValidity(DReyeVR::Eye Index) const -{ - switch (Index) - { - case DReyeVR::Eye::LEFT: - return EyeTrackerData.Left.EyeOpennessValid; - case DReyeVR::Eye::RIGHT: - return EyeTrackerData.Right.EyeOpennessValid; - default: // need a default case for MSVC >:( - return EyeTrackerData.Right.EyeOpennessValid; - } -} - -float AggregateData::GetPupilDiameter(DReyeVR::Eye Index) const // returns diameter in mm -{ - switch (Index) - { - case DReyeVR::Eye::LEFT: - return EyeTrackerData.Left.PupilDiameter; - case DReyeVR::Eye::RIGHT: - return EyeTrackerData.Right.PupilDiameter; - default: // need a default case for MSVC >:( - return EyeTrackerData.Right.PupilDiameter; - } -} - -const FVector2D &AggregateData::GetPupilPosition(DReyeVR::Eye Index) const -{ - switch (Index) - { - case DReyeVR::Eye::LEFT: - return EyeTrackerData.Left.PupilPosition; - case DReyeVR::Eye::RIGHT: - return EyeTrackerData.Right.PupilPosition; - default: // need a default case for MSVC >:( - return EyeTrackerData.Right.PupilPosition; - } -} - -bool AggregateData::GetPupilPositionValidity(DReyeVR::Eye Index) const -{ - switch (Index) - { - case DReyeVR::Eye::LEFT: - return EyeTrackerData.Left.PupilPositionValid; - case DReyeVR::Eye::RIGHT: - return EyeTrackerData.Right.PupilPositionValid; - default: // need a default case for MSVC >:( - return EyeTrackerData.Right.PupilPositionValid; - } -} - -// from EgoVars -const FVector &AggregateData::GetCameraLocation() const -{ - return EgoVars.CameraLocation; -} - -const FRotator &AggregateData::GetCameraRotation() const -{ - return EgoVars.CameraRotation; -} - -const FVector &AggregateData::GetCameraLocationAbs() const -{ - return EgoVars.CameraLocationAbs; -} - -const FRotator &AggregateData::GetCameraRotationAbs() const -{ - return EgoVars.CameraRotationAbs; -} - -float AggregateData::GetVehicleVelocity() const -{ - return EgoVars.Velocity; // returns ego velocity in cm/s -} - -const FVector &AggregateData::GetVehicleLocation() const -{ - return EgoVars.VehicleLocation; -} - -const FRotator &AggregateData::GetVehicleRotation() const -{ - return EgoVars.VehicleRotation; -} - -// focus -const FString &AggregateData::GetFocusActorName() const -{ - return FocusData.ActorNameTag; -} - -const FVector &AggregateData::GetFocusActorPoint() const -{ - return FocusData.HitPoint; -} - -float AggregateData::GetFocusActorDistance() const -{ - return FocusData.Distance; -} - -const DReyeVR::UserInputs &AggregateData::GetUserInputs() const -{ - return Inputs; -} - -void AggregateData::UpdateCamera(const FVector &NewCameraLoc, const FRotator &NewCameraRot) -{ - EgoVars.CameraLocation = NewCameraLoc; - EgoVars.CameraRotation = NewCameraRot; -} - -void AggregateData::UpdateCameraAbs(const FVector &NewCameraLocAbs, const FRotator &NewCameraRotAbs) -{ - EgoVars.CameraLocationAbs = NewCameraLocAbs; - EgoVars.CameraRotationAbs = NewCameraRotAbs; -} - -void AggregateData::UpdateVehicle(const FVector &NewVehicleLoc, const FRotator &NewVehicleRot) -{ - EgoVars.VehicleLocation = NewVehicleLoc; - EgoVars.VehicleRotation = NewVehicleRot; -} - -void AggregateData::Update(int64_t NewTimestamp, const struct EyeTracker &NewEyeData, - const struct EgoVariables &NewEgoVars, const struct FocusInfo &NewFocus, - const struct UserInputs &NewInputs) -{ - TimestampCarlaUE4 = NewTimestamp; - EyeTrackerData = NewEyeData; - EgoVars = NewEgoVars; - FocusData = NewFocus; - Inputs = NewInputs; -} - -void AggregateData::Read(std::ifstream &InFile) -{ - /// CAUTION: make sure the order of writes/reads is the same - ReadValue(InFile, TimestampCarlaUE4); - EgoVars.Read(InFile); - EyeTrackerData.Read(InFile); - FocusData.Read(InFile); - Inputs.Read(InFile); -} - -void AggregateData::Write(std::ofstream &OutFile) const -{ - /// CAUTION: make sure the order of writes/reads is the same - WriteValue(OutFile, GetTimestampCarla()); - EgoVars.Write(OutFile); - EyeTrackerData.Write(OutFile); - FocusData.Write(OutFile); - Inputs.Write(OutFile); -} - -FString AggregateData::ToString() const -{ - FString print; - print += FString::Printf(TEXT(" [DReyeVR]TimestampCarla:%ld,\n"), long(TimestampCarlaUE4)); - print += FString::Printf(TEXT(" [DReyeVR]EyeTracker:%s,\n"), *EyeTrackerData.ToString()); - print += FString::Printf(TEXT(" [DReyeVR]FocusInfo:%s,\n"), *FocusData.ToString()); - print += FString::Printf(TEXT(" [DReyeVR]EgoVariables:%s,\n"), *EgoVars.ToString()); - print += FString::Printf(TEXT(" [DReyeVR]UserInputs:%s,\n"), *Inputs.ToString()); - return print; -} - -/// ========================================== /// -/// ------------:CUSTOMACTORDATA:------------- /// -/// ========================================== /// - -void CustomActorData::MaterialParamsStruct::Apply(class UMaterialInstanceDynamic *DynamicMaterial) const -{ - /// PARAMS: - // these are either scalar (float) or vector (FLinearColor) attributes baked into the texture as follows - - /// SCALAR: - // "Metallic" -> controls how metal-like your surface looks like, default 0 - // "Specular" -> used to scale the current amount of specularity on non-metallic surfaces. Bw [0, 1], default 0.5 - // "Roughness" -> Controls how rough the material is. [0 (smooth/mirror), 1(rough/diffuse)], default 0 - // "Anisotropy" -> Determines the extent the specular highlight is stretched along the tangent. Bw [0, 1], default 0 - // "Opacity" -> How opaque is this material NOTE: ONLY APPLIES TO TRANSLUCENT MATERIAL. Bw [0, 1], default 0.15 - - /// VECTOR: - // "BaseColor" -> defines the overall colour of the material (each channel is clamped to [0, 1]) - // "Emissive" -> controls which parts of the material appear to glow - - /// NOTE: Opacity only gets applied when the material is based on the TranslucentParamMaterial, all the other scalar - // params only get applied in the opaque case. - - // assign material params - if (DynamicMaterial != nullptr) - { - DynamicMaterial->SetScalarParameterValue("Metallic", Metallic); - DynamicMaterial->SetScalarParameterValue("Specular", Specular); - DynamicMaterial->SetScalarParameterValue("Roughness", Roughness); - DynamicMaterial->SetScalarParameterValue("Anisotropy", Anisotropy); - DynamicMaterial->SetScalarParameterValue("Opacity", Opacity); - DynamicMaterial->SetVectorParameterValue("BaseColor", BaseColor); - DynamicMaterial->SetVectorParameterValue("Emissive", Emissive); - } -} - -void CustomActorData::MaterialParamsStruct::Read(std::ifstream &InFile) -{ - ReadValue(InFile, Metallic); - ReadValue(InFile, Specular); - ReadValue(InFile, Roughness); - ReadValue(InFile, Anisotropy); - ReadValue(InFile, Opacity); - ReadFLinearColor(InFile, BaseColor); - ReadFLinearColor(InFile, Emissive); - ReadFString(InFile, MaterialPath); -} - -void CustomActorData::MaterialParamsStruct::Write(std::ofstream &OutFile) const -{ - WriteValue(OutFile, Metallic); - WriteValue(OutFile, Specular); - WriteValue(OutFile, Roughness); - WriteValue(OutFile, Anisotropy); - WriteValue(OutFile, Opacity); - WriteFLinearColor(OutFile, BaseColor); - WriteFLinearColor(OutFile, Emissive); - WriteFString(OutFile, MaterialPath); -} - -FString PrintFLinearColor(const FLinearColor &F) -{ - // so the print output is consistent with FVector::ToString(), FVector2D::ToString(), FRotator::ToString() - // and the parser can treat this similarly - return FString::Printf(TEXT("R=%.6f G=%.6f B=%.6f A=%.6f"), F.R, F.G, F.B, F.A); -} - -FString CustomActorData::MaterialParamsStruct::ToString() const -{ - FString Print = ""; - Print += FString::Printf(TEXT("Metallic:%.3f,"), Metallic); - Print += FString::Printf(TEXT("Specular:%.3f,"), Specular); - Print += FString::Printf(TEXT("Roughness:%.3f,"), Roughness); - Print += FString::Printf(TEXT("Anisotropy:%.3f,"), Anisotropy); - Print += FString::Printf(TEXT("Opacity:%.3f,"), Opacity); - Print += FString::Printf(TEXT("BaseColor:%s,"), *PrintFLinearColor(BaseColor)); - Print += FString::Printf(TEXT("Emissive:%s,"), *PrintFLinearColor(Emissive)); - Print += FString::Printf(TEXT("Path:%s,"), *MaterialPath); - return Print; -} - -void CustomActorData::Read(std::ifstream &InFile) -{ - // 9 dof - ReadFVector(InFile, Location); - ReadFRotator(InFile, Rotation); - ReadFVector(InFile, Scale3D); - // visual properties - ReadFString(InFile, MeshPath); - // material properties - MaterialParams.Read(InFile); - // other - ReadFString(InFile, Other); - ReadFString(InFile, Name); -} - -void CustomActorData::Write(std::ofstream &OutFile) const -{ - // 9 dof - WriteFVector(OutFile, Location); - WriteFRotator(OutFile, Rotation); - WriteFVector(OutFile, Scale3D); - // visual properties - WriteFString(OutFile, MeshPath); - // material properties - MaterialParams.Write(OutFile); - // other - WriteFString(OutFile, Other); - WriteFString(OutFile, Name); -} - -FString CustomActorData::ToString() const -{ - FString Print = " [DReyeVR_CA]"; - Print += FString::Printf(TEXT("Name:%s,"), *Name); - Print += FString::Printf(TEXT("Location:%s,"), *Location.ToString()); - Print += FString::Printf(TEXT("Rotation:%s,"), *Rotation.ToString()); - Print += FString::Printf(TEXT("Scale3D:%s,"), *Scale3D.ToString()); - Print += FString::Printf(TEXT("MeshPath:%s,"), *MeshPath); - Print += FString::Printf(TEXT("Material:{%s},"), *MaterialParams.ToString()); - Print += FString::Printf(TEXT("Other:%s,"), *Other); - return Print; -} - -std::string CustomActorData::GetUniqueName() const -{ - return TCHAR_TO_UTF8(*Name); -} - +#include +#include + +namespace DReyeVR +{ + +/// ========================================== /// +/// ----------------:EYEDATA:----------------- /// +/// ========================================== /// + +void EyeData::Read(std::ifstream &InFile) +{ + ReadFVector(InFile, GazeDir); + ReadFVector(InFile, GazeOrigin); + ReadValue(InFile, GazeValid); +} + +void EyeData::Write(std::ofstream &OutFile) const +{ + WriteFVector(OutFile, GazeDir); + WriteFVector(OutFile, GazeOrigin); + WriteValue(OutFile, GazeValid); +} + +FString EyeData::ToString() const +{ + FString Print; + Print += FString::Printf(TEXT("GazeDir:%s,"), *GazeDir.ToString()); + Print += FString::Printf(TEXT("GazeOrigin:%s,"), *GazeOrigin.ToString()); + Print += FString::Printf(TEXT("GazeValid:%d,"), GazeValid); + return Print; +} + +/// ========================================== /// +/// ------------:COMBINEDEYEDATA:------------- /// +/// ========================================== /// + +void CombinedEyeData::Read(std::ifstream &InFile) +{ + EyeData::Read(InFile); + ReadValue(InFile, Vergence); +} + +void CombinedEyeData::Write(std::ofstream &OutFile) const +{ + EyeData::Write(OutFile); + WriteValue(OutFile, Vergence); +} + +FString CombinedEyeData::ToString() const +{ + FString Print = EyeData::ToString(); + Print += FString::Printf(TEXT("GazeVergence:%.4f,"), Vergence); + return Print; +} + +/// ========================================== /// +/// -------------:SINGLEEYEDATA:-------------- /// +/// ========================================== /// + +void SingleEyeData::Read(std::ifstream &InFile) +{ + EyeData::Read(InFile); + ReadValue(InFile, EyeOpenness); + ReadValue(InFile, EyeOpennessValid); + ReadValue(InFile, PupilDiameter); + ReadFVector2D(InFile, PupilPosition); + ReadValue(InFile, PupilPositionValid); +} + +void SingleEyeData::Write(std::ofstream &OutFile) const +{ + EyeData::Write(OutFile); + WriteValue(OutFile, EyeOpenness); + WriteValue(OutFile, EyeOpennessValid); + WriteValue(OutFile, PupilDiameter); + WriteFVector2D(OutFile, PupilPosition); + WriteValue(OutFile, PupilPositionValid); +} + +FString SingleEyeData::ToString() const +{ + FString Print = EyeData::ToString(); + Print += FString::Printf(TEXT("EyeOpenness:%.4f,"), EyeOpenness); + Print += FString::Printf(TEXT("EyeOpennessValid:%d,"), EyeOpennessValid); + Print += FString::Printf(TEXT("PupilDiameter:%.4f,"), PupilDiameter); + Print += FString::Printf(TEXT("PupilPosition:%s,"), *PupilPosition.ToString()); + Print += FString::Printf(TEXT("PupilPositionValid:%d,"), PupilPositionValid); + return Print; +} + +/// ========================================== /// +/// --------------:EGOVARIABLES:-------------- /// +/// ========================================== /// + +void EgoVariables::Read(std::ifstream &InFile) +{ + ReadFVector(InFile, CameraLocation); + ReadFRotator(InFile, CameraRotation); + ReadFVector(InFile, CameraLocationAbs); + ReadFRotator(InFile, CameraRotationAbs); + ReadFVector(InFile, VehicleLocation); + ReadFRotator(InFile, VehicleRotation); + ReadValue(InFile, Velocity); +} + +void EgoVariables::Write(std::ofstream &OutFile) const +{ + WriteFVector(OutFile, CameraLocation); + WriteFRotator(OutFile, CameraRotation); + WriteFVector(OutFile, CameraLocationAbs); + WriteFRotator(OutFile, CameraRotationAbs); + WriteFVector(OutFile, VehicleLocation); + WriteFRotator(OutFile, VehicleRotation); + WriteValue(OutFile, Velocity); +} + +FString EgoVariables::ToString() const +{ + FString Print; + Print += FString::Printf(TEXT("VehicleLoc:%s,"), *VehicleLocation.ToString()); + Print += FString::Printf(TEXT("VehicleRot:%s,"), *VehicleRotation.ToString()); + Print += FString::Printf(TEXT("VehicleVel:%.4f,"), Velocity); + Print += FString::Printf(TEXT("CameraLoc:%s,"), *CameraLocation.ToString()); + Print += FString::Printf(TEXT("CameraRot:%s,"), *CameraRotation.ToString()); + Print += FString::Printf(TEXT("CameraLocAbs:%s,"), *CameraLocationAbs.ToString()); + Print += FString::Printf(TEXT("CameraRotAbs:%s,"), *CameraRotationAbs.ToString()); + return Print; +} + +/// ========================================== /// +/// --------------:USERINPUTS:---------------- /// +/// ========================================== /// + +void UserInputs::Read(std::ifstream &InFile) +{ + ReadValue(InFile, Throttle); + ReadValue(InFile, Steering); + ReadValue(InFile, Brake); + ReadValue(InFile, ToggledReverse); + ReadValue(InFile, TurnSignalLeft); + ReadValue(InFile, TurnSignalRight); + ReadValue(InFile, HoldHandbrake); +} + +void UserInputs::Write(std::ofstream &OutFile) const +{ + WriteValue(OutFile, Throttle); + WriteValue(OutFile, Steering); + WriteValue(OutFile, Brake); + WriteValue(OutFile, ToggledReverse); + WriteValue(OutFile, TurnSignalLeft); + WriteValue(OutFile, TurnSignalRight); + WriteValue(OutFile, HoldHandbrake); +} + +FString UserInputs::ToString() const +{ + FString Print; + Print += FString::Printf(TEXT("Throttle:%.4f,"), Throttle); + Print += FString::Printf(TEXT("Steering:%.4f,"), Steering); + Print += FString::Printf(TEXT("Brake:%.4f,"), Brake); + Print += FString::Printf(TEXT("ToggledReverse:%d,"), ToggledReverse); + Print += FString::Printf(TEXT("TurnSignalLeft:%d,"), TurnSignalLeft); + Print += FString::Printf(TEXT("TurnSignalRight:%d,"), TurnSignalRight); + Print += FString::Printf(TEXT("HoldHandbrake:%d,"), HoldHandbrake); + return Print; +} + +/// ========================================== /// +/// ---------------:FOCUSINFO:---------------- /// +/// ========================================== /// + +void FocusInfo::Read(std::ifstream &InFile) +{ + ReadFString(InFile, ActorNameTag); + ReadValue(InFile, bDidHit); + ReadFVector(InFile, HitPoint); + ReadFVector(InFile, Normal); + ReadValue(InFile, Distance); +} + +void FocusInfo::Write(std::ofstream &OutFile) const +{ + WriteFString(OutFile, ActorNameTag); + WriteValue(OutFile, bDidHit); + WriteFVector(OutFile, HitPoint); + WriteFVector(OutFile, Normal); + WriteValue(OutFile, Distance); +} + +FString FocusInfo::ToString() const +{ + FString Print; + Print += FString::Printf(TEXT("Hit:%d,"), bDidHit); + Print += FString::Printf(TEXT("Distance:%.4f,"), Distance); + Print += FString::Printf(TEXT("HitPoint:%s,"), *HitPoint.ToString()); + Print += FString::Printf(TEXT("HitNormal:%s,"), *Normal.ToString()); + Print += FString::Printf(TEXT("ActorName:%s,"), *ActorNameTag); + return Print; +} + +/// ========================================== /// +/// ---------------:EYETRACKER:--------------- /// +/// ========================================== /// + +void EyeTracker::Read(std::ifstream &InFile) +{ + ReadValue(InFile, TimestampDevice); + ReadValue(InFile, FrameSequence); + Combined.Read(InFile); + Left.Read(InFile); + Right.Read(InFile); +} + +void EyeTracker::Write(std::ofstream &OutFile) const +{ + WriteValue(OutFile, TimestampDevice); + WriteValue(OutFile, FrameSequence); + Combined.Write(OutFile); + Left.Write(OutFile); + Right.Write(OutFile); +} + +FString EyeTracker::ToString() const +{ + FString Print; + Print += FString::Printf(TEXT("TimestampDevice:%ld,"), long(TimestampDevice)); + Print += FString::Printf(TEXT("FrameSequence:%ld,"), long(FrameSequence)); + Print += FString::Printf(TEXT("COMBINED:{%s},"), *Combined.ToString()); + Print += FString::Printf(TEXT("LEFT:{%s},"), *Left.ToString()); + Print += FString::Printf(TEXT("RIGHT:{%s},"), *Right.ToString()); + return Print; +} + +/// ========================================== /// +/// ------------:CONFIGFILEDATA:-------------- /// +/// ========================================== /// + +void ConfigFileData::Set(const std::string &Contents) +{ + StringContents = FString(Contents.c_str()); +} + +void ConfigFileData::Read(std::ifstream &InFile) +{ + ReadFString(InFile, StringContents); +} + +void ConfigFileData::Write(std::ofstream &OutFile) const +{ + WriteFString(OutFile, StringContents); +} + +FString ConfigFileData::ToString() const +{ + return StringContents; +} + +/// ========================================== /// +/// -------------:AGGREGATEDATA:-------------- /// +/// ========================================== /// + +int64_t AggregateData::GetTimestampCarla() const +{ + return TimestampCarlaUE4; +} + +int64_t AggregateData::GetTimestampDevice() const +{ + return EyeTrackerData.TimestampDevice; +} + +int64_t AggregateData::GetFrameSequence() const +{ + return EyeTrackerData.FrameSequence; +} + +float AggregateData::GetGazeVergence() const +{ + return EyeTrackerData.Combined.Vergence; // in cm (default UE4 units) +} + +const FVector &AggregateData::GetGazeDir(DReyeVR::Gaze Index) const +{ + switch (Index) + { + case DReyeVR::Gaze::LEFT: + return EyeTrackerData.Left.GazeDir; + case DReyeVR::Gaze::RIGHT: + return EyeTrackerData.Right.GazeDir; + case DReyeVR::Gaze::COMBINED: + return EyeTrackerData.Combined.GazeDir; + default: // need a default case for MSVC >:( + return EyeTrackerData.Combined.GazeDir; + } +} + +const FVector &AggregateData::GetGazeOrigin(DReyeVR::Gaze Index) const +{ + switch (Index) + { + case DReyeVR::Gaze::LEFT: + return EyeTrackerData.Left.GazeOrigin; + case DReyeVR::Gaze::RIGHT: + return EyeTrackerData.Right.GazeOrigin; + case DReyeVR::Gaze::COMBINED: + return EyeTrackerData.Combined.GazeOrigin; + default: // need a default case for MSVC >:( + return EyeTrackerData.Combined.GazeOrigin; + } +} + +bool AggregateData::GetGazeValidity(DReyeVR::Gaze Index) const +{ + switch (Index) + { + case DReyeVR::Gaze::LEFT: + return EyeTrackerData.Left.GazeValid; + case DReyeVR::Gaze::RIGHT: + return EyeTrackerData.Right.GazeValid; + case DReyeVR::Gaze::COMBINED: + return EyeTrackerData.Combined.GazeValid; + default: // need a default case for MSVC >:( + return EyeTrackerData.Combined.GazeValid; + } +} + +float AggregateData::GetEyeOpenness(DReyeVR::Eye Index) const // returns eye openness as a percentage [0,1] +{ + switch (Index) + { + case DReyeVR::Eye::LEFT: + return EyeTrackerData.Left.EyeOpenness; + case DReyeVR::Eye::RIGHT: + return EyeTrackerData.Right.EyeOpenness; + default: // need a default case for MSVC >:( + return EyeTrackerData.Right.EyeOpenness; + } +} + +bool AggregateData::GetEyeOpennessValidity(DReyeVR::Eye Index) const +{ + switch (Index) + { + case DReyeVR::Eye::LEFT: + return EyeTrackerData.Left.EyeOpennessValid; + case DReyeVR::Eye::RIGHT: + return EyeTrackerData.Right.EyeOpennessValid; + default: // need a default case for MSVC >:( + return EyeTrackerData.Right.EyeOpennessValid; + } +} + +float AggregateData::GetPupilDiameter(DReyeVR::Eye Index) const // returns diameter in mm +{ + switch (Index) + { + case DReyeVR::Eye::LEFT: + return EyeTrackerData.Left.PupilDiameter; + case DReyeVR::Eye::RIGHT: + return EyeTrackerData.Right.PupilDiameter; + default: // need a default case for MSVC >:( + return EyeTrackerData.Right.PupilDiameter; + } +} + +const FVector2D &AggregateData::GetPupilPosition(DReyeVR::Eye Index) const +{ + switch (Index) + { + case DReyeVR::Eye::LEFT: + return EyeTrackerData.Left.PupilPosition; + case DReyeVR::Eye::RIGHT: + return EyeTrackerData.Right.PupilPosition; + default: // need a default case for MSVC >:( + return EyeTrackerData.Right.PupilPosition; + } +} + +bool AggregateData::GetPupilPositionValidity(DReyeVR::Eye Index) const +{ + switch (Index) + { + case DReyeVR::Eye::LEFT: + return EyeTrackerData.Left.PupilPositionValid; + case DReyeVR::Eye::RIGHT: + return EyeTrackerData.Right.PupilPositionValid; + default: // need a default case for MSVC >:( + return EyeTrackerData.Right.PupilPositionValid; + } +} + +// from EgoVars +const FVector &AggregateData::GetCameraLocation() const +{ + return EgoVars.CameraLocation; +} + +const FRotator &AggregateData::GetCameraRotation() const +{ + return EgoVars.CameraRotation; +} + +const FVector &AggregateData::GetCameraLocationAbs() const +{ + return EgoVars.CameraLocationAbs; +} + +const FRotator &AggregateData::GetCameraRotationAbs() const +{ + return EgoVars.CameraRotationAbs; +} + +float AggregateData::GetVehicleVelocity() const +{ + return EgoVars.Velocity; // returns ego velocity in cm/s +} + +const FVector &AggregateData::GetVehicleLocation() const +{ + return EgoVars.VehicleLocation; +} + +const FRotator &AggregateData::GetVehicleRotation() const +{ + return EgoVars.VehicleRotation; +} + +// focus +const FString &AggregateData::GetFocusActorName() const +{ + return FocusData.ActorNameTag; +} + +const FVector &AggregateData::GetFocusActorPoint() const +{ + return FocusData.HitPoint; +} + +float AggregateData::GetFocusActorDistance() const +{ + return FocusData.Distance; +} + +const DReyeVR::UserInputs &AggregateData::GetUserInputs() const +{ + return Inputs; +} + +void AggregateData::UpdateCamera(const FVector &NewCameraLoc, const FRotator &NewCameraRot) +{ + EgoVars.CameraLocation = NewCameraLoc; + EgoVars.CameraRotation = NewCameraRot; +} + +void AggregateData::UpdateCameraAbs(const FVector &NewCameraLocAbs, const FRotator &NewCameraRotAbs) +{ + EgoVars.CameraLocationAbs = NewCameraLocAbs; + EgoVars.CameraRotationAbs = NewCameraRotAbs; +} + +void AggregateData::UpdateVehicle(const FVector &NewVehicleLoc, const FRotator &NewVehicleRot) +{ + EgoVars.VehicleLocation = NewVehicleLoc; + EgoVars.VehicleRotation = NewVehicleRot; +} + +void AggregateData::Update(int64_t NewTimestamp, const struct EyeTracker &NewEyeData, + const struct EgoVariables &NewEgoVars, const struct FocusInfo &NewFocus, + const struct UserInputs &NewInputs) +{ + TimestampCarlaUE4 = NewTimestamp; + EyeTrackerData = NewEyeData; + EgoVars = NewEgoVars; + FocusData = NewFocus; + Inputs = NewInputs; +} + +void AggregateData::Read(std::ifstream &InFile) +{ + /// CAUTION: make sure the order of writes/reads is the same + ReadValue(InFile, TimestampCarlaUE4); + EgoVars.Read(InFile); + EyeTrackerData.Read(InFile); + FocusData.Read(InFile); + Inputs.Read(InFile); +} + +void AggregateData::Write(std::ofstream &OutFile) const +{ + /// CAUTION: make sure the order of writes/reads is the same + WriteValue(OutFile, GetTimestampCarla()); + EgoVars.Write(OutFile); + EyeTrackerData.Write(OutFile); + FocusData.Write(OutFile); + Inputs.Write(OutFile); +} + +FString AggregateData::ToString() const +{ + FString print; + print += FString::Printf(TEXT(" [DReyeVR]TimestampCarla:%ld,\n"), long(TimestampCarlaUE4)); + print += FString::Printf(TEXT(" [DReyeVR]EyeTracker:%s,\n"), *EyeTrackerData.ToString()); + print += FString::Printf(TEXT(" [DReyeVR]FocusInfo:%s,\n"), *FocusData.ToString()); + print += FString::Printf(TEXT(" [DReyeVR]EgoVariables:%s,\n"), *EgoVars.ToString()); + print += FString::Printf(TEXT(" [DReyeVR]UserInputs:%s,\n"), *Inputs.ToString()); + return print; +} + +/// ========================================== /// +/// ------------:CUSTOMACTORDATA:------------- /// +/// ========================================== /// + +void CustomActorData::MaterialParamsStruct::Apply(class UMaterialInstanceDynamic *DynamicMaterial) const +{ + /// PARAMS: + // these are either scalar (float) or vector (FLinearColor) attributes baked into the texture as follows + + /// SCALAR: + // "Metallic" -> controls how metal-like your surface looks like, default 0 + // "Specular" -> used to scale the current amount of specularity on non-metallic surfaces. Bw [0, 1], default 0.5 + // "Roughness" -> Controls how rough the material is. [0 (smooth/mirror), 1(rough/diffuse)], default 0 + // "Anisotropy" -> Determines the extent the specular highlight is stretched along the tangent. Bw [0, 1], default 0 + // "Opacity" -> How opaque is this material NOTE: ONLY APPLIES TO TRANSLUCENT MATERIAL. Bw [0, 1], default 0.15 + + /// VECTOR: + // "BaseColor" -> defines the overall colour of the material (each channel is clamped to [0, 1]) + // "Emissive" -> controls which parts of the material appear to glow + + /// NOTE: Opacity only gets applied when the material is based on the TranslucentParamMaterial, all the other scalar + // params only get applied in the opaque case. + + // assign material params + if (DynamicMaterial != nullptr) + { + DynamicMaterial->SetScalarParameterValue("Metallic", Metallic); + DynamicMaterial->SetScalarParameterValue("Specular", Specular); + DynamicMaterial->SetScalarParameterValue("Roughness", Roughness); + DynamicMaterial->SetScalarParameterValue("Anisotropy", Anisotropy); + DynamicMaterial->SetScalarParameterValue("Opacity", Opacity); + DynamicMaterial->SetVectorParameterValue("BaseColor", BaseColor); + DynamicMaterial->SetVectorParameterValue("Emissive", Emissive); + } +} + +void CustomActorData::MaterialParamsStruct::Read(std::ifstream &InFile) +{ + ReadValue(InFile, Metallic); + ReadValue(InFile, Specular); + ReadValue(InFile, Roughness); + ReadValue(InFile, Anisotropy); + ReadValue(InFile, Opacity); + ReadFLinearColor(InFile, BaseColor); + ReadFLinearColor(InFile, Emissive); + ReadFString(InFile, MaterialPath); +} + +void CustomActorData::MaterialParamsStruct::Write(std::ofstream &OutFile) const +{ + WriteValue(OutFile, Metallic); + WriteValue(OutFile, Specular); + WriteValue(OutFile, Roughness); + WriteValue(OutFile, Anisotropy); + WriteValue(OutFile, Opacity); + WriteFLinearColor(OutFile, BaseColor); + WriteFLinearColor(OutFile, Emissive); + WriteFString(OutFile, MaterialPath); +} + +FString PrintFLinearColor(const FLinearColor &F) +{ + // so the print output is consistent with FVector::ToString(), FVector2D::ToString(), FRotator::ToString() + // and the parser can treat this similarly + return FString::Printf(TEXT("R=%.6f G=%.6f B=%.6f A=%.6f"), F.R, F.G, F.B, F.A); +} + +FString CustomActorData::MaterialParamsStruct::ToString() const +{ + FString Print = ""; + Print += FString::Printf(TEXT("Metallic:%.3f,"), Metallic); + Print += FString::Printf(TEXT("Specular:%.3f,"), Specular); + Print += FString::Printf(TEXT("Roughness:%.3f,"), Roughness); + Print += FString::Printf(TEXT("Anisotropy:%.3f,"), Anisotropy); + Print += FString::Printf(TEXT("Opacity:%.3f,"), Opacity); + Print += FString::Printf(TEXT("BaseColor:%s,"), *PrintFLinearColor(BaseColor)); + Print += FString::Printf(TEXT("Emissive:%s,"), *PrintFLinearColor(Emissive)); + Print += FString::Printf(TEXT("Path:%s,"), *MaterialPath); + return Print; +} + +void CustomActorData::Read(std::ifstream &InFile) +{ + // 9 dof + ReadFVector(InFile, Location); + ReadFRotator(InFile, Rotation); + ReadFVector(InFile, Scale3D); + // visual properties + ReadFString(InFile, MeshPath); + // material properties + MaterialParams.Read(InFile); + // other + ReadFString(InFile, Other); + ReadFString(InFile, Name); +} + +void CustomActorData::Write(std::ofstream &OutFile) const +{ + // 9 dof + WriteFVector(OutFile, Location); + WriteFRotator(OutFile, Rotation); + WriteFVector(OutFile, Scale3D); + // visual properties + WriteFString(OutFile, MeshPath); + // material properties + MaterialParams.Write(OutFile); + // other + WriteFString(OutFile, Other); + WriteFString(OutFile, Name); +} + +FString CustomActorData::ToString() const +{ + FString Print = " [DReyeVR_CA]"; + Print += FString::Printf(TEXT("Name:%s,"), *Name); + Print += FString::Printf(TEXT("Location:%s,"), *Location.ToString()); + Print += FString::Printf(TEXT("Rotation:%s,"), *Rotation.ToString()); + Print += FString::Printf(TEXT("Scale3D:%s,"), *Scale3D.ToString()); + Print += FString::Printf(TEXT("MeshPath:%s,"), *MeshPath); + Print += FString::Printf(TEXT("Material:{%s},"), *MaterialParams.ToString()); + Print += FString::Printf(TEXT("Other:%s,"), *Other); + return Print; +} + +std::string CustomActorData::GetUniqueName() const +{ + return TCHAR_TO_UTF8(*Name); +} + }; // namespace DReyeVR \ No newline at end of file diff --git a/Carla/Sensor/DReyeVRData.h b/Carla/Sensor/DReyeVRData.h index 3495fb4..330ef18 100644 --- a/Carla/Sensor/DReyeVRData.h +++ b/Carla/Sensor/DReyeVRData.h @@ -1,245 +1,245 @@ -#pragma once - -#include "Carla/Recorder/CarlaRecorderHelpers.h" // WriteValue, WriteFVector, WriteFString, ... -#include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic -#include // timing threads -#include // int64_t -#include -#include -#include -#include -#include - -namespace DReyeVR -{ - -struct CARLA_API DataSerializer -{ - DataSerializer() = default; - virtual ~DataSerializer() = default; - - virtual void Read(std::ifstream &InFile) = 0; - virtual void Write(std::ofstream &OutFile) const = 0; - virtual FString ToString() const = 0; -}; - -struct CARLA_API EyeData : public DataSerializer -{ - FVector GazeDir = FVector::ZeroVector; - FVector GazeOrigin = FVector::ZeroVector; - bool GazeValid = false; - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -struct CARLA_API CombinedEyeData : EyeData -{ - float Vergence = 0.f; // in cm (default UE4 units) - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -struct CARLA_API SingleEyeData : EyeData -{ - float EyeOpenness = 0.f; - bool EyeOpennessValid = false; - float PupilDiameter = 0.f; - FVector2D PupilPosition = FVector2D::ZeroVector; - bool PupilPositionValid = false; - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -struct CARLA_API EgoVariables : public DataSerializer -{ - // World coordinate Ego vehicle location & rotation - FVector VehicleLocation = FVector::ZeroVector; - FRotator VehicleRotation = FRotator::ZeroRotator; - // Relative Camera position and orientation (for HMD offsets) - FVector CameraLocation = FVector::ZeroVector; - FRotator CameraRotation = FRotator::ZeroRotator; - // Absolute Camera position and orientation (includes vehicle & HMD offset) - FVector CameraLocationAbs = FVector::ZeroVector; - FRotator CameraRotationAbs = FRotator::ZeroRotator; - // Ego variables - float Velocity = 0.f; // note this is in cm/s (default UE4 units) - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -struct CARLA_API UserInputs : public DataSerializer -{ - // User inputs - float Throttle = 0.f; - float Steering = 0.f; - float Brake = 0.f; - bool ToggledReverse = false; - bool TurnSignalLeft = false; - bool TurnSignalRight = false; - bool HoldHandbrake = false; - // Add more inputs here! - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -struct CARLA_API FocusInfo : public DataSerializer -{ - // substitute for SRanipal FFocusInfo in SRanipal_Eyes_Enums.h - TWeakObjectPtr Actor; - FVector HitPoint; // in world space (absolute location) - FVector Normal; - FString ActorNameTag = "None"; // Tag of the actor being focused on - float Distance; - bool bDidHit; - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -struct CARLA_API EyeTracker : public DataSerializer -{ - int64_t TimestampDevice = 0; // timestamp from the eye tracker device (with its own clock) - int64_t FrameSequence = 0; // "Frame sequence" of SRanipal or just the tick frame in UE4 - CombinedEyeData Combined; - SingleEyeData Left; - SingleEyeData Right; - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -enum class Gaze -{ - COMBINED, // default for functions - RIGHT, - LEFT, -}; - -enum class Eye -{ - RIGHT, - LEFT, -}; - -// all DReyeVR Config data (only used once at the start of each recording) -class CARLA_API ConfigFileData : public DataSerializer -{ - private: - FString StringContents; // all the config files, concatenated - public: - void Set(const std::string &Contents); - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; -}; - -// all DReyeVR sensor data is held here -class CARLA_API AggregateData : public DataSerializer -{ - public: - AggregateData() = default; - /////////////////////////:GETTERS:////////////////////////////// - - int64_t GetTimestampCarla() const; - int64_t GetTimestampDevice() const; - int64_t GetFrameSequence() const; - float GetGazeVergence() const; - const FVector &GetGazeDir(DReyeVR::Gaze Index = DReyeVR::Gaze::COMBINED) const; - const FVector &GetGazeOrigin(DReyeVR::Gaze Index = DReyeVR::Gaze::COMBINED) const; - bool GetGazeValidity(DReyeVR::Gaze Index = DReyeVR::Gaze::COMBINED) const; - float GetEyeOpenness(DReyeVR::Eye Index) const; // returns eye openness as a percentage [0,1] - bool GetEyeOpennessValidity(DReyeVR::Eye Index) const; - float GetPupilDiameter(DReyeVR::Eye Index) const; // returns diameter in mm - const FVector2D &GetPupilPosition(DReyeVR::Eye Index) const; - bool GetPupilPositionValidity(DReyeVR::Eye Index) const; - - // from EgoVars - const FVector &GetCameraLocation() const; - const FRotator &GetCameraRotation() const; - const FVector &GetCameraLocationAbs() const; - const FRotator &GetCameraRotationAbs() const; - float GetVehicleVelocity() const; - const FVector &GetVehicleLocation() const; - const FRotator &GetVehicleRotation() const; - - // focus - const FString &GetFocusActorName() const; - const FVector &GetFocusActorPoint() const; - float GetFocusActorDistance() const; - const DReyeVR::UserInputs &GetUserInputs() const; - - ////////////////////:SETTERS:////////////////////// - void UpdateCamera(const FVector &NewCameraLoc, const FRotator &NewCameraRot); - void UpdateCameraAbs(const FVector &NewCameraLocAbs, const FRotator &NewCameraRotAbs); - void UpdateVehicle(const FVector &NewVehicleLoc, const FRotator &NewVehicleRot); - void Update(int64_t NewTimestamp, const struct EyeTracker &NewEyeData, const struct EgoVariables &NewEgoVars, - const struct FocusInfo &NewFocus, const struct UserInputs &NewInputs); - - ////////////////////:SERIALIZATION:////////////////////// - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; - - private: - int64_t TimestampCarlaUE4; // Carla Timestamp (EgoSensor Tick() event) in milliseconds - struct EyeTracker EyeTrackerData; - struct EgoVariables EgoVars; - struct FocusInfo FocusData; - struct UserInputs Inputs; -}; - -class CARLA_API CustomActorData : public DataSerializer -{ - public: - FString Name; // unique actor name of this actor - // 9 dof (location, rotation, scale) for non-rigid body in 3D space - FVector Location; - FRotator Rotation; - FVector Scale3D; - // visual properties - FString MeshPath; - // material properties - struct CARLA_API MaterialParamsStruct : public DataSerializer - { - /// for an explanation of these, see MaterialParamsStruct::Apply - // in DReyeVRData.inl - float Metallic = 1.f; - float Specular = 0.f; - float Roughness = 1.f; - float Anisotropy = 1.f; - float Opacity = 1.f; - FLinearColor BaseColor = FLinearColor::Red; - // usually a scale factor like 500 is good to emit bright light on a sunny day - FLinearColor Emissive = 500.f * FLinearColor::Red; - FString MaterialPath; - void Apply(class UMaterialInstanceDynamic *Material) const; - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; - }; - MaterialParamsStruct MaterialParams; - // other - FString Other; // any other data deemed necessary to record - - CustomActorData() = default; - - void Read(std::ifstream &InFile) override; - void Write(std::ofstream &OutFile) const override; - FString ToString() const override; - std::string GetUniqueName() const; -}; - +#pragma once + +#include "Carla/Recorder/CarlaRecorderHelpers.h" // WriteValue, WriteFVector, WriteFString, ... +#include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic +#include // timing threads +#include // int64_t +#include +#include +#include +#include +#include + +namespace DReyeVR +{ + +struct CARLA_API DataSerializer +{ + DataSerializer() = default; + virtual ~DataSerializer() = default; + + virtual void Read(std::ifstream &InFile) = 0; + virtual void Write(std::ofstream &OutFile) const = 0; + virtual FString ToString() const = 0; +}; + +struct CARLA_API EyeData : public DataSerializer +{ + FVector GazeDir = FVector::ZeroVector; + FVector GazeOrigin = FVector::ZeroVector; + bool GazeValid = false; + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +struct CARLA_API CombinedEyeData : EyeData +{ + float Vergence = 0.f; // in cm (default UE4 units) + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +struct CARLA_API SingleEyeData : EyeData +{ + float EyeOpenness = 0.f; + bool EyeOpennessValid = false; + float PupilDiameter = 0.f; + FVector2D PupilPosition = FVector2D::ZeroVector; + bool PupilPositionValid = false; + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +struct CARLA_API EgoVariables : public DataSerializer +{ + // World coordinate Ego vehicle location & rotation + FVector VehicleLocation = FVector::ZeroVector; + FRotator VehicleRotation = FRotator::ZeroRotator; + // Relative Camera position and orientation (for HMD offsets) + FVector CameraLocation = FVector::ZeroVector; + FRotator CameraRotation = FRotator::ZeroRotator; + // Absolute Camera position and orientation (includes vehicle & HMD offset) + FVector CameraLocationAbs = FVector::ZeroVector; + FRotator CameraRotationAbs = FRotator::ZeroRotator; + // Ego variables + float Velocity = 0.f; // note this is in cm/s (default UE4 units) + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +struct CARLA_API UserInputs : public DataSerializer +{ + // User inputs + float Throttle = 0.f; + float Steering = 0.f; + float Brake = 0.f; + bool ToggledReverse = false; + bool TurnSignalLeft = false; + bool TurnSignalRight = false; + bool HoldHandbrake = false; + // Add more inputs here! + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +struct CARLA_API FocusInfo : public DataSerializer +{ + // substitute for SRanipal FFocusInfo in SRanipal_Eyes_Enums.h + TWeakObjectPtr Actor; + FVector HitPoint; // in world space (absolute location) + FVector Normal; + FString ActorNameTag = "None"; // Tag of the actor being focused on + float Distance; + bool bDidHit; + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +struct CARLA_API EyeTracker : public DataSerializer +{ + int64_t TimestampDevice = 0; // timestamp from the eye tracker device (with its own clock) + int64_t FrameSequence = 0; // "Frame sequence" of SRanipal or just the tick frame in UE4 + CombinedEyeData Combined; + SingleEyeData Left; + SingleEyeData Right; + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +enum class Gaze +{ + COMBINED, // default for functions + RIGHT, + LEFT, +}; + +enum class Eye +{ + RIGHT, + LEFT, +}; + +// all DReyeVR Config data (only used once at the start of each recording) +class CARLA_API ConfigFileData : public DataSerializer +{ + private: + FString StringContents; // all the config files, concatenated + public: + void Set(const std::string &Contents); + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + +// all DReyeVR sensor data is held here +class CARLA_API AggregateData : public DataSerializer +{ + public: + AggregateData() = default; + /////////////////////////:GETTERS:////////////////////////////// + + int64_t GetTimestampCarla() const; + int64_t GetTimestampDevice() const; + int64_t GetFrameSequence() const; + float GetGazeVergence() const; + const FVector &GetGazeDir(DReyeVR::Gaze Index = DReyeVR::Gaze::COMBINED) const; + const FVector &GetGazeOrigin(DReyeVR::Gaze Index = DReyeVR::Gaze::COMBINED) const; + bool GetGazeValidity(DReyeVR::Gaze Index = DReyeVR::Gaze::COMBINED) const; + float GetEyeOpenness(DReyeVR::Eye Index) const; // returns eye openness as a percentage [0,1] + bool GetEyeOpennessValidity(DReyeVR::Eye Index) const; + float GetPupilDiameter(DReyeVR::Eye Index) const; // returns diameter in mm + const FVector2D &GetPupilPosition(DReyeVR::Eye Index) const; + bool GetPupilPositionValidity(DReyeVR::Eye Index) const; + + // from EgoVars + const FVector &GetCameraLocation() const; + const FRotator &GetCameraRotation() const; + const FVector &GetCameraLocationAbs() const; + const FRotator &GetCameraRotationAbs() const; + float GetVehicleVelocity() const; + const FVector &GetVehicleLocation() const; + const FRotator &GetVehicleRotation() const; + + // focus + const FString &GetFocusActorName() const; + const FVector &GetFocusActorPoint() const; + float GetFocusActorDistance() const; + const DReyeVR::UserInputs &GetUserInputs() const; + + ////////////////////:SETTERS:////////////////////// + void UpdateCamera(const FVector &NewCameraLoc, const FRotator &NewCameraRot); + void UpdateCameraAbs(const FVector &NewCameraLocAbs, const FRotator &NewCameraRotAbs); + void UpdateVehicle(const FVector &NewVehicleLoc, const FRotator &NewVehicleRot); + void Update(int64_t NewTimestamp, const struct EyeTracker &NewEyeData, const struct EgoVariables &NewEgoVars, + const struct FocusInfo &NewFocus, const struct UserInputs &NewInputs); + + ////////////////////:SERIALIZATION:////////////////////// + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; + + private: + int64_t TimestampCarlaUE4; // Carla Timestamp (EgoSensor Tick() event) in milliseconds + struct EyeTracker EyeTrackerData; + struct EgoVariables EgoVars; + struct FocusInfo FocusData; + struct UserInputs Inputs; +}; + +class CARLA_API CustomActorData : public DataSerializer +{ + public: + FString Name; // unique actor name of this actor + // 9 dof (location, rotation, scale) for non-rigid body in 3D space + FVector Location; + FRotator Rotation; + FVector Scale3D; + // visual properties + FString MeshPath; + // material properties + struct CARLA_API MaterialParamsStruct : public DataSerializer + { + /// for an explanation of these, see MaterialParamsStruct::Apply + // in DReyeVRData.inl + float Metallic = 1.f; + float Specular = 0.f; + float Roughness = 1.f; + float Anisotropy = 1.f; + float Opacity = 1.f; + FLinearColor BaseColor = FLinearColor::Red; + // usually a scale factor like 500 is good to emit bright light on a sunny day + FLinearColor Emissive = 500.f * FLinearColor::Red; + FString MaterialPath; + void Apply(class UMaterialInstanceDynamic *Material) const; + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; + }; + MaterialParamsStruct MaterialParams; + // other + FString Other; // any other data deemed necessary to record + + CustomActorData() = default; + + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; + std::string GetUniqueName() const; +}; + }; // namespace DReyeVR \ No newline at end of file diff --git a/Carla/Sensor/DReyeVRSensor.cpp b/Carla/Sensor/DReyeVRSensor.cpp index 4124d62..5498167 100644 --- a/Carla/Sensor/DReyeVRSensor.cpp +++ b/Carla/Sensor/DReyeVRSensor.cpp @@ -1,279 +1,279 @@ -#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor -#include "Carla.h" // all carla things -#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" // MakeGenericSensorDefinition -#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor -#include "Carla/Game/CarlaStatics.h" // GetGameInstance - -#include -#include - -// vector types for serialization -#include "carla/geom/Vector2D.h" -#include "carla/geom/Vector3D.h" -#include "carla/sensor/s11n/DReyeVRSerializer.h" // DReyeVRSerializer::Data - -class DReyeVR::AggregateData *ADReyeVRSensor::Data = nullptr; -class DReyeVR::ConfigFileData *ADReyeVRSensor::ConfigFile = nullptr; -bool ADReyeVRSensor::bIsReplaying = false; // initially not replaying - -ADReyeVRSensor::ADReyeVRSensor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) -{ - // no need for any other initialization - PrimaryActorTick.bCanEverTick = true; - if (ADReyeVRSensor::Data == nullptr) - ADReyeVRSensor::Data = new DReyeVR::AggregateData(); - if (ADReyeVRSensor::ConfigFile == nullptr) - ADReyeVRSensor::ConfigFile = new DReyeVR::ConfigFileData(); -} - -FActorDefinition ADReyeVRSensor::GetSensorDefinition() -{ - // What our sensor is going to be called: - auto Definition = UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition(TEXT("dreyevr"), TEXT("sensor_base")); - - /// NOTE: only has EActorAttributeType for bool, int, float, string, and RGBColor - // see /Plugins/Carla/Source/Carla/Actor/ActorAttribute.h for the whole list - - // append all Variable variations to the definition - // Definition.Variations.Append(); - - return Definition; -} - -void ADReyeVRSensor::Set(const FActorDescription &Description) -{ - Super::Set(Description); -} - -void ADReyeVRSensor::SetOwner(AActor *Owner) -{ - Super::SetOwner(Owner); - if (Owner != nullptr) - { - // Set Transform to the same as the Owner - SetActorLocation(Owner->GetActorLocation()); - SetActorRotation(Owner->GetActorRotation()); - } -} - -void ADReyeVRSensor::BeginPlay() -{ - Super::BeginPlay(); - World = GetWorld(); - - // assign statics - ADReyeVRSensor::sWorld = World; - ADReyeVRSensor::DReyeVRSensorPtr = this; - - UCarlaGameInstance *CarlaGame = UCarlaStatics::GetGameInstance(World); - SetEpisode(*(CarlaGame->GetCarlaEpisode())); - SetDataStream(CarlaGame->GetServer().OpenStream()); // initialize boost::optional -} - -void ADReyeVRSensor::BeginDestroy() -{ - Super::BeginDestroy(); -} - -void ADReyeVRSensor::PostPhysTick(UWorld *W, ELevelTick TickType, float DeltaSeconds) -{ - /// NOTE: this function defines the routine for streaming data to the PythonAPI - if (!this->bStreamData) // param for enabling or disabling the data streaming - return; - auto Stream = GetDataStream(*this); - - struct // overloaded lambdas to convert UE4 types to carla::geom types - { - carla::geom::Vector3D operator()(const FVector &In) - { - return carla::geom::Vector3D{In.X, In.Y, In.Z}; - }; - carla::geom::Vector3D operator()(const FRotator &In) - { - return carla::geom::Vector3D{In.Pitch, In.Yaw, In.Roll}; - }; - carla::geom::Vector2D operator()(const FVector2D &In) - { - return carla::geom::Vector2D{In.X, In.Y}; - }; - std::string operator()(const FString &In) - { - return carla::rpc::FromFString(In); - }; - } ToGeom; - - /// TODO: refactor this somehow - /// to see where this is sent, see LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h - Stream.Send(*this, - carla::sensor::s11n::DReyeVRSerializer::Data{ - Data->GetTimestampCarla(), // Timestamp of Carla (ms) - Data->GetTimestampDevice(), // Timestamp of SRanipal (ms) - Data->GetFrameSequence(), // Frame sequence - // camera - ToGeom(Data->GetCameraLocation()), // HMD absolute location - ToGeom(Data->GetCameraRotation()), // HMD absolute rotation - // combined gaze - ToGeom(Data->GetGazeDir()), // Combined gaze ray direction - ToGeom(Data->GetGazeOrigin()), // Stream EyeOrigin Vec3 - Data->GetGazeValidity(), // Validity of combined gaze - Data->GetGazeVergence(), // Vergence (float) of combined ray - // left gaze/eye - ToGeom(Data->GetGazeDir(DReyeVR::Gaze::LEFT)), // Left eye gaze ray direction - ToGeom(Data->GetGazeOrigin(DReyeVR::Gaze::LEFT)), // Left eye gaze origin - Data->GetGazeValidity(DReyeVR::Gaze::LEFT), // Validity of left gaze - Data->GetEyeOpenness(DReyeVR::Eye::LEFT), // Left eye openness - Data->GetEyeOpennessValidity(DReyeVR::Eye::LEFT), // Validity of left eye openness - ToGeom(Data->GetPupilPosition(DReyeVR::Eye::LEFT)), // Left pupil position - Data->GetPupilPositionValidity(DReyeVR::Eye::LEFT), // Validity of left eye posn - Data->GetPupilDiameter(DReyeVR::Eye::LEFT), // Left eye diameter (mm) - // right gaze/eye - ToGeom(Data->GetGazeDir(DReyeVR::Gaze::RIGHT)), // Right eye gaze ray direction - ToGeom(Data->GetGazeOrigin(DReyeVR::Gaze::RIGHT)), // Dight eye gaze origin - Data->GetGazeValidity(DReyeVR::Gaze::RIGHT), // Validity of right gaze - Data->GetEyeOpenness(DReyeVR::Eye::RIGHT), // Right eye openness - Data->GetEyeOpennessValidity(DReyeVR::Eye::RIGHT), // Validity of right eye openness - ToGeom(Data->GetPupilPosition(DReyeVR::Eye::RIGHT)), // Right pupil position - Data->GetPupilPositionValidity(DReyeVR::Eye::RIGHT), // Validity of left eye posn - Data->GetPupilDiameter(DReyeVR::Eye::RIGHT), // Right eye diameter (mm) - // focus - ToGeom(Data->GetFocusActorName()), // Focus Actor's name - ToGeom(Data->GetFocusActorPoint()), // Focus Actor's location in world space - Data->GetFocusActorDistance(), // Focus Actor's distance to the sensor - // user inputs - Data->GetUserInputs().Throttle, // Vehicle input throttle - Data->GetUserInputs().Steering, // Vehicle input steering - Data->GetUserInputs().Brake, // Vehicle input brake - Data->GetUserInputs().ToggledReverse, // Vehicle input gear (reverse, fwd) - Data->GetUserInputs().HoldHandbrake // Vehicle input handbrake - }); -} - -void ADReyeVRSensor::UpdateData(const DReyeVR::AggregateData &RecorderData, const double Per) -{ - // update global values - ADReyeVRSensor::bIsReplaying = true; // Replay has started - if (ADReyeVRSensor::Data != nullptr) - { - // update local values but first interpolate camera and vehicle pose (Location & Rotation) - if (Per != 0.0) - { - // interp Camera - FVector NewCameraLoc; - FRotator NewCameraRot; - InterpPositionAndRotation(ADReyeVRSensor::Data->GetCameraLocation(), // old location - ADReyeVRSensor::Data->GetCameraRotation(), // old rotation - RecorderData.GetCameraLocation(), // new location - RecorderData.GetCameraRotation(), // new rotation - Per, NewCameraLoc, NewCameraRot); - // interp Camera (absolute) - FVector NewCameraLocAbs; - FRotator NewCameraRotAbs; - InterpPositionAndRotation(ADReyeVRSensor::Data->GetCameraLocationAbs(), // old location - ADReyeVRSensor::Data->GetCameraRotationAbs(), // old rotation - RecorderData.GetCameraLocationAbs(), // new location - RecorderData.GetCameraRotationAbs(), // new rotation - Per, NewCameraLocAbs, NewCameraRotAbs); - // interp vehicle - FVector NewVehicleLoc; - FRotator NewVehicleRot; - InterpPositionAndRotation(ADReyeVRSensor::Data->GetVehicleLocation(), // old location - ADReyeVRSensor::Data->GetVehicleRotation(), // old rotation - RecorderData.GetVehicleLocation(), // new location - RecorderData.GetVehicleRotation(), // new rotation - Per, NewVehicleLoc, NewVehicleRot); - (*ADReyeVRSensor::Data) = RecorderData; - // update camera positions to the interpolated ones - ADReyeVRSensor::Data->UpdateCamera(NewCameraLoc, NewCameraRot); - ADReyeVRSensor::Data->UpdateCameraAbs(NewCameraLocAbs, NewCameraRotAbs); - ADReyeVRSensor::Data->UpdateVehicle(NewVehicleLoc, NewVehicleRot); - } - else - { - // assign updated DReyeVR data without interpolation - (*ADReyeVRSensor::Data) = RecorderData; - } - } -} - -void ADReyeVRSensor::UpdateData(const class DReyeVR::ConfigFileData &RecorderData, const double Per) -{ - // should be implemented in the EgoSensor (child) impl - unimplemented(); -} - -void ADReyeVRSensor::UpdateData(const class DReyeVR::CustomActorData &RecorderData, const double Per) -{ - // should be implemented in the EgoSensor (child) impl - unimplemented(); -} - -void ADReyeVRSensor::StopReplaying() -{ - ADReyeVRSensor::bIsReplaying = false; -} - -bool ADReyeVRSensor::IsReplaying() const -{ - return ADReyeVRSensor::bIsReplaying; -} - -// smoothly interpolate with Per -void ADReyeVRSensor::InterpPositionAndRotation(const FVector &Pos1, const FRotator &Rot1, const FVector &Pos2, - const FRotator &Rot2, const double Per, FVector &Location, - FRotator &Rotation) -{ - // inspired by CarlaReplayerHelper.cpp:CarlaReplayerHelper::ProcessReplayerPosition - check(Per >= 0.f && Per <= 1.f); - if (Per == 0.0f) // check to assign first position or interpolate between both - { - Location = Pos1; - Rotation = Rot1; - return; - } - Location = FMath::Lerp(Pos1, Pos2, Per); - Rotation = FMath::Lerp(Rot1, Rot2, Per); -} - -// static function to get the DReyeVR sensor -class UWorld *ADReyeVRSensor::sWorld = nullptr; // static world ptr -class ADReyeVRSensor *ADReyeVRSensor::DReyeVRSensorPtr = nullptr; // static "singleton" ptr -class ADReyeVRSensor *ADReyeVRSensor::GetDReyeVRSensor(class UWorld *World) // static getter -{ - // pass in GetWorld() whenever you want the check to be the most up-to-date - if (World != nullptr && World != ADReyeVRSensor::sWorld) - { - // check if the world has been reloaded and we need to refresh our internal pointers - DReyeVR_LOG_WARN("Detected world change! Invalidating cached data"); - ADReyeVRSensor::sWorld = World; - ADReyeVRSensor::DReyeVRSensorPtr = nullptr; - ADReyeVRCustomActor::ActiveCustomActors.clear(); - } - - if (ADReyeVRSensor::DReyeVRSensorPtr == nullptr) // if need to look for DReyeVR sensor in world - { - // need to find the DReyeVR sensor - TArray FoundActors; - if (ADReyeVRSensor::sWorld != nullptr) - { - UGameplayStatics::GetAllActorsOfClass(ADReyeVRSensor::sWorld, ADReyeVRSensor::StaticClass(), FoundActors); - } - if (FoundActors.Num() > 0) - { - /// TODO: check if multiple DReyeVRSensors exist in the world - ADReyeVRSensor::DReyeVRSensorPtr = CastChecked(FoundActors[0]); - ensure(ADReyeVRSensor::DReyeVRSensorPtr != nullptr); - } - if (FoundActors.Num() > 1) - { - DReyeVR_LOG_ERROR("Multiple DReyeVR sensors active in the world! Not supported."); - } - } - - // check if DReyeVR sensor was found - if (ADReyeVRSensor::DReyeVRSensorPtr == nullptr) - { - DReyeVR_LOG_ERROR("No DReyeVRSensor found in the world!"); - } - - return DReyeVRSensorPtr; -} +#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor +#include "Carla.h" // all carla things +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" // MakeGenericSensorDefinition +#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor +#include "Carla/Game/CarlaStatics.h" // GetGameInstance + +#include +#include + +// vector types for serialization +#include "carla/geom/Vector2D.h" +#include "carla/geom/Vector3D.h" +#include "carla/sensor/s11n/DReyeVRSerializer.h" // DReyeVRSerializer::Data + +class DReyeVR::AggregateData *ADReyeVRSensor::Data = nullptr; +class DReyeVR::ConfigFileData *ADReyeVRSensor::ConfigFile = nullptr; +bool ADReyeVRSensor::bIsReplaying = false; // initially not replaying + +ADReyeVRSensor::ADReyeVRSensor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +{ + // no need for any other initialization + PrimaryActorTick.bCanEverTick = true; + if (ADReyeVRSensor::Data == nullptr) + ADReyeVRSensor::Data = new DReyeVR::AggregateData(); + if (ADReyeVRSensor::ConfigFile == nullptr) + ADReyeVRSensor::ConfigFile = new DReyeVR::ConfigFileData(); +} + +FActorDefinition ADReyeVRSensor::GetSensorDefinition() +{ + // What our sensor is going to be called: + auto Definition = UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition(TEXT("dreyevr"), TEXT("sensor_base")); + + /// NOTE: only has EActorAttributeType for bool, int, float, string, and RGBColor + // see /Plugins/Carla/Source/Carla/Actor/ActorAttribute.h for the whole list + + // append all Variable variations to the definition + // Definition.Variations.Append(); + + return Definition; +} + +void ADReyeVRSensor::Set(const FActorDescription &Description) +{ + Super::Set(Description); +} + +void ADReyeVRSensor::SetOwner(AActor *Owner) +{ + Super::SetOwner(Owner); + if (Owner != nullptr) + { + // Set Transform to the same as the Owner + SetActorLocation(Owner->GetActorLocation()); + SetActorRotation(Owner->GetActorRotation()); + } +} + +void ADReyeVRSensor::BeginPlay() +{ + Super::BeginPlay(); + World = GetWorld(); + + // assign statics + ADReyeVRSensor::sWorld = World; + ADReyeVRSensor::DReyeVRSensorPtr = this; + + UCarlaGameInstance *CarlaGame = UCarlaStatics::GetGameInstance(World); + SetEpisode(*(CarlaGame->GetCarlaEpisode())); + SetDataStream(CarlaGame->GetServer().OpenStream()); // initialize boost::optional +} + +void ADReyeVRSensor::BeginDestroy() +{ + Super::BeginDestroy(); +} + +void ADReyeVRSensor::PostPhysTick(UWorld *W, ELevelTick TickType, float DeltaSeconds) +{ + /// NOTE: this function defines the routine for streaming data to the PythonAPI + if (!this->bStreamData) // param for enabling or disabling the data streaming + return; + auto Stream = GetDataStream(*this); + + struct // overloaded lambdas to convert UE4 types to carla::geom types + { + carla::geom::Vector3D operator()(const FVector &In) + { + return carla::geom::Vector3D{In.X, In.Y, In.Z}; + }; + carla::geom::Vector3D operator()(const FRotator &In) + { + return carla::geom::Vector3D{In.Pitch, In.Yaw, In.Roll}; + }; + carla::geom::Vector2D operator()(const FVector2D &In) + { + return carla::geom::Vector2D{In.X, In.Y}; + }; + std::string operator()(const FString &In) + { + return carla::rpc::FromFString(In); + }; + } ToGeom; + + /// TODO: refactor this somehow + /// to see where this is sent, see LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h + Stream.Send(*this, + carla::sensor::s11n::DReyeVRSerializer::Data{ + Data->GetTimestampCarla(), // Timestamp of Carla (ms) + Data->GetTimestampDevice(), // Timestamp of SRanipal (ms) + Data->GetFrameSequence(), // Frame sequence + // camera + ToGeom(Data->GetCameraLocation()), // HMD absolute location + ToGeom(Data->GetCameraRotation()), // HMD absolute rotation + // combined gaze + ToGeom(Data->GetGazeDir()), // Combined gaze ray direction + ToGeom(Data->GetGazeOrigin()), // Stream EyeOrigin Vec3 + Data->GetGazeValidity(), // Validity of combined gaze + Data->GetGazeVergence(), // Vergence (float) of combined ray + // left gaze/eye + ToGeom(Data->GetGazeDir(DReyeVR::Gaze::LEFT)), // Left eye gaze ray direction + ToGeom(Data->GetGazeOrigin(DReyeVR::Gaze::LEFT)), // Left eye gaze origin + Data->GetGazeValidity(DReyeVR::Gaze::LEFT), // Validity of left gaze + Data->GetEyeOpenness(DReyeVR::Eye::LEFT), // Left eye openness + Data->GetEyeOpennessValidity(DReyeVR::Eye::LEFT), // Validity of left eye openness + ToGeom(Data->GetPupilPosition(DReyeVR::Eye::LEFT)), // Left pupil position + Data->GetPupilPositionValidity(DReyeVR::Eye::LEFT), // Validity of left eye posn + Data->GetPupilDiameter(DReyeVR::Eye::LEFT), // Left eye diameter (mm) + // right gaze/eye + ToGeom(Data->GetGazeDir(DReyeVR::Gaze::RIGHT)), // Right eye gaze ray direction + ToGeom(Data->GetGazeOrigin(DReyeVR::Gaze::RIGHT)), // Dight eye gaze origin + Data->GetGazeValidity(DReyeVR::Gaze::RIGHT), // Validity of right gaze + Data->GetEyeOpenness(DReyeVR::Eye::RIGHT), // Right eye openness + Data->GetEyeOpennessValidity(DReyeVR::Eye::RIGHT), // Validity of right eye openness + ToGeom(Data->GetPupilPosition(DReyeVR::Eye::RIGHT)), // Right pupil position + Data->GetPupilPositionValidity(DReyeVR::Eye::RIGHT), // Validity of left eye posn + Data->GetPupilDiameter(DReyeVR::Eye::RIGHT), // Right eye diameter (mm) + // focus + ToGeom(Data->GetFocusActorName()), // Focus Actor's name + ToGeom(Data->GetFocusActorPoint()), // Focus Actor's location in world space + Data->GetFocusActorDistance(), // Focus Actor's distance to the sensor + // user inputs + Data->GetUserInputs().Throttle, // Vehicle input throttle + Data->GetUserInputs().Steering, // Vehicle input steering + Data->GetUserInputs().Brake, // Vehicle input brake + Data->GetUserInputs().ToggledReverse, // Vehicle input gear (reverse, fwd) + Data->GetUserInputs().HoldHandbrake // Vehicle input handbrake + }); +} + +void ADReyeVRSensor::UpdateData(const DReyeVR::AggregateData &RecorderData, const double Per) +{ + // update global values + ADReyeVRSensor::bIsReplaying = true; // Replay has started + if (ADReyeVRSensor::Data != nullptr) + { + // update local values but first interpolate camera and vehicle pose (Location & Rotation) + if (Per != 0.0) + { + // interp Camera + FVector NewCameraLoc; + FRotator NewCameraRot; + InterpPositionAndRotation(ADReyeVRSensor::Data->GetCameraLocation(), // old location + ADReyeVRSensor::Data->GetCameraRotation(), // old rotation + RecorderData.GetCameraLocation(), // new location + RecorderData.GetCameraRotation(), // new rotation + Per, NewCameraLoc, NewCameraRot); + // interp Camera (absolute) + FVector NewCameraLocAbs; + FRotator NewCameraRotAbs; + InterpPositionAndRotation(ADReyeVRSensor::Data->GetCameraLocationAbs(), // old location + ADReyeVRSensor::Data->GetCameraRotationAbs(), // old rotation + RecorderData.GetCameraLocationAbs(), // new location + RecorderData.GetCameraRotationAbs(), // new rotation + Per, NewCameraLocAbs, NewCameraRotAbs); + // interp vehicle + FVector NewVehicleLoc; + FRotator NewVehicleRot; + InterpPositionAndRotation(ADReyeVRSensor::Data->GetVehicleLocation(), // old location + ADReyeVRSensor::Data->GetVehicleRotation(), // old rotation + RecorderData.GetVehicleLocation(), // new location + RecorderData.GetVehicleRotation(), // new rotation + Per, NewVehicleLoc, NewVehicleRot); + (*ADReyeVRSensor::Data) = RecorderData; + // update camera positions to the interpolated ones + ADReyeVRSensor::Data->UpdateCamera(NewCameraLoc, NewCameraRot); + ADReyeVRSensor::Data->UpdateCameraAbs(NewCameraLocAbs, NewCameraRotAbs); + ADReyeVRSensor::Data->UpdateVehicle(NewVehicleLoc, NewVehicleRot); + } + else + { + // assign updated DReyeVR data without interpolation + (*ADReyeVRSensor::Data) = RecorderData; + } + } +} + +void ADReyeVRSensor::UpdateData(const class DReyeVR::ConfigFileData &RecorderData, const double Per) +{ + // should be implemented in the EgoSensor (child) impl + unimplemented(); +} + +void ADReyeVRSensor::UpdateData(const class DReyeVR::CustomActorData &RecorderData, const double Per) +{ + // should be implemented in the EgoSensor (child) impl + unimplemented(); +} + +void ADReyeVRSensor::StopReplaying() +{ + ADReyeVRSensor::bIsReplaying = false; +} + +bool ADReyeVRSensor::IsReplaying() const +{ + return ADReyeVRSensor::bIsReplaying; +} + +// smoothly interpolate with Per +void ADReyeVRSensor::InterpPositionAndRotation(const FVector &Pos1, const FRotator &Rot1, const FVector &Pos2, + const FRotator &Rot2, const double Per, FVector &Location, + FRotator &Rotation) +{ + // inspired by CarlaReplayerHelper.cpp:CarlaReplayerHelper::ProcessReplayerPosition + check(Per >= 0.f && Per <= 1.f); + if (Per == 0.0f) // check to assign first position or interpolate between both + { + Location = Pos1; + Rotation = Rot1; + return; + } + Location = FMath::Lerp(Pos1, Pos2, Per); + Rotation = FMath::Lerp(Rot1, Rot2, Per); +} + +// static function to get the DReyeVR sensor +class UWorld *ADReyeVRSensor::sWorld = nullptr; // static world ptr +class ADReyeVRSensor *ADReyeVRSensor::DReyeVRSensorPtr = nullptr; // static "singleton" ptr +class ADReyeVRSensor *ADReyeVRSensor::GetDReyeVRSensor(class UWorld *World) // static getter +{ + // pass in GetWorld() whenever you want the check to be the most up-to-date + if (World != nullptr && World != ADReyeVRSensor::sWorld) + { + // check if the world has been reloaded and we need to refresh our internal pointers + DReyeVR_LOG_WARN("Detected world change! Invalidating cached data"); + ADReyeVRSensor::sWorld = World; + ADReyeVRSensor::DReyeVRSensorPtr = nullptr; + ADReyeVRCustomActor::ActiveCustomActors.clear(); + } + + if (ADReyeVRSensor::DReyeVRSensorPtr == nullptr) // if need to look for DReyeVR sensor in world + { + // need to find the DReyeVR sensor + TArray FoundActors; + if (ADReyeVRSensor::sWorld != nullptr) + { + UGameplayStatics::GetAllActorsOfClass(ADReyeVRSensor::sWorld, ADReyeVRSensor::StaticClass(), FoundActors); + } + if (FoundActors.Num() > 0) + { + /// TODO: check if multiple DReyeVRSensors exist in the world + ADReyeVRSensor::DReyeVRSensorPtr = CastChecked(FoundActors[0]); + ensure(ADReyeVRSensor::DReyeVRSensorPtr != nullptr); + } + if (FoundActors.Num() > 1) + { + DReyeVR_LOG_ERROR("Multiple DReyeVR sensors active in the world! Not supported."); + } + } + + // check if DReyeVR sensor was found + if (ADReyeVRSensor::DReyeVRSensorPtr == nullptr) + { + DReyeVR_LOG_ERROR("No DReyeVRSensor found in the world!"); + } + + return DReyeVRSensorPtr; +} diff --git a/Carla/Sensor/DReyeVRSensor.h b/Carla/Sensor/DReyeVRSensor.h index 7edef65..2032b07 100644 --- a/Carla/Sensor/DReyeVRSensor.h +++ b/Carla/Sensor/DReyeVRSensor.h @@ -1,75 +1,75 @@ -#pragma once - -#include "Carla/Actor/ActorDefinition.h" // FActorDefinition -#include "Carla/Actor/ActorDescription.h" // FActorDescription -#include "Carla/Game/CarlaEpisode.h" // UCarlaEpisode -#include "Carla/Sensor/Sensor.h" // ASensor -#include "DReyeVRData.h" // AggregateData, CustomActorData -#include // int64_t -#include -#include - -#include "DReyeVRSensor.generated.h" - -class UCarlaEpisode; - -UCLASS() -class CARLA_API ADReyeVRSensor : public ASensor -{ - GENERATED_BODY() - - public: - ADReyeVRSensor(const FObjectInitializer &ObjectInitializer); - - static FActorDefinition GetSensorDefinition(); - - void Set(const FActorDescription &ActorDescription) override; - - void SetOwner(AActor *Owner) override; - - virtual void PostPhysTick(UWorld *W, ELevelTick TickType, float DeltaSeconds) override; - - // everything stored in the sensor is held in this struct - /// TODO: make this non-static and use a smarter scheme for cross-class communication - static class DReyeVR::AggregateData *Data; - static class DReyeVR::ConfigFileData *ConfigFile; - - class DReyeVR::AggregateData *GetData() - { - return ADReyeVRSensor::Data; - } - - const class DReyeVR::AggregateData *GetData() const - { - // read-only variant of GetData - return const_cast(ADReyeVRSensor::Data); - } - - bool IsReplaying() const; - virtual void UpdateData(const class DReyeVR::AggregateData &RecorderData, const double Per); // starts replaying - virtual void UpdateData(const class DReyeVR::ConfigFileData &RecorderData, const double Per); - virtual void UpdateData(const class DReyeVR::CustomActorData &RecorderData, const double Per); - void StopReplaying(); - virtual void TakeScreenshot() - { - /// TODO: make this a pure virtual function (abstract class) - DReyeVR_LOG_WARN("Not implemented! Implement in EgoSensor!"); - }; - - static class ADReyeVRSensor *GetDReyeVRSensor(class UWorld *World = nullptr); - static bool bIsReplaying; - - protected: - void BeginPlay() override; - void BeginDestroy() override; - - class UWorld *World; - static class UWorld *sWorld; // to get info about the world: time, frames, etc. - - bool bStreamData = true; - - static class ADReyeVRSensor *DReyeVRSensorPtr; - static void InterpPositionAndRotation(const FVector &Pos1, const FRotator &Rot1, const FVector &Pos2, - const FRotator &Rot2, const double Per, FVector &Location, - FRotator &Rotation); +#pragma once + +#include "Carla/Actor/ActorDefinition.h" // FActorDefinition +#include "Carla/Actor/ActorDescription.h" // FActorDescription +#include "Carla/Game/CarlaEpisode.h" // UCarlaEpisode +#include "Carla/Sensor/Sensor.h" // ASensor +#include "DReyeVRData.h" // AggregateData, CustomActorData +#include // int64_t +#include +#include + +#include "DReyeVRSensor.generated.h" + +class UCarlaEpisode; + +UCLASS() +class CARLA_API ADReyeVRSensor : public ASensor +{ + GENERATED_BODY() + + public: + ADReyeVRSensor(const FObjectInitializer &ObjectInitializer); + + static FActorDefinition GetSensorDefinition(); + + void Set(const FActorDescription &ActorDescription) override; + + void SetOwner(AActor *Owner) override; + + virtual void PostPhysTick(UWorld *W, ELevelTick TickType, float DeltaSeconds) override; + + // everything stored in the sensor is held in this struct + /// TODO: make this non-static and use a smarter scheme for cross-class communication + static class DReyeVR::AggregateData *Data; + static class DReyeVR::ConfigFileData *ConfigFile; + + class DReyeVR::AggregateData *GetData() + { + return ADReyeVRSensor::Data; + } + + const class DReyeVR::AggregateData *GetData() const + { + // read-only variant of GetData + return const_cast(ADReyeVRSensor::Data); + } + + bool IsReplaying() const; + virtual void UpdateData(const class DReyeVR::AggregateData &RecorderData, const double Per); // starts replaying + virtual void UpdateData(const class DReyeVR::ConfigFileData &RecorderData, const double Per); + virtual void UpdateData(const class DReyeVR::CustomActorData &RecorderData, const double Per); + void StopReplaying(); + virtual void TakeScreenshot() + { + /// TODO: make this a pure virtual function (abstract class) + DReyeVR_LOG_WARN("Not implemented! Implement in EgoSensor!"); + }; + + static class ADReyeVRSensor *GetDReyeVRSensor(class UWorld *World = nullptr); + static bool bIsReplaying; + + protected: + void BeginPlay() override; + void BeginDestroy() override; + + class UWorld *World; + static class UWorld *sWorld; // to get info about the world: time, frames, etc. + + bool bStreamData = true; + + static class ADReyeVRSensor *DReyeVRSensorPtr; + static void InterpPositionAndRotation(const FVector &Pos1, const FRotator &Rot1, const FVector &Pos2, + const FRotator &Rot2, const double Per, FVector &Location, + FRotator &Rotation); }; \ No newline at end of file diff --git a/Carla/Settings/CarlaSettingsDelegate.cpp b/Carla/Settings/CarlaSettingsDelegate.cpp index 9deb600..b726da1 100644 --- a/Carla/Settings/CarlaSettingsDelegate.cpp +++ b/Carla/Settings/CarlaSettingsDelegate.cpp @@ -1,451 +1,451 @@ -#include "Carla.h" -#include "Carla/Settings/CarlaSettingsDelegate.h" - -#include "Carla/Settings/CarlaSettings.h" - -#include "Async.h" -#include "Components/StaticMeshComponent.h" -#include "Engine/DirectionalLight.h" -#include "Engine/Engine.h" -#include "Engine/LocalPlayer.h" -#include "Engine/PostProcessVolume.h" -#include "Engine/StaticMesh.h" -#include "GameFramework/HUD.h" -#include "InstancedFoliageActor.h" -#include "Kismet/GameplayStatics.h" -#include "Landscape.h" -#include "Scalability.h" - - -static constexpr float CARLA_SETTINGS_MAX_SCALE_SIZE = 50.0f; - -/// quality settings configuration between runs -EQualityLevel UCarlaSettingsDelegate::AppliedLowPostResetQualityLevel = EQualityLevel::Epic; - -UCarlaSettingsDelegate::UCarlaSettingsDelegate() - : ActorSpawnedDelegate(FOnActorSpawned::FDelegate::CreateUObject( - this, - &UCarlaSettingsDelegate::OnActorSpawned)) {} - -void UCarlaSettingsDelegate::Reset() -{ - AppliedLowPostResetQualityLevel = EQualityLevel::Epic; -} - -void UCarlaSettingsDelegate::RegisterSpawnHandler(UWorld *InWorld) -{ - CheckCarlaSettings(InWorld); - InWorld->AddOnActorSpawnedHandler(ActorSpawnedDelegate); -} - -void UCarlaSettingsDelegate::OnActorSpawned(AActor *InActor) -{ - check(CarlaSettings != nullptr); - if (InActor != nullptr && IsValid(InActor) && !InActor->IsPendingKill() && - !InActor->IsA() && // foliage culling is - // controlled per instance - !InActor->IsA() && // dont touch landscapes nor roads - !InActor->ActorHasTag(UCarlaSettings::CARLA_ROAD_TAG) && - !InActor->ActorHasTag(UCarlaSettings::CARLA_SKY_TAG)) - { - TArray components; - InActor->GetComponents(components); - switch (CarlaSettings->GetQualityLevel()) - { - case EQualityLevel::Low: { - // apply settings for this actor for the current quality level - float dist = CarlaSettings->LowStaticMeshMaxDrawDistance; - const float maxscale = InActor->GetActorScale().GetMax(); - if (maxscale > CARLA_SETTINGS_MAX_SCALE_SIZE) - { - dist *= 100.0f; - } - SetActorComponentsDrawDistance(InActor, dist); - break; - } - default: break; - } - } -} - -void UCarlaSettingsDelegate::ApplyQualityLevelPostRestart() -{ - CheckCarlaSettings(nullptr); - UWorld *InWorld = CarlaSettings->GetWorld(); - - const EQualityLevel QualityLevel = CarlaSettings->GetQualityLevel(); - - if (AppliedLowPostResetQualityLevel == QualityLevel) - { - return; - } - - // enable temporal changes of quality (prevent saving last quality settings to file) - Scalability::ToggleTemporaryQualityLevels(true); - - switch (QualityLevel) - { - case EQualityLevel::Low: - { - // execute tweaks for quality - LaunchLowQualityCommands(InWorld); - // iterate all directional lights, deactivate shadows - SetAllLights(InWorld, CarlaSettings->LowLightFadeDistance, false, true); - // Set all the roads the low quality materials - SetAllRoads(InWorld, CarlaSettings->LowRoadPieceMeshMaxDrawDistance, CarlaSettings->LowRoadMaterials); - // Set all actors with static meshes a max distance configured in the - // global settings for the low quality - // SetAllActorsDrawDistance(InWorld, CarlaSettings->LowStaticMeshMaxDrawDistance); - SetAllActorsDrawDistance(InWorld, 0); // full render distance - // Disable all post process volumes - SetPostProcessEffectsEnabled(InWorld, false); - break; - } - default: - UE_LOG(LogCarla, Warning, TEXT("Unknown quality level, falling back to default.")); - case EQualityLevel::Epic: - { - LaunchEpicQualityCommands(InWorld); - SetAllLights(InWorld, 0.0f, true, false); - SetAllRoads(InWorld, 0, CarlaSettings->EpicRoadMaterials); - SetAllActorsDrawDistance(InWorld, 0); - SetPostProcessEffectsEnabled(InWorld, true); - break; - } - } - AppliedLowPostResetQualityLevel = QualityLevel; -} - -void UCarlaSettingsDelegate::ApplyQualityLevelPreRestart() -{ - CheckCarlaSettings(nullptr); - UWorld *InWorld = CarlaSettings->GetWorld(); - if (!IsValid(InWorld) || InWorld->IsPendingKill()) - { - return; - } - // enable or disable world and hud rendering - APlayerController *playercontroller = UGameplayStatics::GetPlayerController(InWorld, 0); - if (playercontroller) - { - ULocalPlayer *player = playercontroller->GetLocalPlayer(); - if (player) - { - player->ViewportClient->bDisableWorldRendering = CarlaSettings->bDisableRendering; - } - // if we already have a hud class: - AHUD *hud = playercontroller->GetHUD(); - if (hud) - { - hud->bShowHUD = !CarlaSettings->bDisableRendering; - } - } - -} - -UWorld *UCarlaSettingsDelegate::GetLocalWorld() -{ - return GEngine->GetWorldFromContextObjectChecked(this); -} - -void UCarlaSettingsDelegate::CheckCarlaSettings(UWorld *world) -{ - if (IsValid(CarlaSettings)) - { - return; - } - if (world == nullptr || !IsValid(world) || world->IsPendingKill()) - { - world = GetLocalWorld(); - } - check(world != nullptr); - auto GameInstance = Cast(world->GetGameInstance()); - check(GameInstance != nullptr); - CarlaSettings = &GameInstance->GetCarlaSettings(); - check(CarlaSettings != nullptr); -} - -void UCarlaSettingsDelegate::LaunchLowQualityCommands(UWorld *world) const -{ - if (!world) - { - return; - } - - // launch commands to lower quality settings - GEngine->Exec(world, TEXT("r.DefaultFeature.MotionBlur 0")); - GEngine->Exec(world, TEXT("r.DefaultFeature.Bloom 0")); - GEngine->Exec(world, TEXT("r.DefaultFeature.AmbientOcclusion 0")); - GEngine->Exec(world, TEXT("r.AmbientOcclusionLevels 0")); - GEngine->Exec(world, TEXT("r.DefaultFeature.AmbientOcclusionStaticFraction 0")); - GEngine->Exec(world, TEXT("r.RHICmdBypass 0")); - GEngine->Exec(world, TEXT("r.DefaultFeature.AntiAliasing 1")); - GEngine->Exec(world, TEXT("r.Streaming.PoolSize 2000")); - GEngine->Exec(world, TEXT("r.HZBOcclusion 0")); - GEngine->Exec(world, TEXT("r.MinScreenRadiusForLights 0.01")); - GEngine->Exec(world, TEXT("r.SeparateTranslucency 0")); - GEngine->Exec(world, TEXT("r.FinishCurrentFrame 0")); - GEngine->Exec(world, TEXT("r.MotionBlurQuality 0")); - GEngine->Exec(world, TEXT("r.PostProcessAAQuality 0")); - GEngine->Exec(world, TEXT("r.BloomQuality 1")); - GEngine->Exec(world, TEXT("r.SSR.Quality 0")); - GEngine->Exec(world, TEXT("r.DepthOfFieldQuality 0")); - GEngine->Exec(world, TEXT("r.SceneColorFormat 2")); - GEngine->Exec(world, TEXT("r.TranslucencyVolumeBlur 0")); - GEngine->Exec(world, TEXT("r.TranslucencyLightingVolumeDim 4")); - GEngine->Exec(world, TEXT("r.MaxAnisotropy 8")); - GEngine->Exec(world, TEXT("r.LensFlareQuality 0")); - GEngine->Exec(world, TEXT("r.SceneColorFringeQuality 0")); - GEngine->Exec(world, TEXT("r.FastBlurThreshold 0")); - GEngine->Exec(world, TEXT("r.SSR.MaxRoughness 0.1")); - GEngine->Exec(world, TEXT("r.AllowOcclusionQueries 1")); - GEngine->Exec(world, TEXT("r.SSR 0")); - // GEngine->Exec(world,TEXT("r.StencilForLODDither 1")); //readonly - GEngine->Exec(world, TEXT("r.EarlyZPass 2")); // transparent before opaque - GEngine->Exec(world, TEXT("r.EarlyZPassMovable 1")); - GEngine->Exec(world, TEXT("Foliage.DitheredLOD 0")); - // GEngine->Exec(world,TEXT("r.ForwardShading 0")); //readonly - GEngine->Exec(world, TEXT("sg.PostProcessQuality 0")); - // GEngine->Exec(world,TEXT("r.ViewDistanceScale 0.1")); //--> too extreme - // (far clip too short) - GEngine->Exec(world, TEXT("sg.ShadowQuality 0")); - GEngine->Exec(world, TEXT("sg.TextureQuality 0")); - GEngine->Exec(world, TEXT("sg.EffectsQuality 0")); - GEngine->Exec(world, TEXT("sg.FoliageQuality 0")); - GEngine->Exec(world, TEXT("foliage.DensityScale 0")); - GEngine->Exec(world, TEXT("grass.DensityScale 0")); - GEngine->Exec(world, TEXT("r.TranslucentLightingVolume 0")); - GEngine->Exec(world, TEXT("r.LightShaftDownSampleFactor 4")); - GEngine->Exec(world, TEXT("r.OcclusionQueryLocation 1")); - // GEngine->Exec(world,TEXT("r.BasePassOutputsVelocity 0")); //--> readonly - // GEngine->Exec(world,TEXT("r.DetailMode 0")); //-->will change to lods 0 - GEngine->Exec(world, TEXT("r.DefaultFeature.AutoExposure 1")); - -} - -void UCarlaSettingsDelegate::SetAllRoads( - UWorld *world, - const float max_draw_distance, - const TArray &road_pieces_materials) const -{ - if (!world || !IsValid(world) || world->IsPendingKill()) - { - return; - } - AsyncTask(ENamedThreads::GameThread, [=]() { - if (!world || !IsValid(world) || world->IsPendingKill()) - { - return; - } - TArray actors; - UGameplayStatics::GetAllActorsWithTag(world, UCarlaSettings::CARLA_ROAD_TAG, actors); - - for (int32 i = 0; i < actors.Num(); i++) - { - AActor *actor = actors[i]; - if (!IsValid(actor) || actor->IsPendingKill()) - { - continue; - } - TArray components; - actor->GetComponents(components); - for (int32 j = 0; j < components.Num(); j++) - { - UStaticMeshComponent *staticmeshcomponent = Cast(components[j]); - if (staticmeshcomponent) - { - staticmeshcomponent->bAllowCullDistanceVolume = (max_draw_distance > 0); - staticmeshcomponent->bUseAsOccluder = false; - staticmeshcomponent->LDMaxDrawDistance = max_draw_distance; - staticmeshcomponent->CastShadow = (max_draw_distance == 0); - if (road_pieces_materials.Num() > 0) - { - TArray meshslotsnames = staticmeshcomponent->GetMaterialSlotNames(); - for (int32 k = 0; k < meshslotsnames.Num(); k++) - { - const FName &slotname = meshslotsnames[k]; - road_pieces_materials.ContainsByPredicate( - [staticmeshcomponent, slotname](const FStaticMaterial &material) - { - if (material.MaterialSlotName.IsEqual(slotname)) - { - staticmeshcomponent->SetMaterial( - staticmeshcomponent->GetMaterialIndex(slotname), - material.MaterialInterface); - return true; - } - else - { - return false; - } - }); - } - } - } - } - } - }); // ,DELAY_TIME_TO_SET_ALL_ROADS, false); -} - -void UCarlaSettingsDelegate::SetActorComponentsDrawDistance( - AActor *actor, - const float max_draw_distance) const -{ - if (!actor) - { - return; - } - TArray components; - actor->GetComponents(components, false); - float dist = max_draw_distance; - const float maxscale = actor->GetActorScale().GetMax(); - if (maxscale > CARLA_SETTINGS_MAX_SCALE_SIZE) - { - dist *= 100.0f; - } - for (int32 j = 0; j < components.Num(); j++) - { - UPrimitiveComponent *primitivecomponent = Cast(components[j]); - if (IsValid(primitivecomponent)) - { - primitivecomponent->SetCullDistance(dist); - primitivecomponent->bAllowCullDistanceVolume = dist > 0; - } - } -} - -void UCarlaSettingsDelegate::SetAllActorsDrawDistance(UWorld *world, const float max_draw_distance) const -{ - /// @TODO: use semantics to grab all actors by type - /// (vehicles,ground,people,props) and set different distances configured in - /// the global properties - if (!world || !IsValid(world) || world->IsPendingKill()) - { - return; - } - AsyncTask(ENamedThreads::GameThread, [=]() { - if (!world || !IsValid(world) || world->IsPendingKill()) - { - return; - } - TArray actors; - // set the lower quality - max draw distance - UGameplayStatics::GetAllActorsOfClass(world, AActor::StaticClass(), actors); - for (int32 i = 0; i < actors.Num(); i++) - { - AActor *actor = actors[i]; - if (!IsValid(actor) || actor->IsPendingKill() || - actor->IsA() || // foliage culling is controlled - // per instance - actor->IsA() || // dont touch landscapes nor roads - actor->ActorHasTag(UCarlaSettings::CARLA_ROAD_TAG) || - actor->ActorHasTag(UCarlaSettings::CARLA_SKY_TAG)) - { - continue; - } - SetActorComponentsDrawDistance(actor, max_draw_distance); - } - }); -} - -void UCarlaSettingsDelegate::SetPostProcessEffectsEnabled(UWorld *world, const bool enabled) const -{ - TArray actors; - UGameplayStatics::GetAllActorsOfClass(world, APostProcessVolume::StaticClass(), actors); - for (int32 i = 0; i < actors.Num(); i++) - { - AActor *actor = actors[i]; - if (!IsValid(actor) || actor->IsPendingKill()) - { - continue; - } - APostProcessVolume *postprocessvolume = Cast(actor); - if (postprocessvolume) - { - postprocessvolume->bEnabled = enabled; - } - } -} - -void UCarlaSettingsDelegate::LaunchEpicQualityCommands(UWorld *world) const -{ - if (!world) - { - return; - } - - GEngine->Exec(world, TEXT("r.AmbientOcclusionLevels -1")); - GEngine->Exec(world, TEXT("r.RHICmdBypass 1")); - GEngine->Exec(world, TEXT("r.DefaultFeature.AntiAliasing 1")); - GEngine->Exec(world, TEXT("r.Streaming.PoolSize 2000")); - GEngine->Exec(world, TEXT("r.MinScreenRadiusForLights 0.03")); - GEngine->Exec(world, TEXT("r.SeparateTranslucency 1")); - GEngine->Exec(world, TEXT("r.PostProcessAAQuality 4")); - GEngine->Exec(world, TEXT("r.BloomQuality 5")); - GEngine->Exec(world, TEXT("r.SSR.Quality 3")); - GEngine->Exec(world, TEXT("r.DepthOfFieldQuality 2")); - GEngine->Exec(world, TEXT("r.SceneColorFormat 4")); - GEngine->Exec(world, TEXT("r.TranslucencyVolumeBlur 1")); - GEngine->Exec(world, TEXT("r.TranslucencyLightingVolumeDim 64")); - GEngine->Exec(world, TEXT("r.MaxAnisotropy 8")); - GEngine->Exec(world, TEXT("r.LensFlareQuality 2")); - GEngine->Exec(world, TEXT("r.SceneColorFringeQuality 1")); - GEngine->Exec(world, TEXT("r.FastBlurThreshold 100")); - GEngine->Exec(world, TEXT("r.SSR.MaxRoughness -1")); - // GEngine->Exec(world,TEXT("r.StencilForLODDither 0")); //readonly - GEngine->Exec(world, TEXT("r.EarlyZPass 3")); - GEngine->Exec(world, TEXT("r.EarlyZPassMovable 1")); - GEngine->Exec(world, TEXT("Foliage.DitheredLOD 1")); - GEngine->Exec(world, TEXT("sg.PostProcessQuality 3")); - GEngine->Exec(world, TEXT("r.ViewDistanceScale 1")); // --> too extreme (far - // clip too short) - GEngine->Exec(world, TEXT("sg.ShadowQuality 3")); - GEngine->Exec(world, TEXT("sg.TextureQuality 3")); - GEngine->Exec(world, TEXT("sg.EffectsQuality 3")); - GEngine->Exec(world, TEXT("sg.FoliageQuality 3")); - GEngine->Exec(world, TEXT("foliage.DensityScale 1")); - GEngine->Exec(world, TEXT("grass.DensityScale 1")); - GEngine->Exec(world, TEXT("r.TranslucentLightingVolume 1")); - GEngine->Exec(world, TEXT("r.LightShaftDownSampleFactor 2")); - // GEngine->Exec(world,TEXT("r.OcclusionQueryLocation 0")); - // GEngine->Exec(world,TEXT("r.BasePassOutputsVelocity 0")); //readonly - GEngine->Exec(world, TEXT("r.DetailMode 2")); -} - -void UCarlaSettingsDelegate::SetAllLights( - UWorld *world, - const float max_distance_fade, - const bool cast_shadows, - const bool hide_non_directional) const -{ - if (!world || !IsValid(world) || world->IsPendingKill()) - { - return; - } - AsyncTask(ENamedThreads::GameThread, [=]() { - if (!world || !IsValid(world) || world->IsPendingKill()) - { - return; - } - TArray actors; - UGameplayStatics::GetAllActorsOfClass(world, ALight::StaticClass(), actors); - for (int32 i = 0; i < actors.Num(); i++) - { - if (!IsValid(actors[i]) || actors[i]->IsPendingKill()) - { - continue; - } - // tweak directional lights - ADirectionalLight *directionallight = Cast(actors[i]); - if (directionallight) - { - directionallight->SetCastShadows(cast_shadows); - directionallight->SetLightFunctionFadeDistance(max_distance_fade); - continue; - } - // disable any other type of light - actors[i]->SetActorHiddenInGame(hide_non_directional); - } - }); - -} +#include "Carla.h" +#include "Carla/Settings/CarlaSettingsDelegate.h" + +#include "Carla/Settings/CarlaSettings.h" + +#include "Async.h" +#include "Components/StaticMeshComponent.h" +#include "Engine/DirectionalLight.h" +#include "Engine/Engine.h" +#include "Engine/LocalPlayer.h" +#include "Engine/PostProcessVolume.h" +#include "Engine/StaticMesh.h" +#include "GameFramework/HUD.h" +#include "InstancedFoliageActor.h" +#include "Kismet/GameplayStatics.h" +#include "Landscape.h" +#include "Scalability.h" + + +static constexpr float CARLA_SETTINGS_MAX_SCALE_SIZE = 50.0f; + +/// quality settings configuration between runs +EQualityLevel UCarlaSettingsDelegate::AppliedLowPostResetQualityLevel = EQualityLevel::Epic; + +UCarlaSettingsDelegate::UCarlaSettingsDelegate() + : ActorSpawnedDelegate(FOnActorSpawned::FDelegate::CreateUObject( + this, + &UCarlaSettingsDelegate::OnActorSpawned)) {} + +void UCarlaSettingsDelegate::Reset() +{ + AppliedLowPostResetQualityLevel = EQualityLevel::Epic; +} + +void UCarlaSettingsDelegate::RegisterSpawnHandler(UWorld *InWorld) +{ + CheckCarlaSettings(InWorld); + InWorld->AddOnActorSpawnedHandler(ActorSpawnedDelegate); +} + +void UCarlaSettingsDelegate::OnActorSpawned(AActor *InActor) +{ + check(CarlaSettings != nullptr); + if (InActor != nullptr && IsValid(InActor) && !InActor->IsPendingKill() && + !InActor->IsA() && // foliage culling is + // controlled per instance + !InActor->IsA() && // dont touch landscapes nor roads + !InActor->ActorHasTag(UCarlaSettings::CARLA_ROAD_TAG) && + !InActor->ActorHasTag(UCarlaSettings::CARLA_SKY_TAG)) + { + TArray components; + InActor->GetComponents(components); + switch (CarlaSettings->GetQualityLevel()) + { + case EQualityLevel::Low: { + // apply settings for this actor for the current quality level + float dist = CarlaSettings->LowStaticMeshMaxDrawDistance; + const float maxscale = InActor->GetActorScale().GetMax(); + if (maxscale > CARLA_SETTINGS_MAX_SCALE_SIZE) + { + dist *= 100.0f; + } + SetActorComponentsDrawDistance(InActor, dist); + break; + } + default: break; + } + } +} + +void UCarlaSettingsDelegate::ApplyQualityLevelPostRestart() +{ + CheckCarlaSettings(nullptr); + UWorld *InWorld = CarlaSettings->GetWorld(); + + const EQualityLevel QualityLevel = CarlaSettings->GetQualityLevel(); + + if (AppliedLowPostResetQualityLevel == QualityLevel) + { + return; + } + + // enable temporal changes of quality (prevent saving last quality settings to file) + Scalability::ToggleTemporaryQualityLevels(true); + + switch (QualityLevel) + { + case EQualityLevel::Low: + { + // execute tweaks for quality + LaunchLowQualityCommands(InWorld); + // iterate all directional lights, deactivate shadows + SetAllLights(InWorld, CarlaSettings->LowLightFadeDistance, false, true); + // Set all the roads the low quality materials + SetAllRoads(InWorld, CarlaSettings->LowRoadPieceMeshMaxDrawDistance, CarlaSettings->LowRoadMaterials); + // Set all actors with static meshes a max distance configured in the + // global settings for the low quality + // SetAllActorsDrawDistance(InWorld, CarlaSettings->LowStaticMeshMaxDrawDistance); + SetAllActorsDrawDistance(InWorld, 0); // full render distance + // Disable all post process volumes + SetPostProcessEffectsEnabled(InWorld, false); + break; + } + default: + UE_LOG(LogCarla, Warning, TEXT("Unknown quality level, falling back to default.")); + case EQualityLevel::Epic: + { + LaunchEpicQualityCommands(InWorld); + SetAllLights(InWorld, 0.0f, true, false); + SetAllRoads(InWorld, 0, CarlaSettings->EpicRoadMaterials); + SetAllActorsDrawDistance(InWorld, 0); + SetPostProcessEffectsEnabled(InWorld, true); + break; + } + } + AppliedLowPostResetQualityLevel = QualityLevel; +} + +void UCarlaSettingsDelegate::ApplyQualityLevelPreRestart() +{ + CheckCarlaSettings(nullptr); + UWorld *InWorld = CarlaSettings->GetWorld(); + if (!IsValid(InWorld) || InWorld->IsPendingKill()) + { + return; + } + // enable or disable world and hud rendering + APlayerController *playercontroller = UGameplayStatics::GetPlayerController(InWorld, 0); + if (playercontroller) + { + ULocalPlayer *player = playercontroller->GetLocalPlayer(); + if (player) + { + player->ViewportClient->bDisableWorldRendering = CarlaSettings->bDisableRendering; + } + // if we already have a hud class: + AHUD *hud = playercontroller->GetHUD(); + if (hud) + { + hud->bShowHUD = !CarlaSettings->bDisableRendering; + } + } + +} + +UWorld *UCarlaSettingsDelegate::GetLocalWorld() +{ + return GEngine->GetWorldFromContextObjectChecked(this); +} + +void UCarlaSettingsDelegate::CheckCarlaSettings(UWorld *world) +{ + if (IsValid(CarlaSettings)) + { + return; + } + if (world == nullptr || !IsValid(world) || world->IsPendingKill()) + { + world = GetLocalWorld(); + } + check(world != nullptr); + auto GameInstance = Cast(world->GetGameInstance()); + check(GameInstance != nullptr); + CarlaSettings = &GameInstance->GetCarlaSettings(); + check(CarlaSettings != nullptr); +} + +void UCarlaSettingsDelegate::LaunchLowQualityCommands(UWorld *world) const +{ + if (!world) + { + return; + } + + // launch commands to lower quality settings + GEngine->Exec(world, TEXT("r.DefaultFeature.MotionBlur 0")); + GEngine->Exec(world, TEXT("r.DefaultFeature.Bloom 0")); + GEngine->Exec(world, TEXT("r.DefaultFeature.AmbientOcclusion 0")); + GEngine->Exec(world, TEXT("r.AmbientOcclusionLevels 0")); + GEngine->Exec(world, TEXT("r.DefaultFeature.AmbientOcclusionStaticFraction 0")); + GEngine->Exec(world, TEXT("r.RHICmdBypass 0")); + GEngine->Exec(world, TEXT("r.DefaultFeature.AntiAliasing 1")); + GEngine->Exec(world, TEXT("r.Streaming.PoolSize 2000")); + GEngine->Exec(world, TEXT("r.HZBOcclusion 0")); + GEngine->Exec(world, TEXT("r.MinScreenRadiusForLights 0.01")); + GEngine->Exec(world, TEXT("r.SeparateTranslucency 0")); + GEngine->Exec(world, TEXT("r.FinishCurrentFrame 0")); + GEngine->Exec(world, TEXT("r.MotionBlurQuality 0")); + GEngine->Exec(world, TEXT("r.PostProcessAAQuality 0")); + GEngine->Exec(world, TEXT("r.BloomQuality 1")); + GEngine->Exec(world, TEXT("r.SSR.Quality 0")); + GEngine->Exec(world, TEXT("r.DepthOfFieldQuality 0")); + GEngine->Exec(world, TEXT("r.SceneColorFormat 2")); + GEngine->Exec(world, TEXT("r.TranslucencyVolumeBlur 0")); + GEngine->Exec(world, TEXT("r.TranslucencyLightingVolumeDim 4")); + GEngine->Exec(world, TEXT("r.MaxAnisotropy 8")); + GEngine->Exec(world, TEXT("r.LensFlareQuality 0")); + GEngine->Exec(world, TEXT("r.SceneColorFringeQuality 0")); + GEngine->Exec(world, TEXT("r.FastBlurThreshold 0")); + GEngine->Exec(world, TEXT("r.SSR.MaxRoughness 0.1")); + GEngine->Exec(world, TEXT("r.AllowOcclusionQueries 1")); + GEngine->Exec(world, TEXT("r.SSR 0")); + // GEngine->Exec(world,TEXT("r.StencilForLODDither 1")); //readonly + GEngine->Exec(world, TEXT("r.EarlyZPass 2")); // transparent before opaque + GEngine->Exec(world, TEXT("r.EarlyZPassMovable 1")); + GEngine->Exec(world, TEXT("Foliage.DitheredLOD 0")); + // GEngine->Exec(world,TEXT("r.ForwardShading 0")); //readonly + GEngine->Exec(world, TEXT("sg.PostProcessQuality 0")); + // GEngine->Exec(world,TEXT("r.ViewDistanceScale 0.1")); //--> too extreme + // (far clip too short) + GEngine->Exec(world, TEXT("sg.ShadowQuality 0")); + GEngine->Exec(world, TEXT("sg.TextureQuality 0")); + GEngine->Exec(world, TEXT("sg.EffectsQuality 0")); + GEngine->Exec(world, TEXT("sg.FoliageQuality 0")); + GEngine->Exec(world, TEXT("foliage.DensityScale 0")); + GEngine->Exec(world, TEXT("grass.DensityScale 0")); + GEngine->Exec(world, TEXT("r.TranslucentLightingVolume 0")); + GEngine->Exec(world, TEXT("r.LightShaftDownSampleFactor 4")); + GEngine->Exec(world, TEXT("r.OcclusionQueryLocation 1")); + // GEngine->Exec(world,TEXT("r.BasePassOutputsVelocity 0")); //--> readonly + // GEngine->Exec(world,TEXT("r.DetailMode 0")); //-->will change to lods 0 + GEngine->Exec(world, TEXT("r.DefaultFeature.AutoExposure 1")); + +} + +void UCarlaSettingsDelegate::SetAllRoads( + UWorld *world, + const float max_draw_distance, + const TArray &road_pieces_materials) const +{ + if (!world || !IsValid(world) || world->IsPendingKill()) + { + return; + } + AsyncTask(ENamedThreads::GameThread, [=]() { + if (!world || !IsValid(world) || world->IsPendingKill()) + { + return; + } + TArray actors; + UGameplayStatics::GetAllActorsWithTag(world, UCarlaSettings::CARLA_ROAD_TAG, actors); + + for (int32 i = 0; i < actors.Num(); i++) + { + AActor *actor = actors[i]; + if (!IsValid(actor) || actor->IsPendingKill()) + { + continue; + } + TArray components; + actor->GetComponents(components); + for (int32 j = 0; j < components.Num(); j++) + { + UStaticMeshComponent *staticmeshcomponent = Cast(components[j]); + if (staticmeshcomponent) + { + staticmeshcomponent->bAllowCullDistanceVolume = (max_draw_distance > 0); + staticmeshcomponent->bUseAsOccluder = false; + staticmeshcomponent->LDMaxDrawDistance = max_draw_distance; + staticmeshcomponent->CastShadow = (max_draw_distance == 0); + if (road_pieces_materials.Num() > 0) + { + TArray meshslotsnames = staticmeshcomponent->GetMaterialSlotNames(); + for (int32 k = 0; k < meshslotsnames.Num(); k++) + { + const FName &slotname = meshslotsnames[k]; + road_pieces_materials.ContainsByPredicate( + [staticmeshcomponent, slotname](const FStaticMaterial &material) + { + if (material.MaterialSlotName.IsEqual(slotname)) + { + staticmeshcomponent->SetMaterial( + staticmeshcomponent->GetMaterialIndex(slotname), + material.MaterialInterface); + return true; + } + else + { + return false; + } + }); + } + } + } + } + } + }); // ,DELAY_TIME_TO_SET_ALL_ROADS, false); +} + +void UCarlaSettingsDelegate::SetActorComponentsDrawDistance( + AActor *actor, + const float max_draw_distance) const +{ + if (!actor) + { + return; + } + TArray components; + actor->GetComponents(components, false); + float dist = max_draw_distance; + const float maxscale = actor->GetActorScale().GetMax(); + if (maxscale > CARLA_SETTINGS_MAX_SCALE_SIZE) + { + dist *= 100.0f; + } + for (int32 j = 0; j < components.Num(); j++) + { + UPrimitiveComponent *primitivecomponent = Cast(components[j]); + if (IsValid(primitivecomponent)) + { + primitivecomponent->SetCullDistance(dist); + primitivecomponent->bAllowCullDistanceVolume = dist > 0; + } + } +} + +void UCarlaSettingsDelegate::SetAllActorsDrawDistance(UWorld *world, const float max_draw_distance) const +{ + /// @TODO: use semantics to grab all actors by type + /// (vehicles,ground,people,props) and set different distances configured in + /// the global properties + if (!world || !IsValid(world) || world->IsPendingKill()) + { + return; + } + AsyncTask(ENamedThreads::GameThread, [=]() { + if (!world || !IsValid(world) || world->IsPendingKill()) + { + return; + } + TArray actors; + // set the lower quality - max draw distance + UGameplayStatics::GetAllActorsOfClass(world, AActor::StaticClass(), actors); + for (int32 i = 0; i < actors.Num(); i++) + { + AActor *actor = actors[i]; + if (!IsValid(actor) || actor->IsPendingKill() || + actor->IsA() || // foliage culling is controlled + // per instance + actor->IsA() || // dont touch landscapes nor roads + actor->ActorHasTag(UCarlaSettings::CARLA_ROAD_TAG) || + actor->ActorHasTag(UCarlaSettings::CARLA_SKY_TAG)) + { + continue; + } + SetActorComponentsDrawDistance(actor, max_draw_distance); + } + }); +} + +void UCarlaSettingsDelegate::SetPostProcessEffectsEnabled(UWorld *world, const bool enabled) const +{ + TArray actors; + UGameplayStatics::GetAllActorsOfClass(world, APostProcessVolume::StaticClass(), actors); + for (int32 i = 0; i < actors.Num(); i++) + { + AActor *actor = actors[i]; + if (!IsValid(actor) || actor->IsPendingKill()) + { + continue; + } + APostProcessVolume *postprocessvolume = Cast(actor); + if (postprocessvolume) + { + postprocessvolume->bEnabled = enabled; + } + } +} + +void UCarlaSettingsDelegate::LaunchEpicQualityCommands(UWorld *world) const +{ + if (!world) + { + return; + } + + GEngine->Exec(world, TEXT("r.AmbientOcclusionLevels -1")); + GEngine->Exec(world, TEXT("r.RHICmdBypass 1")); + GEngine->Exec(world, TEXT("r.DefaultFeature.AntiAliasing 1")); + GEngine->Exec(world, TEXT("r.Streaming.PoolSize 2000")); + GEngine->Exec(world, TEXT("r.MinScreenRadiusForLights 0.03")); + GEngine->Exec(world, TEXT("r.SeparateTranslucency 1")); + GEngine->Exec(world, TEXT("r.PostProcessAAQuality 4")); + GEngine->Exec(world, TEXT("r.BloomQuality 5")); + GEngine->Exec(world, TEXT("r.SSR.Quality 3")); + GEngine->Exec(world, TEXT("r.DepthOfFieldQuality 2")); + GEngine->Exec(world, TEXT("r.SceneColorFormat 4")); + GEngine->Exec(world, TEXT("r.TranslucencyVolumeBlur 1")); + GEngine->Exec(world, TEXT("r.TranslucencyLightingVolumeDim 64")); + GEngine->Exec(world, TEXT("r.MaxAnisotropy 8")); + GEngine->Exec(world, TEXT("r.LensFlareQuality 2")); + GEngine->Exec(world, TEXT("r.SceneColorFringeQuality 1")); + GEngine->Exec(world, TEXT("r.FastBlurThreshold 100")); + GEngine->Exec(world, TEXT("r.SSR.MaxRoughness -1")); + // GEngine->Exec(world,TEXT("r.StencilForLODDither 0")); //readonly + GEngine->Exec(world, TEXT("r.EarlyZPass 3")); + GEngine->Exec(world, TEXT("r.EarlyZPassMovable 1")); + GEngine->Exec(world, TEXT("Foliage.DitheredLOD 1")); + GEngine->Exec(world, TEXT("sg.PostProcessQuality 3")); + GEngine->Exec(world, TEXT("r.ViewDistanceScale 1")); // --> too extreme (far + // clip too short) + GEngine->Exec(world, TEXT("sg.ShadowQuality 3")); + GEngine->Exec(world, TEXT("sg.TextureQuality 3")); + GEngine->Exec(world, TEXT("sg.EffectsQuality 3")); + GEngine->Exec(world, TEXT("sg.FoliageQuality 3")); + GEngine->Exec(world, TEXT("foliage.DensityScale 1")); + GEngine->Exec(world, TEXT("grass.DensityScale 1")); + GEngine->Exec(world, TEXT("r.TranslucentLightingVolume 1")); + GEngine->Exec(world, TEXT("r.LightShaftDownSampleFactor 2")); + // GEngine->Exec(world,TEXT("r.OcclusionQueryLocation 0")); + // GEngine->Exec(world,TEXT("r.BasePassOutputsVelocity 0")); //readonly + GEngine->Exec(world, TEXT("r.DetailMode 2")); +} + +void UCarlaSettingsDelegate::SetAllLights( + UWorld *world, + const float max_distance_fade, + const bool cast_shadows, + const bool hide_non_directional) const +{ + if (!world || !IsValid(world) || world->IsPendingKill()) + { + return; + } + AsyncTask(ENamedThreads::GameThread, [=]() { + if (!world || !IsValid(world) || world->IsPendingKill()) + { + return; + } + TArray actors; + UGameplayStatics::GetAllActorsOfClass(world, ALight::StaticClass(), actors); + for (int32 i = 0; i < actors.Num(); i++) + { + if (!IsValid(actors[i]) || actors[i]->IsPendingKill()) + { + continue; + } + // tweak directional lights + ADirectionalLight *directionallight = Cast(actors[i]); + if (directionallight) + { + directionallight->SetCastShadows(cast_shadows); + directionallight->SetLightFunctionFadeDistance(max_distance_fade); + continue; + } + // disable any other type of light + actors[i]->SetActorHiddenInGame(hide_non_directional); + } + }); + +} diff --git a/Carla/Traffic/SignComponent.h b/Carla/Traffic/SignComponent.h index 3dc123e..1d7ffaf 100644 --- a/Carla/Traffic/SignComponent.h +++ b/Carla/Traffic/SignComponent.h @@ -1,87 +1,87 @@ -// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "CoreMinimal.h" -#include "Components/SceneComponent.h" -#include "Components/BoxComponent.h" -#include "Carla/OpenDrive/OpenDrive.h" -#include - -#include "Vehicle/CarlaWheeledVehicle.h" -#include "UObject/ConstructorHelpers.h" - -#include -#include -#include -#include - -#include "SignComponent.generated.h" - -namespace carla -{ -namespace road -{ - class Map; -namespace element -{ - class RoadInfoSignal; -} -} -} - -namespace cr = carla::road; -namespace cre = carla::road::element; - -/// Class representing an OpenDRIVE Signal -UCLASS( ClassGroup=(Custom), meta=(BlueprintSpawnableComponent) ) -class CARLA_API USignComponent : public USceneComponent -{ - GENERATED_BODY() - -public: - USignComponent(); - - UFUNCTION(Category = "Traffic Sign", BlueprintPure) - const FString &GetSignId() const; - - UFUNCTION(Category = "Traffic Sign", BlueprintCallable) - void SetSignId(const FString &Id); - - // Initialize sign (e.g. generate trigger boxes) - virtual void InitializeSign(const cr::Map &Map); - - void AddEffectTriggerVolume(UBoxComponent* TriggerVolume); - - const TArray GetEffectTriggerVolume() const; - -protected: - // Called when the game starts - virtual void BeginPlay() override; - - // Called every frame - virtual void TickComponent(float DeltaTime, ELevelTick TickType, FActorComponentTickFunction* ThisTickFunction) override; - - TArray> - GetAllReferencesToThisSignal(const cr::Map &Map); - - const cr::Signal* GetSignal(const cr::Map &Map) const; - - /// Generates a trigger box component in the parent actor - /// BoxSize should be in Unreal units - UBoxComponent* GenerateTriggerBox(const FTransform &BoxTransform, - float BoxSize); - -private: - - UPROPERTY(Category = "Traffic Sign", EditAnywhere) - FString SignId = ""; - - UPROPERTY() - TArray EffectTriggerVolumes; - -}; +// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "CoreMinimal.h" +#include "Components/SceneComponent.h" +#include "Components/BoxComponent.h" +#include "Carla/OpenDrive/OpenDrive.h" +#include + +#include "Vehicle/CarlaWheeledVehicle.h" +#include "UObject/ConstructorHelpers.h" + +#include +#include +#include +#include + +#include "SignComponent.generated.h" + +namespace carla +{ +namespace road +{ + class Map; +namespace element +{ + class RoadInfoSignal; +} +} +} + +namespace cr = carla::road; +namespace cre = carla::road::element; + +/// Class representing an OpenDRIVE Signal +UCLASS( ClassGroup=(Custom), meta=(BlueprintSpawnableComponent) ) +class CARLA_API USignComponent : public USceneComponent +{ + GENERATED_BODY() + +public: + USignComponent(); + + UFUNCTION(Category = "Traffic Sign", BlueprintPure) + const FString &GetSignId() const; + + UFUNCTION(Category = "Traffic Sign", BlueprintCallable) + void SetSignId(const FString &Id); + + // Initialize sign (e.g. generate trigger boxes) + virtual void InitializeSign(const cr::Map &Map); + + void AddEffectTriggerVolume(UBoxComponent* TriggerVolume); + + const TArray GetEffectTriggerVolume() const; + +protected: + // Called when the game starts + virtual void BeginPlay() override; + + // Called every frame + virtual void TickComponent(float DeltaTime, ELevelTick TickType, FActorComponentTickFunction* ThisTickFunction) override; + + TArray> + GetAllReferencesToThisSignal(const cr::Map &Map); + + const cr::Signal* GetSignal(const cr::Map &Map) const; + + /// Generates a trigger box component in the parent actor + /// BoxSize should be in Unreal units + UBoxComponent* GenerateTriggerBox(const FTransform &BoxTransform, + float BoxSize); + +private: + + UPROPERTY(Category = "Traffic Sign", EditAnywhere) + FString SignId = ""; + + UPROPERTY() + TArray EffectTriggerVolumes; + +}; diff --git a/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Carla/Vehicle/CarlaWheeledVehicle.cpp index 78dd59c..41ff0b8 100644 --- a/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -1,870 +1,870 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// Copyright (c) 2019 Intel Corporation -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "Components/BoxComponent.h" -#include "Engine/CollisionProfile.h" -#include "MovementComponents/DefaultMovementComponent.h" -#include "Rendering/SkeletalMeshRenderData.h" -#include "UObject/UObjectGlobals.h" - -#include "PhysXPublic.h" -#include "PhysXVehicleManager.h" -#include "TireConfig.h" -#include "VehicleWheel.h" - -#include "Carla.h" -#include "Carla/Game/CarlaHUD.h" -#include "Carla/Game/CarlaStatics.h" -#include "Carla/Trigger/FrictionTrigger.h" -#include "Carla/Util/ActorAttacher.h" -#include "Carla/Util/EmptyActor.h" -#include "Carla/Util/BoundingBoxCalculator.h" -#include "Carla/Vehicle/CarlaWheeledVehicle.h" - -// ============================================================================= -// -- Constructor and destructor ----------------------------------------------- -// ============================================================================= - -ACarlaWheeledVehicle::ACarlaWheeledVehicle(const FObjectInitializer& ObjectInitializer) : - Super(ObjectInitializer) -{ - VehicleBounds = CreateDefaultSubobject(TEXT("VehicleBounds")); - VehicleBounds->SetupAttachment(RootComponent); - VehicleBounds->SetHiddenInGame(true); - VehicleBounds->SetCollisionProfileName(UCollisionProfile::NoCollision_ProfileName); - - VelocityControl = CreateDefaultSubobject(TEXT("VelocityControl")); - VelocityControl->Deactivate(); - - GetVehicleMovementComponent()->bReverseAsBrake = false; - - BaseMovementComponent = CreateDefaultSubobject(TEXT("BaseMovementComponent")); - - // Initialize audio components - ConstructSounds(); - - // Initialize collision sound upon collisions - ConstructCollisionHandler(); -} - -ACarlaWheeledVehicle::~ACarlaWheeledVehicle() {} - -void ACarlaWheeledVehicle::SetWheelCollision(UWheeledVehicleMovementComponent4W *Vehicle4W, - const FVehiclePhysicsControl &PhysicsControl ) { - - #ifdef WHEEL_SWEEP_ENABLED - const bool IsBike = IsTwoWheeledVehicle(); - - if (IsBike) - return; - - const bool IsEqual = Vehicle4W->UseSweepWheelCollision == PhysicsControl.UseSweepWheelCollision; - - if (IsEqual) - return; - - Vehicle4W->UseSweepWheelCollision = PhysicsControl.UseSweepWheelCollision; - - #else - - if (PhysicsControl.UseSweepWheelCollision) - UE_LOG(LogCarla, Warning, TEXT("Error: Sweep for wheel collision is not available. \ - Make sure you have installed the required patch.") ); - - #endif - -} - -void ACarlaWheeledVehicle::BeginPlay() -{ - Super::BeginPlay(); - - UDefaultMovementComponent::CreateDefaultMovementComponent(this); - - // Get constraint components and their initial transforms - FTransform ActorInverseTransform = GetActorTransform().Inverse(); - ConstraintsComponents.Empty(); - DoorComponentsTransform.Empty(); - ConstraintDoor.Empty(); - for (FName& ComponentName : ConstraintComponentNames) - { - UPhysicsConstraintComponent* ConstraintComponent = - Cast(GetDefaultSubobjectByName(ComponentName)); - if (ConstraintComponent) - { - UPrimitiveComponent* DoorComponent = Cast( - GetDefaultSubobjectByName(ConstraintComponent->ComponentName1.ComponentName)); - if(DoorComponent) - { - UE_LOG(LogCarla, Warning, TEXT("Door name: %s"), *(DoorComponent->GetName())); - FTransform ComponentWorldTransform = DoorComponent->GetComponentTransform(); - FTransform RelativeTransform = ComponentWorldTransform * ActorInverseTransform; - DoorComponentsTransform.Add(DoorComponent, RelativeTransform); - ConstraintDoor.Add(ConstraintComponent, DoorComponent); - ConstraintsComponents.Add(ConstraintComponent); - ConstraintComponent->TermComponentConstraint(); - } - else - { - UE_LOG(LogCarla, Error, TEXT("Missing component for constraint: %s"), *(ConstraintComponent->GetName())); - } - } - } - ResetConstraints(); - - // get collision disable constraints (used to prevent doors from colliding with each other) - CollisionDisableConstraints.Empty(); - TArray Constraints; - GetComponents(Constraints); - for (UPhysicsConstraintComponent* Constraint : Constraints) - { - if (!ConstraintsComponents.Contains(Constraint)) - { - UPrimitiveComponent* CollisionDisabledComponent1 = Cast( - GetDefaultSubobjectByName(Constraint->ComponentName1.ComponentName)); - UPrimitiveComponent* CollisionDisabledComponent2 = Cast( - GetDefaultSubobjectByName(Constraint->ComponentName2.ComponentName)); - if (CollisionDisabledComponent1) - { - CollisionDisableConstraints.Add(CollisionDisabledComponent1, Constraint); - } - if (CollisionDisabledComponent2) - { - CollisionDisableConstraints.Add(CollisionDisabledComponent2, Constraint); - } - } - } - - float FrictionScale = 3.5f; - - UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( - GetVehicleMovementComponent()); - check(Vehicle4W != nullptr); - - // Setup Tire Configs with default value. This is needed to avoid getting - // friction values of previously created TireConfigs for the same vehicle - // blueprint. - TArray OriginalFrictions; - OriginalFrictions.Init(FrictionScale, Vehicle4W->Wheels.Num()); - SetWheelsFrictionScale(OriginalFrictions); - - // Check if it overlaps with a Friction trigger, if so, update the friction - // scale. - TArray OverlapActors; - GetOverlappingActors(OverlapActors, AFrictionTrigger::StaticClass()); - for (const auto &Actor : OverlapActors) - { - AFrictionTrigger *FrictionTrigger = Cast(Actor); - if (FrictionTrigger) - { - FrictionScale = FrictionTrigger->Friction; - } - } - - // Set the friction scale to Wheel CDO and update wheel setups - TArray NewWheelSetups = Vehicle4W->WheelSetups; - - for (const auto &WheelSetup : NewWheelSetups) - { - UVehicleWheel *Wheel = WheelSetup.WheelClass.GetDefaultObject(); - check(Wheel != nullptr); - } - - Vehicle4W->WheelSetups = NewWheelSetups; - - LastPhysicsControl = GetVehiclePhysicsControl(); - - // Turn off all audio until vehicle starts running - SetVolume(0); -} - -void ACarlaWheeledVehicle::Tick(float DeltaSeconds) -{ - Super::Tick(DeltaSeconds); - - // Play sound that requires constant ticking - TickSounds(DeltaSeconds); -} - -// ============================================================================= -// -- Sound Functions ---------------------------------------------------------- -// ============================================================================= - -float ACarlaWheeledVehicle::Volume = 1.f; // static for all non-ego vehicles (use DReyeVRLevel::SetVolume) - -void ACarlaWheeledVehicle::ConstructSounds() -{ - // add all sounds here - - static ConstructorHelpers::FObjectFinder EngineCueObj( - TEXT("SoundCue'/Game/DReyeVR/Sounds/EngineRev/EngineRev.EngineRev'")); - EngineRevSound = CreateDefaultSubobject(FName("EngineRevSound")); - EngineRevSound->SetupAttachment(GetRootComponent()); // attach to self - EngineRevSound->bAutoActivate = true; // start playing on begin - EngineRevSound->SetSound(EngineCueObj.Object); // using this sound - EngineRevSound->SetRelativeLocation(EngineLocnInVehicle); // location of "engine" in vehicle (3D sound) - EngineRevSound->SetFloatParameter(FName("RPM"), 0.f); // initially idle - EngineRevSound->bAutoDestroy = false; // No automatic destroy, persist along with vehicle - check(EngineRevSound != nullptr); - - static ConstructorHelpers::FObjectFinder CarCrashCue( - TEXT("SoundCue'/Game/DReyeVR/Sounds/Crash/CrashCue.CrashCue'")); - CrashSound = CreateDefaultSubobject(TEXT("CarCrash")); - CrashSound->SetupAttachment(GetRootComponent()); - CrashSound->bAutoActivate = false; - CrashSound->SetSound(CarCrashCue.Object); - CrashSound->bAutoDestroy = false; - check(CrashSound != nullptr); -} - -void ACarlaWheeledVehicle::TickSounds(float DeltaSeconds) -{ - // Respect the global vehicle volume param - SetVolume(ACarlaWheeledVehicle::Volume); - - if (EngineRevSound) - { - if (!EngineRevSound->IsPlaying()) - { - EngineRevSound->Play(); // turn on the engine sound if not already on - } - float RPM = FMath::Clamp(GetVehicleMovementComponent()->GetEngineRotationSpeed(), 0.f, 5650.0f); - EngineRevSound->SetFloatParameter(FName("RPM"), RPM); - } - // add other sounds that need tick-level granularity here... -} - -void ACarlaWheeledVehicle::SetVolume(const float VolumeIn) -{ - if (EngineRevSound) - EngineRevSound->SetVolumeMultiplier(VolumeIn); - if (CrashSound) - CrashSound->SetVolumeMultiplier(VolumeIn); -} - -// ============================================================================= -// -- Collision Functions ------------------------------------------------------ -// ============================================================================= - -void ACarlaWheeledVehicle::ConstructCollisionHandler() -{ - // using Carla's GetVehicleBoundingBox function - UBoxComponent *Bounds = this->GetVehicleBoundingBox(); - Bounds->SetGenerateOverlapEvents(true); - Bounds->SetCollisionEnabled(ECollisionEnabled::QueryOnly); - Bounds->SetCollisionProfileName(TEXT("Trigger")); - Bounds->OnComponentBeginOverlap.AddDynamic(this, &ACarlaWheeledVehicle::OnOverlapBegin); -} - -bool ACarlaWheeledVehicle::EnableCollisionForActor(AActor *OtherActor) -{ - // define whether or not we should "collide" with these actors - // as opposed to actors such as the ground/grass - const FString OtherName = OtherActor->GetName().ToLower(); - double Now = GetWorld()->GetTimeSeconds(); - bool bIsAVehicle = OtherActor->IsA(ACarlaWheeledVehicle::StaticClass()); - return (CollisionCooldownTime < Now && // respect collision audio cooldown - (bIsAVehicle || // do collide with vehicles - OtherName.Contains("spline") || // do collide with carla "spline" (misc) objects - OtherName.Contains("streetlight") || // do collide with street lights - OtherName.Contains("curb") // do collide with curb objects - )); -} - -void ACarlaWheeledVehicle::OnOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, - UPrimitiveComponent *OtherComp, int32 OtherBodyIndex, bool bFromSweep, - const FHitResult &SweepResult) -{ - if (OtherActor == nullptr || OtherActor == this) - return; - - // can be more flexible, such as having collisions with static props or people too - if (EnableCollisionForActor(OtherActor)) - { - // emit the car collision sound at the midpoint between the vehicles' collision - /// TODO: would be ideal to use FHitPoint::ImpactPoint but there is a bug in UE4 where this is not initialized - // see: https://answers.unrealengine.com/questions/219744/component-overlap-hit-position-always-returns-000.html - FVector SoundEmitLocation = EngineLocnInVehicle; - bool bIsAVehicle = OtherActor->IsA(ACarlaWheeledVehicle::StaticClass()); - if (bIsAVehicle) { // in the case where the other actor is a vehicle, do emit the sound at the location midpoint - SoundEmitLocation = (OtherActor->GetActorLocation() - this->GetActorLocation()) / 2.f; - SoundEmitLocation += 75.f * FVector::UpVector; // Make the sound emitted not at the ground (0.75m above ground) - } - if (CrashSound != nullptr) { - CrashSound->SetRelativeLocation(SoundEmitLocation); - CrashSound->Play(); - CollisionCooldownTime = GetWorld()->GetTimeSeconds() + 0.5f; // have at least 0.5s of buffer between collision audio - } - } -} - -// ============================================================================= -// -- CARLA -------------------------------------------------------------------- -// ============================================================================= - -void ACarlaWheeledVehicle::AdjustVehicleBounds() -{ - FBoundingBox BoundingBox = UBoundingBoxCalculator::GetVehicleBoundingBox(this); - - const FTransform& CompToWorldTransform = RootComponent->GetComponentTransform(); - const FRotator Rotation = CompToWorldTransform.GetRotation().Rotator(); - const FVector Translation = CompToWorldTransform.GetLocation(); - const FVector Scale = CompToWorldTransform.GetScale3D(); - - // Invert BB origin to local space - BoundingBox.Origin -= Translation; - BoundingBox.Origin = Rotation.UnrotateVector(BoundingBox.Origin); - BoundingBox.Origin /= Scale; - - // Prepare Box Collisions - FTransform Transform; - Transform.SetTranslation(BoundingBox.Origin); - VehicleBounds->SetRelativeTransform(Transform); - VehicleBounds->SetBoxExtent(BoundingBox.Extent); -} - -// ============================================================================= -// -- Get functions ------------------------------------------------------------ -// ============================================================================= - -float ACarlaWheeledVehicle::GetVehicleForwardSpeed() const -{ - return BaseMovementComponent->GetVehicleForwardSpeed(); -} - -FVector ACarlaWheeledVehicle::GetVehicleOrientation() const -{ - return GetVehicleTransform().GetRotation().GetForwardVector(); -} - -int32 ACarlaWheeledVehicle::GetVehicleCurrentGear() const -{ - return BaseMovementComponent->GetVehicleCurrentGear(); -} - -FTransform ACarlaWheeledVehicle::GetVehicleBoundingBoxTransform() const -{ - return VehicleBounds->GetRelativeTransform(); -} - -FVector ACarlaWheeledVehicle::GetVehicleBoundingBoxExtent() const -{ - return VehicleBounds->GetScaledBoxExtent(); -} - -float ACarlaWheeledVehicle::GetMaximumSteerAngle() const -{ - const auto &Wheels = GetVehicleMovementComponent()->Wheels; - check(Wheels.Num() > 0); - const auto *FrontWheel = Wheels[0]; - check(FrontWheel != nullptr); - return FrontWheel->SteerAngle; -} - -// ============================================================================= -// -- Set functions ------------------------------------------------------------ -// ============================================================================= - -void ACarlaWheeledVehicle::FlushVehicleControl() -{ - BaseMovementComponent->ProcessControl(InputControl.Control); - InputControl.Control.bReverse = InputControl.Control.Gear < 0; - LastAppliedControl = InputControl.Control; - InputControl.Priority = EVehicleInputPriority::INVALID; -} - -void ACarlaWheeledVehicle::SetThrottleInput(const float Value) -{ - FVehicleControl Control = InputControl.Control; - Control.Throttle = Value; - ApplyVehicleControl(Control, EVehicleInputPriority::User); -} - -void ACarlaWheeledVehicle::SetSteeringInput(const float Value) -{ - FVehicleControl Control = InputControl.Control; - Control.Steer = Value; - ApplyVehicleControl(Control, EVehicleInputPriority::User); -} - -void ACarlaWheeledVehicle::SetBrakeInput(const float Value) -{ - FVehicleControl Control = InputControl.Control; - Control.Brake = Value; - ApplyVehicleControl(Control, EVehicleInputPriority::User); -} - -void ACarlaWheeledVehicle::SetReverse(const bool Value) -{ - FVehicleControl Control = InputControl.Control; - Control.bReverse = Value; - ApplyVehicleControl(Control, EVehicleInputPriority::User); -} - -void ACarlaWheeledVehicle::SetHandbrakeInput(const bool Value) -{ - FVehicleControl Control = InputControl.Control; - Control.bHandBrake = Value; - ApplyVehicleControl(Control, EVehicleInputPriority::User); -} - -TArray ACarlaWheeledVehicle::GetWheelsFrictionScale() -{ - UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( - GetVehicleMovement()); - check(Vehicle4W != nullptr); - - TArray WheelsFrictionScale; - for (auto &Wheel : Vehicle4W->Wheels) - { - WheelsFrictionScale.Add(Wheel->TireConfig->GetFrictionScale()); - } - return WheelsFrictionScale; -} - -void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray &WheelsFrictionScale) -{ - UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( - GetVehicleMovement()); - check(Vehicle4W != nullptr); - check(Vehicle4W->Wheels.Num() == WheelsFrictionScale.Num()); - - for (int32 i = 0; i < Vehicle4W->Wheels.Num(); ++i) - { - Vehicle4W->Wheels[i]->TireConfig->SetFrictionScale(WheelsFrictionScale[i]); - } -} - -FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const -{ - UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( - GetVehicleMovement()); - check(Vehicle4W != nullptr); - - FVehiclePhysicsControl PhysicsControl; - - // Engine Setup - PhysicsControl.TorqueCurve = Vehicle4W->EngineSetup.TorqueCurve.EditorCurveData; - PhysicsControl.MaxRPM = Vehicle4W->EngineSetup.MaxRPM; - PhysicsControl.MOI = Vehicle4W->EngineSetup.MOI; - PhysicsControl.DampingRateFullThrottle = Vehicle4W->EngineSetup.DampingRateFullThrottle; - PhysicsControl.DampingRateZeroThrottleClutchEngaged = - Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchEngaged; - PhysicsControl.DampingRateZeroThrottleClutchDisengaged = - Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchDisengaged; - - // Transmission Setup - PhysicsControl.bUseGearAutoBox = Vehicle4W->TransmissionSetup.bUseGearAutoBox; - PhysicsControl.GearSwitchTime = Vehicle4W->TransmissionSetup.GearSwitchTime; - PhysicsControl.ClutchStrength = Vehicle4W->TransmissionSetup.ClutchStrength; - PhysicsControl.FinalRatio = Vehicle4W->TransmissionSetup.FinalRatio; - - TArray ForwardGears; - - for (const auto &Gear : Vehicle4W->TransmissionSetup.ForwardGears) - { - FGearPhysicsControl GearPhysicsControl; - - GearPhysicsControl.Ratio = Gear.Ratio; - GearPhysicsControl.UpRatio = Gear.UpRatio; - GearPhysicsControl.DownRatio = Gear.DownRatio; - - ForwardGears.Add(GearPhysicsControl); - } - - PhysicsControl.ForwardGears = ForwardGears; - - // Vehicle Setup - PhysicsControl.Mass = Vehicle4W->Mass; - PhysicsControl.DragCoefficient = Vehicle4W->DragCoefficient; - - // Center of mass offset (Center of mass is always zero vector in local - // position) - UPrimitiveComponent *UpdatedPrimitive = Cast(Vehicle4W->UpdatedComponent); - check(UpdatedPrimitive != nullptr); - - PhysicsControl.CenterOfMass = UpdatedPrimitive->BodyInstance.COMNudge; - - // Transmission Setup - PhysicsControl.SteeringCurve = Vehicle4W->SteeringCurve.EditorCurveData; - - // Wheels Setup - TArray Wheels; - - for (int32 i = 0; i < Vehicle4W->WheelSetups.Num(); ++i) - { - FWheelPhysicsControl PhysicsWheel; - - PxVehicleWheelData PWheelData = Vehicle4W->PVehicle->mWheelsSimData.getWheelData(i); - PhysicsWheel.DampingRate = Cm2ToM2(PWheelData.mDampingRate); - PhysicsWheel.MaxSteerAngle = FMath::RadiansToDegrees(PWheelData.mMaxSteer); - PhysicsWheel.Radius = PWheelData.mRadius; - PhysicsWheel.MaxBrakeTorque = Cm2ToM2(PWheelData.mMaxBrakeTorque); - PhysicsWheel.MaxHandBrakeTorque = Cm2ToM2(PWheelData.mMaxHandBrakeTorque); - - PxVehicleTireData PTireData = Vehicle4W->PVehicle->mWheelsSimData.getTireData(i); - PhysicsWheel.LatStiffMaxLoad = PTireData.mLatStiffX; - PhysicsWheel.LatStiffValue = PTireData.mLatStiffY; - PhysicsWheel.LongStiffValue = PTireData.mLongitudinalStiffnessPerUnitGravity; - - PhysicsWheel.TireFriction = Vehicle4W->Wheels[i]->TireConfig->GetFrictionScale(); - PhysicsWheel.Position = Vehicle4W->Wheels[i]->Location; - - Wheels.Add(PhysicsWheel); - } - - PhysicsControl.Wheels = Wheels; - - return PhysicsControl; -} - -FVehicleLightState ACarlaWheeledVehicle::GetVehicleLightState() const -{ - return InputControl.LightState; -} - -void ACarlaWheeledVehicle::RestoreVehiclePhysicsControl() -{ - ApplyVehiclePhysicsControl(LastPhysicsControl); -} - -void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl) -{ - LastPhysicsControl = PhysicsControl; - - UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( - GetVehicleMovement()); - check(Vehicle4W != nullptr); - - // Engine Setup - Vehicle4W->EngineSetup.TorqueCurve.EditorCurveData = PhysicsControl.TorqueCurve; - Vehicle4W->EngineSetup.MaxRPM = PhysicsControl.MaxRPM; - - Vehicle4W->EngineSetup.MOI = PhysicsControl.MOI; - - Vehicle4W->EngineSetup.DampingRateFullThrottle = PhysicsControl.DampingRateFullThrottle; - Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchEngaged = - PhysicsControl.DampingRateZeroThrottleClutchEngaged; - Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchDisengaged = - PhysicsControl.DampingRateZeroThrottleClutchDisengaged; - - // Transmission Setup - Vehicle4W->TransmissionSetup.bUseGearAutoBox = PhysicsControl.bUseGearAutoBox; - Vehicle4W->TransmissionSetup.GearSwitchTime = PhysicsControl.GearSwitchTime; - Vehicle4W->TransmissionSetup.ClutchStrength = PhysicsControl.ClutchStrength; - Vehicle4W->TransmissionSetup.FinalRatio = PhysicsControl.FinalRatio; - - TArray ForwardGears; - - for (const auto &Gear : PhysicsControl.ForwardGears) - { - FVehicleGearData GearData; - - GearData.Ratio = Gear.Ratio; - GearData.UpRatio = Gear.UpRatio; - GearData.DownRatio = Gear.DownRatio; - - ForwardGears.Add(GearData); - } - - Vehicle4W->TransmissionSetup.ForwardGears = ForwardGears; - - // Vehicle Setup - Vehicle4W->Mass = PhysicsControl.Mass; - Vehicle4W->DragCoefficient = PhysicsControl.DragCoefficient; - - // Center of mass - UPrimitiveComponent *UpdatedPrimitive = Cast(Vehicle4W->UpdatedComponent); - check(UpdatedPrimitive != nullptr); - - UpdatedPrimitive->BodyInstance.COMNudge = PhysicsControl.CenterOfMass; - - // Transmission Setup - Vehicle4W->SteeringCurve.EditorCurveData = PhysicsControl.SteeringCurve; - - // Wheels Setup - const int PhysicsWheelsNum = PhysicsControl.Wheels.Num(); - if (PhysicsWheelsNum != 4) - { - UE_LOG(LogCarla, Error, TEXT("Number of WheelPhysicsControl is not 4.")); - return; - } - - // Change, if required, the collision mode for wheels - SetWheelCollision(Vehicle4W, PhysicsControl); - - TArray NewWheelSetups = Vehicle4W->WheelSetups; - - for (int32 i = 0; i < PhysicsWheelsNum; ++i) - { - UVehicleWheel *Wheel = NewWheelSetups[i].WheelClass.GetDefaultObject(); - check(Wheel != nullptr); - - // Assigning new tire config - Wheel->TireConfig = DuplicateObject(Wheel->TireConfig, nullptr); - - // Setting a new value to friction - Wheel->TireConfig->SetFrictionScale(PhysicsControl.Wheels[i].TireFriction); - } - - Vehicle4W->WheelSetups = NewWheelSetups; - - // Recreate Physics State for vehicle setup - GetWorld()->GetPhysicsScene()->GetPxScene()->lockWrite(); - Vehicle4W->RecreatePhysicsState(); - GetWorld()->GetPhysicsScene()->GetPxScene()->unlockWrite(); - - for (int32 i = 0; i < PhysicsWheelsNum; ++i) - { - PxVehicleWheelData PWheelData = Vehicle4W->PVehicle->mWheelsSimData.getWheelData(i); - - PWheelData.mRadius = PhysicsControl.Wheels[i].Radius; - PWheelData.mMaxSteer = FMath::DegreesToRadians(PhysicsControl.Wheels[i].MaxSteerAngle); - PWheelData.mDampingRate = M2ToCm2(PhysicsControl.Wheels[i].DampingRate); - PWheelData.mMaxBrakeTorque = M2ToCm2(PhysicsControl.Wheels[i].MaxBrakeTorque); - PWheelData.mMaxHandBrakeTorque = M2ToCm2(PhysicsControl.Wheels[i].MaxHandBrakeTorque); - Vehicle4W->PVehicle->mWheelsSimData.setWheelData(i, PWheelData); - - PxVehicleTireData PTireData = Vehicle4W->PVehicle->mWheelsSimData.getTireData(i); - PTireData.mLatStiffX = PhysicsControl.Wheels[i].LatStiffMaxLoad; - PTireData.mLatStiffY = PhysicsControl.Wheels[i].LatStiffValue; - PTireData.mLongitudinalStiffnessPerUnitGravity = PhysicsControl.Wheels[i].LongStiffValue; - Vehicle4W->PVehicle->mWheelsSimData.setTireData(i, PTireData); - } - - ResetConstraints(); - - auto * Recorder = UCarlaStatics::GetRecorder(GetWorld()); - if (Recorder && Recorder->IsEnabled()) - { - Recorder->AddPhysicsControl(*this); - } -} - -void ACarlaWheeledVehicle::ActivateVelocityControl(const FVector &Velocity) -{ - VelocityControl->Activate(Velocity); -} - -void ACarlaWheeledVehicle::DeactivateVelocityControl() -{ - VelocityControl->Deactivate(); -} - -void ACarlaWheeledVehicle::ShowDebugTelemetry(bool Enabled) -{ - if (GetWorld()->GetFirstPlayerController()) - { - ACarlaHUD* hud = Cast(GetWorld()->GetFirstPlayerController()->GetHUD()); - if (hud) { - - // Set/Unset the car movement component in HUD to show the temetry - if (Enabled) { - hud->AddDebugVehicleForTelemetry(GetVehicleMovementComponent()); - } - else{ - if (hud->DebugVehicle == GetVehicleMovementComponent()) { - hud->AddDebugVehicleForTelemetry(nullptr); - GetVehicleMovementComponent()->StopTelemetry(); - } - } - - } - else { - UE_LOG(LogCarla, Warning, TEXT("ACarlaWheeledVehicle::ShowDebugTelemetry:: Cannot find HUD for debug info")); - } - } -} - -void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState &LightState) -{ - InputControl.LightState = LightState; - RefreshLightState(LightState); -} - -void ACarlaWheeledVehicle::SetCarlaMovementComponent(UBaseCarlaMovementComponent* MovementComponent) -{ - if (BaseMovementComponent) - { - BaseMovementComponent->DestroyComponent(); - } - BaseMovementComponent = MovementComponent; -} - -void ACarlaWheeledVehicle::SetWheelSteerDirection(EVehicleWheelLocation WheelLocation, float AngleInDeg) { - - if (bPhysicsEnabled == false) - { - check((uint8)WheelLocation >= 0) - check((uint8)WheelLocation < 4) - UVehicleAnimInstance *VehicleAnim = Cast(GetMesh()->GetAnimInstance()); - check(VehicleAnim != nullptr) - VehicleAnim->SetWheelRotYaw((uint8)WheelLocation, AngleInDeg); - } - else - { - UE_LOG(LogTemp, Warning, TEXT("Cannot set wheel steer direction. Physics are enabled.")) - } -} - -float ACarlaWheeledVehicle::GetWheelSteerAngle(EVehicleWheelLocation WheelLocation) { - - check((uint8)WheelLocation >= 0) - check((uint8)WheelLocation < 4) - UVehicleAnimInstance *VehicleAnim = Cast(GetMesh()->GetAnimInstance()); - check(VehicleAnim != nullptr) - check(VehicleAnim->GetWheeledVehicleMovementComponent() != nullptr) - - if (bPhysicsEnabled == true) - { - return VehicleAnim->GetWheeledVehicleMovementComponent()->Wheels[(uint8)WheelLocation]->GetSteerAngle(); - } - else - { - return VehicleAnim->GetWheelRotAngle((uint8)WheelLocation); - } -} - -void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { - if(!GetCarlaMovementComponent()) - { - return; - } - - UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( - GetVehicleMovement()); - check(Vehicle4W != nullptr); - - if(bPhysicsEnabled == enabled) - return; - - SetActorEnableCollision(true); - auto RootComponent = Cast(GetRootComponent()); - RootComponent->SetSimulatePhysics(enabled); - RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); - - UVehicleAnimInstance *VehicleAnim = Cast(GetMesh()->GetAnimInstance()); - check(VehicleAnim != nullptr) - - GetWorld()->GetPhysicsScene()->GetPxScene()->lockWrite(); - if (enabled) - { - Vehicle4W->RecreatePhysicsState(); - VehicleAnim->ResetWheelCustomRotations(); - } - else - { - Vehicle4W->DestroyPhysicsState(); - } - - GetWorld()->GetPhysicsScene()->GetPxScene()->unlockWrite(); - - bPhysicsEnabled = enabled; - - ResetConstraints(); - -} - -void ACarlaWheeledVehicle::ResetConstraints() -{ - for (int i = 0; i < ConstraintsComponents.Num(); i++) - { - OpenDoorPhys(EVehicleDoor(i)); - } - for (int i = 0; i < ConstraintsComponents.Num(); i++) - { - CloseDoorPhys(EVehicleDoor(i)); - } -} - -FVector ACarlaWheeledVehicle::GetVelocity() const -{ - return BaseMovementComponent->GetVelocity(); -} - -void ACarlaWheeledVehicle::EndPlay(const EEndPlayReason::Type EndPlayReason) -{ - ShowDebugTelemetry(false); -} - -void ACarlaWheeledVehicle::OpenDoor(const EVehicleDoor DoorIdx) { - if (int(DoorIdx) >= ConstraintsComponents.Num() && DoorIdx != EVehicleDoor::All) { - UE_LOG(LogTemp, Warning, TEXT("This door is not configured for this car.")); - return; - } - - if (DoorIdx == EVehicleDoor::All) { - for (int i = 0; i < ConstraintsComponents.Num(); i++) - { - OpenDoorPhys(EVehicleDoor(i)); - } - return; - } - - OpenDoorPhys(DoorIdx); -} - -void ACarlaWheeledVehicle::CloseDoor(const EVehicleDoor DoorIdx) { - if (int(DoorIdx) >= ConstraintsComponents.Num() && DoorIdx != EVehicleDoor::All) { - UE_LOG(LogTemp, Warning, TEXT("This door is not configured for this car.")); - return; - } - - if (DoorIdx == EVehicleDoor::All) { - for (int i = 0; i < ConstraintsComponents.Num(); i++) - { - CloseDoorPhys(EVehicleDoor(i)); - } - return; - } - - CloseDoorPhys(DoorIdx); -} - -void ACarlaWheeledVehicle::OpenDoorPhys(const EVehicleDoor DoorIdx) -{ - UPhysicsConstraintComponent* Constraint = ConstraintsComponents[static_cast(DoorIdx)]; - UPrimitiveComponent* DoorComponent = ConstraintDoor[Constraint]; - DoorComponent->DetachFromComponent( - FDetachmentTransformRules(EDetachmentRule::KeepWorld, false)); - FTransform DoorInitialTransform = - DoorComponentsTransform[DoorComponent] * GetActorTransform(); - DoorComponent->SetWorldTransform(DoorInitialTransform); - DoorComponent->SetSimulatePhysics(true); - DoorComponent->SetCollisionProfileName(TEXT("BlockAll")); - float AngleLimit = Constraint->ConstraintInstance.GetAngularSwing1Limit(); - FRotator AngularRotationOffset = Constraint->ConstraintInstance.AngularRotationOffset; - - if (Constraint->ConstraintInstance.AngularRotationOffset.Yaw < 0.0f) - { - AngleLimit = -AngleLimit; - } - Constraint->SetAngularOrientationTarget(FRotator(0, AngleLimit, 0)); - Constraint->SetAngularDriveParams(DoorOpenStrength, 1.0, 0.0); - - Constraint->InitComponentConstraint(); - - UPhysicsConstraintComponent** CollisionDisable = - CollisionDisableConstraints.Find(DoorComponent); - if (CollisionDisable) - { - (*CollisionDisable)->InitComponentConstraint(); - } -} - -void ACarlaWheeledVehicle::CloseDoorPhys(const EVehicleDoor DoorIdx) -{ - UPhysicsConstraintComponent* Constraint = ConstraintsComponents[static_cast(DoorIdx)]; - UPrimitiveComponent* DoorComponent = ConstraintDoor[Constraint]; - FTransform DoorInitialTransform = - DoorComponentsTransform[DoorComponent] * GetActorTransform(); - DoorComponent->SetSimulatePhysics(false); - DoorComponent->SetCollisionProfileName(TEXT("NoCollision")); - DoorComponent->SetWorldTransform(DoorInitialTransform); - DoorComponent->AttachToComponent( - GetMesh(), FAttachmentTransformRules(EAttachmentRule::KeepWorld, true)); -} +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// Copyright (c) 2019 Intel Corporation +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Components/BoxComponent.h" +#include "Engine/CollisionProfile.h" +#include "MovementComponents/DefaultMovementComponent.h" +#include "Rendering/SkeletalMeshRenderData.h" +#include "UObject/UObjectGlobals.h" + +#include "PhysXPublic.h" +#include "PhysXVehicleManager.h" +#include "TireConfig.h" +#include "VehicleWheel.h" + +#include "Carla.h" +#include "Carla/Game/CarlaHUD.h" +#include "Carla/Game/CarlaStatics.h" +#include "Carla/Trigger/FrictionTrigger.h" +#include "Carla/Util/ActorAttacher.h" +#include "Carla/Util/EmptyActor.h" +#include "Carla/Util/BoundingBoxCalculator.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" + +// ============================================================================= +// -- Constructor and destructor ----------------------------------------------- +// ============================================================================= + +ACarlaWheeledVehicle::ACarlaWheeledVehicle(const FObjectInitializer& ObjectInitializer) : + Super(ObjectInitializer) +{ + VehicleBounds = CreateDefaultSubobject(TEXT("VehicleBounds")); + VehicleBounds->SetupAttachment(RootComponent); + VehicleBounds->SetHiddenInGame(true); + VehicleBounds->SetCollisionProfileName(UCollisionProfile::NoCollision_ProfileName); + + VelocityControl = CreateDefaultSubobject(TEXT("VelocityControl")); + VelocityControl->Deactivate(); + + GetVehicleMovementComponent()->bReverseAsBrake = false; + + BaseMovementComponent = CreateDefaultSubobject(TEXT("BaseMovementComponent")); + + // Initialize audio components + ConstructSounds(); + + // Initialize collision sound upon collisions + ConstructCollisionHandler(); +} + +ACarlaWheeledVehicle::~ACarlaWheeledVehicle() {} + +void ACarlaWheeledVehicle::SetWheelCollision(UWheeledVehicleMovementComponent4W *Vehicle4W, + const FVehiclePhysicsControl &PhysicsControl ) { + + #ifdef WHEEL_SWEEP_ENABLED + const bool IsBike = IsTwoWheeledVehicle(); + + if (IsBike) + return; + + const bool IsEqual = Vehicle4W->UseSweepWheelCollision == PhysicsControl.UseSweepWheelCollision; + + if (IsEqual) + return; + + Vehicle4W->UseSweepWheelCollision = PhysicsControl.UseSweepWheelCollision; + + #else + + if (PhysicsControl.UseSweepWheelCollision) + UE_LOG(LogCarla, Warning, TEXT("Error: Sweep for wheel collision is not available. \ + Make sure you have installed the required patch.") ); + + #endif + +} + +void ACarlaWheeledVehicle::BeginPlay() +{ + Super::BeginPlay(); + + UDefaultMovementComponent::CreateDefaultMovementComponent(this); + + // Get constraint components and their initial transforms + FTransform ActorInverseTransform = GetActorTransform().Inverse(); + ConstraintsComponents.Empty(); + DoorComponentsTransform.Empty(); + ConstraintDoor.Empty(); + for (FName& ComponentName : ConstraintComponentNames) + { + UPhysicsConstraintComponent* ConstraintComponent = + Cast(GetDefaultSubobjectByName(ComponentName)); + if (ConstraintComponent) + { + UPrimitiveComponent* DoorComponent = Cast( + GetDefaultSubobjectByName(ConstraintComponent->ComponentName1.ComponentName)); + if(DoorComponent) + { + UE_LOG(LogCarla, Warning, TEXT("Door name: %s"), *(DoorComponent->GetName())); + FTransform ComponentWorldTransform = DoorComponent->GetComponentTransform(); + FTransform RelativeTransform = ComponentWorldTransform * ActorInverseTransform; + DoorComponentsTransform.Add(DoorComponent, RelativeTransform); + ConstraintDoor.Add(ConstraintComponent, DoorComponent); + ConstraintsComponents.Add(ConstraintComponent); + ConstraintComponent->TermComponentConstraint(); + } + else + { + UE_LOG(LogCarla, Error, TEXT("Missing component for constraint: %s"), *(ConstraintComponent->GetName())); + } + } + } + ResetConstraints(); + + // get collision disable constraints (used to prevent doors from colliding with each other) + CollisionDisableConstraints.Empty(); + TArray Constraints; + GetComponents(Constraints); + for (UPhysicsConstraintComponent* Constraint : Constraints) + { + if (!ConstraintsComponents.Contains(Constraint)) + { + UPrimitiveComponent* CollisionDisabledComponent1 = Cast( + GetDefaultSubobjectByName(Constraint->ComponentName1.ComponentName)); + UPrimitiveComponent* CollisionDisabledComponent2 = Cast( + GetDefaultSubobjectByName(Constraint->ComponentName2.ComponentName)); + if (CollisionDisabledComponent1) + { + CollisionDisableConstraints.Add(CollisionDisabledComponent1, Constraint); + } + if (CollisionDisabledComponent2) + { + CollisionDisableConstraints.Add(CollisionDisabledComponent2, Constraint); + } + } + } + + float FrictionScale = 3.5f; + + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( + GetVehicleMovementComponent()); + check(Vehicle4W != nullptr); + + // Setup Tire Configs with default value. This is needed to avoid getting + // friction values of previously created TireConfigs for the same vehicle + // blueprint. + TArray OriginalFrictions; + OriginalFrictions.Init(FrictionScale, Vehicle4W->Wheels.Num()); + SetWheelsFrictionScale(OriginalFrictions); + + // Check if it overlaps with a Friction trigger, if so, update the friction + // scale. + TArray OverlapActors; + GetOverlappingActors(OverlapActors, AFrictionTrigger::StaticClass()); + for (const auto &Actor : OverlapActors) + { + AFrictionTrigger *FrictionTrigger = Cast(Actor); + if (FrictionTrigger) + { + FrictionScale = FrictionTrigger->Friction; + } + } + + // Set the friction scale to Wheel CDO and update wheel setups + TArray NewWheelSetups = Vehicle4W->WheelSetups; + + for (const auto &WheelSetup : NewWheelSetups) + { + UVehicleWheel *Wheel = WheelSetup.WheelClass.GetDefaultObject(); + check(Wheel != nullptr); + } + + Vehicle4W->WheelSetups = NewWheelSetups; + + LastPhysicsControl = GetVehiclePhysicsControl(); + + // Turn off all audio until vehicle starts running + SetVolume(0); +} + +void ACarlaWheeledVehicle::Tick(float DeltaSeconds) +{ + Super::Tick(DeltaSeconds); + + // Play sound that requires constant ticking + TickSounds(DeltaSeconds); +} + +// ============================================================================= +// -- Sound Functions ---------------------------------------------------------- +// ============================================================================= + +float ACarlaWheeledVehicle::Volume = 1.f; // static for all non-ego vehicles (use DReyeVRLevel::SetVolume) + +void ACarlaWheeledVehicle::ConstructSounds() +{ + // add all sounds here + + static ConstructorHelpers::FObjectFinder EngineCueObj( + TEXT("SoundCue'/Game/DReyeVR/Sounds/EngineRev/EngineRev.EngineRev'")); + EngineRevSound = CreateDefaultSubobject(FName("EngineRevSound")); + EngineRevSound->SetupAttachment(GetRootComponent()); // attach to self + EngineRevSound->bAutoActivate = true; // start playing on begin + EngineRevSound->SetSound(EngineCueObj.Object); // using this sound + EngineRevSound->SetRelativeLocation(EngineLocnInVehicle); // location of "engine" in vehicle (3D sound) + EngineRevSound->SetFloatParameter(FName("RPM"), 0.f); // initially idle + EngineRevSound->bAutoDestroy = false; // No automatic destroy, persist along with vehicle + check(EngineRevSound != nullptr); + + static ConstructorHelpers::FObjectFinder CarCrashCue( + TEXT("SoundCue'/Game/DReyeVR/Sounds/Crash/CrashCue.CrashCue'")); + CrashSound = CreateDefaultSubobject(TEXT("CarCrash")); + CrashSound->SetupAttachment(GetRootComponent()); + CrashSound->bAutoActivate = false; + CrashSound->SetSound(CarCrashCue.Object); + CrashSound->bAutoDestroy = false; + check(CrashSound != nullptr); +} + +void ACarlaWheeledVehicle::TickSounds(float DeltaSeconds) +{ + // Respect the global vehicle volume param + SetVolume(ACarlaWheeledVehicle::Volume); + + if (EngineRevSound) + { + if (!EngineRevSound->IsPlaying()) + { + EngineRevSound->Play(); // turn on the engine sound if not already on + } + float RPM = FMath::Clamp(GetVehicleMovementComponent()->GetEngineRotationSpeed(), 0.f, 5650.0f); + EngineRevSound->SetFloatParameter(FName("RPM"), RPM); + } + // add other sounds that need tick-level granularity here... +} + +void ACarlaWheeledVehicle::SetVolume(const float VolumeIn) +{ + if (EngineRevSound) + EngineRevSound->SetVolumeMultiplier(VolumeIn); + if (CrashSound) + CrashSound->SetVolumeMultiplier(VolumeIn); +} + +// ============================================================================= +// -- Collision Functions ------------------------------------------------------ +// ============================================================================= + +void ACarlaWheeledVehicle::ConstructCollisionHandler() +{ + // using Carla's GetVehicleBoundingBox function + UBoxComponent *Bounds = this->GetVehicleBoundingBox(); + Bounds->SetGenerateOverlapEvents(true); + Bounds->SetCollisionEnabled(ECollisionEnabled::QueryOnly); + Bounds->SetCollisionProfileName(TEXT("Trigger")); + Bounds->OnComponentBeginOverlap.AddDynamic(this, &ACarlaWheeledVehicle::OnOverlapBegin); +} + +bool ACarlaWheeledVehicle::EnableCollisionForActor(AActor *OtherActor) +{ + // define whether or not we should "collide" with these actors + // as opposed to actors such as the ground/grass + const FString OtherName = OtherActor->GetName().ToLower(); + double Now = GetWorld()->GetTimeSeconds(); + bool bIsAVehicle = OtherActor->IsA(ACarlaWheeledVehicle::StaticClass()); + return (CollisionCooldownTime < Now && // respect collision audio cooldown + (bIsAVehicle || // do collide with vehicles + OtherName.Contains("spline") || // do collide with carla "spline" (misc) objects + OtherName.Contains("streetlight") || // do collide with street lights + OtherName.Contains("curb") // do collide with curb objects + )); +} + +void ACarlaWheeledVehicle::OnOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, + UPrimitiveComponent *OtherComp, int32 OtherBodyIndex, bool bFromSweep, + const FHitResult &SweepResult) +{ + if (OtherActor == nullptr || OtherActor == this) + return; + + // can be more flexible, such as having collisions with static props or people too + if (EnableCollisionForActor(OtherActor)) + { + // emit the car collision sound at the midpoint between the vehicles' collision + /// TODO: would be ideal to use FHitPoint::ImpactPoint but there is a bug in UE4 where this is not initialized + // see: https://answers.unrealengine.com/questions/219744/component-overlap-hit-position-always-returns-000.html + FVector SoundEmitLocation = EngineLocnInVehicle; + bool bIsAVehicle = OtherActor->IsA(ACarlaWheeledVehicle::StaticClass()); + if (bIsAVehicle) { // in the case where the other actor is a vehicle, do emit the sound at the location midpoint + SoundEmitLocation = (OtherActor->GetActorLocation() - this->GetActorLocation()) / 2.f; + SoundEmitLocation += 75.f * FVector::UpVector; // Make the sound emitted not at the ground (0.75m above ground) + } + if (CrashSound != nullptr) { + CrashSound->SetRelativeLocation(SoundEmitLocation); + CrashSound->Play(); + CollisionCooldownTime = GetWorld()->GetTimeSeconds() + 0.5f; // have at least 0.5s of buffer between collision audio + } + } +} + +// ============================================================================= +// -- CARLA -------------------------------------------------------------------- +// ============================================================================= + +void ACarlaWheeledVehicle::AdjustVehicleBounds() +{ + FBoundingBox BoundingBox = UBoundingBoxCalculator::GetVehicleBoundingBox(this); + + const FTransform& CompToWorldTransform = RootComponent->GetComponentTransform(); + const FRotator Rotation = CompToWorldTransform.GetRotation().Rotator(); + const FVector Translation = CompToWorldTransform.GetLocation(); + const FVector Scale = CompToWorldTransform.GetScale3D(); + + // Invert BB origin to local space + BoundingBox.Origin -= Translation; + BoundingBox.Origin = Rotation.UnrotateVector(BoundingBox.Origin); + BoundingBox.Origin /= Scale; + + // Prepare Box Collisions + FTransform Transform; + Transform.SetTranslation(BoundingBox.Origin); + VehicleBounds->SetRelativeTransform(Transform); + VehicleBounds->SetBoxExtent(BoundingBox.Extent); +} + +// ============================================================================= +// -- Get functions ------------------------------------------------------------ +// ============================================================================= + +float ACarlaWheeledVehicle::GetVehicleForwardSpeed() const +{ + return BaseMovementComponent->GetVehicleForwardSpeed(); +} + +FVector ACarlaWheeledVehicle::GetVehicleOrientation() const +{ + return GetVehicleTransform().GetRotation().GetForwardVector(); +} + +int32 ACarlaWheeledVehicle::GetVehicleCurrentGear() const +{ + return BaseMovementComponent->GetVehicleCurrentGear(); +} + +FTransform ACarlaWheeledVehicle::GetVehicleBoundingBoxTransform() const +{ + return VehicleBounds->GetRelativeTransform(); +} + +FVector ACarlaWheeledVehicle::GetVehicleBoundingBoxExtent() const +{ + return VehicleBounds->GetScaledBoxExtent(); +} + +float ACarlaWheeledVehicle::GetMaximumSteerAngle() const +{ + const auto &Wheels = GetVehicleMovementComponent()->Wheels; + check(Wheels.Num() > 0); + const auto *FrontWheel = Wheels[0]; + check(FrontWheel != nullptr); + return FrontWheel->SteerAngle; +} + +// ============================================================================= +// -- Set functions ------------------------------------------------------------ +// ============================================================================= + +void ACarlaWheeledVehicle::FlushVehicleControl() +{ + BaseMovementComponent->ProcessControl(InputControl.Control); + InputControl.Control.bReverse = InputControl.Control.Gear < 0; + LastAppliedControl = InputControl.Control; + InputControl.Priority = EVehicleInputPriority::INVALID; +} + +void ACarlaWheeledVehicle::SetThrottleInput(const float Value) +{ + FVehicleControl Control = InputControl.Control; + Control.Throttle = Value; + ApplyVehicleControl(Control, EVehicleInputPriority::User); +} + +void ACarlaWheeledVehicle::SetSteeringInput(const float Value) +{ + FVehicleControl Control = InputControl.Control; + Control.Steer = Value; + ApplyVehicleControl(Control, EVehicleInputPriority::User); +} + +void ACarlaWheeledVehicle::SetBrakeInput(const float Value) +{ + FVehicleControl Control = InputControl.Control; + Control.Brake = Value; + ApplyVehicleControl(Control, EVehicleInputPriority::User); +} + +void ACarlaWheeledVehicle::SetReverse(const bool Value) +{ + FVehicleControl Control = InputControl.Control; + Control.bReverse = Value; + ApplyVehicleControl(Control, EVehicleInputPriority::User); +} + +void ACarlaWheeledVehicle::SetHandbrakeInput(const bool Value) +{ + FVehicleControl Control = InputControl.Control; + Control.bHandBrake = Value; + ApplyVehicleControl(Control, EVehicleInputPriority::User); +} + +TArray ACarlaWheeledVehicle::GetWheelsFrictionScale() +{ + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( + GetVehicleMovement()); + check(Vehicle4W != nullptr); + + TArray WheelsFrictionScale; + for (auto &Wheel : Vehicle4W->Wheels) + { + WheelsFrictionScale.Add(Wheel->TireConfig->GetFrictionScale()); + } + return WheelsFrictionScale; +} + +void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray &WheelsFrictionScale) +{ + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( + GetVehicleMovement()); + check(Vehicle4W != nullptr); + check(Vehicle4W->Wheels.Num() == WheelsFrictionScale.Num()); + + for (int32 i = 0; i < Vehicle4W->Wheels.Num(); ++i) + { + Vehicle4W->Wheels[i]->TireConfig->SetFrictionScale(WheelsFrictionScale[i]); + } +} + +FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const +{ + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( + GetVehicleMovement()); + check(Vehicle4W != nullptr); + + FVehiclePhysicsControl PhysicsControl; + + // Engine Setup + PhysicsControl.TorqueCurve = Vehicle4W->EngineSetup.TorqueCurve.EditorCurveData; + PhysicsControl.MaxRPM = Vehicle4W->EngineSetup.MaxRPM; + PhysicsControl.MOI = Vehicle4W->EngineSetup.MOI; + PhysicsControl.DampingRateFullThrottle = Vehicle4W->EngineSetup.DampingRateFullThrottle; + PhysicsControl.DampingRateZeroThrottleClutchEngaged = + Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchEngaged; + PhysicsControl.DampingRateZeroThrottleClutchDisengaged = + Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchDisengaged; + + // Transmission Setup + PhysicsControl.bUseGearAutoBox = Vehicle4W->TransmissionSetup.bUseGearAutoBox; + PhysicsControl.GearSwitchTime = Vehicle4W->TransmissionSetup.GearSwitchTime; + PhysicsControl.ClutchStrength = Vehicle4W->TransmissionSetup.ClutchStrength; + PhysicsControl.FinalRatio = Vehicle4W->TransmissionSetup.FinalRatio; + + TArray ForwardGears; + + for (const auto &Gear : Vehicle4W->TransmissionSetup.ForwardGears) + { + FGearPhysicsControl GearPhysicsControl; + + GearPhysicsControl.Ratio = Gear.Ratio; + GearPhysicsControl.UpRatio = Gear.UpRatio; + GearPhysicsControl.DownRatio = Gear.DownRatio; + + ForwardGears.Add(GearPhysicsControl); + } + + PhysicsControl.ForwardGears = ForwardGears; + + // Vehicle Setup + PhysicsControl.Mass = Vehicle4W->Mass; + PhysicsControl.DragCoefficient = Vehicle4W->DragCoefficient; + + // Center of mass offset (Center of mass is always zero vector in local + // position) + UPrimitiveComponent *UpdatedPrimitive = Cast(Vehicle4W->UpdatedComponent); + check(UpdatedPrimitive != nullptr); + + PhysicsControl.CenterOfMass = UpdatedPrimitive->BodyInstance.COMNudge; + + // Transmission Setup + PhysicsControl.SteeringCurve = Vehicle4W->SteeringCurve.EditorCurveData; + + // Wheels Setup + TArray Wheels; + + for (int32 i = 0; i < Vehicle4W->WheelSetups.Num(); ++i) + { + FWheelPhysicsControl PhysicsWheel; + + PxVehicleWheelData PWheelData = Vehicle4W->PVehicle->mWheelsSimData.getWheelData(i); + PhysicsWheel.DampingRate = Cm2ToM2(PWheelData.mDampingRate); + PhysicsWheel.MaxSteerAngle = FMath::RadiansToDegrees(PWheelData.mMaxSteer); + PhysicsWheel.Radius = PWheelData.mRadius; + PhysicsWheel.MaxBrakeTorque = Cm2ToM2(PWheelData.mMaxBrakeTorque); + PhysicsWheel.MaxHandBrakeTorque = Cm2ToM2(PWheelData.mMaxHandBrakeTorque); + + PxVehicleTireData PTireData = Vehicle4W->PVehicle->mWheelsSimData.getTireData(i); + PhysicsWheel.LatStiffMaxLoad = PTireData.mLatStiffX; + PhysicsWheel.LatStiffValue = PTireData.mLatStiffY; + PhysicsWheel.LongStiffValue = PTireData.mLongitudinalStiffnessPerUnitGravity; + + PhysicsWheel.TireFriction = Vehicle4W->Wheels[i]->TireConfig->GetFrictionScale(); + PhysicsWheel.Position = Vehicle4W->Wheels[i]->Location; + + Wheels.Add(PhysicsWheel); + } + + PhysicsControl.Wheels = Wheels; + + return PhysicsControl; +} + +FVehicleLightState ACarlaWheeledVehicle::GetVehicleLightState() const +{ + return InputControl.LightState; +} + +void ACarlaWheeledVehicle::RestoreVehiclePhysicsControl() +{ + ApplyVehiclePhysicsControl(LastPhysicsControl); +} + +void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl) +{ + LastPhysicsControl = PhysicsControl; + + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( + GetVehicleMovement()); + check(Vehicle4W != nullptr); + + // Engine Setup + Vehicle4W->EngineSetup.TorqueCurve.EditorCurveData = PhysicsControl.TorqueCurve; + Vehicle4W->EngineSetup.MaxRPM = PhysicsControl.MaxRPM; + + Vehicle4W->EngineSetup.MOI = PhysicsControl.MOI; + + Vehicle4W->EngineSetup.DampingRateFullThrottle = PhysicsControl.DampingRateFullThrottle; + Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchEngaged = + PhysicsControl.DampingRateZeroThrottleClutchEngaged; + Vehicle4W->EngineSetup.DampingRateZeroThrottleClutchDisengaged = + PhysicsControl.DampingRateZeroThrottleClutchDisengaged; + + // Transmission Setup + Vehicle4W->TransmissionSetup.bUseGearAutoBox = PhysicsControl.bUseGearAutoBox; + Vehicle4W->TransmissionSetup.GearSwitchTime = PhysicsControl.GearSwitchTime; + Vehicle4W->TransmissionSetup.ClutchStrength = PhysicsControl.ClutchStrength; + Vehicle4W->TransmissionSetup.FinalRatio = PhysicsControl.FinalRatio; + + TArray ForwardGears; + + for (const auto &Gear : PhysicsControl.ForwardGears) + { + FVehicleGearData GearData; + + GearData.Ratio = Gear.Ratio; + GearData.UpRatio = Gear.UpRatio; + GearData.DownRatio = Gear.DownRatio; + + ForwardGears.Add(GearData); + } + + Vehicle4W->TransmissionSetup.ForwardGears = ForwardGears; + + // Vehicle Setup + Vehicle4W->Mass = PhysicsControl.Mass; + Vehicle4W->DragCoefficient = PhysicsControl.DragCoefficient; + + // Center of mass + UPrimitiveComponent *UpdatedPrimitive = Cast(Vehicle4W->UpdatedComponent); + check(UpdatedPrimitive != nullptr); + + UpdatedPrimitive->BodyInstance.COMNudge = PhysicsControl.CenterOfMass; + + // Transmission Setup + Vehicle4W->SteeringCurve.EditorCurveData = PhysicsControl.SteeringCurve; + + // Wheels Setup + const int PhysicsWheelsNum = PhysicsControl.Wheels.Num(); + if (PhysicsWheelsNum != 4) + { + UE_LOG(LogCarla, Error, TEXT("Number of WheelPhysicsControl is not 4.")); + return; + } + + // Change, if required, the collision mode for wheels + SetWheelCollision(Vehicle4W, PhysicsControl); + + TArray NewWheelSetups = Vehicle4W->WheelSetups; + + for (int32 i = 0; i < PhysicsWheelsNum; ++i) + { + UVehicleWheel *Wheel = NewWheelSetups[i].WheelClass.GetDefaultObject(); + check(Wheel != nullptr); + + // Assigning new tire config + Wheel->TireConfig = DuplicateObject(Wheel->TireConfig, nullptr); + + // Setting a new value to friction + Wheel->TireConfig->SetFrictionScale(PhysicsControl.Wheels[i].TireFriction); + } + + Vehicle4W->WheelSetups = NewWheelSetups; + + // Recreate Physics State for vehicle setup + GetWorld()->GetPhysicsScene()->GetPxScene()->lockWrite(); + Vehicle4W->RecreatePhysicsState(); + GetWorld()->GetPhysicsScene()->GetPxScene()->unlockWrite(); + + for (int32 i = 0; i < PhysicsWheelsNum; ++i) + { + PxVehicleWheelData PWheelData = Vehicle4W->PVehicle->mWheelsSimData.getWheelData(i); + + PWheelData.mRadius = PhysicsControl.Wheels[i].Radius; + PWheelData.mMaxSteer = FMath::DegreesToRadians(PhysicsControl.Wheels[i].MaxSteerAngle); + PWheelData.mDampingRate = M2ToCm2(PhysicsControl.Wheels[i].DampingRate); + PWheelData.mMaxBrakeTorque = M2ToCm2(PhysicsControl.Wheels[i].MaxBrakeTorque); + PWheelData.mMaxHandBrakeTorque = M2ToCm2(PhysicsControl.Wheels[i].MaxHandBrakeTorque); + Vehicle4W->PVehicle->mWheelsSimData.setWheelData(i, PWheelData); + + PxVehicleTireData PTireData = Vehicle4W->PVehicle->mWheelsSimData.getTireData(i); + PTireData.mLatStiffX = PhysicsControl.Wheels[i].LatStiffMaxLoad; + PTireData.mLatStiffY = PhysicsControl.Wheels[i].LatStiffValue; + PTireData.mLongitudinalStiffnessPerUnitGravity = PhysicsControl.Wheels[i].LongStiffValue; + Vehicle4W->PVehicle->mWheelsSimData.setTireData(i, PTireData); + } + + ResetConstraints(); + + auto * Recorder = UCarlaStatics::GetRecorder(GetWorld()); + if (Recorder && Recorder->IsEnabled()) + { + Recorder->AddPhysicsControl(*this); + } +} + +void ACarlaWheeledVehicle::ActivateVelocityControl(const FVector &Velocity) +{ + VelocityControl->Activate(Velocity); +} + +void ACarlaWheeledVehicle::DeactivateVelocityControl() +{ + VelocityControl->Deactivate(); +} + +void ACarlaWheeledVehicle::ShowDebugTelemetry(bool Enabled) +{ + if (GetWorld()->GetFirstPlayerController()) + { + ACarlaHUD* hud = Cast(GetWorld()->GetFirstPlayerController()->GetHUD()); + if (hud) { + + // Set/Unset the car movement component in HUD to show the temetry + if (Enabled) { + hud->AddDebugVehicleForTelemetry(GetVehicleMovementComponent()); + } + else{ + if (hud->DebugVehicle == GetVehicleMovementComponent()) { + hud->AddDebugVehicleForTelemetry(nullptr); + GetVehicleMovementComponent()->StopTelemetry(); + } + } + + } + else { + UE_LOG(LogCarla, Warning, TEXT("ACarlaWheeledVehicle::ShowDebugTelemetry:: Cannot find HUD for debug info")); + } + } +} + +void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState &LightState) +{ + InputControl.LightState = LightState; + RefreshLightState(LightState); +} + +void ACarlaWheeledVehicle::SetCarlaMovementComponent(UBaseCarlaMovementComponent* MovementComponent) +{ + if (BaseMovementComponent) + { + BaseMovementComponent->DestroyComponent(); + } + BaseMovementComponent = MovementComponent; +} + +void ACarlaWheeledVehicle::SetWheelSteerDirection(EVehicleWheelLocation WheelLocation, float AngleInDeg) { + + if (bPhysicsEnabled == false) + { + check((uint8)WheelLocation >= 0) + check((uint8)WheelLocation < 4) + UVehicleAnimInstance *VehicleAnim = Cast(GetMesh()->GetAnimInstance()); + check(VehicleAnim != nullptr) + VehicleAnim->SetWheelRotYaw((uint8)WheelLocation, AngleInDeg); + } + else + { + UE_LOG(LogTemp, Warning, TEXT("Cannot set wheel steer direction. Physics are enabled.")) + } +} + +float ACarlaWheeledVehicle::GetWheelSteerAngle(EVehicleWheelLocation WheelLocation) { + + check((uint8)WheelLocation >= 0) + check((uint8)WheelLocation < 4) + UVehicleAnimInstance *VehicleAnim = Cast(GetMesh()->GetAnimInstance()); + check(VehicleAnim != nullptr) + check(VehicleAnim->GetWheeledVehicleMovementComponent() != nullptr) + + if (bPhysicsEnabled == true) + { + return VehicleAnim->GetWheeledVehicleMovementComponent()->Wheels[(uint8)WheelLocation]->GetSteerAngle(); + } + else + { + return VehicleAnim->GetWheelRotAngle((uint8)WheelLocation); + } +} + +void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { + if(!GetCarlaMovementComponent()) + { + return; + } + + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( + GetVehicleMovement()); + check(Vehicle4W != nullptr); + + if(bPhysicsEnabled == enabled) + return; + + SetActorEnableCollision(true); + auto RootComponent = Cast(GetRootComponent()); + RootComponent->SetSimulatePhysics(enabled); + RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); + + UVehicleAnimInstance *VehicleAnim = Cast(GetMesh()->GetAnimInstance()); + check(VehicleAnim != nullptr) + + GetWorld()->GetPhysicsScene()->GetPxScene()->lockWrite(); + if (enabled) + { + Vehicle4W->RecreatePhysicsState(); + VehicleAnim->ResetWheelCustomRotations(); + } + else + { + Vehicle4W->DestroyPhysicsState(); + } + + GetWorld()->GetPhysicsScene()->GetPxScene()->unlockWrite(); + + bPhysicsEnabled = enabled; + + ResetConstraints(); + +} + +void ACarlaWheeledVehicle::ResetConstraints() +{ + for (int i = 0; i < ConstraintsComponents.Num(); i++) + { + OpenDoorPhys(EVehicleDoor(i)); + } + for (int i = 0; i < ConstraintsComponents.Num(); i++) + { + CloseDoorPhys(EVehicleDoor(i)); + } +} + +FVector ACarlaWheeledVehicle::GetVelocity() const +{ + return BaseMovementComponent->GetVelocity(); +} + +void ACarlaWheeledVehicle::EndPlay(const EEndPlayReason::Type EndPlayReason) +{ + ShowDebugTelemetry(false); +} + +void ACarlaWheeledVehicle::OpenDoor(const EVehicleDoor DoorIdx) { + if (int(DoorIdx) >= ConstraintsComponents.Num() && DoorIdx != EVehicleDoor::All) { + UE_LOG(LogTemp, Warning, TEXT("This door is not configured for this car.")); + return; + } + + if (DoorIdx == EVehicleDoor::All) { + for (int i = 0; i < ConstraintsComponents.Num(); i++) + { + OpenDoorPhys(EVehicleDoor(i)); + } + return; + } + + OpenDoorPhys(DoorIdx); +} + +void ACarlaWheeledVehicle::CloseDoor(const EVehicleDoor DoorIdx) { + if (int(DoorIdx) >= ConstraintsComponents.Num() && DoorIdx != EVehicleDoor::All) { + UE_LOG(LogTemp, Warning, TEXT("This door is not configured for this car.")); + return; + } + + if (DoorIdx == EVehicleDoor::All) { + for (int i = 0; i < ConstraintsComponents.Num(); i++) + { + CloseDoorPhys(EVehicleDoor(i)); + } + return; + } + + CloseDoorPhys(DoorIdx); +} + +void ACarlaWheeledVehicle::OpenDoorPhys(const EVehicleDoor DoorIdx) +{ + UPhysicsConstraintComponent* Constraint = ConstraintsComponents[static_cast(DoorIdx)]; + UPrimitiveComponent* DoorComponent = ConstraintDoor[Constraint]; + DoorComponent->DetachFromComponent( + FDetachmentTransformRules(EDetachmentRule::KeepWorld, false)); + FTransform DoorInitialTransform = + DoorComponentsTransform[DoorComponent] * GetActorTransform(); + DoorComponent->SetWorldTransform(DoorInitialTransform); + DoorComponent->SetSimulatePhysics(true); + DoorComponent->SetCollisionProfileName(TEXT("BlockAll")); + float AngleLimit = Constraint->ConstraintInstance.GetAngularSwing1Limit(); + FRotator AngularRotationOffset = Constraint->ConstraintInstance.AngularRotationOffset; + + if (Constraint->ConstraintInstance.AngularRotationOffset.Yaw < 0.0f) + { + AngleLimit = -AngleLimit; + } + Constraint->SetAngularOrientationTarget(FRotator(0, AngleLimit, 0)); + Constraint->SetAngularDriveParams(DoorOpenStrength, 1.0, 0.0); + + Constraint->InitComponentConstraint(); + + UPhysicsConstraintComponent** CollisionDisable = + CollisionDisableConstraints.Find(DoorComponent); + if (CollisionDisable) + { + (*CollisionDisable)->InitComponentConstraint(); + } +} + +void ACarlaWheeledVehicle::CloseDoorPhys(const EVehicleDoor DoorIdx) +{ + UPhysicsConstraintComponent* Constraint = ConstraintsComponents[static_cast(DoorIdx)]; + UPrimitiveComponent* DoorComponent = ConstraintDoor[Constraint]; + FTransform DoorInitialTransform = + DoorComponentsTransform[DoorComponent] * GetActorTransform(); + DoorComponent->SetSimulatePhysics(false); + DoorComponent->SetCollisionProfileName(TEXT("NoCollision")); + DoorComponent->SetWorldTransform(DoorInitialTransform); + DoorComponent->AttachToComponent( + GetMesh(), FAttachmentTransformRules(EAttachmentRule::KeepWorld, true)); +} diff --git a/Carla/Vehicle/CarlaWheeledVehicle.h b/Carla/Vehicle/CarlaWheeledVehicle.h index 2257e65..51e82a6 100644 --- a/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Carla/Vehicle/CarlaWheeledVehicle.h @@ -1,379 +1,379 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "WheeledVehicle.h" - -#include "Vehicle/CarlaWheeledVehicleState.h" -#include "Vehicle/VehicleControl.h" -#include "Vehicle/VehicleLightState.h" -#include "Vehicle/VehicleInputPriority.h" -#include "Vehicle/VehiclePhysicsControl.h" -#include "VehicleVelocityControl.h" -#include "WheeledVehicleMovementComponent4W.h" -#include "VehicleAnimInstance.h" -#include "PhysicsEngine/PhysicsConstraintComponent.h" -#include "MovementComponents/BaseCarlaMovementComponent.h" -#include "Components/AudioComponent.h" // UAudioComponent -#include "Sound/SoundCue.h" // USoundCue - -#include "CoreMinimal.h" - -//-----CARSIM-------------------------------- -#ifdef WITH_CARSIM -#include "CarSimMovementComponent.h" -#endif -//------------------------------------------- - -#include "CarlaWheeledVehicle.generated.h" - -class UBoxComponent; - -UENUM() -enum class EVehicleWheelLocation : uint8 { - - FL_Wheel = 0, - FR_Wheel = 1, - BL_Wheel = 2, - BR_Wheel = 3, - //Use for bikes and bicycles - Front_Wheel = 0, - Back_Wheel = 1, -}; - -/// Type of door to open/close -// When adding new door types, make sure that All is the last one. -UENUM(BlueprintType) -enum class EVehicleDoor : uint8 { - FL = 0, - FR = 1, - RL = 2, - RR = 3, - Hood = 4, - Trunk = 5, - All = 6 -}; - -/// Base class for CARLA wheeled vehicles. -UCLASS() -class CARLA_API ACarlaWheeledVehicle : public AWheeledVehicle -{ - GENERATED_BODY() - - // =========================================================================== - /// @name Constructor and destructor - // =========================================================================== - /// @{ -public: - - ACarlaWheeledVehicle(const FObjectInitializer &ObjectInitializer); - - ~ACarlaWheeledVehicle(); - - /// @} - // =========================================================================== - /// @name Get functions - // =========================================================================== - /// @{ -public: - - /// Vehicle control currently applied to this vehicle. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - const FVehicleControl &GetVehicleControl() const - { - return LastAppliedControl; - } - - /// Transform of the vehicle. Location is shifted so it matches center of the - /// vehicle bounds rather than the actor's location. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - FTransform GetVehicleTransform() const - { - return GetActorTransform(); - } - - /// Forward speed in cm/s. Might be negative if goes backwards. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - float GetVehicleForwardSpeed() const; - - /// Orientation vector of the vehicle, pointing forward. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - FVector GetVehicleOrientation() const; - - /// Active gear of the vehicle. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - int32 GetVehicleCurrentGear() const; - - /// Transform of the vehicle's bounding box relative to the vehicle. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - FTransform GetVehicleBoundingBoxTransform() const; - - /// Extent of the vehicle's bounding box. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - FVector GetVehicleBoundingBoxExtent() const; - - /// Get vehicle's bounding box component. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - UBoxComponent *GetVehicleBoundingBox() const - { - return VehicleBounds; - } - - /// Get the maximum angle at which the front wheel can steer. - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - float GetMaximumSteerAngle() const; - - /// @} - // =========================================================================== - /// @name AI debug state - // =========================================================================== - /// @{ -public: - - /// @todo This function should be private to AWheeledVehicleAIController. - void SetAIVehicleState(ECarlaWheeledVehicleState InState) - { - State = InState; - } - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - ECarlaWheeledVehicleState GetAIVehicleState() const - { - return State; - } - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - FVehiclePhysicsControl GetVehiclePhysicsControl() const; - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void RestoreVehiclePhysicsControl(); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - FVehicleLightState GetVehicleLightState() const; - - void ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void SetSimulatePhysics(bool enabled); - - void SetWheelCollision(UWheeledVehicleMovementComponent4W *Vehicle4W, const FVehiclePhysicsControl &PhysicsControl); - - void SetVehicleLightState(const FVehicleLightState &LightState); - - UFUNCTION(BlueprintNativeEvent) - bool IsTwoWheeledVehicle(); - virtual bool IsTwoWheeledVehicle_Implementation() { - return false; - } - - /// @} - // =========================================================================== - /// @name Vehicle input control - // =========================================================================== - /// @{ -public: - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void ApplyVehicleControl(const FVehicleControl &Control, EVehicleInputPriority Priority) - { - if (InputControl.Priority <= Priority) - { - InputControl.Control = Control; - InputControl.Priority = Priority; - } - } - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void ActivateVelocityControl(const FVector &Velocity); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void DeactivateVelocityControl(); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void ShowDebugTelemetry(bool Enabled); - - /// @todo This function should be private to AWheeledVehicleAIController. - void FlushVehicleControl(); - - /// @} - // =========================================================================== - /// @name DEPRECATED Set functions - // =========================================================================== - /// @{ -public: - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void SetThrottleInput(float Value); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void SetSteeringInput(float Value); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void SetBrakeInput(float Value); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void SetReverse(bool Value); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void ToggleReverse() - { - SetReverse(!LastAppliedControl.bReverse); - } - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void SetHandbrakeInput(bool Value); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void HoldHandbrake() - { - SetHandbrakeInput(true); - } - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void ReleaseHandbrake() - { - SetHandbrakeInput(false); - } - - TArray GetWheelsFrictionScale(); - - void SetWheelsFrictionScale(TArray &WheelsFrictionScale); - - void SetCarlaMovementComponent(UBaseCarlaMovementComponent* MoementComponent); - - template - T* GetCarlaMovementComponent() const - { - return Cast(BaseMovementComponent); - } - - static float Volume; - virtual void SetVolume(const float VolumeIn); - void PlayCrashSound(const float DelayBeforePlay = 0.f) const; - /// @} - // =========================================================================== - /// @name Overriden from AActor - // =========================================================================== - /// @{ - - virtual void Tick(float DeltaTime) override; // called once per frame -protected: - - virtual void BeginPlay() override; - virtual void EndPlay(const EEndPlayReason::Type EndPlayReason); - - // sounds (DReyeVR) - void ConstructSounds(); - virtual void TickSounds(float DeltaSeconds); - UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - FVector EngineLocnInVehicle{180.f, 0.f, 70.f}; - // need to disable these for EgoVehicle to have our own Ego versions - UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UAudioComponent *EngineRevSound = nullptr; // driver feedback on throttle - UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UAudioComponent *CrashSound = nullptr; // crashing with another actor - double CollisionCooldownTime = 0.0; - // can add more sounds here... like a horn maybe? - - // collisions (DReyeVR) - bool EnableCollisionForActor(AActor *OtherActor); - void ConstructCollisionHandler(); // needs to be called in the constructor - UFUNCTION() - void OnOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, UPrimitiveComponent *OtherComp, - int32 OtherBodyIndex, bool bFromSweep, const FHitResult &SweepResult); - - UFUNCTION(BlueprintImplementableEvent) - void RefreshLightState(const FVehicleLightState &VehicleLightState); - - UFUNCTION(BlueprintCallable, CallInEditor) - void AdjustVehicleBounds(); - - UPROPERTY(Category="Door Animation", EditAnywhere, BlueprintReadWrite) - TArray ConstraintComponentNames; - - UPROPERTY(Category="Door Animation", EditAnywhere, BlueprintReadWrite) - float DoorOpenStrength = 100.0f; - - UFUNCTION(BlueprintCallable, CallInEditor) - void ResetConstraints(); - -private: - - /// Current state of the vehicle controller (for debugging purposes). - UPROPERTY(Category = "AI Controller", VisibleAnywhere) - ECarlaWheeledVehicleState State = ECarlaWheeledVehicleState::UNKNOWN; - - UPROPERTY(Category = "CARLA Wheeled Vehicle", EditAnywhere) - UBoxComponent *VehicleBounds; - - UPROPERTY(Category = "CARLA Wheeled Vehicle", EditAnywhere) - UVehicleVelocityControl* VelocityControl; - - struct - { - EVehicleInputPriority Priority = EVehicleInputPriority::INVALID; - FVehicleControl Control; - FVehicleLightState LightState; - } - InputControl; - - FVehicleControl LastAppliedControl; - FVehiclePhysicsControl LastPhysicsControl; - -public: - - /// Set the rotation of the car wheels indicated by the user - /// 0 = FL_VehicleWheel, 1 = FR_VehicleWheel, 2 = BL_VehicleWheel, 3 = BR_VehicleWheel - /// NOTE : This is purely aesthetic. It will not modify the physics of the car in any way - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void SetWheelSteerDirection(EVehicleWheelLocation WheelLocation, float AngleInDeg); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - float GetWheelSteerAngle(EVehicleWheelLocation WheelLocation); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void OpenDoor(const EVehicleDoor DoorIdx); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void CloseDoor(const EVehicleDoor DoorIdx); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void OpenDoorPhys(const EVehicleDoor DoorIdx); - - UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) - void CloseDoorPhys(const EVehicleDoor DoorIdx); - - virtual FVector GetVelocity() const override; - -//-----CARSIM-------------------------------- - UPROPERTY(Category="CARLA Wheeled Vehicle", EditAnywhere) - float CarSimOriginOffset = 150.f; -//------------------------------------------- - -private: - - UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere) - bool bPhysicsEnabled = true; - - // Small workarround to allow optional CarSim plugin usage - UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - UBaseCarlaMovementComponent * BaseMovementComponent = nullptr; - - UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - TArray ConstraintsComponents; - - UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - TMap ConstraintDoor; - - // container of the initial transform of the door, used to reset its position - UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - TMap DoorComponentsTransform; - - UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - TMap CollisionDisableConstraints; - -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "WheeledVehicle.h" + +#include "Vehicle/CarlaWheeledVehicleState.h" +#include "Vehicle/VehicleControl.h" +#include "Vehicle/VehicleLightState.h" +#include "Vehicle/VehicleInputPriority.h" +#include "Vehicle/VehiclePhysicsControl.h" +#include "VehicleVelocityControl.h" +#include "WheeledVehicleMovementComponent4W.h" +#include "VehicleAnimInstance.h" +#include "PhysicsEngine/PhysicsConstraintComponent.h" +#include "MovementComponents/BaseCarlaMovementComponent.h" +#include "Components/AudioComponent.h" // UAudioComponent +#include "Sound/SoundCue.h" // USoundCue + +#include "CoreMinimal.h" + +//-----CARSIM-------------------------------- +#ifdef WITH_CARSIM +#include "CarSimMovementComponent.h" +#endif +//------------------------------------------- + +#include "CarlaWheeledVehicle.generated.h" + +class UBoxComponent; + +UENUM() +enum class EVehicleWheelLocation : uint8 { + + FL_Wheel = 0, + FR_Wheel = 1, + BL_Wheel = 2, + BR_Wheel = 3, + //Use for bikes and bicycles + Front_Wheel = 0, + Back_Wheel = 1, +}; + +/// Type of door to open/close +// When adding new door types, make sure that All is the last one. +UENUM(BlueprintType) +enum class EVehicleDoor : uint8 { + FL = 0, + FR = 1, + RL = 2, + RR = 3, + Hood = 4, + Trunk = 5, + All = 6 +}; + +/// Base class for CARLA wheeled vehicles. +UCLASS() +class CARLA_API ACarlaWheeledVehicle : public AWheeledVehicle +{ + GENERATED_BODY() + + // =========================================================================== + /// @name Constructor and destructor + // =========================================================================== + /// @{ +public: + + ACarlaWheeledVehicle(const FObjectInitializer &ObjectInitializer); + + ~ACarlaWheeledVehicle(); + + /// @} + // =========================================================================== + /// @name Get functions + // =========================================================================== + /// @{ +public: + + /// Vehicle control currently applied to this vehicle. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + const FVehicleControl &GetVehicleControl() const + { + return LastAppliedControl; + } + + /// Transform of the vehicle. Location is shifted so it matches center of the + /// vehicle bounds rather than the actor's location. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FTransform GetVehicleTransform() const + { + return GetActorTransform(); + } + + /// Forward speed in cm/s. Might be negative if goes backwards. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + float GetVehicleForwardSpeed() const; + + /// Orientation vector of the vehicle, pointing forward. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FVector GetVehicleOrientation() const; + + /// Active gear of the vehicle. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + int32 GetVehicleCurrentGear() const; + + /// Transform of the vehicle's bounding box relative to the vehicle. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FTransform GetVehicleBoundingBoxTransform() const; + + /// Extent of the vehicle's bounding box. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FVector GetVehicleBoundingBoxExtent() const; + + /// Get vehicle's bounding box component. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + UBoxComponent *GetVehicleBoundingBox() const + { + return VehicleBounds; + } + + /// Get the maximum angle at which the front wheel can steer. + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + float GetMaximumSteerAngle() const; + + /// @} + // =========================================================================== + /// @name AI debug state + // =========================================================================== + /// @{ +public: + + /// @todo This function should be private to AWheeledVehicleAIController. + void SetAIVehicleState(ECarlaWheeledVehicleState InState) + { + State = InState; + } + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + ECarlaWheeledVehicleState GetAIVehicleState() const + { + return State; + } + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FVehiclePhysicsControl GetVehiclePhysicsControl() const; + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void RestoreVehiclePhysicsControl(); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FVehicleLightState GetVehicleLightState() const; + + void ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void SetSimulatePhysics(bool enabled); + + void SetWheelCollision(UWheeledVehicleMovementComponent4W *Vehicle4W, const FVehiclePhysicsControl &PhysicsControl); + + void SetVehicleLightState(const FVehicleLightState &LightState); + + UFUNCTION(BlueprintNativeEvent) + bool IsTwoWheeledVehicle(); + virtual bool IsTwoWheeledVehicle_Implementation() { + return false; + } + + /// @} + // =========================================================================== + /// @name Vehicle input control + // =========================================================================== + /// @{ +public: + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void ApplyVehicleControl(const FVehicleControl &Control, EVehicleInputPriority Priority) + { + if (InputControl.Priority <= Priority) + { + InputControl.Control = Control; + InputControl.Priority = Priority; + } + } + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void ActivateVelocityControl(const FVector &Velocity); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void DeactivateVelocityControl(); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void ShowDebugTelemetry(bool Enabled); + + /// @todo This function should be private to AWheeledVehicleAIController. + void FlushVehicleControl(); + + /// @} + // =========================================================================== + /// @name DEPRECATED Set functions + // =========================================================================== + /// @{ +public: + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void SetThrottleInput(float Value); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void SetSteeringInput(float Value); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void SetBrakeInput(float Value); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void SetReverse(bool Value); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void ToggleReverse() + { + SetReverse(!LastAppliedControl.bReverse); + } + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void SetHandbrakeInput(bool Value); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void HoldHandbrake() + { + SetHandbrakeInput(true); + } + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void ReleaseHandbrake() + { + SetHandbrakeInput(false); + } + + TArray GetWheelsFrictionScale(); + + void SetWheelsFrictionScale(TArray &WheelsFrictionScale); + + void SetCarlaMovementComponent(UBaseCarlaMovementComponent* MoementComponent); + + template + T* GetCarlaMovementComponent() const + { + return Cast(BaseMovementComponent); + } + + static float Volume; + virtual void SetVolume(const float VolumeIn); + void PlayCrashSound(const float DelayBeforePlay = 0.f) const; + /// @} + // =========================================================================== + /// @name Overriden from AActor + // =========================================================================== + /// @{ + + virtual void Tick(float DeltaTime) override; // called once per frame +protected: + + virtual void BeginPlay() override; + virtual void EndPlay(const EEndPlayReason::Type EndPlayReason); + + // sounds (DReyeVR) + void ConstructSounds(); + virtual void TickSounds(float DeltaSeconds); + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + FVector EngineLocnInVehicle{180.f, 0.f, 70.f}; + // need to disable these for EgoVehicle to have our own Ego versions + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *EngineRevSound = nullptr; // driver feedback on throttle + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *CrashSound = nullptr; // crashing with another actor + double CollisionCooldownTime = 0.0; + // can add more sounds here... like a horn maybe? + + // collisions (DReyeVR) + bool EnableCollisionForActor(AActor *OtherActor); + void ConstructCollisionHandler(); // needs to be called in the constructor + UFUNCTION() + void OnOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, UPrimitiveComponent *OtherComp, + int32 OtherBodyIndex, bool bFromSweep, const FHitResult &SweepResult); + + UFUNCTION(BlueprintImplementableEvent) + void RefreshLightState(const FVehicleLightState &VehicleLightState); + + UFUNCTION(BlueprintCallable, CallInEditor) + void AdjustVehicleBounds(); + + UPROPERTY(Category="Door Animation", EditAnywhere, BlueprintReadWrite) + TArray ConstraintComponentNames; + + UPROPERTY(Category="Door Animation", EditAnywhere, BlueprintReadWrite) + float DoorOpenStrength = 100.0f; + + UFUNCTION(BlueprintCallable, CallInEditor) + void ResetConstraints(); + +private: + + /// Current state of the vehicle controller (for debugging purposes). + UPROPERTY(Category = "AI Controller", VisibleAnywhere) + ECarlaWheeledVehicleState State = ECarlaWheeledVehicleState::UNKNOWN; + + UPROPERTY(Category = "CARLA Wheeled Vehicle", EditAnywhere) + UBoxComponent *VehicleBounds; + + UPROPERTY(Category = "CARLA Wheeled Vehicle", EditAnywhere) + UVehicleVelocityControl* VelocityControl; + + struct + { + EVehicleInputPriority Priority = EVehicleInputPriority::INVALID; + FVehicleControl Control; + FVehicleLightState LightState; + } + InputControl; + + FVehicleControl LastAppliedControl; + FVehiclePhysicsControl LastPhysicsControl; + +public: + + /// Set the rotation of the car wheels indicated by the user + /// 0 = FL_VehicleWheel, 1 = FR_VehicleWheel, 2 = BL_VehicleWheel, 3 = BR_VehicleWheel + /// NOTE : This is purely aesthetic. It will not modify the physics of the car in any way + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void SetWheelSteerDirection(EVehicleWheelLocation WheelLocation, float AngleInDeg); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + float GetWheelSteerAngle(EVehicleWheelLocation WheelLocation); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void OpenDoor(const EVehicleDoor DoorIdx); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void CloseDoor(const EVehicleDoor DoorIdx); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void OpenDoorPhys(const EVehicleDoor DoorIdx); + + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + void CloseDoorPhys(const EVehicleDoor DoorIdx); + + virtual FVector GetVelocity() const override; + +//-----CARSIM-------------------------------- + UPROPERTY(Category="CARLA Wheeled Vehicle", EditAnywhere) + float CarSimOriginOffset = 150.f; +//------------------------------------------- + +private: + + UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere) + bool bPhysicsEnabled = true; + + // Small workarround to allow optional CarSim plugin usage + UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) + UBaseCarlaMovementComponent * BaseMovementComponent = nullptr; + + UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) + TArray ConstraintsComponents; + + UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) + TMap ConstraintDoor; + + // container of the initial transform of the door, used to reset its position + UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) + TMap DoorComponentsTransform; + + UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) + TMap CollisionDisableConstraints; + +}; diff --git a/Carla/Weather/Weather.cpp b/Carla/Weather/Weather.cpp index 2319ad1..12a6c56 100644 --- a/Carla/Weather/Weather.cpp +++ b/Carla/Weather/Weather.cpp @@ -1,90 +1,90 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "Carla.h" -#include "Carla/Weather/Weather.h" -#include "Carla/Game/CarlaStatics.h" - -AWeather::AWeather(const FObjectInitializer& ObjectInitializer) - : Super(ObjectInitializer) -{ - PrimaryActorTick.bCanEverTick = false; - RootComponent = ObjectInitializer.CreateDefaultSubobject(this, TEXT("RootComponent")); -} - -void AWeather::ApplyWeather(const FWeatherParameters &InWeather) -{ - SetWeather(InWeather); - -#ifdef CARLA_WEATHER_EXTRA_LOG - UE_LOG(LogCarla, Log, TEXT("Changing weather:")); - UE_LOG(LogCarla, Log, TEXT(" - Cloudiness = %.2f"), Weather.Cloudiness); - UE_LOG(LogCarla, Log, TEXT(" - Precipitation = %.2f"), Weather.Precipitation); - UE_LOG(LogCarla, Log, TEXT(" - PrecipitationDeposits = %.2f"), Weather.PrecipitationDeposits); - UE_LOG(LogCarla, Log, TEXT(" - WindIntensity = %.2f"), Weather.WindIntensity); - UE_LOG(LogCarla, Log, TEXT(" - SunAzimuthAngle = %.2f"), Weather.SunAzimuthAngle); - UE_LOG(LogCarla, Log, TEXT(" - SunAltitudeAngle = %.2f"), Weather.SunAltitudeAngle); - UE_LOG(LogCarla, Log, TEXT(" - FogDensity = %.2f"), Weather.FogDensity); - UE_LOG(LogCarla, Log, TEXT(" - FogDistance = %.2f"), Weather.FogDistance); - UE_LOG(LogCarla, Log, TEXT(" - FogFalloff = %.2f"), Weather.FogFalloff); - UE_LOG(LogCarla, Log, TEXT(" - Wetness = %.2f"), Weather.Wetness); - UE_LOG(LogCarla, Log, TEXT(" - ScatteringIntensity = %.2f"), Weather.ScatteringIntensity); - UE_LOG(LogCarla, Log, TEXT(" - MieScatteringScale = %.2f"), Weather.MieScatteringScale); - UE_LOG(LogCarla, Log, TEXT(" - RayleighScatteringScale = %.2f"), Weather.RayleighScatteringScale); -#endif // CARLA_WEATHER_EXTRA_LOG - - // Call the blueprint that actually changes the weather. - RefreshWeather(Weather); -} - -void AWeather::NotifyWeather() -{ - // Call the blueprint that actually changes the weather. - RefreshWeather(Weather); -} - -void AWeather::SetWeather(const FWeatherParameters &InWeather) -{ - // check if weather has changed (else, do nothing) - if (InWeather != Weather) - { - Weather = InWeather; - - // Record the weather update - AddWeatherToRecorder(); - } -} - -void AWeather::AddWeatherToRecorder() const -{ - auto *Recorder = UCarlaStatics::GetRecorder(GetWorld()); - if (Recorder && Recorder->IsEnabled()) - { - Recorder->AddWeather(GetCurrentWeather()); - } -} - -AWeather *AWeather::FindWeatherInstance(UWorld *World) -{ - if(World) - { - // find the Weather actor in the world (TODO: spawn if necessary) - TArray FoundWeathers; - UGameplayStatics::GetAllActorsOfClass(World, AWeather::StaticClass(), FoundWeathers); - if (FoundWeathers.Num() > 0) - { - /// TODO: check for more than one weather(s) - return CastChecked(FoundWeathers[0]); - } - else - { - UE_LOG(LogCarla, Error, TEXT("No Weather actor found in world")); - return nullptr; - } - } - UE_LOG(LogCarla, Error, TEXT("UWorld unavailable for finding weather")); - return nullptr; -} +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Carla.h" +#include "Carla/Weather/Weather.h" +#include "Carla/Game/CarlaStatics.h" + +AWeather::AWeather(const FObjectInitializer& ObjectInitializer) + : Super(ObjectInitializer) +{ + PrimaryActorTick.bCanEverTick = false; + RootComponent = ObjectInitializer.CreateDefaultSubobject(this, TEXT("RootComponent")); +} + +void AWeather::ApplyWeather(const FWeatherParameters &InWeather) +{ + SetWeather(InWeather); + +#ifdef CARLA_WEATHER_EXTRA_LOG + UE_LOG(LogCarla, Log, TEXT("Changing weather:")); + UE_LOG(LogCarla, Log, TEXT(" - Cloudiness = %.2f"), Weather.Cloudiness); + UE_LOG(LogCarla, Log, TEXT(" - Precipitation = %.2f"), Weather.Precipitation); + UE_LOG(LogCarla, Log, TEXT(" - PrecipitationDeposits = %.2f"), Weather.PrecipitationDeposits); + UE_LOG(LogCarla, Log, TEXT(" - WindIntensity = %.2f"), Weather.WindIntensity); + UE_LOG(LogCarla, Log, TEXT(" - SunAzimuthAngle = %.2f"), Weather.SunAzimuthAngle); + UE_LOG(LogCarla, Log, TEXT(" - SunAltitudeAngle = %.2f"), Weather.SunAltitudeAngle); + UE_LOG(LogCarla, Log, TEXT(" - FogDensity = %.2f"), Weather.FogDensity); + UE_LOG(LogCarla, Log, TEXT(" - FogDistance = %.2f"), Weather.FogDistance); + UE_LOG(LogCarla, Log, TEXT(" - FogFalloff = %.2f"), Weather.FogFalloff); + UE_LOG(LogCarla, Log, TEXT(" - Wetness = %.2f"), Weather.Wetness); + UE_LOG(LogCarla, Log, TEXT(" - ScatteringIntensity = %.2f"), Weather.ScatteringIntensity); + UE_LOG(LogCarla, Log, TEXT(" - MieScatteringScale = %.2f"), Weather.MieScatteringScale); + UE_LOG(LogCarla, Log, TEXT(" - RayleighScatteringScale = %.2f"), Weather.RayleighScatteringScale); +#endif // CARLA_WEATHER_EXTRA_LOG + + // Call the blueprint that actually changes the weather. + RefreshWeather(Weather); +} + +void AWeather::NotifyWeather() +{ + // Call the blueprint that actually changes the weather. + RefreshWeather(Weather); +} + +void AWeather::SetWeather(const FWeatherParameters &InWeather) +{ + // check if weather has changed (else, do nothing) + if (InWeather != Weather) + { + Weather = InWeather; + + // Record the weather update + AddWeatherToRecorder(); + } +} + +void AWeather::AddWeatherToRecorder() const +{ + auto *Recorder = UCarlaStatics::GetRecorder(GetWorld()); + if (Recorder && Recorder->IsEnabled()) + { + Recorder->AddWeather(GetCurrentWeather()); + } +} + +AWeather *AWeather::FindWeatherInstance(UWorld *World) +{ + if(World) + { + // find the Weather actor in the world (TODO: spawn if necessary) + TArray FoundWeathers; + UGameplayStatics::GetAllActorsOfClass(World, AWeather::StaticClass(), FoundWeathers); + if (FoundWeathers.Num() > 0) + { + /// TODO: check for more than one weather(s) + return CastChecked(FoundWeathers[0]); + } + else + { + UE_LOG(LogCarla, Error, TEXT("No Weather actor found in world")); + return nullptr; + } + } + UE_LOG(LogCarla, Error, TEXT("UWorld unavailable for finding weather")); + return nullptr; +} diff --git a/Carla/Weather/Weather.h b/Carla/Weather/Weather.h index 1d76b8b..302551a 100644 --- a/Carla/Weather/Weather.h +++ b/Carla/Weather/Weather.h @@ -1,55 +1,55 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "GameFramework/Actor.h" - -#include "Carla/Weather/WeatherParameters.h" - -#include "Weather.generated.h" - -UCLASS(Abstract) -class CARLA_API AWeather : public AActor -{ - GENERATED_BODY() - -public: - - AWeather(const FObjectInitializer& ObjectInitializer); - - /// Update the weather parameters and notifies it to the blueprint's event - UFUNCTION(BlueprintCallable) - void ApplyWeather(const FWeatherParameters &WeatherParameters); - - /// Notifing the weather to the blueprint's event - void NotifyWeather(); - - /// Update the weather parameters without notifing it to the blueprint's event - UFUNCTION(BlueprintCallable) - void SetWeather(const FWeatherParameters &WeatherParameters); - - /// Returns the current WeatherParameters - UFUNCTION(BlueprintCallable) - const FWeatherParameters &GetCurrentWeather() const - { - return Weather; - } - - static AWeather *FindWeatherInstance(UWorld *World); - -protected: - - UFUNCTION(BlueprintImplementableEvent) - void RefreshWeather(const FWeatherParameters &WeatherParameters); - -private: - - void AddWeatherToRecorder() const; - - UPROPERTY(VisibleAnywhere) - FWeatherParameters Weather; -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "GameFramework/Actor.h" + +#include "Carla/Weather/WeatherParameters.h" + +#include "Weather.generated.h" + +UCLASS(Abstract) +class CARLA_API AWeather : public AActor +{ + GENERATED_BODY() + +public: + + AWeather(const FObjectInitializer& ObjectInitializer); + + /// Update the weather parameters and notifies it to the blueprint's event + UFUNCTION(BlueprintCallable) + void ApplyWeather(const FWeatherParameters &WeatherParameters); + + /// Notifing the weather to the blueprint's event + void NotifyWeather(); + + /// Update the weather parameters without notifing it to the blueprint's event + UFUNCTION(BlueprintCallable) + void SetWeather(const FWeatherParameters &WeatherParameters); + + /// Returns the current WeatherParameters + UFUNCTION(BlueprintCallable) + const FWeatherParameters &GetCurrentWeather() const + { + return Weather; + } + + static AWeather *FindWeatherInstance(UWorld *World); + +protected: + + UFUNCTION(BlueprintImplementableEvent) + void RefreshWeather(const FWeatherParameters &WeatherParameters); + +private: + + void AddWeatherToRecorder() const; + + UPROPERTY(VisibleAnywhere) + FWeatherParameters Weather; +}; diff --git a/Carla/Weather/WeatherParameters.h b/Carla/Weather/WeatherParameters.h index a6fdac0..b223f12 100644 --- a/Carla/Weather/WeatherParameters.h +++ b/Carla/Weather/WeatherParameters.h @@ -1,97 +1,97 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "WeatherParameters.generated.h" - -USTRUCT(BlueprintType) -struct CARLA_API FWeatherParameters -{ - GENERATED_BODY() - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) - float Cloudiness = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) - float Precipitation = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) - float PrecipitationDeposits = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) - float WindIntensity = 0.35f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "360.0", UIMin = "0.0", UIMax = "360.0")) - float SunAzimuthAngle = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "-90.0", ClampMax = "90.0", UIMin = "-90.0", UIMax = "90.0")) - float SunAltitudeAngle = 75.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) - float FogDensity = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", UIMin = "0.0", UIMax = "1000.0")) - float FogDistance = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", UIMin = "0.0", UIMax = "10.0")) - float FogFalloff = 0.2f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) - float Wetness = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) - float ScatteringIntensity = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "5.0", UIMin = "0.0", UIMax = "5.0")) - float MieScatteringScale = 0.0f; - - UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "2.0", UIMin = "0.0", UIMax = "2.0")) - float RayleighScatteringScale = 0.0331f; - - bool operator==(const FWeatherParameters &Other) const - { - return ( - Cloudiness == Other.Cloudiness && - Precipitation == Other.Precipitation && - PrecipitationDeposits == Other.PrecipitationDeposits && - WindIntensity == Other.WindIntensity && - SunAzimuthAngle == Other.SunAzimuthAngle && - SunAltitudeAngle == Other.SunAltitudeAngle && - FogDensity == Other.FogDensity && - FogDistance == Other.FogDistance && - FogFalloff == Other.FogFalloff && - Wetness == Other.Wetness && - ScatteringIntensity == Other.ScatteringIntensity && - MieScatteringScale == Other.MieScatteringScale && - RayleighScatteringScale == Other.RayleighScatteringScale - ); - } - - bool operator!=(const FWeatherParameters &Other) const - { - return !(*this == Other); - } - - FString ToString() const - { - FString Print; - Print += FString::Printf(TEXT("Cloudiness: %.2f, "), Cloudiness); - Print += FString::Printf(TEXT("Precipitation: %.2f, "), Precipitation); - Print += FString::Printf(TEXT("PrecipitationDeposits: %.2f, "), PrecipitationDeposits); - Print += FString::Printf(TEXT("WindIntensity: %.2f, "), WindIntensity); - Print += FString::Printf(TEXT("SunAzimuthAngle: %.2f, "), SunAzimuthAngle); - Print += FString::Printf(TEXT("SunAltitudeAngle: %.2f, "), SunAltitudeAngle); - Print += FString::Printf(TEXT("FogDensity: %.2f, "), FogDensity); - Print += FString::Printf(TEXT("FogDistance: %.2f, "), FogDistance); - Print += FString::Printf(TEXT("FogFalloff: %.2f, "), FogFalloff); - Print += FString::Printf(TEXT("Wetness: %.2f, "), Wetness); - Print += FString::Printf(TEXT("ScatteringIntensity: %.2f, "), ScatteringIntensity); - Print += FString::Printf(TEXT("MieScatteringScale: %.2f, "), MieScatteringScale); - Print += FString::Printf(TEXT("RayleighScatteringScale: %.2f, "), RayleighScatteringScale); - return Print; - } -}; +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "WeatherParameters.generated.h" + +USTRUCT(BlueprintType) +struct CARLA_API FWeatherParameters +{ + GENERATED_BODY() + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) + float Cloudiness = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) + float Precipitation = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) + float PrecipitationDeposits = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) + float WindIntensity = 0.35f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "360.0", UIMin = "0.0", UIMax = "360.0")) + float SunAzimuthAngle = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "-90.0", ClampMax = "90.0", UIMin = "-90.0", UIMax = "90.0")) + float SunAltitudeAngle = 75.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) + float FogDensity = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", UIMin = "0.0", UIMax = "1000.0")) + float FogDistance = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", UIMin = "0.0", UIMax = "10.0")) + float FogFalloff = 0.2f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) + float Wetness = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "100.0", UIMin = "0.0", UIMax = "100.0")) + float ScatteringIntensity = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "5.0", UIMin = "0.0", UIMax = "5.0")) + float MieScatteringScale = 0.0f; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, meta=(ClampMin = "0.0", ClampMax = "2.0", UIMin = "0.0", UIMax = "2.0")) + float RayleighScatteringScale = 0.0331f; + + bool operator==(const FWeatherParameters &Other) const + { + return ( + Cloudiness == Other.Cloudiness && + Precipitation == Other.Precipitation && + PrecipitationDeposits == Other.PrecipitationDeposits && + WindIntensity == Other.WindIntensity && + SunAzimuthAngle == Other.SunAzimuthAngle && + SunAltitudeAngle == Other.SunAltitudeAngle && + FogDensity == Other.FogDensity && + FogDistance == Other.FogDistance && + FogFalloff == Other.FogFalloff && + Wetness == Other.Wetness && + ScatteringIntensity == Other.ScatteringIntensity && + MieScatteringScale == Other.MieScatteringScale && + RayleighScatteringScale == Other.RayleighScatteringScale + ); + } + + bool operator!=(const FWeatherParameters &Other) const + { + return !(*this == Other); + } + + FString ToString() const + { + FString Print; + Print += FString::Printf(TEXT("Cloudiness: %.2f, "), Cloudiness); + Print += FString::Printf(TEXT("Precipitation: %.2f, "), Precipitation); + Print += FString::Printf(TEXT("PrecipitationDeposits: %.2f, "), PrecipitationDeposits); + Print += FString::Printf(TEXT("WindIntensity: %.2f, "), WindIntensity); + Print += FString::Printf(TEXT("SunAzimuthAngle: %.2f, "), SunAzimuthAngle); + Print += FString::Printf(TEXT("SunAltitudeAngle: %.2f, "), SunAltitudeAngle); + Print += FString::Printf(TEXT("FogDensity: %.2f, "), FogDensity); + Print += FString::Printf(TEXT("FogDistance: %.2f, "), FogDistance); + Print += FString::Printf(TEXT("FogFalloff: %.2f, "), FogFalloff); + Print += FString::Printf(TEXT("Wetness: %.2f, "), Wetness); + Print += FString::Printf(TEXT("ScatteringIntensity: %.2f, "), ScatteringIntensity); + Print += FString::Printf(TEXT("MieScatteringScale: %.2f, "), MieScatteringScale); + Print += FString::Printf(TEXT("RayleighScatteringScale: %.2f, "), RayleighScatteringScale); + return Print; + } +}; diff --git a/CarlaUE4/CarlaUE4.Build.cs b/CarlaUE4/CarlaUE4.Build.cs index a42e7fb..2639835 100644 --- a/CarlaUE4/CarlaUE4.Build.cs +++ b/CarlaUE4/CarlaUE4.Build.cs @@ -1,84 +1,84 @@ -// Fill out your copyright notice in the Description page of Project Settings. - -using System; -using System.IO; -using UnrealBuildTool; - -public class CarlaUE4 : ModuleRules -{ - private bool IsWindows(ReadOnlyTargetRules Target) - { - return (Target.Platform == UnrealTargetPlatform.Win64) || (Target.Platform == UnrealTargetPlatform.Win32); - } - public CarlaUE4(ReadOnlyTargetRules Target) : base(Target) - { - PrivatePCHHeaderFile = "CarlaUE4.h"; - ShadowVariableWarningLevel = WarningLevel.Off; // -Wno-shadow - - // include LibCarla so we can #include headers - string LibCarlaIncludePath = - Path.GetFullPath(Path.Combine(ModuleDirectory, "..", "..", "..", "..", "LibCarla", "source")); - PublicIncludePaths.Add(LibCarlaIncludePath); - PrivateIncludePaths.Add(LibCarlaIncludePath); - - PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "UMG" }); - - if (Target.Type == TargetType.Editor) - { - PublicDependencyModuleNames.AddRange(new string[] { "UnrealEd" }); - } - else - { - // only build this carla exception in package mode - PublicDefinitions.Add("NO_DREYEVR_EXCEPTIONS"); - } - - // Add module for SteamVR support with UE4 - PublicDependencyModuleNames.AddRange(new string[] { "HeadMountedDisplay" }); - - if (IsWindows(Target)) - { - bEnableExceptions = true; // enable unwind semantics for C++-style exceptions - } - - //////////////////////////////////////////////////////////////////////////////////// - // Edit these variables to enable/disable features of DReyeVR - bool UseSRanipalPlugin = true; - bool UseLogitechPlugin = true; - bool UseFoveatedRender = false; // currently only supported in editor - //////////////////////////////////////////////////////////////////////////////////// - - if (!IsWindows(Target)) - { - // adjust definitions so they are OS-compatible - UseSRanipalPlugin = false; // SRanipal only works on Windows - UseLogitechPlugin = false; // LogitechWheelPlugin also only works on Windows - UseFoveatedRender = false; // Vive VRS plugin requires engine fork - } - - // Add these preprocessor definitions to code - PublicDefinitions.Add("USE_SRANIPAL_PLUGIN=" + (UseSRanipalPlugin ? "true" : "false")); - PublicDefinitions.Add("USE_LOGITECH_PLUGIN=" + (UseLogitechPlugin ? "true" : "false")); - PublicDefinitions.Add("USE_FOVEATED_RENDER=" + (UseFoveatedRender ? "true" : "false")); - - // Add plugin dependencies - if (UseSRanipalPlugin) - { - PrivateDependencyModuleNames.AddRange(new string[] { "SRanipal", "SRanipalEye" }); - PrivateIncludePathModuleNames.AddRange(new string[] { "SRanipal", "SRanipalEye" }); - } - - if (UseLogitechPlugin) - { - PrivateDependencyModuleNames.AddRange(new string[] { "LogitechWheelPlugin" }); - } - - if (UseFoveatedRender) - { - // Add VRS plugin and and EyeTracker dependencies - PublicDependencyModuleNames.AddRange(new string[] { "EyeTracker", "VRSPlugin" }); - } - - PrivateDependencyModuleNames.AddRange(new string[] { "ImageWriteQueue" }); - } -} +// Fill out your copyright notice in the Description page of Project Settings. + +using System; +using System.IO; +using UnrealBuildTool; + +public class CarlaUE4 : ModuleRules +{ + private bool IsWindows(ReadOnlyTargetRules Target) + { + return (Target.Platform == UnrealTargetPlatform.Win64) || (Target.Platform == UnrealTargetPlatform.Win32); + } + public CarlaUE4(ReadOnlyTargetRules Target) : base(Target) + { + PrivatePCHHeaderFile = "CarlaUE4.h"; + ShadowVariableWarningLevel = WarningLevel.Off; // -Wno-shadow + + // include LibCarla so we can #include headers + string LibCarlaIncludePath = + Path.GetFullPath(Path.Combine(ModuleDirectory, "..", "..", "..", "..", "LibCarla", "source")); + PublicIncludePaths.Add(LibCarlaIncludePath); + PrivateIncludePaths.Add(LibCarlaIncludePath); + + PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "UMG" }); + + if (Target.Type == TargetType.Editor) + { + PublicDependencyModuleNames.AddRange(new string[] { "UnrealEd" }); + } + else + { + // only build this carla exception in package mode + PublicDefinitions.Add("NO_DREYEVR_EXCEPTIONS"); + } + + // Add module for SteamVR support with UE4 + PublicDependencyModuleNames.AddRange(new string[] { "HeadMountedDisplay" }); + + if (IsWindows(Target)) + { + bEnableExceptions = true; // enable unwind semantics for C++-style exceptions + } + + //////////////////////////////////////////////////////////////////////////////////// + // Edit these variables to enable/disable features of DReyeVR + bool UseSRanipalPlugin = true; + bool UseLogitechPlugin = true; + bool UseFoveatedRender = false; // currently only supported in editor + //////////////////////////////////////////////////////////////////////////////////// + + if (!IsWindows(Target)) + { + // adjust definitions so they are OS-compatible + UseSRanipalPlugin = false; // SRanipal only works on Windows + UseLogitechPlugin = false; // LogitechWheelPlugin also only works on Windows + UseFoveatedRender = false; // Vive VRS plugin requires engine fork + } + + // Add these preprocessor definitions to code + PublicDefinitions.Add("USE_SRANIPAL_PLUGIN=" + (UseSRanipalPlugin ? "true" : "false")); + PublicDefinitions.Add("USE_LOGITECH_PLUGIN=" + (UseLogitechPlugin ? "true" : "false")); + PublicDefinitions.Add("USE_FOVEATED_RENDER=" + (UseFoveatedRender ? "true" : "false")); + + // Add plugin dependencies + if (UseSRanipalPlugin) + { + PrivateDependencyModuleNames.AddRange(new string[] { "SRanipal", "SRanipalEye" }); + PrivateIncludePathModuleNames.AddRange(new string[] { "SRanipal", "SRanipalEye" }); + } + + if (UseLogitechPlugin) + { + PrivateDependencyModuleNames.AddRange(new string[] { "LogitechWheelPlugin" }); + } + + if (UseFoveatedRender) + { + // Add VRS plugin and and EyeTracker dependencies + PublicDependencyModuleNames.AddRange(new string[] { "EyeTracker", "VRSPlugin" }); + } + + PrivateDependencyModuleNames.AddRange(new string[] { "ImageWriteQueue" }); + } +} diff --git a/CarlaUE4/CarlaUE4.cpp b/CarlaUE4/CarlaUE4.cpp index f4af712..1ddf467 100644 --- a/CarlaUE4/CarlaUE4.cpp +++ b/CarlaUE4/CarlaUE4.cpp @@ -1,7 +1,7 @@ -// Fill out your copyright notice in the Description page of Project Settings. - -#include "CarlaUE4.h" - -IMPLEMENT_PRIMARY_GAME_MODULE(FDefaultGameModuleImpl, CarlaUE4, "CarlaUE4"); - -DEFINE_LOG_CATEGORY(LogDReyeVR); +// Fill out your copyright notice in the Description page of Project Settings. + +#include "CarlaUE4.h" + +IMPLEMENT_PRIMARY_GAME_MODULE(FDefaultGameModuleImpl, CarlaUE4, "CarlaUE4"); + +DEFINE_LOG_CATEGORY(LogDReyeVR); diff --git a/CarlaUE4/CarlaUE4.h b/CarlaUE4/CarlaUE4.h index cdb9a4b..c7c1779 100644 --- a/CarlaUE4/CarlaUE4.h +++ b/CarlaUE4/CarlaUE4.h @@ -1,36 +1,36 @@ -// Fill out your copyright notice in the Description page of Project Settings. - -#pragma once - -#include "Engine.h" - -#include "Util/NonCopyable.h" - -DECLARE_LOG_CATEGORY_EXTERN(LogDReyeVR, Log, All); - -constexpr inline const char *file_name_only(const char *path) -{ - // note since this is a constexpr function, it gets evaluated at compile time rather - // than runtime so there is no runtime performance overhead! -#ifdef _WIN32 - constexpr char os_sep = '\\'; -#else - constexpr char os_sep = '/'; -#endif - const char *filename_start = path; - while (*path) - { - if (*path++ == os_sep) // keep searching until found last os sep - filename_start = path; - } - return filename_start; // includes extension -} - -// fancy logging that includes [filename::function:line] prefix -#define __DReyeVR_LOG(msg, verbosity, ...) \ - UE_LOG(LogDReyeVR, verbosity, TEXT("[%s::%s:%d] %s"), UTF8_TO_TCHAR(file_name_only(__FILE__)), \ - UTF8_TO_TCHAR(__func__), __LINE__, *FString::Printf(TEXT(msg), ##__VA_ARGS__)); - -#define LOG(msg, ...) __DReyeVR_LOG(msg, Log, ##__VA_ARGS__); -#define LOG_WARN(msg, ...) __DReyeVR_LOG(msg, Warning, ##__VA_ARGS__); -#define LOG_ERROR(msg, ...) __DReyeVR_LOG(msg, Error, ##__VA_ARGS__); +// Fill out your copyright notice in the Description page of Project Settings. + +#pragma once + +#include "Engine.h" + +#include "Util/NonCopyable.h" + +DECLARE_LOG_CATEGORY_EXTERN(LogDReyeVR, Log, All); + +constexpr inline const char *file_name_only(const char *path) +{ + // note since this is a constexpr function, it gets evaluated at compile time rather + // than runtime so there is no runtime performance overhead! +#ifdef _WIN32 + constexpr char os_sep = '\\'; +#else + constexpr char os_sep = '/'; +#endif + const char *filename_start = path; + while (*path) + { + if (*path++ == os_sep) // keep searching until found last os sep + filename_start = path; + } + return filename_start; // includes extension +} + +// fancy logging that includes [filename::function:line] prefix +#define __DReyeVR_LOG(msg, verbosity, ...) \ + UE_LOG(LogDReyeVR, verbosity, TEXT("[%s::%s:%d] %s"), UTF8_TO_TCHAR(file_name_only(__FILE__)), \ + UTF8_TO_TCHAR(__func__), __LINE__, *FString::Printf(TEXT(msg), ##__VA_ARGS__)); + +#define LOG(msg, ...) __DReyeVR_LOG(msg, Log, ##__VA_ARGS__); +#define LOG_WARN(msg, ...) __DReyeVR_LOG(msg, Warning, ##__VA_ARGS__); +#define LOG_ERROR(msg, ...) __DReyeVR_LOG(msg, Error, ##__VA_ARGS__); diff --git a/Config/CarlaUE4.uproject b/Config/CarlaUE4.uproject index 193188b..939391b 100644 --- a/Config/CarlaUE4.uproject +++ b/Config/CarlaUE4.uproject @@ -1,124 +1,124 @@ -{ - "FileVersion": 3, - "EngineAssociation": "4.26", - "Category": "", - "Description": "", - "Modules": [ - { - "Name": "CarlaUE4", - "Type": "Runtime", - "LoadingPhase": "Default", - "AdditionalDependencies": [ - "Engine", - "PhysXVehicles", - "Carla", - "CoreUObject" - ] - } - ], - "Plugins": [ - { - "Name": "Carla", - "Enabled": true - }, - { - "Name": "OnlineSubsystemGooglePlay", - "Enabled": false, - "SupportedTargetPlatforms": [ - "Android" - ] - }, - { - "Name": "AndroidPermission", - "Enabled": false - }, - { - "Name": "AppleARKit", - "Enabled": false - }, - { - "Name": "LocationServicesBPLibrary", - "Enabled": false - }, - { - "Name": "AndroidDeviceProfileSelector", - "Enabled": false - }, - { - "Name": "ExampleDeviceProfileSelector", - "Enabled": false - }, - { - "Name": "IOSDeviceProfileSelector", - "Enabled": false - }, - { - "Name": "UObjectPlugin", - "Enabled": false - }, - { - "Name": "AndroidMedia", - "Enabled": false - }, - { - "Name": "HTML5Networking", - "Enabled": false - }, - { - "Name": "MobileLauncherProfileWizard", - "Enabled": false - }, - { - "Name": "MobilePatchingUtils", - "Enabled": false - }, - { - "Name": "AndroidMoviePlayer", - "Enabled": false - }, - { - "Name": "AppleMoviePlayer", - "Enabled": false - }, - { - "Name": "GoogleCloudMessaging", - "Enabled": false - }, - { - "Name": "PerformanceMonitor", - "Enabled": true - }, - { - "Name": "OculusVR", - "Enabled": false - }, - { - "Name": "SteamVR", - "Enabled": true, - "SupportedTargetPlatforms": [ - "Win32", - "Win64", - "Linux", - "Mac" - ], - "WhitelistPlatforms": [ - "Win32", - "Win64", - "Linux" - ] - }, - { - "Name": "RenderDocPlugin", - "Enabled": true - }, - { - "Name": "CarSim", - "Enabled": false, - "MarketplaceURL": "com.epicgames.launcher://ue/marketplace/content/2d712649ca864c80812da7b5252f5608" - }, - { - "Name": "EditorScriptingUtilities", - "Enabled": true - } - ] +{ + "FileVersion": 3, + "EngineAssociation": "4.26", + "Category": "", + "Description": "", + "Modules": [ + { + "Name": "CarlaUE4", + "Type": "Runtime", + "LoadingPhase": "Default", + "AdditionalDependencies": [ + "Engine", + "PhysXVehicles", + "Carla", + "CoreUObject" + ] + } + ], + "Plugins": [ + { + "Name": "Carla", + "Enabled": true + }, + { + "Name": "OnlineSubsystemGooglePlay", + "Enabled": false, + "SupportedTargetPlatforms": [ + "Android" + ] + }, + { + "Name": "AndroidPermission", + "Enabled": false + }, + { + "Name": "AppleARKit", + "Enabled": false + }, + { + "Name": "LocationServicesBPLibrary", + "Enabled": false + }, + { + "Name": "AndroidDeviceProfileSelector", + "Enabled": false + }, + { + "Name": "ExampleDeviceProfileSelector", + "Enabled": false + }, + { + "Name": "IOSDeviceProfileSelector", + "Enabled": false + }, + { + "Name": "UObjectPlugin", + "Enabled": false + }, + { + "Name": "AndroidMedia", + "Enabled": false + }, + { + "Name": "HTML5Networking", + "Enabled": false + }, + { + "Name": "MobileLauncherProfileWizard", + "Enabled": false + }, + { + "Name": "MobilePatchingUtils", + "Enabled": false + }, + { + "Name": "AndroidMoviePlayer", + "Enabled": false + }, + { + "Name": "AppleMoviePlayer", + "Enabled": false + }, + { + "Name": "GoogleCloudMessaging", + "Enabled": false + }, + { + "Name": "PerformanceMonitor", + "Enabled": true + }, + { + "Name": "OculusVR", + "Enabled": false + }, + { + "Name": "SteamVR", + "Enabled": true, + "SupportedTargetPlatforms": [ + "Win32", + "Win64", + "Linux", + "Mac" + ], + "WhitelistPlatforms": [ + "Win32", + "Win64", + "Linux" + ] + }, + { + "Name": "RenderDocPlugin", + "Enabled": true + }, + { + "Name": "CarSim", + "Enabled": false, + "MarketplaceURL": "com.epicgames.launcher://ue/marketplace/content/2d712649ca864c80812da7b5252f5608" + }, + { + "Name": "EditorScriptingUtilities", + "Enabled": true + } + ] } \ No newline at end of file diff --git a/Config/DReyeVRConfig.ini b/Config/DReyeVRConfig.ini index cd73b09..767ec59 100644 --- a/Config/DReyeVRConfig.ini +++ b/Config/DReyeVRConfig.ini @@ -1,119 +1,119 @@ -# NOTE: this is a weird config file bc it is custom written for DReyeVR -# - use hashtags '#' for comments (supports inline) - -# some serialization formats: -# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) -# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) -# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) -# bool: True or False - -[EgoVehicle] -VehicleType="TeslaM3" # this is the name of the .ini config file in Config/EgoVehicles/ - -# general parameters for all vehicles -SpeedometerInMPH=True # set to False to use KPH -EnableTurnSignalAction=True # True to enable turn signal animation (& sound), else false -TurnSignalDuration=3.0 # time (in s) that the turn signals stay on for -DrawDebugEditor=False # draw debug lines/sphere for eye gaze in the editor - -[CameraParams] -FieldOfView=90.0 # horizontal field of view (only in stereo camera => NOT VR) -ScreenPercentage=100 # 100% is native resolution, increase for supersampling, decrease for subsampling -# all the intensities range from [0 (off) to 1 (maximum)] -MotionBlurIntensity=0 # how much motion blur in the camera -VignetteIntensity=0 # how intense the vignetting is (darkened corners) -BloomIntensity=0 # how intense the bloom is -SceneFringeIntensity=0 # how intense the SceneFringe is -LensFlareIntensity=0 # how intense the lens flares are -GrainIntensity=0 # how intense the grain is - -[EgoSensor] -StreamSensorData=True # Set to False to skip streaming sensor data (for PythonAPI) on every tick -MaxTraceLenM=1000.0 # maximum trace length (in meters) to use for world-hit point calculation -DrawDebugFocusTrace=True # draw the debug focus trace & hit point in editor - -[VehicleInputs] -ScaleSteeringDamping=0.6 -ScaleThrottleInput=1.0 -ScaleBrakeInput=1.0 -InvertMouseY=False -ScaleMouseY=1.0 -ScaleMouseX=1.0 - -[EgoVehicleHUD] -HUDScaleVR=6 # scale all HUD elements in VR mode only -DrawFPSCounter=True # draw's FPS (frames per second) in top right corner of flat screen -DrawFlatReticle=True # reticle in flat-screen mode -DrawGaze=False # draw debug gaze lines on flat-screen hud -DrawSpectatorReticle=True # reticle in spectator mode during vr (VR spectator HUD only) -ReticleSize=100 # (percent) diameter of reticle (thickness also scales) -EnableSpectatorScreen=True # whether or not to enable the flat-screen spectator when in VR - -[Game] -AutomaticallySpawnEgo=True # use to spawn EgoVehicle, o/w defaults to spectator & Ego can be spawned via PythonAPI -DoSpawnEgoVehicleTransform=False # True uses the SpawnEgoVehicleTransform below, False uses Carla's own spawn points -SpawnEgoVehicleTransform=(X=3010, Y=390, Z=0.0 | R=0, P=0.0, Y=0 | X=1.0, Y=1.0, Z=1.0) # !! This is only for Town03 !! - -[Sound] -DefaultEngineRev="SoundCue'/Game/DReyeVR/Sounds/EngineRev/EngineRev.EngineRev'" -DefaultCrashSound="SoundCue'/Game/DReyeVR/Sounds/Crash/CrashCue.CrashCue'" -DefaultGearShiftSound="SoundWave'/Game/DReyeVR/Sounds/GearShift.GearShift'" -DefaultTurnSignalSound="SoundWave'/Game/DReyeVR/Sounds/TurnSignal.TurnSignal'" -EgoVolumePercent=100 -NonEgoVolumePercent=100 -AmbientVolumePercent=20 - -[Replayer] -CameraFollowHMD=True # Whether or not to have the camera pose follow the recorded HMD pose -UseCarlaSpectator=False # Use the built-in Carla spectator (not recommended) or spawn our own (recommended) - -# Enable or disable replay interpolation with *ReplayInterpolation* -# True is the default CARLA behavior, this may cause replay timesteps in between ground truth data -# False ensures that every frame will match exactly with the recorded data at the exact timesteps (no interpolation) -ReplayInterpolation=False # see above - -# for taking per-frame screen capture during replay (for post-hoc analysis) -RecordFrames=True # additionally capture camera screenshots on replay tick (requires no replay interpolation!) -RecordAllShaders=False # Enable or disable rendering the scene with additional (beyond RGB) shaders such as depth -RecordAllPoses=False # Enable or disable rendering the scene with all camera poses (beyond driver's seat) -FileFormatJPG=True # either JPG or PNG -LinearGamma=True # force linear gamme for frame capture render (recommended) -FrameWidth=1280 # resolution x for screenshot -FrameHeight=720 # resolution y for screenshot -FrameDir="FrameCap" # directory name for screenshot -FrameName="tick" # title of screenshot (differentiated via tick-suffix) - -[CameraPose] -# starting pose should be one of: {DriversSeat, Front, BirdsEyeView, ThirdPerson} -StartingPose="DriversSeat" # starting position of camera in vehicle (on begin play) -# offsets from the EgoVehicle's bounding box positions if you need -Front=(X=1.1, Y=0.0, Z=0.3 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # front "license plate" view -BirdsEyeView=(X=0.0, Y=0.0, Z=15 | R=0.0, P=270.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # top down view -ThirdPerson=(X=-2, Y=0.0, Z=4 | R=0.0, P=330.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # back angled view - -[WheelFace] -# ABXY and Dpad buttons as custom-actors on the steering wheel face -EnableWheelButtons=True # enable dpad & ABXY indicator buttons on wheel face or not -ABXYLocation=(X=-7, Y=-10, Z=4) # location relative to steering wheel where the center of ABXY is -DpadLocation=(X=-7, Y=10, Z=4) # location relative to steering wheel where the center of Dpad is -QuadButtonSpread=2.0 # distance between the 4 buttons -# Autopilot status indicator (blue light) -EnableAutopilotIndicator=True # enable blue light indicator for autopilot status -AutopilotIndicatorLoc=(X=-7, Y=0, Z=4) # location relative to steering wheel for center of indicator -AutopilotIndicatorSize=0.03 # size of the indicator - -# for Logitech hardware of the racing sim -[Hardware] -DeviceIdx=0 # Device index of the hardware (Logitech has 2, can be 0 or 1) -LogUpdates=False # whether or not to print debug messages -DeltaInputThreshold=0.02 # how much change the logi wheels need applied to overtake autopilot -ForceFeedbackMagnitude=30 # "Level of saturation" for the physical wheel actuation (0 to 100) - -# VariableRateShading is an experimental attempt to squeeze more performance out of DReyeVR -# by reducing rendering quality of the scene in the periphery, which we should know from the real-time -# gaze tracking. Unfortunately the development to port HTC Vive's VariableRateShading is still WIP and -# currently only works in the Editor, not in a shipping/package game where it'd be most useful. We are -# actively working on this feature and will enable VRS once it is fully supported. -[VariableRateShading] # disabled by default (would need to enable via CarlaUE4.Build.cs flag) -Enabled=True # currently only works in Editor mode (but enabled in Build.cs settings) -UsingEyeTracking=True # use eye tracking for foveated rendering if available +# NOTE: this is a weird config file bc it is custom written for DReyeVR +# - use hashtags '#' for comments (supports inline) + +# some serialization formats: +# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) +# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) +# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) +# bool: True or False + +[EgoVehicle] +VehicleType="TeslaM3" # this is the name of the .ini config file in Config/EgoVehicles/ + +# general parameters for all vehicles +SpeedometerInMPH=True # set to False to use KPH +EnableTurnSignalAction=True # True to enable turn signal animation (& sound), else false +TurnSignalDuration=3.0 # time (in s) that the turn signals stay on for +DrawDebugEditor=True # draw debug lines/sphere for eye gaze in the editor + +[CameraParams] +FieldOfView=90.0 # horizontal field of view (only in stereo camera => NOT VR) +ScreenPercentage=100 # 100% is native resolution, increase for supersampling, decrease for subsampling +# all the intensities range from [0 (off) to 1 (maximum)] +MotionBlurIntensity=0 # how much motion blur in the camera +VignetteIntensity=0 # how intense the vignetting is (darkened corners) +BloomIntensity=0 # how intense the bloom is +SceneFringeIntensity=0 # how intense the SceneFringe is +LensFlareIntensity=0 # how intense the lens flares are +GrainIntensity=0 # how intense the grain is + +[EgoSensor] +StreamSensorData=True # Set to False to skip streaming sensor data (for PythonAPI) on every tick +MaxTraceLenM=1000.0 # maximum trace length (in meters) to use for world-hit point calculation +DrawDebugFocusTrace=True # draw the debug focus trace & hit point in editor + +[VehicleInputs] +ScaleSteeringDamping=0.6 +ScaleThrottleInput=1.0 +ScaleBrakeInput=1.0 +InvertMouseY=False +ScaleMouseY=1.0 +ScaleMouseX=1.0 + +[EgoVehicleHUD] +HUDScaleVR=6 # scale all HUD elements in VR mode only +DrawFPSCounter=True # draw's FPS (frames per second) in top right corner of flat screen +DrawFlatReticle=True # reticle in flat-screen mode +DrawGaze=False # draw debug gaze lines on flat-screen hud +DrawSpectatorReticle=True # reticle in spectator mode during vr (VR spectator HUD only) +ReticleSize=100 # (percent) diameter of reticle (thickness also scales) +EnableSpectatorScreen=True # whether or not to enable the flat-screen spectator when in VR + +[Game] +AutomaticallySpawnEgo=True # use to spawn EgoVehicle, o/w defaults to spectator & Ego can be spawned via PythonAPI +DoSpawnEgoVehicleTransform=False # True uses the SpawnEgoVehicleTransform below, False uses Carla's own spawn points +SpawnEgoVehicleTransform=(X=-147.066772, Y=-1322.415039, Z=15.68335 | R=0, P=0.0, Y=-90 | X=1.0, Y=1.0, Z=1.0) # Town05: car park + +[Sound] +DefaultEngineRev="SoundCue'/Game/DReyeVR/Sounds/EngineRev/EngineRev.EngineRev'" +DefaultCrashSound="SoundCue'/Game/DReyeVR/Sounds/Crash/CrashCue.CrashCue'" +DefaultGearShiftSound="SoundWave'/Game/DReyeVR/Sounds/GearShift.GearShift'" +DefaultTurnSignalSound="SoundWave'/Game/DReyeVR/Sounds/TurnSignal.TurnSignal'" +EgoVolumePercent=100 +NonEgoVolumePercent=100 +AmbientVolumePercent=20 + +[Replayer] +CameraFollowHMD=True # Whether or not to have the camera pose follow the recorded HMD pose +UseCarlaSpectator=False # Use the built-in Carla spectator (not recommended) or spawn our own (recommended) + +# Enable or disable replay interpolation with *ReplayInterpolation* +# True is the default CARLA behavior, this may cause replay timesteps in between ground truth data +# False ensures that every frame will match exactly with the recorded data at the exact timesteps (no interpolation) +ReplayInterpolation=False # see above + +# for taking per-frame screen capture during replay (for post-hoc analysis) +RecordFrames=True # additionally capture camera screenshots on replay tick (requires no replay interpolation!) +RecordAllShaders=True # Enable or disable rendering the scene with additional (beyond RGB) shaders such as depth +RecordAllPoses=True # Enable or disable rendering the scene with all camera poses (beyond driver's seat) +FileFormatJPG=True # either JPG or PNG +LinearGamma=True # force linear gamme for frame capture render (recommended) +FrameWidth=1280 # resolution x for screenshot +FrameHeight=720 # resolution y for screenshot +FrameDir="FrameCap" # directory name for screenshot +FrameName="tick" # title of screenshot (differentiated via tick-suffix) + +[CameraPose] +# starting pose should be one of: {DriversSeat, Front, BirdsEyeView, ThirdPerson} +StartingPose="DriversSeat" # starting position of camera in vehicle (on begin play) +# offsets from the EgoVehicle's bounding box positions if you need +Front=(X=1.1, Y=0.0, Z=0.3 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # front "license plate" view +BirdsEyeView=(X=0.0, Y=0.0, Z=15 | R=0.0, P=270.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # top down view +ThirdPerson=(X=-2, Y=0.0, Z=4 | R=0.0, P=330.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # back angled view + +[WheelFace] +# ABXY and Dpad buttons as custom-actors on the steering wheel face +EnableWheelButtons=False # enable dpad & ABXY indicator buttons on wheel face or not +ABXYLocation=(X=-7, Y=-10, Z=4) # location relative to steering wheel where the center of ABXY is +DpadLocation=(X=-7, Y=10, Z=4) # location relative to steering wheel where the center of Dpad is +QuadButtonSpread=2.0 # distance between the 4 buttons +# Autopilot status indicator (blue light) +EnableAutopilotIndicator=True # enable blue light indicator for autopilot status +AutopilotIndicatorLoc=(X=-7, Y=0, Z=4) # location relative to steering wheel for center of indicator +AutopilotIndicatorSize=0.03 # size of the indicator + +# for Logitech hardware of the racing sim +[Hardware] +DeviceIdx=0 # Device index of the hardware (Logitech has 2, can be 0 or 1) +LogUpdates=True # whether or not to print debug messages +DeltaInputThreshold=0.02 # how much change the logi wheels need applied to overtake autopilot +ForceFeedbackMagnitude=50 # "Level of saturation" for the physical wheel actuation (0 to 100) + +# VariableRateShading is an experimental attempt to squeeze more performance out of DReyeVR +# by reducing rendering quality of the scene in the periphery, which we should know from the real-time +# gaze tracking. Unfortunately the development to port HTC Vive's VariableRateShading is still WIP and +# currently only works in the Editor, not in a shipping/package game where it'd be most useful. We are +# actively working on this feature and will enable VRS once it is fully supported. +[VariableRateShading] # disabled by default (would need to enable via CarlaUE4.Build.cs flag) +Enabled=True # currently only works in Editor mode (but enabled in Build.cs settings) +UsingEyeTracking=True # use eye tracking for foveated rendering if available diff --git a/Config/Default.Package.json b/Config/Default.Package.json index 3dfa4d9..806b66a 100644 --- a/Config/Default.Package.json +++ b/Config/Default.Package.json @@ -1,469 +1,469 @@ -{ - "props": [ - { - "name": "ATM", - "path": "/Game/Carla/Static/Static/SM_Atm.SM_Atm", - "size": "Medium" - }, - { - "name": "Barbeque", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_Barbecue.SM_Barbecue", - "size": "Small" - }, - { - "name": "Barrel", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_Barrel.SM_Barrel", - "size": "Small" - }, - { - "name": "Bench01", - "path": "/Game/Carla/Static/Static/SM_Bench01.SM_Bench01", - "size": "Medium" - }, - { - "name": "Bench02", - "path": "/Game/Carla/Static/Static/SM_Bench02.SM_Bench02", - "size": "Medium" - }, - { - "name": "Bench03", - "path": "/Game/Carla/Static/Static/SM_Bench03.SM_Bench03", - "size": "Medium" - }, - { - "name": "Bike Helmet", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_bikehelmet.SM_bikehelmet", - "size": "Tiny" - }, - { - "name": "Bin", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_Bin.SM_Bin", - "size": "Medium" - }, - { - "name": "Box01", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_Box01.SM_Box01", - "size": "Small" - }, - { - "name": "Box02", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_box02.SM_box02", - "size": "Small" - }, - { - "name": "Box03", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_box03.SM_box03", - "size": "Small" - }, - { - "name": "Briefcase", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_Briefcase.SM_Briefcase", - "size": "Small" - }, - { - "name": "BrokenTile01", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile01.SM_BrokenTile01", - "size": "Tiny" - }, - { - "name": "BrokenTile02", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile02.SM_BrokenTile02", - "size": "Tiny" - }, - { - "name": "BrokenTile03", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile03.SM_BrokenTile03", - "size": "Tiny" - }, - { - "name": "BrokenTile04", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile04.SM_BrokenTile04", - "size": "Tiny" - }, - { - "name": "BusStop", - "path": "/Game/Carla/Static/Static/Materials/BusStop/SM_BusStop.SM_BusStop", - "size": "Big" - }, - { - "name": "VendingMachine", - "path": "/Game/Carla/Static/Static/SM_CarlaCola.SM_CarlaCola", - "size": "Medium" - }, - { - "name": "ChainBarrier", - "path": "/Game/Carla/Static/Static/SM_ChainBarrier.SM_ChainBarrier", - "size": "Medium" - }, - { - "name": "ChainBarrierEnd", - "path": "/Game/Carla/Static/Static/SM_ChainBarrierEnd.SM_ChainBarrierEnd", - "size": "Small" - }, - { - "name": "ClothContainer", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_ClothContainer.SM_ClothContainer", - "size": "Medium" - }, - { - "name": "ClothesLine", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_ClothesLine.SM_ClothesLine", - "size": "Big" - }, - { - "name": "ColaCan", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_ColaCan.SM_ColaCan", - "size": "Tiny" - }, - { - "name": "ConstructionCone", - "path": "/Game/Carla/Static/Dynamic/Construction/SM_ConstructionCone.SM_ConstructionCone", - "size": "Small" - }, - { - "name": "Container", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_Container.SM_Container", - "size": "Medium" - }, - { - "name": "CreasedBox01", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_CreasedBox01.SM_CreasedBox01", - "size": "Small" - }, - { - "name": "CreasedBox02", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_CreasedBox02.SM_CreasedBox02", - "size": "Small" - }, - { - "name": "CreasedBox03", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_CreasedBox03.SM_CreasedBox03", - "size": "Small" - }, - { - "name": "DirtDebris01", - "path": "/Game/Carla/Static/Other/SM_DirtDebris01.SM_DirtDebris01", - "size": "Small" - }, - { - "name": "DirtDebris02", - "path": "/Game/Carla/Static/Other/SM_DirtDebris02.SM_DirtDebris02", - "size": "Small" - }, - { - "name": "DirtDebris03", - "path": "/Game/Carla/Static/Other/SM_DirtDebris03.SM_DirtDebris03", - "size": "Small" - }, - { - "name": "Garbage01", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage01.SM_Garbage01", - "size": "Tiny" - }, - { - "name": "Garbage02", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage02.SM_Garbage02", - "size": "Tiny" - }, - { - "name": "Garbage03", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage03.SM_Garbage03", - "size": "Tiny" - }, - { - "name": "Garbage04", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage04.SM_Garbage04", - "size": "Tiny" - }, - { - "name": "Garbage05", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage05.SM_Garbage05", - "size": "Tiny" - }, - { - "name": "Garbage06", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage06.SM_Garbage06", - "size": "Tiny" - }, - { - "name": "GardenLamp", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_GardenLamp.SM_GardenLamp", - "size": "Small" - }, - { - "name": "GlassContainer", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_GlassContainer.SM_GlassContainer", - "size": "Medium" - }, - { - "name": "Gnome", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_Gnome.SM_Gnome", - "size": "Small" - }, - { - "name": "GuitarCase", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_GuitarCase.SM_GuitarCase", - "size": "Small" - }, - { - "name": "IronPlank", - "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_IronPlank.SM_IronPlank", - "size": "Small" - }, - { - "name": "Kiosk_01", - "path": "/Game/Carla/Static/Building/SM_Kiosk01.SM_Kiosk01", - "size": "Medium" - }, - { - "name": "MailBox", - "path": "/Game/Carla/Static/Static/SM_MailBox.SM_MailBox", - "size": "Small" - }, - { - "name": "MapTable", - "path": "/Game/Carla/Static/Static/SM_MapTable.SM_MapTable", - "size": "Medium" - }, - { - "name": "Mobile", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_Mobile.SM_Mobile", - "size": "Tiny" - }, - { - "name": "MotorHelmet", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/Sm_Motorhelmet.Sm_Motorhelmet", - "size": "Small" - }, - { - "name": "Pergola", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_Pergola.SM_Pergola", - "size": "Big" - }, - { - "name": "PlantPot01", - "path": "/Game/Carla/Static/Static/SM_Plantpot01.SM_Plantpot01", - "size": "Small" - }, - { - "name": "PlantPot02", - "path": "/Game/Carla/Static/Static/SM_PlantPot02.SM_PlantPot02", - "size": "Small" - }, - { - "name": "PlantPot03", - "path": "/Game/Carla/Static/Static/SM_PlantPot03.SM_PlantPot03", - "size": "Small" - }, - { - "name": "PlantPot04", - "path": "/Game/Carla/Static/Static/SM_PlantPot04.SM_PlantPot04", - "size": "Small" - }, - { - "name": "PlantPot05", - "path": "/Game/Carla/Static/Static/SM_PlantPot05.SM_PlantPot05", - "size": "Small" - }, - { - "name": "PlantPot06", - "path": "/Game/Carla/Static/Static/SM_PlantPot06.SM_PlantPot06", - "size": "Small" - }, - { - "name": "PlantPot07", - "path": "/Game/Carla/Static/Static/SM_PlantPot07.SM_PlantPot07", - "size": "Small" - }, - { - "name": "PlantPot08", - "path": "/Game/Carla/Static/Static/SM_PlantPot08.SM_PlantPot08", - "size": "Small" - }, - { - "name": "PlasticBag", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_PlasticBag.SM_PlasticBag", - "size": "Small" - }, - { - "name": "PlasticChair", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_PlasticChair.SM_PlasticChair", - "size": "Small" - }, - { - "name": "PlasticTable", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_PlasticTable.SM_PlasticTable", - "size": "Medium" - }, - { - "name": "PlatformGarbage01", - "path": "/Game/Carla/Static/Static/SM_PlatformGarbage01.SM_PlatformGarbage01", - "size": "Medium" - }, - { - "name": "Purse", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_Purse.SM_Purse", - "size": "Small" - }, - { - "name": "ShoppingCart", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_ShoppinCart.SM_ShoppinCart", - "size": "Medium" - }, - { - "name": "ShoppingBag", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_ShoppingBag.SM_ShoppingBag", - "size": "Small" - }, - { - "name": "ShoppingTrolley", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_ShoppingTrolley.SM_ShoppingTrolley", - "size": "Small" - }, - { - "name": "Slide", - "path": "/Game/Carla/Static/Static/SM_Slide.SM_Slide", - "size": "Big" - }, - { - "name": "StreetSign01", - "path": "/Game/Carla/Static/Static/SM_StreetAD01.SM_StreetAD01", - "size": "Medium" - }, - { - "name": "StreetSign", - "path": "/Game/Carla/Static/Static/SM_StreetAD02.SM_StreetAD02", - "size": "Small" - }, - { - "name": "StreetSign04", - "path": "/Game/Carla/Static/Static/SM_StreetAD04.SM_StreetAD04", - "size": "Small" - }, - { - "name": "StreetBarrier", - "path": "/Game/Carla/Static/Dynamic/Construction/SM_StreetBarrier.SM_StreetBarrier", - "size": "Small" - }, - { - "name": "StreetFountain", - "path": "/Game/Carla/Static/Static/SM_StreetFountain.SM_StreetFountain", - "size": "Small" - }, - { - "name": "Swing", - "path": "/Game/Carla/Static/Static/SM_Swing.SM_Swing", - "size": "Medium" - }, - { - "name": "SwingCouch", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_SwingCouch.SM_SwingCouch", - "size": "Medium" - }, - { - "name": "Table", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_Table.SM_Table", - "size": "Medium" - }, - { - "name": "TrafficCone01", - "path": "/Game/Carla/Static/Dynamic/Construction/SM_TrafficCones_01.SM_TrafficCones_01", - "size": "Small" - }, - { - "name": "TrafficCone02", - "path": "/Game/Carla/Static/Dynamic/Construction/SM_TrafficCones_02.SM_TrafficCones_02", - "size": "Small" - }, - { - "name": "TrafficWarning", - "path": "/Game/Carla/Static/Dynamic/Construction/SM_TrafficCones_03.SM_TrafficCones_03", - "size": "Big" - }, - { - "name": "Trampoline", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_Trampoline.SM_Trampoline", - "size": "Big" - }, - { - "name": "TrashBag", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_TrasdhBag.SM_TrasdhBag", - "size": "Small" - }, - { - "name": "TrashCan01", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_TrashCan01.SM_TrashCan01", - "size": "Small" - }, - { - "name": "TrashCan02", - "path": "/Game/Carla/Static/Static/SM_trashCanV3.SM_trashCanV3", - "size": "Small" - }, - { - "name": "TrashCan03", - "path": "/Game/Carla/Static/Dynamic/Trash/SM_TrashCan03.SM_TrashCan03", - "size": "Small" - }, - { - "name": "TrashCan04", - "path": "/Game/Carla/Static/Static/SM_TrashCan04.SM_TrashCan04", - "size": "Small" - }, - { - "name": "TrashCan05", - "path": "/Game/Carla/Static/Static/SM_TrashCan05.SM_TrashCan05", - "size": "Small" - }, - { - "name": "TravelCase", - "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_TravelCase.SM_TravelCase", - "size": "Small" - }, - { - "name": "WateringCan", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_WateringCan.SM_WateringCan", - "size": "Small" - }, - { - "name": "DogHouse", - "path": "/Game/Carla/Static/Dynamic/Garden/SM_DogHouse.SM_DogHouse", - "size": "Small" - }, - { - "name": "Fountain", - "path": "/Game/Carla/Static/Static/SM_Fountain.SM_Fountain", - "size": "big" - }, - { - "name": "Advertisement", - "path": "/Game/Carla/Static/Dynamic/Bar-Restaurant/SM_Advertise.SM_Advertise", - "size": "Small" - }, - { - "name": "Calibrator", - "path": "/Game/Carla/Static/Static/Calibrator/SM_calibration.SM_calibration", - "size": "Small" - }, - { - "name": "DReyeVR_sign_left", - "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_left.SM_DReyeVR_sign_left", - "size": "Big" - }, - { - "name": "DReyeVR_sign_straight", - "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_straight.SM_DReyeVR_sign_straight", - "size": "Big" - }, - { - "name": "DReyeVR_sign_right", - "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_right.SM_DReyeVR_sign_right", - "size": "Big" - }, - { - "name": "DReyeVR_sign_goal", - "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_goal.SM_DReyeVR_sign_goal", - "size": "Big" - } - ] +{ + "props": [ + { + "name": "ATM", + "path": "/Game/Carla/Static/Static/SM_Atm.SM_Atm", + "size": "Medium" + }, + { + "name": "Barbeque", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_Barbecue.SM_Barbecue", + "size": "Small" + }, + { + "name": "Barrel", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_Barrel.SM_Barrel", + "size": "Small" + }, + { + "name": "Bench01", + "path": "/Game/Carla/Static/Static/SM_Bench01.SM_Bench01", + "size": "Medium" + }, + { + "name": "Bench02", + "path": "/Game/Carla/Static/Static/SM_Bench02.SM_Bench02", + "size": "Medium" + }, + { + "name": "Bench03", + "path": "/Game/Carla/Static/Static/SM_Bench03.SM_Bench03", + "size": "Medium" + }, + { + "name": "Bike Helmet", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_bikehelmet.SM_bikehelmet", + "size": "Tiny" + }, + { + "name": "Bin", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_Bin.SM_Bin", + "size": "Medium" + }, + { + "name": "Box01", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_Box01.SM_Box01", + "size": "Small" + }, + { + "name": "Box02", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_box02.SM_box02", + "size": "Small" + }, + { + "name": "Box03", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_box03.SM_box03", + "size": "Small" + }, + { + "name": "Briefcase", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_Briefcase.SM_Briefcase", + "size": "Small" + }, + { + "name": "BrokenTile01", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile01.SM_BrokenTile01", + "size": "Tiny" + }, + { + "name": "BrokenTile02", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile02.SM_BrokenTile02", + "size": "Tiny" + }, + { + "name": "BrokenTile03", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile03.SM_BrokenTile03", + "size": "Tiny" + }, + { + "name": "BrokenTile04", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_BrokenTile04.SM_BrokenTile04", + "size": "Tiny" + }, + { + "name": "BusStop", + "path": "/Game/Carla/Static/Static/Materials/BusStop/SM_BusStop.SM_BusStop", + "size": "Big" + }, + { + "name": "VendingMachine", + "path": "/Game/Carla/Static/Static/SM_CarlaCola.SM_CarlaCola", + "size": "Medium" + }, + { + "name": "ChainBarrier", + "path": "/Game/Carla/Static/Static/SM_ChainBarrier.SM_ChainBarrier", + "size": "Medium" + }, + { + "name": "ChainBarrierEnd", + "path": "/Game/Carla/Static/Static/SM_ChainBarrierEnd.SM_ChainBarrierEnd", + "size": "Small" + }, + { + "name": "ClothContainer", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_ClothContainer.SM_ClothContainer", + "size": "Medium" + }, + { + "name": "ClothesLine", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_ClothesLine.SM_ClothesLine", + "size": "Big" + }, + { + "name": "ColaCan", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_ColaCan.SM_ColaCan", + "size": "Tiny" + }, + { + "name": "ConstructionCone", + "path": "/Game/Carla/Static/Dynamic/Construction/SM_ConstructionCone.SM_ConstructionCone", + "size": "Small" + }, + { + "name": "Container", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_Container.SM_Container", + "size": "Medium" + }, + { + "name": "CreasedBox01", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_CreasedBox01.SM_CreasedBox01", + "size": "Small" + }, + { + "name": "CreasedBox02", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_CreasedBox02.SM_CreasedBox02", + "size": "Small" + }, + { + "name": "CreasedBox03", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_CreasedBox03.SM_CreasedBox03", + "size": "Small" + }, + { + "name": "DirtDebris01", + "path": "/Game/Carla/Static/Other/SM_DirtDebris01.SM_DirtDebris01", + "size": "Small" + }, + { + "name": "DirtDebris02", + "path": "/Game/Carla/Static/Other/SM_DirtDebris02.SM_DirtDebris02", + "size": "Small" + }, + { + "name": "DirtDebris03", + "path": "/Game/Carla/Static/Other/SM_DirtDebris03.SM_DirtDebris03", + "size": "Small" + }, + { + "name": "Garbage01", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage01.SM_Garbage01", + "size": "Tiny" + }, + { + "name": "Garbage02", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage02.SM_Garbage02", + "size": "Tiny" + }, + { + "name": "Garbage03", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage03.SM_Garbage03", + "size": "Tiny" + }, + { + "name": "Garbage04", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage04.SM_Garbage04", + "size": "Tiny" + }, + { + "name": "Garbage05", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage05.SM_Garbage05", + "size": "Tiny" + }, + { + "name": "Garbage06", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_Garbage06.SM_Garbage06", + "size": "Tiny" + }, + { + "name": "GardenLamp", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_GardenLamp.SM_GardenLamp", + "size": "Small" + }, + { + "name": "GlassContainer", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_GlassContainer.SM_GlassContainer", + "size": "Medium" + }, + { + "name": "Gnome", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_Gnome.SM_Gnome", + "size": "Small" + }, + { + "name": "GuitarCase", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_GuitarCase.SM_GuitarCase", + "size": "Small" + }, + { + "name": "IronPlank", + "path": "/Game/Carla/Static/Dynamic/Trash/Wastes/SM_IronPlank.SM_IronPlank", + "size": "Small" + }, + { + "name": "Kiosk_01", + "path": "/Game/Carla/Static/Building/SM_Kiosk01.SM_Kiosk01", + "size": "Medium" + }, + { + "name": "MailBox", + "path": "/Game/Carla/Static/Static/SM_MailBox.SM_MailBox", + "size": "Small" + }, + { + "name": "MapTable", + "path": "/Game/Carla/Static/Static/SM_MapTable.SM_MapTable", + "size": "Medium" + }, + { + "name": "Mobile", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_Mobile.SM_Mobile", + "size": "Tiny" + }, + { + "name": "MotorHelmet", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/Sm_Motorhelmet.Sm_Motorhelmet", + "size": "Small" + }, + { + "name": "Pergola", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_Pergola.SM_Pergola", + "size": "Big" + }, + { + "name": "PlantPot01", + "path": "/Game/Carla/Static/Static/SM_Plantpot01.SM_Plantpot01", + "size": "Small" + }, + { + "name": "PlantPot02", + "path": "/Game/Carla/Static/Static/SM_PlantPot02.SM_PlantPot02", + "size": "Small" + }, + { + "name": "PlantPot03", + "path": "/Game/Carla/Static/Static/SM_PlantPot03.SM_PlantPot03", + "size": "Small" + }, + { + "name": "PlantPot04", + "path": "/Game/Carla/Static/Static/SM_PlantPot04.SM_PlantPot04", + "size": "Small" + }, + { + "name": "PlantPot05", + "path": "/Game/Carla/Static/Static/SM_PlantPot05.SM_PlantPot05", + "size": "Small" + }, + { + "name": "PlantPot06", + "path": "/Game/Carla/Static/Static/SM_PlantPot06.SM_PlantPot06", + "size": "Small" + }, + { + "name": "PlantPot07", + "path": "/Game/Carla/Static/Static/SM_PlantPot07.SM_PlantPot07", + "size": "Small" + }, + { + "name": "PlantPot08", + "path": "/Game/Carla/Static/Static/SM_PlantPot08.SM_PlantPot08", + "size": "Small" + }, + { + "name": "PlasticBag", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_PlasticBag.SM_PlasticBag", + "size": "Small" + }, + { + "name": "PlasticChair", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_PlasticChair.SM_PlasticChair", + "size": "Small" + }, + { + "name": "PlasticTable", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_PlasticTable.SM_PlasticTable", + "size": "Medium" + }, + { + "name": "PlatformGarbage01", + "path": "/Game/Carla/Static/Static/SM_PlatformGarbage01.SM_PlatformGarbage01", + "size": "Medium" + }, + { + "name": "Purse", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_Purse.SM_Purse", + "size": "Small" + }, + { + "name": "ShoppingCart", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_ShoppinCart.SM_ShoppinCart", + "size": "Medium" + }, + { + "name": "ShoppingBag", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_ShoppingBag.SM_ShoppingBag", + "size": "Small" + }, + { + "name": "ShoppingTrolley", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_ShoppingTrolley.SM_ShoppingTrolley", + "size": "Small" + }, + { + "name": "Slide", + "path": "/Game/Carla/Static/Static/SM_Slide.SM_Slide", + "size": "Big" + }, + { + "name": "StreetSign01", + "path": "/Game/Carla/Static/Static/SM_StreetAD01.SM_StreetAD01", + "size": "Medium" + }, + { + "name": "StreetSign", + "path": "/Game/Carla/Static/Static/SM_StreetAD02.SM_StreetAD02", + "size": "Small" + }, + { + "name": "StreetSign04", + "path": "/Game/Carla/Static/Static/SM_StreetAD04.SM_StreetAD04", + "size": "Small" + }, + { + "name": "StreetBarrier", + "path": "/Game/Carla/Static/Dynamic/Construction/SM_StreetBarrier.SM_StreetBarrier", + "size": "Small" + }, + { + "name": "StreetFountain", + "path": "/Game/Carla/Static/Static/SM_StreetFountain.SM_StreetFountain", + "size": "Small" + }, + { + "name": "Swing", + "path": "/Game/Carla/Static/Static/SM_Swing.SM_Swing", + "size": "Medium" + }, + { + "name": "SwingCouch", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_SwingCouch.SM_SwingCouch", + "size": "Medium" + }, + { + "name": "Table", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_Table.SM_Table", + "size": "Medium" + }, + { + "name": "TrafficCone01", + "path": "/Game/Carla/Static/Dynamic/Construction/SM_TrafficCones_01.SM_TrafficCones_01", + "size": "Small" + }, + { + "name": "TrafficCone02", + "path": "/Game/Carla/Static/Dynamic/Construction/SM_TrafficCones_02.SM_TrafficCones_02", + "size": "Small" + }, + { + "name": "TrafficWarning", + "path": "/Game/Carla/Static/Dynamic/Construction/SM_TrafficCones_03.SM_TrafficCones_03", + "size": "Big" + }, + { + "name": "Trampoline", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_Trampoline.SM_Trampoline", + "size": "Big" + }, + { + "name": "TrashBag", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_TrasdhBag.SM_TrasdhBag", + "size": "Small" + }, + { + "name": "TrashCan01", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_TrashCan01.SM_TrashCan01", + "size": "Small" + }, + { + "name": "TrashCan02", + "path": "/Game/Carla/Static/Static/SM_trashCanV3.SM_trashCanV3", + "size": "Small" + }, + { + "name": "TrashCan03", + "path": "/Game/Carla/Static/Dynamic/Trash/SM_TrashCan03.SM_TrashCan03", + "size": "Small" + }, + { + "name": "TrashCan04", + "path": "/Game/Carla/Static/Static/SM_TrashCan04.SM_TrashCan04", + "size": "Small" + }, + { + "name": "TrashCan05", + "path": "/Game/Carla/Static/Static/SM_TrashCan05.SM_TrashCan05", + "size": "Small" + }, + { + "name": "TravelCase", + "path": "/Game/Carla/Static/Dynamic/PedestrianProps/SM_TravelCase.SM_TravelCase", + "size": "Small" + }, + { + "name": "WateringCan", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_WateringCan.SM_WateringCan", + "size": "Small" + }, + { + "name": "DogHouse", + "path": "/Game/Carla/Static/Dynamic/Garden/SM_DogHouse.SM_DogHouse", + "size": "Small" + }, + { + "name": "Fountain", + "path": "/Game/Carla/Static/Static/SM_Fountain.SM_Fountain", + "size": "big" + }, + { + "name": "Advertisement", + "path": "/Game/Carla/Static/Dynamic/Bar-Restaurant/SM_Advertise.SM_Advertise", + "size": "Small" + }, + { + "name": "Calibrator", + "path": "/Game/Carla/Static/Static/Calibrator/SM_calibration.SM_calibration", + "size": "Small" + }, + { + "name": "DReyeVR_sign_left", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_left.SM_DReyeVR_sign_left", + "size": "Big" + }, + { + "name": "DReyeVR_sign_straight", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_straight.SM_DReyeVR_sign_straight", + "size": "Big" + }, + { + "name": "DReyeVR_sign_right", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_right.SM_DReyeVR_sign_right", + "size": "Big" + }, + { + "name": "DReyeVR_sign_goal", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_goal.SM_DReyeVR_sign_goal", + "size": "Big" + } + ] } \ No newline at end of file diff --git a/Config/DefaultEngine.ini b/Config/DefaultEngine.ini index ca91e98..57c07d1 100644 --- a/Config/DefaultEngine.ini +++ b/Config/DefaultEngine.ini @@ -1,199 +1,199 @@ -[/Script/Engine.Engine] -bSmoothFrameRate=false -SmoothedFrameRateRange=(LowerBound=(Type="ERangeBoundTypes::Inclusive",Value=22),UpperBound=(Type="ERangeBoundTypes::Exclusive",Value=120)) - -[/Script/HardwareTargeting.HardwareTargetingSettings] -TargetedHardwareClass=Desktop -AppliedTargetedHardwareClass=Desktop -DefaultGraphicsPerformance=Maximum -AppliedDefaultGraphicsPerformance=Maximum - -[/Script/EngineSettings.GameMapsSettings] -EditorStartupMap=/Game/Carla/Maps/Town03.Town03 -LocalMapOptions= -TransitionMap=/Game/Carla/Maps/Town03.Town03 -bUseSplitscreen=True -TwoPlayerSplitscreenLayout=Horizontal -ThreePlayerSplitscreenLayout=FavorTop -FourPlayerSplitscreenLayout=Grid -bOffsetPlayerGamepadIds=False -GameInstanceClass=/Script/Carla.CarlaGameInstance -GameDefaultMap=/Game/Carla/Maps/Town03.Town03 -ServerDefaultMap=/Game/Carla/Maps/Town03.Town03 -GlobalDefaultGameMode=/Script/CarlaUE4.DReyeVRGameMode -GlobalDefaultServerGameMode=/Script/CarlaUE4.DReyeVRGameMode - -[/Script/Engine.RendererSettings] -r.DefaultFeature.MotionBlur=True -r.BasePassOutputsVelocity=True -r.BasePassForceOutputsVelocity=False -r.AllowStaticLighting=False -r.DiscardUnusedQuality=True -r.DefaultFeature.Bloom=False -r.DefaultFeature.AmbientOcclusion=False -r.DefaultFeature.AmbientOcclusionStaticFraction=False -r.DefaultFeature.AutoExposure=False -r.CustomDepth=3 -r.Streaming.PoolSize=4000 -r.TextureStreaming=True -r.GenerateMeshDistanceFields=True -r.DistanceFieldBuild.EightBit=False -r.DistanceFieldBuild.Compress=False -r.DistanceFields.AtlasSizeXY=1024 -r.DistanceFields.AtlasSizeZ=2048 -r.DefaultFeature.AutoExposure.ExtendDefaultLuminanceRange=True -r.VirtualTextures=True -vr.InstancedStereo=True -r.AllowGlobalClipPlane=True -vr.PixelDensity=1.0 -r.ReflectionCaptureResolution=16 - -[/Script/AIModule.AISense_Sight] -bAutoRegisterAllPawnsAsSources=False -bAutoRegisterNewPawnsAsSources=False - -[/Script/NavigationSystem.RecastNavMesh] -RuntimeGeneration=Static - -[/Script/AIModule.CrowdManager] -MaxAgents=1000 - -[/Script/LinuxTargetPlatform.LinuxTargetSettings] -SpatializationPlugin= -ReverbPlugin= -OcclusionPlugin= --TargetedRHIs=SF_VULKAN_SM5 --TargetedRHIs=GLSL_430 -+TargetedRHIs=SF_VULKAN_SM5 -+TargetedRHIs=GLSL_430 - -[/Script/IOSRuntimeSettings.IOSRuntimeSettings] -bSupportsPortraitOrientation=False -bSupportsUpsideDownOrientation=False -bSupportsLandscapeLeftOrientation=True -PreferredLandscapeOrientation=LandscapeLeft - -[/Script/MacTargetPlatform.MacTargetSettings] --TargetedRHIs=SF_METAL_SM5 -+TargetedRHIs=SF_METAL_SM5 -MaxShaderLanguageVersion=3 -UseFastIntrinsics=False -EnableMathOptimisations=True -AudioSampleRate=0 -AudioCallbackBufferFrameSize=0 -AudioNumBuffersToEnqueue=0 -AudioMaxChannels=0 -AudioNumSourceWorkers=0 -SpatializationPlugin= -ReverbPlugin= -OcclusionPlugin= - -[/Script/Engine.PhysicsSettings] -DefaultGravityZ=-980.000000 -DefaultTerminalVelocity=4000.000000 -DefaultFluidFriction=0.300000 -SimulateScratchMemorySize=262144 -RagdollAggregateThreshold=4 -TriangleMeshTriangleMinAreaThreshold=5.000000 -bEnableShapeSharing=False -bEnablePCM=False -bEnableStabilization=False -bWarnMissingLocks=True -bEnable2DPhysics=False -PhysicErrorCorrection=(PingExtrapolation=0.100000,PingLimit=100.000000,ErrorPerLinearDifference=1.000000,ErrorPerAngularDifference=1.000000,MaxRestoredStateError=1.000000,MaxLinearHardSnapDistance=400.000000,PositionLerp=0.000000,AngleLerp=0.400000,LinearVelocityCoefficient=100.000000,AngularVelocityCoefficient=10.000000,ErrorAccumulationSeconds=0.500000,ErrorAccumulationDistanceSq=15.000000,ErrorAccumulationSimilarity=100.000000) -LockedAxis=Invalid -DefaultDegreesOfFreedom=Full3D -BounceThresholdVelocity=200.000000 -FrictionCombineMode=Average -RestitutionCombineMode=Average -MaxAngularVelocity=3600.000000 -MaxDepenetrationVelocity=0.000000 -ContactOffsetMultiplier=0.010000 -MinContactOffset=0.000100 -MaxContactOffset=1.000000 -bSimulateSkeletalMeshOnDedicatedServer=True -DefaultShapeComplexity=CTF_UseSimpleAndComplex -bDefaultHasComplexCollision=True -bSuppressFaceRemapTable=False -bSupportUVFromHitResults=False -bDisableActiveActors=False -bDisableKinematicStaticPairs=False -bDisableKinematicKinematicPairs=False -bDisableCCD=False -bEnableEnhancedDeterminism=True -MaxPhysicsDeltaTime=0.333330 -bSubstepping=True -bSubsteppingAsync=False -MaxSubstepDeltaTime=0.010000 -MaxSubsteps=10 -SyncSceneSmoothingFactor=0.000000 -InitialAverageFrameRate=0.016667 -PhysXTreeRebuildRate=10 -DefaultBroadphaseSettings=(bUseMBPOnClient=False,bUseMBPOnServer=False,MBPBounds=(Min=(X=0.000000,Y=0.000000,Z=0.000000),Max=(X=0.000000,Y=0.000000,Z=0.000000),IsValid=0),MBPNumSubdivs=2) - -[/Script/WindowsTargetPlatform.WindowsTargetSettings] -DefaultGraphicsRHI=DefaultGraphicsRHI_DX11 - -[/Script/Engine.CollisionProfile] --Profiles=(Name="NoCollision",CollisionEnabled=NoCollision,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="No collision",bCanModify=False) --Profiles=(Name="BlockAll",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldStatic",CustomResponses=,HelpMessage="WorldStatic object that blocks all actors by default. All new custom channels will use its own default response. ",bCanModify=False) --Profiles=(Name="OverlapAll",CollisionEnabled=QueryOnly,ObjectTypeName="WorldStatic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ",bCanModify=False) --Profiles=(Name="BlockAllDynamic",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldDynamic",CustomResponses=,HelpMessage="WorldDynamic object that blocks all actors by default. All new custom channels will use its own default response. ",bCanModify=False) --Profiles=(Name="OverlapAllDynamic",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that overlaps all actors by default. All new custom channels will use its own default response. ",bCanModify=False) --Profiles=(Name="IgnoreOnlyPawn",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that ignores Pawn and Vehicle. All other channels will be set to default.",bCanModify=False) --Profiles=(Name="OverlapOnlyPawn",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that overlaps Pawn, Camera, and Vehicle. All other channels will be set to default. ",bCanModify=False) --Profiles=(Name="Pawn",CollisionEnabled=QueryAndPhysics,ObjectTypeName="Pawn",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object. Can be used for capsule of any playerable character or AI. ",bCanModify=False) --Profiles=(Name="Spectator",CollisionEnabled=QueryOnly,ObjectTypeName="Pawn",CustomResponses=((Channel="WorldStatic",Response=ECR_Block),(Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore),(Channel="PhysicsBody",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Destructible",Response=ECR_Ignore)),HelpMessage="Pawn object that ignores all other actors except WorldStatic.",bCanModify=False) --Profiles=(Name="CharacterMesh",CollisionEnabled=QueryOnly,ObjectTypeName="Pawn",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object that is used for Character Mesh. All other channels will be set to default.",bCanModify=False) --Profiles=(Name="PhysicsActor",CollisionEnabled=QueryAndPhysics,ObjectTypeName="PhysicsBody",CustomResponses=,HelpMessage="Simulating actors",bCanModify=False) --Profiles=(Name="Destructible",CollisionEnabled=QueryAndPhysics,ObjectTypeName="Destructible",CustomResponses=,HelpMessage="Destructible actors",bCanModify=False) --Profiles=(Name="InvisibleWall",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldStatic object that is invisible.",bCanModify=False) --Profiles=(Name="InvisibleWallDynamic",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that is invisible.",bCanModify=False) --Profiles=(Name="Trigger",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that is used for trigger. All other channels will be set to default.",bCanModify=False) --Profiles=(Name="Ragdoll",CollisionEnabled=QueryAndPhysics,ObjectTypeName="PhysicsBody",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Simulating Skeletal Mesh Component. All other channels will be set to default.",bCanModify=False) --Profiles=(Name="Vehicle",CollisionEnabled=QueryAndPhysics,ObjectTypeName="Vehicle",CustomResponses=,HelpMessage="Vehicle object that blocks Vehicle, WorldStatic, and WorldDynamic. All other channels will be set to default.",bCanModify=False) --Profiles=(Name="UI",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Block),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ",bCanModify=False) -+Profiles=(Name="NoCollision",CollisionEnabled=NoCollision,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="No collision") -+Profiles=(Name="BlockAll",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=,HelpMessage="WorldStatic object that blocks all actors by default. All new custom channels will use its own default response. ") -+Profiles=(Name="OverlapAll",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ") --ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") --ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") --ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") --ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") --ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") -+ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") -+ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") -+ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") -+ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") -+ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") --CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") --CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") --CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") --CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") -+CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") -+CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") -+CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") -+CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") -+Profiles=(Name="BlockAllDynamic",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=,HelpMessage="WorldDynamic object that blocks all actors by default. All new custom channels will use its own default response. ") -+Profiles=(Name="OverlapAllDynamic",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that overlaps all actors by default. All new custom channels will use its own default response. ") -+Profiles=(Name="IgnoreOnlyPawn",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that ignores Pawn and Vehicle. All other channels will be set to default.") -+Profiles=(Name="OverlapOnlyPawn",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that overlaps Pawn, Camera, and Vehicle. All other channels will be set to default. ") -+Profiles=(Name="Pawn",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="Pawn",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object. Can be used for capsule of any playerable character or AI. ") -+Profiles=(Name="Spectator",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="Pawn",CustomResponses=((Channel="WorldStatic"),(Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore),(Channel="PhysicsBody",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Destructible",Response=ECR_Ignore)),HelpMessage="Pawn object that ignores all other actors except WorldStatic.") -+Profiles=(Name="CharacterMesh",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="Pawn",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object that is used for Character Mesh. All other channels will be set to default.") -+Profiles=(Name="PhysicsActor",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="PhysicsBody",CustomResponses=,HelpMessage="Simulating actors") -+Profiles=(Name="Destructible",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="Destructible",CustomResponses=,HelpMessage="Destructible actors") -+Profiles=(Name="InvisibleWall",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldStatic object that is invisible.") -+Profiles=(Name="InvisibleWallDynamic",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that is invisible.") -+Profiles=(Name="Trigger",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that is used for trigger. All other channels will be set to default.") -+Profiles=(Name="Ragdoll",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="PhysicsBody",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Simulating Skeletal Mesh Component. All other channels will be set to default.") -+Profiles=(Name="Vehicle",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="Vehicle",CustomResponses=,HelpMessage="Vehicle object that blocks Vehicle, WorldStatic, and WorldDynamic. All other channels will be set to default.") -+Profiles=(Name="UI",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility"),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ") -+Profiles=(Name="CustomSensorCollision",CollisionEnabled=QueryOnly,bCanModify=True,ObjectTypeName="SensorObject",CustomResponses=((Channel="WorldStatic",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Ignore),(Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore),(Channel="PhysicsBody",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Destructible",Response=ECR_Ignore),(Channel="SensorObject"),(Channel="SensorTrace")),HelpMessage="Used for custom collision meshes for objects that has very complex meshes but we want them to appear in raycast based sensors") -+DefaultChannelResponses=(Channel=ECC_GameTraceChannel1,DefaultResponse=ECR_Ignore,bTraceType=False,bStaticObject=False,Name="SensorObject") -+DefaultChannelResponses=(Channel=ECC_GameTraceChannel2,DefaultResponse=ECR_Ignore,bTraceType=True,bStaticObject=False,Name="SensorTrace") -+DefaultChannelResponses=(Channel=ECC_GameTraceChannel3,DefaultResponse=ECR_Overlap,bTraceType=True,bStaticObject=False,Name="OverlapChannel") -+DefaultChannelResponses=(Channel=ECC_GameTraceChannel4,DefaultResponse=ECR_Block,bTraceType=True,bStaticObject=False,Name="DReyeVRSensorTrace") -+EditProfiles=(Name="BlockAll",CustomResponses=((Channel="SensorObject"),(Channel="SensorTrace"))) -+EditProfiles=(Name="OverlapAll",CustomResponses=((Channel="SensorObject",Response=ECR_Overlap),(Channel="SensorTrace",Response=ECR_Overlap))) - +[/Script/Engine.Engine] +bSmoothFrameRate=false +SmoothedFrameRateRange=(LowerBound=(Type="ERangeBoundTypes::Inclusive",Value=22),UpperBound=(Type="ERangeBoundTypes::Exclusive",Value=120)) + +[/Script/HardwareTargeting.HardwareTargetingSettings] +TargetedHardwareClass=Desktop +AppliedTargetedHardwareClass=Desktop +DefaultGraphicsPerformance=Maximum +AppliedDefaultGraphicsPerformance=Maximum + +[/Script/EngineSettings.GameMapsSettings] +EditorStartupMap=/Game/Carla/Maps/Town03.Town03 +LocalMapOptions= +TransitionMap=/Game/Carla/Maps/Town03.Town03 +bUseSplitscreen=True +TwoPlayerSplitscreenLayout=Horizontal +ThreePlayerSplitscreenLayout=FavorTop +FourPlayerSplitscreenLayout=Grid +bOffsetPlayerGamepadIds=False +GameInstanceClass=/Script/Carla.CarlaGameInstance +GameDefaultMap=/Game/Carla/Maps/Town03.Town03 +ServerDefaultMap=/Game/Carla/Maps/Town03.Town03 +GlobalDefaultGameMode=/Script/CarlaUE4.DReyeVRGameMode +GlobalDefaultServerGameMode=/Script/CarlaUE4.DReyeVRGameMode + +[/Script/Engine.RendererSettings] +r.DefaultFeature.MotionBlur=True +r.BasePassOutputsVelocity=True +r.BasePassForceOutputsVelocity=False +r.AllowStaticLighting=False +r.DiscardUnusedQuality=True +r.DefaultFeature.Bloom=False +r.DefaultFeature.AmbientOcclusion=False +r.DefaultFeature.AmbientOcclusionStaticFraction=False +r.DefaultFeature.AutoExposure=False +r.CustomDepth=3 +r.Streaming.PoolSize=4000 +r.TextureStreaming=True +r.GenerateMeshDistanceFields=True +r.DistanceFieldBuild.EightBit=False +r.DistanceFieldBuild.Compress=False +r.DistanceFields.AtlasSizeXY=1024 +r.DistanceFields.AtlasSizeZ=2048 +r.DefaultFeature.AutoExposure.ExtendDefaultLuminanceRange=True +r.VirtualTextures=True +vr.InstancedStereo=True +r.AllowGlobalClipPlane=True +vr.PixelDensity=1.0 +r.ReflectionCaptureResolution=16 + +[/Script/AIModule.AISense_Sight] +bAutoRegisterAllPawnsAsSources=False +bAutoRegisterNewPawnsAsSources=False + +[/Script/NavigationSystem.RecastNavMesh] +RuntimeGeneration=Static + +[/Script/AIModule.CrowdManager] +MaxAgents=1000 + +[/Script/LinuxTargetPlatform.LinuxTargetSettings] +SpatializationPlugin= +ReverbPlugin= +OcclusionPlugin= +-TargetedRHIs=SF_VULKAN_SM5 +-TargetedRHIs=GLSL_430 ++TargetedRHIs=SF_VULKAN_SM5 ++TargetedRHIs=GLSL_430 + +[/Script/IOSRuntimeSettings.IOSRuntimeSettings] +bSupportsPortraitOrientation=False +bSupportsUpsideDownOrientation=False +bSupportsLandscapeLeftOrientation=True +PreferredLandscapeOrientation=LandscapeLeft + +[/Script/MacTargetPlatform.MacTargetSettings] +-TargetedRHIs=SF_METAL_SM5 ++TargetedRHIs=SF_METAL_SM5 +MaxShaderLanguageVersion=3 +UseFastIntrinsics=False +EnableMathOptimisations=True +AudioSampleRate=0 +AudioCallbackBufferFrameSize=0 +AudioNumBuffersToEnqueue=0 +AudioMaxChannels=0 +AudioNumSourceWorkers=0 +SpatializationPlugin= +ReverbPlugin= +OcclusionPlugin= + +[/Script/Engine.PhysicsSettings] +DefaultGravityZ=-980.000000 +DefaultTerminalVelocity=4000.000000 +DefaultFluidFriction=0.300000 +SimulateScratchMemorySize=262144 +RagdollAggregateThreshold=4 +TriangleMeshTriangleMinAreaThreshold=5.000000 +bEnableShapeSharing=False +bEnablePCM=False +bEnableStabilization=False +bWarnMissingLocks=True +bEnable2DPhysics=False +PhysicErrorCorrection=(PingExtrapolation=0.100000,PingLimit=100.000000,ErrorPerLinearDifference=1.000000,ErrorPerAngularDifference=1.000000,MaxRestoredStateError=1.000000,MaxLinearHardSnapDistance=400.000000,PositionLerp=0.000000,AngleLerp=0.400000,LinearVelocityCoefficient=100.000000,AngularVelocityCoefficient=10.000000,ErrorAccumulationSeconds=0.500000,ErrorAccumulationDistanceSq=15.000000,ErrorAccumulationSimilarity=100.000000) +LockedAxis=Invalid +DefaultDegreesOfFreedom=Full3D +BounceThresholdVelocity=200.000000 +FrictionCombineMode=Average +RestitutionCombineMode=Average +MaxAngularVelocity=3600.000000 +MaxDepenetrationVelocity=0.000000 +ContactOffsetMultiplier=0.010000 +MinContactOffset=0.000100 +MaxContactOffset=1.000000 +bSimulateSkeletalMeshOnDedicatedServer=True +DefaultShapeComplexity=CTF_UseSimpleAndComplex +bDefaultHasComplexCollision=True +bSuppressFaceRemapTable=False +bSupportUVFromHitResults=False +bDisableActiveActors=False +bDisableKinematicStaticPairs=False +bDisableKinematicKinematicPairs=False +bDisableCCD=False +bEnableEnhancedDeterminism=True +MaxPhysicsDeltaTime=0.333330 +bSubstepping=True +bSubsteppingAsync=False +MaxSubstepDeltaTime=0.010000 +MaxSubsteps=10 +SyncSceneSmoothingFactor=0.000000 +InitialAverageFrameRate=0.016667 +PhysXTreeRebuildRate=10 +DefaultBroadphaseSettings=(bUseMBPOnClient=False,bUseMBPOnServer=False,MBPBounds=(Min=(X=0.000000,Y=0.000000,Z=0.000000),Max=(X=0.000000,Y=0.000000,Z=0.000000),IsValid=0),MBPNumSubdivs=2) + +[/Script/WindowsTargetPlatform.WindowsTargetSettings] +DefaultGraphicsRHI=DefaultGraphicsRHI_DX11 + +[/Script/Engine.CollisionProfile] +-Profiles=(Name="NoCollision",CollisionEnabled=NoCollision,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="No collision",bCanModify=False) +-Profiles=(Name="BlockAll",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldStatic",CustomResponses=,HelpMessage="WorldStatic object that blocks all actors by default. All new custom channels will use its own default response. ",bCanModify=False) +-Profiles=(Name="OverlapAll",CollisionEnabled=QueryOnly,ObjectTypeName="WorldStatic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ",bCanModify=False) +-Profiles=(Name="BlockAllDynamic",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldDynamic",CustomResponses=,HelpMessage="WorldDynamic object that blocks all actors by default. All new custom channels will use its own default response. ",bCanModify=False) +-Profiles=(Name="OverlapAllDynamic",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that overlaps all actors by default. All new custom channels will use its own default response. ",bCanModify=False) +-Profiles=(Name="IgnoreOnlyPawn",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that ignores Pawn and Vehicle. All other channels will be set to default.",bCanModify=False) +-Profiles=(Name="OverlapOnlyPawn",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that overlaps Pawn, Camera, and Vehicle. All other channels will be set to default. ",bCanModify=False) +-Profiles=(Name="Pawn",CollisionEnabled=QueryAndPhysics,ObjectTypeName="Pawn",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object. Can be used for capsule of any playerable character or AI. ",bCanModify=False) +-Profiles=(Name="Spectator",CollisionEnabled=QueryOnly,ObjectTypeName="Pawn",CustomResponses=((Channel="WorldStatic",Response=ECR_Block),(Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore),(Channel="PhysicsBody",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Destructible",Response=ECR_Ignore)),HelpMessage="Pawn object that ignores all other actors except WorldStatic.",bCanModify=False) +-Profiles=(Name="CharacterMesh",CollisionEnabled=QueryOnly,ObjectTypeName="Pawn",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object that is used for Character Mesh. All other channels will be set to default.",bCanModify=False) +-Profiles=(Name="PhysicsActor",CollisionEnabled=QueryAndPhysics,ObjectTypeName="PhysicsBody",CustomResponses=,HelpMessage="Simulating actors",bCanModify=False) +-Profiles=(Name="Destructible",CollisionEnabled=QueryAndPhysics,ObjectTypeName="Destructible",CustomResponses=,HelpMessage="Destructible actors",bCanModify=False) +-Profiles=(Name="InvisibleWall",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldStatic object that is invisible.",bCanModify=False) +-Profiles=(Name="InvisibleWallDynamic",CollisionEnabled=QueryAndPhysics,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that is invisible.",bCanModify=False) +-Profiles=(Name="Trigger",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that is used for trigger. All other channels will be set to default.",bCanModify=False) +-Profiles=(Name="Ragdoll",CollisionEnabled=QueryAndPhysics,ObjectTypeName="PhysicsBody",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Simulating Skeletal Mesh Component. All other channels will be set to default.",bCanModify=False) +-Profiles=(Name="Vehicle",CollisionEnabled=QueryAndPhysics,ObjectTypeName="Vehicle",CustomResponses=,HelpMessage="Vehicle object that blocks Vehicle, WorldStatic, and WorldDynamic. All other channels will be set to default.",bCanModify=False) +-Profiles=(Name="UI",CollisionEnabled=QueryOnly,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Block),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ",bCanModify=False) ++Profiles=(Name="NoCollision",CollisionEnabled=NoCollision,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="No collision") ++Profiles=(Name="BlockAll",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=,HelpMessage="WorldStatic object that blocks all actors by default. All new custom channels will use its own default response. ") ++Profiles=(Name="OverlapAll",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ") +-ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") +-ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") +-ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") +-ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") +-ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") ++ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") ++ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") ++ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") ++ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") ++ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") +-CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") +-CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") +-CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") +-CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") ++CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") ++CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") ++CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") ++CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") ++Profiles=(Name="BlockAllDynamic",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=,HelpMessage="WorldDynamic object that blocks all actors by default. All new custom channels will use its own default response. ") ++Profiles=(Name="OverlapAllDynamic",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that overlaps all actors by default. All new custom channels will use its own default response. ") ++Profiles=(Name="IgnoreOnlyPawn",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that ignores Pawn and Vehicle. All other channels will be set to default.") ++Profiles=(Name="OverlapOnlyPawn",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that overlaps Pawn, Camera, and Vehicle. All other channels will be set to default. ") ++Profiles=(Name="Pawn",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="Pawn",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object. Can be used for capsule of any playerable character or AI. ") ++Profiles=(Name="Spectator",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="Pawn",CustomResponses=((Channel="WorldStatic"),(Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore),(Channel="PhysicsBody",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Destructible",Response=ECR_Ignore)),HelpMessage="Pawn object that ignores all other actors except WorldStatic.") ++Profiles=(Name="CharacterMesh",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="Pawn",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Pawn object that is used for Character Mesh. All other channels will be set to default.") ++Profiles=(Name="PhysicsActor",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="PhysicsBody",CustomResponses=,HelpMessage="Simulating actors") ++Profiles=(Name="Destructible",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="Destructible",CustomResponses=,HelpMessage="Destructible actors") ++Profiles=(Name="InvisibleWall",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldStatic object that is invisible.") ++Profiles=(Name="InvisibleWallDynamic",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that is invisible.") ++Profiles=(Name="Trigger",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that is used for trigger. All other channels will be set to default.") ++Profiles=(Name="Ragdoll",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="PhysicsBody",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore)),HelpMessage="Simulating Skeletal Mesh Component. All other channels will be set to default.") ++Profiles=(Name="Vehicle",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="Vehicle",CustomResponses=,HelpMessage="Vehicle object that blocks Vehicle, WorldStatic, and WorldDynamic. All other channels will be set to default.") ++Profiles=(Name="UI",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility"),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ") ++Profiles=(Name="CustomSensorCollision",CollisionEnabled=QueryOnly,bCanModify=True,ObjectTypeName="SensorObject",CustomResponses=((Channel="WorldStatic",Response=ECR_Ignore),(Channel="WorldDynamic",Response=ECR_Ignore),(Channel="Pawn",Response=ECR_Ignore),(Channel="Visibility",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore),(Channel="PhysicsBody",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore),(Channel="Destructible",Response=ECR_Ignore),(Channel="SensorObject"),(Channel="SensorTrace")),HelpMessage="Used for custom collision meshes for objects that has very complex meshes but we want them to appear in raycast based sensors") ++DefaultChannelResponses=(Channel=ECC_GameTraceChannel1,DefaultResponse=ECR_Ignore,bTraceType=False,bStaticObject=False,Name="SensorObject") ++DefaultChannelResponses=(Channel=ECC_GameTraceChannel2,DefaultResponse=ECR_Ignore,bTraceType=True,bStaticObject=False,Name="SensorTrace") ++DefaultChannelResponses=(Channel=ECC_GameTraceChannel3,DefaultResponse=ECR_Overlap,bTraceType=True,bStaticObject=False,Name="OverlapChannel") ++DefaultChannelResponses=(Channel=ECC_GameTraceChannel4,DefaultResponse=ECR_Block,bTraceType=True,bStaticObject=False,Name="DReyeVRSensorTrace") ++EditProfiles=(Name="BlockAll",CustomResponses=((Channel="SensorObject"),(Channel="SensorTrace"))) ++EditProfiles=(Name="OverlapAll",CustomResponses=((Channel="SensorObject",Response=ECR_Overlap),(Channel="SensorTrace",Response=ECR_Overlap))) + diff --git a/Config/DefaultGame.ini b/Config/DefaultGame.ini index ff84233..afbc07c 100644 --- a/Config/DefaultGame.ini +++ b/Config/DefaultGame.ini @@ -1,91 +1,91 @@ -[/Script/EngineSettings.GeneralProjectSettings] -ProjectID=675BF8694238308FA9368292CC440350 -ProjectName=CARLA UE4 + DReyeVR -CompanyName=CVC -CopyrightNotice="Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). This work is licensed under the terms of the MIT license. For a copy, see ." -ProjectVersion=0.9.13 - -[/Script/Carla.CarlaSettings] -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapRoad.CheapRoad"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalkCurb.CheapSideWalkCurb"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalk_00.CheapSideWalk_00"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapLaneMarking.CheapLaneMarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -LowLightFadeDistance=1000.000000 -LowStaticMeshMaxDrawDistance=10000.000000 -LowRoadPieceMeshMaxDrawDistance=15000.000000 -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/WetPavement/WetPavement_Complex_Road_N2.WetPavement_Complex_Road_N2"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/WetPavement/WetPavement_Complex_Concrete.WetPavement_Complex_Concrete"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SideWalks/SidewalkN4/WetPavement_SidewalkN4.WetPavement_SidewalkN4"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) -+EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/LaneMarking/Lanemarking.Lanemarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) - -[/Script/UnrealEd.ProjectPackagingSettings] -Build=IfProjectHasCode -BuildConfiguration=PPBC_Development -StagingDirectory=(Path="") -FullRebuild=False -ForDistribution=False -IncludeDebugFiles=True -BlueprintNativizationMethod=Disabled -bIncludeNativizedAssetsInProjectGeneration=False -UsePakFile=True -bGenerateChunks=False -bGenerateNoChunks=False -bChunkHardReferencesOnly=False -bBuildHttpChunkInstallData=False -HttpChunkInstallDataDirectory=(Path="") -HttpChunkInstallDataVersion= -IncludePrerequisites=True -IncludeAppLocalPrerequisites=False -bShareMaterialShaderCode=False -bSharedMaterialNativeLibraries=False -ApplocalPrerequisitesDirectory=(Path="") -IncludeCrashReporter=False -InternationalizationPreset=English --CulturesToStage=en -+CulturesToStage=en -bCookAll=False -bCookMapsOnly=False -bCompressed=False -bEncryptIniFiles=False -bEncryptPakIndex=False -bSkipEditorContent=False -+MapsToCook=(FilePath="/Game/Carla/Maps/Town01") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town01_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town02") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town02_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town03") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town03_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town04") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town04_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town05") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town05_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town06") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town06_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town07") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town07_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town10HD") -+MapsToCook=(FilePath="/Game/Carla/Maps/Town10HD_Opt") -+MapsToCook=(FilePath="/Game/Carla/Maps/OpenDriveMap") -+MapsToCook=(FilePath="/Game/Carla/Maps/TestMaps/EmptyMap") -+DirectoriesToAlwaysCook=(Path="/Game/Carla/Static/GenericMaterials/Licenseplates/Textures") -+DirectoriesToAlwaysCook=(Path="/Game/DReyeVR") -+DirectoriesToAlwaysCook=(Path="/Game/DReyeVR/EgoVehicle/Extra") -+DirectoriesToAlwaysCook=(Path="/Carla/PostProcessingMaterials") -+DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/OpenDrive") -+DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/Nav") -+DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/TM") -+DirectoriesToAlwaysStageAsUFS=(Path="Carla/Config") -bNativizeBlueprintAssets=False -bNativizeOnlySelectedBlueprints=False - -[/Script/VRSSettingsEditor.VRSSettings] -vrs.EnableVRS=True -vrs.EnableEyeTracking=True -vrs.VRSRenderType=0 -FoveationPatternPreset=NARROW -FoveationPatternDetail=(FoveatedHorizontalRadius=0.000000,FoveatedVerticalRadius=0.000000,MiddleHorizontalRadius=0.000000,MiddleVerticalRadius=0.000000,PeripheralHorizontalRadius=0.000000,PeripheralVerticalRadius=0.000000) -CustomFoveationPatternSettings=(FoveatedHorizontalRadius=0.250000,FoveatedVerticalRadius=0.250000,MiddleHorizontalRadius=0.330000,MiddleVerticalRadius=0.330000,PeripheralHorizontalRadius=1.500000,PeripheralVerticalRadius=1.500000) -ShadingRatePreset=HIGHEST_PERFORMANCE -ShadingRateDetail=(FoveatedShadingRate=X1_PER_PIXEL,MiddleShadingRate=X1_PER_2X2PIXEL,PeripheralShadingRate=X1_PER_4X4PIXEL) -CustomShadingRateSettings=(FoveatedShadingRate=X16_PER_PIXEL,MiddleShadingRate=X16_PER_PIXEL,PeripheralShadingRate=X16_PER_PIXEL) - +[/Script/EngineSettings.GeneralProjectSettings] +ProjectID=675BF8694238308FA9368292CC440350 +ProjectName=CARLA UE4 + DReyeVR +CompanyName=CVC +CopyrightNotice="Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). This work is licensed under the terms of the MIT license. For a copy, see ." +ProjectVersion=0.9.13 + +[/Script/Carla.CarlaSettings] ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapRoad.CheapRoad"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalkCurb.CheapSideWalkCurb"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapSideWalk_00.CheapSideWalk_00"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++LowRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SimpleRoad/CheapLaneMarking.CheapLaneMarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) +LowLightFadeDistance=1000.000000 +LowStaticMeshMaxDrawDistance=10000.000000 +LowRoadPieceMeshMaxDrawDistance=15000.000000 ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/WetPavement/WetPavement_Complex_Road_N2.WetPavement_Complex_Road_N2"',MaterialSlotName="Tileroad_Road",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/WetPavement/WetPavement_Complex_Concrete.WetPavement_Complex_Concrete"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SideWalks/SidewalkN4/WetPavement_SidewalkN4.WetPavement_SidewalkN4"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) ++EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/LaneMarking/Lanemarking.Lanemarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) + +[/Script/UnrealEd.ProjectPackagingSettings] +Build=IfProjectHasCode +BuildConfiguration=PPBC_Development +StagingDirectory=(Path="") +FullRebuild=False +ForDistribution=False +IncludeDebugFiles=True +BlueprintNativizationMethod=Disabled +bIncludeNativizedAssetsInProjectGeneration=False +UsePakFile=True +bGenerateChunks=False +bGenerateNoChunks=False +bChunkHardReferencesOnly=False +bBuildHttpChunkInstallData=False +HttpChunkInstallDataDirectory=(Path="") +HttpChunkInstallDataVersion= +IncludePrerequisites=True +IncludeAppLocalPrerequisites=False +bShareMaterialShaderCode=False +bSharedMaterialNativeLibraries=False +ApplocalPrerequisitesDirectory=(Path="") +IncludeCrashReporter=False +InternationalizationPreset=English +-CulturesToStage=en ++CulturesToStage=en +bCookAll=False +bCookMapsOnly=False +bCompressed=False +bEncryptIniFiles=False +bEncryptPakIndex=False +bSkipEditorContent=False ++MapsToCook=(FilePath="/Game/Carla/Maps/Town01") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town01_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town02") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town02_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town03") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town03_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town04") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town04_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town05") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town05_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town06") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town06_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town07") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town07_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town10HD") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town10HD_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/OpenDriveMap") ++MapsToCook=(FilePath="/Game/Carla/Maps/TestMaps/EmptyMap") ++DirectoriesToAlwaysCook=(Path="/Game/Carla/Static/GenericMaterials/Licenseplates/Textures") ++DirectoriesToAlwaysCook=(Path="/Game/DReyeVR") ++DirectoriesToAlwaysCook=(Path="/Game/DReyeVR/EgoVehicle/Extra") ++DirectoriesToAlwaysCook=(Path="/Carla/PostProcessingMaterials") ++DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/OpenDrive") ++DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/Nav") ++DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/TM") ++DirectoriesToAlwaysStageAsUFS=(Path="Carla/Config") +bNativizeBlueprintAssets=False +bNativizeOnlySelectedBlueprints=False + +[/Script/VRSSettingsEditor.VRSSettings] +vrs.EnableVRS=True +vrs.EnableEyeTracking=True +vrs.VRSRenderType=0 +FoveationPatternPreset=NARROW +FoveationPatternDetail=(FoveatedHorizontalRadius=0.000000,FoveatedVerticalRadius=0.000000,MiddleHorizontalRadius=0.000000,MiddleVerticalRadius=0.000000,PeripheralHorizontalRadius=0.000000,PeripheralVerticalRadius=0.000000) +CustomFoveationPatternSettings=(FoveatedHorizontalRadius=0.250000,FoveatedVerticalRadius=0.250000,MiddleHorizontalRadius=0.330000,MiddleVerticalRadius=0.330000,PeripheralHorizontalRadius=1.500000,PeripheralVerticalRadius=1.500000) +ShadingRatePreset=HIGHEST_PERFORMANCE +ShadingRateDetail=(FoveatedShadingRate=X1_PER_PIXEL,MiddleShadingRate=X1_PER_2X2PIXEL,PeripheralShadingRate=X1_PER_4X4PIXEL) +CustomShadingRateSettings=(FoveatedShadingRate=X16_PER_PIXEL,MiddleShadingRate=X16_PER_PIXEL,PeripheralShadingRate=X16_PER_PIXEL) + diff --git a/Config/DefaultInput.ini b/Config/DefaultInput.ini index 87a830a..6c96b7c 100644 --- a/Config/DefaultInput.ini +++ b/Config/DefaultInput.ini @@ -1,153 +1,153 @@ - - -[/Script/Engine.InputSettings] --AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) --AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) --AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) --AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) --AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) --AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) --AxisConfig=(AxisKeyName="Mouse2D",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) -+AxisConfig=(AxisKeyName="Mouse2D",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MouseWheelAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_LeftTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_RightTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Left_TriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Left_Grip1Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Left_Grip2Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Right_TriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Right_Grip1Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MotionController_Right_Grip2Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_Special_Left_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Gamepad_Special_Left_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Daydream_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Daydream_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Daydream_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Daydream_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Vive_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Vive_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Vive_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Vive_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Vive_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="Vive_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="MixedReality_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusGo_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusGo_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusGo_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusGo_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Left_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Right_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="OculusTouch_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Grip_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Touch",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Grip_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -+AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) -bAltEnterTogglesFullscreen=True -bF11TogglesFullscreen=True -bUseMouseForTouch=False -bEnableMouseSmoothing=True -bEnableFOVScaling=True -bCaptureMouseOnLaunch=False -bAlwaysShowTouchInterface=False -bShowConsoleOnFourFingerTap=True -bEnableGestureRecognizer=False -bUseAutocorrect=False -DefaultViewportMouseCaptureMode=CaptureDuringMouseDown -DefaultViewportMouseLockMode=DoNotLock -FOVScale=0.011110 -DoubleClickTime=0.200000 -+ActionMappings=(ActionName="ToggleReverse_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=LeftAlt) -+ActionMappings=(ActionName="RestartLevel",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=R) -+ActionMappings=(ActionName="Handbrake",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=SpaceBar) -+ActionMappings=(ActionName="ToggleManualMode",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=M) -+ActionMappings=(ActionName="ResetCamera_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=G) -+ActionMappings=(ActionName="Jump",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Enter) -+ActionMappings=(ActionName="ToggleReverse",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Q) -+ActionMappings=(ActionName="UseTheForce",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=F) -+ActionMappings=(ActionName="NextCameraView_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Tab) -+ActionMappings=(ActionName="PrevCameraView_DReyeVR",bShift=True,bCtrl=False,bAlt=False,bCmd=False,Key=Tab) -+ActionMappings=(ActionName="ChangeWeather",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=C) -+ActionMappings=(ActionName="ToggleAutopilot",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=P) -+ActionMappings=(ActionName="PlayPause_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=SpaceBar) -+ActionMappings=(ActionName="FastForward_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Right) -+ActionMappings=(ActionName="Rewind_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Left) -+ActionMappings=(ActionName="Restart_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=BackSpace) -+ActionMappings=(ActionName="Incr_Timestep_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Up) -+ActionMappings=(ActionName="Decr_Timestep_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Down) -+ActionMappings=(ActionName="ToggleReverse_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Z) -+ActionMappings=(ActionName="TurnSignalLeft_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Q) -+ActionMappings=(ActionName="TurnSignalRight_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=E) -+ActionMappings=(ActionName="EgoVehicle_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=One) -+ActionMappings=(ActionName="Spectator_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Two) -+ActionMappings=(ActionName="AI_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Three) -+ActionMappings=(ActionName="CameraFwd_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Up) -+ActionMappings=(ActionName="CameraBack_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Down) -+ActionMappings=(ActionName="CameraLeft_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Left) -+ActionMappings=(ActionName="CameraRight_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Right) -+ActionMappings=(ActionName="CameraUp_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=PageUp) -+ActionMappings=(ActionName="CameraDown_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=PageDown) -+ActionMappings=(ActionName="NextShader_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Period) -+ActionMappings=(ActionName="PrevShader_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Comma) -+AxisMappings=(AxisName="Throttle_DReyeVR",Scale=1.000000,Key=W) -+AxisMappings=(AxisName="Brake_DReyeVR",Scale=1.000000,Key=S) -+AxisMappings=(AxisName="Steer_DReyeVR",Scale=1.000000,Key=D) -+AxisMappings=(AxisName="Steer_DReyeVR",Scale=-1.000000,Key=A) -+AxisMappings=(AxisName="MouseLookUp_DReyeVR",Scale=-1.000000,Key=MouseY) -+AxisMappings=(AxisName="MouseTurn_DReyeVR",Scale=1.000000,Key=MouseX) -+AxisMappings=(AxisName="CameraZoom",Scale=-20.000000,Key=MouseWheelAxis) -+AxisMappings=(AxisName="CameraZoom",Scale=-10.000000,Key=PageUp) -+AxisMappings=(AxisName="CameraZoom",Scale=10.000000,Key=PageDown) -+AxisMappings=(AxisName="CameraUp",Scale=1.000000,Key=Up) -+AxisMappings=(AxisName="CameraUp",Scale=-1.000000,Key=Down) -+AxisMappings=(AxisName="CameraRight",Scale=1.000000,Key=Right) -+AxisMappings=(AxisName="CameraRight",Scale=-1.000000,Key=Left) -+AxisMappings=(AxisName="MoveForward",Scale=1.000000,Key=W) -+AxisMappings=(AxisName="MoveRight",Scale=1.000000,Key=D) -+AxisMappings=(AxisName="MoveRight",Scale=-1.000000,Key=A) -+AxisMappings=(AxisName="Brake",Scale=1.000000,Key=B) -+AxisMappings=(AxisName="MoveForward",Scale=-1.000000,Key=S) -+AxisMappings=(AxisName="MoveUp",Scale=1.000000,Key=E) -+AxisMappings=(AxisName="MoveUp",Scale=-1.000000,Key=Q) -DefaultPlayerInputClass=/Script/Engine.PlayerInput -DefaultInputComponentClass=/Script/Engine.InputComponent -DefaultTouchInterface=/Engine/MobileResources/HUD/DefaultVirtualJoysticks.DefaultVirtualJoysticks --ConsoleKeys=Tilde -+ConsoleKeys=Tilde - + + +[/Script/Engine.InputSettings] +-AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) +-AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) +-AxisConfig=(AxisKeyName="Mouse2D",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) ++AxisConfig=(AxisKeyName="Mouse2D",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MouseWheelAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_LeftTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_RightTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Left_TriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Left_Grip1Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Left_Grip2Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Right_TriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Right_Grip1Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MotionController_Right_Grip2Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_Special_Left_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_Special_Left_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Daydream_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Daydream_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Daydream_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Daydream_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusGo_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusGo_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusGo_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusGo_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Grip_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Touch",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Grip_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) +bAltEnterTogglesFullscreen=True +bF11TogglesFullscreen=True +bUseMouseForTouch=False +bEnableMouseSmoothing=True +bEnableFOVScaling=True +bCaptureMouseOnLaunch=False +bAlwaysShowTouchInterface=False +bShowConsoleOnFourFingerTap=True +bEnableGestureRecognizer=False +bUseAutocorrect=False +DefaultViewportMouseCaptureMode=CaptureDuringMouseDown +DefaultViewportMouseLockMode=DoNotLock +FOVScale=0.011110 +DoubleClickTime=0.200000 ++ActionMappings=(ActionName="ToggleReverse_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=LeftAlt) ++ActionMappings=(ActionName="RestartLevel",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=R) ++ActionMappings=(ActionName="Handbrake",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=SpaceBar) ++ActionMappings=(ActionName="ToggleManualMode",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=M) ++ActionMappings=(ActionName="ResetCamera_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=G) ++ActionMappings=(ActionName="Jump",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Enter) ++ActionMappings=(ActionName="ToggleReverse",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Q) ++ActionMappings=(ActionName="UseTheForce",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=F) ++ActionMappings=(ActionName="NextCameraView_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Tab) ++ActionMappings=(ActionName="PrevCameraView_DReyeVR",bShift=True,bCtrl=False,bAlt=False,bCmd=False,Key=Tab) ++ActionMappings=(ActionName="ChangeWeather",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=C) ++ActionMappings=(ActionName="ToggleAutopilot",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=P) ++ActionMappings=(ActionName="PlayPause_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=SpaceBar) ++ActionMappings=(ActionName="FastForward_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Right) ++ActionMappings=(ActionName="Rewind_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Left) ++ActionMappings=(ActionName="Restart_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=BackSpace) ++ActionMappings=(ActionName="Incr_Timestep_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Up) ++ActionMappings=(ActionName="Decr_Timestep_DReyeVR",bShift=False,bCtrl=False,bAlt=True,bCmd=False,Key=Down) ++ActionMappings=(ActionName="ToggleReverse_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Z) ++ActionMappings=(ActionName="TurnSignalLeft_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Q) ++ActionMappings=(ActionName="TurnSignalRight_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=E) ++ActionMappings=(ActionName="EgoVehicle_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=One) ++ActionMappings=(ActionName="Spectator_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Two) ++ActionMappings=(ActionName="AI_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Three) ++ActionMappings=(ActionName="CameraFwd_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Up) ++ActionMappings=(ActionName="CameraBack_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Down) ++ActionMappings=(ActionName="CameraLeft_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Left) ++ActionMappings=(ActionName="CameraRight_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Right) ++ActionMappings=(ActionName="CameraUp_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=PageUp) ++ActionMappings=(ActionName="CameraDown_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=PageDown) ++ActionMappings=(ActionName="NextShader_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Period) ++ActionMappings=(ActionName="PrevShader_DReyeVR",bShift=False,bCtrl=False,bAlt=False,bCmd=False,Key=Comma) ++AxisMappings=(AxisName="Throttle_DReyeVR",Scale=1.000000,Key=W) ++AxisMappings=(AxisName="Brake_DReyeVR",Scale=1.000000,Key=S) ++AxisMappings=(AxisName="Steer_DReyeVR",Scale=1.000000,Key=D) ++AxisMappings=(AxisName="Steer_DReyeVR",Scale=-1.000000,Key=A) ++AxisMappings=(AxisName="MouseLookUp_DReyeVR",Scale=-1.000000,Key=MouseY) ++AxisMappings=(AxisName="MouseTurn_DReyeVR",Scale=1.000000,Key=MouseX) ++AxisMappings=(AxisName="CameraZoom",Scale=-20.000000,Key=MouseWheelAxis) ++AxisMappings=(AxisName="CameraZoom",Scale=-10.000000,Key=PageUp) ++AxisMappings=(AxisName="CameraZoom",Scale=10.000000,Key=PageDown) ++AxisMappings=(AxisName="CameraUp",Scale=1.000000,Key=Up) ++AxisMappings=(AxisName="CameraUp",Scale=-1.000000,Key=Down) ++AxisMappings=(AxisName="CameraRight",Scale=1.000000,Key=Right) ++AxisMappings=(AxisName="CameraRight",Scale=-1.000000,Key=Left) ++AxisMappings=(AxisName="MoveForward",Scale=1.000000,Key=W) ++AxisMappings=(AxisName="MoveRight",Scale=1.000000,Key=D) ++AxisMappings=(AxisName="MoveRight",Scale=-1.000000,Key=A) ++AxisMappings=(AxisName="Brake",Scale=1.000000,Key=B) ++AxisMappings=(AxisName="MoveForward",Scale=-1.000000,Key=S) ++AxisMappings=(AxisName="MoveUp",Scale=1.000000,Key=E) ++AxisMappings=(AxisName="MoveUp",Scale=-1.000000,Key=Q) +DefaultPlayerInputClass=/Script/Engine.PlayerInput +DefaultInputComponentClass=/Script/Engine.InputComponent +DefaultTouchInterface=/Engine/MobileResources/HUD/DefaultVirtualJoysticks.DefaultVirtualJoysticks +-ConsoleKeys=Tilde ++ConsoleKeys=Tilde + diff --git a/Config/EgoVehicles/Jeep.ini b/Config/EgoVehicles/Jeep.ini index 95eae1e..15bc2a1 100644 --- a/Config/EgoVehicles/Jeep.ini +++ b/Config/EgoVehicles/Jeep.ini @@ -1,55 +1,55 @@ -# Config for custom EgoVehicle -# Vehicle: Jeep Wrangler Rubicon - -# some serialization formats: -# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) -# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) -# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) -# bool: True or False - -[Blueprint] -# get this by right clicking on the item in the asset menu and select "Copy Reference" -Path="Blueprint'/Game/DReyeVR/EgoVehicle/Jeep/BP_Jeep.BP_Jeep'" - -[CameraPose] -# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) -DriversSeat=(X=-30, Y=-33.0, Z=145.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera - -[Sounds] -EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis - -[Dashboard] -SpeedometerEnabled=True -SpeedometerTransform=(X=30.0, Y=0.0, Z=125.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -TurnSignalsEnabled=True -TurnSignalsTransform=(X=30.0, Y=11.0, Z=120.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -GearShifterEnabled=True -GearShifterTransform=(X=30.0, Y=15.0, Z=125.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) - -[Mirrors] -# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS -# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! - -# rear view mirror -RearMirrorEnabled=True -RearMirrorChassisTransform=(X=20, Y=1.43, Z=158.0 | R=0.0, P=5.0, Y=13.06 | X=1.0, Y=1.0, Z=1.0) -RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) -RearReflectionTransform=(X=-2.55, Y=0.0, Z=-2.2 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.006, Z=1.0) -RearScreenPercentage=85 # 100 is max quality, 0 is minimum quality -# left view side mirror -LeftMirrorEnabled=True -LeftMirrorTransform=(X=32.0, Y=-78.0, Z=125.5 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) -LeftReflectionTransform=(X=0, Y=0, Z=3.0 | R=30.0, P=83, Y=22.5 | X=0.005, Y=0.003, Z=1.0) -LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality -# right view side mirror -RightMirrorEnabled=True -RightMirrorTransform=(X=32.0, Y=78.0, Z=125.5 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) -RightReflectionTransform=(X=0.0, Y=0.0, Z=3.0 | R=340, P=90.0, Y=0 | X=0.005, Y=0.003, Z=1.0) -RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality - -[SteeringWheel] -Enabled=True -InitLocation=(X=12.0, Y=-32.0, Z=112.0) # position of the steering wheel in the vehicle -InitRotation=(R=0.0, P=-15.0, Y=0.0) # tilt of the steering wheel at rest -MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) -SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) +# Config for custom EgoVehicle +# Vehicle: Jeep Wrangler Rubicon + +# some serialization formats: +# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) +# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) +# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) +# bool: True or False + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/Jeep/BP_Jeep.BP_Jeep'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=-30, Y=-33.0, Z=145.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=30.0, Y=0.0, Z=125.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=30.0, Y=11.0, Z=120.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=30.0, Y=15.0, Z=125.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + +[Mirrors] +# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS +# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! + +# rear view mirror +RearMirrorEnabled=True +RearMirrorChassisTransform=(X=20, Y=1.43, Z=158.0 | R=0.0, P=5.0, Y=13.06 | X=1.0, Y=1.0, Z=1.0) +RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) +RearReflectionTransform=(X=-2.55, Y=0.0, Z=-2.2 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.006, Z=1.0) +RearScreenPercentage=85 # 100 is max quality, 0 is minimum quality +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=32.0, Y=-78.0, Z=125.5 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) +LeftReflectionTransform=(X=0, Y=0, Z=3.0 | R=30.0, P=83, Y=22.5 | X=0.005, Y=0.003, Z=1.0) +LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=32.0, Y=78.0, Z=125.5 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) +RightReflectionTransform=(X=0.0, Y=0.0, Z=3.0 | R=340, P=90.0, Y=0 | X=0.005, Y=0.003, Z=1.0) +RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=True +InitLocation=(X=12.0, Y=-32.0, Z=112.0) # position of the steering wheel in the vehicle +InitRotation=(R=0.0, P=-15.0, Y=0.0) # tilt of the steering wheel at rest +MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/Config/EgoVehicles/Mustang66.ini b/Config/EgoVehicles/Mustang66.ini index 9ee87e6..13ac487 100644 --- a/Config/EgoVehicles/Mustang66.ini +++ b/Config/EgoVehicles/Mustang66.ini @@ -1,55 +1,55 @@ -# Config for custom EgoVehicle -# Vehicle: Mustang 1966 - -# some serialization formats: -# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) -# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) -# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) -# bool: True or False - -[Blueprint] -# get this by right clicking on the item in the asset menu and select "Copy Reference" -Path="Blueprint'/Game/DReyeVR/EgoVehicle/Mustang66/BP_Mustang66.BP_Mustang66'" - -[CameraPose] -# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) -DriversSeat=(X=-20.0, Y=-40.0, Z=110.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera - -[Sounds] -EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis - -[Dashboard] -SpeedometerEnabled=True -SpeedometerTransform=(X=60.0, Y=0.0, Z=90.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -TurnSignalsEnabled=True -TurnSignalsTransform=(X=60.0, Y=11.0, Z=85.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -GearShifterEnabled=True -GearShifterTransform=(X=60.0, Y=15.0, Z=90.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) - -[Mirrors] -# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS -# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! - -# rear view mirror -RearMirrorEnabled=True -RearMirrorChassisTransform=(X=10.0, Y=0.0, Z=120.0 | R=0.0, P=3.0, Y=20.06 | X=1.0, Y=1.0, Z=1.0) -RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) -RearReflectionTransform=(X=-7, Y=0.0, Z=0.0 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.007, Z=1.0) -RearScreenPercentage=85 # 100 is max quality, 0 is minimum quality -# left view side mirror -LeftMirrorEnabled=True -LeftMirrorTransform=(X=22.0, Y=-88.0, Z=97 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) -LeftReflectionTransform=(X=0, Y=0, Z=0.0 | R=43, P=86, Y=22 | X=0.003, Y=0.003, Z=1.0) -LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality -# right view side mirror -RightMirrorEnabled=True -RightMirrorTransform=(X=-22, Y=87.7, Z=97 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) -RightReflectionTransform=(X=0.0, Y=0.0, Z=0 | R=-4.16, P=90.0, Y=18.4 | X=0.003, Y=0.003, Z=1.0) -RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality - -[SteeringWheel] -Enabled=True -InitLocation=(X=31.33, Y=-42.0, Z=76.8) # position of the steering wheel in the vehicle -InitRotation=(R=0.0, P=-10.0, Y=0.0) # tilt of the steering wheel at rest -MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) -SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) +# Config for custom EgoVehicle +# Vehicle: Mustang 1966 + +# some serialization formats: +# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) +# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) +# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) +# bool: True or False + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/Mustang66/BP_Mustang66.BP_Mustang66'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=-20.0, Y=-40.0, Z=110.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=60.0, Y=0.0, Z=90.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=60.0, Y=11.0, Z=85.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=60.0, Y=15.0, Z=90.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + +[Mirrors] +# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS +# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! + +# rear view mirror +RearMirrorEnabled=True +RearMirrorChassisTransform=(X=10.0, Y=0.0, Z=120.0 | R=0.0, P=3.0, Y=20.06 | X=1.0, Y=1.0, Z=1.0) +RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) +RearReflectionTransform=(X=-7, Y=0.0, Z=0.0 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.007, Z=1.0) +RearScreenPercentage=85 # 100 is max quality, 0 is minimum quality +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=22.0, Y=-88.0, Z=97 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) +LeftReflectionTransform=(X=0, Y=0, Z=0.0 | R=43, P=86, Y=22 | X=0.003, Y=0.003, Z=1.0) +LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=-22, Y=87.7, Z=97 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) +RightReflectionTransform=(X=0.0, Y=0.0, Z=0 | R=-4.16, P=90.0, Y=18.4 | X=0.003, Y=0.003, Z=1.0) +RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=True +InitLocation=(X=31.33, Y=-42.0, Z=76.8) # position of the steering wheel in the vehicle +InitRotation=(R=0.0, P=-10.0, Y=0.0) # tilt of the steering wheel at rest +MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/Config/EgoVehicles/TeslaM3.ini b/Config/EgoVehicles/TeslaM3.ini index 22699b4..3e426f1 100644 --- a/Config/EgoVehicles/TeslaM3.ini +++ b/Config/EgoVehicles/TeslaM3.ini @@ -1,55 +1,55 @@ -# Config for custom EgoVehicle -# Vehicle: Tesla Model 3 - -# some serialization formats: -# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) -# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) -# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) -# bool: True or False - -[Blueprint] -# get this by right clicking on the item in the asset menu and select "Copy Reference" -Path="Blueprint'/Game/DReyeVR/EgoVehicle/TeslaM3/BP_TeslaM3.BP_TeslaM3'" - -[CameraPose] -# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) -DriversSeat=(X=20.0, Y=-40.0, Z=120.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera - -[Sounds] -EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis - -[Dashboard] -SpeedometerEnabled=True -SpeedometerTransform=(X=110.0, Y=0.0, Z=105.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -TurnSignalsEnabled=True -TurnSignalsTransform=(X=110.0, Y=11.0, Z=100.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -GearShifterEnabled=True -GearShifterTransform=(X=110.0, Y=15.0, Z=105.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) - -[Mirrors] -# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS -# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! - -# rear view mirror -RearMirrorEnabled=True -RearMirrorChassisTransform=(X=48.0, Y=0.0, Z=123.0 | R=0.0, P=2.0, Y=21.06 | X=1.0, Y=1.0, Z=1.0) -RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) -RearReflectionTransform=(X=-7, Y=0.0, Z=0.0 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.007, Z=1.0) -RearScreenPercentage=85 # 100 is max quality, 0 is minimum quality -# left view side mirror -LeftMirrorEnabled=True -LeftMirrorTransform=(X=62.0, Y=-98.0, Z=105.5 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) -LeftReflectionTransform=(X=0, Y=0, Z=-3.0 | R=43.2, P=81, Y=27 | X=0.003, Y=0.005, Z=1.0) -LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality -# right view side mirror -RightMirrorEnabled=True -RightMirrorTransform=(X=62, Y=98, Z=100.5 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) -RightReflectionTransform=(X=0.0, Y=0.0, Z=2.22 | R=-1, P=90.0, Y=21.6 | X=0.003, Y=0.005, Z=1.0) -RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality - -[SteeringWheel] -Enabled=True -InitLocation=(X=85.0, Y=-40.0, Z=85.0) # position of the steering wheel in the vehicle -InitRotation=(R=0.0, P=-10.0, Y=0.0) # tilt of the steering wheel at rest -MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) -SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) +# Config for custom EgoVehicle +# Vehicle: Tesla Model 3 + +# some serialization formats: +# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) +# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) +# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) +# bool: True or False + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/TeslaM3/BP_TeslaM3.BP_TeslaM3'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=20.0, Y=-40.0, Z=120.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=110.0, Y=0.0, Z=105.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=110.0, Y=11.0, Z=100.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=110.0, Y=15.0, Z=105.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + +[Mirrors] +# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS +# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! + +# rear view mirror +RearMirrorEnabled=True +RearMirrorChassisTransform=(X=48.0, Y=0.0, Z=123.0 | R=0.0, P=2.0, Y=21.06 | X=1.0, Y=1.0, Z=1.0) +RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) +RearReflectionTransform=(X=-7, Y=0.0, Z=0.0 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.007, Z=1.0) +RearScreenPercentage=85 # 100 is max quality, 0 is minimum quality +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=62.0, Y=-98.0, Z=105.5 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) +LeftReflectionTransform=(X=0, Y=0, Z=-3.0 | R=43.2, P=81, Y=27 | X=0.003, Y=0.005, Z=1.0) +LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=62, Y=98, Z=100.5 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) +RightReflectionTransform=(X=0.0, Y=0.0, Z=2.22 | R=-1, P=90.0, Y=21.6 | X=0.003, Y=0.005, Z=1.0) +RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=True +InitLocation=(X=85.0, Y=-40.0, Z=85.0) # position of the steering wheel in the vehicle +InitRotation=(R=0.0, P=-10.0, Y=0.0) # tilt of the steering wheel at rest +MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/Config/EgoVehicles/Vespa.ini b/Config/EgoVehicles/Vespa.ini index 64459cc..a6b926e 100644 --- a/Config/EgoVehicles/Vespa.ini +++ b/Config/EgoVehicles/Vespa.ini @@ -1,56 +1,56 @@ -# Config for custom EgoVehicle -# Vehicle: Vespa 2-wheeled vehicle - -# some serialization formats: -# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) -# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) -# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) -# bool: True or False - -[Blueprint] -# get this by right clicking on the item in the asset menu and select "Copy Reference" -Path="Blueprint'/Game/DReyeVR/EgoVehicle/Vespa/BP_Vespa.BP_Vespa'" - -[CameraPose] -# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) -DriversSeat=(X=-30.0, Y=0.0, Z=130.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera - -[Sounds] -EngineLocn=(X=0.0 | Y=0.0 | Z=30.0) # where is the engine in the Vehicle chassis - -[Dashboard] -SpeedometerEnabled=True -SpeedometerTransform=(X=40.0, Y=0.0, Z=119.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -TurnSignalsEnabled=True -TurnSignalsTransform=(X=30.0, Y=0.0, Z=126.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) -GearShifterEnabled=True -GearShifterTransform=(X=26.0, Y=0.0, Z=111.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) - - -[Mirrors] -# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS -# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! - -# rear view mirror -RearMirrorEnabled=False -RearMirrorChassisTransform=(X=48.0, Y=0.0, Z=123.0 | R=0.0, P=0.0, Y=25.06 | X=1.0, Y=1.0, Z=1.0) -RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) -RearReflectionTransform=(X=-7, Y=0.0, Z=0.0 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.007, Z=1.0) -RearScreenPercentage=0 # 100 is max quality, 0 is minimum quality -# left view side mirror -LeftMirrorEnabled=True -LeftMirrorTransform=(X=23.2, Y=-37.5, Z=118 | R=0.0, P=0.0, Y=-7 | X=1, Y=1, Z=1) -LeftReflectionTransform=(X=0.43, Y=0.17, Z=0.036 | R=43.2, P=90, Y=47.6 | X=0.003, Y=0.003, Z=1.0) -LeftScreenPercentage=100 # 100 is max quality, 0 is minimum quality -# right view side mirror -RightMirrorEnabled=True -RightMirrorTransform=(X=23.07, Y=37.5, Z=118.46 | R=0, P=-4, Y=2.79 | X=1, Y=1, Z=1) -RightReflectionTransform=(X=0.0, Y=0.0, Z=-0.78 | R=68, P=90.0, Y=75.6 | X=0.003, Y=0.003, Z=1.0) -RightScreenPercentage=100 # 100 is max quality, 0 is minimum quality - -[SteeringWheel] -Enabled=False -InitLocation=(X=85.0, Y=-40.0, Z=85.0) # position of the steering wheel in the vehicle -InitRotation=(R=0.0, P=-10.0, Y=0.0) # tilt of the steering wheel at rest -MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) -SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) +# Config for custom EgoVehicle +# Vehicle: Vespa 2-wheeled vehicle + +# some serialization formats: +# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) +# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) +# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) +# bool: True or False + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/Vespa/BP_Vespa.BP_Vespa'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=-30.0, Y=0.0, Z=130.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=0.0 | Y=0.0 | Z=30.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=40.0, Y=0.0, Z=119.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=30.0, Y=0.0, Z=126.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=26.0, Y=0.0, Z=111.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + + +[Mirrors] +# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS +# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! + +# rear view mirror +RearMirrorEnabled=False +RearMirrorChassisTransform=(X=48.0, Y=0.0, Z=123.0 | R=0.0, P=0.0, Y=25.06 | X=1.0, Y=1.0, Z=1.0) +RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) +RearReflectionTransform=(X=-7, Y=0.0, Z=0.0 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.007, Z=1.0) +RearScreenPercentage=0 # 100 is max quality, 0 is minimum quality +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=23.2, Y=-37.5, Z=118 | R=0.0, P=0.0, Y=-7 | X=1, Y=1, Z=1) +LeftReflectionTransform=(X=0.43, Y=0.17, Z=0.036 | R=43.2, P=90, Y=47.6 | X=0.003, Y=0.003, Z=1.0) +LeftScreenPercentage=100 # 100 is max quality, 0 is minimum quality +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=23.07, Y=37.5, Z=118.46 | R=0, P=-4, Y=2.79 | X=1, Y=1, Z=1) +RightReflectionTransform=(X=0.0, Y=0.0, Z=-0.78 | R=68, P=90.0, Y=75.6 | X=0.003, Y=0.003, Z=1.0) +RightScreenPercentage=100 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=False +InitLocation=(X=85.0, Y=-40.0, Z=85.0) # position of the steering wheel in the vehicle +InitRotation=(R=0.0, P=-10.0, Y=0.0) # tilt of the steering wheel at rest +MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/DReyeVR/ConfigFile.h b/DReyeVR/ConfigFile.h index 7c20580..ce88c42 100644 --- a/DReyeVR/ConfigFile.h +++ b/DReyeVR/ConfigFile.h @@ -1,334 +1,334 @@ -#pragma once -#include // std::ifstream -#include // std::istream -#include // std::istringstream -#include -#include - -const static FString CarlaUE4Path = FPaths::ConvertRelativePathToFull(FPaths::ProjectDir()); - -struct ConfigFile -{ - ConfigFile() = default; // empty constructor (no params yet) - ConfigFile(const FString &Path, bool bVerbose = true) : FilePath(Path) - { - /// TODO: add feature to "hot-reload" new params during runtime - bSuccessfulUpdate = ReadFile(bVerbose); // ensures all the variables are updated upon construction - - // simple sanity check to ensure exporting and importing the same config file works as intended - // (exporting self and creating a new import should be equal to self) - static bool bSanityCheck = this->IsEqual(ConfigFile::Import(this->Export())); - ensureMsgf(bSanityCheck, TEXT("Sanity check for ConfigFile import/export failed!")); - } - - template bool Get(const FString &Section, const FString &Variable, T &Value) const - { - const std::string SectionStdStr(TCHAR_TO_UTF8(*Section)); - const std::string VariableStdStr(TCHAR_TO_UTF8(*Variable)); - return GetValue(SectionStdStr, VariableStdStr, Value); - } - - template T Get(const FString &Section, const FString &Variable) const - { - T Value; - /// TODO: implement exception when Get returns false? - Get(Section, Variable, Value); - return Value; - } - - template - T GetConstrained(const FString &Section, const FString &Variable, const std::unordered_set &Options, - const T &DefaultValue) const - { - T Value = Get(Section, Variable); - if (Options.find(Value) == Options.end()) - { - // not found within the constrained available options - Value = DefaultValue; - } - return Value; - } - - bool bIsValid() const - { - return bSuccessfulUpdate; - } - - bool IsEqual(const ConfigFile &Other, bool bPrintWarning = false) const - { - // calculates if A subset B and B subset A - return this->IsSubset(Other, bPrintWarning) && Other.IsSubset(*this, bPrintWarning); - } - - bool IsSubset(const ConfigFile &Other, bool bPrintWarning = false) const - { - // only checking that this is a perfect subset of Other - // => Other can contain data that this config does not have - // (if you want perfect equality, do A.CompareEqual(B) && B.CompareEqual(A)) - struct Comparison - { - Comparison(const std::string &Section, const std::string &Variable, const FString &Expected, - const FString &Other) - : SectionName(Section), VariableName(Variable), ThisValue(Expected), OtherValue(Other) - { - } - - Comparison(const std::string &Section, const std::string &Variable) - : SectionName(Section), VariableName(Variable), bIsMissing(true) - { - } - const std::string SectionName, VariableName; - const FString ThisValue, OtherValue; - const bool bIsMissing = false; - }; - std::vector Diff = {}; - for (const auto &SectionData : Sections) - { - const std::string &SectionName = SectionData.first; - const IniSection &Section = SectionData.second; - for (const auto &EntryData : Section.Entries) - { - const std::string &VariableName = EntryData.first; - const ParamString &Value = EntryData.second; - ParamString OtherValue; - if (Other.Find(SectionName, VariableName, OtherValue)) - { - // compare equality - if (!Value.DataStr.Equals(OtherValue.DataStr, ESearchCase::IgnoreCase)) - { - Diff.push_back({SectionName, VariableName, Value.DataStr, OtherValue.DataStr}); - } - } - else // did not find, missing - { - Diff.push_back({SectionName, VariableName}); - } - } - } - - bool bIsDifferent = (Diff.size() > 0); - // print differences - if (bPrintWarning && bIsDifferent) - { - LOG_WARN("Found config differences this {\"%s\"} and Other {\"%s\"}", *FilePath, *Other.FilePath); - for (const Comparison &Comp : Diff) - { - if (Comp.bIsMissing) - { - LOG_WARN("Missing [%s] \"%s\"", *FString(Comp.SectionName.c_str()), - *FString(Comp.VariableName.c_str())); - } - else - { - LOG_WARN("This [%s] \"%s\" {%s} does not match {%s}", *FString(Comp.SectionName.c_str()), - *FString(Comp.VariableName.c_str()), *Comp.ThisValue, *Comp.OtherValue); - } - } - } - return !bIsDifferent; - } - - void Insert(const ConfigFile &Other) - { - if (!Other.bIsValid()) - return; - FilePath += ";" + Other.FilePath; - if (Other.Sections.size() > 0) - Sections.insert(Other.Sections.begin(), Other.Sections.end()); - bSuccessfulUpdate = true; - } - - static ConfigFile Import(const std::string &Configuration) - { - // takes a flattened INI configuration file as parameter and reads it into a ConfigFile class - return ConfigFile(Configuration); - } - - std::string Export() const - { - std::ostringstream oss; - oss << std::endl - << "# This is an exported config file originally from \"" << TCHAR_TO_UTF8(*FilePath) << "\"" << std::endl - << std::endl; - for (const auto &SectionData : Sections) - { - const std::string &SectionName = SectionData.first; - const IniSection &Section = SectionData.second; - oss << "[" << SectionName << "]" << std::endl; // The overarching section first - for (const auto &EntryData : Section.Entries) - { - const std::string &VariableName = EntryData.first; - const ParamString &Data = EntryData.second; - const std::string DataUTF = TCHAR_TO_UTF8(*Data.DataStr); // convert to UTF-8 format - const std::string DataStdStr = Data.bHasQuotes ? "\"" + DataUTF + "\"" : DataUTF; - oss << VariableName << "=" << DataStdStr << std::endl; - } - oss << std::endl; - } - return oss.str(); - } - - private: - bool ReadFile(bool bVerbose) - { - check(!FilePath.IsEmpty()); - if (bVerbose) - { - LOG("Reading config from %s", *FilePath); - } - std::ifstream MatchingFile(TCHAR_TO_ANSI(*FilePath), std::ios::in); - if (MatchingFile) - { - return Update(MatchingFile); - } - LOG_ERROR("Unable to open the config file \"%s\"", *FilePath); - return false; - } - - bool Update(std::istream &InputStream) // reload the internally tracked table of params - { - /// performs a single pass over the config stream to collect all variables into Params - std::string Line; - std::string Section = ""; - while (std::getline(InputStream, Line)) - { - if (InputStream.bad()) // IO error - return false; - // std::string stdKey = std::string(TCHAR_TO_UTF8(*Key)); - if (Line[0] == '#' || Line[0] == ';') // ignore comments - continue; - std::istringstream iss_Line(Line); - if (Line[0] == '[') // test section - { - std::getline(iss_Line, Section, ']'); - Section = Section.substr(1); // skip leading '[' - continue; - } - std::string Key; - if (std::getline(iss_Line, Key, '=')) // gets left side of '=' into FileKey - { - std::string Value; - if (std::getline(iss_Line, Value, '#')) // gets left side of '#' for comments - { - // ensure there is a section (create one if necesary) to store this key:value pair - if (Sections.find(Section) == Sections.end()) - { - Sections.insert({Section, IniSection(Section)}); - } - check(Sections.find(Section) != Sections.end()); - auto &CorrespondingSection = Sections.find(Section)->second; - CorrespondingSection.Entries.insert({Key, ParamString(Value)}); - } - } - } - return true; - } - - private: - struct ParamString - { - ParamString() = default; - ParamString(const std::string &Value) - { - DataStr = FString(Value.c_str()).TrimStartAndEnd().TrimQuotes(&bHasQuotes); - } - - FString DataStr = ""; // string representation of the data to parse into primitives - - template inline T DecipherToType() const - { - // supports FVector, FVector2D, FLinearColor, FQuat, and FRotator, - // basically any UE4 type that has a ::InitFromString method - T Ret; - if (Ret.InitFromString(DataStr) == false) - { - LOG_ERROR("Unable to decipher \"%s\" to a type", *DataStr); - } - return Ret; - } - - template <> inline bool DecipherToType() const - { - return DataStr.ToBool(); - } - - template <> inline int DecipherToType() const - { - return FCString::Atoi(*DataStr); - } - - template <> inline float DecipherToType() const - { - return FCString::Atof(*DataStr); - } - - template <> inline FString DecipherToType() const - { - return DataStr; - } - - template <> inline FName DecipherToType() const - { - return FName(*DataStr); - } - bool bHasQuotes = false; - }; - - struct IniSection - { - IniSection(const std::string &SectionName) : SectionHeader(SectionName) - { - } - - std::string SectionHeader; // typically what is contained in [Sections] - std::unordered_map Entries; // everything else - }; - - private: - // construct a ConfigFile by passing in the entire contents of the config file (rather than the path to read) - ConfigFile(const std::string &ConfigurationContents) : FilePath("") - { - std::istringstream iss(ConfigurationContents); - bSuccessfulUpdate = Update(iss); - } - - // using std::string variant for internal use (FString for user-facing) - template bool GetValue(const std::string &SectionName, const std::string &VariableName, T &Value) const - { - ParamString Param; - bool bFound = Find(SectionName, VariableName, Param); - if (bFound) - Value = Param.DecipherToType(); - return bFound; - } - - bool Find(const std::string &SectionName, const std::string &VariableName, ParamString &Out) const - { - auto SectionIt = Sections.find(SectionName); - if (SectionIt == Sections.end()) - { - LOG_ERROR("No section in config file matches \"%s\"", *FString(SectionName.c_str())); - return false; - } - const IniSection &Section = SectionIt->second; - auto EntryIt = Section.Entries.find(VariableName); - if (EntryIt == Section.Entries.end()) - { - LOG_ERROR("No entry for \"%s\" in [%s] section found!", *FString(VariableName.c_str()), - *FString(SectionName.c_str())); - return false; - } - Out = EntryIt->second; - - // enable this for debug purposes - // LOG("Read [%s]\"%s\" -> %s", *FString(SectionName.c_str()), *FString(VariableName.c_str()), *Out.DataStr); - return true; // found successfully! - } - - private: - FString FilePath; // const except for overwrite - bool bSuccessfulUpdate = false; - std::unordered_map Sections; -}; - -static ConfigFile GeneralParams(FPaths::Combine(CarlaUE4Path, TEXT("Config/DReyeVRConfig.ini"))); +#pragma once +#include // std::ifstream +#include // std::istream +#include // std::istringstream +#include +#include + +const static FString CarlaUE4Path = FPaths::ConvertRelativePathToFull(FPaths::ProjectDir()); + +struct ConfigFile +{ + ConfigFile() = default; // empty constructor (no params yet) + ConfigFile(const FString &Path, bool bVerbose = true) : FilePath(Path) + { + /// TODO: add feature to "hot-reload" new params during runtime + bSuccessfulUpdate = ReadFile(bVerbose); // ensures all the variables are updated upon construction + + // simple sanity check to ensure exporting and importing the same config file works as intended + // (exporting self and creating a new import should be equal to self) + static bool bSanityCheck = this->IsEqual(ConfigFile::Import(this->Export())); + ensureMsgf(bSanityCheck, TEXT("Sanity check for ConfigFile import/export failed!")); + } + + template bool Get(const FString &Section, const FString &Variable, T &Value) const + { + const std::string SectionStdStr(TCHAR_TO_UTF8(*Section)); + const std::string VariableStdStr(TCHAR_TO_UTF8(*Variable)); + return GetValue(SectionStdStr, VariableStdStr, Value); + } + + template T Get(const FString &Section, const FString &Variable) const + { + T Value; + /// TODO: implement exception when Get returns false? + Get(Section, Variable, Value); + return Value; + } + + template + T GetConstrained(const FString &Section, const FString &Variable, const std::unordered_set &Options, + const T &DefaultValue) const + { + T Value = Get(Section, Variable); + if (Options.find(Value) == Options.end()) + { + // not found within the constrained available options + Value = DefaultValue; + } + return Value; + } + + bool bIsValid() const + { + return bSuccessfulUpdate; + } + + bool IsEqual(const ConfigFile &Other, bool bPrintWarning = false) const + { + // calculates if A subset B and B subset A + return this->IsSubset(Other, bPrintWarning) && Other.IsSubset(*this, bPrintWarning); + } + + bool IsSubset(const ConfigFile &Other, bool bPrintWarning = false) const + { + // only checking that this is a perfect subset of Other + // => Other can contain data that this config does not have + // (if you want perfect equality, do A.CompareEqual(B) && B.CompareEqual(A)) + struct Comparison + { + Comparison(const std::string &Section, const std::string &Variable, const FString &Expected, + const FString &Other) + : SectionName(Section), VariableName(Variable), ThisValue(Expected), OtherValue(Other) + { + } + + Comparison(const std::string &Section, const std::string &Variable) + : SectionName(Section), VariableName(Variable), bIsMissing(true) + { + } + const std::string SectionName, VariableName; + const FString ThisValue, OtherValue; + const bool bIsMissing = false; + }; + std::vector Diff = {}; + for (const auto &SectionData : Sections) + { + const std::string &SectionName = SectionData.first; + const IniSection &Section = SectionData.second; + for (const auto &EntryData : Section.Entries) + { + const std::string &VariableName = EntryData.first; + const ParamString &Value = EntryData.second; + ParamString OtherValue; + if (Other.Find(SectionName, VariableName, OtherValue)) + { + // compare equality + if (!Value.DataStr.Equals(OtherValue.DataStr, ESearchCase::IgnoreCase)) + { + Diff.push_back({SectionName, VariableName, Value.DataStr, OtherValue.DataStr}); + } + } + else // did not find, missing + { + Diff.push_back({SectionName, VariableName}); + } + } + } + + bool bIsDifferent = (Diff.size() > 0); + // print differences + if (bPrintWarning && bIsDifferent) + { + LOG_WARN("Found config differences this {\"%s\"} and Other {\"%s\"}", *FilePath, *Other.FilePath); + for (const Comparison &Comp : Diff) + { + if (Comp.bIsMissing) + { + LOG_WARN("Missing [%s] \"%s\"", *FString(Comp.SectionName.c_str()), + *FString(Comp.VariableName.c_str())); + } + else + { + LOG_WARN("This [%s] \"%s\" {%s} does not match {%s}", *FString(Comp.SectionName.c_str()), + *FString(Comp.VariableName.c_str()), *Comp.ThisValue, *Comp.OtherValue); + } + } + } + return !bIsDifferent; + } + + void Insert(const ConfigFile &Other) + { + if (!Other.bIsValid()) + return; + FilePath += ";" + Other.FilePath; + if (Other.Sections.size() > 0) + Sections.insert(Other.Sections.begin(), Other.Sections.end()); + bSuccessfulUpdate = true; + } + + static ConfigFile Import(const std::string &Configuration) + { + // takes a flattened INI configuration file as parameter and reads it into a ConfigFile class + return ConfigFile(Configuration); + } + + std::string Export() const + { + std::ostringstream oss; + oss << std::endl + << "# This is an exported config file originally from \"" << TCHAR_TO_UTF8(*FilePath) << "\"" << std::endl + << std::endl; + for (const auto &SectionData : Sections) + { + const std::string &SectionName = SectionData.first; + const IniSection &Section = SectionData.second; + oss << "[" << SectionName << "]" << std::endl; // The overarching section first + for (const auto &EntryData : Section.Entries) + { + const std::string &VariableName = EntryData.first; + const ParamString &Data = EntryData.second; + const std::string DataUTF = TCHAR_TO_UTF8(*Data.DataStr); // convert to UTF-8 format + const std::string DataStdStr = Data.bHasQuotes ? "\"" + DataUTF + "\"" : DataUTF; + oss << VariableName << "=" << DataStdStr << std::endl; + } + oss << std::endl; + } + return oss.str(); + } + + private: + bool ReadFile(bool bVerbose) + { + check(!FilePath.IsEmpty()); + if (bVerbose) + { + LOG("Reading config from %s", *FilePath); + } + std::ifstream MatchingFile(TCHAR_TO_ANSI(*FilePath), std::ios::in); + if (MatchingFile) + { + return Update(MatchingFile); + } + LOG_ERROR("Unable to open the config file \"%s\"", *FilePath); + return false; + } + + bool Update(std::istream &InputStream) // reload the internally tracked table of params + { + /// performs a single pass over the config stream to collect all variables into Params + std::string Line; + std::string Section = ""; + while (std::getline(InputStream, Line)) + { + if (InputStream.bad()) // IO error + return false; + // std::string stdKey = std::string(TCHAR_TO_UTF8(*Key)); + if (Line[0] == '#' || Line[0] == ';') // ignore comments + continue; + std::istringstream iss_Line(Line); + if (Line[0] == '[') // test section + { + std::getline(iss_Line, Section, ']'); + Section = Section.substr(1); // skip leading '[' + continue; + } + std::string Key; + if (std::getline(iss_Line, Key, '=')) // gets left side of '=' into FileKey + { + std::string Value; + if (std::getline(iss_Line, Value, '#')) // gets left side of '#' for comments + { + // ensure there is a section (create one if necesary) to store this key:value pair + if (Sections.find(Section) == Sections.end()) + { + Sections.insert({Section, IniSection(Section)}); + } + check(Sections.find(Section) != Sections.end()); + auto &CorrespondingSection = Sections.find(Section)->second; + CorrespondingSection.Entries.insert({Key, ParamString(Value)}); + } + } + } + return true; + } + + private: + struct ParamString + { + ParamString() = default; + ParamString(const std::string &Value) + { + DataStr = FString(Value.c_str()).TrimStartAndEnd().TrimQuotes(&bHasQuotes); + } + + FString DataStr = ""; // string representation of the data to parse into primitives + + template inline T DecipherToType() const + { + // supports FVector, FVector2D, FLinearColor, FQuat, and FRotator, + // basically any UE4 type that has a ::InitFromString method + T Ret; + if (Ret.InitFromString(DataStr) == false) + { + LOG_ERROR("Unable to decipher \"%s\" to a type", *DataStr); + } + return Ret; + } + + template <> inline bool DecipherToType() const + { + return DataStr.ToBool(); + } + + template <> inline int DecipherToType() const + { + return FCString::Atoi(*DataStr); + } + + template <> inline float DecipherToType() const + { + return FCString::Atof(*DataStr); + } + + template <> inline FString DecipherToType() const + { + return DataStr; + } + + template <> inline FName DecipherToType() const + { + return FName(*DataStr); + } + bool bHasQuotes = false; + }; + + struct IniSection + { + IniSection(const std::string &SectionName) : SectionHeader(SectionName) + { + } + + std::string SectionHeader; // typically what is contained in [Sections] + std::unordered_map Entries; // everything else + }; + + private: + // construct a ConfigFile by passing in the entire contents of the config file (rather than the path to read) + ConfigFile(const std::string &ConfigurationContents) : FilePath("") + { + std::istringstream iss(ConfigurationContents); + bSuccessfulUpdate = Update(iss); + } + + // using std::string variant for internal use (FString for user-facing) + template bool GetValue(const std::string &SectionName, const std::string &VariableName, T &Value) const + { + ParamString Param; + bool bFound = Find(SectionName, VariableName, Param); + if (bFound) + Value = Param.DecipherToType(); + return bFound; + } + + bool Find(const std::string &SectionName, const std::string &VariableName, ParamString &Out) const + { + auto SectionIt = Sections.find(SectionName); + if (SectionIt == Sections.end()) + { + LOG_ERROR("No section in config file matches \"%s\"", *FString(SectionName.c_str())); + return false; + } + const IniSection &Section = SectionIt->second; + auto EntryIt = Section.Entries.find(VariableName); + if (EntryIt == Section.Entries.end()) + { + LOG_ERROR("No entry for \"%s\" in [%s] section found!", *FString(VariableName.c_str()), + *FString(SectionName.c_str())); + return false; + } + Out = EntryIt->second; + + // enable this for debug purposes + // LOG("Read [%s]\"%s\" -> %s", *FString(SectionName.c_str()), *FString(VariableName.c_str()), *Out.DataStr); + return true; // found successfully! + } + + private: + FString FilePath; // const except for overwrite + bool bSuccessfulUpdate = false; + std::unordered_map Sections; +}; + +static ConfigFile GeneralParams(FPaths::Combine(CarlaUE4Path, TEXT("Config/DReyeVRConfig.ini"))); diff --git a/DReyeVR/DReyeVRFactory.cpp b/DReyeVR/DReyeVRFactory.cpp index 6c58ebe..e0da4de 100644 --- a/DReyeVR/DReyeVRFactory.cpp +++ b/DReyeVR/DReyeVRFactory.cpp @@ -1,183 +1,183 @@ -#include "DReyeVRFactory.h" -#include "Carla.h" // to avoid linker errors -#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" // UActorBlueprintFunctionLibrary -#include "Carla/Actor/VehicleParameters.h" // FVehicleParameters -#include "Carla/Game/CarlaEpisode.h" // UCarlaEpisode -#include "DReyeVRGameMode.h" // ADReyeVRGameMode -#include "DReyeVRUtils.h" // DReyeVRCategory -#include "EgoSensor.h" // AEgoSensor -#include "EgoVehicle.h" // AEgoVehicle - -ADReyeVRFactory::ADReyeVRFactory(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) -{ - for (const std::string &NameStdStr : VehicleTypes) - { - const FString Name = FString(NameStdStr.c_str()); - ConfigFile VehicleParams(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles"), Name + ".ini")); - FString BP_Path; - // make sure we can load the BP path and its nonempty (else construct a C++ EgoVehicle class) - if (VehicleParams.bIsValid() && VehicleParams.Get("Blueprint", "Path", BP_Path) && !BP_Path.IsEmpty()) - { - ConstructorHelpers::FObjectFinder BlueprintObject(*UE4RefToClassPath(BP_Path)); - BP_Classes.Add(Name, BlueprintObject.Object); - } - else - { - LOG_WARN("Unable to load custom EgoVehicle \"%s\"", *Name); - } - } -} - -TArray ADReyeVRFactory::GetDefinitions() -{ - TArray Definitions; - - for (auto &BP_Class_pair : BP_Classes) - { - FActorDefinition Def; - FVehicleParameters Parameters; - Parameters.Model = BP_Class_pair.Key; // vehicle type - /// TODO: BP_Path?? - Parameters.ObjectType = BP_Class_pair.Key; - Parameters.Class = BP_Class_pair.Value; - /// TODO: manage number of wheels? (though carla's 2-wheeled are just secret 4-wheeled) - Parameters.NumberOfWheels = 4; - - ADReyeVRFactory::MakeVehicleDefinition(Parameters, Def); - Definitions.Add(Def); - } - - FActorDefinition EgoSensorDef; - { - const FString Id = "ego_sensor"; - ADReyeVRFactory::MakeSensorDefinition(Id, EgoSensorDef); - Definitions.Add(EgoSensorDef); - } - - return Definitions; -} - -// copied and modified from UActorBlueprintFunctionLibrary -FActorDefinition MakeGenericDefinition(const FString &Category, const FString &Type, const FString &Id) -{ - FActorDefinition Definition; - - TArray Tags = {Category.ToLower(), Type.ToLower(), Id.ToLower()}; - Definition.Id = FString::Join(Tags, TEXT(".")); - Definition.Tags = FString::Join(Tags, TEXT(",")); - return Definition; -} - -void ADReyeVRFactory::MakeVehicleDefinition(const FVehicleParameters &Parameters, FActorDefinition &Definition) -{ - // assign the ID/Tags with category (ex. "vehicle.tesla.model3" => "harplab.dreyevr.model3") - Definition = MakeGenericDefinition(DReyeVRCategory, TEXT("DReyeVR_Vehicle"), Parameters.Model); - Definition.Class = Parameters.Class; - - FActorAttribute ActorRole; - ActorRole.Id = "role_name"; - ActorRole.Type = EActorAttributeType::String; - ActorRole.Value = "hero"; - Definition.Attributes.Emplace(ActorRole); - - FActorAttribute ObjectType; - ObjectType.Id = "object_type"; - ObjectType.Type = EActorAttributeType::String; - ObjectType.Value = Parameters.ObjectType; - Definition.Attributes.Emplace(ObjectType); - - FActorAttribute NumberOfWheels; - NumberOfWheels.Id = "number_of_wheels"; - NumberOfWheels.Type = EActorAttributeType::Int; - NumberOfWheels.Value = FString::FromInt(Parameters.NumberOfWheels); - Definition.Attributes.Emplace(NumberOfWheels); - - FActorAttribute Generation; - Generation.Id = "generation"; - Generation.Type = EActorAttributeType::Int; - Generation.Value = FString::FromInt(Parameters.Generation); - Definition.Attributes.Emplace(Generation); -} - -void ADReyeVRFactory::MakeSensorDefinition(const FString &Id, FActorDefinition &Definition) -{ - Definition = MakeGenericDefinition(DReyeVRCategory, TEXT("DReyeVR_Sensor"), Id); - Definition.Class = AEgoSensor::StaticClass(); -} - -FActorSpawnResult ADReyeVRFactory::SpawnActor(const FTransform &SpawnAtTransform, - const FActorDescription &ActorDescription) -{ - auto *World = GetWorld(); - if (World == nullptr) - { - LOG_ERROR("cannot spawn \"%s\" into an empty world.", *ActorDescription.Id); - return {}; - } - - AActor *SpawnedActor = nullptr; - - FActorSpawnParameters SpawnParameters; - SpawnParameters.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; - - auto SpawnSingleton = [World, SpawnParameters](UClass *ActorClass, const FString &Id, const FTransform &SpawnAt, - const std::function &SpawnFn) -> AActor * { - // function to spawn a singleton: only one actor can exist in the world at once - ensure(World != nullptr); - AActor *SpawnedSingleton = nullptr; - TArray Found; - UGameplayStatics::GetAllActorsOfClass(World, ActorClass, Found); - if (Found.Num() == 0) - { - LOG("Spawning DReyeVR actor (\"%s\") at: %s", *Id, *SpawnAt.ToString()); - SpawnedSingleton = SpawnFn(); - } - else - { - LOG_WARN("Requested to spawn another DReyeVR actor (\"%s\") but one already exists in the world!", *Id); - ensure(Found.Num() == 1); // should only have one other that was previously spawned - SpawnedSingleton = Found[0]; - } - return SpawnedSingleton; - }; - - if (UClass::FindCommonBase(ActorDescription.Class, AEgoVehicle::StaticClass()) == - AEgoVehicle::StaticClass()) // is EgoVehicle or derived class - { - // see if this requested actor description is one of the available EgoVehicles - /// NOTE: multi-ego-vehicle is not officially supported by DReyeVR, but it could be an interesting extension - for (const auto &AvailableEgoVehicles : BP_Classes) - { - const FString &Name = AvailableEgoVehicles.Key; - if (ActorDescription.Id.ToLower().Contains(Name.ToLower())) // contains name - { - // check if an EgoVehicle already exists, if so, don't spawn another. - SpawnedActor = SpawnSingleton(ActorDescription.Class, ActorDescription.Id, SpawnAtTransform, [&]() { - auto *Class = AvailableEgoVehicles.Value; - return World->SpawnActor(Class, SpawnAtTransform, SpawnParameters); - }); - } - } - // update the GameMode's EgoVehicle in case it was spawned by someone else - auto *Game = Cast(UGameplayStatics::GetGameMode(World)); - if (Game != nullptr) - Game->SetEgoVehicle(Cast(SpawnedActor)); - } - else if (ActorDescription.Class == AEgoSensor::StaticClass()) - { - // there should only ever be one DReyeVR sensor in the world! - SpawnedActor = SpawnSingleton(ActorDescription.Class, ActorDescription.Id, SpawnAtTransform, [&]() { - return World->SpawnActor(ActorDescription.Class, SpawnAtTransform, SpawnParameters); - }); - } - else - { - LOG_ERROR("Unknown actor class in DReyeVR factory!"); - } - - if (SpawnedActor == nullptr) - { - LOG_WARN("Unable to spawn DReyeVR actor (\"%s\")", *ActorDescription.Id) - } - return FActorSpawnResult(SpawnedActor); -} +#include "DReyeVRFactory.h" +#include "Carla.h" // to avoid linker errors +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" // UActorBlueprintFunctionLibrary +#include "Carla/Actor/VehicleParameters.h" // FVehicleParameters +#include "Carla/Game/CarlaEpisode.h" // UCarlaEpisode +#include "DReyeVRGameMode.h" // ADReyeVRGameMode +#include "DReyeVRUtils.h" // DReyeVRCategory +#include "EgoSensor.h" // AEgoSensor +#include "EgoVehicle.h" // AEgoVehicle + +ADReyeVRFactory::ADReyeVRFactory(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +{ + for (const std::string &NameStdStr : VehicleTypes) + { + const FString Name = FString(NameStdStr.c_str()); + ConfigFile VehicleParams(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles"), Name + ".ini")); + FString BP_Path; + // make sure we can load the BP path and its nonempty (else construct a C++ EgoVehicle class) + if (VehicleParams.bIsValid() && VehicleParams.Get("Blueprint", "Path", BP_Path) && !BP_Path.IsEmpty()) + { + ConstructorHelpers::FObjectFinder BlueprintObject(*UE4RefToClassPath(BP_Path)); + BP_Classes.Add(Name, BlueprintObject.Object); + } + else + { + LOG_WARN("Unable to load custom EgoVehicle \"%s\"", *Name); + } + } +} + +TArray ADReyeVRFactory::GetDefinitions() +{ + TArray Definitions; + + for (auto &BP_Class_pair : BP_Classes) + { + FActorDefinition Def; + FVehicleParameters Parameters; + Parameters.Model = BP_Class_pair.Key; // vehicle type + /// TODO: BP_Path?? + Parameters.ObjectType = BP_Class_pair.Key; + Parameters.Class = BP_Class_pair.Value; + /// TODO: manage number of wheels? (though carla's 2-wheeled are just secret 4-wheeled) + Parameters.NumberOfWheels = 4; + + ADReyeVRFactory::MakeVehicleDefinition(Parameters, Def); + Definitions.Add(Def); + } + + FActorDefinition EgoSensorDef; + { + const FString Id = "ego_sensor"; + ADReyeVRFactory::MakeSensorDefinition(Id, EgoSensorDef); + Definitions.Add(EgoSensorDef); + } + + return Definitions; +} + +// copied and modified from UActorBlueprintFunctionLibrary +FActorDefinition MakeGenericDefinition(const FString &Category, const FString &Type, const FString &Id) +{ + FActorDefinition Definition; + + TArray Tags = {Category.ToLower(), Type.ToLower(), Id.ToLower()}; + Definition.Id = FString::Join(Tags, TEXT(".")); + Definition.Tags = FString::Join(Tags, TEXT(",")); + return Definition; +} + +void ADReyeVRFactory::MakeVehicleDefinition(const FVehicleParameters &Parameters, FActorDefinition &Definition) +{ + // assign the ID/Tags with category (ex. "vehicle.tesla.model3" => "harplab.dreyevr.model3") + Definition = MakeGenericDefinition(DReyeVRCategory, TEXT("DReyeVR_Vehicle"), Parameters.Model); + Definition.Class = Parameters.Class; + + FActorAttribute ActorRole; + ActorRole.Id = "role_name"; + ActorRole.Type = EActorAttributeType::String; + ActorRole.Value = "hero"; + Definition.Attributes.Emplace(ActorRole); + + FActorAttribute ObjectType; + ObjectType.Id = "object_type"; + ObjectType.Type = EActorAttributeType::String; + ObjectType.Value = Parameters.ObjectType; + Definition.Attributes.Emplace(ObjectType); + + FActorAttribute NumberOfWheels; + NumberOfWheels.Id = "number_of_wheels"; + NumberOfWheels.Type = EActorAttributeType::Int; + NumberOfWheels.Value = FString::FromInt(Parameters.NumberOfWheels); + Definition.Attributes.Emplace(NumberOfWheels); + + FActorAttribute Generation; + Generation.Id = "generation"; + Generation.Type = EActorAttributeType::Int; + Generation.Value = FString::FromInt(Parameters.Generation); + Definition.Attributes.Emplace(Generation); +} + +void ADReyeVRFactory::MakeSensorDefinition(const FString &Id, FActorDefinition &Definition) +{ + Definition = MakeGenericDefinition(DReyeVRCategory, TEXT("DReyeVR_Sensor"), Id); + Definition.Class = AEgoSensor::StaticClass(); +} + +FActorSpawnResult ADReyeVRFactory::SpawnActor(const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription) +{ + auto *World = GetWorld(); + if (World == nullptr) + { + LOG_ERROR("cannot spawn \"%s\" into an empty world.", *ActorDescription.Id); + return {}; + } + + AActor *SpawnedActor = nullptr; + + FActorSpawnParameters SpawnParameters; + SpawnParameters.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + + auto SpawnSingleton = [World, SpawnParameters](UClass *ActorClass, const FString &Id, const FTransform &SpawnAt, + const std::function &SpawnFn) -> AActor * { + // function to spawn a singleton: only one actor can exist in the world at once + ensure(World != nullptr); + AActor *SpawnedSingleton = nullptr; + TArray Found; + UGameplayStatics::GetAllActorsOfClass(World, ActorClass, Found); + if (Found.Num() == 0) + { + LOG("Spawning DReyeVR actor (\"%s\") at: %s", *Id, *SpawnAt.ToString()); + SpawnedSingleton = SpawnFn(); + } + else + { + LOG_WARN("Requested to spawn another DReyeVR actor (\"%s\") but one already exists in the world!", *Id); + ensure(Found.Num() == 1); // should only have one other that was previously spawned + SpawnedSingleton = Found[0]; + } + return SpawnedSingleton; + }; + + if (UClass::FindCommonBase(ActorDescription.Class, AEgoVehicle::StaticClass()) == + AEgoVehicle::StaticClass()) // is EgoVehicle or derived class + { + // see if this requested actor description is one of the available EgoVehicles + /// NOTE: multi-ego-vehicle is not officially supported by DReyeVR, but it could be an interesting extension + for (const auto &AvailableEgoVehicles : BP_Classes) + { + const FString &Name = AvailableEgoVehicles.Key; + if (ActorDescription.Id.ToLower().Contains(Name.ToLower())) // contains name + { + // check if an EgoVehicle already exists, if so, don't spawn another. + SpawnedActor = SpawnSingleton(ActorDescription.Class, ActorDescription.Id, SpawnAtTransform, [&]() { + auto *Class = AvailableEgoVehicles.Value; + return World->SpawnActor(Class, SpawnAtTransform, SpawnParameters); + }); + } + } + // update the GameMode's EgoVehicle in case it was spawned by someone else + auto *Game = Cast(UGameplayStatics::GetGameMode(World)); + if (Game != nullptr) + Game->SetEgoVehicle(Cast(SpawnedActor)); + } + else if (ActorDescription.Class == AEgoSensor::StaticClass()) + { + // there should only ever be one DReyeVR sensor in the world! + SpawnedActor = SpawnSingleton(ActorDescription.Class, ActorDescription.Id, SpawnAtTransform, [&]() { + return World->SpawnActor(ActorDescription.Class, SpawnAtTransform, SpawnParameters); + }); + } + else + { + LOG_ERROR("Unknown actor class in DReyeVR factory!"); + } + + if (SpawnedActor == nullptr) + { + LOG_WARN("Unable to spawn DReyeVR actor (\"%s\")", *ActorDescription.Id) + } + return FActorSpawnResult(SpawnedActor); +} diff --git a/DReyeVR/DReyeVRFactory.h b/DReyeVR/DReyeVRFactory.h index 554c0a8..813432f 100644 --- a/DReyeVR/DReyeVRFactory.h +++ b/DReyeVR/DReyeVRFactory.h @@ -1,40 +1,40 @@ -#pragma once - -#include "Carla/Actor/ActorSpawnResult.h" -#include "Carla/Actor/CarlaActorFactory.h" -#include "Carla/Actor/VehicleParameters.h" - -#include -#include - -#include "DReyeVRFactory.generated.h" - -/// Factory in charge of spawning DReyeVR actors. -UCLASS() -class ADReyeVRFactory : public ACarlaActorFactory -{ - GENERATED_BODY() - public: - ADReyeVRFactory(const FObjectInitializer &ObjectInitializer); - - TArray GetDefinitions() final; - - FActorSpawnResult SpawnActor(const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription) final; - - private: - void MakeVehicleDefinition(const FVehicleParameters &Parameters, FActorDefinition &Definition); - void MakeSensorDefinition(const FString &Id, FActorDefinition &Definition); - - // place the names of all your new custom EgoVehicle types here: - /// IMPORTANT: make sure these match the ConfigFile AND Blueprint!! - // We expect Config/EgoVehicle/XYZ.ini and Content/DReyeVR/EgoVehicles/XYZ/BP_XYZ.uasset - const std::vector VehicleTypes = { - "TeslaM3", // Tesla Model 3 (Default) - "Mustang66", // Mustang66 - "Jeep", // JeepWranglerRubicon - "Vespa" // Vespa (2WheeledVehicles) - // add more here - }; - - TMap BP_Classes; +#pragma once + +#include "Carla/Actor/ActorSpawnResult.h" +#include "Carla/Actor/CarlaActorFactory.h" +#include "Carla/Actor/VehicleParameters.h" + +#include +#include + +#include "DReyeVRFactory.generated.h" + +/// Factory in charge of spawning DReyeVR actors. +UCLASS() +class ADReyeVRFactory : public ACarlaActorFactory +{ + GENERATED_BODY() + public: + ADReyeVRFactory(const FObjectInitializer &ObjectInitializer); + + TArray GetDefinitions() final; + + FActorSpawnResult SpawnActor(const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription) final; + + private: + void MakeVehicleDefinition(const FVehicleParameters &Parameters, FActorDefinition &Definition); + void MakeSensorDefinition(const FString &Id, FActorDefinition &Definition); + + // place the names of all your new custom EgoVehicle types here: + /// IMPORTANT: make sure these match the ConfigFile AND Blueprint!! + // We expect Config/EgoVehicle/XYZ.ini and Content/DReyeVR/EgoVehicles/XYZ/BP_XYZ.uasset + const std::vector VehicleTypes = { + "TeslaM3", // Tesla Model 3 (Default) + "Mustang66", // Mustang66 + "Jeep", // JeepWranglerRubicon + "Vespa" // Vespa (2WheeledVehicles) + // add more here + }; + + TMap BP_Classes; }; \ No newline at end of file diff --git a/DReyeVR/DReyeVRGameMode.cpp b/DReyeVR/DReyeVRGameMode.cpp index 5406af8..3a4e3d5 100644 --- a/DReyeVR/DReyeVRGameMode.cpp +++ b/DReyeVR/DReyeVRGameMode.cpp @@ -1,628 +1,628 @@ -#include "DReyeVRGameMode.h" -#include "Carla/AI/AIControllerFactory.h" // AAIControllerFactory -#include "Carla/Actor/StaticMeshFactory.h" // AStaticMeshFactory -#include "Carla/Game/CarlaStatics.h" // GetReplayer, GetEpisode -#include "Carla/Recorder/CarlaReplayer.h" // ACarlaReplayer -#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor -#include "Carla/Sensor/SensorFactory.h" // ASensorFactory -#include "Carla/Trigger/TriggerFactory.h" // TriggerFactory -#include "Carla/Vehicle/CarlaWheeledVehicle.h" // ACarlaWheeledVehicle -#include "Carla/Weather/Weather.h" // AWeather -#include "Components/AudioComponent.h" // UAudioComponent -#include "DReyeVRFactory.h" // ADReyeVRFactory -#include "DReyeVRPawn.h" // ADReyeVRPawn -#include "DReyeVRUtils.h" // FindDefnInRegistry -#include "EgoVehicle.h" // AEgoVehicle -#include "FlatHUD.h" // ADReyeVRHUD -#include "HeadMountedDisplayFunctionLibrary.h" // IsHeadMountedDisplayAvailable -#include "Kismet/GameplayStatics.h" // GetPlayerController -#include "UObject/UObjectIterator.h" // TObjectInterator - -ADReyeVRGameMode::ADReyeVRGameMode(FObjectInitializer const &FO) : Super(FO) -{ - // initialize stuff here - PrimaryActorTick.bCanEverTick = false; - PrimaryActorTick.bStartWithTickEnabled = false; - - // initialize default classes - this->HUDClass = ADReyeVRHUD::StaticClass(); - // find object UClass rather than UBlueprint - // https://forums.unrealengine.com/t/cdo-constructor-failed-to-find-thirdperson-c-template-mannequin-animbp/99003 - static ConstructorHelpers::FObjectFinder WeatherBP( - TEXT("/Game/Carla/Blueprints/Weather/BP_Weather.BP_Weather_C")); - this->WeatherClass = WeatherBP.Object; - - // initialize actor factories - // https://forums.unrealengine.com/t/what-is-the-right-syntax-of-fclassfinder-and-how-could-i-generaly-use-it-to-find-a-specific-blueprint/363884 - static ConstructorHelpers::FClassFinder VehicleFactoryBP( - TEXT("Blueprint'/Game/Carla/Blueprints/Vehicles/VehicleFactory'")); - static ConstructorHelpers::FClassFinder WalkerFactoryBP( - TEXT("Blueprint'/Game/Carla/Blueprints/Walkers/WalkerFactory'")); - static ConstructorHelpers::FClassFinder PropFactoryBP( - TEXT("Blueprint'/Game/Carla/Blueprints/Props/PropFactory'")); - - this->ActorFactories = TSet>{ - VehicleFactoryBP.Class, - ASensorFactory::StaticClass(), - WalkerFactoryBP.Class, - PropFactoryBP.Class, - ATriggerFactory::StaticClass(), - AAIControllerFactory::StaticClass(), - AStaticMeshFactory::StaticClass(), - ADReyeVRFactory::StaticClass(), // this is what registers the DReyeVR actors - }; - - // read config variables - EgoVolumePercent = GeneralParams.Get("Sound", "EgoVolumePercent"); - NonEgoVolumePercent = GeneralParams.Get("Sound", "NonEgoVolumePercent"); - AmbientVolumePercent = GeneralParams.Get("Sound", "AmbientVolumePercent"); - bDoSpawnEgoVehicleTransform = GeneralParams.Get("Game", "DoSpawnEgoVehicleTransform"); - SpawnEgoVehicleTransform = GeneralParams.Get("Game", "SpawnEgoVehicleTransform"); - - // Recorder/replayer - bUseCarlaSpectator = GeneralParams.Get("Replayer", "UseCarlaSpectator"); - bool bEnableReplayInterpolation = GeneralParams.Get("Replayer", "ReplayInterpolation"); - bReplaySync = !bEnableReplayInterpolation; // synchronous => no interpolation! -} - -void ADReyeVRGameMode::BeginPlay() -{ - Super::BeginPlay(); - - // Initialize player - GetPlayer(); - - // Can we tick? - SetActorTickEnabled(false); // make sure we do not tick ourselves - - // set all the volumes (ego, non-ego, ambient/world) - SetVolume(); - - // start input mapping - SetupPlayerInputComponent(); - - // spawn the DReyeVR pawn and possess it (first) - SetupDReyeVRPawn(); - ensure(GetPawn() != nullptr); - - // Initialize the DReyeVR EgoVehicle and Sensor (second) - if (GeneralParams.Get("Game", "AutomaticallySpawnEgo")) - { - SetupEgoVehicle(); - ensure(GetEgoVehicle() != nullptr); - } - - // Initialize DReyeVR spectator (third) - SetupSpectator(); - ensure(GetSpectator() != nullptr); -} - -void ADReyeVRGameMode::SetupDReyeVRPawn() -{ - if (DReyeVR_Pawn.IsValid()) - { - LOG("Not spawning new DReyeVR pawn"); - return; - } - FActorSpawnParameters SpawnParams; - SpawnParams.Owner = this; - SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; - DReyeVR_Pawn = GetWorld()->SpawnActor(FVector::ZeroVector, FRotator::ZeroRotator, SpawnParams); - /// NOTE: the pawn is automatically possessed by player0 - // as the constructor has the AutoPossessPlayer != disabled - // if you want to manually possess then you can do Player->Possess(DReyeVR_Pawn); - if (!DReyeVR_Pawn.IsValid()) - { - LOG_ERROR("Unable to spawn DReyeVR pawn!") - } - else - { - DReyeVR_Pawn.Get()->BeginPlayer(GetPlayer()); - LOG("Successfully spawned DReyeVR pawn"); - } -} - -void ADReyeVRGameMode::SetEgoVehicle(AEgoVehicle *Ego) -{ - EgoVehiclePtr.Reset(); - EgoVehiclePtr = Ego; - check(EgoVehiclePtr.IsValid()); - ensure(GetPawn() != nullptr); // also respawn DReyeVR pawn if needed - // assign the (possibly new) EgoVehicle to the pawn - if (GetPawn() != nullptr) - { - DReyeVR_Pawn.Get()->BeginEgoVehicle(EgoVehiclePtr.Get(), GetWorld()); - } -} - -bool ADReyeVRGameMode::SetupEgoVehicle() -{ - if (EgoVehiclePtr.IsValid()) - { - LOG("Not spawning new EgoVehicle"); - return true; - } - - TArray FoundActors; - UGameplayStatics::GetAllActorsOfClass(GetWorld(), AEgoVehicle::StaticClass(), FoundActors); - if (FoundActors.Num() > 0) - { - for (AActor *Vehicle : FoundActors) - { - LOG("Found EgoVehicle in world: %s", *(Vehicle->GetName())); - EgoVehiclePtr = CastChecked(Vehicle); - /// TODO: handle multiple ego-vehcles? (we should only ever have one!) - break; - } - } - else - { - LOG("Did not find EgoVehicle in map... spawning..."); - // use the provided transform if requested, else generate a spawn point - FTransform SpawnPt = bDoSpawnEgoVehicleTransform ? SpawnEgoVehicleTransform : GetSpawnPoint(); - SpawnEgoVehicle(SpawnPt); // constructs and assigns EgoVehiclePtr - } - - // finalize the EgoVehicle by installing the DReyeVR_Pawn to control it - return (EgoVehiclePtr.IsValid()); -} - -void ADReyeVRGameMode::SetupSpectator() -{ - if (SpectatorPtr.IsValid()) - { - LOG("Not spawning new Spectator"); - return; - } - - // always disable the Carla spectator from DReyeVR use - UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); - APawn *CarlaSpectator = nullptr; - if (Episode != nullptr) - { - CarlaSpectator = Episode->GetSpectatorPawn(); - if (CarlaSpectator != nullptr) - CarlaSpectator->SetActorHiddenInGame(true); - } - - // whether or not to use Carla spectator - if (bUseCarlaSpectator) - { - if (CarlaSpectator != nullptr) - SpectatorPtr = CarlaSpectator; - else if (GetPlayer() != nullptr) - SpectatorPtr = Player.Get()->GetPawn(); - } - - // spawn the Spectator pawn - { - LOG("Spawning DReyeVR Spectator Pawn in the world"); - FVector SpawnLocn; - FRotator SpawnRotn; - if (EgoVehiclePtr.IsValid()) - { - SpawnLocn = EgoVehiclePtr.Get()->GetCameraPosn(); - SpawnRotn = EgoVehiclePtr.Get()->GetCameraRot(); - } - else - { - // spawn above the vehicle recommended spawn pt - FTransform RecommendedPt = GetSpawnPoint(); - SpawnLocn = RecommendedPt.GetLocation(); - SpawnLocn.Z += 10.f * 100.f; // up in the air 10m ish - SpawnRotn = RecommendedPt.Rotator(); - } - // create new spectator pawn - FActorSpawnParameters SpawnParams; - SpawnParams.Owner = this; - SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; - SpawnParams.ObjectFlags |= RF_Transient; - SpectatorPtr = GetWorld()->SpawnActor(ASpectatorPawn::StaticClass(), // spectator - SpawnLocn, SpawnRotn, SpawnParams); - } - - if (SpectatorPtr.IsValid()) - { - SpectatorPtr.Get()->SetActorHiddenInGame(true); // make spectator invisible - SpectatorPtr.Get()->GetRootComponent()->DestroyPhysicsState(); // no physics (just no-clip) - SpectatorPtr.Get()->SetActorEnableCollision(false); // no collisions - LOG("Successfully initiated spectator actor"); - } - - // automatically possess the spectator ptr if no ego vehicle present! - if (!EgoVehiclePtr.IsValid()) - { - PossessSpectator(); - } -} - -APawn *ADReyeVRGameMode::GetSpectator() -{ - return SafePtrGet("Spectator", SpectatorPtr, [&](void) { SetupSpectator(); }); -} - -AEgoVehicle *ADReyeVRGameMode::GetEgoVehicle() -{ - return SafePtrGet("EgoVehicle", EgoVehiclePtr, [&](void) { SetupEgoVehicle(); }); -} - -APlayerController *ADReyeVRGameMode::GetPlayer() -{ - return SafePtrGet("Player", Player, - [&](void) { Player = GetWorld()->GetFirstPlayerController(); }); -} - -ADReyeVRPawn *ADReyeVRGameMode::GetPawn() -{ - return SafePtrGet("Pawn", DReyeVR_Pawn, [&](void) { SetupDReyeVRPawn(); }); -} - -void ADReyeVRGameMode::BeginDestroy() -{ - Super::BeginDestroy(); - - if (DReyeVR_Pawn.IsValid()) - DReyeVR_Pawn.Get()->Destroy(); - DReyeVR_Pawn = nullptr; // release object and assign to null - - if (EgoVehiclePtr.IsValid()) - EgoVehiclePtr.Get()->Destroy(); - EgoVehiclePtr = nullptr; - - if (SpectatorPtr.IsValid()) - SpectatorPtr.Get()->Destroy(); - SpectatorPtr = nullptr; - - LOG("DReyeVRGameMode has been destroyed"); -} - -void ADReyeVRGameMode::Tick(float DeltaSeconds) -{ - Super::Tick(DeltaSeconds); - /// TODO: clean up replay init - if (!bRecorderInitiated) // can't do this in constructor - { - // Initialize recorder/replayer - SetupReplayer(); // once this is successfully run, it no longer gets executed - } - - DrawBBoxes(); -} - -void ADReyeVRGameMode::SetupPlayerInputComponent() -{ - if (GetPlayer() == nullptr) - return; - check(Player.IsValid()); - InputComponent = NewObject(this); - InputComponent->RegisterComponent(); - // set up gameplay key bindings - check(InputComponent); - Player.Get()->PushInputComponent(InputComponent); // enable this InputComponent with the PlayerController - // InputComponent->BindAction("ToggleCamera", IE_Pressed, this, &ADReyeVRGameMode::ToggleSpectator); - InputComponent->BindAction("PlayPause_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayPlayPause); - InputComponent->BindAction("FastForward_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayFastForward); - InputComponent->BindAction("Rewind_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayRewind); - InputComponent->BindAction("Restart_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayRestart); - InputComponent->BindAction("Incr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplaySpeedUp); - InputComponent->BindAction("Decr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplaySlowDown); - // Driver Handoff examples - InputComponent->BindAction("EgoVehicle_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::PossessEgoVehicle); - InputComponent->BindAction("Spectator_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::PossessSpectator); - InputComponent->BindAction("AI_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::HandoffDriverToAI); -} - -void ADReyeVRGameMode::PossessEgoVehicle() -{ - if (GetEgoVehicle() == nullptr || GetPawn() == nullptr || GetPlayer() == nullptr) - return; - - check(EgoVehiclePtr.IsValid()); - check(DReyeVR_Pawn.IsValid()); - check(Player.IsValid()); - EgoVehiclePtr.Get()->SetAutopilot(false); - - // check if already possessing EgoVehicle (DReyeVRPawn) - if (Player.Get()->GetPawn() == DReyeVR_Pawn.Get()) - { - LOG("Already possessing EgoVehicle"); - return; - } - - LOG("Possessing DReyeVR EgoVehicle"); - Player.Get()->Possess(DReyeVR_Pawn.Get()); - DReyeVR_Pawn.Get()->BeginEgoVehicle(EgoVehiclePtr.Get(), GetWorld()); -} - -void ADReyeVRGameMode::PossessSpectator() -{ - if (GetSpectator() == nullptr || GetPlayer() == nullptr) - return; - - check(SpectatorPtr.IsValid()); - check(Player.IsValid()); - - // check if already possessing spectator - if (Player.Get()->GetPawn() == SpectatorPtr.Get()) - { - LOG("Already possessing Spectator"); - return; - } - - if (EgoVehiclePtr.IsValid()) - { - // spawn from EgoVehicle head position - const FVector &EgoLocn = EgoVehiclePtr.Get()->GetCameraPosn(); - const FRotator &EgoRotn = EgoVehiclePtr.Get()->GetCameraRot(); - SpectatorPtr.Get()->SetActorLocationAndRotation(EgoLocn, EgoRotn); - } - // repossess the ego vehicle - Player.Get()->Possess(SpectatorPtr.Get()); - LOG("Possessing spectator player"); -} - -void ADReyeVRGameMode::HandoffDriverToAI() -{ - if (GetEgoVehicle() == nullptr) - return; - - check(EgoVehiclePtr.IsValid()); - - { // check if autopilot already enabled - if (EgoVehiclePtr.Get()->GetAutopilotStatus() == true) - { - LOG("EgoVehicle autopilot already on"); - return; - } - } - EgoVehiclePtr.Get()->SetAutopilot(true); - LOG("Enabling EgoVehicle Autopilot"); -} - -void ADReyeVRGameMode::ReplayPlayPause() -{ - auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); - if (Replayer != nullptr && Replayer->IsEnabled()) - { - LOG("Toggle Replayer Play-Pause"); - Replayer->PlayPause(); - } -} - -void ADReyeVRGameMode::ReplayFastForward() -{ - auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); - if (Replayer != nullptr && Replayer->IsEnabled()) - { - LOG("Advance replay by +1.0s"); - Replayer->Advance(1.0); - } -} - -void ADReyeVRGameMode::ReplayRewind() -{ - auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); - if (Replayer != nullptr && Replayer->IsEnabled()) - { - LOG("Advance replay by -1.0s"); - Replayer->Advance(-1.0); - } -} - -void ADReyeVRGameMode::ReplayRestart() -{ - auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); - if (Replayer != nullptr && Replayer->IsEnabled()) - { - LOG("Restarting recording replay..."); - Replayer->Restart(); - } -} - -void ADReyeVRGameMode::ChangeTimestep(UWorld *World, double AmntChangeSeconds) -{ - if (bReplaySync) - { - LOG("Changing timestep of replay during a synchronous replay is not supported. Enable ReplayInterpolation to " - "achieve this.") - return; - } - ensure(World != nullptr); - auto *Replayer = UCarlaStatics::GetReplayer(World); - if (Replayer != nullptr && Replayer->IsEnabled()) - { - double NewFactor = ReplayTimeFactor + AmntChangeSeconds; - if (AmntChangeSeconds > 0) - { - if (NewFactor < ReplayTimeFactorMax) - { - LOG("Increase replay time factor: %.3fx -> %.3fx", ReplayTimeFactor, NewFactor); - Replayer->SetTimeFactor(NewFactor); - } - else - { - LOG("Unable to increase replay time factor (%.3f) beyond %.3fx", ReplayTimeFactor, ReplayTimeFactorMax); - Replayer->SetTimeFactor(ReplayTimeFactorMax); - } - } - else - { - if (NewFactor > ReplayTimeFactorMin) - { - LOG("Decrease replay time factor: %.3fx -> %.3fx", ReplayTimeFactor, NewFactor); - Replayer->SetTimeFactor(NewFactor); - } - else - { - LOG("Unable to decrease replay time factor (%.3f) below %.3fx", ReplayTimeFactor, ReplayTimeFactorMin); - Replayer->SetTimeFactor(ReplayTimeFactorMin); - } - } - ReplayTimeFactor = FMath::Clamp(NewFactor, ReplayTimeFactorMin, ReplayTimeFactorMax); - } -} - -void ADReyeVRGameMode::ReplaySpeedUp() -{ - ChangeTimestep(GetWorld(), AmntPlaybackIncr); -} - -void ADReyeVRGameMode::ReplaySlowDown() -{ - ChangeTimestep(GetWorld(), -AmntPlaybackIncr); -} - -void ADReyeVRGameMode::SetupReplayer() -{ - auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); - if (Replayer != nullptr) - { - Replayer->SetSyncMode(bReplaySync); - if (bReplaySync) - { - LOG("Replay operating in frame-wise (1:1) synchronous mode (no replay interpolation)"); - } - bRecorderInitiated = true; - } -} - -void ADReyeVRGameMode::DrawBBoxes() -{ -#if 0 - TArray FoundActors; - if (GetWorld() != nullptr) - { - UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); - } - for (AActor *A : FoundActors) - { - std::string name = TCHAR_TO_UTF8(*A->GetName()); - if (A->GetName().Contains("DReyeVR")) - continue; // skip drawing a bbox over the EgoVehicle - if (BBoxes.find(name) == BBoxes.end()) - { - BBoxes[name] = ADReyeVRCustomActor::CreateNew(SM_CUBE, MAT_TRANSLUCENT, GetWorld(), "BBox" + A->GetName()); - } - const float DistThresh = 20.f; // meters before nearby bounding boxes become red - ADReyeVRCustomActor *BBox = BBoxes[name]; - ensure(BBox != nullptr); - if (BBox != nullptr) - { - BBox->Activate(); - BBox->MaterialParams.Opacity = 0.1f; - FLinearColor Col = FLinearColor::Green; - if (FVector::Distance(GetEgoVehicle()->GetActorLocation(), A->GetActorLocation()) < DistThresh * 100.f) - { - Col = FLinearColor::Red; - } - BBox->MaterialParams.BaseColor = Col; - BBox->MaterialParams.Emissive = 0.1 * Col; - - FVector Origin; - FVector BoxExtent; - A->GetActorBounds(true, Origin, BoxExtent, false); - // LOG("Origin: %s Extent %s"), *Origin.ToString(), *BoxExtent.ToString()); - // divide by 100 to get from cm to m, multiply by 2 bc the cube is scaled in both X and Y - BBox->SetActorScale3D(2 * BoxExtent / 100.f); - BBox->SetActorLocation(Origin); - // extent already covers the rotation aspect since the bbox is dynamic and axis aligned - // BBox->SetActorRotation(A->GetActorRotation()); - } - } -#endif -} - -void ADReyeVRGameMode::ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per) -{ - // first spawn the actor if not currently active - const std::string ActorName = TCHAR_TO_UTF8(*RecorderData.Name); - ADReyeVRCustomActor *A = nullptr; - if (ADReyeVRCustomActor::ActiveCustomActors.find(ActorName) == ADReyeVRCustomActor::ActiveCustomActors.end()) - { - /// TODO: also track KnownNumMaterials? - A = ADReyeVRCustomActor::CreateNew(RecorderData.MeshPath, RecorderData.MaterialParams.MaterialPath, GetWorld(), - RecorderData.Name); - } - else - { - A = ADReyeVRCustomActor::ActiveCustomActors[ActorName]; - } - // ensure the actor is currently active (spawned) - // now that we know this actor exists, update its internals - if (A != nullptr) - { - A->SetInternals(RecorderData); - A->Activate(); - A->Tick(Per); // update locations immediately - } -} - -void ADReyeVRGameMode::SetVolume() -{ - // update the non-ego volume percent - ACarlaWheeledVehicle::Volume = NonEgoVolumePercent / 100.f; - - // for all in-world audio components such as ambient birdsong, fountain splashing, smoke, etc. - for (TObjectIterator Itr; Itr; ++Itr) - { - if (Itr->GetWorld() != GetWorld()) // World Check - { - continue; - } - Itr->SetVolumeMultiplier(AmbientVolumePercent / 100.f); - } - - // for all in-world vehicles (including the EgoVehicle) manually set their volumes - TArray FoundActors; - UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); - for (AActor *A : FoundActors) - { - ACarlaWheeledVehicle *Vehicle = Cast(A); - if (Vehicle != nullptr) - { - float NewVolume = ACarlaWheeledVehicle::Volume; // Non ego volume - if (Vehicle->IsA(AEgoVehicle::StaticClass())) // dynamic cast, requires -frrti - NewVolume = EgoVolumePercent / 100.f; - Vehicle->SetVolume(NewVolume); - } - } -} - -void ADReyeVRGameMode::SpawnEgoVehicle(const FTransform &SpawnPt) -{ - UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); - check(Episode != nullptr); - FActorDefinition EgoVehicleDefn = FindEgoVehicleDefinition(Episode); - FActorDescription DReyeVRDescr; - { // create a Description from the Definition to spawn the actor - DReyeVRDescr.UId = EgoVehicleDefn.UId; - DReyeVRDescr.Id = EgoVehicleDefn.Id; - DReyeVRDescr.Class = EgoVehicleDefn.Class; - // add all the attributes from the definition to the description - for (FActorAttribute A : EgoVehicleDefn.Attributes) - { - DReyeVRDescr.Variations.Add(A.Id, std::move(A)); - } - } - // calls Episode::SpawnActor => SpawnActorWithInfo => ActorDispatcher->SpawnActor => SpawnFunctions[UId] - EgoVehiclePtr = static_cast(Episode->SpawnActor(SpawnPt, DReyeVRDescr)); -} - -FTransform ADReyeVRGameMode::GetSpawnPoint(int SpawnPointIndex) const -{ - ACarlaGameModeBase *GM = UCarlaStatics::GetGameMode(GetWorld()); - if (GM != nullptr) - { - TArray SpawnPoints = GM->GetSpawnPointsTransforms(); - size_t WhichPoint = 0; // default to first one - if (SpawnPointIndex < 0) - WhichPoint = FMath::RandRange(0, SpawnPoints.Num()); - else - WhichPoint = FMath::Clamp(SpawnPointIndex, 0, SpawnPoints.Num()); - - if (WhichPoint < SpawnPoints.Num()) // SpawnPoints could be empty - return SpawnPoints[WhichPoint]; - } - /// TODO: return a safe bet (position of the player start maybe?) - return FTransform(FRotator::ZeroRotator, FVector::ZeroVector, FVector::OneVector); +#include "DReyeVRGameMode.h" +#include "Carla/AI/AIControllerFactory.h" // AAIControllerFactory +#include "Carla/Actor/StaticMeshFactory.h" // AStaticMeshFactory +#include "Carla/Game/CarlaStatics.h" // GetReplayer, GetEpisode +#include "Carla/Recorder/CarlaReplayer.h" // ACarlaReplayer +#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor +#include "Carla/Sensor/SensorFactory.h" // ASensorFactory +#include "Carla/Trigger/TriggerFactory.h" // TriggerFactory +#include "Carla/Vehicle/CarlaWheeledVehicle.h" // ACarlaWheeledVehicle +#include "Carla/Weather/Weather.h" // AWeather +#include "Components/AudioComponent.h" // UAudioComponent +#include "DReyeVRFactory.h" // ADReyeVRFactory +#include "DReyeVRPawn.h" // ADReyeVRPawn +#include "DReyeVRUtils.h" // FindDefnInRegistry +#include "EgoVehicle.h" // AEgoVehicle +#include "FlatHUD.h" // ADReyeVRHUD +#include "HeadMountedDisplayFunctionLibrary.h" // IsHeadMountedDisplayAvailable +#include "Kismet/GameplayStatics.h" // GetPlayerController +#include "UObject/UObjectIterator.h" // TObjectInterator + +ADReyeVRGameMode::ADReyeVRGameMode(FObjectInitializer const &FO) : Super(FO) +{ + // initialize stuff here + PrimaryActorTick.bCanEverTick = false; + PrimaryActorTick.bStartWithTickEnabled = false; + + // initialize default classes + this->HUDClass = ADReyeVRHUD::StaticClass(); + // find object UClass rather than UBlueprint + // https://forums.unrealengine.com/t/cdo-constructor-failed-to-find-thirdperson-c-template-mannequin-animbp/99003 + static ConstructorHelpers::FObjectFinder WeatherBP( + TEXT("/Game/Carla/Blueprints/Weather/BP_Weather.BP_Weather_C")); + this->WeatherClass = WeatherBP.Object; + + // initialize actor factories + // https://forums.unrealengine.com/t/what-is-the-right-syntax-of-fclassfinder-and-how-could-i-generaly-use-it-to-find-a-specific-blueprint/363884 + static ConstructorHelpers::FClassFinder VehicleFactoryBP( + TEXT("Blueprint'/Game/Carla/Blueprints/Vehicles/VehicleFactory'")); + static ConstructorHelpers::FClassFinder WalkerFactoryBP( + TEXT("Blueprint'/Game/Carla/Blueprints/Walkers/WalkerFactory'")); + static ConstructorHelpers::FClassFinder PropFactoryBP( + TEXT("Blueprint'/Game/Carla/Blueprints/Props/PropFactory'")); + + this->ActorFactories = TSet>{ + VehicleFactoryBP.Class, + ASensorFactory::StaticClass(), + WalkerFactoryBP.Class, + PropFactoryBP.Class, + ATriggerFactory::StaticClass(), + AAIControllerFactory::StaticClass(), + AStaticMeshFactory::StaticClass(), + ADReyeVRFactory::StaticClass(), // this is what registers the DReyeVR actors + }; + + // read config variables + EgoVolumePercent = GeneralParams.Get("Sound", "EgoVolumePercent"); + NonEgoVolumePercent = GeneralParams.Get("Sound", "NonEgoVolumePercent"); + AmbientVolumePercent = GeneralParams.Get("Sound", "AmbientVolumePercent"); + bDoSpawnEgoVehicleTransform = GeneralParams.Get("Game", "DoSpawnEgoVehicleTransform"); + SpawnEgoVehicleTransform = GeneralParams.Get("Game", "SpawnEgoVehicleTransform"); + + // Recorder/replayer + bUseCarlaSpectator = GeneralParams.Get("Replayer", "UseCarlaSpectator"); + bool bEnableReplayInterpolation = GeneralParams.Get("Replayer", "ReplayInterpolation"); + bReplaySync = !bEnableReplayInterpolation; // synchronous => no interpolation! +} + +void ADReyeVRGameMode::BeginPlay() +{ + Super::BeginPlay(); + + // Initialize player + GetPlayer(); + + // Can we tick? + SetActorTickEnabled(false); // make sure we do not tick ourselves + + // set all the volumes (ego, non-ego, ambient/world) + SetVolume(); + + // start input mapping + SetupPlayerInputComponent(); + + // spawn the DReyeVR pawn and possess it (first) + SetupDReyeVRPawn(); + ensure(GetPawn() != nullptr); + + // Initialize the DReyeVR EgoVehicle and Sensor (second) + if (GeneralParams.Get("Game", "AutomaticallySpawnEgo")) + { + SetupEgoVehicle(); + ensure(GetEgoVehicle() != nullptr); + } + + // Initialize DReyeVR spectator (third) + SetupSpectator(); + ensure(GetSpectator() != nullptr); +} + +void ADReyeVRGameMode::SetupDReyeVRPawn() +{ + if (DReyeVR_Pawn.IsValid()) + { + LOG("Not spawning new DReyeVR pawn"); + return; + } + FActorSpawnParameters SpawnParams; + SpawnParams.Owner = this; + SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + DReyeVR_Pawn = GetWorld()->SpawnActor(FVector::ZeroVector, FRotator::ZeroRotator, SpawnParams); + /// NOTE: the pawn is automatically possessed by player0 + // as the constructor has the AutoPossessPlayer != disabled + // if you want to manually possess then you can do Player->Possess(DReyeVR_Pawn); + if (!DReyeVR_Pawn.IsValid()) + { + LOG_ERROR("Unable to spawn DReyeVR pawn!") + } + else + { + DReyeVR_Pawn.Get()->BeginPlayer(GetPlayer()); + LOG("Successfully spawned DReyeVR pawn"); + } +} + +void ADReyeVRGameMode::SetEgoVehicle(AEgoVehicle *Ego) +{ + EgoVehiclePtr.Reset(); + EgoVehiclePtr = Ego; + check(EgoVehiclePtr.IsValid()); + ensure(GetPawn() != nullptr); // also respawn DReyeVR pawn if needed + // assign the (possibly new) EgoVehicle to the pawn + if (GetPawn() != nullptr) + { + DReyeVR_Pawn.Get()->BeginEgoVehicle(EgoVehiclePtr.Get(), GetWorld()); + } +} + +bool ADReyeVRGameMode::SetupEgoVehicle() +{ + if (EgoVehiclePtr.IsValid()) + { + LOG("Not spawning new EgoVehicle"); + return true; + } + + TArray FoundActors; + UGameplayStatics::GetAllActorsOfClass(GetWorld(), AEgoVehicle::StaticClass(), FoundActors); + if (FoundActors.Num() > 0) + { + for (AActor *Vehicle : FoundActors) + { + LOG("Found EgoVehicle in world: %s", *(Vehicle->GetName())); + EgoVehiclePtr = CastChecked(Vehicle); + /// TODO: handle multiple ego-vehcles? (we should only ever have one!) + break; + } + } + else + { + LOG("Did not find EgoVehicle in map... spawning..."); + // use the provided transform if requested, else generate a spawn point + FTransform SpawnPt = bDoSpawnEgoVehicleTransform ? SpawnEgoVehicleTransform : GetSpawnPoint(); + SpawnEgoVehicle(SpawnPt); // constructs and assigns EgoVehiclePtr + } + + // finalize the EgoVehicle by installing the DReyeVR_Pawn to control it + return (EgoVehiclePtr.IsValid()); +} + +void ADReyeVRGameMode::SetupSpectator() +{ + if (SpectatorPtr.IsValid()) + { + LOG("Not spawning new Spectator"); + return; + } + + // always disable the Carla spectator from DReyeVR use + UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + APawn *CarlaSpectator = nullptr; + if (Episode != nullptr) + { + CarlaSpectator = Episode->GetSpectatorPawn(); + if (CarlaSpectator != nullptr) + CarlaSpectator->SetActorHiddenInGame(true); + } + + // whether or not to use Carla spectator + if (bUseCarlaSpectator) + { + if (CarlaSpectator != nullptr) + SpectatorPtr = CarlaSpectator; + else if (GetPlayer() != nullptr) + SpectatorPtr = Player.Get()->GetPawn(); + } + + // spawn the Spectator pawn + { + LOG("Spawning DReyeVR Spectator Pawn in the world"); + FVector SpawnLocn; + FRotator SpawnRotn; + if (EgoVehiclePtr.IsValid()) + { + SpawnLocn = EgoVehiclePtr.Get()->GetCameraPosn(); + SpawnRotn = EgoVehiclePtr.Get()->GetCameraRot(); + } + else + { + // spawn above the vehicle recommended spawn pt + FTransform RecommendedPt = GetSpawnPoint(); + SpawnLocn = RecommendedPt.GetLocation(); + SpawnLocn.Z += 10.f * 100.f; // up in the air 10m ish + SpawnRotn = RecommendedPt.Rotator(); + } + // create new spectator pawn + FActorSpawnParameters SpawnParams; + SpawnParams.Owner = this; + SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + SpawnParams.ObjectFlags |= RF_Transient; + SpectatorPtr = GetWorld()->SpawnActor(ASpectatorPawn::StaticClass(), // spectator + SpawnLocn, SpawnRotn, SpawnParams); + } + + if (SpectatorPtr.IsValid()) + { + SpectatorPtr.Get()->SetActorHiddenInGame(true); // make spectator invisible + SpectatorPtr.Get()->GetRootComponent()->DestroyPhysicsState(); // no physics (just no-clip) + SpectatorPtr.Get()->SetActorEnableCollision(false); // no collisions + LOG("Successfully initiated spectator actor"); + } + + // automatically possess the spectator ptr if no ego vehicle present! + if (!EgoVehiclePtr.IsValid()) + { + PossessSpectator(); + } +} + +APawn *ADReyeVRGameMode::GetSpectator() +{ + return SafePtrGet("Spectator", SpectatorPtr, [&](void) { SetupSpectator(); }); +} + +AEgoVehicle *ADReyeVRGameMode::GetEgoVehicle() +{ + return SafePtrGet("EgoVehicle", EgoVehiclePtr, [&](void) { SetupEgoVehicle(); }); +} + +APlayerController *ADReyeVRGameMode::GetPlayer() +{ + return SafePtrGet("Player", Player, + [&](void) { Player = GetWorld()->GetFirstPlayerController(); }); +} + +ADReyeVRPawn *ADReyeVRGameMode::GetPawn() +{ + return SafePtrGet("Pawn", DReyeVR_Pawn, [&](void) { SetupDReyeVRPawn(); }); +} + +void ADReyeVRGameMode::BeginDestroy() +{ + Super::BeginDestroy(); + + if (DReyeVR_Pawn.IsValid()) + DReyeVR_Pawn.Get()->Destroy(); + DReyeVR_Pawn = nullptr; // release object and assign to null + + if (EgoVehiclePtr.IsValid()) + EgoVehiclePtr.Get()->Destroy(); + EgoVehiclePtr = nullptr; + + if (SpectatorPtr.IsValid()) + SpectatorPtr.Get()->Destroy(); + SpectatorPtr = nullptr; + + LOG("DReyeVRGameMode has been destroyed"); +} + +void ADReyeVRGameMode::Tick(float DeltaSeconds) +{ + Super::Tick(DeltaSeconds); + /// TODO: clean up replay init + if (!bRecorderInitiated) // can't do this in constructor + { + // Initialize recorder/replayer + SetupReplayer(); // once this is successfully run, it no longer gets executed + } + + DrawBBoxes(); +} + +void ADReyeVRGameMode::SetupPlayerInputComponent() +{ + if (GetPlayer() == nullptr) + return; + check(Player.IsValid()); + InputComponent = NewObject(this); + InputComponent->RegisterComponent(); + // set up gameplay key bindings + check(InputComponent); + Player.Get()->PushInputComponent(InputComponent); // enable this InputComponent with the PlayerController + // InputComponent->BindAction("ToggleCamera", IE_Pressed, this, &ADReyeVRGameMode::ToggleSpectator); + InputComponent->BindAction("PlayPause_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayPlayPause); + InputComponent->BindAction("FastForward_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayFastForward); + InputComponent->BindAction("Rewind_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayRewind); + InputComponent->BindAction("Restart_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayRestart); + InputComponent->BindAction("Incr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplaySpeedUp); + InputComponent->BindAction("Decr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplaySlowDown); + // Driver Handoff examples + InputComponent->BindAction("EgoVehicle_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::PossessEgoVehicle); + InputComponent->BindAction("Spectator_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::PossessSpectator); + InputComponent->BindAction("AI_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::HandoffDriverToAI); +} + +void ADReyeVRGameMode::PossessEgoVehicle() +{ + if (GetEgoVehicle() == nullptr || GetPawn() == nullptr || GetPlayer() == nullptr) + return; + + check(EgoVehiclePtr.IsValid()); + check(DReyeVR_Pawn.IsValid()); + check(Player.IsValid()); + EgoVehiclePtr.Get()->SetAutopilot(false); + + // check if already possessing EgoVehicle (DReyeVRPawn) + if (Player.Get()->GetPawn() == DReyeVR_Pawn.Get()) + { + LOG("Already possessing EgoVehicle"); + return; + } + + LOG("Possessing DReyeVR EgoVehicle"); + Player.Get()->Possess(DReyeVR_Pawn.Get()); + DReyeVR_Pawn.Get()->BeginEgoVehicle(EgoVehiclePtr.Get(), GetWorld()); +} + +void ADReyeVRGameMode::PossessSpectator() +{ + if (GetSpectator() == nullptr || GetPlayer() == nullptr) + return; + + check(SpectatorPtr.IsValid()); + check(Player.IsValid()); + + // check if already possessing spectator + if (Player.Get()->GetPawn() == SpectatorPtr.Get()) + { + LOG("Already possessing Spectator"); + return; + } + + if (EgoVehiclePtr.IsValid()) + { + // spawn from EgoVehicle head position + const FVector &EgoLocn = EgoVehiclePtr.Get()->GetCameraPosn(); + const FRotator &EgoRotn = EgoVehiclePtr.Get()->GetCameraRot(); + SpectatorPtr.Get()->SetActorLocationAndRotation(EgoLocn, EgoRotn); + } + // repossess the ego vehicle + Player.Get()->Possess(SpectatorPtr.Get()); + LOG("Possessing spectator player"); +} + +void ADReyeVRGameMode::HandoffDriverToAI() +{ + if (GetEgoVehicle() == nullptr) + return; + + check(EgoVehiclePtr.IsValid()); + + { // check if autopilot already enabled + if (EgoVehiclePtr.Get()->GetAutopilotStatus() == true) + { + LOG("EgoVehicle autopilot already on"); + return; + } + } + EgoVehiclePtr.Get()->SetAutopilot(true); + LOG("Enabling EgoVehicle Autopilot"); +} + +void ADReyeVRGameMode::ReplayPlayPause() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Toggle Replayer Play-Pause"); + Replayer->PlayPause(); + } +} + +void ADReyeVRGameMode::ReplayFastForward() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Advance replay by +1.0s"); + Replayer->Advance(1.0); + } +} + +void ADReyeVRGameMode::ReplayRewind() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Advance replay by -1.0s"); + Replayer->Advance(-1.0); + } +} + +void ADReyeVRGameMode::ReplayRestart() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Restarting recording replay..."); + Replayer->Restart(); + } +} + +void ADReyeVRGameMode::ChangeTimestep(UWorld *World, double AmntChangeSeconds) +{ + if (bReplaySync) + { + LOG("Changing timestep of replay during a synchronous replay is not supported. Enable ReplayInterpolation to " + "achieve this.") + return; + } + ensure(World != nullptr); + auto *Replayer = UCarlaStatics::GetReplayer(World); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + double NewFactor = ReplayTimeFactor + AmntChangeSeconds; + if (AmntChangeSeconds > 0) + { + if (NewFactor < ReplayTimeFactorMax) + { + LOG("Increase replay time factor: %.3fx -> %.3fx", ReplayTimeFactor, NewFactor); + Replayer->SetTimeFactor(NewFactor); + } + else + { + LOG("Unable to increase replay time factor (%.3f) beyond %.3fx", ReplayTimeFactor, ReplayTimeFactorMax); + Replayer->SetTimeFactor(ReplayTimeFactorMax); + } + } + else + { + if (NewFactor > ReplayTimeFactorMin) + { + LOG("Decrease replay time factor: %.3fx -> %.3fx", ReplayTimeFactor, NewFactor); + Replayer->SetTimeFactor(NewFactor); + } + else + { + LOG("Unable to decrease replay time factor (%.3f) below %.3fx", ReplayTimeFactor, ReplayTimeFactorMin); + Replayer->SetTimeFactor(ReplayTimeFactorMin); + } + } + ReplayTimeFactor = FMath::Clamp(NewFactor, ReplayTimeFactorMin, ReplayTimeFactorMax); + } +} + +void ADReyeVRGameMode::ReplaySpeedUp() +{ + ChangeTimestep(GetWorld(), AmntPlaybackIncr); +} + +void ADReyeVRGameMode::ReplaySlowDown() +{ + ChangeTimestep(GetWorld(), -AmntPlaybackIncr); +} + +void ADReyeVRGameMode::SetupReplayer() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr) + { + Replayer->SetSyncMode(bReplaySync); + if (bReplaySync) + { + LOG("Replay operating in frame-wise (1:1) synchronous mode (no replay interpolation)"); + } + bRecorderInitiated = true; + } +} + +void ADReyeVRGameMode::DrawBBoxes() +{ +#if 0 + TArray FoundActors; + if (GetWorld() != nullptr) + { + UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); + } + for (AActor *A : FoundActors) + { + std::string name = TCHAR_TO_UTF8(*A->GetName()); + if (A->GetName().Contains("DReyeVR")) + continue; // skip drawing a bbox over the EgoVehicle + if (BBoxes.find(name) == BBoxes.end()) + { + BBoxes[name] = ADReyeVRCustomActor::CreateNew(SM_CUBE, MAT_TRANSLUCENT, GetWorld(), "BBox" + A->GetName()); + } + const float DistThresh = 20.f; // meters before nearby bounding boxes become red + ADReyeVRCustomActor *BBox = BBoxes[name]; + ensure(BBox != nullptr); + if (BBox != nullptr) + { + BBox->Activate(); + BBox->MaterialParams.Opacity = 0.1f; + FLinearColor Col = FLinearColor::Green; + if (FVector::Distance(GetEgoVehicle()->GetActorLocation(), A->GetActorLocation()) < DistThresh * 100.f) + { + Col = FLinearColor::Red; + } + BBox->MaterialParams.BaseColor = Col; + BBox->MaterialParams.Emissive = 0.1 * Col; + + FVector Origin; + FVector BoxExtent; + A->GetActorBounds(true, Origin, BoxExtent, false); + // LOG("Origin: %s Extent %s"), *Origin.ToString(), *BoxExtent.ToString()); + // divide by 100 to get from cm to m, multiply by 2 bc the cube is scaled in both X and Y + BBox->SetActorScale3D(2 * BoxExtent / 100.f); + BBox->SetActorLocation(Origin); + // extent already covers the rotation aspect since the bbox is dynamic and axis aligned + // BBox->SetActorRotation(A->GetActorRotation()); + } + } +#endif +} + +void ADReyeVRGameMode::ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per) +{ + // first spawn the actor if not currently active + const std::string ActorName = TCHAR_TO_UTF8(*RecorderData.Name); + ADReyeVRCustomActor *A = nullptr; + if (ADReyeVRCustomActor::ActiveCustomActors.find(ActorName) == ADReyeVRCustomActor::ActiveCustomActors.end()) + { + /// TODO: also track KnownNumMaterials? + A = ADReyeVRCustomActor::CreateNew(RecorderData.MeshPath, RecorderData.MaterialParams.MaterialPath, GetWorld(), + RecorderData.Name); + } + else + { + A = ADReyeVRCustomActor::ActiveCustomActors[ActorName]; + } + // ensure the actor is currently active (spawned) + // now that we know this actor exists, update its internals + if (A != nullptr) + { + A->SetInternals(RecorderData); + A->Activate(); + A->Tick(Per); // update locations immediately + } +} + +void ADReyeVRGameMode::SetVolume() +{ + // update the non-ego volume percent + ACarlaWheeledVehicle::Volume = NonEgoVolumePercent / 100.f; + + // for all in-world audio components such as ambient birdsong, fountain splashing, smoke, etc. + for (TObjectIterator Itr; Itr; ++Itr) + { + if (Itr->GetWorld() != GetWorld()) // World Check + { + continue; + } + Itr->SetVolumeMultiplier(AmbientVolumePercent / 100.f); + } + + // for all in-world vehicles (including the EgoVehicle) manually set their volumes + TArray FoundActors; + UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); + for (AActor *A : FoundActors) + { + ACarlaWheeledVehicle *Vehicle = Cast(A); + if (Vehicle != nullptr) + { + float NewVolume = ACarlaWheeledVehicle::Volume; // Non ego volume + if (Vehicle->IsA(AEgoVehicle::StaticClass())) // dynamic cast, requires -frrti + NewVolume = EgoVolumePercent / 100.f; + Vehicle->SetVolume(NewVolume); + } + } +} + +void ADReyeVRGameMode::SpawnEgoVehicle(const FTransform &SpawnPt) +{ + UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + check(Episode != nullptr); + FActorDefinition EgoVehicleDefn = FindEgoVehicleDefinition(Episode); + FActorDescription DReyeVRDescr; + { // create a Description from the Definition to spawn the actor + DReyeVRDescr.UId = EgoVehicleDefn.UId; + DReyeVRDescr.Id = EgoVehicleDefn.Id; + DReyeVRDescr.Class = EgoVehicleDefn.Class; + // add all the attributes from the definition to the description + for (FActorAttribute A : EgoVehicleDefn.Attributes) + { + DReyeVRDescr.Variations.Add(A.Id, std::move(A)); + } + } + // calls Episode::SpawnActor => SpawnActorWithInfo => ActorDispatcher->SpawnActor => SpawnFunctions[UId] + EgoVehiclePtr = static_cast(Episode->SpawnActor(SpawnPt, DReyeVRDescr)); +} + +FTransform ADReyeVRGameMode::GetSpawnPoint(int SpawnPointIndex) const +{ + ACarlaGameModeBase *GM = UCarlaStatics::GetGameMode(GetWorld()); + if (GM != nullptr) + { + TArray SpawnPoints = GM->GetSpawnPointsTransforms(); + size_t WhichPoint = 0; // default to first one + if (SpawnPointIndex < 0) + WhichPoint = FMath::RandRange(0, SpawnPoints.Num()); + else + WhichPoint = FMath::Clamp(SpawnPointIndex, 0, SpawnPoints.Num()); + + if (WhichPoint < SpawnPoints.Num()) // SpawnPoints could be empty + return SpawnPoints[WhichPoint]; + } + /// TODO: return a safe bet (position of the player start maybe?) + return FTransform(FRotator::ZeroRotator, FVector::ZeroVector, FVector::OneVector); } \ No newline at end of file diff --git a/DReyeVR/DReyeVRGameMode.h b/DReyeVR/DReyeVRGameMode.h index 53818dd..20fe8b8 100644 --- a/DReyeVR/DReyeVRGameMode.h +++ b/DReyeVR/DReyeVRGameMode.h @@ -1,97 +1,97 @@ -#pragma once - -#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor -#include "Carla/Game/CarlaGameModeBase.h" // ACarlaGameModeBase -#include "Carla/Sensor/DReyeVRData.h" // DReyeVR:: -#include "DReyeVRPawn.h" // ADReyeVRPawn -#include "DReyeVRUtils.h" // SafePtrGet -#include // std::unordered_map - -#include "DReyeVRGameMode.generated.h" - -class AEgoVehicle; - -UCLASS() -class ADReyeVRGameMode : public ACarlaGameModeBase -{ - GENERATED_UCLASS_BODY() - - public: - ADReyeVRGameMode(); - - virtual void BeginPlay() override; - - virtual void BeginDestroy() override; - - virtual void Tick(float DeltaSeconds) override; - - APawn *GetSpectator(); - AEgoVehicle *GetEgoVehicle(); - APlayerController *GetPlayer(); - ADReyeVRPawn *GetPawn(); - - void SetEgoVehicle(AEgoVehicle *Ego); - - // input handling - void SetupPlayerInputComponent(); - - // EgoVehicle functions - void PossessEgoVehicle(); - void PossessSpectator(); - void HandoffDriverToAI(); - - // Replay media functions - void ChangeTimestep(UWorld *World, double AmntChangeSeconds); - void ReplayPlayPause(); - void ReplayFastForward(); - void ReplayRewind(); - void ReplayRestart(); - void ReplaySpeedUp(); - void ReplaySlowDown(); - - // Replayer - void SetupReplayer(); - - // Meta world functions - void SetVolume(); - FTransform GetSpawnPoint(int SpawnPointIndex = 0) const; - - // Custom actors - void ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per); - void DrawBBoxes(); - std::unordered_map BBoxes; - - private: - // for handling inputs and possessions - void SetupDReyeVRPawn(); - void SetupSpectator(); - bool SetupEgoVehicle(); - void SpawnEgoVehicle(const FTransform &SpawnPt); - - // TWeakObjectPtr's allow us to check if the underlying object is alive - // in case it was destroyed by someone other than us (ex. garbage collection) - TWeakObjectPtr Player; - TWeakObjectPtr DReyeVR_Pawn; - TWeakObjectPtr SpectatorPtr; - TWeakObjectPtr EgoVehiclePtr; - - // for toggling bw spectator mode - bool bIsSpectating = true; - - // for audio control - float EgoVolumePercent; - float NonEgoVolumePercent; - float AmbientVolumePercent; - - bool bDoSpawnEgoVehicleTransform = false; // whether or not to use provided SpawnEgoVehicleTransform - FTransform SpawnEgoVehicleTransform; - - // for recorder/replayer params - const double AmntPlaybackIncr = 0.25; // how much the playback speed changes (multiplicative, ex: 1x + 0.1 = 1.1x) - double ReplayTimeFactor = 1.0; // same as CarlaReplayer.h::TimeFactor (but local) - double ReplayTimeFactorMin = 0.0; // minimum playback of 0 (paused) - double ReplayTimeFactorMax = 4.0; // maximum of 4.0x playback - bool bReplaySync = false; // false allows for interpolation - bool bUseCarlaSpectator = false; // use the Carla spectator or spawn our own - bool bRecorderInitiated = false; // allows tick-wise checking for replayer/recorder +#pragma once + +#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor +#include "Carla/Game/CarlaGameModeBase.h" // ACarlaGameModeBase +#include "Carla/Sensor/DReyeVRData.h" // DReyeVR:: +#include "DReyeVRPawn.h" // ADReyeVRPawn +#include "DReyeVRUtils.h" // SafePtrGet +#include // std::unordered_map + +#include "DReyeVRGameMode.generated.h" + +class AEgoVehicle; + +UCLASS() +class ADReyeVRGameMode : public ACarlaGameModeBase +{ + GENERATED_UCLASS_BODY() + + public: + ADReyeVRGameMode(); + + virtual void BeginPlay() override; + + virtual void BeginDestroy() override; + + virtual void Tick(float DeltaSeconds) override; + + APawn *GetSpectator(); + AEgoVehicle *GetEgoVehicle(); + APlayerController *GetPlayer(); + ADReyeVRPawn *GetPawn(); + + void SetEgoVehicle(AEgoVehicle *Ego); + + // input handling + void SetupPlayerInputComponent(); + + // EgoVehicle functions + void PossessEgoVehicle(); + void PossessSpectator(); + void HandoffDriverToAI(); + + // Replay media functions + void ChangeTimestep(UWorld *World, double AmntChangeSeconds); + void ReplayPlayPause(); + void ReplayFastForward(); + void ReplayRewind(); + void ReplayRestart(); + void ReplaySpeedUp(); + void ReplaySlowDown(); + + // Replayer + void SetupReplayer(); + + // Meta world functions + void SetVolume(); + FTransform GetSpawnPoint(int SpawnPointIndex = 0) const; + + // Custom actors + void ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per); + void DrawBBoxes(); + std::unordered_map BBoxes; + + private: + // for handling inputs and possessions + void SetupDReyeVRPawn(); + void SetupSpectator(); + bool SetupEgoVehicle(); + void SpawnEgoVehicle(const FTransform &SpawnPt); + + // TWeakObjectPtr's allow us to check if the underlying object is alive + // in case it was destroyed by someone other than us (ex. garbage collection) + TWeakObjectPtr Player; + TWeakObjectPtr DReyeVR_Pawn; + TWeakObjectPtr SpectatorPtr; + TWeakObjectPtr EgoVehiclePtr; + + // for toggling bw spectator mode + bool bIsSpectating = true; + + // for audio control + float EgoVolumePercent; + float NonEgoVolumePercent; + float AmbientVolumePercent; + + bool bDoSpawnEgoVehicleTransform = false; // whether or not to use provided SpawnEgoVehicleTransform + FTransform SpawnEgoVehicleTransform; + + // for recorder/replayer params + const double AmntPlaybackIncr = 0.25; // how much the playback speed changes (multiplicative, ex: 1x + 0.1 = 1.1x) + double ReplayTimeFactor = 1.0; // same as CarlaReplayer.h::TimeFactor (but local) + double ReplayTimeFactorMin = 0.0; // minimum playback of 0 (paused) + double ReplayTimeFactorMax = 4.0; // maximum of 4.0x playback + bool bReplaySync = false; // false allows for interpolation + bool bUseCarlaSpectator = false; // use the Carla spectator or spawn our own + bool bRecorderInitiated = false; // allows tick-wise checking for replayer/recorder }; \ No newline at end of file diff --git a/DReyeVR/DReyeVRPawn.cpp b/DReyeVR/DReyeVRPawn.cpp index 655e5ea..0176269 100644 --- a/DReyeVR/DReyeVRPawn.cpp +++ b/DReyeVR/DReyeVRPawn.cpp @@ -1,754 +1,754 @@ -#include "DReyeVRPawn.h" -#include "DReyeVRUtils.h" // CreatePostProcessingEffect -#include "EgoVehicle.h" // AEgoVehicle -#include "HeadMountedDisplayFunctionLibrary.h" // SetTrackingOrigin, GetWorldToMetersScale -#include "HeadMountedDisplayTypes.h" // ESpectatorScreenMode -#include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic -#include "UObject/UObjectGlobals.h" // LoadObject, NewObject - -ADReyeVRPawn::ADReyeVRPawn(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) -{ - // this actor (pawn) ticks BEFORE the physics simulation, hence before EgoVehicle tick - PrimaryActorTick.bCanEverTick = true; - PrimaryActorTick.TickGroup = TG_PrePhysics; - - auto *RootComponent = CreateDefaultSubobject(TEXT("DReyeVR_RootComponent")); - SetRootComponent(RootComponent); - - // auto possess player 0 (this automatically calls Possess, which calls SetupInputComponent) - AutoPossessPlayer = EAutoReceiveInput::Player0; - - // read params - ReadConfigVariables(); - - // spawn and construct the first person camera - ConstructCamera(); - - // log - LOG("Spawning DReyeVR pawn for player0"); -} - -void ADReyeVRPawn::ReadConfigVariables() -{ - // camera - GeneralParams.Get("CameraParams", "FieldOfView", FieldOfView); - /// NOTE: all the postprocessing params are used in DReyeVRUtils::CreatePostProcessingParams - - // input scaling - GeneralParams.Get("VehicleInputs", "InvertMouseY", InvertMouseY); - GeneralParams.Get("VehicleInputs", "ScaleMouseY", ScaleMouseY); - GeneralParams.Get("VehicleInputs", "ScaleMouseX", ScaleMouseX); - - // HUD - GeneralParams.Get("EgoVehicleHUD", "HUDScaleVR", HUDScaleVR); - GeneralParams.Get("EgoVehicleHUD", "DrawFPSCounter", bDrawFPSCounter); - GeneralParams.Get("EgoVehicleHUD", "DrawFlatReticle", bDrawFlatReticle); - GeneralParams.Get("EgoVehicleHUD", "ReticleSize", ReticleSize); - GeneralParams.Get("EgoVehicleHUD", "DrawGaze", bDrawGaze); - GeneralParams.Get("EgoVehicleHUD", "DrawSpectatorReticle", bDrawSpectatorReticle); - GeneralParams.Get("EgoVehicleHUD", "EnableSpectatorScreen", bEnableSpectatorScreen); - - // wheel hardware - GeneralParams.Get("Hardware", "DeviceIdx", WheelDeviceIdx); - GeneralParams.Get("Hardware", "LogUpdates", bLogLogitechWheel); - GeneralParams.Get("Hardware", "ForceFeedbackMagnitude", SaturationPercentage); - GeneralParams.Get("Hardware", "DeltaInputThreshold", LogiThresh); -} - -void ADReyeVRPawn::ConstructCamera() -{ - // Create a camera and attach to root component - FirstPersonCam = CreateDefaultSubobject(TEXT("FirstPersonCam")); - - // the default shader behaviour will be to use RGB (no shader) - FirstPersonCam->PostProcessSettings = CreatePostProcessingEffect(0); // default (0) is RGB - FirstPersonCam->bUsePawnControlRotation = false; // free for VR movement - FirstPersonCam->bLockToHmd = true; // lock orientation and position to HMD - FirstPersonCam->FieldOfView = FieldOfView; // editable - FirstPersonCam->SetupAttachment(RootComponent); -} - -void ADReyeVRPawn::BeginPlay() -{ - Super::BeginPlay(); - - World = GetWorld(); - ensure(World != nullptr); - FirstPersonCam->RegisterComponentWithWorld(World); -} - -void ADReyeVRPawn::BeginPlayer(APlayerController *PlayerIn) -{ - Player = PlayerIn; - ensure(Player != nullptr); - - // Setup the HUD - InitFlatHUD(); -} - -void ADReyeVRPawn::BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World) -{ - /// NOTE: this should be run very early! - // before anything that needs the EgoVehicle pointer (since this initializes it!) - - SetEgoVehicle(Vehicle); - ensure(EgoVehicle != nullptr); - EgoVehicle->SetPawn(this); - - // register inputs that require EgoVehicle - ensure(InputComponent != nullptr); - SetupEgoVehicleInputComponent(InputComponent, EgoVehicle); -} - -void ADReyeVRPawn::BeginDestroy() -{ - Super::BeginDestroy(); - - if (bIsLogiConnected) - DestroyLogiWheel(false); - - LOG("DReyeVRPawn has been destroyed"); -} - -void ADReyeVRPawn::Tick(float DeltaTime) -{ - Super::Tick(DeltaTime); - - // Tick SteamVR - TickSteamVR(); - - // Tick the logitech wheel - TickLogiWheel(); - - // Tick spectator screen - TickSpectatorScreen(DeltaTime); -} - -/// ========================================== /// -/// ----------------:STEAMVR:----------------- /// -/// ========================================== /// - -void ADReyeVRPawn::InitSteamVR() -{ - bIsHMDConnected = UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayEnabled(); - if (bIsHMDConnected) - { - FString HMD_Name = UHeadMountedDisplayFunctionLibrary::GetHMDDeviceName().ToString(); - FString HMD_Version = UHeadMountedDisplayFunctionLibrary::GetVersionString(); - LOG("SteamVR HMD enabled: %s, version %s", *HMD_Name, *HMD_Version); - // Now we'll begin with setting up the VR Origin logic - // this tracking origin is what moves the HMD camera to the right position - UHeadMountedDisplayFunctionLibrary::SetTrackingOrigin(EHMDTrackingOrigin::Eye); // Also have Floor & Stage Level - InitSpectator(); - } - else - { - LOG_WARN("No SteamVR head mounted device enabled!"); - } -} - -void ADReyeVRPawn::TickSteamVR() -{ - /// NOTE: this exists because UE4's package mode has a slight warm-up time for the SteamVR - // plugin so it is not available to run UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayEnabled - // on BeginPlay. UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayConnected() is a weaker - // function that determines if a VR headset is connected at all (not connected + enabled) so we use - // that here to try to enable the SteamVR plugin on every tick UNTIL it is enabled (bIsHMDConnected == true) - if (!bIsHMDConnected && UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayConnected()) - { - // try reinitializing steamvr if the headset is connected but not active - InitSteamVR(); - } -} - -void ADReyeVRPawn::InitReticleTexture() -{ - if (bIsHMDConnected) - ReticleSize *= HUDScaleVR; - - /// NOTE: need to create transient like this bc of a UE4 bug in release mode - // https://forums.unrealengine.com/development-discussion/rendering/1767838-fimageutils-createtexture2d-crashes-in-packaged-build - TArray ReticleSrc; // pixel values array for eye reticle texture - if (bRectangularReticle) - { - GenerateSquareImage(ReticleSrc, ReticleSize, FColor(255, 0, 0, 128)); - } - else - { - GenerateCrosshairImage(ReticleSrc, ReticleSize, FColor(255, 0, 0, 128)); - } - ReticleTexture = CreateTexture2DFromArray(ReticleSrc); - check(ReticleTexture->Resource); -} - -void ADReyeVRPawn::InitSpectator() -{ - if (!bIsHMDConnected) - return; - // see https://docs.unrealengine.com/4.26/en-US/SharingAndReleasing/XRDevelopment/VR/DevelopVR/VRSpectatorScreen/ - auto SpectatorScreenMode = ESpectatorScreenMode::Disabled; // black window - if (bEnableSpectatorScreen) - { - // draws the left eye view cropped to the entire window - SpectatorScreenMode = ESpectatorScreenMode::SingleEyeCroppedToFill; - if (bDrawSpectatorReticle) - { - InitReticleTexture(); // generate array of pixel values - if (ReticleTexture != nullptr) - { - // draws the full screen view of the left eye (same as SingleEyeCroppedToFill) plus a texture overlaid - SpectatorScreenMode = ESpectatorScreenMode::TexturePlusEye; - UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenTexture(ReticleTexture); - } - else - { - LOG_ERROR("Reticle texture is null! Unable to use for spectator screen"); - } - } - } - UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenMode(SpectatorScreenMode); -} - -void ADReyeVRPawn::TickSpectatorScreen(float DeltaSeconds) -{ - // first draw the UE4 spectator screen (the flat-screen window during VR-play) - if (bIsHMDConnected) - { - // Draw the spectator vr screen and overlay elements - DrawSpectatorScreen(); - } - else // or overlay the HUD on the render window (flat-screen) if not playing in VR - { - // draws flat screen HUD if not in VR - DrawFlatHUD(DeltaSeconds); - } -} - -void ADReyeVRPawn::DrawSpectatorScreen() -{ - if (!bEnableSpectatorScreen || !Player || !EgoVehicle || !bIsHMDConnected) - return; - - // calculate View size (of open window). Note this is not the same as resolution - FIntPoint ViewSize; - Player->GetViewportSize(ViewSize.X, ViewSize.Y); - - /// TODO: draw other things on the spectator screen? - if (bDrawSpectatorReticle) - { - // project the 3D world point to 2D using the player's viewport - FVector2D ReticlePos; - { - // get where in the world the intersection occurs - const FVector HitPoint = EgoVehicle->GetSensor()->GetData()->GetFocusActorPoint(); - bool bPlayerViewportRelative = true; - UGameplayStatics::ProjectWorldToScreen(Player, HitPoint, ReticlePos, bPlayerViewportRelative); - } - - /// HACK: correct for offset likely due to using left eye for camera projection - ReticlePos.X += 0.3f * ReticleSize; - - /// NOTE: the SetSpectatorScreenModeTexturePlusEyeLayout expects normalized positions on the screen - // define min and max bounds (where the texture is actually drawn on screen) - const FVector2D TextureRectMin = (ReticlePos - 0.5f * ReticleSize) / ViewSize; // top left - const FVector2D TextureRectMax = (ReticlePos + 0.5f * ReticleSize) / ViewSize; // bottom right - auto Within01 = [](const float Num) { return 0.f <= Num && Num <= 1.f; }; - bool RectMinValid = Within01(TextureRectMin.X) && Within01(TextureRectMin.Y); - bool RectMaxValid = Within01(TextureRectMax.X) && Within01(TextureRectMax.Y); - const FVector2D WindowTopLeft{0.f, 0.f}; // top left of screen - const FVector2D WindowBottomRight{1.f, 1.f}; // bottom right of screen - if (RectMinValid && RectMaxValid) - { - /// TODO: disable the texture when RectMin or RectMax is invalid - UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenModeTexturePlusEyeLayout( - WindowTopLeft, // whole window (top left) - WindowBottomRight, // whole window (top -> bottom right) - TextureRectMin, // top left of texture - TextureRectMax, // bottom right of texture - true, // draw eye data as background - false, // clear w/ black - true // use alpha - ); - } - } -} - -/// ========================================== /// -/// ----------------:FLATHUD:----------------- /// -/// ========================================== /// - -void ADReyeVRPawn::InitFlatHUD() -{ - check(Player); - class AHUD *Raw_HUD = Player->GetHUD(); - ensure(Raw_HUD); - FlatHUD = Cast(Raw_HUD); - if (FlatHUD) - FlatHUD->SetPlayer(Player); - else - LOG_WARN("Unable to initialize DReyeVR HUD!"); - // make sure to disable the flat hud when in VR (not supported, only displays on half of one eye screen) - if (bIsHMDConnected) - { - bDrawFlatHud = false; - } -} - -void ADReyeVRPawn::DrawFlatHUD(float DeltaSeconds) -{ - if (!FlatHUD || !Player || !EgoVehicle || !bDrawFlatHud || bIsHMDConnected) - return; - - // calculate View size (of open window). Note this is not the same as resolution - FIntPoint ViewSize; - Player->GetViewportSize(ViewSize.X, ViewSize.Y); - - const auto *SensorData = EgoVehicle->GetSensor()->GetData(); - check(SensorData != nullptr); - - // Draw elements of the HUD - if (bDrawFlatReticle) // Draw reticle on flat-screen HUD - { - // get where in the world the intersection occurs - const FVector HitPoint = SensorData->GetFocusActorPoint(); - - const float Diameter = ReticleSize; - const float Thickness = (ReticleSize / 2.f) / 10.f; // 10 % of radius - // FlatHUD->DrawDynamicSquare(GazeEnd, Diameter, FColor(255, 0, 0, 255), Thickness); - FlatHUD->DrawDynamicCrosshair(HitPoint, Diameter, FColor(255, 0, 0, 255), true, Thickness); - } - - if (bDrawFPSCounter) - { - FlatHUD->DrawDynamicText(FString::FromInt(int(1.f / DeltaSeconds)), FVector2D(ViewSize.X - 100, 50), - FColor(0, 255, 0, 213), 2); - } - - if (bDrawGaze) - { - const FVector &WorldPos = GetCamera()->GetComponentLocation(); - const FRotator &WorldRot = GetCamera()->GetComponentRotation(); - const FVector &GazeOrigin = SensorData->GetGazeOrigin(); - const FVector RayStart = WorldPos + WorldRot.RotateVector(GazeOrigin); - const FVector RayEnd = SensorData->GetFocusActorPoint(); - - // Draw line components in FlatHUD - FlatHUD->DrawDynamicLine(RayStart, RayEnd, FColor::Red, 3.0f); - } -} - -/// ========================================== /// -/// ---------------:LOGITECH:----------------- /// -/// ========================================== /// - -void ADReyeVRPawn::InitLogiWheel() -{ -#if USE_LOGITECH_PLUGIN - LogiSteeringInitialize(false); - bIsLogiConnected = LogiIsConnected(WheelDeviceIdx); // get status of connected device - if (bIsLogiConnected) - { - const size_t n = 1000; // name shouldn't be more than 1000 chars right? - wchar_t *NameBuffer = (wchar_t *)malloc(n * sizeof(wchar_t)); - if (LogiGetFriendlyProductName(WheelDeviceIdx, NameBuffer, n) == false) - { - LOG_WARN("Unable to get Logi friendly name!"); - NameBuffer = L"Unknown"; - } - std::wstring wNameStr(NameBuffer, n); - std::string NameStr(wNameStr.begin(), wNameStr.end()); - FString LogiName(NameStr.c_str()); - LOG("Found a Logitech device (%s) connected on input %d", *LogiName, WheelDeviceIdx); - free(NameBuffer); // no longer needed - } - else - { - const FString LogiError = "Could not find Logitech device connected on input 0"; - const bool PrintToLog = false; // kinda annoying when flooding the logs with warning messages - const bool PrintToScreen = true; - const float ScreenDurationSec = 20.f; - const FLinearColor MsgColour = FLinearColor(1, 0, 0, 1); // RED - UKismetSystemLibrary::PrintString(World, LogiError, PrintToScreen, PrintToLog, MsgColour, ScreenDurationSec); - if (PrintToLog) - LOG_ERROR("%s", *LogiError); // Error is RED - } -#endif -} - -void ADReyeVRPawn::DestroyLogiWheel(bool DestroyModule) -{ -#if USE_LOGITECH_PLUGIN - if (bIsLogiConnected) - { - // stop any forces on the wheel (we only use spring force feedback) - LogiStopSpringForce(WheelDeviceIdx); - - if (DestroyModule) // only destroy the module at the end of the game (not ego life) - { - // shutdown the entire module (dangerous bc lingering pointers) - LogiSteeringShutdown(); - } - } -#endif -} - -void ADReyeVRPawn::TickLogiWheel() -{ - if (EgoVehicle == nullptr) - return; - // first try to initialize the Logi hardware if not currently active - if (!bIsLogiConnected) - { - InitLogiWheel(); - } -#if USE_LOGITECH_PLUGIN - bIsLogiConnected = LogiIsConnected(WheelDeviceIdx); // get status of connected device - if (bIsLogiConnected && bOverrideInputsWithKbd == false) - { - // Taking logitech inputs for steering - LogitechWheelUpdate(); - - // Add Force Feedback to the hardware steering wheel when a LogitechWheel is used - ApplyForceFeedback(); - } - bOverrideInputsWithKbd = false; // disable for the next tick (unless held, which will set to true) -#endif -} - -#if USE_LOGITECH_PLUGIN - -// const std::vector VarNames = {"rgdwPOV[0]", "rgdwPOV[1]", "rgdwPOV[2]", "rgdwPOV[3]"}; -const std::vector VarNames = { // 34 values - "lX", "lY", "lZ", "lRz", "lRy", "lRz", // variable names - "rglSlider[0]", "rglSlider[1]", "rgdwPOV[0]", "rgbButtons[0]", "lVX", "lVY", "lVZ", - "lVRx", "lVRy", "lVRz", "rglVSlider[0]", "rglVSlider[1]", "lAX", "lAY", - "lAZ", "lARx", "lARy", "lARz", "rglASlider[0]", "rglASlider[1]", "lFX", - "lFY", "lFZ", "lFRx", "lFRy", "lFRz", "rglFSlider[0]", "rglFSlider[1]"}; -/// NOTE: this is a debug function used to dump all the information we can regarding -// the Logitech wheel hardware we used since the exact buttons were not documented in -// the repo: https://github.com/HARPLab/LogitechWheelPlugin -void ADReyeVRPawn::LogLogitechPluginStruct(const struct DIJOYSTATE2 *Now) -{ - if (Old == nullptr) - { - Old = new struct DIJOYSTATE2; - (*Old) = (*Now); // assign to the new (current) dijoystate struct - return; // initializing the Old struct ptr - } - const std::vector NowVals = { - Now->lX, Now->lY, Now->lZ, Now->lRx, Now->lRy, Now->lRz, Now->rglSlider[0], Now->rglSlider[1], - // Converting unsigned int & unsigned char to int - int(Now->rgdwPOV[0]), int(Now->rgbButtons[0]), Now->lVX, Now->lVY, Now->lVZ, Now->lVRx, Now->lVRy, Now->lVRz, - Now->rglVSlider[0], Now->rglVSlider[1], Now->lAX, Now->lAY, Now->lAZ, Now->lARx, Now->lARy, Now->lARz, - Now->rglASlider[0], Now->rglASlider[1], Now->lFX, Now->lFY, Now->lFZ, Now->lFRx, Now->lFRy, Now->lFRz, - Now->rglFSlider[0], Now->rglFSlider[1]}; // 32 elements - // Getting the (34) values from the old struct - const std::vector OldVals = { - Old->lX, Old->lY, Old->lZ, Old->lRx, Old->lRy, Old->lRz, Old->rglSlider[0], Old->rglSlider[1], - // Converting unsigned int & unsigned char to int - int(Old->rgdwPOV[0]), int(Old->rgbButtons[0]), Old->lVX, Old->lVY, Old->lVZ, Old->lVRx, Old->lVRy, Old->lVRz, - Old->rglVSlider[0], Old->rglVSlider[1], Old->lAX, Old->lAY, Old->lAZ, Old->lARx, Old->lARy, Old->lARz, - Old->rglASlider[0], Old->rglASlider[1], Old->lFX, Old->lFY, Old->lFZ, Old->lFRx, Old->lFRy, Old->lFRz, - Old->rglFSlider[0], Old->rglFSlider[1]}; - - check(NowVals.size() == OldVals.size() && NowVals.size() == VarNames.size()); - - // print any differences - bool isDiff = false; - for (size_t i = 0; i < NowVals.size(); i++) - { - if (NowVals[i] != OldVals[i]) - { - if (!isDiff) // only gets triggered at MOST once - { - LOG("Logging joystick at t=%.3f", UGameplayStatics::GetRealTimeSeconds(World)); - isDiff = true; - } - LOG("Triggered \"%s\" from %d to %d", *(VarNames[i]), OldVals[i], NowVals[i]); - } - } - - // also check the 128 rgbButtons array - for (size_t i = 0; i < 127; i++) - { - if (Old->rgbButtons[i] != Now->rgbButtons[i]) - { - if (!isDiff) // only gets triggered at MOST once - { - LOG("Logging joystick at t=%.3f", UGameplayStatics::GetRealTimeSeconds(World)); - isDiff = true; - } - LOG("Triggered \"rgbButtons[%d]\" from %d to %d", int(i), int(OldVals[i]), int(NowVals[i])); - } - } - - // assign the current joystate into the old one - (*Old) = (*Now); -} - -void ADReyeVRPawn::LogitechWheelUpdate() -{ - check(EgoVehicle); - ensure(bOverrideInputsWithKbd == false); // kbd inputs should be false - - // only execute this in Windows, the Logitech plugin is incompatible with Linux - if (LogiUpdate() == false) // update the logitech wheel - LOG_WARN("Logitech wheel %d failed to update!", WheelDeviceIdx); - DIJOYSTATE2 *WheelState = LogiGetState(WheelDeviceIdx); - ensure(WheelState != nullptr); - if (bLogLogitechWheel) - LogLogitechPluginStruct(WheelState); - /// NOTE: obtained these from LogitechWheelInputDevice.cpp:~111 - // -32768 to 32767. -32768 = all the way to the left. 32767 = all the way to the right. - const float WheelRotation = FMath::Clamp(float(WheelState->lX), -32767.0f, 32767.0f) / 32767.0f; // (-1, 1) - // -32768 to 32767. 32767 = pedal not pressed. -32768 = pedal fully pressed. - const float AccelerationPedal = fabs(((WheelState->lY - 32767.0f) / (65535.0f))); // (0, 1) - // -32768 to 32767. Higher value = less pressure on brake pedal - const float BrakePedal = fabs(((WheelState->lRz - 32767.0f) / (65535.0f))); // (0, 1) - // -1 = not pressed. 0 = Top. 0.25 = Right. 0.5 = Bottom. 0.75 = Left. - const float Dpad = fabs(((WheelState->rgdwPOV[0] - 32767.0f) / (65535.0f))); - - // weird behaviour: "Pedals will output a value of 0.5 until the wheel/pedals receive any kind of input" - // as per https://github.com/HARPLab/LogitechWheelPlugin - if (bPedalsDefaulting) - { - // this bPedalsDefaulting flag is initially set to not send inputs when the pedals are "defaulting", once the - // pedals/wheel is used (pressed/turned) once then this flag is ignored (false) for the remainder of the game - if (!FMath::IsNearlyEqual(WheelRotation, 0.f, LogiThresh) || // wheel is not at 0 (rest) - !FMath::IsNearlyEqual(AccelerationPedal, 0.5f, LogiThresh) || // accel pedal is pressed - !FMath::IsNearlyEqual(BrakePedal, 0.5f, LogiThresh)) // brake pedal is pressed - { - bPedalsDefaulting = false; - } - } - else - { - /// NOTE: directly calling the EgoVehicle functions - if (EgoVehicle->GetAutopilotStatus() && - (FMath::IsNearlyEqual(WheelRotation, WheelRotationLast, LogiThresh) && - FMath::IsNearlyEqual(AccelerationPedal, AccelerationPedalLast, LogiThresh) && - FMath::IsNearlyEqual(BrakePedal, BrakePedalLast, LogiThresh))) - { - // let the autopilot drive if the user is not putting significant inputs - // ie. if their inputs are close enough to what was previously input - /// TODO: this system might break down if the autopilot is putting in sufficiently - /// strong inputs, since the autopilot controls might might inadvertently - /// be considered as human-input controls which amplifies the input and - /// causes a positive cycle loop (which would be better avoided) - } - else - { - // driver has issued sufficient input to warrant manual takeover (disables autopilot) - EgoVehicle->SetAutopilot(false); - EgoVehicle->AddSteering(WheelRotation); - EgoVehicle->AddThrottle(AccelerationPedal); - EgoVehicle->AddBrake(BrakePedal); - } - } - // save the last values for the wheel & pedals - WheelRotationLast = WheelRotation; - AccelerationPedalLast = AccelerationPedal; - BrakePedalLast = BrakePedal; - - ManageButtonPresses(*WheelState); -} - -void ADReyeVRPawn::ManageButtonPresses(const DIJOYSTATE2 &WheelState) -{ - const bool bABXY_A = static_cast(WheelState.rgbButtons[0]); - const bool bABXY_B = static_cast(WheelState.rgbButtons[2]); - const bool bABXY_X = static_cast(WheelState.rgbButtons[1]); - const bool bABXY_Y = static_cast(WheelState.rgbButtons[3]); - - if (bABXY_A || bABXY_B || bABXY_X || bABXY_Y) - EgoVehicle->PressReverse(); - else - EgoVehicle->ReleaseReverse(); - - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_A, bABXY_A); - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_B, bABXY_B); - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_X, bABXY_X); - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_Y, bABXY_Y); - - bool bTurnSignalR = static_cast(WheelState.rgbButtons[4]); - bool bTurnSignalL = static_cast(WheelState.rgbButtons[5]); - - if (bTurnSignalR) - EgoVehicle->PressTurnSignalR(); - else - EgoVehicle->ReleaseTurnSignalR(); - - if (bTurnSignalL) - EgoVehicle->PressTurnSignalL(); - else - EgoVehicle->ReleaseTurnSignalL(); - - // if (WheelState.rgbButtons[23]) // big red button on right side of g923 - - const bool bDPad_Up = (WheelState.rgdwPOV[0] == 0); - const bool bDPad_Right = (WheelState.rgdwPOV[0] == 9000); - const bool bDPad_Down = (WheelState.rgdwPOV[0] == 18000); - const bool bDPad_Left = (WheelState.rgdwPOV[0] == 27000); - const bool bPositive = static_cast(WheelState.rgbButtons[19]); - const bool bNegative = static_cast(WheelState.rgbButtons[20]); - - EgoVehicle->CameraPositionAdjust(bDPad_Up, bDPad_Right, bDPad_Down, bDPad_Left, bPositive, bNegative); - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Up, bDPad_Up); - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Right, bDPad_Right); - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Left, bDPad_Left); - EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Down, bDPad_Down); -} - -void ADReyeVRPawn::ApplyForceFeedback() const -{ - check(EgoVehicle); - - // only execute this in Windows, the Logitech plugin is incompatible with Linux - // const float Speed = EgoVehicle->GetVelocity().Size(); // get magnitude of self (AActor's) velocity - /// TODO: move outside this function (in tick()) to avoid redundancy - if (bIsLogiConnected && LogiHasForceFeedback(WheelDeviceIdx)) - { - // actuate the logi wheel to match the autopilot steering - float RawWheel = EgoVehicle->GetWheelSteerAngle(EVehicleWheelLocation::Front_Wheel); - // "Specifies the center of the spring force effect" - const int OffsetPercentage = static_cast(RawWheel * 0.5f); - const int CoeffPercentage = 100; // "Slope of the effect strength increase relative to deflection from Offset" - LogiPlaySpringForce(WheelDeviceIdx, OffsetPercentage, SaturationPercentage, CoeffPercentage); - } - else - { - LogiStopSpringForce(WheelDeviceIdx); - } - /// NOTE: there are other kinds of forces as described in the LogitechWheelPlugin API: - // https://github.com/HARPLab/LogitechWheelPlugin/blob/master/LogitechWheelPlugin/Source/LogitechWheelPlugin/Private/LogitechBWheelInputDevice.cpp - // For example: - /* - Force Types - 0 = Spring 5 = Dirt Road - 1 = Constant 6 = Bumpy Road - 2 = Damper 7 = Slippery Road - 3 = Side Collision 8 = Surface Effect - 4 = Frontal Collision 9 = Car Airborne - */ -} -#endif - -/// ========================================== /// -/// --------------:INPUTRELAY:---------------- /// -/// ========================================== /// - -// the whole reason to possess this Pawn instance is to relay these inputs -// back to the EgoVehicle so that the EgoVehicle can still be controlled by an AI controller -// and these inputs will not be blocked. -// Else, (since only one AController can possess an actor) either the PlayerController -// or AIController would be in control exclusively. - -void ADReyeVRPawn::SetupPlayerInputComponent(UInputComponent *PlayerInputComponent) -{ - /// NOTE: this function gets called once the pawn is possessed - Super::SetupPlayerInputComponent(PlayerInputComponent); - this->InputComponent = PlayerInputComponent; // keep track of this - check(InputComponent); - - /// NOTE: an Action is a digital input, an Axis is an analog input - /// Mouse X and Y input for looking up and turning - PlayerInputComponent->BindAxis("MouseLookUp_DReyeVR", this, &ADReyeVRPawn::MouseLookUp); - PlayerInputComponent->BindAxis("MouseTurn_DReyeVR", this, &ADReyeVRPawn::MouseTurn); -} - -void ADReyeVRPawn::SetupEgoVehicleInputComponent(UInputComponent *PlayerInputComponent, AEgoVehicle *EV) -{ - LOG("Initializing EgoVehicle relay mechanisms"); - // this function sets up the direct relay mechanisms to call EgoVehicle input functions - check(PlayerInputComponent != nullptr); - check(EV != nullptr); - // steering and throttle analog inputs (axes) - PlayerInputComponent->BindAxis("Steer_DReyeVR", EV, &AEgoVehicle::AddSteering); - PlayerInputComponent->BindAxis("Throttle_DReyeVR", EV, &AEgoVehicle::AddThrottle); - PlayerInputComponent->BindAxis("Brake_DReyeVR", EV, &AEgoVehicle::AddBrake); - // button actions (press & release) - PlayerInputComponent->BindAction("ToggleReverse_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressReverse); - PlayerInputComponent->BindAction("ToggleReverse_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseReverse); - PlayerInputComponent->BindAction("TurnSignalRight_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressTurnSignalR); - PlayerInputComponent->BindAction("TurnSignalLeft_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseTurnSignalL); - PlayerInputComponent->BindAction("TurnSignalLeft_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressTurnSignalL); - PlayerInputComponent->BindAction("TurnSignalRight_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseTurnSignalR); - // camera view adjustments - PlayerInputComponent->BindAction("NextCameraView_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressNextCameraView); - PlayerInputComponent->BindAction("NextCameraView_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseNextCameraView); - PlayerInputComponent->BindAction("PrevCameraView_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressPrevCameraView); - PlayerInputComponent->BindAction("PrevCameraView_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleasePrevCameraView); - // camera shader adjustments - PlayerInputComponent->BindAction("NextShader_DReyeVR", IE_Pressed, this, &ADReyeVRPawn::NextShader); - PlayerInputComponent->BindAction("PrevShader_DReyeVR", IE_Pressed, this, &ADReyeVRPawn::PrevShader); - // camera position adjustments - PlayerInputComponent->BindAction("CameraFwd_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraFwd); - PlayerInputComponent->BindAction("CameraBack_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraBack); - PlayerInputComponent->BindAction("CameraLeft_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraLeft); - PlayerInputComponent->BindAction("CameraRight_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraRight); - PlayerInputComponent->BindAction("CameraUp_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraUp); - PlayerInputComponent->BindAction("CameraDown_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraDown); -} - -/// ========================================== /// -/// -----------------:INPUT:------------------ /// -/// ========================================== /// - -void ADReyeVRPawn::NextShader() -{ - /// NOTE: the shader/postprocessing functions are defined in DReyeVRUtils.h - CurrentShaderIdx = (CurrentShaderIdx + 1) % GetNumberOfShaders(); - // update the camera's postprocessing effects - FirstPersonCam->PostProcessSettings = CreatePostProcessingEffect(CurrentShaderIdx); -} - -void ADReyeVRPawn::PrevShader() -{ - /// NOTE: the shader/postprocessing functions are defined in DReyeVRUtils.h - if (CurrentShaderIdx == 0) - CurrentShaderIdx = GetNumberOfShaders(); - CurrentShaderIdx--; - // update the camera's postprocessing effects - FirstPersonCam->PostProcessSettings = CreatePostProcessingEffect(CurrentShaderIdx); -} - -/// ========================================== /// -/// -----------------:MOUSE:------------------ /// -/// ========================================== /// - -/// NOTE: in UE4 rotators are of the form: {Pitch, Yaw, Roll} (stored in degrees) -/// We are basing the limits off of "Cervical Spine Functional Anatomy ad the Biomechanics of Injury": -// "The cervical spine's range of motion is approximately 80 deg to 90 deg of flexion, 70 deg of extension, -// 20 deg to 45 deg of lateral flexion, and up to 90 deg of rotation to both sides." -// (www.ncbi.nlm.nih.gov/pmc/articles/PMC1250253/) -/// NOTE: flexion = looking down to chest, extension = looking up , lateral = roll -/// ALSO: These functions are only used in non-VR mode, in VR you can move freely - -void ADReyeVRPawn::MouseLookUp(const float mY_Input) -{ - if (mY_Input != 0.f) - { - const float ScaleY = (this->InvertMouseY ? 1 : -1) * this->ScaleMouseY; // negative Y is "normal" controls - FRotator UpDir = this->GetCamera()->GetRelativeRotation() + FRotator(ScaleY * mY_Input, 0.f, 0.f); - // get the limits of a human neck (only clamping pitch) - const float MinFlexion = -85.f; - const float MaxExtension = 70.f; - UpDir.Pitch = FMath::Clamp(UpDir.Pitch, MinFlexion, MaxExtension); - this->GetCamera()->SetRelativeRotation(UpDir); - } -} - -void ADReyeVRPawn::MouseTurn(const float mX_Input) -{ - if (mX_Input != 0.f) - { - const float ScaleX = this->ScaleMouseX; - FRotator CurrentDir = this->GetCamera()->GetRelativeRotation(); - FRotator TurnDir = CurrentDir + FRotator(0.f, ScaleX * mX_Input, 0.f); - // get the limits of a human neck (only clamping pitch) - const float MinLeft = -90.f; - const float MaxRight = 90.f; // may consider increasing to allow users to look through the back window - TurnDir.Yaw = FMath::Clamp(TurnDir.Yaw, MinLeft, MaxRight); - this->GetCamera()->SetRelativeRotation(TurnDir); - } +#include "DReyeVRPawn.h" +#include "DReyeVRUtils.h" // CreatePostProcessingEffect +#include "EgoVehicle.h" // AEgoVehicle +#include "HeadMountedDisplayFunctionLibrary.h" // SetTrackingOrigin, GetWorldToMetersScale +#include "HeadMountedDisplayTypes.h" // ESpectatorScreenMode +#include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic +#include "UObject/UObjectGlobals.h" // LoadObject, NewObject + +ADReyeVRPawn::ADReyeVRPawn(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +{ + // this actor (pawn) ticks BEFORE the physics simulation, hence before EgoVehicle tick + PrimaryActorTick.bCanEverTick = true; + PrimaryActorTick.TickGroup = TG_PrePhysics; + + auto *RootComponent = CreateDefaultSubobject(TEXT("DReyeVR_RootComponent")); + SetRootComponent(RootComponent); + + // auto possess player 0 (this automatically calls Possess, which calls SetupInputComponent) + AutoPossessPlayer = EAutoReceiveInput::Player0; + + // read params + ReadConfigVariables(); + + // spawn and construct the first person camera + ConstructCamera(); + + // log + LOG("Spawning DReyeVR pawn for player0"); +} + +void ADReyeVRPawn::ReadConfigVariables() +{ + // camera + GeneralParams.Get("CameraParams", "FieldOfView", FieldOfView); + /// NOTE: all the postprocessing params are used in DReyeVRUtils::CreatePostProcessingParams + + // input scaling + GeneralParams.Get("VehicleInputs", "InvertMouseY", InvertMouseY); + GeneralParams.Get("VehicleInputs", "ScaleMouseY", ScaleMouseY); + GeneralParams.Get("VehicleInputs", "ScaleMouseX", ScaleMouseX); + + // HUD + GeneralParams.Get("EgoVehicleHUD", "HUDScaleVR", HUDScaleVR); + GeneralParams.Get("EgoVehicleHUD", "DrawFPSCounter", bDrawFPSCounter); + GeneralParams.Get("EgoVehicleHUD", "DrawFlatReticle", bDrawFlatReticle); + GeneralParams.Get("EgoVehicleHUD", "ReticleSize", ReticleSize); + GeneralParams.Get("EgoVehicleHUD", "DrawGaze", bDrawGaze); + GeneralParams.Get("EgoVehicleHUD", "DrawSpectatorReticle", bDrawSpectatorReticle); + GeneralParams.Get("EgoVehicleHUD", "EnableSpectatorScreen", bEnableSpectatorScreen); + + // wheel hardware + GeneralParams.Get("Hardware", "DeviceIdx", WheelDeviceIdx); + GeneralParams.Get("Hardware", "LogUpdates", bLogLogitechWheel); + GeneralParams.Get("Hardware", "ForceFeedbackMagnitude", SaturationPercentage); + GeneralParams.Get("Hardware", "DeltaInputThreshold", LogiThresh); +} + +void ADReyeVRPawn::ConstructCamera() +{ + // Create a camera and attach to root component + FirstPersonCam = CreateDefaultSubobject(TEXT("FirstPersonCam")); + + // the default shader behaviour will be to use RGB (no shader) + FirstPersonCam->PostProcessSettings = CreatePostProcessingEffect(0); // default (0) is RGB + FirstPersonCam->bUsePawnControlRotation = false; // free for VR movement + FirstPersonCam->bLockToHmd = true; // lock orientation and position to HMD + FirstPersonCam->FieldOfView = FieldOfView; // editable + FirstPersonCam->SetupAttachment(RootComponent); +} + +void ADReyeVRPawn::BeginPlay() +{ + Super::BeginPlay(); + + World = GetWorld(); + ensure(World != nullptr); + FirstPersonCam->RegisterComponentWithWorld(World); +} + +void ADReyeVRPawn::BeginPlayer(APlayerController *PlayerIn) +{ + Player = PlayerIn; + ensure(Player != nullptr); + + // Setup the HUD + InitFlatHUD(); +} + +void ADReyeVRPawn::BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World) +{ + /// NOTE: this should be run very early! + // before anything that needs the EgoVehicle pointer (since this initializes it!) + + SetEgoVehicle(Vehicle); + ensure(EgoVehicle != nullptr); + EgoVehicle->SetPawn(this); + + // register inputs that require EgoVehicle + ensure(InputComponent != nullptr); + SetupEgoVehicleInputComponent(InputComponent, EgoVehicle); +} + +void ADReyeVRPawn::BeginDestroy() +{ + Super::BeginDestroy(); + + if (bIsLogiConnected) + DestroyLogiWheel(false); + + LOG("DReyeVRPawn has been destroyed"); +} + +void ADReyeVRPawn::Tick(float DeltaTime) +{ + Super::Tick(DeltaTime); + + // Tick SteamVR + TickSteamVR(); + + // Tick the logitech wheel + TickLogiWheel(); + + // Tick spectator screen + TickSpectatorScreen(DeltaTime); +} + +/// ========================================== /// +/// ----------------:STEAMVR:----------------- /// +/// ========================================== /// + +void ADReyeVRPawn::InitSteamVR() +{ + bIsHMDConnected = UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayEnabled(); + if (bIsHMDConnected) + { + FString HMD_Name = UHeadMountedDisplayFunctionLibrary::GetHMDDeviceName().ToString(); + FString HMD_Version = UHeadMountedDisplayFunctionLibrary::GetVersionString(); + LOG("SteamVR HMD enabled: %s, version %s", *HMD_Name, *HMD_Version); + // Now we'll begin with setting up the VR Origin logic + // this tracking origin is what moves the HMD camera to the right position + UHeadMountedDisplayFunctionLibrary::SetTrackingOrigin(EHMDTrackingOrigin::Eye); // Also have Floor & Stage Level + InitSpectator(); + } + else + { + LOG_WARN("No SteamVR head mounted device enabled!"); + } +} + +void ADReyeVRPawn::TickSteamVR() +{ + /// NOTE: this exists because UE4's package mode has a slight warm-up time for the SteamVR + // plugin so it is not available to run UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayEnabled + // on BeginPlay. UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayConnected() is a weaker + // function that determines if a VR headset is connected at all (not connected + enabled) so we use + // that here to try to enable the SteamVR plugin on every tick UNTIL it is enabled (bIsHMDConnected == true) + if (!bIsHMDConnected && UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayConnected()) + { + // try reinitializing steamvr if the headset is connected but not active + InitSteamVR(); + } +} + +void ADReyeVRPawn::InitReticleTexture() +{ + if (bIsHMDConnected) + ReticleSize *= HUDScaleVR; + + /// NOTE: need to create transient like this bc of a UE4 bug in release mode + // https://forums.unrealengine.com/development-discussion/rendering/1767838-fimageutils-createtexture2d-crashes-in-packaged-build + TArray ReticleSrc; // pixel values array for eye reticle texture + if (bRectangularReticle) + { + GenerateSquareImage(ReticleSrc, ReticleSize, FColor(255, 0, 0, 128)); + } + else + { + GenerateCrosshairImage(ReticleSrc, ReticleSize, FColor(255, 0, 0, 128)); + } + ReticleTexture = CreateTexture2DFromArray(ReticleSrc); + check(ReticleTexture->Resource); +} + +void ADReyeVRPawn::InitSpectator() +{ + if (!bIsHMDConnected) + return; + // see https://docs.unrealengine.com/4.26/en-US/SharingAndReleasing/XRDevelopment/VR/DevelopVR/VRSpectatorScreen/ + auto SpectatorScreenMode = ESpectatorScreenMode::Disabled; // black window + if (bEnableSpectatorScreen) + { + // draws the left eye view cropped to the entire window + SpectatorScreenMode = ESpectatorScreenMode::SingleEyeCroppedToFill; + if (bDrawSpectatorReticle) + { + InitReticleTexture(); // generate array of pixel values + if (ReticleTexture != nullptr) + { + // draws the full screen view of the left eye (same as SingleEyeCroppedToFill) plus a texture overlaid + SpectatorScreenMode = ESpectatorScreenMode::TexturePlusEye; + UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenTexture(ReticleTexture); + } + else + { + LOG_ERROR("Reticle texture is null! Unable to use for spectator screen"); + } + } + } + UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenMode(SpectatorScreenMode); +} + +void ADReyeVRPawn::TickSpectatorScreen(float DeltaSeconds) +{ + // first draw the UE4 spectator screen (the flat-screen window during VR-play) + if (bIsHMDConnected) + { + // Draw the spectator vr screen and overlay elements + DrawSpectatorScreen(); + } + else // or overlay the HUD on the render window (flat-screen) if not playing in VR + { + // draws flat screen HUD if not in VR + DrawFlatHUD(DeltaSeconds); + } +} + +void ADReyeVRPawn::DrawSpectatorScreen() +{ + if (!bEnableSpectatorScreen || !Player || !EgoVehicle || !bIsHMDConnected) + return; + + // calculate View size (of open window). Note this is not the same as resolution + FIntPoint ViewSize; + Player->GetViewportSize(ViewSize.X, ViewSize.Y); + + /// TODO: draw other things on the spectator screen? + if (bDrawSpectatorReticle) + { + // project the 3D world point to 2D using the player's viewport + FVector2D ReticlePos; + { + // get where in the world the intersection occurs + const FVector HitPoint = EgoVehicle->GetSensor()->GetData()->GetFocusActorPoint(); + bool bPlayerViewportRelative = true; + UGameplayStatics::ProjectWorldToScreen(Player, HitPoint, ReticlePos, bPlayerViewportRelative); + } + + /// HACK: correct for offset likely due to using left eye for camera projection + ReticlePos.X += 0.3f * ReticleSize; + + /// NOTE: the SetSpectatorScreenModeTexturePlusEyeLayout expects normalized positions on the screen + // define min and max bounds (where the texture is actually drawn on screen) + const FVector2D TextureRectMin = (ReticlePos - 0.5f * ReticleSize) / ViewSize; // top left + const FVector2D TextureRectMax = (ReticlePos + 0.5f * ReticleSize) / ViewSize; // bottom right + auto Within01 = [](const float Num) { return 0.f <= Num && Num <= 1.f; }; + bool RectMinValid = Within01(TextureRectMin.X) && Within01(TextureRectMin.Y); + bool RectMaxValid = Within01(TextureRectMax.X) && Within01(TextureRectMax.Y); + const FVector2D WindowTopLeft{0.f, 0.f}; // top left of screen + const FVector2D WindowBottomRight{1.f, 1.f}; // bottom right of screen + if (RectMinValid && RectMaxValid) + { + /// TODO: disable the texture when RectMin or RectMax is invalid + UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenModeTexturePlusEyeLayout( + WindowTopLeft, // whole window (top left) + WindowBottomRight, // whole window (top -> bottom right) + TextureRectMin, // top left of texture + TextureRectMax, // bottom right of texture + true, // draw eye data as background + false, // clear w/ black + true // use alpha + ); + } + } +} + +/// ========================================== /// +/// ----------------:FLATHUD:----------------- /// +/// ========================================== /// + +void ADReyeVRPawn::InitFlatHUD() +{ + check(Player); + class AHUD *Raw_HUD = Player->GetHUD(); + ensure(Raw_HUD); + FlatHUD = Cast(Raw_HUD); + if (FlatHUD) + FlatHUD->SetPlayer(Player); + else + LOG_WARN("Unable to initialize DReyeVR HUD!"); + // make sure to disable the flat hud when in VR (not supported, only displays on half of one eye screen) + if (bIsHMDConnected) + { + bDrawFlatHud = false; + } +} + +void ADReyeVRPawn::DrawFlatHUD(float DeltaSeconds) +{ + if (!FlatHUD || !Player || !EgoVehicle || !bDrawFlatHud || bIsHMDConnected) + return; + + // calculate View size (of open window). Note this is not the same as resolution + FIntPoint ViewSize; + Player->GetViewportSize(ViewSize.X, ViewSize.Y); + + const auto *SensorData = EgoVehicle->GetSensor()->GetData(); + check(SensorData != nullptr); + + // Draw elements of the HUD + if (bDrawFlatReticle) // Draw reticle on flat-screen HUD + { + // get where in the world the intersection occurs + const FVector HitPoint = SensorData->GetFocusActorPoint(); + + const float Diameter = ReticleSize; + const float Thickness = (ReticleSize / 2.f) / 10.f; // 10 % of radius + // FlatHUD->DrawDynamicSquare(GazeEnd, Diameter, FColor(255, 0, 0, 255), Thickness); + FlatHUD->DrawDynamicCrosshair(HitPoint, Diameter, FColor(255, 0, 0, 255), true, Thickness); + } + + if (bDrawFPSCounter) + { + FlatHUD->DrawDynamicText(FString::FromInt(int(1.f / DeltaSeconds)), FVector2D(ViewSize.X - 100, 50), + FColor(0, 255, 0, 213), 2); + } + + if (bDrawGaze) + { + const FVector &WorldPos = GetCamera()->GetComponentLocation(); + const FRotator &WorldRot = GetCamera()->GetComponentRotation(); + const FVector &GazeOrigin = SensorData->GetGazeOrigin(); + const FVector RayStart = WorldPos + WorldRot.RotateVector(GazeOrigin); + const FVector RayEnd = SensorData->GetFocusActorPoint(); + + // Draw line components in FlatHUD + FlatHUD->DrawDynamicLine(RayStart, RayEnd, FColor::Red, 3.0f); + } +} + +/// ========================================== /// +/// ---------------:LOGITECH:----------------- /// +/// ========================================== /// + +void ADReyeVRPawn::InitLogiWheel() +{ +#if USE_LOGITECH_PLUGIN + LogiSteeringInitialize(false); + bIsLogiConnected = LogiIsConnected(WheelDeviceIdx); // get status of connected device + if (bIsLogiConnected) + { + const size_t n = 1000; // name shouldn't be more than 1000 chars right? + wchar_t *NameBuffer = (wchar_t *)malloc(n * sizeof(wchar_t)); + if (LogiGetFriendlyProductName(WheelDeviceIdx, NameBuffer, n) == false) + { + LOG_WARN("Unable to get Logi friendly name!"); + NameBuffer = L"Unknown"; + } + std::wstring wNameStr(NameBuffer, n); + std::string NameStr(wNameStr.begin(), wNameStr.end()); + FString LogiName(NameStr.c_str()); + LOG("Found a Logitech device (%s) connected on input %d", *LogiName, WheelDeviceIdx); + free(NameBuffer); // no longer needed + } + else + { + const FString LogiError = "Could not find Logitech device connected on input 0"; + const bool PrintToLog = false; // kinda annoying when flooding the logs with warning messages + const bool PrintToScreen = true; + const float ScreenDurationSec = 20.f; + const FLinearColor MsgColour = FLinearColor(1, 0, 0, 1); // RED + UKismetSystemLibrary::PrintString(World, LogiError, PrintToScreen, PrintToLog, MsgColour, ScreenDurationSec); + if (PrintToLog) + LOG_ERROR("%s", *LogiError); // Error is RED + } +#endif +} + +void ADReyeVRPawn::DestroyLogiWheel(bool DestroyModule) +{ +#if USE_LOGITECH_PLUGIN + if (bIsLogiConnected) + { + // stop any forces on the wheel (we only use spring force feedback) + LogiStopSpringForce(WheelDeviceIdx); + + if (DestroyModule) // only destroy the module at the end of the game (not ego life) + { + // shutdown the entire module (dangerous bc lingering pointers) + LogiSteeringShutdown(); + } + } +#endif +} + +void ADReyeVRPawn::TickLogiWheel() +{ + if (EgoVehicle == nullptr) + return; + // first try to initialize the Logi hardware if not currently active + if (!bIsLogiConnected) + { + InitLogiWheel(); + } +#if USE_LOGITECH_PLUGIN + bIsLogiConnected = LogiIsConnected(WheelDeviceIdx); // get status of connected device + if (bIsLogiConnected && bOverrideInputsWithKbd == false) + { + // Taking logitech inputs for steering + LogitechWheelUpdate(); + + // Add Force Feedback to the hardware steering wheel when a LogitechWheel is used + ApplyForceFeedback(); + } + bOverrideInputsWithKbd = false; // disable for the next tick (unless held, which will set to true) +#endif +} + +#if USE_LOGITECH_PLUGIN + +// const std::vector VarNames = {"rgdwPOV[0]", "rgdwPOV[1]", "rgdwPOV[2]", "rgdwPOV[3]"}; +const std::vector VarNames = { // 34 values + "lX", "lY", "lZ", "lRz", "lRy", "lRz", // variable names + "rglSlider[0]", "rglSlider[1]", "rgdwPOV[0]", "rgbButtons[0]", "lVX", "lVY", "lVZ", + "lVRx", "lVRy", "lVRz", "rglVSlider[0]", "rglVSlider[1]", "lAX", "lAY", + "lAZ", "lARx", "lARy", "lARz", "rglASlider[0]", "rglASlider[1]", "lFX", + "lFY", "lFZ", "lFRx", "lFRy", "lFRz", "rglFSlider[0]", "rglFSlider[1]"}; +/// NOTE: this is a debug function used to dump all the information we can regarding +// the Logitech wheel hardware we used since the exact buttons were not documented in +// the repo: https://github.com/HARPLab/LogitechWheelPlugin +void ADReyeVRPawn::LogLogitechPluginStruct(const struct DIJOYSTATE2 *Now) +{ + if (Old == nullptr) + { + Old = new struct DIJOYSTATE2; + (*Old) = (*Now); // assign to the new (current) dijoystate struct + return; // initializing the Old struct ptr + } + const std::vector NowVals = { + Now->lX, Now->lY, Now->lZ, Now->lRx, Now->lRy, Now->lRz, Now->rglSlider[0], Now->rglSlider[1], + // Converting unsigned int & unsigned char to int + int(Now->rgdwPOV[0]), int(Now->rgbButtons[0]), Now->lVX, Now->lVY, Now->lVZ, Now->lVRx, Now->lVRy, Now->lVRz, + Now->rglVSlider[0], Now->rglVSlider[1], Now->lAX, Now->lAY, Now->lAZ, Now->lARx, Now->lARy, Now->lARz, + Now->rglASlider[0], Now->rglASlider[1], Now->lFX, Now->lFY, Now->lFZ, Now->lFRx, Now->lFRy, Now->lFRz, + Now->rglFSlider[0], Now->rglFSlider[1]}; // 32 elements + // Getting the (34) values from the old struct + const std::vector OldVals = { + Old->lX, Old->lY, Old->lZ, Old->lRx, Old->lRy, Old->lRz, Old->rglSlider[0], Old->rglSlider[1], + // Converting unsigned int & unsigned char to int + int(Old->rgdwPOV[0]), int(Old->rgbButtons[0]), Old->lVX, Old->lVY, Old->lVZ, Old->lVRx, Old->lVRy, Old->lVRz, + Old->rglVSlider[0], Old->rglVSlider[1], Old->lAX, Old->lAY, Old->lAZ, Old->lARx, Old->lARy, Old->lARz, + Old->rglASlider[0], Old->rglASlider[1], Old->lFX, Old->lFY, Old->lFZ, Old->lFRx, Old->lFRy, Old->lFRz, + Old->rglFSlider[0], Old->rglFSlider[1]}; + + check(NowVals.size() == OldVals.size() && NowVals.size() == VarNames.size()); + + // print any differences + bool isDiff = false; + for (size_t i = 0; i < NowVals.size(); i++) + { + if (NowVals[i] != OldVals[i]) + { + if (!isDiff) // only gets triggered at MOST once + { + LOG("Logging joystick at t=%.3f", UGameplayStatics::GetRealTimeSeconds(World)); + isDiff = true; + } + LOG("Triggered \"%s\" from %d to %d", *(VarNames[i]), OldVals[i], NowVals[i]); + } + } + + // also check the 128 rgbButtons array + for (size_t i = 0; i < 127; i++) + { + if (Old->rgbButtons[i] != Now->rgbButtons[i]) + { + if (!isDiff) // only gets triggered at MOST once + { + LOG("Logging joystick at t=%.3f", UGameplayStatics::GetRealTimeSeconds(World)); + isDiff = true; + } + LOG("Triggered \"rgbButtons[%d]\" from %d to %d", int(i), int(OldVals[i]), int(NowVals[i])); + } + } + + // assign the current joystate into the old one + (*Old) = (*Now); +} + +void ADReyeVRPawn::LogitechWheelUpdate() +{ + check(EgoVehicle); + ensure(bOverrideInputsWithKbd == false); // kbd inputs should be false + + // only execute this in Windows, the Logitech plugin is incompatible with Linux + if (LogiUpdate() == false) // update the logitech wheel + LOG_WARN("Logitech wheel %d failed to update!", WheelDeviceIdx); + DIJOYSTATE2 *WheelState = LogiGetState(WheelDeviceIdx); + ensure(WheelState != nullptr); + if (bLogLogitechWheel) + LogLogitechPluginStruct(WheelState); + /// NOTE: obtained these from LogitechWheelInputDevice.cpp:~111 + // -32768 to 32767. -32768 = all the way to the left. 32767 = all the way to the right. + const float WheelRotation = FMath::Clamp(float(WheelState->lX), -32767.0f, 32767.0f) / 32767.0f; // (-1, 1) + // -32768 to 32767. 32767 = pedal not pressed. -32768 = pedal fully pressed. + const float AccelerationPedal = fabs(((WheelState->lY - 32767.0f) / (65535.0f))); // (0, 1) + // -32768 to 32767. Higher value = less pressure on brake pedal + const float BrakePedal = fabs(((WheelState->lRz - 32767.0f) / (65535.0f))); // (0, 1) + // -1 = not pressed. 0 = Top. 0.25 = Right. 0.5 = Bottom. 0.75 = Left. + const float Dpad = fabs(((WheelState->rgdwPOV[0] - 32767.0f) / (65535.0f))); + + // weird behaviour: "Pedals will output a value of 0.5 until the wheel/pedals receive any kind of input" + // as per https://github.com/HARPLab/LogitechWheelPlugin + if (bPedalsDefaulting) + { + // this bPedalsDefaulting flag is initially set to not send inputs when the pedals are "defaulting", once the + // pedals/wheel is used (pressed/turned) once then this flag is ignored (false) for the remainder of the game + if (!FMath::IsNearlyEqual(WheelRotation, 0.f, LogiThresh) || // wheel is not at 0 (rest) + !FMath::IsNearlyEqual(AccelerationPedal, 0.5f, LogiThresh) || // accel pedal is pressed + !FMath::IsNearlyEqual(BrakePedal, 0.5f, LogiThresh)) // brake pedal is pressed + { + bPedalsDefaulting = false; + } + } + else + { + /// NOTE: directly calling the EgoVehicle functions + if (EgoVehicle->GetAutopilotStatus() && + (FMath::IsNearlyEqual(WheelRotation, WheelRotationLast, LogiThresh) && + FMath::IsNearlyEqual(AccelerationPedal, AccelerationPedalLast, LogiThresh) && + FMath::IsNearlyEqual(BrakePedal, BrakePedalLast, LogiThresh))) + { + // let the autopilot drive if the user is not putting significant inputs + // ie. if their inputs are close enough to what was previously input + /// TODO: this system might break down if the autopilot is putting in sufficiently + /// strong inputs, since the autopilot controls might might inadvertently + /// be considered as human-input controls which amplifies the input and + /// causes a positive cycle loop (which would be better avoided) + } + else + { + // driver has issued sufficient input to warrant manual takeover (disables autopilot) + EgoVehicle->SetAutopilot(false); + EgoVehicle->AddSteering(WheelRotation); + EgoVehicle->AddThrottle(AccelerationPedal); + EgoVehicle->AddBrake(BrakePedal); + } + } + // save the last values for the wheel & pedals + WheelRotationLast = WheelRotation; + AccelerationPedalLast = AccelerationPedal; + BrakePedalLast = BrakePedal; + + ManageButtonPresses(*WheelState); +} + +void ADReyeVRPawn::ManageButtonPresses(const DIJOYSTATE2 &WheelState) +{ + const bool bABXY_A = static_cast(WheelState.rgbButtons[0]); + const bool bABXY_B = static_cast(WheelState.rgbButtons[2]); + const bool bABXY_X = static_cast(WheelState.rgbButtons[1]); + const bool bABXY_Y = static_cast(WheelState.rgbButtons[3]); + + if (bABXY_A || bABXY_B || bABXY_X || bABXY_Y) + EgoVehicle->PressReverse(); + else + EgoVehicle->ReleaseReverse(); + + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_A, bABXY_A); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_B, bABXY_B); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_X, bABXY_X); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_Y, bABXY_Y); + + bool bTurnSignalR = static_cast(WheelState.rgbButtons[4]); + bool bTurnSignalL = static_cast(WheelState.rgbButtons[5]); + + if (bTurnSignalR) + EgoVehicle->PressTurnSignalR(); + else + EgoVehicle->ReleaseTurnSignalR(); + + if (bTurnSignalL) + EgoVehicle->PressTurnSignalL(); + else + EgoVehicle->ReleaseTurnSignalL(); + + // if (WheelState.rgbButtons[23]) // big red button on right side of g923 + + const bool bDPad_Up = (WheelState.rgdwPOV[0] == 0); + const bool bDPad_Right = (WheelState.rgdwPOV[0] == 9000); + const bool bDPad_Down = (WheelState.rgdwPOV[0] == 18000); + const bool bDPad_Left = (WheelState.rgdwPOV[0] == 27000); + const bool bPositive = static_cast(WheelState.rgbButtons[19]); + const bool bNegative = static_cast(WheelState.rgbButtons[20]); + + EgoVehicle->CameraPositionAdjust(bDPad_Up, bDPad_Right, bDPad_Down, bDPad_Left, bPositive, bNegative); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Up, bDPad_Up); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Right, bDPad_Right); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Left, bDPad_Left); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Down, bDPad_Down); +} + +void ADReyeVRPawn::ApplyForceFeedback() const +{ + check(EgoVehicle); + + // only execute this in Windows, the Logitech plugin is incompatible with Linux + // const float Speed = EgoVehicle->GetVelocity().Size(); // get magnitude of self (AActor's) velocity + /// TODO: move outside this function (in tick()) to avoid redundancy + if (bIsLogiConnected && LogiHasForceFeedback(WheelDeviceIdx)) + { + // actuate the logi wheel to match the autopilot steering + float RawWheel = EgoVehicle->GetWheelSteerAngle(EVehicleWheelLocation::Front_Wheel); + // "Specifies the center of the spring force effect" + const int OffsetPercentage = static_cast(RawWheel * 0.5f); + const int CoeffPercentage = 100; // "Slope of the effect strength increase relative to deflection from Offset" + LogiPlaySpringForce(WheelDeviceIdx, OffsetPercentage, SaturationPercentage, CoeffPercentage); + } + else + { + LogiStopSpringForce(WheelDeviceIdx); + } + /// NOTE: there are other kinds of forces as described in the LogitechWheelPlugin API: + // https://github.com/HARPLab/LogitechWheelPlugin/blob/master/LogitechWheelPlugin/Source/LogitechWheelPlugin/Private/LogitechBWheelInputDevice.cpp + // For example: + /* + Force Types + 0 = Spring 5 = Dirt Road + 1 = Constant 6 = Bumpy Road + 2 = Damper 7 = Slippery Road + 3 = Side Collision 8 = Surface Effect + 4 = Frontal Collision 9 = Car Airborne + */ +} +#endif + +/// ========================================== /// +/// --------------:INPUTRELAY:---------------- /// +/// ========================================== /// + +// the whole reason to possess this Pawn instance is to relay these inputs +// back to the EgoVehicle so that the EgoVehicle can still be controlled by an AI controller +// and these inputs will not be blocked. +// Else, (since only one AController can possess an actor) either the PlayerController +// or AIController would be in control exclusively. + +void ADReyeVRPawn::SetupPlayerInputComponent(UInputComponent *PlayerInputComponent) +{ + /// NOTE: this function gets called once the pawn is possessed + Super::SetupPlayerInputComponent(PlayerInputComponent); + this->InputComponent = PlayerInputComponent; // keep track of this + check(InputComponent); + + /// NOTE: an Action is a digital input, an Axis is an analog input + /// Mouse X and Y input for looking up and turning + PlayerInputComponent->BindAxis("MouseLookUp_DReyeVR", this, &ADReyeVRPawn::MouseLookUp); + PlayerInputComponent->BindAxis("MouseTurn_DReyeVR", this, &ADReyeVRPawn::MouseTurn); +} + +void ADReyeVRPawn::SetupEgoVehicleInputComponent(UInputComponent *PlayerInputComponent, AEgoVehicle *EV) +{ + LOG("Initializing EgoVehicle relay mechanisms"); + // this function sets up the direct relay mechanisms to call EgoVehicle input functions + check(PlayerInputComponent != nullptr); + check(EV != nullptr); + // steering and throttle analog inputs (axes) + PlayerInputComponent->BindAxis("Steer_DReyeVR", EV, &AEgoVehicle::AddSteering); + PlayerInputComponent->BindAxis("Throttle_DReyeVR", EV, &AEgoVehicle::AddThrottle); + PlayerInputComponent->BindAxis("Brake_DReyeVR", EV, &AEgoVehicle::AddBrake); + // button actions (press & release) + PlayerInputComponent->BindAction("ToggleReverse_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressReverse); + PlayerInputComponent->BindAction("ToggleReverse_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseReverse); + PlayerInputComponent->BindAction("TurnSignalRight_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressTurnSignalR); + PlayerInputComponent->BindAction("TurnSignalLeft_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseTurnSignalL); + PlayerInputComponent->BindAction("TurnSignalLeft_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressTurnSignalL); + PlayerInputComponent->BindAction("TurnSignalRight_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseTurnSignalR); + // camera view adjustments + PlayerInputComponent->BindAction("NextCameraView_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressNextCameraView); + PlayerInputComponent->BindAction("NextCameraView_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseNextCameraView); + PlayerInputComponent->BindAction("PrevCameraView_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressPrevCameraView); + PlayerInputComponent->BindAction("PrevCameraView_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleasePrevCameraView); + // camera shader adjustments + PlayerInputComponent->BindAction("NextShader_DReyeVR", IE_Pressed, this, &ADReyeVRPawn::NextShader); + PlayerInputComponent->BindAction("PrevShader_DReyeVR", IE_Pressed, this, &ADReyeVRPawn::PrevShader); + // camera position adjustments + PlayerInputComponent->BindAction("CameraFwd_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraFwd); + PlayerInputComponent->BindAction("CameraBack_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraBack); + PlayerInputComponent->BindAction("CameraLeft_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraLeft); + PlayerInputComponent->BindAction("CameraRight_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraRight); + PlayerInputComponent->BindAction("CameraUp_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraUp); + PlayerInputComponent->BindAction("CameraDown_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraDown); +} + +/// ========================================== /// +/// -----------------:INPUT:------------------ /// +/// ========================================== /// + +void ADReyeVRPawn::NextShader() +{ + /// NOTE: the shader/postprocessing functions are defined in DReyeVRUtils.h + CurrentShaderIdx = (CurrentShaderIdx + 1) % GetNumberOfShaders(); + // update the camera's postprocessing effects + FirstPersonCam->PostProcessSettings = CreatePostProcessingEffect(CurrentShaderIdx); +} + +void ADReyeVRPawn::PrevShader() +{ + /// NOTE: the shader/postprocessing functions are defined in DReyeVRUtils.h + if (CurrentShaderIdx == 0) + CurrentShaderIdx = GetNumberOfShaders(); + CurrentShaderIdx--; + // update the camera's postprocessing effects + FirstPersonCam->PostProcessSettings = CreatePostProcessingEffect(CurrentShaderIdx); +} + +/// ========================================== /// +/// -----------------:MOUSE:------------------ /// +/// ========================================== /// + +/// NOTE: in UE4 rotators are of the form: {Pitch, Yaw, Roll} (stored in degrees) +/// We are basing the limits off of "Cervical Spine Functional Anatomy ad the Biomechanics of Injury": +// "The cervical spine's range of motion is approximately 80 deg to 90 deg of flexion, 70 deg of extension, +// 20 deg to 45 deg of lateral flexion, and up to 90 deg of rotation to both sides." +// (www.ncbi.nlm.nih.gov/pmc/articles/PMC1250253/) +/// NOTE: flexion = looking down to chest, extension = looking up , lateral = roll +/// ALSO: These functions are only used in non-VR mode, in VR you can move freely + +void ADReyeVRPawn::MouseLookUp(const float mY_Input) +{ + if (mY_Input != 0.f) + { + const float ScaleY = (this->InvertMouseY ? 1 : -1) * this->ScaleMouseY; // negative Y is "normal" controls + FRotator UpDir = this->GetCamera()->GetRelativeRotation() + FRotator(ScaleY * mY_Input, 0.f, 0.f); + // get the limits of a human neck (only clamping pitch) + const float MinFlexion = -85.f; + const float MaxExtension = 70.f; + UpDir.Pitch = FMath::Clamp(UpDir.Pitch, MinFlexion, MaxExtension); + this->GetCamera()->SetRelativeRotation(UpDir); + } +} + +void ADReyeVRPawn::MouseTurn(const float mX_Input) +{ + if (mX_Input != 0.f) + { + const float ScaleX = this->ScaleMouseX; + FRotator CurrentDir = this->GetCamera()->GetRelativeRotation(); + FRotator TurnDir = CurrentDir + FRotator(0.f, ScaleX * mX_Input, 0.f); + // get the limits of a human neck (only clamping pitch) + const float MinLeft = -90.f; + const float MaxRight = 90.f; // may consider increasing to allow users to look through the back window + TurnDir.Yaw = FMath::Clamp(TurnDir.Yaw, MinLeft, MaxRight); + this->GetCamera()->SetRelativeRotation(TurnDir); + } } \ No newline at end of file diff --git a/DReyeVR/DReyeVRPawn.h b/DReyeVR/DReyeVRPawn.h index f0153e7..a866043 100644 --- a/DReyeVR/DReyeVRPawn.h +++ b/DReyeVR/DReyeVRPawn.h @@ -1,146 +1,146 @@ -#pragma once - -#include "Camera/CameraComponent.h" // UCameraComponent -#include "Engine/Scene.h" // FPostProcessSettings -#include "GameFramework/Pawn.h" // CreatePlayerInputComponent - -#ifndef _WIN32 -// can only use LogitechWheel plugin on Windows! :( -#undef USE_LOGITECH_PLUGIN -#define USE_LOGITECH_PLUGIN false -#endif - -#if USE_LOGITECH_PLUGIN -#include "LogitechSteeringWheelLib.h" // LogitechWheel plugin for hardware integration & force feedback -#endif - -#include "DReyeVRPawn.generated.h" - -class AEgoVehicle; - -UCLASS() -class ADReyeVRPawn : public APawn -{ - GENERATED_BODY() - - public: - ADReyeVRPawn(const FObjectInitializer &ObjectInitializer); - - virtual void SetupPlayerInputComponent(UInputComponent *PlayerInputComponent) override; - virtual void Tick(float DeltaSeconds) override; - - void BeginPlayer(APlayerController *PlayerIn); - void BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World); - - void SetEgoVehicle(AEgoVehicle *Vehicle) - { - EgoVehicle = Vehicle; - } - - APlayerController *GetPlayer() - { - return Player; - } - - UCameraComponent *GetCamera() - { - return FirstPersonCam; - } - - const UCameraComponent *GetCamera() const - { - return FirstPersonCam; - } - - bool GetIsLogiConnected() const - { - return bIsLogiConnected; - } - - protected: - virtual void BeginPlay() override; - virtual void BeginDestroy() override; - void ReadConfigVariables(); - - class UWorld *World = nullptr; - class AEgoVehicle *EgoVehicle = nullptr; - - private: - ////////////////:CAMERA://////////////// - UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UCameraComponent *FirstPersonCam; - void ConstructCamera(); - float FieldOfView = 90.f; // in degrees - void NextShader(); - void PrevShader(); - size_t CurrentShaderIdx = 0; // 0th shader is rgb (camera) - - void TickSpectatorScreen(float DeltaSeconds); // to render the spectator screen (VR) or flat-screen hud (non-VR) - void DrawSpectatorScreen(); - void DrawFlatHUD(float DeltaSeconds); - - ////////////////:STEAMVR://////////////// - void InitSteamVR(); // Initialize the Head Mounted Display - void InitSpectator(); // Initialize the VR spectator - void TickSteamVR(); // Ensure SteamVR is active on every tick - void InitReticleTexture(); // initializes the spectator-reticle texture - UTexture2D *ReticleTexture; // UE4 texture for eye reticle - float HUDScaleVR; // How much to scale the HUD in VR - - ////////////////:FLATHUD://////////////// - // (Flat) HUD (NOTE: ONLY FOR NON VR) - void InitFlatHUD(); - UPROPERTY(Category = HUD, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class ADReyeVRHUD *FlatHUD; - FVector2D ReticlePos; // 2D reticle position from eye gaze - int ReticleSize = 100; // diameter of reticle (line thickness is 10% of this) - bool bDrawFlatHud = true; // whether to draw the flat hud at all (default true, but false in VR) - bool bDrawFPSCounter = true; // draw FPS counter in top left corner - bool bDrawGaze = false; // whether or not to draw a line for gaze-ray on HUD - bool bDrawSpectatorReticle = true; // Reticle used in the VR-spectator mode - bool bDrawFlatReticle = true; // Reticle used in the flat mode (uses HUD) (ONLY in non-vr mode) - bool bEnableSpectatorScreen = false; // don't spent time rendering the spectator screen - bool bRectangularReticle = false; // draw the reticle texture on the HUD & Spectator (NOT RECOMMENDED) - - ////////////////:INPUTS://////////////// - void MouseLookUp(const float mY_Input); - void MouseTurn(const float mX_Input); - bool InvertMouseY; - float ScaleMouseY; - float ScaleMouseX; - - // keyboard mechanisms to access Axis vehicle control (steering, throttle, brake) - void SetBrakeKbd(const float in); - void SetSteeringKbd(const float in); - void SetThrottleKbd(const float in); - // most of the time, the participant will use the logi for inputs, but if needed the experimenter - // can use the keyboard to reposition/takeover without input conflict - bool bOverrideInputsWithKbd = true; // keyboard > logi priority for inputs - - void SetupEgoVehicleInputComponent(UInputComponent *PlayerInputComponent, AEgoVehicle *EV); - UInputComponent *InputComponent = nullptr; - APlayerController *Player = nullptr; - - ////////////////:LOGI://////////////// - void InitLogiWheel(); - void TickLogiWheel(); - void DestroyLogiWheel(bool DestroyModule); - bool bLogLogitechWheel = false; - float LogiThresh = 0.02f; // threshold for change needed to overtake AI controls - int SaturationPercentage = 30; // "Level of saturation... comparable to a magnitude" - int WheelDeviceIdx = 0; // usually leaving as 0 is fine, only use 1 if 0 is taken -#if USE_LOGITECH_PLUGIN - struct DIJOYSTATE2 *Old = nullptr; // global "old" struct for the last state - void LogLogitechPluginStruct(const struct DIJOYSTATE2 *Now); - void LogitechWheelUpdate(); // for logitech wheel integration - void ManageButtonPresses(const DIJOYSTATE2 &WheelState); // for managing button presses - void ApplyForceFeedback() const; // for logitech wheel integration - float WheelRotationLast, AccelerationPedalLast, BrakePedalLast; -#endif - bool bIsLogiConnected = false; // check if Logi device is connected (on BeginPlay) - bool bIsHMDConnected = false; // checks for HMD connection on BeginPlay - // default logi plugin behaviour is to set things to 0.5 for some reason - // "Pedals will output a value of 0.5 until the wheel/pedals receive any kind of input." - // https://github.com/HARPLab/LogitechWheelPlugin - bool bPedalsDefaulting = true; -}; +#pragma once + +#include "Camera/CameraComponent.h" // UCameraComponent +#include "Engine/Scene.h" // FPostProcessSettings +#include "GameFramework/Pawn.h" // CreatePlayerInputComponent + +#ifndef _WIN32 +// can only use LogitechWheel plugin on Windows! :( +#undef USE_LOGITECH_PLUGIN +#define USE_LOGITECH_PLUGIN false +#endif + +#if USE_LOGITECH_PLUGIN +#include "LogitechSteeringWheelLib.h" // LogitechWheel plugin for hardware integration & force feedback +#endif + +#include "DReyeVRPawn.generated.h" + +class AEgoVehicle; + +UCLASS() +class ADReyeVRPawn : public APawn +{ + GENERATED_BODY() + + public: + ADReyeVRPawn(const FObjectInitializer &ObjectInitializer); + + virtual void SetupPlayerInputComponent(UInputComponent *PlayerInputComponent) override; + virtual void Tick(float DeltaSeconds) override; + + void BeginPlayer(APlayerController *PlayerIn); + void BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World); + + void SetEgoVehicle(AEgoVehicle *Vehicle) + { + EgoVehicle = Vehicle; + } + + APlayerController *GetPlayer() + { + return Player; + } + + UCameraComponent *GetCamera() + { + return FirstPersonCam; + } + + const UCameraComponent *GetCamera() const + { + return FirstPersonCam; + } + + bool GetIsLogiConnected() const + { + return bIsLogiConnected; + } + + protected: + virtual void BeginPlay() override; + virtual void BeginDestroy() override; + void ReadConfigVariables(); + + class UWorld *World = nullptr; + class AEgoVehicle *EgoVehicle = nullptr; + + private: + ////////////////:CAMERA://////////////// + UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UCameraComponent *FirstPersonCam; + void ConstructCamera(); + float FieldOfView = 90.f; // in degrees + void NextShader(); + void PrevShader(); + size_t CurrentShaderIdx = 0; // 0th shader is rgb (camera) + + void TickSpectatorScreen(float DeltaSeconds); // to render the spectator screen (VR) or flat-screen hud (non-VR) + void DrawSpectatorScreen(); + void DrawFlatHUD(float DeltaSeconds); + + ////////////////:STEAMVR://////////////// + void InitSteamVR(); // Initialize the Head Mounted Display + void InitSpectator(); // Initialize the VR spectator + void TickSteamVR(); // Ensure SteamVR is active on every tick + void InitReticleTexture(); // initializes the spectator-reticle texture + UTexture2D *ReticleTexture; // UE4 texture for eye reticle + float HUDScaleVR; // How much to scale the HUD in VR + + ////////////////:FLATHUD://////////////// + // (Flat) HUD (NOTE: ONLY FOR NON VR) + void InitFlatHUD(); + UPROPERTY(Category = HUD, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class ADReyeVRHUD *FlatHUD; + FVector2D ReticlePos; // 2D reticle position from eye gaze + int ReticleSize = 100; // diameter of reticle (line thickness is 10% of this) + bool bDrawFlatHud = true; // whether to draw the flat hud at all (default true, but false in VR) + bool bDrawFPSCounter = true; // draw FPS counter in top left corner + bool bDrawGaze = false; // whether or not to draw a line for gaze-ray on HUD + bool bDrawSpectatorReticle = true; // Reticle used in the VR-spectator mode + bool bDrawFlatReticle = true; // Reticle used in the flat mode (uses HUD) (ONLY in non-vr mode) + bool bEnableSpectatorScreen = false; // don't spent time rendering the spectator screen + bool bRectangularReticle = false; // draw the reticle texture on the HUD & Spectator (NOT RECOMMENDED) + + ////////////////:INPUTS://////////////// + void MouseLookUp(const float mY_Input); + void MouseTurn(const float mX_Input); + bool InvertMouseY; + float ScaleMouseY; + float ScaleMouseX; + + // keyboard mechanisms to access Axis vehicle control (steering, throttle, brake) + void SetBrakeKbd(const float in); + void SetSteeringKbd(const float in); + void SetThrottleKbd(const float in); + // most of the time, the participant will use the logi for inputs, but if needed the experimenter + // can use the keyboard to reposition/takeover without input conflict + bool bOverrideInputsWithKbd = true; // keyboard > logi priority for inputs + + void SetupEgoVehicleInputComponent(UInputComponent *PlayerInputComponent, AEgoVehicle *EV); + UInputComponent *InputComponent = nullptr; + APlayerController *Player = nullptr; + + ////////////////:LOGI://////////////// + void InitLogiWheel(); + void TickLogiWheel(); + void DestroyLogiWheel(bool DestroyModule); + bool bLogLogitechWheel = false; + float LogiThresh = 0.02f; // threshold for change needed to overtake AI controls + int SaturationPercentage = 30; // "Level of saturation... comparable to a magnitude" + int WheelDeviceIdx = 0; // usually leaving as 0 is fine, only use 1 if 0 is taken +#if USE_LOGITECH_PLUGIN + struct DIJOYSTATE2 *Old = nullptr; // global "old" struct for the last state + void LogLogitechPluginStruct(const struct DIJOYSTATE2 *Now); + void LogitechWheelUpdate(); // for logitech wheel integration + void ManageButtonPresses(const DIJOYSTATE2 &WheelState); // for managing button presses + void ApplyForceFeedback() const; // for logitech wheel integration + float WheelRotationLast, AccelerationPedalLast, BrakePedalLast; +#endif + bool bIsLogiConnected = false; // check if Logi device is connected (on BeginPlay) + bool bIsHMDConnected = false; // checks for HMD connection on BeginPlay + // default logi plugin behaviour is to set things to 0.5 for some reason + // "Pedals will output a value of 0.5 until the wheel/pedals receive any kind of input." + // https://github.com/HARPLab/LogitechWheelPlugin + bool bPedalsDefaulting = true; +}; diff --git a/DReyeVR/DReyeVRUtils.h b/DReyeVR/DReyeVRUtils.h index 15ab659..e7195f8 100644 --- a/DReyeVR/DReyeVRUtils.h +++ b/DReyeVR/DReyeVRUtils.h @@ -1,432 +1,432 @@ -#ifndef DREYEVR_UTIL -#define DREYEVR_UTIL - -#include "Carla/Sensor/ShaderBasedSensor.h" // FSensorShader -#include "ConfigFile.h" // ConfigFile class -#include "CoreMinimal.h" -#include "Engine/Texture2D.h" // UTexture2D -#include "HighResScreenshot.h" // FHighResScreenshotConfig -#include "ImageWriteQueue.h" // TImagePixelData -#include "ImageWriteTask.h" // FImageWriteTask -#include // CityScapesPalette - -// instead of vehicle.dreyevr.model3 or sensor.dreyevr.ego_sensor, we use "harplab" for category -// => harplab.dreyevr_vehicle.model3 & harplab.dreyevr_sensor.ego_sensor -// in PythonAPI use world.get_actors().filter("harplab.dreyevr_vehicle.*") or -// world.get_blueprint_library().filter("harplab.dreyevr_sensor.*") and you won't accidentally get these actors when -// performing filter("vehicle.*") or filter("sensor.*") -static const FString DReyeVRCategory("HarpLab"); - -template -T *SafePtrGet(const FString &Name, TWeakObjectPtr &Ptr, const std::function &RemedyFunction) -{ - if (Ptr.IsValid()) - return Ptr.Get(); - // object was destroyed! possibly by external process (ex. map change) - if (!Ptr.IsExplicitlyNull()) - { // dangling pointer!! - LOG_WARN("Dangling pointer \"%s\" (%p) is invalid! Attempting to remedy", Ptr.Get(), *Name); - } - RemedyFunction(); - // try to remedy - if (Ptr.IsValid()) - return Ptr.Get(); - LOG_ERROR("Unable to remedy (%s)", *Name); - return nullptr; -} - -static FString UE4RefToClassPath(const FString &UE4ReferencePath) -{ - // converts (reference) strings of the type "Type'/Game/PATH/asset.asset'" to "/Game/PATH/asset.asset_C" - // for use in ConstructorHelpers::FClassFinder - const FString NoneStr = FString(""); // replace with empty string ("") - const FString SingleQuoteStr = FString("'"); - // find the start position in the string (ignore the type (Blueprint, SkeletalMesh, Skeleton, AnimBP, etc.)) - const int StartPos = UE4ReferencePath.Find(SingleQuoteStr, ESearchCase::CaseSensitive, ESearchDir::FromStart, 0); - FString Ret = UE4ReferencePath.RightChop(StartPos); - Ret.ReplaceInline(*SingleQuoteStr, *NoneStr, ESearchCase::CaseSensitive); - Ret += "_C"; // to force class type suffix - return Ret; -} - -static FString CleanNameForDReyeVR(const FString &RawName) -{ - // should be equivalent to GetClass()->GetDisplayNameText().ToString() - // for our purposes (spawning different type EgoVehicles) - FString CleanName = RawName; - CleanName.RemoveSpacesInline(); // one word -#define DELETE_INLINE(x) CleanName.ReplaceInline(*FString(x), *FString(""), ESearchCase::CaseSensitive); - DELETE_INLINE("BP_"); // might start w/ BP_XYZ - DELETE_INLINE("BP"); // might start w/ BPXYZ - DELETE_INLINE("_C"); // might end with _C - DELETE_INLINE("Ego"); // default object is EgoVehicle - DELETE_INLINE("SKEL_"); // skeleton class starts with SKEL_ - - return CleanName; -} - -static FActorDefinition FindDefnInRegistry(const UCarlaEpisode *Episode, const UClass *ClassType) -{ - // searches through the registers actors (definitions) to find one with the matching class type - check(Episode != nullptr); - - FActorDefinition FoundDefinition; - bool bFoundDef = false; - for (const auto &Defn : Episode->GetActorDefinitions()) - { - if (Defn.Class == ClassType) - { - LOG("Found appropriate definition registered at UId: %d as \"%s\"", Defn.UId, *Defn.Id); - FoundDefinition = Defn; - bFoundDef = true; - break; // assumes the first is the ONLY one matching this class (Ex. EgoVehicle, EgoSensor) - } - } - if (!bFoundDef) - { - LOG_ERROR("Unable to find appropriate definition in registry!"); - } - return FoundDefinition; -} - -static FActorDefinition FindEgoVehicleDefinition(const UCarlaEpisode *Episode) -{ - - FString LoadVehicle = "TeslaM3"; // default vehicle - if (GeneralParams.Get("EgoVehicle", "VehicleType", LoadVehicle)) - { - LOG("Loading new default EgoVehicle: \"%s\"", *LoadVehicle); - } - // searches through the registers actors (definitions) to find one with the matching class type - check(Episode != nullptr); - - FActorDefinition FoundDefinition; - bool bFoundDef = false; - for (const auto &Defn : Episode->GetActorDefinitions()) - { - const auto &LowerId = Defn.Id.ToLower(); // perform string comparisons on lowercase (ignore case) - // contains both the DReyeVR category (HarpLab) and specific EgoVehicle - if (LowerId.Contains(DReyeVRCategory.ToLower()) && LowerId.Contains(LoadVehicle.ToLower())) - { - LOG("Found appropriate definition for \"%s\" registered at UId: %d as \"%s\"", // - *LoadVehicle, Defn.UId, *Defn.Id); - FoundDefinition = Defn; - bFoundDef = true; - break; // assumes the first is the ONLY one matching this class (Ex. EgoVehicle, EgoSensor) - } - } - if (!bFoundDef) - { - LOG_ERROR("Unable to find appropriate definition in registry!"); - } - return FoundDefinition; -} - -static FVector ComputeClosestToRayIntersection(const FVector &L0, const FVector &LDir, const FVector &R0, - const FVector &RDir) -{ - // Recall that a 'line' can be defined as (L = origin(0) + t * direction(Dir)) for some t - - // Calculating shortest line segment intersecting both lines - // Implementation sourced from http://paulbourke.net/geometry/pointlineplane/ - FVector L0R0 = L0 - R0; // segment between L origin and R origin - if (L0R0.Size() == 0.f) // same origin - return FVector::ZeroVector; - const float epsilon = 0.00001f; // small positive real number - - // Calculating dot-product equation to find perpendicular shortest-line-segment - float d1343 = L0R0.X * RDir.X + L0R0.Y * RDir.Y + L0R0.Z * RDir.Z; - float d4321 = RDir.X * LDir.X + RDir.Y * LDir.Y + RDir.Z * LDir.Z; - float d1321 = L0R0.X * LDir.X + L0R0.Y * LDir.Y + L0R0.Z * LDir.Z; - float d4343 = RDir.X * RDir.X + RDir.Y * RDir.Y + RDir.Z * RDir.Z; - float d2121 = LDir.X * LDir.X + LDir.Y * LDir.Y + LDir.Z * LDir.Z; - float denom = d2121 * d4343 - d4321 * d4321; - if (abs(denom) < epsilon) - return FVector::ZeroVector; // no intersection, would cause div by 0 err - float numer = d1343 * d4321 - d1321 * d4343; - - // calculate scalars (mu) that scale the unit direction XDir to reach the desired points - float muL = numer / denom; // variable scale of direction vector for LEFT ray - float muR = (d1343 + d4321 * (muL)) / d4343; // variable scale of direction vector for RIGHT ray - - // calculate the points on the respective rays that create the intersecting line - FVector ptL = L0 + muL * LDir; // the point on the Left ray - FVector ptR = R0 + muR * RDir; // the point on the Right ray - - FVector ShortestLineSeg = ptL - ptR; // the shortest line segment between the two rays - // calculate the vector between the middle of the two endpoints and return its magnitude - FVector ptM = (ptL + ptR) / 2.0f; // middle point between two endpoints of shortest-line-segment - FVector oM = (L0 + R0) / 2.0f; // midpoint between two (L & R) origins - return ptM - oM; // Combined ray between midpoints of endpoints -} - -static void GenerateSquareImage(TArray &Src, const float Size, const FColor &Colour) -{ - // Used to initialize any grid-based image onto an array - Src.Reserve(Size * Size); // allocate width*height space - for (int i = 0; i < Size; i++) - { - for (int j = 0; j < Size; j++) - { - // RGBA colours - FColor PixelColour; - const int Thickness = Size / 10; - bool LeftOrRight = (i < Thickness || i > Size - Thickness); - bool TopOrBottom = (j < Thickness || j > Size - Thickness); - if (LeftOrRight || TopOrBottom) - PixelColour = Colour; // (semi-opaque red) - else - PixelColour = FColor(0, 0, 0, 0); // (fully transparent inside) - Src.Add(PixelColour); - } - } -} - -static void GenerateCrosshairImage(TArray &Src, const float Size, const FColor &Colour) -{ - // Used to initialize any bitmap-based image that will be used as a - Src.Reserve(Size * Size); // allocate width*height space - for (int i = 0; i < Size; i++) - { - for (int j = 0; j < Size; j++) - { - // RGBA colours - FColor PixelColour; - - const int x = i - Size / 2; - const int y = j - Size / 2; - const float Radius = Size / 3.f; - const int RadThickness = 3 * Size / 100.f; - const int LineLen = 4 * RadThickness; - const float RadLo = Radius - LineLen; - const float RadHi = Radius + LineLen; - bool BelowRadius = (FMath::Square(x) + FMath::Square(y) <= FMath::Square(Radius + RadThickness)); - bool AboveRadius = (FMath::Square(x) + FMath::Square(y) >= FMath::Square(Radius - RadThickness)); - if (BelowRadius && AboveRadius) - PixelColour = Colour; // (semi-opaque red) - else - { - // Draw little rectangular markers - const bool RightMarker = (RadLo < x && x < RadHi) && std::fabs(y) < RadThickness; - const bool LeftMarker = (RadLo < -x && -x < RadHi) && std::fabs(y) < RadThickness; - const bool TopMarker = (RadLo < y && y < RadHi) && std::fabs(x) < RadThickness; - const bool BottomMarker = (RadLo < -y && -y < RadHi) && std::fabs(x) < RadThickness; - if (RightMarker || LeftMarker || TopMarker || BottomMarker) - PixelColour = Colour; // (semi-opaque red) - else - PixelColour = FColor(0, 0, 0, 0); // (fully transparent inside) - } - - Src.Add(PixelColour); - } - } -} - -static float CmPerSecondToXPerHour(const bool MilesPerHour) -{ - // convert cm/s to X/h - // X = miles if MilesPerHour == true, else X = KM - if (MilesPerHour) - { - return 0.0223694f; - } - return 0.036f; -} - -static void SaveFrameToDisk(UTextureRenderTarget2D &RenderTarget, const FString &FilePath, const bool FileFormatJPG) -{ - FTextureRenderTargetResource *RTResource = RenderTarget.GameThread_GetRenderTargetResource(); - const size_t H = RenderTarget.GetSurfaceHeight(); - const size_t W = RenderTarget.GetSurfaceWidth(); - const FIntPoint DestSize(W, H); - TImagePixelData PixelData(DestSize); - - // Read pixels into array - // heavily inspired by Carla's Carla/Sensor/PixelReader.cpp:WritePixelsToArray function - TArray Pixels; - Pixels.AddUninitialized(H * W); - FReadSurfaceDataFlags ReadPixelFlags(RCM_UNorm); - ReadPixelFlags.SetLinearToGamma(true); - if (RTResource == nullptr) - { - LOG_ERROR("Missing render target!"); - return; - } - if (!RTResource->ReadPixels(Pixels, ReadPixelFlags)) - LOG_ERROR("Unable to read pixels!"); - - // dump pixel array to disk - PixelData.Pixels = Pixels; - TUniquePtr ImageTask = MakeUnique(); - ImageTask->PixelData = MakeUnique>(PixelData); - ImageTask->Filename = FilePath; - // LOG("Saving screenshot to %s", *FilePath); - ImageTask->Format = FileFormatJPG ? EImageFormat::JPEG : EImageFormat::PNG; // lower quality, less storage - ImageTask->CompressionQuality = (int32)EImageCompressionQuality::Default; - ImageTask->bOverwriteFile = true; - ImageTask->PixelPreProcessors.Add(TAsyncAlphaWrite(255)); - FHighResScreenshotConfig &HighResScreenshotConfig = GetHighResScreenshotConfig(); - HighResScreenshotConfig.ImageWriteQueue->Enqueue(MoveTemp(ImageTask)); -} - -static UTexture2D *CreateTexture2DFromArray(const TArray &Contents) -{ - const size_t Size = std::sqrt(Contents.Num()); - ensure(Size * Size == Contents.Num()); - UTexture2D *Texture = UTexture2D::CreateTransient(Size, Size, PF_B8G8R8A8); - void *TextureData = Texture->PlatformData->Mips[0].BulkData.Lock(LOCK_READ_WRITE); - FMemory::Memcpy(TextureData, Contents.GetData(), 4 * Contents.Num()); - Texture->PlatformData->Mips[0].BulkData.Unlock(); - Texture->UpdateResource(); - check(Texture); - return Texture; -} - -/// ========================================== /// -/// ----------------:SHADER:------------------ /// -/// ========================================== /// - -static FSensorShader InitSemanticSegmentationShader(class UObject *Parent = nullptr) -{ - const FString Path = - "Material'/Carla/PostProcessingMaterials/DReyeVR_SemanticSegmentation.DReyeVR_SemanticSegmentation'"; - UMaterial *MaterialFound = LoadObject(nullptr, *Path); - check(MaterialFound != nullptr); - UMaterialInstanceDynamic *SemanticSegmentationMaterial = - UMaterialInstanceDynamic::Create(MaterialFound, Parent, FName(TEXT("DReyeVR_SemanticSegmentationShader"))); - - // create the array used for tag-colour segmentation - TArray TextureSrc; - const size_t NumTags = carla::image::CityScapesPalette::GetNumberOfTags(); - const int TexSize = 256; // making this array a 16x16=256 length 2d array that holds the raw colours - TextureSrc.Reserve(TexSize); - for (int i = 0; i < TexSize; i++) - { - if (i < NumTags) // fill the first n (NumTags) with the tags directly - { - auto Colour = carla::image::CityScapesPalette::GetColor(i); - TextureSrc.Add(FColor(Colour[0], Colour[1], Colour[2], 255)); - } - else // fill the overflow with black - TextureSrc.Add(FColor::Black); - } - - UTexture2D *TagColourTexture = CreateTexture2DFromArray(TextureSrc); - - // update the tagger-colour matrix param so all the sampled colours are from the CITYSCAPES_PALETTE_MAP - // defined in LibCarla/source/carla/image/CityScapesPalette.h - SemanticSegmentationMaterial->SetTextureParameterValue("TagColours", TagColourTexture); - return FSensorShader{SemanticSegmentationMaterial, 1.f}; -} - -static FSensorShader InitDepthShader(class UObject *Parent = nullptr) -{ - const FString Path = "Material'/Carla/PostProcessingMaterials/DReyeVR_DepthEffect.DReyeVR_DepthEffect'"; - UMaterial *MaterialFound = LoadObject(nullptr, *Path); - check(MaterialFound != nullptr); - UMaterialInstanceDynamic *DepthMaterial = - UMaterialInstanceDynamic::Create(MaterialFound, Parent, FName(TEXT("DReyeVR_DepthShader"))); - return FSensorShader{DepthMaterial, 1.f}; -} - -/// ========================================== /// -/// ------------:POSTPROCESSING:-------------- /// -/// ========================================== /// - -// collection of shader factory functions so shaders can be easily regenerated at runtime (useful when GC'd) -static std::vector> ShaderFactory = {}; - -static size_t GetNumberOfShaders() -{ - return ShaderFactory.size(); -} - -static FPostProcessSettings CreatePostProcessingParams(const std::vector &Shaders) -{ - // modifying from here: https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/FPostProcessSettings/ - FPostProcessSettings PP; - PP.bOverride_VignetteIntensity = true; - PP.VignetteIntensity = GeneralParams.Get("CameraParams", "VignetteIntensity"); - - PP.bOverride_ScreenPercentage = true; - PP.ScreenPercentage = GeneralParams.Get("CameraParams", "ScreenPercentage"); - - PP.bOverride_BloomIntensity = true; - PP.BloomIntensity = GeneralParams.Get("CameraParams", "BloomIntensity"); - - PP.bOverride_SceneFringeIntensity = true; - PP.SceneFringeIntensity = GeneralParams.Get("CameraParams", "SceneFringeIntensity"); - - PP.bOverride_LensFlareIntensity = true; - PP.LensFlareIntensity = GeneralParams.Get("CameraParams", "LensFlareIntensity"); - - PP.bOverride_GrainIntensity = true; - PP.GrainIntensity = GeneralParams.Get("CameraParams", "GrainIntensity"); - - PP.bOverride_MotionBlurAmount = true; - PP.MotionBlurAmount = GeneralParams.Get("CameraParams", "MotionBlurIntensity"); - - // append shaders to this postprocess effect - for (const FSensorShader &ShaderInfo : Shaders) - { - ensure(ShaderInfo.PostProcessMaterial != nullptr); - PP.AddBlendable(ShaderInfo.PostProcessMaterial, ShaderInfo.Weight); - } - - return PP; -} - -static void InitShaderFactory() -{ - // initializes the static (global) ShaderFactory container with the factory functions - // to generate the shaders defined here. - - ShaderFactory.clear(); // clear all old shaders - ShaderFactory = {}; -// helper lambda #define to reduce boilerplate code -#define SHADER_LAMBDA(x) []() { return CreatePostProcessingParams(x); } - // denote the order of the shaders that we will use as lambdas to create their shader - ShaderFactory.push_back(SHADER_LAMBDA({})); // rgb (no postprocessing) - ShaderFactory.push_back(SHADER_LAMBDA({InitSemanticSegmentationShader()})); // semantics - ShaderFactory.push_back(SHADER_LAMBDA({InitDepthShader()})); // depth - - /// TODO: add more shaders here - /// TODO: use enum for shaders -} - -static FPostProcessSettings CreatePostProcessingEffect(size_t Idx) -{ - if (GetNumberOfShaders() == 0) - { - InitShaderFactory(); - ensure(GetNumberOfShaders() > 0); - } - // check the index is valid, and call the shader factory function to be used immediately - Idx = std::min(Idx, GetNumberOfShaders() - 1); - /// NOTE: this can be slow (as it needs to load objects (shaders) from disk and potentially recompile them), - // so be wary of using this in a performance-critical section - return ShaderFactory[Idx](); -} - -static FHitResult SimpleRayTrace(const UWorld *World, const FVector &Start, const FVector &End, - const std::vector &Ignored = {}) -{ - // run a trace from the start to the end to sample visibility channel - FCollisionQueryParams TraceParam; - TraceParam = FCollisionQueryParams(FName("RayTrace"), true); - for (const AActor *A : Ignored) - { - TraceParam.AddIgnoredActor(A); - } - TraceParam.bTraceComplex = true; - TraceParam.bReturnPhysicalMaterial = false; - FHitResult Hit(EForceInit::ForceInit); - World->LineTraceSingleByChannel(Hit, Start, End, ECC_Visibility, TraceParam); - DrawDebugLine(World, - Start, // start line - End, // end line - FColor::Green, false, -1, 0, 1); - return Hit; -} - +#ifndef DREYEVR_UTIL +#define DREYEVR_UTIL + +#include "Carla/Sensor/ShaderBasedSensor.h" // FSensorShader +#include "ConfigFile.h" // ConfigFile class +#include "CoreMinimal.h" +#include "Engine/Texture2D.h" // UTexture2D +#include "HighResScreenshot.h" // FHighResScreenshotConfig +#include "ImageWriteQueue.h" // TImagePixelData +#include "ImageWriteTask.h" // FImageWriteTask +#include // CityScapesPalette + +// instead of vehicle.dreyevr.model3 or sensor.dreyevr.ego_sensor, we use "harplab" for category +// => harplab.dreyevr_vehicle.model3 & harplab.dreyevr_sensor.ego_sensor +// in PythonAPI use world.get_actors().filter("harplab.dreyevr_vehicle.*") or +// world.get_blueprint_library().filter("harplab.dreyevr_sensor.*") and you won't accidentally get these actors when +// performing filter("vehicle.*") or filter("sensor.*") +static const FString DReyeVRCategory("HarpLab"); + +template +T *SafePtrGet(const FString &Name, TWeakObjectPtr &Ptr, const std::function &RemedyFunction) +{ + if (Ptr.IsValid()) + return Ptr.Get(); + // object was destroyed! possibly by external process (ex. map change) + if (!Ptr.IsExplicitlyNull()) + { // dangling pointer!! + LOG_WARN("Dangling pointer \"%s\" (%p) is invalid! Attempting to remedy", Ptr.Get(), *Name); + } + RemedyFunction(); + // try to remedy + if (Ptr.IsValid()) + return Ptr.Get(); + LOG_ERROR("Unable to remedy (%s)", *Name); + return nullptr; +} + +static FString UE4RefToClassPath(const FString &UE4ReferencePath) +{ + // converts (reference) strings of the type "Type'/Game/PATH/asset.asset'" to "/Game/PATH/asset.asset_C" + // for use in ConstructorHelpers::FClassFinder + const FString NoneStr = FString(""); // replace with empty string ("") + const FString SingleQuoteStr = FString("'"); + // find the start position in the string (ignore the type (Blueprint, SkeletalMesh, Skeleton, AnimBP, etc.)) + const int StartPos = UE4ReferencePath.Find(SingleQuoteStr, ESearchCase::CaseSensitive, ESearchDir::FromStart, 0); + FString Ret = UE4ReferencePath.RightChop(StartPos); + Ret.ReplaceInline(*SingleQuoteStr, *NoneStr, ESearchCase::CaseSensitive); + Ret += "_C"; // to force class type suffix + return Ret; +} + +static FString CleanNameForDReyeVR(const FString &RawName) +{ + // should be equivalent to GetClass()->GetDisplayNameText().ToString() + // for our purposes (spawning different type EgoVehicles) + FString CleanName = RawName; + CleanName.RemoveSpacesInline(); // one word +#define DELETE_INLINE(x) CleanName.ReplaceInline(*FString(x), *FString(""), ESearchCase::CaseSensitive); + DELETE_INLINE("BP_"); // might start w/ BP_XYZ + DELETE_INLINE("BP"); // might start w/ BPXYZ + DELETE_INLINE("_C"); // might end with _C + DELETE_INLINE("Ego"); // default object is EgoVehicle + DELETE_INLINE("SKEL_"); // skeleton class starts with SKEL_ + + return CleanName; +} + +static FActorDefinition FindDefnInRegistry(const UCarlaEpisode *Episode, const UClass *ClassType) +{ + // searches through the registers actors (definitions) to find one with the matching class type + check(Episode != nullptr); + + FActorDefinition FoundDefinition; + bool bFoundDef = false; + for (const auto &Defn : Episode->GetActorDefinitions()) + { + if (Defn.Class == ClassType) + { + LOG("Found appropriate definition registered at UId: %d as \"%s\"", Defn.UId, *Defn.Id); + FoundDefinition = Defn; + bFoundDef = true; + break; // assumes the first is the ONLY one matching this class (Ex. EgoVehicle, EgoSensor) + } + } + if (!bFoundDef) + { + LOG_ERROR("Unable to find appropriate definition in registry!"); + } + return FoundDefinition; +} + +static FActorDefinition FindEgoVehicleDefinition(const UCarlaEpisode *Episode) +{ + + FString LoadVehicle = "TeslaM3"; // default vehicle + if (GeneralParams.Get("EgoVehicle", "VehicleType", LoadVehicle)) + { + LOG("Loading new default EgoVehicle: \"%s\"", *LoadVehicle); + } + // searches through the registers actors (definitions) to find one with the matching class type + check(Episode != nullptr); + + FActorDefinition FoundDefinition; + bool bFoundDef = false; + for (const auto &Defn : Episode->GetActorDefinitions()) + { + const auto &LowerId = Defn.Id.ToLower(); // perform string comparisons on lowercase (ignore case) + // contains both the DReyeVR category (HarpLab) and specific EgoVehicle + if (LowerId.Contains(DReyeVRCategory.ToLower()) && LowerId.Contains(LoadVehicle.ToLower())) + { + LOG("Found appropriate definition for \"%s\" registered at UId: %d as \"%s\"", // + *LoadVehicle, Defn.UId, *Defn.Id); + FoundDefinition = Defn; + bFoundDef = true; + break; // assumes the first is the ONLY one matching this class (Ex. EgoVehicle, EgoSensor) + } + } + if (!bFoundDef) + { + LOG_ERROR("Unable to find appropriate definition in registry!"); + } + return FoundDefinition; +} + +static FVector ComputeClosestToRayIntersection(const FVector &L0, const FVector &LDir, const FVector &R0, + const FVector &RDir) +{ + // Recall that a 'line' can be defined as (L = origin(0) + t * direction(Dir)) for some t + + // Calculating shortest line segment intersecting both lines + // Implementation sourced from http://paulbourke.net/geometry/pointlineplane/ + FVector L0R0 = L0 - R0; // segment between L origin and R origin + if (L0R0.Size() == 0.f) // same origin + return FVector::ZeroVector; + const float epsilon = 0.00001f; // small positive real number + + // Calculating dot-product equation to find perpendicular shortest-line-segment + float d1343 = L0R0.X * RDir.X + L0R0.Y * RDir.Y + L0R0.Z * RDir.Z; + float d4321 = RDir.X * LDir.X + RDir.Y * LDir.Y + RDir.Z * LDir.Z; + float d1321 = L0R0.X * LDir.X + L0R0.Y * LDir.Y + L0R0.Z * LDir.Z; + float d4343 = RDir.X * RDir.X + RDir.Y * RDir.Y + RDir.Z * RDir.Z; + float d2121 = LDir.X * LDir.X + LDir.Y * LDir.Y + LDir.Z * LDir.Z; + float denom = d2121 * d4343 - d4321 * d4321; + if (abs(denom) < epsilon) + return FVector::ZeroVector; // no intersection, would cause div by 0 err + float numer = d1343 * d4321 - d1321 * d4343; + + // calculate scalars (mu) that scale the unit direction XDir to reach the desired points + float muL = numer / denom; // variable scale of direction vector for LEFT ray + float muR = (d1343 + d4321 * (muL)) / d4343; // variable scale of direction vector for RIGHT ray + + // calculate the points on the respective rays that create the intersecting line + FVector ptL = L0 + muL * LDir; // the point on the Left ray + FVector ptR = R0 + muR * RDir; // the point on the Right ray + + FVector ShortestLineSeg = ptL - ptR; // the shortest line segment between the two rays + // calculate the vector between the middle of the two endpoints and return its magnitude + FVector ptM = (ptL + ptR) / 2.0f; // middle point between two endpoints of shortest-line-segment + FVector oM = (L0 + R0) / 2.0f; // midpoint between two (L & R) origins + return ptM - oM; // Combined ray between midpoints of endpoints +} + +static void GenerateSquareImage(TArray &Src, const float Size, const FColor &Colour) +{ + // Used to initialize any grid-based image onto an array + Src.Reserve(Size * Size); // allocate width*height space + for (int i = 0; i < Size; i++) + { + for (int j = 0; j < Size; j++) + { + // RGBA colours + FColor PixelColour; + const int Thickness = Size / 10; + bool LeftOrRight = (i < Thickness || i > Size - Thickness); + bool TopOrBottom = (j < Thickness || j > Size - Thickness); + if (LeftOrRight || TopOrBottom) + PixelColour = Colour; // (semi-opaque red) + else + PixelColour = FColor(0, 0, 0, 0); // (fully transparent inside) + Src.Add(PixelColour); + } + } +} + +static void GenerateCrosshairImage(TArray &Src, const float Size, const FColor &Colour) +{ + // Used to initialize any bitmap-based image that will be used as a + Src.Reserve(Size * Size); // allocate width*height space + for (int i = 0; i < Size; i++) + { + for (int j = 0; j < Size; j++) + { + // RGBA colours + FColor PixelColour; + + const int x = i - Size / 2; + const int y = j - Size / 2; + const float Radius = Size / 3.f; + const int RadThickness = 3 * Size / 100.f; + const int LineLen = 4 * RadThickness; + const float RadLo = Radius - LineLen; + const float RadHi = Radius + LineLen; + bool BelowRadius = (FMath::Square(x) + FMath::Square(y) <= FMath::Square(Radius + RadThickness)); + bool AboveRadius = (FMath::Square(x) + FMath::Square(y) >= FMath::Square(Radius - RadThickness)); + if (BelowRadius && AboveRadius) + PixelColour = Colour; // (semi-opaque red) + else + { + // Draw little rectangular markers + const bool RightMarker = (RadLo < x && x < RadHi) && std::fabs(y) < RadThickness; + const bool LeftMarker = (RadLo < -x && -x < RadHi) && std::fabs(y) < RadThickness; + const bool TopMarker = (RadLo < y && y < RadHi) && std::fabs(x) < RadThickness; + const bool BottomMarker = (RadLo < -y && -y < RadHi) && std::fabs(x) < RadThickness; + if (RightMarker || LeftMarker || TopMarker || BottomMarker) + PixelColour = Colour; // (semi-opaque red) + else + PixelColour = FColor(0, 0, 0, 0); // (fully transparent inside) + } + + Src.Add(PixelColour); + } + } +} + +static float CmPerSecondToXPerHour(const bool MilesPerHour) +{ + // convert cm/s to X/h + // X = miles if MilesPerHour == true, else X = KM + if (MilesPerHour) + { + return 0.0223694f; + } + return 0.036f; +} + +static void SaveFrameToDisk(UTextureRenderTarget2D &RenderTarget, const FString &FilePath, const bool FileFormatJPG) +{ + FTextureRenderTargetResource *RTResource = RenderTarget.GameThread_GetRenderTargetResource(); + const size_t H = RenderTarget.GetSurfaceHeight(); + const size_t W = RenderTarget.GetSurfaceWidth(); + const FIntPoint DestSize(W, H); + TImagePixelData PixelData(DestSize); + + // Read pixels into array + // heavily inspired by Carla's Carla/Sensor/PixelReader.cpp:WritePixelsToArray function + TArray Pixels; + Pixels.AddUninitialized(H * W); + FReadSurfaceDataFlags ReadPixelFlags(RCM_UNorm); + ReadPixelFlags.SetLinearToGamma(true); + if (RTResource == nullptr) + { + LOG_ERROR("Missing render target!"); + return; + } + if (!RTResource->ReadPixels(Pixels, ReadPixelFlags)) + LOG_ERROR("Unable to read pixels!"); + + // dump pixel array to disk + PixelData.Pixels = Pixels; + TUniquePtr ImageTask = MakeUnique(); + ImageTask->PixelData = MakeUnique>(PixelData); + ImageTask->Filename = FilePath; + // LOG("Saving screenshot to %s", *FilePath); + ImageTask->Format = FileFormatJPG ? EImageFormat::JPEG : EImageFormat::PNG; // lower quality, less storage + ImageTask->CompressionQuality = (int32)EImageCompressionQuality::Default; + ImageTask->bOverwriteFile = true; + ImageTask->PixelPreProcessors.Add(TAsyncAlphaWrite(255)); + FHighResScreenshotConfig &HighResScreenshotConfig = GetHighResScreenshotConfig(); + HighResScreenshotConfig.ImageWriteQueue->Enqueue(MoveTemp(ImageTask)); +} + +static UTexture2D *CreateTexture2DFromArray(const TArray &Contents) +{ + const size_t Size = std::sqrt(Contents.Num()); + ensure(Size * Size == Contents.Num()); + UTexture2D *Texture = UTexture2D::CreateTransient(Size, Size, PF_B8G8R8A8); + void *TextureData = Texture->PlatformData->Mips[0].BulkData.Lock(LOCK_READ_WRITE); + FMemory::Memcpy(TextureData, Contents.GetData(), 4 * Contents.Num()); + Texture->PlatformData->Mips[0].BulkData.Unlock(); + Texture->UpdateResource(); + check(Texture); + return Texture; +} + +/// ========================================== /// +/// ----------------:SHADER:------------------ /// +/// ========================================== /// + +static FSensorShader InitSemanticSegmentationShader(class UObject *Parent = nullptr) +{ + const FString Path = + "Material'/Carla/PostProcessingMaterials/DReyeVR_SemanticSegmentation.DReyeVR_SemanticSegmentation'"; + UMaterial *MaterialFound = LoadObject(nullptr, *Path); + check(MaterialFound != nullptr); + UMaterialInstanceDynamic *SemanticSegmentationMaterial = + UMaterialInstanceDynamic::Create(MaterialFound, Parent, FName(TEXT("DReyeVR_SemanticSegmentationShader"))); + + // create the array used for tag-colour segmentation + TArray TextureSrc; + const size_t NumTags = carla::image::CityScapesPalette::GetNumberOfTags(); + const int TexSize = 256; // making this array a 16x16=256 length 2d array that holds the raw colours + TextureSrc.Reserve(TexSize); + for (int i = 0; i < TexSize; i++) + { + if (i < NumTags) // fill the first n (NumTags) with the tags directly + { + auto Colour = carla::image::CityScapesPalette::GetColor(i); + TextureSrc.Add(FColor(Colour[0], Colour[1], Colour[2], 255)); + } + else // fill the overflow with black + TextureSrc.Add(FColor::Black); + } + + UTexture2D *TagColourTexture = CreateTexture2DFromArray(TextureSrc); + + // update the tagger-colour matrix param so all the sampled colours are from the CITYSCAPES_PALETTE_MAP + // defined in LibCarla/source/carla/image/CityScapesPalette.h + SemanticSegmentationMaterial->SetTextureParameterValue("TagColours", TagColourTexture); + return FSensorShader{SemanticSegmentationMaterial, 1.f}; +} + +static FSensorShader InitDepthShader(class UObject *Parent = nullptr) +{ + const FString Path = "Material'/Carla/PostProcessingMaterials/DReyeVR_DepthEffect.DReyeVR_DepthEffect'"; + UMaterial *MaterialFound = LoadObject(nullptr, *Path); + check(MaterialFound != nullptr); + UMaterialInstanceDynamic *DepthMaterial = + UMaterialInstanceDynamic::Create(MaterialFound, Parent, FName(TEXT("DReyeVR_DepthShader"))); + return FSensorShader{DepthMaterial, 1.f}; +} + +/// ========================================== /// +/// ------------:POSTPROCESSING:-------------- /// +/// ========================================== /// + +// collection of shader factory functions so shaders can be easily regenerated at runtime (useful when GC'd) +static std::vector> ShaderFactory = {}; + +static size_t GetNumberOfShaders() +{ + return ShaderFactory.size(); +} + +static FPostProcessSettings CreatePostProcessingParams(const std::vector &Shaders) +{ + // modifying from here: https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/FPostProcessSettings/ + FPostProcessSettings PP; + PP.bOverride_VignetteIntensity = true; + PP.VignetteIntensity = GeneralParams.Get("CameraParams", "VignetteIntensity"); + + PP.bOverride_ScreenPercentage = true; + PP.ScreenPercentage = GeneralParams.Get("CameraParams", "ScreenPercentage"); + + PP.bOverride_BloomIntensity = true; + PP.BloomIntensity = GeneralParams.Get("CameraParams", "BloomIntensity"); + + PP.bOverride_SceneFringeIntensity = true; + PP.SceneFringeIntensity = GeneralParams.Get("CameraParams", "SceneFringeIntensity"); + + PP.bOverride_LensFlareIntensity = true; + PP.LensFlareIntensity = GeneralParams.Get("CameraParams", "LensFlareIntensity"); + + PP.bOverride_GrainIntensity = true; + PP.GrainIntensity = GeneralParams.Get("CameraParams", "GrainIntensity"); + + PP.bOverride_MotionBlurAmount = true; + PP.MotionBlurAmount = GeneralParams.Get("CameraParams", "MotionBlurIntensity"); + + // append shaders to this postprocess effect + for (const FSensorShader &ShaderInfo : Shaders) + { + ensure(ShaderInfo.PostProcessMaterial != nullptr); + PP.AddBlendable(ShaderInfo.PostProcessMaterial, ShaderInfo.Weight); + } + + return PP; +} + +static void InitShaderFactory() +{ + // initializes the static (global) ShaderFactory container with the factory functions + // to generate the shaders defined here. + + ShaderFactory.clear(); // clear all old shaders + ShaderFactory = {}; +// helper lambda #define to reduce boilerplate code +#define SHADER_LAMBDA(x) []() { return CreatePostProcessingParams(x); } + // denote the order of the shaders that we will use as lambdas to create their shader + ShaderFactory.push_back(SHADER_LAMBDA({})); // rgb (no postprocessing) + ShaderFactory.push_back(SHADER_LAMBDA({InitSemanticSegmentationShader()})); // semantics + ShaderFactory.push_back(SHADER_LAMBDA({InitDepthShader()})); // depth + + /// TODO: add more shaders here + /// TODO: use enum for shaders +} + +static FPostProcessSettings CreatePostProcessingEffect(size_t Idx) +{ + if (GetNumberOfShaders() == 0) + { + InitShaderFactory(); + ensure(GetNumberOfShaders() > 0); + } + // check the index is valid, and call the shader factory function to be used immediately + Idx = std::min(Idx, GetNumberOfShaders() - 1); + /// NOTE: this can be slow (as it needs to load objects (shaders) from disk and potentially recompile them), + // so be wary of using this in a performance-critical section + return ShaderFactory[Idx](); +} + +static FHitResult SimpleRayTrace(const UWorld *World, const FVector &Start, const FVector &End, + const std::vector &Ignored = {}) +{ + // run a trace from the start to the end to sample visibility channel + FCollisionQueryParams TraceParam; + TraceParam = FCollisionQueryParams(FName("RayTrace"), true); + for (const AActor *A : Ignored) + { + TraceParam.AddIgnoredActor(A); + } + TraceParam.bTraceComplex = true; + TraceParam.bReturnPhysicalMaterial = false; + FHitResult Hit(EForceInit::ForceInit); + World->LineTraceSingleByChannel(Hit, Start, End, ECC_Visibility, TraceParam); + DrawDebugLine(World, + Start, // start line + End, // end line + FColor::Green, false, -1, 0, 1); + return Hit; +} + #endif \ No newline at end of file diff --git a/DReyeVR/EgoInputs.cpp b/DReyeVR/EgoInputs.cpp index efb3ac2..b205134 100644 --- a/DReyeVR/EgoInputs.cpp +++ b/DReyeVR/EgoInputs.cpp @@ -1,278 +1,278 @@ -#include "EgoVehicle.h" -#include "Math/NumericLimits.h" // TNumericLimits::Max -#include // std::string, std::wstring - -////////////////:INPUTS://////////////// -/// NOTE: Here we define all the Input functions for the EgoVehicle just to keep them -// from cluttering the EgoVehcile.cpp file - -const DReyeVR::UserInputs &AEgoVehicle::GetVehicleInputs() const -{ - return VehicleInputs; -} - -const FTransform &AEgoVehicle::GetCameraRootPose() const -{ - return CameraPoseOffset; -} - -void AEgoVehicle::CameraFwd() -{ - // move by (1, 0, 0) - CameraPositionAdjust(FVector::ForwardVector); -} - -void AEgoVehicle::CameraBack() -{ - // move by (-1, 0, 0) - CameraPositionAdjust(FVector::BackwardVector); -} - -void AEgoVehicle::CameraLeft() -{ - // move by (0, -1, 0) - CameraPositionAdjust(FVector::LeftVector); -} - -void AEgoVehicle::CameraRight() -{ - // move by (0, 1, 0) - CameraPositionAdjust(FVector::RightVector); -} - -void AEgoVehicle::CameraUp() -{ - // move by (0, 0, 1) - CameraPositionAdjust(FVector::UpVector); -} - -void AEgoVehicle::CameraDown() -{ - // move by (0, 0, -1) - CameraPositionAdjust(FVector::DownVector); -} - -void AEgoVehicle::CameraPositionAdjust(const FVector &Disp) -{ - if (Disp.Equals(FVector::ZeroVector, 0.0001f)) - return; - // preserves adjustment even after changing view - CameraPoseOffset.SetLocation(CameraPoseOffset.GetLocation() + Disp); - VRCameraRoot->SetRelativeLocation(CameraPose.GetLocation() + CameraPoseOffset.GetLocation()); - /// TODO: account for rotation? scale? -} - -void AEgoVehicle::CameraPositionAdjust(bool bForward, bool bRight, bool bBackwards, bool bLeft, bool bUp, bool bDown) -{ - // add the corresponding directions according to the adjustment booleans - const FVector Disp = FVector::ForwardVector * bForward + FVector::RightVector * bRight + - FVector::BackwardVector * bBackwards + FVector::LeftVector * bLeft + FVector::UpVector * bUp + - FVector::DownVector * bDown; - CameraPositionAdjust(Disp); -} - -void AEgoVehicle::PressNextCameraView() -{ - if (!bCanPressNextCameraView) - return; - bCanPressNextCameraView = false; - NextCameraView(); -}; -void AEgoVehicle::ReleaseNextCameraView() -{ - bCanPressNextCameraView = true; -}; - -void AEgoVehicle::PressPrevCameraView() -{ - if (!bCanPressPrevCameraView) - return; - bCanPressPrevCameraView = false; - PrevCameraView(); -}; -void AEgoVehicle::ReleasePrevCameraView() -{ - bCanPressPrevCameraView = true; -}; - -void AEgoVehicle::NextCameraView() -{ - if (CameraPoseKeys.Num() == 0) - return; - CurrentCameraTransformIdx = (CurrentCameraTransformIdx + 1) % (CameraPoseKeys.Num()); - const FString &Key = CameraPoseKeys[CurrentCameraTransformIdx]; - LOG("Switching manually to next camera view: \"%s\"", *Key); - SetCameraRootPose(CurrentCameraTransformIdx); -} - -void AEgoVehicle::PrevCameraView() -{ - if (CameraPoseKeys.Num() == 0) - return; - if (CurrentCameraTransformIdx == 0) - CurrentCameraTransformIdx = CameraPoseKeys.Num(); - CurrentCameraTransformIdx--; - const FString &Key = CameraPoseKeys[CurrentCameraTransformIdx]; - LOG("Switching manually to prev camera view: \"%s\"", *Key); - SetCameraRootPose(CurrentCameraTransformIdx); -} - -void AEgoVehicle::AddSteering(const float SteeringInput) -{ - float ScaledSteeringInput = this->ScaleSteeringInput * SteeringInput; - // assign to input struct - VehicleInputs.Steering += ScaledSteeringInput; -} - -void AEgoVehicle::AddThrottle(const float ThrottleInput) -{ - float ScaledThrottleInput = this->ScaleThrottleInput * ThrottleInput; - - // apply new light state - FVehicleLightState Lights = GetVehicleLightState(); - Lights.Reverse = false; - Lights.Brake = false; - SetVehicleLightState(Lights); - - // assign to input struct - VehicleInputs.Throttle += ScaledThrottleInput; -} - -void AEgoVehicle::AddBrake(const float BrakeInput) -{ - float ScaledBrakeInput = this->ScaleBrakeInput * BrakeInput; - - // apply new light state - FVehicleLightState Lights = GetVehicleLightState(); - Lights.Reverse = false; - Lights.Brake = true; - SetVehicleLightState(Lights); - - // assign to input struct - VehicleInputs.Brake += ScaledBrakeInput; -} - -void AEgoVehicle::PressReverse() -{ - if (!bCanPressReverse) - return; - bCanPressReverse = false; // don't press again until release - bReverse = !bReverse; - - // negate to toggle bw + (forwards) and - (backwards) - // const int CurrentGear = this->GetVehicleMovementComponent()->GetTargetGear(); - // int NewGear = -1; // for when parked - // if (CurrentGear != 0) - // { - // NewGear = bReverse ? -1 * std::abs(CurrentGear) : std::abs(CurrentGear); // negative => backwards - // } - // this->GetVehicleMovementComponent()->SetTargetGear(NewGear, true); // UE4 control - - // apply new light state - FVehicleLightState Lights = this->GetVehicleLightState(); - Lights.Reverse = this->bReverse; - this->SetVehicleLightState(Lights); - - // LOG("Toggle Reverse"); - // assign to input struct - VehicleInputs.ToggledReverse = true; - - PlayGearShiftSound(); - - // call to parent - SetReverse(bReverse); -} - -void AEgoVehicle::ReleaseReverse() -{ - VehicleInputs.ToggledReverse = false; - bCanPressReverse = true; -} - -void AEgoVehicle::PressTurnSignalR() -{ - if (!bCanPressTurnSignalR) - return; - bCanPressTurnSignalR = false; // don't press again until release - // store in local input container - VehicleInputs.TurnSignalRight = true; - - if (bEnableTurnSignalAction) - { - // apply new light state - FVehicleLightState Lights = this->GetVehicleLightState(); - Lights.RightBlinker = true; - Lights.LeftBlinker = false; - this->SetVehicleLightState(Lights); - // play sound - this->PlayTurnSignalSound(); - } - RightSignalTimeToDie = TNumericLimits::Max(); // wait until button released (+inf until then) - LeftSignalTimeToDie = 0.f; // immediately stop left signal -} - -void AEgoVehicle::ReleaseTurnSignalR() -{ - if (bCanPressTurnSignalR) - return; - VehicleInputs.TurnSignalRight = false; - RightSignalTimeToDie = GetWorld()->GetTimeSeconds() + this->TurnSignalDuration; // reset counter - bCanPressTurnSignalR = true; -} - -void AEgoVehicle::PressTurnSignalL() -{ - if (!bCanPressTurnSignalL) - return; - bCanPressTurnSignalL = false; // don't press again until release - // store in local input container - VehicleInputs.TurnSignalLeft = true; - - if (bEnableTurnSignalAction) - { - // apply new light state - FVehicleLightState Lights = this->GetVehicleLightState(); - Lights.RightBlinker = false; - Lights.LeftBlinker = true; - this->SetVehicleLightState(Lights); - // play sound - this->PlayTurnSignalSound(); - } - RightSignalTimeToDie = 0.f; // immediately stop right signal - LeftSignalTimeToDie = TNumericLimits::Max(); // wait until button released (+inf until then) -} - -void AEgoVehicle::ReleaseTurnSignalL() -{ - if (bCanPressTurnSignalL) - return; - VehicleInputs.TurnSignalLeft = false; - LeftSignalTimeToDie = GetWorld()->GetTimeSeconds() + this->TurnSignalDuration; // reset counter - bCanPressTurnSignalL = true; -} - -void AEgoVehicle::TickVehicleInputs() -{ - FVehicleControl LastAppliedControl = GetVehicleControl(); - - int bIncludeLast = static_cast(GetAutopilotStatus()); - FVehicleControl ManualInputs; - // only include LastAppliedControl when autopilot is running (bc it would have flushed earlier this tick) - ManualInputs.Steer = VehicleInputs.Steering + bIncludeLast * LastAppliedControl.Steer; - ManualInputs.Brake = VehicleInputs.Brake + bIncludeLast * LastAppliedControl.Brake; - ManualInputs.Throttle = VehicleInputs.Throttle + bIncludeLast * LastAppliedControl.Throttle; - ManualInputs.bReverse = bReverse; - - // apply inputs to this vehicle only when either one of the parameter is non-zero or autopilot is on - if ((!FMath::IsNearlyEqual(ManualInputs.Steer, 0.f, 0.02f) || - !FMath::IsNearlyEqual(ManualInputs.Brake, 0.f, 0.02f) || - !FMath::IsNearlyEqual(ManualInputs.Throttle, 0.f, 0.02f)) || - GetAutopilotStatus()) - { - this->ApplyVehicleControl(ManualInputs, EVehicleInputPriority::User); - // send these inputs to the Carla (parent) vehicle - FlushVehicleControl(); - } - - VehicleInputs = DReyeVR::UserInputs(); // clear inputs for this frame -} +#include "EgoVehicle.h" +#include "Math/NumericLimits.h" // TNumericLimits::Max +#include // std::string, std::wstring + +////////////////:INPUTS://////////////// +/// NOTE: Here we define all the Input functions for the EgoVehicle just to keep them +// from cluttering the EgoVehcile.cpp file + +const DReyeVR::UserInputs &AEgoVehicle::GetVehicleInputs() const +{ + return VehicleInputs; +} + +const FTransform &AEgoVehicle::GetCameraRootPose() const +{ + return CameraPoseOffset; +} + +void AEgoVehicle::CameraFwd() +{ + // move by (1, 0, 0) + CameraPositionAdjust(FVector::ForwardVector); +} + +void AEgoVehicle::CameraBack() +{ + // move by (-1, 0, 0) + CameraPositionAdjust(FVector::BackwardVector); +} + +void AEgoVehicle::CameraLeft() +{ + // move by (0, -1, 0) + CameraPositionAdjust(FVector::LeftVector); +} + +void AEgoVehicle::CameraRight() +{ + // move by (0, 1, 0) + CameraPositionAdjust(FVector::RightVector); +} + +void AEgoVehicle::CameraUp() +{ + // move by (0, 0, 1) + CameraPositionAdjust(FVector::UpVector); +} + +void AEgoVehicle::CameraDown() +{ + // move by (0, 0, -1) + CameraPositionAdjust(FVector::DownVector); +} + +void AEgoVehicle::CameraPositionAdjust(const FVector &Disp) +{ + if (Disp.Equals(FVector::ZeroVector, 0.0001f)) + return; + // preserves adjustment even after changing view + CameraPoseOffset.SetLocation(CameraPoseOffset.GetLocation() + Disp); + VRCameraRoot->SetRelativeLocation(CameraPose.GetLocation() + CameraPoseOffset.GetLocation()); + /// TODO: account for rotation? scale? +} + +void AEgoVehicle::CameraPositionAdjust(bool bForward, bool bRight, bool bBackwards, bool bLeft, bool bUp, bool bDown) +{ + // add the corresponding directions according to the adjustment booleans + const FVector Disp = FVector::ForwardVector * bForward + FVector::RightVector * bRight + + FVector::BackwardVector * bBackwards + FVector::LeftVector * bLeft + FVector::UpVector * bUp + + FVector::DownVector * bDown; + CameraPositionAdjust(Disp); +} + +void AEgoVehicle::PressNextCameraView() +{ + if (!bCanPressNextCameraView) + return; + bCanPressNextCameraView = false; + NextCameraView(); +}; +void AEgoVehicle::ReleaseNextCameraView() +{ + bCanPressNextCameraView = true; +}; + +void AEgoVehicle::PressPrevCameraView() +{ + if (!bCanPressPrevCameraView) + return; + bCanPressPrevCameraView = false; + PrevCameraView(); +}; +void AEgoVehicle::ReleasePrevCameraView() +{ + bCanPressPrevCameraView = true; +}; + +void AEgoVehicle::NextCameraView() +{ + if (CameraPoseKeys.Num() == 0) + return; + CurrentCameraTransformIdx = (CurrentCameraTransformIdx + 1) % (CameraPoseKeys.Num()); + const FString &Key = CameraPoseKeys[CurrentCameraTransformIdx]; + LOG("Switching manually to next camera view: \"%s\"", *Key); + SetCameraRootPose(CurrentCameraTransformIdx); +} + +void AEgoVehicle::PrevCameraView() +{ + if (CameraPoseKeys.Num() == 0) + return; + if (CurrentCameraTransformIdx == 0) + CurrentCameraTransformIdx = CameraPoseKeys.Num(); + CurrentCameraTransformIdx--; + const FString &Key = CameraPoseKeys[CurrentCameraTransformIdx]; + LOG("Switching manually to prev camera view: \"%s\"", *Key); + SetCameraRootPose(CurrentCameraTransformIdx); +} + +void AEgoVehicle::AddSteering(const float SteeringInput) +{ + float ScaledSteeringInput = this->ScaleSteeringInput * SteeringInput; + // assign to input struct + VehicleInputs.Steering += ScaledSteeringInput; +} + +void AEgoVehicle::AddThrottle(const float ThrottleInput) +{ + float ScaledThrottleInput = this->ScaleThrottleInput * ThrottleInput; + + // apply new light state + FVehicleLightState Lights = GetVehicleLightState(); + Lights.Reverse = false; + Lights.Brake = false; + SetVehicleLightState(Lights); + + // assign to input struct + VehicleInputs.Throttle += ScaledThrottleInput; +} + +void AEgoVehicle::AddBrake(const float BrakeInput) +{ + float ScaledBrakeInput = this->ScaleBrakeInput * BrakeInput; + + // apply new light state + FVehicleLightState Lights = GetVehicleLightState(); + Lights.Reverse = false; + Lights.Brake = true; + SetVehicleLightState(Lights); + + // assign to input struct + VehicleInputs.Brake += ScaledBrakeInput; +} + +void AEgoVehicle::PressReverse() +{ + if (!bCanPressReverse) + return; + bCanPressReverse = false; // don't press again until release + bReverse = !bReverse; + + // negate to toggle bw + (forwards) and - (backwards) + // const int CurrentGear = this->GetVehicleMovementComponent()->GetTargetGear(); + // int NewGear = -1; // for when parked + // if (CurrentGear != 0) + // { + // NewGear = bReverse ? -1 * std::abs(CurrentGear) : std::abs(CurrentGear); // negative => backwards + // } + // this->GetVehicleMovementComponent()->SetTargetGear(NewGear, true); // UE4 control + + // apply new light state + FVehicleLightState Lights = this->GetVehicleLightState(); + Lights.Reverse = this->bReverse; + this->SetVehicleLightState(Lights); + + // LOG("Toggle Reverse"); + // assign to input struct + VehicleInputs.ToggledReverse = true; + + PlayGearShiftSound(); + + // call to parent + SetReverse(bReverse); +} + +void AEgoVehicle::ReleaseReverse() +{ + VehicleInputs.ToggledReverse = false; + bCanPressReverse = true; +} + +void AEgoVehicle::PressTurnSignalR() +{ + if (!bCanPressTurnSignalR) + return; + bCanPressTurnSignalR = false; // don't press again until release + // store in local input container + VehicleInputs.TurnSignalRight = true; + + if (bEnableTurnSignalAction) + { + // apply new light state + FVehicleLightState Lights = this->GetVehicleLightState(); + Lights.RightBlinker = true; + Lights.LeftBlinker = false; + this->SetVehicleLightState(Lights); + // play sound + this->PlayTurnSignalSound(); + } + RightSignalTimeToDie = TNumericLimits::Max(); // wait until button released (+inf until then) + LeftSignalTimeToDie = 0.f; // immediately stop left signal +} + +void AEgoVehicle::ReleaseTurnSignalR() +{ + if (bCanPressTurnSignalR) + return; + VehicleInputs.TurnSignalRight = false; + RightSignalTimeToDie = GetWorld()->GetTimeSeconds() + this->TurnSignalDuration; // reset counter + bCanPressTurnSignalR = true; +} + +void AEgoVehicle::PressTurnSignalL() +{ + if (!bCanPressTurnSignalL) + return; + bCanPressTurnSignalL = false; // don't press again until release + // store in local input container + VehicleInputs.TurnSignalLeft = true; + + if (bEnableTurnSignalAction) + { + // apply new light state + FVehicleLightState Lights = this->GetVehicleLightState(); + Lights.RightBlinker = false; + Lights.LeftBlinker = true; + this->SetVehicleLightState(Lights); + // play sound + this->PlayTurnSignalSound(); + } + RightSignalTimeToDie = 0.f; // immediately stop right signal + LeftSignalTimeToDie = TNumericLimits::Max(); // wait until button released (+inf until then) +} + +void AEgoVehicle::ReleaseTurnSignalL() +{ + if (bCanPressTurnSignalL) + return; + VehicleInputs.TurnSignalLeft = false; + LeftSignalTimeToDie = GetWorld()->GetTimeSeconds() + this->TurnSignalDuration; // reset counter + bCanPressTurnSignalL = true; +} + +void AEgoVehicle::TickVehicleInputs() +{ + FVehicleControl LastAppliedControl = GetVehicleControl(); + + int bIncludeLast = static_cast(GetAutopilotStatus()); + FVehicleControl ManualInputs; + // only include LastAppliedControl when autopilot is running (bc it would have flushed earlier this tick) + ManualInputs.Steer = VehicleInputs.Steering + bIncludeLast * LastAppliedControl.Steer; + ManualInputs.Brake = VehicleInputs.Brake + bIncludeLast * LastAppliedControl.Brake; + ManualInputs.Throttle = VehicleInputs.Throttle + bIncludeLast * LastAppliedControl.Throttle; + ManualInputs.bReverse = bReverse; + + // apply inputs to this vehicle only when either one of the parameter is non-zero or autopilot is on + if ((!FMath::IsNearlyEqual(ManualInputs.Steer, 0.f, 0.02f) || + !FMath::IsNearlyEqual(ManualInputs.Brake, 0.f, 0.02f) || + !FMath::IsNearlyEqual(ManualInputs.Throttle, 0.f, 0.02f)) || + GetAutopilotStatus()) + { + this->ApplyVehicleControl(ManualInputs, EVehicleInputPriority::User); + // send these inputs to the Carla (parent) vehicle + FlushVehicleControl(); + } + + VehicleInputs = DReyeVR::UserInputs(); // clear inputs for this frame +} diff --git a/DReyeVR/EgoSensor.cpp b/DReyeVR/EgoSensor.cpp index 62b106e..797801e 100644 --- a/DReyeVR/EgoSensor.cpp +++ b/DReyeVR/EgoSensor.cpp @@ -1,616 +1,616 @@ -#include "EgoSensor.h" - -#include "Carla/Game/CarlaStatics.h" // GetCurrentEpisode -#include "DReyeVRUtils.h" // GeneralParams.Get, ComputeClosestToRayIntersection -#include "EgoVehicle.h" // AEgoVehicle -#include "Kismet/GameplayStatics.h" // UGameplayStatics::ProjectWorldToScreen -#include "Kismet/KismetMathLibrary.h" // Sin, Cos, Normalize -#include "Misc/DateTime.h" // FDateTime -#include "UObject/UObjectBaseUtility.h" // GetName - -#if USE_SRANIPAL_PLUGIN -#include "SRanipal_API.h" // SRanipal_GetVersion -#endif - -#if USE_FOVEATED_RENDER -#include "EyeTrackerTypes.h" // FEyeTrackerStereoGazeData -#include "VRSBlueprintFunctionLibrary.h" // VRS -#endif - -#include - -#ifndef NO_DREYEVR_EXCEPTIONS -#include -#include - -namespace carla -{ -void throw_exception(const std::exception &e) -{ - // It should never reach this part. - std::terminate(); -} -} // namespace carla -#endif - -AEgoSensor::AEgoSensor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) -{ - ReadConfigVariables(); - - // Initialize the frame capture (constructor call to create USceneCaptureComponent2D) - ConstructFrameCapture(); -} - -void AEgoSensor::ReadConfigVariables() -{ - GeneralParams.Get("EgoSensor", "StreamSensorData", bStreamData); - GeneralParams.Get("EgoSensor", "MaxTraceLenM", MaxTraceLenM); - GeneralParams.Get("EgoSensor", "DrawDebugFocusTrace", bDrawDebugFocusTrace); - - // variables corresponding to the action of screencapture during replay - GeneralParams.Get("Replayer", "RecordAllShaders", bRecordAllShaders); - GeneralParams.Get("Replayer", "RecordAllPoses", bRecordAllPoses); - GeneralParams.Get("Replayer", "RecordFrames", bCaptureFrameData); - GeneralParams.Get("Replayer", "FileFormatJPG", bFileFormatJPG); - GeneralParams.Get("Replayer", "LinearGamma", bFrameCapForceLinearGamma); - GeneralParams.Get("Replayer", "FrameWidth", FrameCapWidth); - GeneralParams.Get("Replayer", "FrameHeight", FrameCapHeight); - GeneralParams.Get("Replayer", "FrameDir", FrameCapLocation); - GeneralParams.Get("Replayer", "FrameName", FrameCapFilename); - -#if USE_FOVEATED_RENDER - // foveated rendering variables - GeneralParams.Get("VariableRateShading", "Enabled", bEnableFovRender); - GeneralParams.Get("VariableRateShading", "UsingEyeTracking", bUseEyeTrackingVRS); -#endif -} - -void AEgoSensor::BeginPlay() -{ - Super::BeginPlay(); - - World = GetWorld(); - ChronoStartTime = std::chrono::system_clock::now(); - - // Initialize the eye tracker hardware - InitEyeTracker(); - -#if USE_FOVEATED_RENDER - // Initialize VRS plugin (using our VRS fork!) - UVariableRateShadingFunctionLibrary::EnableVRS(bEnableFovRender); - UVariableRateShadingFunctionLibrary::EnableEyeTracking(bUseEyeTrackingVRS); - LOG("Initialized Variable Rate Shading (VRS) plugin"); -#endif - - LOG("Initialized DReyeVR EgoSensor"); -} - -void AEgoSensor::BeginDestroy() -{ - Super::BeginDestroy(); - - if (RecordingCF != nullptr) - { - delete RecordingCF; - } - - DestroyEyeTracker(); - - LOG("EgoSensor has been destroyed"); -} - -void AEgoSensor::ManualTick(float DeltaSeconds) -{ - if (!ADReyeVRSensor::bIsReplaying) // only update the sensor with local values if not replaying - { - const float Timestamp = int64_t(1000.f * UGameplayStatics::GetRealTimeSeconds(World)); - /// TODO: query the eye tracker hardware asynchronously (not limited to UE4 tick) - TickEyeTracker(); // query the eye-tracker hardware for current data - ComputeFocusInfo(); // compute gaze focus data - ComputeEgoVars(); // get all necessary ego-vehicle data - - // Update the internal sensor data that gets handed off to Carla (for recording/replaying/PythonAPI) - const auto &Inputs = Vehicle.IsValid() ? Vehicle.Get()->GetVehicleInputs() : DReyeVR::UserInputs{}; - GetData()->Update(Timestamp, // TimestampCarla (ms) - EyeSensorData, // EyeTrackerData - EgoVars, // EgoVehicleVariables - FocusInfoData, // FocusData - Inputs // User inputs - ); - TickFoveatedRender(); - } - TickCount++; -} - -/// ========================================== /// -/// ---------------:EYETRACKER:--------------- /// -/// ========================================== /// - -void AEgoSensor::InitEyeTracker() -{ -#if USE_SRANIPAL_PLUGIN - bSRanipalEnabled = false; - - char *SR_Version_chars = new char[128](); - ViveSR::anipal::SRanipal_GetVersion(SR_Version_chars); - const FString SR_Version(SR_Version_chars); - { - // we found that these versions work great, other versions may cause random crashes - const std::vector SupportedVers = {"1.3.1.1", "1.3.2.0", "1.3.3.0"}; - auto FoundVersion = std::find(SupportedVers.begin(), SupportedVers.end(), std::string(SR_Version_chars)); - bool bIsCompatible = (FoundVersion != SupportedVers.end()); - if (!bIsCompatible) - { - std::string SupportedVersStr = ""; - for (const auto &Ver : SupportedVers) - SupportedVersStr += Ver + ", "; - LOG_ERROR("Detected incompatible SRanipal version: %s", *SR_Version); - LOG_WARN("Please use a compatible SRanipal version such as: {%s}", *FString(SupportedVersStr.c_str())); - LOG_WARN("Check out the DReyeVR documentation to download a supported version."); - LOG_WARN("Disabling SRanipal for now..."); - bSRanipalEnabled = false; - return; - } - - // initialize SRanipal framework for eye tracking - LOG("Attempting to use SRanipal (%s) for eye tracking", *SR_Version); - } - // Initialize the SRanipal eye tracker (WINDOWS ONLY) - SRanipalFramework = SRanipalEye_Framework::Instance(); - SRanipal = SRanipalEye_Core::Instance(); - // no easily discernible difference between v1 and v2 - /// TODO: use the status output from StartFramework to determine if SRanipal loaded successfully - int Status = SRanipalFramework->StartFramework(SupportedEyeVersion::version1); - if (Status == SRanipalEye_Framework::FrameworkStatus::ERROR || - Status == SRanipalEye_Framework::FrameworkStatus::NOT_SUPPORT) - { - LOG_ERROR("Unable to start SRanipal framework (%d)!", Status); - return; - } - // SRanipal->SetEyeParameter_() // can set the eye gaze jitter parameter - // see SRanipal_Eyes_Enums.h - // Get the reference timing to synchronize the SRanipal timer with Carla - LOG("Successfully started SRanipal (%s) framework", *SR_Version); - bSRanipalEnabled = true; -#else - LOG("Not using SRanipal eye tracking"); -#endif -} - -void AEgoSensor::DestroyEyeTracker() -{ -#if USE_SRANIPAL_PLUGIN - if (SRanipalFramework) - { - SRanipalFramework->StopFramework(); - SRanipalEye_Framework::DestroyEyeFramework(); - } - if (SRanipal) - SRanipalEye_Core::DestroyEyeModule(); -#endif -} - -void AEgoSensor::TickEyeTracker() -{ - /// TODO: move this function to an async thread to obtain 120hz data capture - auto Combined = &(EyeSensorData.Combined); - auto Left = &(EyeSensorData.Left); - auto Right = &(EyeSensorData.Right); -#if USE_SRANIPAL_PLUGIN - if (bSRanipalEnabled) - { - /// NOTE: the GazeRay is the normalized direction vector of the actual gaze "ray" - // Getting real eye tracker data - check(SRanipal != nullptr); - // Assigns EyeOrigin and Gaze direction (normalized) of combined gaze - Combined->GazeValid = SRanipal->GetGazeRay(GazeIndex::COMBINE, Combined->GazeOrigin, Combined->GazeDir); - // Assign Left/Right Gaze direction - Left->GazeValid = SRanipal->GetGazeRay(GazeIndex::LEFT, Left->GazeOrigin, Left->GazeDir); - Right->GazeValid = SRanipal->GetGazeRay(GazeIndex::RIGHT, Right->GazeOrigin, Right->GazeDir); - /// NOTE: the eye gazes are reversed bc SRanipal has a bug in their closed libraries - // see: https://forum.vive.com/topic/9306-possible-bug-in-unreal-sdk-for-leftright-eye-gazes - const bool SRANIPAL_EYE_SWAP_BUG = true; - if (SRANIPAL_EYE_SWAP_BUG) // if the latest SRanipal does not have this bug - { - std::swap(Left->GazeDir, Right->GazeDir); // need to swap the gaze directions - } - // Assign Eye openness - Left->EyeOpennessValid = SRanipal->GetEyeOpenness(EyeIndex::LEFT, Left->EyeOpenness); - Right->EyeOpennessValid = SRanipal->GetEyeOpenness(EyeIndex::RIGHT, Right->EyeOpenness); - // Assign Pupil positions - Left->PupilPositionValid = SRanipal->GetPupilPosition(EyeIndex::LEFT, Left->PupilPosition); - Right->PupilPositionValid = SRanipal->GetPupilPosition(EyeIndex::RIGHT, Right->PupilPosition); - - // Get the "EyeData" which holds useful information such as the timestamp - int EyeDataStatus = SRanipal->GetEyeData_(&EyeData); - if (EyeDataStatus == ViveSR::Error::WORK) - { - EyeSensorData.TimestampDevice = EyeData.timestamp; - EyeSensorData.FrameSequence = EyeData.frame_sequence; - // Assign Pupil Diameters - Left->PupilDiameter = EyeData.verbose_data.left.pupil_diameter_mm; - Right->PupilDiameter = EyeData.verbose_data.right.pupil_diameter_mm; - } - } - else - { - ComputeDummyEyeData(); - } -#else - ComputeDummyEyeData(); -#endif - Combined->Vergence = ComputeVergence(Left->GazeOrigin, Left->GazeDir, Right->GazeOrigin, Right->GazeDir); - - // FPlatformProcess::Sleep(0.00833f); // use in async thread to get 120hz -} - -void AEgoSensor::ComputeDummyEyeData() -{ - // Function to make "dummy" eye data where the eye gaze just looks around in a CCW circle. - // Useful for when the eye data is unavailable (Plugin not initialized, on Linux, etc.) - auto Combined = &(EyeSensorData.Combined); - auto Left = &(EyeSensorData.Left); - auto Right = &(EyeSensorData.Right); - // generate dummy values bc no hardware sensor is present - EyeSensorData.TimestampDevice = int64_t( - std::chrono::duration_cast(std::chrono::system_clock::now() - ChronoStartTime) - .count()); - EyeSensorData.FrameSequence = TickCount; // get the current tick - - // generate gaze that rotates in CCW fashion around the camera ray - const float TimeNow = EyeSensorData.TimestampDevice / 1000.f; - Combined->GazeDir.X = 5.0; - Combined->GazeDir.Y = UKismetMathLibrary::Cos(TimeNow); - Combined->GazeDir.Z = UKismetMathLibrary::Sin(TimeNow); - UKismetMathLibrary::Vector_Normalize(Combined->GazeDir, 0.0001); - - // Assign the origin position to the (3D space) origin - Combined->GazeValid = true; // for our Linux case, this is valid - Combined->GazeOrigin = FVector::ZeroVector; - - // Assign the endpoint of the combined position (faked in Linux) to the left & right gazes too - Left->GazeDir = Combined->GazeDir; - Left->GazeOrigin = Combined->GazeOrigin + 5 * FVector::LeftVector; - Right->GazeDir = Combined->GazeDir; - Right->GazeOrigin = Combined->GazeOrigin + 5 * FVector::RightVector; -} - -void AEgoSensor::ComputeFocusInfo() -{ - // ECC_Visibility: General visibility testing channel. - // ECC_Camera: Usually used when tracing from the camera to something. - // https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/ECollisionChannel/ - // https://zompidev.blogspot.com/2021/08/visibility-vs-camera-trace-channels-in.html - ComputeTraceFocusInfo(ECC_Visibility); -} - -bool AEgoSensor::ComputeGazeTrace(FHitResult &Hit, const ECollisionChannel TraceChannel, float TraceRadius) const -{ - const float TraceLen = MaxTraceLenM * 100.f; // convert to m from cm - const FRotator &WorldRot = GetData()->GetCameraRotationAbs(); - const FVector &WorldPos = GetData()->GetCameraLocationAbs(); - const FVector GazeOrigin = WorldPos + WorldRot.RotateVector(GetData()->GetGazeOrigin()); - const FVector GazeRay = TraceLen * WorldRot.RotateVector(GetData()->GetGazeDir()).GetSafeNormal(); - // Create collision information container. - FCollisionQueryParams TraceParam; - TraceParam = FCollisionQueryParams(FName("TraceParam"), true); - if (Vehicle.IsValid()) - TraceParam.AddIgnoredActor(Vehicle.Get()); // don't collide with the vehicle since that would be useless - TraceParam.bTraceComplex = true; - TraceParam.bReturnPhysicalMaterial = false; - Hit = FHitResult(EForceInit::ForceInit); - bool bDidHit = false; - - // 0 for a point, >0 for a sphear trace - TraceRadius = FMath::Max(TraceRadius, 0.f); // clamp to be positive - - ensure(World != nullptr); - if (TraceRadius == 0.f) // Single ray/line trace - { - bDidHit = World->LineTraceSingleByChannel(Hit, GazeOrigin, GazeOrigin + GazeRay, TraceChannel, TraceParam); - } - else // Sphear line trace - { - FCollisionShape Sphear = FCollisionShape(); - Sphear.SetSphere(TraceRadius); - bDidHit = World->SweepSingleByChannel(Hit, GazeOrigin, GazeOrigin + GazeRay, FQuat(0.f, 0.f, 0.f, 0.f), - TraceChannel, Sphear, TraceParam); - } - - if (!bDidHit) - { - // focus point is just straight ahead to the maximum trace length - Hit.Actor = nullptr; - Hit.Location = GazeOrigin + GazeRay; - Hit.Distance = TraceLen; - } - - if (bDrawDebugFocusTrace) - { - DrawDebugSphere(World, Hit.Location, 8.0f, 30, FColor::Blue); - DrawDebugLine(World, - GazeOrigin, // start line - GazeOrigin + GazeRay, // end line - FColor::Purple, false, -1, 0, 1); - } - return bDidHit; -} - -void AEgoSensor::ComputeTraceFocusInfo(const ECollisionChannel TraceChannel, float TraceRadius) -{ - FHitResult Hit; - bool bDidHit = ComputeGazeTrace(Hit, TraceChannel, TraceRadius); - // Update fields - FString ActorName = "None"; - if (Hit.Actor != nullptr) - { - Hit.Actor->GetName(ActorName); - FString Suffix = ""; // suffix to the actor "name" (actor type we care about) - if (Cast(Hit.Actor) != nullptr) - Suffix = "_Vehicle"; - else if (Cast(Hit.Actor) != nullptr) - Suffix = "_Walker"; - else if (Cast(Hit.Actor) != nullptr) - Suffix = "_TrafficLight"; - /// TODO: add more suffixes here. - ActorName += Suffix; - } - - // update internal data structure (see DReyeVRData::FocusInfo) - FocusInfoData.Actor = Hit.Actor; // pointer to actor being hit (if any, else nullptr) - FocusInfoData.HitPoint = Hit.Location; // absolute (world) location of hit - FocusInfoData.Normal = Hit.Normal; // normal of hit surface (if hit) - FocusInfoData.ActorNameTag = ActorName; // name of the actor being hit (if any, else "None") - FocusInfoData.Distance = Hit.Distance; // distance from ray start - FocusInfoData.bDidHit = bDidHit; // whether or not there was a hit -} - -float AEgoSensor::ComputeVergence(const FVector &L0, const FVector &LDir, const FVector &R0, const FVector &RDir) const -{ - // Compute length of ray-to- intersection of the left and right eye gazes in 3D space (length in centimeters) - return ComputeClosestToRayIntersection(L0, LDir, R0, RDir).Size(); // units are cm (default for UE4) -} - -/// ========================================== /// -/// ---------------:EGOVARS:------------------ /// -/// ========================================== /// - -void AEgoSensor::SetEgoVehicle(class AEgoVehicle *NewEgoVehicle) -{ - Vehicle = NewEgoVehicle; - check(Vehicle.IsValid()); - - // Also check that the ConfigFileData variable can be written to with Vehicle params - check(ConfigFile); // this is a static variable created in the parent (ADReyeVRSensor) - - // track both the VehicleParams and GeneralParams - const auto ConfigFileStr = Vehicle.Get()->GetVehicleParams().Export() + GeneralParams.Export(); - ConfigFile->Set(ConfigFileStr); // track this config file once - - // saved from some previous request to compare, but failed bc no EgoVehicle - if (RecordingCF != nullptr) - { - UpdateData(*RecordingCF, 0.f); - } -} - -void AEgoSensor::ComputeEgoVars() -{ - if (!Vehicle.IsValid()) - { - LOG_WARN("Invalid EgoVehicle, cannot compute EgoVars"); - return; - } - // See DReyeVRData::EgoVariables - auto *Ego = Vehicle.Get(); - auto *Camera = Ego->GetCamera(); - check(Camera); - EgoVars.VehicleLocation = Ego->GetActorLocation(); - EgoVars.VehicleRotation = Ego->GetActorRotation(); - EgoVars.CameraLocation = Camera->GetRelativeLocation(); - EgoVars.CameraRotation = Camera->GetRelativeRotation(); - EgoVars.CameraLocationAbs = Camera->GetComponentLocation(); - EgoVars.CameraRotationAbs = Camera->GetComponentRotation(); - EgoVars.Velocity = Ego->GetVehicleForwardSpeed(); -} - -/// ========================================== /// -/// ---------------:FRAMECAP:----------------- /// -/// ========================================== /// - -void AEgoSensor::ConstructFrameCapture() -{ - if (bCaptureFrameData) - { - // Frame capture - CaptureRenderTarget = CreateDefaultSubobject(TEXT("CaptureRenderTarget_DReyeVR")); - CaptureRenderTarget->CompressionSettings = TextureCompressionSettings::TC_Default; - CaptureRenderTarget->SRGB = false; - CaptureRenderTarget->bAutoGenerateMips = false; - CaptureRenderTarget->bGPUSharedFlag = true; - CaptureRenderTarget->ClearColor = FLinearColor::Black; - CaptureRenderTarget->UpdateResourceImmediate(true); - // CaptureRenderTarget->OverrideFormat = EPixelFormat::PF_FloatRGB; - CaptureRenderTarget->AddressX = TextureAddress::TA_Clamp; - CaptureRenderTarget->AddressY = TextureAddress::TA_Clamp; - CaptureRenderTarget->InitCustomFormat(FrameCapWidth, FrameCapHeight, PF_B8G8R8A8, bFrameCapForceLinearGamma); - check(CaptureRenderTarget->GetSurfaceWidth() > 0 && CaptureRenderTarget->GetSurfaceHeight() > 0); - - FrameCap = CreateDefaultSubobject(TEXT("FrameCap")); - FrameCap->PrimitiveRenderMode = ESceneCapturePrimitiveRenderMode::PRM_RenderScenePrimitives; - FrameCap->bCaptureOnMovement = false; - FrameCap->bCaptureEveryFrame = false; - FrameCap->bAlwaysPersistRenderingState = true; - FrameCap->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR; - - // apply postprocessing effects - FrameCap->PostProcessSettings = CreatePostProcessingEffect(0); - - FrameCap->Deactivate(); - FrameCap->TextureTarget = CaptureRenderTarget; - FrameCap->UpdateContent(); - FrameCap->Activate(); - } - if (FrameCap && !bCaptureFrameData) - { - FrameCap->Deactivate(); - } -} - -void AEgoSensor::InitFrameCapture() -{ - if (bCaptureFrameData) - { - // initialize frame capture attachment to the ego vehicle - if (FrameCap && Vehicle.IsValid()) - FrameCap->SetupAttachment(Vehicle.Get()->GetCamera()); - - // creates the directory for the frame capture to take place - /// TODO: add check for absolute paths - FrameCapLocation = FPaths::ConvertRelativePathToFull(FPaths::ProjectDir() + FrameCapLocation); - // The returned string has the following format: yyyy.mm.dd-hh.mm.ss - FString DirName = FDateTime::Now().ToString(); // timestamp directory - FrameCapLocation = FPaths::Combine(FrameCapLocation, DirName); - - // create directory if not present - LOG("Outputting frame capture data to %s", *FrameCapLocation); - IPlatformFile &PlatformFile = FPlatformFileManager::Get().GetPlatformFile(); - if (!PlatformFile.DirectoryExists(*FrameCapLocation)) - { -#ifdef CreateDirectory - // using Windows system calls - CreateDirectory(*FrameCapLocation, NULL); -#else - // this only seems to work on Unix systems, else CreateDirectoryW is not linked? - PlatformFile.CreateDirectory(*FrameCapLocation); -#endif - } - bCreatedDirectory = true; - } -} - -void AEgoSensor::TakeScreenshot() -{ - /// NOTE: this is a slow function that takes multiple high-res screenshots (with different shader params) - // of the current scene and writes the images to disk immediately. The intention is to use this function - // during synchronized replay with screen capture so that performance is not an issue since the simulator - // is not necessarily running in real-time. - - // create directory if necessary - if (bCaptureFrameData && !bCreatedDirectory) - { - InitFrameCapture(); // Set up frame capture directory - } - - // capture the screenshot to the directory - if (bCaptureFrameData && FrameCap && Vehicle.IsValid()) - { - for (int i = 0; i < GetNumberOfShaders(); i++) - { - // apply the postprocessing effect - FrameCap->PostProcessSettings = CreatePostProcessingEffect(i); - // loop through all camera poses - for (int j = 0; j < Vehicle.Get()->GetNumCameraPoses(); j++) - { - // set this pose - Vehicle.Get()->SetCameraRootPose(j); - - // using 5 digits to reach frame 99999 ~ 30m (assuming ~50fps frame capture) - // suffix is denoted as _s(hader)X_p(ose)Y_Z.png where X is the shader idx, Y is the pose idx, Z is tick - const FString Suffix = FString::Printf(TEXT("_s%d_p%d_%05d.png"), i, j, ScreenshotCount); - // apply the camera view (position & orientation) - FMinimalViewInfo DesiredView; - Vehicle.Get()->GetCamera()->GetCameraView(0, DesiredView); - FrameCap->SetCameraView(DesiredView); // move camera to the camera view - // capture the scene and save the screenshot to disk - FrameCap->CaptureScene(); // also available: CaptureSceneDeferred() - SaveFrameToDisk(*CaptureRenderTarget, FPaths::Combine(FrameCapLocation, FrameCapFilename + Suffix), - bFileFormatJPG); - if (!bRecordAllPoses) - { - // exit after the first camera pose (seated) - break; - } - } - // set camera pose back to 0 - Vehicle.Get()->SetCameraRootPose(0); - if (!bRecordAllShaders) - { - // exit after the first shader (rgb) - break; - } - } - ScreenshotCount++; // progress to next frame - } -} - -/// ========================================== /// -/// ------------:FOVEATEDRENDER:-------------- /// -/// ========================================== /// - -void AEgoSensor::ConvertToEyeTrackerSpace(FVector &inVec) const -{ - FVector temp = inVec; - inVec.X = -1 * temp.Y; - inVec.Y = temp.Z; - inVec.Z = temp.X; -} - -void AEgoSensor::TickFoveatedRender() -{ -#if USE_FOVEATED_RENDER - FEyeTrackerStereoGazeData F; - F.LeftEyeOrigin = GetData()->GetGazeOrigin(DReyeVR::Gaze::LEFT); - F.LeftEyeDirection = GetData()->GetGazeDir(DReyeVR::Gaze::LEFT); - ConvertToEyeTrackerSpace(F.LeftEyeDirection); - F.RightEyeOrigin = GetData()->GetGazeOrigin(DReyeVR::Gaze::RIGHT); - F.RightEyeDirection = GetData()->GetGazeDir(DReyeVR::Gaze::RIGHT); - ConvertToEyeTrackerSpace(F.RightEyeDirection); - F.FixationPoint = GetData()->GetFocusActorPoint(); - F.ConfidenceValue = 0.99f; - UVariableRateShadingFunctionLibrary::UpdateStereoGazeDataToFoveatedRendering(F); -#endif -} - -/// ========================================== /// -/// ----------------:REPLAY:------------------ /// -/// ========================================== /// - -// don't need to override the base ADReyeVRSensor::UpdateData(); - -void AEgoSensor::UpdateData(const DReyeVR::ConfigFileData &RecordedParams, const double Per) -{ - if (!Vehicle.IsValid()) - { - // LOG_WARN("Unable to compare ConfigFile bc EgoVehicle is invalid!"); - RecordingCF = new DReyeVR::ConfigFileData(); - (*RecordingCF) = RecordedParams; // save these params for later (ex. SetEgoVehicle) - return; - } - // compare the incoming (recording) ConfigFile with our current (live) one - const std::string RecordingExport = TCHAR_TO_UTF8(*RecordedParams.ToString()); - const struct ConfigFile Recorded = ConfigFile::Import(RecordingExport); - - // includes both the vehicle params and general params - struct ConfigFile LiveConfig; - LiveConfig.Insert(Vehicle.Get()->GetVehicleParams()); - LiveConfig.Insert(GeneralParams); - - bool bPrintWarnings = true; - if (LiveConfig.IsSubset(Recorded, bPrintWarnings)) // don't care if Recorded has entries that we dont - { - LOG("Config file comparison successful!"); - } - else - { - LOG_WARN("Config file comparison failed! This means the recording was performed with a different configuration " - "file than what is currently active. You might want to check that this does not affect the validity " - "of your replay."); - } -} - -void AEgoSensor::UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) -{ - if (Vehicle.IsValid() && Vehicle.Get()->GetGame()) - Vehicle.Get()->GetGame()->ReplayCustomActor(RecorderData, Per); +#include "EgoSensor.h" + +#include "Carla/Game/CarlaStatics.h" // GetCurrentEpisode +#include "DReyeVRUtils.h" // GeneralParams.Get, ComputeClosestToRayIntersection +#include "EgoVehicle.h" // AEgoVehicle +#include "Kismet/GameplayStatics.h" // UGameplayStatics::ProjectWorldToScreen +#include "Kismet/KismetMathLibrary.h" // Sin, Cos, Normalize +#include "Misc/DateTime.h" // FDateTime +#include "UObject/UObjectBaseUtility.h" // GetName + +#if USE_SRANIPAL_PLUGIN +#include "SRanipal_API.h" // SRanipal_GetVersion +#endif + +#if USE_FOVEATED_RENDER +#include "EyeTrackerTypes.h" // FEyeTrackerStereoGazeData +#include "VRSBlueprintFunctionLibrary.h" // VRS +#endif + +#include + +#ifndef NO_DREYEVR_EXCEPTIONS +#include +#include + +namespace carla +{ +void throw_exception(const std::exception &e) +{ + // It should never reach this part. + std::terminate(); +} +} // namespace carla +#endif + +AEgoSensor::AEgoSensor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +{ + ReadConfigVariables(); + + // Initialize the frame capture (constructor call to create USceneCaptureComponent2D) + ConstructFrameCapture(); +} + +void AEgoSensor::ReadConfigVariables() +{ + GeneralParams.Get("EgoSensor", "StreamSensorData", bStreamData); + GeneralParams.Get("EgoSensor", "MaxTraceLenM", MaxTraceLenM); + GeneralParams.Get("EgoSensor", "DrawDebugFocusTrace", bDrawDebugFocusTrace); + + // variables corresponding to the action of screencapture during replay + GeneralParams.Get("Replayer", "RecordAllShaders", bRecordAllShaders); + GeneralParams.Get("Replayer", "RecordAllPoses", bRecordAllPoses); + GeneralParams.Get("Replayer", "RecordFrames", bCaptureFrameData); + GeneralParams.Get("Replayer", "FileFormatJPG", bFileFormatJPG); + GeneralParams.Get("Replayer", "LinearGamma", bFrameCapForceLinearGamma); + GeneralParams.Get("Replayer", "FrameWidth", FrameCapWidth); + GeneralParams.Get("Replayer", "FrameHeight", FrameCapHeight); + GeneralParams.Get("Replayer", "FrameDir", FrameCapLocation); + GeneralParams.Get("Replayer", "FrameName", FrameCapFilename); + +#if USE_FOVEATED_RENDER + // foveated rendering variables + GeneralParams.Get("VariableRateShading", "Enabled", bEnableFovRender); + GeneralParams.Get("VariableRateShading", "UsingEyeTracking", bUseEyeTrackingVRS); +#endif +} + +void AEgoSensor::BeginPlay() +{ + Super::BeginPlay(); + + World = GetWorld(); + ChronoStartTime = std::chrono::system_clock::now(); + + // Initialize the eye tracker hardware + InitEyeTracker(); + +#if USE_FOVEATED_RENDER + // Initialize VRS plugin (using our VRS fork!) + UVariableRateShadingFunctionLibrary::EnableVRS(bEnableFovRender); + UVariableRateShadingFunctionLibrary::EnableEyeTracking(bUseEyeTrackingVRS); + LOG("Initialized Variable Rate Shading (VRS) plugin"); +#endif + + LOG("Initialized DReyeVR EgoSensor"); +} + +void AEgoSensor::BeginDestroy() +{ + Super::BeginDestroy(); + + if (RecordingCF != nullptr) + { + delete RecordingCF; + } + + DestroyEyeTracker(); + + LOG("EgoSensor has been destroyed"); +} + +void AEgoSensor::ManualTick(float DeltaSeconds) +{ + if (!ADReyeVRSensor::bIsReplaying) // only update the sensor with local values if not replaying + { + const float Timestamp = int64_t(1000.f * UGameplayStatics::GetRealTimeSeconds(World)); + /// TODO: query the eye tracker hardware asynchronously (not limited to UE4 tick) + TickEyeTracker(); // query the eye-tracker hardware for current data + ComputeFocusInfo(); // compute gaze focus data + ComputeEgoVars(); // get all necessary ego-vehicle data + + // Update the internal sensor data that gets handed off to Carla (for recording/replaying/PythonAPI) + const auto &Inputs = Vehicle.IsValid() ? Vehicle.Get()->GetVehicleInputs() : DReyeVR::UserInputs{}; + GetData()->Update(Timestamp, // TimestampCarla (ms) + EyeSensorData, // EyeTrackerData + EgoVars, // EgoVehicleVariables + FocusInfoData, // FocusData + Inputs // User inputs + ); + TickFoveatedRender(); + } + TickCount++; +} + +/// ========================================== /// +/// ---------------:EYETRACKER:--------------- /// +/// ========================================== /// + +void AEgoSensor::InitEyeTracker() +{ +#if USE_SRANIPAL_PLUGIN + bSRanipalEnabled = false; + + char *SR_Version_chars = new char[128](); + ViveSR::anipal::SRanipal_GetVersion(SR_Version_chars); + const FString SR_Version(SR_Version_chars); + { + // we found that these versions work great, other versions may cause random crashes + const std::vector SupportedVers = {"1.3.1.1", "1.3.2.0", "1.3.3.0"}; + auto FoundVersion = std::find(SupportedVers.begin(), SupportedVers.end(), std::string(SR_Version_chars)); + bool bIsCompatible = (FoundVersion != SupportedVers.end()); + if (!bIsCompatible) + { + std::string SupportedVersStr = ""; + for (const auto &Ver : SupportedVers) + SupportedVersStr += Ver + ", "; + LOG_ERROR("Detected incompatible SRanipal version: %s", *SR_Version); + LOG_WARN("Please use a compatible SRanipal version such as: {%s}", *FString(SupportedVersStr.c_str())); + LOG_WARN("Check out the DReyeVR documentation to download a supported version."); + LOG_WARN("Disabling SRanipal for now..."); + bSRanipalEnabled = false; + return; + } + + // initialize SRanipal framework for eye tracking + LOG("Attempting to use SRanipal (%s) for eye tracking", *SR_Version); + } + // Initialize the SRanipal eye tracker (WINDOWS ONLY) + SRanipalFramework = SRanipalEye_Framework::Instance(); + SRanipal = SRanipalEye_Core::Instance(); + // no easily discernible difference between v1 and v2 + /// TODO: use the status output from StartFramework to determine if SRanipal loaded successfully + int Status = SRanipalFramework->StartFramework(SupportedEyeVersion::version1); + if (Status == SRanipalEye_Framework::FrameworkStatus::ERROR || + Status == SRanipalEye_Framework::FrameworkStatus::NOT_SUPPORT) + { + LOG_ERROR("Unable to start SRanipal framework (%d)!", Status); + return; + } + // SRanipal->SetEyeParameter_() // can set the eye gaze jitter parameter + // see SRanipal_Eyes_Enums.h + // Get the reference timing to synchronize the SRanipal timer with Carla + LOG("Successfully started SRanipal (%s) framework", *SR_Version); + bSRanipalEnabled = true; +#else + LOG("Not using SRanipal eye tracking"); +#endif +} + +void AEgoSensor::DestroyEyeTracker() +{ +#if USE_SRANIPAL_PLUGIN + if (SRanipalFramework) + { + SRanipalFramework->StopFramework(); + SRanipalEye_Framework::DestroyEyeFramework(); + } + if (SRanipal) + SRanipalEye_Core::DestroyEyeModule(); +#endif +} + +void AEgoSensor::TickEyeTracker() +{ + /// TODO: move this function to an async thread to obtain 120hz data capture + auto Combined = &(EyeSensorData.Combined); + auto Left = &(EyeSensorData.Left); + auto Right = &(EyeSensorData.Right); +#if USE_SRANIPAL_PLUGIN + if (bSRanipalEnabled) + { + /// NOTE: the GazeRay is the normalized direction vector of the actual gaze "ray" + // Getting real eye tracker data + check(SRanipal != nullptr); + // Assigns EyeOrigin and Gaze direction (normalized) of combined gaze + Combined->GazeValid = SRanipal->GetGazeRay(GazeIndex::COMBINE, Combined->GazeOrigin, Combined->GazeDir); + // Assign Left/Right Gaze direction + Left->GazeValid = SRanipal->GetGazeRay(GazeIndex::LEFT, Left->GazeOrigin, Left->GazeDir); + Right->GazeValid = SRanipal->GetGazeRay(GazeIndex::RIGHT, Right->GazeOrigin, Right->GazeDir); + /// NOTE: the eye gazes are reversed bc SRanipal has a bug in their closed libraries + // see: https://forum.vive.com/topic/9306-possible-bug-in-unreal-sdk-for-leftright-eye-gazes + const bool SRANIPAL_EYE_SWAP_BUG = true; + if (SRANIPAL_EYE_SWAP_BUG) // if the latest SRanipal does not have this bug + { + std::swap(Left->GazeDir, Right->GazeDir); // need to swap the gaze directions + } + // Assign Eye openness + Left->EyeOpennessValid = SRanipal->GetEyeOpenness(EyeIndex::LEFT, Left->EyeOpenness); + Right->EyeOpennessValid = SRanipal->GetEyeOpenness(EyeIndex::RIGHT, Right->EyeOpenness); + // Assign Pupil positions + Left->PupilPositionValid = SRanipal->GetPupilPosition(EyeIndex::LEFT, Left->PupilPosition); + Right->PupilPositionValid = SRanipal->GetPupilPosition(EyeIndex::RIGHT, Right->PupilPosition); + + // Get the "EyeData" which holds useful information such as the timestamp + int EyeDataStatus = SRanipal->GetEyeData_(&EyeData); + if (EyeDataStatus == ViveSR::Error::WORK) + { + EyeSensorData.TimestampDevice = EyeData.timestamp; + EyeSensorData.FrameSequence = EyeData.frame_sequence; + // Assign Pupil Diameters + Left->PupilDiameter = EyeData.verbose_data.left.pupil_diameter_mm; + Right->PupilDiameter = EyeData.verbose_data.right.pupil_diameter_mm; + } + } + else + { + ComputeDummyEyeData(); + } +#else + ComputeDummyEyeData(); +#endif + Combined->Vergence = ComputeVergence(Left->GazeOrigin, Left->GazeDir, Right->GazeOrigin, Right->GazeDir); + + // FPlatformProcess::Sleep(0.00833f); // use in async thread to get 120hz +} + +void AEgoSensor::ComputeDummyEyeData() +{ + // Function to make "dummy" eye data where the eye gaze just looks around in a CCW circle. + // Useful for when the eye data is unavailable (Plugin not initialized, on Linux, etc.) + auto Combined = &(EyeSensorData.Combined); + auto Left = &(EyeSensorData.Left); + auto Right = &(EyeSensorData.Right); + // generate dummy values bc no hardware sensor is present + EyeSensorData.TimestampDevice = int64_t( + std::chrono::duration_cast(std::chrono::system_clock::now() - ChronoStartTime) + .count()); + EyeSensorData.FrameSequence = TickCount; // get the current tick + + // generate gaze that rotates in CCW fashion around the camera ray + const float TimeNow = EyeSensorData.TimestampDevice / 1000.f; + Combined->GazeDir.X = 5.0; + Combined->GazeDir.Y = UKismetMathLibrary::Cos(TimeNow); + Combined->GazeDir.Z = UKismetMathLibrary::Sin(TimeNow); + UKismetMathLibrary::Vector_Normalize(Combined->GazeDir, 0.0001); + + // Assign the origin position to the (3D space) origin + Combined->GazeValid = true; // for our Linux case, this is valid + Combined->GazeOrigin = FVector::ZeroVector; + + // Assign the endpoint of the combined position (faked in Linux) to the left & right gazes too + Left->GazeDir = Combined->GazeDir; + Left->GazeOrigin = Combined->GazeOrigin + 5 * FVector::LeftVector; + Right->GazeDir = Combined->GazeDir; + Right->GazeOrigin = Combined->GazeOrigin + 5 * FVector::RightVector; +} + +void AEgoSensor::ComputeFocusInfo() +{ + // ECC_Visibility: General visibility testing channel. + // ECC_Camera: Usually used when tracing from the camera to something. + // https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/ECollisionChannel/ + // https://zompidev.blogspot.com/2021/08/visibility-vs-camera-trace-channels-in.html + ComputeTraceFocusInfo(ECC_Visibility); +} + +bool AEgoSensor::ComputeGazeTrace(FHitResult &Hit, const ECollisionChannel TraceChannel, float TraceRadius) const +{ + const float TraceLen = MaxTraceLenM * 100.f; // convert to m from cm + const FRotator &WorldRot = GetData()->GetCameraRotationAbs(); + const FVector &WorldPos = GetData()->GetCameraLocationAbs(); + const FVector GazeOrigin = WorldPos + WorldRot.RotateVector(GetData()->GetGazeOrigin()); + const FVector GazeRay = TraceLen * WorldRot.RotateVector(GetData()->GetGazeDir()).GetSafeNormal(); + // Create collision information container. + FCollisionQueryParams TraceParam; + TraceParam = FCollisionQueryParams(FName("TraceParam"), true); + if (Vehicle.IsValid()) + TraceParam.AddIgnoredActor(Vehicle.Get()); // don't collide with the vehicle since that would be useless + TraceParam.bTraceComplex = true; + TraceParam.bReturnPhysicalMaterial = false; + Hit = FHitResult(EForceInit::ForceInit); + bool bDidHit = false; + + // 0 for a point, >0 for a sphear trace + TraceRadius = FMath::Max(TraceRadius, 0.f); // clamp to be positive + + ensure(World != nullptr); + if (TraceRadius == 0.f) // Single ray/line trace + { + bDidHit = World->LineTraceSingleByChannel(Hit, GazeOrigin, GazeOrigin + GazeRay, TraceChannel, TraceParam); + } + else // Sphear line trace + { + FCollisionShape Sphear = FCollisionShape(); + Sphear.SetSphere(TraceRadius); + bDidHit = World->SweepSingleByChannel(Hit, GazeOrigin, GazeOrigin + GazeRay, FQuat(0.f, 0.f, 0.f, 0.f), + TraceChannel, Sphear, TraceParam); + } + + if (!bDidHit) + { + // focus point is just straight ahead to the maximum trace length + Hit.Actor = nullptr; + Hit.Location = GazeOrigin + GazeRay; + Hit.Distance = TraceLen; + } + + if (bDrawDebugFocusTrace) + { + DrawDebugSphere(World, Hit.Location, 8.0f, 30, FColor::Blue); + DrawDebugLine(World, + GazeOrigin, // start line + GazeOrigin + GazeRay, // end line + FColor::Purple, false, -1, 0, 1); + } + return bDidHit; +} + +void AEgoSensor::ComputeTraceFocusInfo(const ECollisionChannel TraceChannel, float TraceRadius) +{ + FHitResult Hit; + bool bDidHit = ComputeGazeTrace(Hit, TraceChannel, TraceRadius); + // Update fields + FString ActorName = "None"; + if (Hit.Actor != nullptr) + { + Hit.Actor->GetName(ActorName); + FString Suffix = ""; // suffix to the actor "name" (actor type we care about) + if (Cast(Hit.Actor) != nullptr) + Suffix = "_Vehicle"; + else if (Cast(Hit.Actor) != nullptr) + Suffix = "_Walker"; + else if (Cast(Hit.Actor) != nullptr) + Suffix = "_TrafficLight"; + /// TODO: add more suffixes here. + ActorName += Suffix; + } + + // update internal data structure (see DReyeVRData::FocusInfo) + FocusInfoData.Actor = Hit.Actor; // pointer to actor being hit (if any, else nullptr) + FocusInfoData.HitPoint = Hit.Location; // absolute (world) location of hit + FocusInfoData.Normal = Hit.Normal; // normal of hit surface (if hit) + FocusInfoData.ActorNameTag = ActorName; // name of the actor being hit (if any, else "None") + FocusInfoData.Distance = Hit.Distance; // distance from ray start + FocusInfoData.bDidHit = bDidHit; // whether or not there was a hit +} + +float AEgoSensor::ComputeVergence(const FVector &L0, const FVector &LDir, const FVector &R0, const FVector &RDir) const +{ + // Compute length of ray-to- intersection of the left and right eye gazes in 3D space (length in centimeters) + return ComputeClosestToRayIntersection(L0, LDir, R0, RDir).Size(); // units are cm (default for UE4) +} + +/// ========================================== /// +/// ---------------:EGOVARS:------------------ /// +/// ========================================== /// + +void AEgoSensor::SetEgoVehicle(class AEgoVehicle *NewEgoVehicle) +{ + Vehicle = NewEgoVehicle; + check(Vehicle.IsValid()); + + // Also check that the ConfigFileData variable can be written to with Vehicle params + check(ConfigFile); // this is a static variable created in the parent (ADReyeVRSensor) + + // track both the VehicleParams and GeneralParams + const auto ConfigFileStr = Vehicle.Get()->GetVehicleParams().Export() + GeneralParams.Export(); + ConfigFile->Set(ConfigFileStr); // track this config file once + + // saved from some previous request to compare, but failed bc no EgoVehicle + if (RecordingCF != nullptr) + { + UpdateData(*RecordingCF, 0.f); + } +} + +void AEgoSensor::ComputeEgoVars() +{ + if (!Vehicle.IsValid()) + { + LOG_WARN("Invalid EgoVehicle, cannot compute EgoVars"); + return; + } + // See DReyeVRData::EgoVariables + auto *Ego = Vehicle.Get(); + auto *Camera = Ego->GetCamera(); + check(Camera); + EgoVars.VehicleLocation = Ego->GetActorLocation(); + EgoVars.VehicleRotation = Ego->GetActorRotation(); + EgoVars.CameraLocation = Camera->GetRelativeLocation(); + EgoVars.CameraRotation = Camera->GetRelativeRotation(); + EgoVars.CameraLocationAbs = Camera->GetComponentLocation(); + EgoVars.CameraRotationAbs = Camera->GetComponentRotation(); + EgoVars.Velocity = Ego->GetVehicleForwardSpeed(); +} + +/// ========================================== /// +/// ---------------:FRAMECAP:----------------- /// +/// ========================================== /// + +void AEgoSensor::ConstructFrameCapture() +{ + if (bCaptureFrameData) + { + // Frame capture + CaptureRenderTarget = CreateDefaultSubobject(TEXT("CaptureRenderTarget_DReyeVR")); + CaptureRenderTarget->CompressionSettings = TextureCompressionSettings::TC_Default; + CaptureRenderTarget->SRGB = false; + CaptureRenderTarget->bAutoGenerateMips = false; + CaptureRenderTarget->bGPUSharedFlag = true; + CaptureRenderTarget->ClearColor = FLinearColor::Black; + CaptureRenderTarget->UpdateResourceImmediate(true); + // CaptureRenderTarget->OverrideFormat = EPixelFormat::PF_FloatRGB; + CaptureRenderTarget->AddressX = TextureAddress::TA_Clamp; + CaptureRenderTarget->AddressY = TextureAddress::TA_Clamp; + CaptureRenderTarget->InitCustomFormat(FrameCapWidth, FrameCapHeight, PF_B8G8R8A8, bFrameCapForceLinearGamma); + check(CaptureRenderTarget->GetSurfaceWidth() > 0 && CaptureRenderTarget->GetSurfaceHeight() > 0); + + FrameCap = CreateDefaultSubobject(TEXT("FrameCap")); + FrameCap->PrimitiveRenderMode = ESceneCapturePrimitiveRenderMode::PRM_RenderScenePrimitives; + FrameCap->bCaptureOnMovement = false; + FrameCap->bCaptureEveryFrame = false; + FrameCap->bAlwaysPersistRenderingState = true; + FrameCap->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR; + + // apply postprocessing effects + FrameCap->PostProcessSettings = CreatePostProcessingEffect(0); + + FrameCap->Deactivate(); + FrameCap->TextureTarget = CaptureRenderTarget; + FrameCap->UpdateContent(); + FrameCap->Activate(); + } + if (FrameCap && !bCaptureFrameData) + { + FrameCap->Deactivate(); + } +} + +void AEgoSensor::InitFrameCapture() +{ + if (bCaptureFrameData) + { + // initialize frame capture attachment to the ego vehicle + if (FrameCap && Vehicle.IsValid()) + FrameCap->SetupAttachment(Vehicle.Get()->GetCamera()); + + // creates the directory for the frame capture to take place + /// TODO: add check for absolute paths + FrameCapLocation = FPaths::ConvertRelativePathToFull(FPaths::ProjectDir() + FrameCapLocation); + // The returned string has the following format: yyyy.mm.dd-hh.mm.ss + FString DirName = FDateTime::Now().ToString(); // timestamp directory + FrameCapLocation = FPaths::Combine(FrameCapLocation, DirName); + + // create directory if not present + LOG("Outputting frame capture data to %s", *FrameCapLocation); + IPlatformFile &PlatformFile = FPlatformFileManager::Get().GetPlatformFile(); + if (!PlatformFile.DirectoryExists(*FrameCapLocation)) + { +#ifdef CreateDirectory + // using Windows system calls + CreateDirectory(*FrameCapLocation, NULL); +#else + // this only seems to work on Unix systems, else CreateDirectoryW is not linked? + PlatformFile.CreateDirectory(*FrameCapLocation); +#endif + } + bCreatedDirectory = true; + } +} + +void AEgoSensor::TakeScreenshot() +{ + /// NOTE: this is a slow function that takes multiple high-res screenshots (with different shader params) + // of the current scene and writes the images to disk immediately. The intention is to use this function + // during synchronized replay with screen capture so that performance is not an issue since the simulator + // is not necessarily running in real-time. + + // create directory if necessary + if (bCaptureFrameData && !bCreatedDirectory) + { + InitFrameCapture(); // Set up frame capture directory + } + + // capture the screenshot to the directory + if (bCaptureFrameData && FrameCap && Vehicle.IsValid()) + { + for (int i = 0; i < GetNumberOfShaders(); i++) + { + // apply the postprocessing effect + FrameCap->PostProcessSettings = CreatePostProcessingEffect(i); + // loop through all camera poses + for (int j = 0; j < Vehicle.Get()->GetNumCameraPoses(); j++) + { + // set this pose + Vehicle.Get()->SetCameraRootPose(j); + + // using 5 digits to reach frame 99999 ~ 30m (assuming ~50fps frame capture) + // suffix is denoted as _s(hader)X_p(ose)Y_Z.png where X is the shader idx, Y is the pose idx, Z is tick + const FString Suffix = FString::Printf(TEXT("_s%d_p%d_%05d.png"), i, j, ScreenshotCount); + // apply the camera view (position & orientation) + FMinimalViewInfo DesiredView; + Vehicle.Get()->GetCamera()->GetCameraView(0, DesiredView); + FrameCap->SetCameraView(DesiredView); // move camera to the camera view + // capture the scene and save the screenshot to disk + FrameCap->CaptureScene(); // also available: CaptureSceneDeferred() + SaveFrameToDisk(*CaptureRenderTarget, FPaths::Combine(FrameCapLocation, FrameCapFilename + Suffix), + bFileFormatJPG); + if (!bRecordAllPoses) + { + // exit after the first camera pose (seated) + break; + } + } + // set camera pose back to 0 + Vehicle.Get()->SetCameraRootPose(0); + if (!bRecordAllShaders) + { + // exit after the first shader (rgb) + break; + } + } + ScreenshotCount++; // progress to next frame + } +} + +/// ========================================== /// +/// ------------:FOVEATEDRENDER:-------------- /// +/// ========================================== /// + +void AEgoSensor::ConvertToEyeTrackerSpace(FVector &inVec) const +{ + FVector temp = inVec; + inVec.X = -1 * temp.Y; + inVec.Y = temp.Z; + inVec.Z = temp.X; +} + +void AEgoSensor::TickFoveatedRender() +{ +#if USE_FOVEATED_RENDER + FEyeTrackerStereoGazeData F; + F.LeftEyeOrigin = GetData()->GetGazeOrigin(DReyeVR::Gaze::LEFT); + F.LeftEyeDirection = GetData()->GetGazeDir(DReyeVR::Gaze::LEFT); + ConvertToEyeTrackerSpace(F.LeftEyeDirection); + F.RightEyeOrigin = GetData()->GetGazeOrigin(DReyeVR::Gaze::RIGHT); + F.RightEyeDirection = GetData()->GetGazeDir(DReyeVR::Gaze::RIGHT); + ConvertToEyeTrackerSpace(F.RightEyeDirection); + F.FixationPoint = GetData()->GetFocusActorPoint(); + F.ConfidenceValue = 0.99f; + UVariableRateShadingFunctionLibrary::UpdateStereoGazeDataToFoveatedRendering(F); +#endif +} + +/// ========================================== /// +/// ----------------:REPLAY:------------------ /// +/// ========================================== /// + +// don't need to override the base ADReyeVRSensor::UpdateData(); + +void AEgoSensor::UpdateData(const DReyeVR::ConfigFileData &RecordedParams, const double Per) +{ + if (!Vehicle.IsValid()) + { + // LOG_WARN("Unable to compare ConfigFile bc EgoVehicle is invalid!"); + RecordingCF = new DReyeVR::ConfigFileData(); + (*RecordingCF) = RecordedParams; // save these params for later (ex. SetEgoVehicle) + return; + } + // compare the incoming (recording) ConfigFile with our current (live) one + const std::string RecordingExport = TCHAR_TO_UTF8(*RecordedParams.ToString()); + const struct ConfigFile Recorded = ConfigFile::Import(RecordingExport); + + // includes both the vehicle params and general params + struct ConfigFile LiveConfig; + LiveConfig.Insert(Vehicle.Get()->GetVehicleParams()); + LiveConfig.Insert(GeneralParams); + + bool bPrintWarnings = true; + if (LiveConfig.IsSubset(Recorded, bPrintWarnings)) // don't care if Recorded has entries that we dont + { + LOG("Config file comparison successful!"); + } + else + { + LOG_WARN("Config file comparison failed! This means the recording was performed with a different configuration " + "file than what is currently active. You might want to check that this does not affect the validity " + "of your replay."); + } +} + +void AEgoSensor::UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) +{ + if (Vehicle.IsValid() && Vehicle.Get()->GetGame()) + Vehicle.Get()->GetGame()->ReplayCustomActor(RecorderData, Per); } \ No newline at end of file diff --git a/DReyeVR/EgoSensor.h b/DReyeVR/EgoSensor.h index 3e89d4c..c957b4e 100644 --- a/DReyeVR/EgoSensor.h +++ b/DReyeVR/EgoSensor.h @@ -1,106 +1,106 @@ -#pragma once - -#include "Carla/Sensor/DReyeVRData.h" // DReyeVR namespace -#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor -#include "Components/SceneCaptureComponent2D.h" // USceneCaptureComponent2D -#include // timing threads -#include - -#if USE_SRANIPAL_PLUGIN - -// avoid macro conflict since SRanipal uses "ERROR" often -#ifdef ERROR -#undef ERROR -#endif - -/// NOTE: Can only use SRanipal on Windows machines -#include "SRanipalEye.h" // SRanipal Module Framework -#include "SRanipalEye_Core.h" // SRanipal Eye Tracker -#include "ViveSR_Enums.h" // ViveSR::Error::WORK -// Make sure to patch sranipal before using it here! -#include "SRanipalEye_Framework.h" // StartFramework -#endif - -#include "EgoSensor.generated.h" - -class AEgoVehicle; -class ADReyeVRGameMode; - -UCLASS() -class CARLAUE4_API AEgoSensor : public ADReyeVRSensor -{ - GENERATED_BODY() - - public: - AEgoSensor(const FObjectInitializer &ObjectInitializer); - - void ManualTick(float DeltaSeconds); // Tick called explicitly from DReyeVR EgoVehicle - - void SetEgoVehicle(class AEgoVehicle *EgoVehicle); // provide access to EgoVehicle (and by extension its camera) - - void UpdateData(const DReyeVR::ConfigFileData &RecorderData, const double Per) override; - void UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) override; - - // function where replayer requests a screenshot - void TakeScreenshot() override; - bool ComputeGazeTrace(FHitResult &Hit, const ECollisionChannel TraceChannel, float TraceRadius = 0.f) const; - - protected: - void BeginPlay(); - void BeginDestroy(); - - class UWorld *World; // to get info about the world: time, frames, etc. - - private: - int64_t TickCount = 0; // how many ticks have been executed - void ReadConfigVariables(); - - private: // eye tracker - void InitEyeTracker(); - void DestroyEyeTracker(); - void ComputeDummyEyeData(); // when no hardware sensor is present - void TickEyeTracker(); // tick hardware sensor - void ComputeFocusInfo(); - void ComputeTraceFocusInfo(const ECollisionChannel TraceChannel, float TraceRadius = 0.f); - float MaxTraceLenM = 100.f; // maximum trace length in m - bool bDrawDebugFocusTrace = false; // draw the trace ray and hit point or not - float ComputeVergence(const FVector &L0, const FVector &LDir, const FVector &R0, const FVector &RDir) const; -#if USE_SRANIPAL_PLUGIN - SRanipalEye_Core *SRanipal; // SRanipalEye_Core.h - SRanipalEye_Framework *SRanipalFramework; // SRanipalEye_Framework.h - ViveSR::anipal::Eye::EyeData EyeData; // SRanipal_Eyes_Enums.h - bool bSRanipalEnabled; // Whether or not the framework has been loaded -#endif - struct DReyeVR::EyeTracker EyeSensorData; // data from eye tracker - struct DReyeVR::FocusInfo FocusInfoData; // data from the focus computed from eye gaze - std::chrono::time_point ChronoStartTime; // std::chrono time at BeginPlay - - private: // ego=vehicle variables - void ComputeEgoVars(); - TWeakObjectPtr Vehicle; // the DReyeVR EgoVehicle - struct DReyeVR::EgoVariables EgoVars; // data from vehicle that is getting tracked - DReyeVR::ConfigFileData *RecordingCF = nullptr; - - private: // frame capture - size_t ScreenshotCount = 0; - void ConstructFrameCapture(); // needs to be called in the constructor - void InitFrameCapture(); // needs to be called in BeginPlay - class UTextureRenderTarget2D *CaptureRenderTarget = nullptr; - class USceneCaptureComponent2D *FrameCap = nullptr; - FString FrameCapLocation; // relative to game dir - FString FrameCapFilename; // gets ${tick}.png suffix - int FrameCapWidth; - int FrameCapHeight; - bool bCaptureFrameData; - bool bRecordAllShaders; - bool bRecordAllPoses; - bool bCreatedDirectory = false; - bool bFileFormatJPG = true; - bool bFrameCapForceLinearGamma = true; - - private: // foveated rendering - void TickFoveatedRender(); - void ConvertToEyeTrackerSpace(FVector &inVec) const; - bool bEnableFovRender = false; - bool bUseEyeTrackingVRS = true; +#pragma once + +#include "Carla/Sensor/DReyeVRData.h" // DReyeVR namespace +#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor +#include "Components/SceneCaptureComponent2D.h" // USceneCaptureComponent2D +#include // timing threads +#include + +#if USE_SRANIPAL_PLUGIN + +// avoid macro conflict since SRanipal uses "ERROR" often +#ifdef ERROR +#undef ERROR +#endif + +/// NOTE: Can only use SRanipal on Windows machines +#include "SRanipalEye.h" // SRanipal Module Framework +#include "SRanipalEye_Core.h" // SRanipal Eye Tracker +#include "ViveSR_Enums.h" // ViveSR::Error::WORK +// Make sure to patch sranipal before using it here! +#include "SRanipalEye_Framework.h" // StartFramework +#endif + +#include "EgoSensor.generated.h" + +class AEgoVehicle; +class ADReyeVRGameMode; + +UCLASS() +class CARLAUE4_API AEgoSensor : public ADReyeVRSensor +{ + GENERATED_BODY() + + public: + AEgoSensor(const FObjectInitializer &ObjectInitializer); + + void ManualTick(float DeltaSeconds); // Tick called explicitly from DReyeVR EgoVehicle + + void SetEgoVehicle(class AEgoVehicle *EgoVehicle); // provide access to EgoVehicle (and by extension its camera) + + void UpdateData(const DReyeVR::ConfigFileData &RecorderData, const double Per) override; + void UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) override; + + // function where replayer requests a screenshot + void TakeScreenshot() override; + bool ComputeGazeTrace(FHitResult &Hit, const ECollisionChannel TraceChannel, float TraceRadius = 0.f) const; + + protected: + void BeginPlay(); + void BeginDestroy(); + + class UWorld *World; // to get info about the world: time, frames, etc. + + private: + int64_t TickCount = 0; // how many ticks have been executed + void ReadConfigVariables(); + + private: // eye tracker + void InitEyeTracker(); + void DestroyEyeTracker(); + void ComputeDummyEyeData(); // when no hardware sensor is present + void TickEyeTracker(); // tick hardware sensor + void ComputeFocusInfo(); + void ComputeTraceFocusInfo(const ECollisionChannel TraceChannel, float TraceRadius = 0.f); + float MaxTraceLenM = 100.f; // maximum trace length in m + bool bDrawDebugFocusTrace = false; // draw the trace ray and hit point or not + float ComputeVergence(const FVector &L0, const FVector &LDir, const FVector &R0, const FVector &RDir) const; +#if USE_SRANIPAL_PLUGIN + SRanipalEye_Core *SRanipal; // SRanipalEye_Core.h + SRanipalEye_Framework *SRanipalFramework; // SRanipalEye_Framework.h + ViveSR::anipal::Eye::EyeData EyeData; // SRanipal_Eyes_Enums.h + bool bSRanipalEnabled; // Whether or not the framework has been loaded +#endif + struct DReyeVR::EyeTracker EyeSensorData; // data from eye tracker + struct DReyeVR::FocusInfo FocusInfoData; // data from the focus computed from eye gaze + std::chrono::time_point ChronoStartTime; // std::chrono time at BeginPlay + + private: // ego=vehicle variables + void ComputeEgoVars(); + TWeakObjectPtr Vehicle; // the DReyeVR EgoVehicle + struct DReyeVR::EgoVariables EgoVars; // data from vehicle that is getting tracked + DReyeVR::ConfigFileData *RecordingCF = nullptr; + + private: // frame capture + size_t ScreenshotCount = 0; + void ConstructFrameCapture(); // needs to be called in the constructor + void InitFrameCapture(); // needs to be called in BeginPlay + class UTextureRenderTarget2D *CaptureRenderTarget = nullptr; + class USceneCaptureComponent2D *FrameCap = nullptr; + FString FrameCapLocation; // relative to game dir + FString FrameCapFilename; // gets ${tick}.png suffix + int FrameCapWidth; + int FrameCapHeight; + bool bCaptureFrameData; + bool bRecordAllShaders; + bool bRecordAllPoses; + bool bCreatedDirectory = false; + bool bFileFormatJPG = true; + bool bFrameCapForceLinearGamma = true; + + private: // foveated rendering + void TickFoveatedRender(); + void ConvertToEyeTrackerSpace(FVector &inVec) const; + bool bEnableFovRender = false; + bool bUseEyeTrackingVRS = true; }; \ No newline at end of file diff --git a/DReyeVR/EgoVehicle.cpp b/DReyeVR/EgoVehicle.cpp index 9b67967..73acb60 100644 --- a/DReyeVR/EgoVehicle.cpp +++ b/DReyeVR/EgoVehicle.cpp @@ -1,1080 +1,1080 @@ -#include "EgoVehicle.h" -#include "Carla/Actor/ActorAttribute.h" // FActorAttribute -#include "Carla/Actor/ActorRegistry.h" // Register -#include "Carla/Game/CarlaStatics.h" // GetCurrentEpisode -#include "Carla/Vehicle/CarlaWheeledVehicleState.h" // ECarlaWheeledVehicleState -#include "DReyeVRPawn.h" // ADReyeVRPawn -#include "DrawDebugHelpers.h" // Debug Line/Sphere -#include "Engine/EngineTypes.h" // EBlendMode -#include "Engine/World.h" // GetWorld -#include "GameFramework/Actor.h" // Destroy -#include "Kismet/KismetSystemLibrary.h" // PrintString, QuitGame -#include "Math/Rotator.h" // RotateVector, Clamp -#include "Math/UnrealMathUtility.h" // Clamp - -#include - -// Sets default values -AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) -{ - LOG("Constructing Ego Vehicle: %s", *FString(this->GetName())); - - ReadConfigVariables(); - - // this actor ticks AFTER the physics simulation is done - PrimaryActorTick.bCanEverTick = true; - PrimaryActorTick.bStartWithTickEnabled = true; - PrimaryActorTick.bAllowTickOnDedicatedServer = true; - PrimaryActorTick.TickGroup = TG_PostPhysics; - AIControllerClass = AWheeledVehicleAIController::StaticClass(); - - // Set up the root position to be the this mesh - SetRootComponent(GetMesh()); - - // Initialize the camera components - ConstructCameraRoot(); - - // Initialize audio components - ConstructEgoSounds(); - - // Initialize mirrors - ConstructMirrors(); - - // Initialize text render components - ConstructDashText(); - - // Initialize the steering wheel - ConstructSteeringWheel(); - - LOG("Finished constructing %s", *FString(this->GetName())); -} - -void AEgoVehicle::ReadConfigVariables() -{ - // this matches the BP_XYZ (XYZ) part of the blueprint, or "Vehicle" if just an EgoVehicle - VehicleType = CleanNameForDReyeVR(GetClass()->GetName()); - LOG("Initializing EgoVehicle: \"%s\"", *VehicleType); - if (!VehicleType.Equals("Vehicle", ESearchCase::CaseSensitive)) - { - auto NewParams = ConfigFile(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles"), VehicleType + ".ini")); - if (NewParams.bIsValid()) - VehicleParams = NewParams; - } - - // if the VehicleParams is invalid, use a default - if (!VehicleParams.bIsValid()) - VehicleParams = ConfigFile(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles/TeslaM3.ini")), false); - ensure(VehicleParams.bIsValid()); - - GeneralParams.Get("EgoVehicle", "EnableTurnSignalAction", bEnableTurnSignalAction); - GeneralParams.Get("EgoVehicle", "TurnSignalDuration", TurnSignalDuration); - // mirrors - auto InitMirrorParams = [this](const FString &Name, struct MirrorParams &Params) { - Params.Name = Name; - VehicleParams.Get("Mirrors", Params.Name + "MirrorEnabled", Params.Enabled); - VehicleParams.Get("Mirrors", Params.Name + "MirrorTransform", Params.MirrorTransform); - VehicleParams.Get("Mirrors", Params.Name + "ReflectionTransform", Params.ReflectionTransform); - VehicleParams.Get("Mirrors", Params.Name + "ScreenPercentage", Params.ScreenPercentage); - }; - InitMirrorParams("Rear", RearMirrorParams); - InitMirrorParams("Left", LeftMirrorParams); - InitMirrorParams("Right", RightMirrorParams); - // rear mirror chassis - VehicleParams.Get("Mirrors", "RearMirrorChassisTransform", RearMirrorChassisTransform); - // steering wheel - VehicleParams.Get("SteeringWheel", "MaxSteerAngleDeg", MaxSteerAngleDeg); - VehicleParams.Get("SteeringWheel", "SteeringScale", SteeringAnimScale); - // other/cosmetic - GeneralParams.Get("EgoVehicle", "DrawDebugEditor", bDrawDebugEditor); - // inputs - GeneralParams.Get("VehicleInputs", "ScaleSteeringDamping", ScaleSteeringInput); - GeneralParams.Get("VehicleInputs", "ScaleThrottleInput", ScaleThrottleInput); - GeneralParams.Get("VehicleInputs", "ScaleBrakeInput", ScaleBrakeInput); - // replay - GeneralParams.Get("Replayer", "CameraFollowHMD", bCameraFollowHMD); -} - -void AEgoVehicle::BeginPlay() -{ - // Called when the game starts or when spawned - Super::BeginPlay(); - - // Get information about the world - World = GetWorld(); - ensure(World != nullptr); - - // initialize - InitAIPlayer(); - - // Bug-workaround for initial delay on throttle; see https://github.com/carla-simulator/carla/issues/1640 - this->GetVehicleMovementComponent()->SetTargetGear(1, true); - - // get the GameMode script - SetGame(Cast(UGameplayStatics::GetGameMode(World))); - - BeginThirdPersonCameraInit(); - - LOG("Initialized DReyeVR EgoVehicle"); -} - -void AEgoVehicle::EndPlay(const EEndPlayReason::Type EndPlayReason) -{ - // https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/EEndPlayReason__Type/ - if (EndPlayReason == EEndPlayReason::Destroyed) - { - LOG("DReyeVR EgoVehicle is being destroyed! You'll need to spawn another one!"); - if (GetGame()) - { - GetGame()->PossessSpectator(); - } - } - - if (this->Pawn) - { - this->Pawn->SetEgoVehicle(nullptr); - } -} - -void AEgoVehicle::BeginDestroy() -{ - Super::BeginDestroy(); - - // destroy all spawned entities - if (EgoSensor.IsValid()) - EgoSensor.Get()->Destroy(); - - DestroySteeringWheel(); - - LOG("EgoVehicle has been destroyed"); -} - -// Called every frame -void AEgoVehicle::Tick(float DeltaSeconds) -{ - Super::Tick(DeltaSeconds); - - // Get the current data from the AEgoSensor and use it - UpdateSensor(DeltaSeconds); - - // Update the positions based off replay data - ReplayTick(); - - // Draw debug lines on editor - DebugLines(); - - // Render EgoVehicle dashboard - UpdateDash(); - - // Update the steering wheel to be responsive to user input - TickSteeringWheel(DeltaSeconds); - - // Ensure appropriate autopilot functionality is accessible from EgoVehicle - TickAutopilot(); - - // Update the world level - TickGame(DeltaSeconds); - - // Tick vehicle controls - TickVehicleInputs(); -} - -/// ========================================== /// -/// ----------------:CAMERA:------------------ /// -/// ========================================== /// - -template T *AEgoVehicle::CreateEgoObject(const FString &Name, const FString &Suffix) -{ - // create default subobject with this name and (optionally) add a suffix - // https://docs.unrealengine.com/4.26/en-US/API/Runtime/CoreUObject/UObject/UObject/CreateDefaultSubobject/2/ - // see also: https://dev.epicgames.com/community/snippets/0bk/actor-component-creation - // if the blueprint gets corrupted (ex. object details no longer visible), reparent to BaseVehiclePawn then back - T *Ret = UObject::CreateDefaultSubobject(FName(*(Name + Suffix))); - // disabling tick for these objects by default - Ret->SetComponentTickEnabled(false); - Ret->PrimaryComponentTick.bCanEverTick = false; - Ret->PrimaryComponentTick.bStartWithTickEnabled = false; - return Ret; -} - -void AEgoVehicle::ConstructCameraRoot() -{ - // Spawn the RootComponent and Camera for the VR camera - VRCameraRoot = CreateEgoObject("VRCameraRoot"); - check(VRCameraRoot != nullptr); - VRCameraRoot->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself - VRCameraRoot->SetRelativeLocation(FVector::ZeroVector); - VRCameraRoot->SetRelativeRotation(FRotator::ZeroRotator); - - // add first-person driver's seat - CameraTransforms.Add("DriversSeat", VehicleParams.Get("CameraPose", "DriversSeat")); - - SetCameraRootPose("DriversSeat"); -} - -void AEgoVehicle::BeginThirdPersonCameraInit() -{ - // add third-person views - - std::vector CameraPoses = { - "ThirdPerson", // 2nd - "BirdsEyeView", // 3rd - "Front", // 4th - }; - UBoxComponent *Bounds = this->GetVehicleBoundingBox(); - ensure(Bounds != nullptr); - if (Bounds != nullptr) - { - const FVector BoundingBoxSize = Bounds->GetScaledBoxExtent(); - LOG("Calculated EgoVehicle bounding box: %s", *BoundingBoxSize.ToString()); - for (FString &Key : CameraPoses) - { - FTransform Transform = GeneralParams.Get("CameraPose", Key); - Transform.SetLocation(Transform.GetLocation() * BoundingBoxSize); // scale by bounding box - CameraTransforms.Add(Key, Transform); - } - } - - CameraTransforms.GenerateKeyArray(CameraPoseKeys); - ensure(CameraPoseKeys.Num() > 0); - - // assign the starting camera root pose to the given starting pose - FString StartingPose = GeneralParams.Get("CameraPose", "StartingPose"); - SetCameraRootPose(StartingPose); -} - -void AEgoVehicle::SetCameraRootPose(const FString &CameraPoseName) -{ - FTransform NewCameraTransform; - // given a string (key), index into the map to obtain the FTransform - if (CameraTransforms.Contains(CameraPoseName)) - { - NewCameraTransform = CameraTransforms[CameraPoseName]; - } - else - { - LOG_WARN("Unable to find camera pose named \"%s\". Defaulting to driver's seat!", *CameraPoseName); - NewCameraTransform = CameraTransforms["DriversSeat"]; - } - SetCameraRootPose(NewCameraTransform); -} - -size_t AEgoVehicle::GetNumCameraPoses() const -{ - return CameraTransforms.Num(); -} - -void AEgoVehicle::SetCameraRootPose(size_t CameraPoseIdx) -{ - if (CameraPoseKeys.Num() == 0) - return; - // allow setting the camera root by indexing into CameraTransforms array - CameraPoseIdx = std::min(CameraPoseIdx, static_cast(CameraPoseKeys.Num() - 1)); - const auto &Key = CameraPoseKeys[CameraPoseIdx]; - const FTransform *NewPose = CameraTransforms.Find(Key); - if (NewPose == nullptr) - { - LOG_ERROR("Unable to find camera pose \"%s\"", *Key); - return; - } - SetCameraRootPose(*NewPose); -} - -void AEgoVehicle::SetCameraRootPose(const FTransform &CameraPoseTransform) -{ - // sets the base posision of the Camera root (where the camera is at "rest") - this->CameraPose = CameraPoseTransform; - // LOG("Setting camera pose to: %s", *(CameraPose + CameraPoseOffset).ToString()); - - // First, set the root of the camera to the driver's seat head pos - VRCameraRoot->SetRelativeLocation(CameraPose.GetLocation() + CameraPoseOffset.GetLocation()); - VRCameraRoot->SetRelativeRotation(CameraPose.Rotator() + CameraPoseOffset.Rotator()); -} - -void AEgoVehicle::SetPawn(ADReyeVRPawn *PawnIn) -{ - ensure(VRCameraRoot != nullptr); - this->Pawn = PawnIn; - ensure(Pawn != nullptr); - this->FirstPersonCam = Pawn->GetCamera(); - ensure(FirstPersonCam != nullptr); - FAttachmentTransformRules F(EAttachmentRule::KeepRelative, false); - Pawn->AttachToComponent(VRCameraRoot, F); - FirstPersonCam->AttachToComponent(VRCameraRoot, F); - // Then set the actual camera to be at its origin (attached to VRCameraRoot) - FirstPersonCam->SetRelativeLocation(FVector::ZeroVector); - FirstPersonCam->SetRelativeRotation(FRotator::ZeroRotator); -} - -const FString &AEgoVehicle::GetVehicleType() const -{ - return VehicleType; -} -const UCameraComponent *AEgoVehicle::GetCamera() const -{ - ensure(FirstPersonCam != nullptr); - return FirstPersonCam; -} -UCameraComponent *AEgoVehicle::GetCamera() -{ - ensure(FirstPersonCam != nullptr); - return FirstPersonCam; -} -FVector AEgoVehicle::GetCameraOffset() const -{ - return VRCameraRoot->GetComponentLocation(); -} -FVector AEgoVehicle::GetCameraPosn() const -{ - return GetCamera() ? GetCamera()->GetComponentLocation() : FVector::ZeroVector; -} -FVector AEgoVehicle::GetNextCameraPosn(const float DeltaSeconds) const -{ - // usually only need this is tick before physics - return GetCameraPosn() + DeltaSeconds * GetVelocity(); -} -FRotator AEgoVehicle::GetCameraRot() const -{ - return GetCamera() ? GetCamera()->GetComponentRotation() : FRotator::ZeroRotator; -} -class AEgoSensor *AEgoVehicle::GetSensor() -{ - // tries to return the EgoSensor pointer if it is safe to do so, else re-spawn it - return SafePtrGet("EgoSensor", EgoSensor, [&](void) { this->InitSensor(); }); -} - -const class AEgoSensor *AEgoVehicle::GetSensor() const -{ - // tries to return the EgoSensor pointer if it is safe to do so, else re-spawn it - return const_cast(const_cast(this)->GetSensor()); -} - -const struct ConfigFile &AEgoVehicle::GetVehicleParams() const -{ - return VehicleParams; -} - -/// ========================================== /// -/// ---------------:AIPLAYER:----------------- /// -/// ========================================== /// - -void AEgoVehicle::InitAIPlayer() -{ - this->SpawnDefaultController(); // spawns default (AI) controller and gets possessed by it - auto PlayerController = GetController(); - ensure(PlayerController != nullptr); - AI_Player = Cast(PlayerController); - check(AI_Player != nullptr); - SetAutopilot(false); // initially no autopilot enabled -} - -void AEgoVehicle::SetAutopilot(const bool AutopilotOn) -{ - if (!AI_Player) - return; - bAutopilotEnabled = AutopilotOn; - AI_Player->SetAutopilot(bAutopilotEnabled); - AI_Player->SetStickyControl(bAutopilotEnabled); - // AI_Player->SetActorTickEnabled(bAutopilotEnabled); // want the controller to always tick! -} - -bool AEgoVehicle::GetAutopilotStatus() const -{ - return bAutopilotEnabled; -} - -void AEgoVehicle::TickAutopilot() -{ - ensure(AI_Player != nullptr); - if (AI_Player != nullptr) - { - bAutopilotEnabled = AI_Player->IsAutopilotEnabled(); - TickAutopilotIndicator(bAutopilotEnabled); - } -} - -/// ========================================== /// -/// ----------------:SENSOR:------------------ /// -/// ========================================== /// - -void AEgoVehicle::InitSensor() -{ - // update the world on refresh (ex. --reloadWorld) - World = GetWorld(); - check(World != nullptr); - // Spawn the EyeTracker Carla sensor and attach to Ego-Vehicle: - { - UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(World); - check(Episode != nullptr); - FActorDefinition EgoSensorDef = FindDefnInRegistry(Episode, AEgoSensor::StaticClass()); - FActorDescription Description; - { // create a Description from the Definition to spawn the actor - Description.UId = EgoSensorDef.UId; - Description.Id = EgoSensorDef.Id; - Description.Class = EgoSensorDef.Class; - // add all the attributes from the definition to the description - for (FActorAttribute A : EgoSensorDef.Attributes) - { - Description.Variations.Add(A.Id, std::move(A)); - } - } - // calls Episode::SpawnActor => SpawnActorWithInfo => ActorDispatcher->SpawnActor => SpawnFunctions[UId] - FTransform SpawnPt = FTransform(FRotator::ZeroRotator, GetCameraPosn(), FVector::OneVector); - EgoSensor = static_cast(Episode->SpawnActor(SpawnPt, Description)); - } - check(EgoSensor.IsValid()); - // Attach the EgoSensor as a child to the EgoVehicle - EgoSensor.Get()->SetOwner(this); - EgoSensor.Get()->AttachToActor(this, FAttachmentTransformRules::KeepRelativeTransform); - EgoSensor.Get()->SetActorTransform(FTransform::Identity, false, nullptr, ETeleportType::TeleportPhysics); - EgoSensor.Get()->SetEgoVehicle(this); -} - -void AEgoVehicle::ReplayTick() -{ - if (!EgoSensor.IsValid()) - return; - const bool bIsReplaying = EgoSensor.Get()->IsReplaying(); - // need to enable/disable VehicleMesh simulation - class USkeletalMeshComponent *VehicleMesh = GetMesh(); - if (VehicleMesh) - VehicleMesh->SetSimulatePhysics(!bIsReplaying); // disable physics when replaying (teleporting) - if (FirstPersonCam) - FirstPersonCam->bLockToHmd = !bIsReplaying; // only lock orientation and position to HMD when not replaying - - // perform all sensor updates that occur when replaying - if (bIsReplaying) - { - // this gets reached when the simulator is replaying data from a carla log - const DReyeVR::AggregateData *Replay = EgoSensor.Get()->GetData(); - - // include positional update here, else there is lag/jitter between the camera and the vehicle - // since the Carla Replayer tick differs from the EgoVehicle tick - const FTransform ReplayTransform(Replay->GetVehicleRotation(), // FRotator (Rotation) - Replay->GetVehicleLocation(), // FVector (Location) - FVector::OneVector); // FVector (Scale3D) - // see https://docs.unrealengine.com/4.26/en-US/API/Runtime/Engine/Engine/ETeleportType/ - SetActorTransform(ReplayTransform, false, nullptr, ETeleportType::TeleportPhysics); - - // set the camera reenactment orientation - { - const FTransform CameraOrientation = - bCameraFollowHMD // follow HMD reenacts all the head movmeents that were recorded - ? FTransform(Replay->GetCameraRotation(), Replay->GetCameraLocation(), FVector::OneVector) - : FTransform::Identity; // otherwise just point forward (neutral position) - FirstPersonCam->SetRelativeTransform(CameraOrientation, false, nullptr, ETeleportType::TeleportPhysics); - } - - // overwrite vehicle inputs to use the replay data - VehicleInputs = Replay->GetUserInputs(); - } -} - -void AEgoVehicle::UpdateSensor(const float DeltaSeconds) -{ - if (!EgoSensor.IsValid()) // Spawn and attach the EgoSensor - { - // unfortunately World->SpawnActor *sometimes* fails if used in BeginPlay so - // calling it once in the tick is fine to avoid this crash. - InitSensor(); - } - - if (!EgoSensor.IsValid()) - { - LOG_WARN("EgoSensor initialization failed!"); - return; - } - - // Explicitly update the EgoSensor here, synchronized with EgoVehicle tick - EgoSensor.Get()->ManualTick(DeltaSeconds); // Ensures we always get the latest data -} - -/// ========================================== /// -/// ----------------:MIRROR:------------------ /// -/// ========================================== /// - -void AEgoVehicle::MirrorParams::Initialize(class UStaticMeshComponent *MirrorSM, - class UPlanarReflectionComponent *Reflection, - class USkeletalMeshComponent *VehicleMesh) -{ - check(MirrorSM != nullptr); - MirrorSM->SetupAttachment(VehicleMesh); - MirrorSM->SetRelativeLocation(MirrorTransform.GetLocation()); - MirrorSM->SetRelativeRotation(MirrorTransform.Rotator()); - MirrorSM->SetRelativeScale3D(MirrorTransform.GetScale3D()); - MirrorSM->SetGenerateOverlapEvents(false); // don't collide with itself - MirrorSM->SetCollisionEnabled(ECollisionEnabled::NoCollision); - MirrorSM->SetVisibility(Enabled); - - check(Reflection != nullptr); - Reflection->SetupAttachment(MirrorSM); - Reflection->SetRelativeLocation(ReflectionTransform.GetLocation()); - Reflection->SetRelativeRotation(ReflectionTransform.Rotator()); - Reflection->SetRelativeScale3D(ReflectionTransform.GetScale3D()); - Reflection->NormalDistortionStrength = 0.0f; - Reflection->PrefilterRoughness = 0.0f; - Reflection->DistanceFromPlaneFadeoutStart = 1500.f; - Reflection->DistanceFromPlaneFadeoutEnd = 0.f; - Reflection->AngleFromPlaneFadeStart = 0.f; - Reflection->AngleFromPlaneFadeEnd = 90.f; - Reflection->PrefilterRoughnessDistance = 10000.f; - Reflection->ScreenPercentage = ScreenPercentage; // change this to reduce quality & improve performance - Reflection->bShowPreviewPlane = false; - Reflection->HideComponent(VehicleMesh); - Reflection->SetVisibility(Enabled); - /// TODO: use USceneCaptureComponent::ShowFlags to define what gets rendered in the mirror - // https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/FEngineShowFlags/ -} - -void AEgoVehicle::ConstructMirrors() -{ - - class USkeletalMeshComponent *VehicleMesh = GetMesh(); - /// Rear mirror - { - // the rear mirror is interesting bc we have 3 components: the mirror (specular), the mirror chassis - // (what holds the mirror, typically lambertian), and the planar reflection (invisible but "reflection") - // other mirrors currently only use the mirror and planar reflection, as we didn't cut out the chassis for them - RearMirrorSM = CreateEgoObject(RearMirrorParams.Name + "MirrorSM"); - RearReflection = CreateEgoObject(RearMirrorParams.Name + "Refl"); - RearMirrorChassisSM = CreateEgoObject(RearMirrorParams.Name + "MirrorChassisSM"); - - RearMirrorParams.Initialize(RearMirrorSM, RearReflection, VehicleMesh); - // also add the chassis for this mirror - RearMirrorChassisSM->SetupAttachment(VehicleMesh); - RearMirrorChassisSM->SetRelativeLocation(RearMirrorChassisTransform.GetLocation()); - RearMirrorChassisSM->SetRelativeRotation(RearMirrorChassisTransform.Rotator()); - RearMirrorChassisSM->SetRelativeScale3D(RearMirrorChassisTransform.GetScale3D()); - RearMirrorChassisSM->SetGenerateOverlapEvents(false); // don't collide with itself - RearMirrorChassisSM->SetCollisionEnabled(ECollisionEnabled::NoCollision); - RearMirrorChassisSM->SetVisibility(RearMirrorParams.Enabled); - RearMirrorSM->SetupAttachment(RearMirrorChassisSM); - RearReflection->HideComponent(RearMirrorChassisSM); // don't show this in the reflection - } - /// Left mirror - { - LeftMirrorSM = CreateEgoObject(LeftMirrorParams.Name + "MirrorSM"); - LeftReflection = CreateEgoObject(LeftMirrorParams.Name + "Refl"); - LeftMirrorParams.Initialize(LeftMirrorSM, LeftReflection, VehicleMesh); - } - /// Right mirror - { - RightMirrorSM = CreateEgoObject(RightMirrorParams.Name + "MirrorSM"); - RightReflection = CreateEgoObject(RightMirrorParams.Name + "Refl"); - RightMirrorParams.Initialize(RightMirrorSM, RightReflection, VehicleMesh); - } -} - -/// ========================================== /// -/// ----------------:SOUNDS:------------------ /// -/// ========================================== /// - -template bool FindSound(const FString &Section, const FString &Variable, UAudioComponent *Out) -{ - if (Out != nullptr) // TODO: check that the key is present - { - const FString PathStr = GeneralParams.Get(Section, Variable); - if (!PathStr.IsEmpty()) - { - ConstructorHelpers::FObjectFinder FoundSound(*PathStr); - if (FoundSound.Succeeded()) - { - Out->SetSound(FoundSound.Object); - return true; - } - } - } - return false; -} - -void AEgoVehicle::ConstructEgoSounds() -{ - // shouldn't override this method in ACarlaWHeeledVehicle because it will be - // used in the constructor and calling virtual methods in constructor is bad: - // https://stackoverflow.com/questions/962132/calling-virtual-functions-inside-constructors - - // Initialize ego-centric audio components - { - if (EngineRevSound != nullptr) - { - EngineRevSound->DestroyComponent(); // from the parent class (default sound) - EngineRevSound = nullptr; - } - EgoEngineRevSound = CreateEgoObject("EgoEngineRevSound"); - FindSound("Sound", "DefaultEngineRev", EgoEngineRevSound); - EgoEngineRevSound->SetupAttachment(GetRootComponent()); // attach to self - EgoEngineRevSound->bAutoActivate = true; // start playing on begin - EngineLocnInVehicle = VehicleParams.Get("Sounds", "EngineLocn"); - EgoEngineRevSound->SetRelativeLocation(EngineLocnInVehicle); // location of "engine" in vehicle (3D sound) - EgoEngineRevSound->SetFloatParameter(FName("RPM"), 0.f); // initially idle - EgoEngineRevSound->bAutoDestroy = false; // No automatic destroy, persist along with vehicle - check(EgoEngineRevSound != nullptr); - } - - { - if (CrashSound != nullptr) - { - CrashSound->DestroyComponent(); // from the parent class (default sound) - CrashSound = nullptr; - } - EgoCrashSound = CreateEgoObject("EgoCarCrash"); - FindSound("Sound", "DefaultCrashSound", EgoCrashSound); - EgoCrashSound->SetupAttachment(GetRootComponent()); - EgoCrashSound->bAutoActivate = false; - EgoCrashSound->bAutoDestroy = false; - check(EgoCrashSound != nullptr); - } - - { - GearShiftSound = CreateEgoObject("GearShift"); - FindSound("Sound", "DefaultGearShiftSound", GearShiftSound); - GearShiftSound->SetupAttachment(GetRootComponent()); - GearShiftSound->bAutoActivate = false; - check(GearShiftSound != nullptr); - } - - { - TurnSignalSound = CreateEgoObject("TurnSignal"); - FindSound("Sound", "DefaultTurnSignalSound", TurnSignalSound); - TurnSignalSound->SetupAttachment(GetRootComponent()); - TurnSignalSound->bAutoActivate = false; - check(TurnSignalSound != nullptr); - } - - ConstructEgoCollisionHandler(); -} - -void AEgoVehicle::PlayGearShiftSound(const float DelayBeforePlay) const -{ - if (GearShiftSound != nullptr) - GearShiftSound->Play(DelayBeforePlay); -} - -void AEgoVehicle::PlayTurnSignalSound(const float DelayBeforePlay) const -{ - if (TurnSignalSound != nullptr) - TurnSignalSound->Play(DelayBeforePlay); -} - -void AEgoVehicle::SetVolume(const float VolumeIn) -{ - if (EgoEngineRevSound) - EgoEngineRevSound->SetVolumeMultiplier(VolumeIn); - if (EgoCrashSound) - EgoCrashSound->SetVolumeMultiplier(VolumeIn); - if (GearShiftSound) - GearShiftSound->SetVolumeMultiplier(VolumeIn); - if (TurnSignalSound) - TurnSignalSound->SetVolumeMultiplier(VolumeIn); - Super::SetVolume(VolumeIn); -} - -void AEgoVehicle::TickSounds(float DeltaSeconds) -{ - // Respect the global vehicle volume param - SetVolume(ACarlaWheeledVehicle::Volume); - - if (EgoEngineRevSound) - { - if (!EgoEngineRevSound->IsPlaying()) - EgoEngineRevSound->Play(); // turn on the engine sound if not already on - float RPM = FMath::Clamp(GetVehicleMovementComponent()->GetEngineRotationSpeed(), 0.f, 5650.0f); - EgoEngineRevSound->SetFloatParameter(FName("RPM"), RPM); - } - - // add other sounds that need tick-level granularity here... -} - -void AEgoVehicle::ConstructEgoCollisionHandler() -{ - // using Carla's GetVehicleBoundingBox function - UBoxComponent *Bounds = this->GetVehicleBoundingBox(); - if (Bounds != nullptr) - { - Bounds->SetGenerateOverlapEvents(true); - Bounds->SetCollisionEnabled(ECollisionEnabled::QueryOnly); - Bounds->SetCollisionProfileName(TEXT("DReyeVRTrigger")); - Bounds->OnComponentBeginOverlap.AddDynamic(this, &AEgoVehicle::OnEgoOverlapBegin); - } -} - -void AEgoVehicle::OnEgoOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, - UPrimitiveComponent *OtherComp, int32 OtherBodyIndex, bool bFromSweep, - const FHitResult &SweepResult) -{ - if (OtherActor == nullptr || OtherActor == this) - return; - - // can be more flexible, such as having collisions with static props or people too - if (EnableCollisionForActor(OtherActor)) - { - // move the sound 1m in the direction of the collision - FVector SoundEmitLocation = 100.f * (this->GetActorLocation() - OtherActor->GetActorLocation()).GetSafeNormal(); - SoundEmitLocation.Z = 75.f; // Make the sound emitted not at the ground (75cm off ground) - if (EgoCrashSound != nullptr) - { - EgoCrashSound->SetRelativeLocation(SoundEmitLocation); - EgoCrashSound->Play(0.f); - // have at least 0.5s of buffer between collision audio - CollisionCooldownTime = GetWorld()->GetTimeSeconds() + 0.5f; - } - } -} - -/// ========================================== /// -/// -----------------:DASH:------------------- /// -/// ========================================== /// - -void AEgoVehicle::ConstructDashText() // dashboard text (speedometer, turn signals, gear shifter) -{ - // Create speedometer - if (VehicleParams.Get("Dashboard", "SpeedometerEnabled")) - { - Speedometer = CreateEgoObject("Speedometer"); - Speedometer->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); - Speedometer->SetRelativeTransform(VehicleParams.Get("Dashboard", "SpeedometerTransform")); - Speedometer->SetTextRenderColor(FColor::Red); - Speedometer->SetText(FText::FromString("0")); - Speedometer->SetXScale(1.f); - Speedometer->SetYScale(1.f); - Speedometer->SetWorldSize(10); // scale the font with this - Speedometer->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); - Speedometer->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); - SpeedometerScale = CmPerSecondToXPerHour(GeneralParams.Get("EgoVehicle", "SpeedometerInMPH")); - check(Speedometer != nullptr); - } - - // Create turn signals - if (VehicleParams.Get("Dashboard", "TurnSignalsEnabled")) - { - TurnSignals = CreateEgoObject("TurnSignals"); - TurnSignals->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); - TurnSignals->SetRelativeTransform(VehicleParams.Get("Dashboard", "TurnSignalsTransform")); - TurnSignals->SetTextRenderColor(FColor::Red); - TurnSignals->SetText(FText::FromString("")); - TurnSignals->SetXScale(1.f); - TurnSignals->SetYScale(1.f); - TurnSignals->SetWorldSize(10); // scale the font with this - TurnSignals->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); - TurnSignals->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); - check(TurnSignals != nullptr); - } - - // Create gear shifter - if (VehicleParams.Get("Dashboard", "GearShifterEnabled")) - { - GearShifter = CreateEgoObject("GearShifter"); - GearShifter->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); - GearShifter->SetRelativeTransform(VehicleParams.Get("Dashboard", "GearShifterTransform")); - GearShifter->SetTextRenderColor(FColor::Red); - GearShifter->SetText(FText::FromString("D")); - GearShifter->SetXScale(1.f); - GearShifter->SetYScale(1.f); - GearShifter->SetWorldSize(10); // scale the font with this - GearShifter->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); - GearShifter->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); - check(GearShifter != nullptr); - } -} - -void AEgoVehicle::UpdateDash() -{ - // Draw text components - float XPH; // miles-per-hour or km-per-hour - if (EgoSensor.IsValid() && EgoSensor.Get()->IsReplaying()) - { - const DReyeVR::AggregateData *Replay = EgoSensor.Get()->GetData(); - XPH = Replay->GetVehicleVelocity() * SpeedometerScale; // FwdSpeed is in cm/s - const auto &ReplayInputs = Replay->GetUserInputs(); - if (ReplayInputs.ToggledReverse) - PressReverse(); - else - ReleaseReverse(); - - if (bEnableTurnSignalAction) - { - if (ReplayInputs.TurnSignalLeft) - PressTurnSignalL(); - else - ReleaseTurnSignalL(); - - if (ReplayInputs.TurnSignalRight) - PressTurnSignalR(); - else - ReleaseTurnSignalR(); - } - } - else - { - XPH = GetVehicleForwardSpeed() * SpeedometerScale; // FwdSpeed is in cm/s - } - - if (Speedometer != nullptr) - { - const FString Data = FString::FromInt(int(FMath::RoundHalfFromZero(XPH))); - Speedometer->SetText(FText::FromString(Data)); - } - - if (bEnableTurnSignalAction && TurnSignals != nullptr) - { - // Draw the signals - float Now = GetWorld()->GetTimeSeconds(); - const float StartTime = std::max(RightSignalTimeToDie, LeftSignalTimeToDie) - TurnSignalDuration; - FString TurnSignalStr = ""; - constexpr static float TurnSignalBlinkRate = 0.4f; // rate of blinking - if (std::fmodf(Now - StartTime, TurnSignalBlinkRate * 2) < TurnSignalBlinkRate) - { - if (Now < RightSignalTimeToDie) - TurnSignalStr = ">>>"; - else if (Now < LeftSignalTimeToDie) - TurnSignalStr = "<<<"; - } - TurnSignals->SetText(FText::FromString(TurnSignalStr)); - } - - if (GearShifter != nullptr) - { - // Draw the gear shifter - GearShifter->SetText(bReverse ? FText::FromString("R") : FText::FromString("D")); - } -} - -/// ========================================== /// -/// -----------------:WHEEL:------------------ /// -/// ========================================== /// - -void AEgoVehicle::ConstructSteeringWheel() -{ - const bool bEnableSteeringWheel = VehicleParams.Get("SteeringWheel", "Enabled"); - SteeringWheel = CreateEgoObject("SteeringWheel"); - SteeringWheel->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself - SteeringWheel->SetRelativeLocation(VehicleParams.Get("SteeringWheel", "InitLocation")); - SteeringWheel->SetRelativeRotation(VehicleParams.Get("SteeringWheel", "InitRotation")); - SteeringWheel->SetGenerateOverlapEvents(false); // don't collide with itself - SteeringWheel->SetCollisionEnabled(ECollisionEnabled::NoCollision); - SteeringWheel->SetVisibility(bEnableSteeringWheel); -} - -void AEgoVehicle::InitAutopilotIndicator() -{ - bool bEnableAutopilotIndicator = GeneralParams.Get("WheelFace", "EnableAutopilotIndicator"); - if (SteeringWheel == nullptr || World == nullptr || bEnableAutopilotIndicator == false) - return; - AutopilotIndicator = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "AI_Indicator"); - const FVector AutopilotIndicatorLocation = GeneralParams.Get("WheelFace", "AutopilotIndicatorLoc"); - const float AutopilotIndicatorSize = GeneralParams.Get("WheelFace", "AutopilotIndicatorSize"); - AutopilotIndicator->SetActorLocation(AutopilotIndicatorLocation); - check(AutopilotIndicator != nullptr); - AutopilotIndicator->Activate(); - AutopilotIndicator->SetActorScale3D(AutopilotIndicatorSize * FVector::OneVector); - AutopilotIndicator->AttachToComponent(SteeringWheel, FAttachmentTransformRules::KeepRelativeTransform); - AutopilotIndicator->MaterialParams.BaseColor = ButtonNeutralCol; // close to off - AutopilotIndicator->MaterialParams.Emissive = ButtonNeutralCol; // close to off - AutopilotIndicator->UpdateMaterial(); - AutopilotIndicator->SetActorTickEnabled(false); // don't tick these actors (for performance) - AutopilotIndicator->SetActorRecordEnabled(false); // don't need to record these actors either - AutopilotIndicator->GetMesh()->SetCastShadow(false); // don't want shadows (looks weird) - bInitializedAutopilotIndicator = true; -} - -void AEgoVehicle::InitWheelButtons() -{ - bool bEnableWheelFaceButtons = GeneralParams.Get("WheelFace", "EnableWheelButtons"); - if (SteeringWheel == nullptr || World == nullptr || bEnableWheelFaceButtons == false) - return; - // left buttons (dpad) - Button_DPad_Up = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Up"); // top on left - Button_DPad_Right = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Right"); // right on left - Button_DPad_Down = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Down"); // bottom on left - Button_DPad_Left = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Left"); // left on left - // right buttons (ABXY) - Button_ABXY_Y = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_Y"); // top on right - Button_ABXY_B = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_B"); // right on right - Button_ABXY_A = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_A"); // bottom on right - Button_ABXY_X = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_X"); // left on right - - const FRotator PointLeft(0.f, 0.f, -90.f); - const FRotator PointRight(0.f, 0.f, 90.f); - const FRotator PointUp(0.f, 0.f, 0.f); - const FRotator PointDown(0.f, 0.f, 180.f); - - const FVector LeftCenter = GeneralParams.Get("WheelFace", "ABXYLocation"); - const FVector RightCenter = GeneralParams.Get("WheelFace", "DpadLocation"); - - // increase to separate the buttons more - const float ButtonDist = GeneralParams.Get("WheelFace", "QuadButtonSpread"); - - Button_DPad_Up->SetActorLocation(LeftCenter + ButtonDist * FVector::UpVector); - Button_DPad_Up->SetActorRotation(PointUp); - Button_DPad_Right->SetActorLocation(LeftCenter + ButtonDist * FVector::RightVector); - Button_DPad_Right->SetActorRotation(PointRight); - Button_DPad_Down->SetActorLocation(LeftCenter + ButtonDist * FVector::DownVector); - Button_DPad_Down->SetActorRotation(PointDown); - Button_DPad_Left->SetActorLocation(LeftCenter + ButtonDist * FVector::LeftVector); - Button_DPad_Left->SetActorRotation(PointLeft); - - // (spheres don't need rotation) - Button_ABXY_Y->SetActorLocation(RightCenter + ButtonDist * FVector::UpVector); - Button_ABXY_B->SetActorLocation(RightCenter + ButtonDist * FVector::RightVector); - Button_ABXY_A->SetActorLocation(RightCenter + ButtonDist * FVector::DownVector); - Button_ABXY_X->SetActorLocation(RightCenter + ButtonDist * FVector::LeftVector); - - // for applying the same properties on these actors - auto WheelButtons = {Button_ABXY_A, Button_ABXY_B, Button_ABXY_X, Button_ABXY_Y, - Button_DPad_Up, Button_DPad_Down, Button_DPad_Left, Button_DPad_Right}; - for (auto *Button : WheelButtons) - { - check(Button != nullptr); - Button->Activate(); - Button->SetActorScale3D(0.015f * FVector::OneVector); - Button->AttachToComponent(SteeringWheel, FAttachmentTransformRules::KeepRelativeTransform); - Button->MaterialParams.BaseColor = ButtonNeutralCol; - Button->MaterialParams.Emissive = ButtonNeutralCol; - Button->UpdateMaterial(); - Button->SetActorTickEnabled(false); // don't tick these actors (for performance) - Button->SetActorRecordEnabled(false); // don't need to record these actors either - Button->GetMesh()->SetCastShadow(false); // don't want shadows (looks weird) - } - bInitializedButtons = true; -} - -void AEgoVehicle::UpdateWheelButton(ADReyeVRCustomActor *Button, bool bEnabled) -{ - if (Button == nullptr) - return; - Button->MaterialParams.BaseColor = bEnabled ? ButtonPressedCol : ButtonNeutralCol; - Button->MaterialParams.Emissive = bEnabled ? ButtonPressedCol : ButtonNeutralCol; - Button->UpdateMaterial(); -} - -void AEgoVehicle::TickAutopilotIndicator(bool bAutopilotEnabled) -{ - if (AutopilotIndicator == nullptr) - return; - const FLinearColor On = FLinearColor(0.537, 0.812, 0.941); // baby blue - const FLinearColor Off = 0.1f * FLinearColor(0.537, 0.812, 0.941); // baby blue (off) - AutopilotIndicator->MaterialParams.BaseColor = bAutopilotEnabled ? On : Off; - AutopilotIndicator->MaterialParams.Emissive = 500.f * (bAutopilotEnabled ? On : Off); - AutopilotIndicator->UpdateMaterial(); -} - -void AEgoVehicle::DestroySteeringWheel() -{ - auto WheelButtons = {Button_ABXY_A, Button_ABXY_B, Button_ABXY_X, Button_ABXY_Y, - Button_DPad_Up, Button_DPad_Down, Button_DPad_Left, Button_DPad_Right}; - for (auto *Button : WheelButtons) - { - if (Button) - { - Button->Deactivate(); - Button->Destroy(); - } - } -} - -void AEgoVehicle::TickSteeringWheel(const float DeltaTime) -{ - if (!SteeringWheel) - return; - if (!bInitializedButtons) - InitWheelButtons(); - if (!bInitializedAutopilotIndicator) - InitAutopilotIndicator(); - const FRotator CurrentRotation = SteeringWheel->GetRelativeRotation(); - FRotator NewRotation = CurrentRotation; - if (Pawn && Pawn->GetIsLogiConnected() && !GetAutopilotStatus()) - { - // make the virtual wheel rotation follow the physical steering wheel - const float RawSteering = GetVehicleInputs().Steering; // this is scaled in SetSteering - const float TargetAngle = (RawSteering / ScaleSteeringInput) * SteeringAnimScale; - NewRotation.Roll = TargetAngle; - } - else if (GetMesh() && Cast(GetMesh()->GetAnimInstance()) != nullptr) - { - // use the animation (front wheels) steer angle for the steering wheel - float WheelAngleDeg = GetWheelSteerAngle(EVehicleWheelLocation::Front_Wheel); - // float MaxWheelAngle = GetMaximumSteerAngle(); - float DeltaAngle = 10.f * (2.0f * WheelAngleDeg - CurrentRotation.Roll); - - // create the new rotation using the deltas - NewRotation += DeltaTime * FRotator(0.f, 0.f, DeltaAngle); - - // Clamp the roll amount so the wheel can't spin infinitely - NewRotation.Roll = FMath::Clamp(NewRotation.Roll, -MaxSteerAngleDeg, MaxSteerAngleDeg); - } - SteeringWheel->SetRelativeRotation(NewRotation); -} - -/// ========================================== /// -/// -----------------:LEVEL:------------------ /// -/// ========================================== /// - -void AEgoVehicle::SetGame(ADReyeVRGameMode *Game) -{ - DReyeVRGame = Game; - check(DReyeVRGame != nullptr); - check(DReyeVRGame->GetEgoVehicle() == this); - - DReyeVRGame->GetPawn()->BeginEgoVehicle(this, World); - LOG("Successfully assigned GameMode & controller pawn"); -} - -ADReyeVRGameMode *AEgoVehicle::GetGame() -{ - return DReyeVRGame; -} - -void AEgoVehicle::TickGame(float DeltaSeconds) -{ - if (this->DReyeVRGame != nullptr) - DReyeVRGame->Tick(DeltaSeconds); -} - -/// ========================================== /// -/// ---------------:COSMETIC:----------------- /// -/// ========================================== /// - -void AEgoVehicle::DebugLines() const -{ -#if WITH_EDITOR - - if (bDrawDebugEditor && EgoSensor.IsValid()) - { - // Calculate gaze data (in world space) using eye tracker data - const DReyeVR::AggregateData *Data = EgoSensor.Get()->GetData(); - // Compute World positions and orientations - const FRotator &WorldRot = FirstPersonCam->GetComponentRotation(); - const FVector &WorldPos = FirstPersonCam->GetComponentLocation(); - - // First get the gaze origin and direction and vergence from the EyeTracker Sensor - const float RayLength = FMath::Max(1.f, Data->GetGazeVergence() / 100.f); // vergence to m (from cm) - const float VRMeterScale = 100.f; - - // Both eyes - const FVector CombinedGaze = RayLength * VRMeterScale * Data->GetGazeDir(); - const FVector CombinedOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin()); - - // Left eye - const FVector LeftGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::LEFT); - const FVector LeftOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::LEFT)); - - // Right eye - const FVector RightGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::RIGHT); - const FVector RightOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::RIGHT)); - - // Use Absolute Ray Position to draw debug information - // Rotate and add the gaze ray to the origin - DrawDebugSphere(World, CombinedOrigin + WorldRot.RotateVector(CombinedGaze), 4.0f, 12, FColor::Blue); - - // Draw individual rays for left and right eye - DrawDebugLine(World, - LeftOrigin, // start line - LeftOrigin + 10 * WorldRot.RotateVector(LeftGaze), // end line - FColor::Green, false, -1, 0, 1); - - DrawDebugLine(World, - RightOrigin, // start line - RightOrigin + 10 * WorldRot.RotateVector(RightGaze), // end line - FColor::Yellow, false, -1, 0, 1); - } -#endif +#include "EgoVehicle.h" +#include "Carla/Actor/ActorAttribute.h" // FActorAttribute +#include "Carla/Actor/ActorRegistry.h" // Register +#include "Carla/Game/CarlaStatics.h" // GetCurrentEpisode +#include "Carla/Vehicle/CarlaWheeledVehicleState.h" // ECarlaWheeledVehicleState +#include "DReyeVRPawn.h" // ADReyeVRPawn +#include "DrawDebugHelpers.h" // Debug Line/Sphere +#include "Engine/EngineTypes.h" // EBlendMode +#include "Engine/World.h" // GetWorld +#include "GameFramework/Actor.h" // Destroy +#include "Kismet/KismetSystemLibrary.h" // PrintString, QuitGame +#include "Math/Rotator.h" // RotateVector, Clamp +#include "Math/UnrealMathUtility.h" // Clamp + +#include + +// Sets default values +AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +{ + LOG("Constructing Ego Vehicle: %s", *FString(this->GetName())); + + ReadConfigVariables(); + + // this actor ticks AFTER the physics simulation is done + PrimaryActorTick.bCanEverTick = true; + PrimaryActorTick.bStartWithTickEnabled = true; + PrimaryActorTick.bAllowTickOnDedicatedServer = true; + PrimaryActorTick.TickGroup = TG_PostPhysics; + AIControllerClass = AWheeledVehicleAIController::StaticClass(); + + // Set up the root position to be the this mesh + SetRootComponent(GetMesh()); + + // Initialize the camera components + ConstructCameraRoot(); + + // Initialize audio components + ConstructEgoSounds(); + + // Initialize mirrors + ConstructMirrors(); + + // Initialize text render components + ConstructDashText(); + + // Initialize the steering wheel + ConstructSteeringWheel(); + + LOG("Finished constructing %s", *FString(this->GetName())); +} + +void AEgoVehicle::ReadConfigVariables() +{ + // this matches the BP_XYZ (XYZ) part of the blueprint, or "Vehicle" if just an EgoVehicle + VehicleType = CleanNameForDReyeVR(GetClass()->GetName()); + LOG("Initializing EgoVehicle: \"%s\"", *VehicleType); + if (!VehicleType.Equals("Vehicle", ESearchCase::CaseSensitive)) + { + auto NewParams = ConfigFile(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles"), VehicleType + ".ini")); + if (NewParams.bIsValid()) + VehicleParams = NewParams; + } + + // if the VehicleParams is invalid, use a default + if (!VehicleParams.bIsValid()) + VehicleParams = ConfigFile(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles/TeslaM3.ini")), false); + ensure(VehicleParams.bIsValid()); + + GeneralParams.Get("EgoVehicle", "EnableTurnSignalAction", bEnableTurnSignalAction); + GeneralParams.Get("EgoVehicle", "TurnSignalDuration", TurnSignalDuration); + // mirrors + auto InitMirrorParams = [this](const FString &Name, struct MirrorParams &Params) { + Params.Name = Name; + VehicleParams.Get("Mirrors", Params.Name + "MirrorEnabled", Params.Enabled); + VehicleParams.Get("Mirrors", Params.Name + "MirrorTransform", Params.MirrorTransform); + VehicleParams.Get("Mirrors", Params.Name + "ReflectionTransform", Params.ReflectionTransform); + VehicleParams.Get("Mirrors", Params.Name + "ScreenPercentage", Params.ScreenPercentage); + }; + InitMirrorParams("Rear", RearMirrorParams); + InitMirrorParams("Left", LeftMirrorParams); + InitMirrorParams("Right", RightMirrorParams); + // rear mirror chassis + VehicleParams.Get("Mirrors", "RearMirrorChassisTransform", RearMirrorChassisTransform); + // steering wheel + VehicleParams.Get("SteeringWheel", "MaxSteerAngleDeg", MaxSteerAngleDeg); + VehicleParams.Get("SteeringWheel", "SteeringScale", SteeringAnimScale); + // other/cosmetic + GeneralParams.Get("EgoVehicle", "DrawDebugEditor", bDrawDebugEditor); + // inputs + GeneralParams.Get("VehicleInputs", "ScaleSteeringDamping", ScaleSteeringInput); + GeneralParams.Get("VehicleInputs", "ScaleThrottleInput", ScaleThrottleInput); + GeneralParams.Get("VehicleInputs", "ScaleBrakeInput", ScaleBrakeInput); + // replay + GeneralParams.Get("Replayer", "CameraFollowHMD", bCameraFollowHMD); +} + +void AEgoVehicle::BeginPlay() +{ + // Called when the game starts or when spawned + Super::BeginPlay(); + + // Get information about the world + World = GetWorld(); + ensure(World != nullptr); + + // initialize + InitAIPlayer(); + + // Bug-workaround for initial delay on throttle; see https://github.com/carla-simulator/carla/issues/1640 + this->GetVehicleMovementComponent()->SetTargetGear(1, true); + + // get the GameMode script + SetGame(Cast(UGameplayStatics::GetGameMode(World))); + + BeginThirdPersonCameraInit(); + + LOG("Initialized DReyeVR EgoVehicle"); +} + +void AEgoVehicle::EndPlay(const EEndPlayReason::Type EndPlayReason) +{ + // https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/EEndPlayReason__Type/ + if (EndPlayReason == EEndPlayReason::Destroyed) + { + LOG("DReyeVR EgoVehicle is being destroyed! You'll need to spawn another one!"); + if (GetGame()) + { + GetGame()->PossessSpectator(); + } + } + + if (this->Pawn) + { + this->Pawn->SetEgoVehicle(nullptr); + } +} + +void AEgoVehicle::BeginDestroy() +{ + Super::BeginDestroy(); + + // destroy all spawned entities + if (EgoSensor.IsValid()) + EgoSensor.Get()->Destroy(); + + DestroySteeringWheel(); + + LOG("EgoVehicle has been destroyed"); +} + +// Called every frame +void AEgoVehicle::Tick(float DeltaSeconds) +{ + Super::Tick(DeltaSeconds); + + // Get the current data from the AEgoSensor and use it + UpdateSensor(DeltaSeconds); + + // Update the positions based off replay data + ReplayTick(); + + // Draw debug lines on editor + DebugLines(); + + // Render EgoVehicle dashboard + UpdateDash(); + + // Update the steering wheel to be responsive to user input + TickSteeringWheel(DeltaSeconds); + + // Ensure appropriate autopilot functionality is accessible from EgoVehicle + TickAutopilot(); + + // Update the world level + TickGame(DeltaSeconds); + + // Tick vehicle controls + TickVehicleInputs(); +} + +/// ========================================== /// +/// ----------------:CAMERA:------------------ /// +/// ========================================== /// + +template T *AEgoVehicle::CreateEgoObject(const FString &Name, const FString &Suffix) +{ + // create default subobject with this name and (optionally) add a suffix + // https://docs.unrealengine.com/4.26/en-US/API/Runtime/CoreUObject/UObject/UObject/CreateDefaultSubobject/2/ + // see also: https://dev.epicgames.com/community/snippets/0bk/actor-component-creation + // if the blueprint gets corrupted (ex. object details no longer visible), reparent to BaseVehiclePawn then back + T *Ret = UObject::CreateDefaultSubobject(FName(*(Name + Suffix))); + // disabling tick for these objects by default + Ret->SetComponentTickEnabled(false); + Ret->PrimaryComponentTick.bCanEverTick = false; + Ret->PrimaryComponentTick.bStartWithTickEnabled = false; + return Ret; +} + +void AEgoVehicle::ConstructCameraRoot() +{ + // Spawn the RootComponent and Camera for the VR camera + VRCameraRoot = CreateEgoObject("VRCameraRoot"); + check(VRCameraRoot != nullptr); + VRCameraRoot->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself + VRCameraRoot->SetRelativeLocation(FVector::ZeroVector); + VRCameraRoot->SetRelativeRotation(FRotator::ZeroRotator); + + // add first-person driver's seat + CameraTransforms.Add("DriversSeat", VehicleParams.Get("CameraPose", "DriversSeat")); + + SetCameraRootPose("DriversSeat"); +} + +void AEgoVehicle::BeginThirdPersonCameraInit() +{ + // add third-person views + + std::vector CameraPoses = { + "ThirdPerson", // 2nd + "BirdsEyeView", // 3rd + "Front", // 4th + }; + UBoxComponent *Bounds = this->GetVehicleBoundingBox(); + ensure(Bounds != nullptr); + if (Bounds != nullptr) + { + const FVector BoundingBoxSize = Bounds->GetScaledBoxExtent(); + LOG("Calculated EgoVehicle bounding box: %s", *BoundingBoxSize.ToString()); + for (FString &Key : CameraPoses) + { + FTransform Transform = GeneralParams.Get("CameraPose", Key); + Transform.SetLocation(Transform.GetLocation() * BoundingBoxSize); // scale by bounding box + CameraTransforms.Add(Key, Transform); + } + } + + CameraTransforms.GenerateKeyArray(CameraPoseKeys); + ensure(CameraPoseKeys.Num() > 0); + + // assign the starting camera root pose to the given starting pose + FString StartingPose = GeneralParams.Get("CameraPose", "StartingPose"); + SetCameraRootPose(StartingPose); +} + +void AEgoVehicle::SetCameraRootPose(const FString &CameraPoseName) +{ + FTransform NewCameraTransform; + // given a string (key), index into the map to obtain the FTransform + if (CameraTransforms.Contains(CameraPoseName)) + { + NewCameraTransform = CameraTransforms[CameraPoseName]; + } + else + { + LOG_WARN("Unable to find camera pose named \"%s\". Defaulting to driver's seat!", *CameraPoseName); + NewCameraTransform = CameraTransforms["DriversSeat"]; + } + SetCameraRootPose(NewCameraTransform); +} + +size_t AEgoVehicle::GetNumCameraPoses() const +{ + return CameraTransforms.Num(); +} + +void AEgoVehicle::SetCameraRootPose(size_t CameraPoseIdx) +{ + if (CameraPoseKeys.Num() == 0) + return; + // allow setting the camera root by indexing into CameraTransforms array + CameraPoseIdx = std::min(CameraPoseIdx, static_cast(CameraPoseKeys.Num() - 1)); + const auto &Key = CameraPoseKeys[CameraPoseIdx]; + const FTransform *NewPose = CameraTransforms.Find(Key); + if (NewPose == nullptr) + { + LOG_ERROR("Unable to find camera pose \"%s\"", *Key); + return; + } + SetCameraRootPose(*NewPose); +} + +void AEgoVehicle::SetCameraRootPose(const FTransform &CameraPoseTransform) +{ + // sets the base posision of the Camera root (where the camera is at "rest") + this->CameraPose = CameraPoseTransform; + // LOG("Setting camera pose to: %s", *(CameraPose + CameraPoseOffset).ToString()); + + // First, set the root of the camera to the driver's seat head pos + VRCameraRoot->SetRelativeLocation(CameraPose.GetLocation() + CameraPoseOffset.GetLocation()); + VRCameraRoot->SetRelativeRotation(CameraPose.Rotator() + CameraPoseOffset.Rotator()); +} + +void AEgoVehicle::SetPawn(ADReyeVRPawn *PawnIn) +{ + ensure(VRCameraRoot != nullptr); + this->Pawn = PawnIn; + ensure(Pawn != nullptr); + this->FirstPersonCam = Pawn->GetCamera(); + ensure(FirstPersonCam != nullptr); + FAttachmentTransformRules F(EAttachmentRule::KeepRelative, false); + Pawn->AttachToComponent(VRCameraRoot, F); + FirstPersonCam->AttachToComponent(VRCameraRoot, F); + // Then set the actual camera to be at its origin (attached to VRCameraRoot) + FirstPersonCam->SetRelativeLocation(FVector::ZeroVector); + FirstPersonCam->SetRelativeRotation(FRotator::ZeroRotator); +} + +const FString &AEgoVehicle::GetVehicleType() const +{ + return VehicleType; +} +const UCameraComponent *AEgoVehicle::GetCamera() const +{ + ensure(FirstPersonCam != nullptr); + return FirstPersonCam; +} +UCameraComponent *AEgoVehicle::GetCamera() +{ + ensure(FirstPersonCam != nullptr); + return FirstPersonCam; +} +FVector AEgoVehicle::GetCameraOffset() const +{ + return VRCameraRoot->GetComponentLocation(); +} +FVector AEgoVehicle::GetCameraPosn() const +{ + return GetCamera() ? GetCamera()->GetComponentLocation() : FVector::ZeroVector; +} +FVector AEgoVehicle::GetNextCameraPosn(const float DeltaSeconds) const +{ + // usually only need this is tick before physics + return GetCameraPosn() + DeltaSeconds * GetVelocity(); +} +FRotator AEgoVehicle::GetCameraRot() const +{ + return GetCamera() ? GetCamera()->GetComponentRotation() : FRotator::ZeroRotator; +} +class AEgoSensor *AEgoVehicle::GetSensor() +{ + // tries to return the EgoSensor pointer if it is safe to do so, else re-spawn it + return SafePtrGet("EgoSensor", EgoSensor, [&](void) { this->InitSensor(); }); +} + +const class AEgoSensor *AEgoVehicle::GetSensor() const +{ + // tries to return the EgoSensor pointer if it is safe to do so, else re-spawn it + return const_cast(const_cast(this)->GetSensor()); +} + +const struct ConfigFile &AEgoVehicle::GetVehicleParams() const +{ + return VehicleParams; +} + +/// ========================================== /// +/// ---------------:AIPLAYER:----------------- /// +/// ========================================== /// + +void AEgoVehicle::InitAIPlayer() +{ + this->SpawnDefaultController(); // spawns default (AI) controller and gets possessed by it + auto PlayerController = GetController(); + ensure(PlayerController != nullptr); + AI_Player = Cast(PlayerController); + check(AI_Player != nullptr); + SetAutopilot(false); // initially no autopilot enabled +} + +void AEgoVehicle::SetAutopilot(const bool AutopilotOn) +{ + if (!AI_Player) + return; + bAutopilotEnabled = AutopilotOn; + AI_Player->SetAutopilot(bAutopilotEnabled); + AI_Player->SetStickyControl(bAutopilotEnabled); + // AI_Player->SetActorTickEnabled(bAutopilotEnabled); // want the controller to always tick! +} + +bool AEgoVehicle::GetAutopilotStatus() const +{ + return bAutopilotEnabled; +} + +void AEgoVehicle::TickAutopilot() +{ + ensure(AI_Player != nullptr); + if (AI_Player != nullptr) + { + bAutopilotEnabled = AI_Player->IsAutopilotEnabled(); + TickAutopilotIndicator(bAutopilotEnabled); + } +} + +/// ========================================== /// +/// ----------------:SENSOR:------------------ /// +/// ========================================== /// + +void AEgoVehicle::InitSensor() +{ + // update the world on refresh (ex. --reloadWorld) + World = GetWorld(); + check(World != nullptr); + // Spawn the EyeTracker Carla sensor and attach to Ego-Vehicle: + { + UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(World); + check(Episode != nullptr); + FActorDefinition EgoSensorDef = FindDefnInRegistry(Episode, AEgoSensor::StaticClass()); + FActorDescription Description; + { // create a Description from the Definition to spawn the actor + Description.UId = EgoSensorDef.UId; + Description.Id = EgoSensorDef.Id; + Description.Class = EgoSensorDef.Class; + // add all the attributes from the definition to the description + for (FActorAttribute A : EgoSensorDef.Attributes) + { + Description.Variations.Add(A.Id, std::move(A)); + } + } + // calls Episode::SpawnActor => SpawnActorWithInfo => ActorDispatcher->SpawnActor => SpawnFunctions[UId] + FTransform SpawnPt = FTransform(FRotator::ZeroRotator, GetCameraPosn(), FVector::OneVector); + EgoSensor = static_cast(Episode->SpawnActor(SpawnPt, Description)); + } + check(EgoSensor.IsValid()); + // Attach the EgoSensor as a child to the EgoVehicle + EgoSensor.Get()->SetOwner(this); + EgoSensor.Get()->AttachToActor(this, FAttachmentTransformRules::KeepRelativeTransform); + EgoSensor.Get()->SetActorTransform(FTransform::Identity, false, nullptr, ETeleportType::TeleportPhysics); + EgoSensor.Get()->SetEgoVehicle(this); +} + +void AEgoVehicle::ReplayTick() +{ + if (!EgoSensor.IsValid()) + return; + const bool bIsReplaying = EgoSensor.Get()->IsReplaying(); + // need to enable/disable VehicleMesh simulation + class USkeletalMeshComponent *VehicleMesh = GetMesh(); + if (VehicleMesh) + VehicleMesh->SetSimulatePhysics(!bIsReplaying); // disable physics when replaying (teleporting) + if (FirstPersonCam) + FirstPersonCam->bLockToHmd = !bIsReplaying; // only lock orientation and position to HMD when not replaying + + // perform all sensor updates that occur when replaying + if (bIsReplaying) + { + // this gets reached when the simulator is replaying data from a carla log + const DReyeVR::AggregateData *Replay = EgoSensor.Get()->GetData(); + + // include positional update here, else there is lag/jitter between the camera and the vehicle + // since the Carla Replayer tick differs from the EgoVehicle tick + const FTransform ReplayTransform(Replay->GetVehicleRotation(), // FRotator (Rotation) + Replay->GetVehicleLocation(), // FVector (Location) + FVector::OneVector); // FVector (Scale3D) + // see https://docs.unrealengine.com/4.26/en-US/API/Runtime/Engine/Engine/ETeleportType/ + SetActorTransform(ReplayTransform, false, nullptr, ETeleportType::TeleportPhysics); + + // set the camera reenactment orientation + { + const FTransform CameraOrientation = + bCameraFollowHMD // follow HMD reenacts all the head movmeents that were recorded + ? FTransform(Replay->GetCameraRotation(), Replay->GetCameraLocation(), FVector::OneVector) + : FTransform::Identity; // otherwise just point forward (neutral position) + FirstPersonCam->SetRelativeTransform(CameraOrientation, false, nullptr, ETeleportType::TeleportPhysics); + } + + // overwrite vehicle inputs to use the replay data + VehicleInputs = Replay->GetUserInputs(); + } +} + +void AEgoVehicle::UpdateSensor(const float DeltaSeconds) +{ + if (!EgoSensor.IsValid()) // Spawn and attach the EgoSensor + { + // unfortunately World->SpawnActor *sometimes* fails if used in BeginPlay so + // calling it once in the tick is fine to avoid this crash. + InitSensor(); + } + + if (!EgoSensor.IsValid()) + { + LOG_WARN("EgoSensor initialization failed!"); + return; + } + + // Explicitly update the EgoSensor here, synchronized with EgoVehicle tick + EgoSensor.Get()->ManualTick(DeltaSeconds); // Ensures we always get the latest data +} + +/// ========================================== /// +/// ----------------:MIRROR:------------------ /// +/// ========================================== /// + +void AEgoVehicle::MirrorParams::Initialize(class UStaticMeshComponent *MirrorSM, + class UPlanarReflectionComponent *Reflection, + class USkeletalMeshComponent *VehicleMesh) +{ + check(MirrorSM != nullptr); + MirrorSM->SetupAttachment(VehicleMesh); + MirrorSM->SetRelativeLocation(MirrorTransform.GetLocation()); + MirrorSM->SetRelativeRotation(MirrorTransform.Rotator()); + MirrorSM->SetRelativeScale3D(MirrorTransform.GetScale3D()); + MirrorSM->SetGenerateOverlapEvents(false); // don't collide with itself + MirrorSM->SetCollisionEnabled(ECollisionEnabled::NoCollision); + MirrorSM->SetVisibility(Enabled); + + check(Reflection != nullptr); + Reflection->SetupAttachment(MirrorSM); + Reflection->SetRelativeLocation(ReflectionTransform.GetLocation()); + Reflection->SetRelativeRotation(ReflectionTransform.Rotator()); + Reflection->SetRelativeScale3D(ReflectionTransform.GetScale3D()); + Reflection->NormalDistortionStrength = 0.0f; + Reflection->PrefilterRoughness = 0.0f; + Reflection->DistanceFromPlaneFadeoutStart = 1500.f; + Reflection->DistanceFromPlaneFadeoutEnd = 0.f; + Reflection->AngleFromPlaneFadeStart = 0.f; + Reflection->AngleFromPlaneFadeEnd = 90.f; + Reflection->PrefilterRoughnessDistance = 10000.f; + Reflection->ScreenPercentage = ScreenPercentage; // change this to reduce quality & improve performance + Reflection->bShowPreviewPlane = false; + Reflection->HideComponent(VehicleMesh); + Reflection->SetVisibility(Enabled); + /// TODO: use USceneCaptureComponent::ShowFlags to define what gets rendered in the mirror + // https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/FEngineShowFlags/ +} + +void AEgoVehicle::ConstructMirrors() +{ + + class USkeletalMeshComponent *VehicleMesh = GetMesh(); + /// Rear mirror + { + // the rear mirror is interesting bc we have 3 components: the mirror (specular), the mirror chassis + // (what holds the mirror, typically lambertian), and the planar reflection (invisible but "reflection") + // other mirrors currently only use the mirror and planar reflection, as we didn't cut out the chassis for them + RearMirrorSM = CreateEgoObject(RearMirrorParams.Name + "MirrorSM"); + RearReflection = CreateEgoObject(RearMirrorParams.Name + "Refl"); + RearMirrorChassisSM = CreateEgoObject(RearMirrorParams.Name + "MirrorChassisSM"); + + RearMirrorParams.Initialize(RearMirrorSM, RearReflection, VehicleMesh); + // also add the chassis for this mirror + RearMirrorChassisSM->SetupAttachment(VehicleMesh); + RearMirrorChassisSM->SetRelativeLocation(RearMirrorChassisTransform.GetLocation()); + RearMirrorChassisSM->SetRelativeRotation(RearMirrorChassisTransform.Rotator()); + RearMirrorChassisSM->SetRelativeScale3D(RearMirrorChassisTransform.GetScale3D()); + RearMirrorChassisSM->SetGenerateOverlapEvents(false); // don't collide with itself + RearMirrorChassisSM->SetCollisionEnabled(ECollisionEnabled::NoCollision); + RearMirrorChassisSM->SetVisibility(RearMirrorParams.Enabled); + RearMirrorSM->SetupAttachment(RearMirrorChassisSM); + RearReflection->HideComponent(RearMirrorChassisSM); // don't show this in the reflection + } + /// Left mirror + { + LeftMirrorSM = CreateEgoObject(LeftMirrorParams.Name + "MirrorSM"); + LeftReflection = CreateEgoObject(LeftMirrorParams.Name + "Refl"); + LeftMirrorParams.Initialize(LeftMirrorSM, LeftReflection, VehicleMesh); + } + /// Right mirror + { + RightMirrorSM = CreateEgoObject(RightMirrorParams.Name + "MirrorSM"); + RightReflection = CreateEgoObject(RightMirrorParams.Name + "Refl"); + RightMirrorParams.Initialize(RightMirrorSM, RightReflection, VehicleMesh); + } +} + +/// ========================================== /// +/// ----------------:SOUNDS:------------------ /// +/// ========================================== /// + +template bool FindSound(const FString &Section, const FString &Variable, UAudioComponent *Out) +{ + if (Out != nullptr) // TODO: check that the key is present + { + const FString PathStr = GeneralParams.Get(Section, Variable); + if (!PathStr.IsEmpty()) + { + ConstructorHelpers::FObjectFinder FoundSound(*PathStr); + if (FoundSound.Succeeded()) + { + Out->SetSound(FoundSound.Object); + return true; + } + } + } + return false; +} + +void AEgoVehicle::ConstructEgoSounds() +{ + // shouldn't override this method in ACarlaWHeeledVehicle because it will be + // used in the constructor and calling virtual methods in constructor is bad: + // https://stackoverflow.com/questions/962132/calling-virtual-functions-inside-constructors + + // Initialize ego-centric audio components + { + if (EngineRevSound != nullptr) + { + EngineRevSound->DestroyComponent(); // from the parent class (default sound) + EngineRevSound = nullptr; + } + EgoEngineRevSound = CreateEgoObject("EgoEngineRevSound"); + FindSound("Sound", "DefaultEngineRev", EgoEngineRevSound); + EgoEngineRevSound->SetupAttachment(GetRootComponent()); // attach to self + EgoEngineRevSound->bAutoActivate = true; // start playing on begin + EngineLocnInVehicle = VehicleParams.Get("Sounds", "EngineLocn"); + EgoEngineRevSound->SetRelativeLocation(EngineLocnInVehicle); // location of "engine" in vehicle (3D sound) + EgoEngineRevSound->SetFloatParameter(FName("RPM"), 0.f); // initially idle + EgoEngineRevSound->bAutoDestroy = false; // No automatic destroy, persist along with vehicle + check(EgoEngineRevSound != nullptr); + } + + { + if (CrashSound != nullptr) + { + CrashSound->DestroyComponent(); // from the parent class (default sound) + CrashSound = nullptr; + } + EgoCrashSound = CreateEgoObject("EgoCarCrash"); + FindSound("Sound", "DefaultCrashSound", EgoCrashSound); + EgoCrashSound->SetupAttachment(GetRootComponent()); + EgoCrashSound->bAutoActivate = false; + EgoCrashSound->bAutoDestroy = false; + check(EgoCrashSound != nullptr); + } + + { + GearShiftSound = CreateEgoObject("GearShift"); + FindSound("Sound", "DefaultGearShiftSound", GearShiftSound); + GearShiftSound->SetupAttachment(GetRootComponent()); + GearShiftSound->bAutoActivate = false; + check(GearShiftSound != nullptr); + } + + { + TurnSignalSound = CreateEgoObject("TurnSignal"); + FindSound("Sound", "DefaultTurnSignalSound", TurnSignalSound); + TurnSignalSound->SetupAttachment(GetRootComponent()); + TurnSignalSound->bAutoActivate = false; + check(TurnSignalSound != nullptr); + } + + ConstructEgoCollisionHandler(); +} + +void AEgoVehicle::PlayGearShiftSound(const float DelayBeforePlay) const +{ + if (GearShiftSound != nullptr) + GearShiftSound->Play(DelayBeforePlay); +} + +void AEgoVehicle::PlayTurnSignalSound(const float DelayBeforePlay) const +{ + if (TurnSignalSound != nullptr) + TurnSignalSound->Play(DelayBeforePlay); +} + +void AEgoVehicle::SetVolume(const float VolumeIn) +{ + if (EgoEngineRevSound) + EgoEngineRevSound->SetVolumeMultiplier(VolumeIn); + if (EgoCrashSound) + EgoCrashSound->SetVolumeMultiplier(VolumeIn); + if (GearShiftSound) + GearShiftSound->SetVolumeMultiplier(VolumeIn); + if (TurnSignalSound) + TurnSignalSound->SetVolumeMultiplier(VolumeIn); + Super::SetVolume(VolumeIn); +} + +void AEgoVehicle::TickSounds(float DeltaSeconds) +{ + // Respect the global vehicle volume param + SetVolume(ACarlaWheeledVehicle::Volume); + + if (EgoEngineRevSound) + { + if (!EgoEngineRevSound->IsPlaying()) + EgoEngineRevSound->Play(); // turn on the engine sound if not already on + float RPM = FMath::Clamp(GetVehicleMovementComponent()->GetEngineRotationSpeed(), 0.f, 5650.0f); + EgoEngineRevSound->SetFloatParameter(FName("RPM"), RPM); + } + + // add other sounds that need tick-level granularity here... +} + +void AEgoVehicle::ConstructEgoCollisionHandler() +{ + // using Carla's GetVehicleBoundingBox function + UBoxComponent *Bounds = this->GetVehicleBoundingBox(); + if (Bounds != nullptr) + { + Bounds->SetGenerateOverlapEvents(true); + Bounds->SetCollisionEnabled(ECollisionEnabled::QueryOnly); + Bounds->SetCollisionProfileName(TEXT("DReyeVRTrigger")); + Bounds->OnComponentBeginOverlap.AddDynamic(this, &AEgoVehicle::OnEgoOverlapBegin); + } +} + +void AEgoVehicle::OnEgoOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, + UPrimitiveComponent *OtherComp, int32 OtherBodyIndex, bool bFromSweep, + const FHitResult &SweepResult) +{ + if (OtherActor == nullptr || OtherActor == this) + return; + + // can be more flexible, such as having collisions with static props or people too + if (EnableCollisionForActor(OtherActor)) + { + // move the sound 1m in the direction of the collision + FVector SoundEmitLocation = 100.f * (this->GetActorLocation() - OtherActor->GetActorLocation()).GetSafeNormal(); + SoundEmitLocation.Z = 75.f; // Make the sound emitted not at the ground (75cm off ground) + if (EgoCrashSound != nullptr) + { + EgoCrashSound->SetRelativeLocation(SoundEmitLocation); + EgoCrashSound->Play(0.f); + // have at least 0.5s of buffer between collision audio + CollisionCooldownTime = GetWorld()->GetTimeSeconds() + 0.5f; + } + } +} + +/// ========================================== /// +/// -----------------:DASH:------------------- /// +/// ========================================== /// + +void AEgoVehicle::ConstructDashText() // dashboard text (speedometer, turn signals, gear shifter) +{ + // Create speedometer + if (VehicleParams.Get("Dashboard", "SpeedometerEnabled")) + { + Speedometer = CreateEgoObject("Speedometer"); + Speedometer->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); + Speedometer->SetRelativeTransform(VehicleParams.Get("Dashboard", "SpeedometerTransform")); + Speedometer->SetTextRenderColor(FColor::Red); + Speedometer->SetText(FText::FromString("0")); + Speedometer->SetXScale(1.f); + Speedometer->SetYScale(1.f); + Speedometer->SetWorldSize(10); // scale the font with this + Speedometer->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); + Speedometer->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + SpeedometerScale = CmPerSecondToXPerHour(GeneralParams.Get("EgoVehicle", "SpeedometerInMPH")); + check(Speedometer != nullptr); + } + + // Create turn signals + if (VehicleParams.Get("Dashboard", "TurnSignalsEnabled")) + { + TurnSignals = CreateEgoObject("TurnSignals"); + TurnSignals->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); + TurnSignals->SetRelativeTransform(VehicleParams.Get("Dashboard", "TurnSignalsTransform")); + TurnSignals->SetTextRenderColor(FColor::Red); + TurnSignals->SetText(FText::FromString("")); + TurnSignals->SetXScale(1.f); + TurnSignals->SetYScale(1.f); + TurnSignals->SetWorldSize(10); // scale the font with this + TurnSignals->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); + TurnSignals->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + check(TurnSignals != nullptr); + } + + // Create gear shifter + if (VehicleParams.Get("Dashboard", "GearShifterEnabled")) + { + GearShifter = CreateEgoObject("GearShifter"); + GearShifter->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); + GearShifter->SetRelativeTransform(VehicleParams.Get("Dashboard", "GearShifterTransform")); + GearShifter->SetTextRenderColor(FColor::Red); + GearShifter->SetText(FText::FromString("D")); + GearShifter->SetXScale(1.f); + GearShifter->SetYScale(1.f); + GearShifter->SetWorldSize(10); // scale the font with this + GearShifter->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); + GearShifter->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + check(GearShifter != nullptr); + } +} + +void AEgoVehicle::UpdateDash() +{ + // Draw text components + float XPH; // miles-per-hour or km-per-hour + if (EgoSensor.IsValid() && EgoSensor.Get()->IsReplaying()) + { + const DReyeVR::AggregateData *Replay = EgoSensor.Get()->GetData(); + XPH = Replay->GetVehicleVelocity() * SpeedometerScale; // FwdSpeed is in cm/s + const auto &ReplayInputs = Replay->GetUserInputs(); + if (ReplayInputs.ToggledReverse) + PressReverse(); + else + ReleaseReverse(); + + if (bEnableTurnSignalAction) + { + if (ReplayInputs.TurnSignalLeft) + PressTurnSignalL(); + else + ReleaseTurnSignalL(); + + if (ReplayInputs.TurnSignalRight) + PressTurnSignalR(); + else + ReleaseTurnSignalR(); + } + } + else + { + XPH = GetVehicleForwardSpeed() * SpeedometerScale; // FwdSpeed is in cm/s + } + + if (Speedometer != nullptr) + { + const FString Data = FString::FromInt(int(FMath::RoundHalfFromZero(XPH))); + Speedometer->SetText(FText::FromString(Data)); + } + + if (bEnableTurnSignalAction && TurnSignals != nullptr) + { + // Draw the signals + float Now = GetWorld()->GetTimeSeconds(); + const float StartTime = std::max(RightSignalTimeToDie, LeftSignalTimeToDie) - TurnSignalDuration; + FString TurnSignalStr = ""; + constexpr static float TurnSignalBlinkRate = 0.4f; // rate of blinking + if (std::fmodf(Now - StartTime, TurnSignalBlinkRate * 2) < TurnSignalBlinkRate) + { + if (Now < RightSignalTimeToDie) + TurnSignalStr = ">>>"; + else if (Now < LeftSignalTimeToDie) + TurnSignalStr = "<<<"; + } + TurnSignals->SetText(FText::FromString(TurnSignalStr)); + } + + if (GearShifter != nullptr) + { + // Draw the gear shifter + GearShifter->SetText(bReverse ? FText::FromString("R") : FText::FromString("D")); + } +} + +/// ========================================== /// +/// -----------------:WHEEL:------------------ /// +/// ========================================== /// + +void AEgoVehicle::ConstructSteeringWheel() +{ + const bool bEnableSteeringWheel = VehicleParams.Get("SteeringWheel", "Enabled"); + SteeringWheel = CreateEgoObject("SteeringWheel"); + SteeringWheel->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself + SteeringWheel->SetRelativeLocation(VehicleParams.Get("SteeringWheel", "InitLocation")); + SteeringWheel->SetRelativeRotation(VehicleParams.Get("SteeringWheel", "InitRotation")); + SteeringWheel->SetGenerateOverlapEvents(false); // don't collide with itself + SteeringWheel->SetCollisionEnabled(ECollisionEnabled::NoCollision); + SteeringWheel->SetVisibility(bEnableSteeringWheel); +} + +void AEgoVehicle::InitAutopilotIndicator() +{ + bool bEnableAutopilotIndicator = GeneralParams.Get("WheelFace", "EnableAutopilotIndicator"); + if (SteeringWheel == nullptr || World == nullptr || bEnableAutopilotIndicator == false) + return; + AutopilotIndicator = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "AI_Indicator"); + const FVector AutopilotIndicatorLocation = GeneralParams.Get("WheelFace", "AutopilotIndicatorLoc"); + const float AutopilotIndicatorSize = GeneralParams.Get("WheelFace", "AutopilotIndicatorSize"); + AutopilotIndicator->SetActorLocation(AutopilotIndicatorLocation); + check(AutopilotIndicator != nullptr); + AutopilotIndicator->Activate(); + AutopilotIndicator->SetActorScale3D(AutopilotIndicatorSize * FVector::OneVector); + AutopilotIndicator->AttachToComponent(SteeringWheel, FAttachmentTransformRules::KeepRelativeTransform); + AutopilotIndicator->MaterialParams.BaseColor = ButtonNeutralCol; // close to off + AutopilotIndicator->MaterialParams.Emissive = ButtonNeutralCol; // close to off + AutopilotIndicator->UpdateMaterial(); + AutopilotIndicator->SetActorTickEnabled(false); // don't tick these actors (for performance) + AutopilotIndicator->SetActorRecordEnabled(false); // don't need to record these actors either + AutopilotIndicator->GetMesh()->SetCastShadow(false); // don't want shadows (looks weird) + bInitializedAutopilotIndicator = true; +} + +void AEgoVehicle::InitWheelButtons() +{ + bool bEnableWheelFaceButtons = GeneralParams.Get("WheelFace", "EnableWheelButtons"); + if (SteeringWheel == nullptr || World == nullptr || bEnableWheelFaceButtons == false) + return; + // left buttons (dpad) + Button_DPad_Up = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Up"); // top on left + Button_DPad_Right = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Right"); // right on left + Button_DPad_Down = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Down"); // bottom on left + Button_DPad_Left = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Left"); // left on left + // right buttons (ABXY) + Button_ABXY_Y = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_Y"); // top on right + Button_ABXY_B = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_B"); // right on right + Button_ABXY_A = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_A"); // bottom on right + Button_ABXY_X = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_X"); // left on right + + const FRotator PointLeft(0.f, 0.f, -90.f); + const FRotator PointRight(0.f, 0.f, 90.f); + const FRotator PointUp(0.f, 0.f, 0.f); + const FRotator PointDown(0.f, 0.f, 180.f); + + const FVector LeftCenter = GeneralParams.Get("WheelFace", "ABXYLocation"); + const FVector RightCenter = GeneralParams.Get("WheelFace", "DpadLocation"); + + // increase to separate the buttons more + const float ButtonDist = GeneralParams.Get("WheelFace", "QuadButtonSpread"); + + Button_DPad_Up->SetActorLocation(LeftCenter + ButtonDist * FVector::UpVector); + Button_DPad_Up->SetActorRotation(PointUp); + Button_DPad_Right->SetActorLocation(LeftCenter + ButtonDist * FVector::RightVector); + Button_DPad_Right->SetActorRotation(PointRight); + Button_DPad_Down->SetActorLocation(LeftCenter + ButtonDist * FVector::DownVector); + Button_DPad_Down->SetActorRotation(PointDown); + Button_DPad_Left->SetActorLocation(LeftCenter + ButtonDist * FVector::LeftVector); + Button_DPad_Left->SetActorRotation(PointLeft); + + // (spheres don't need rotation) + Button_ABXY_Y->SetActorLocation(RightCenter + ButtonDist * FVector::UpVector); + Button_ABXY_B->SetActorLocation(RightCenter + ButtonDist * FVector::RightVector); + Button_ABXY_A->SetActorLocation(RightCenter + ButtonDist * FVector::DownVector); + Button_ABXY_X->SetActorLocation(RightCenter + ButtonDist * FVector::LeftVector); + + // for applying the same properties on these actors + auto WheelButtons = {Button_ABXY_A, Button_ABXY_B, Button_ABXY_X, Button_ABXY_Y, + Button_DPad_Up, Button_DPad_Down, Button_DPad_Left, Button_DPad_Right}; + for (auto *Button : WheelButtons) + { + check(Button != nullptr); + Button->Activate(); + Button->SetActorScale3D(0.015f * FVector::OneVector); + Button->AttachToComponent(SteeringWheel, FAttachmentTransformRules::KeepRelativeTransform); + Button->MaterialParams.BaseColor = ButtonNeutralCol; + Button->MaterialParams.Emissive = ButtonNeutralCol; + Button->UpdateMaterial(); + Button->SetActorTickEnabled(false); // don't tick these actors (for performance) + Button->SetActorRecordEnabled(false); // don't need to record these actors either + Button->GetMesh()->SetCastShadow(false); // don't want shadows (looks weird) + } + bInitializedButtons = true; +} + +void AEgoVehicle::UpdateWheelButton(ADReyeVRCustomActor *Button, bool bEnabled) +{ + if (Button == nullptr) + return; + Button->MaterialParams.BaseColor = bEnabled ? ButtonPressedCol : ButtonNeutralCol; + Button->MaterialParams.Emissive = bEnabled ? ButtonPressedCol : ButtonNeutralCol; + Button->UpdateMaterial(); +} + +void AEgoVehicle::TickAutopilotIndicator(bool bAutopilotEnabled) +{ + if (AutopilotIndicator == nullptr) + return; + const FLinearColor On = FLinearColor(0.537, 0.812, 0.941); // baby blue + const FLinearColor Off = 0.1f * FLinearColor(0.537, 0.812, 0.941); // baby blue (off) + AutopilotIndicator->MaterialParams.BaseColor = bAutopilotEnabled ? On : Off; + AutopilotIndicator->MaterialParams.Emissive = 500.f * (bAutopilotEnabled ? On : Off); + AutopilotIndicator->UpdateMaterial(); +} + +void AEgoVehicle::DestroySteeringWheel() +{ + auto WheelButtons = {Button_ABXY_A, Button_ABXY_B, Button_ABXY_X, Button_ABXY_Y, + Button_DPad_Up, Button_DPad_Down, Button_DPad_Left, Button_DPad_Right}; + for (auto *Button : WheelButtons) + { + if (Button) + { + Button->Deactivate(); + Button->Destroy(); + } + } +} + +void AEgoVehicle::TickSteeringWheel(const float DeltaTime) +{ + if (!SteeringWheel) + return; + if (!bInitializedButtons) + InitWheelButtons(); + if (!bInitializedAutopilotIndicator) + InitAutopilotIndicator(); + const FRotator CurrentRotation = SteeringWheel->GetRelativeRotation(); + FRotator NewRotation = CurrentRotation; + if (Pawn && Pawn->GetIsLogiConnected() && !GetAutopilotStatus()) + { + // make the virtual wheel rotation follow the physical steering wheel + const float RawSteering = GetVehicleInputs().Steering; // this is scaled in SetSteering + const float TargetAngle = (RawSteering / ScaleSteeringInput) * SteeringAnimScale; + NewRotation.Roll = TargetAngle; + } + else if (GetMesh() && Cast(GetMesh()->GetAnimInstance()) != nullptr) + { + // use the animation (front wheels) steer angle for the steering wheel + float WheelAngleDeg = GetWheelSteerAngle(EVehicleWheelLocation::Front_Wheel); + // float MaxWheelAngle = GetMaximumSteerAngle(); + float DeltaAngle = 10.f * (2.0f * WheelAngleDeg - CurrentRotation.Roll); + + // create the new rotation using the deltas + NewRotation += DeltaTime * FRotator(0.f, 0.f, DeltaAngle); + + // Clamp the roll amount so the wheel can't spin infinitely + NewRotation.Roll = FMath::Clamp(NewRotation.Roll, -MaxSteerAngleDeg, MaxSteerAngleDeg); + } + SteeringWheel->SetRelativeRotation(NewRotation); +} + +/// ========================================== /// +/// -----------------:LEVEL:------------------ /// +/// ========================================== /// + +void AEgoVehicle::SetGame(ADReyeVRGameMode *Game) +{ + DReyeVRGame = Game; + check(DReyeVRGame != nullptr); + check(DReyeVRGame->GetEgoVehicle() == this); + + DReyeVRGame->GetPawn()->BeginEgoVehicle(this, World); + LOG("Successfully assigned GameMode & controller pawn"); +} + +ADReyeVRGameMode *AEgoVehicle::GetGame() +{ + return DReyeVRGame; +} + +void AEgoVehicle::TickGame(float DeltaSeconds) +{ + if (this->DReyeVRGame != nullptr) + DReyeVRGame->Tick(DeltaSeconds); +} + +/// ========================================== /// +/// ---------------:COSMETIC:----------------- /// +/// ========================================== /// + +void AEgoVehicle::DebugLines() const +{ +#if WITH_EDITOR + + if (bDrawDebugEditor && EgoSensor.IsValid()) + { + // Calculate gaze data (in world space) using eye tracker data + const DReyeVR::AggregateData *Data = EgoSensor.Get()->GetData(); + // Compute World positions and orientations + const FRotator &WorldRot = FirstPersonCam->GetComponentRotation(); + const FVector &WorldPos = FirstPersonCam->GetComponentLocation(); + + // First get the gaze origin and direction and vergence from the EyeTracker Sensor + const float RayLength = FMath::Max(1.f, Data->GetGazeVergence() / 100.f); // vergence to m (from cm) + const float VRMeterScale = 100.f; + + // Both eyes + const FVector CombinedGaze = RayLength * VRMeterScale * Data->GetGazeDir(); + const FVector CombinedOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin()); + + // Left eye + const FVector LeftGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::LEFT); + const FVector LeftOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::LEFT)); + + // Right eye + const FVector RightGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::RIGHT); + const FVector RightOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::RIGHT)); + + // Use Absolute Ray Position to draw debug information + // Rotate and add the gaze ray to the origin + DrawDebugSphere(World, CombinedOrigin + WorldRot.RotateVector(CombinedGaze), 4.0f, 12, FColor::Blue); + + // Draw individual rays for left and right eye + DrawDebugLine(World, + LeftOrigin, // start line + LeftOrigin + 10 * WorldRot.RotateVector(LeftGaze), // end line + FColor::Green, false, -1, 0, 1); + + DrawDebugLine(World, + RightOrigin, // start line + RightOrigin + 10 * WorldRot.RotateVector(RightGaze), // end line + FColor::Yellow, false, -1, 0, 1); + } +#endif } \ No newline at end of file diff --git a/DReyeVR/EgoVehicle.h b/DReyeVR/EgoVehicle.h index 90faf0c..51859d4 100644 --- a/DReyeVR/EgoVehicle.h +++ b/DReyeVR/EgoVehicle.h @@ -1,269 +1,269 @@ -#pragma once - -#include "Camera/CameraComponent.h" // UCameraComponent -#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor -#include "Carla/Game/CarlaEpisode.h" // CarlaEpisode -#include "Carla/Sensor/DReyeVRData.h" // DReyeVR namespace -#include "Carla/Vehicle/CarlaWheeledVehicle.h" // ACarlaWheeledVehicle -#include "Carla/Vehicle/WheeledVehicleAIController.h" // AWheeledVehicleAIController -#include "Components/AudioComponent.h" // UAudioComponent -#include "Components/InputComponent.h" // InputComponent -#include "Components/PlanarReflectionComponent.h" // Planar Reflection -#include "Components/SceneComponent.h" // USceneComponent -#include "CoreMinimal.h" // Unreal functions -#include "DReyeVRGameMode.h" // ADReyeVRGameMode -#include "DReyeVRUtils.h" // GeneralParams.Get -#include "EgoSensor.h" // AEgoSensor -#include "FlatHUD.h" // ADReyeVRHUD -#include "ImageUtils.h" // CreateTexture2D -#include "WheeledVehicle.h" // VehicleMovementComponent -#include -#include - -#include "EgoVehicle.generated.h" - -class ADReyeVRGameMode; -class ADReyeVRPawn; - -UCLASS() -class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle -{ - GENERATED_BODY() - - friend class ADReyeVRPawn; - - public: - // Sets default values for this pawn's properties - AEgoVehicle(const FObjectInitializer &ObjectInitializer); - - void ReadConfigVariables(); - - virtual void Tick(float DeltaTime) override; // called automatically - - // Setters from external classes - void SetGame(ADReyeVRGameMode *Game); - ADReyeVRGameMode *GetGame(); - void SetPawn(ADReyeVRPawn *Pawn); - void SetVolume(const float VolumeIn); - - // Getters - const FString &GetVehicleType() const; - FVector GetCameraOffset() const; - FVector GetCameraPosn() const; - FVector GetNextCameraPosn(const float DeltaSeconds) const; - FRotator GetCameraRot() const; - const UCameraComponent *GetCamera() const; - UCameraComponent *GetCamera(); - const DReyeVR::UserInputs &GetVehicleInputs() const; - const class AEgoSensor *GetSensor() const; - const struct ConfigFile &GetVehicleParams() const; - - // autopilot API - void SetAutopilot(const bool AutopilotOn); - bool GetAutopilotStatus() const; - /// TODO: add custom routes for autopilot - - // Play sounds - void PlayGearShiftSound(const float DelayBeforePlay = 0.f) const; - void PlayTurnSignalSound(const float DelayBeforePlay = 0.f) const; - - // Camera view - size_t GetNumCameraPoses() const; // how many diff poses? - void SetCameraRootPose(const FTransform &Pose); // give arbitrary FTransform - void SetCameraRootPose(const FString &PoseName); // index into named FTransform - void SetCameraRootPose(size_t PoseIdx); // index into ordered FTransform - const FTransform &GetCameraRootPose() const; - void BeginThirdPersonCameraInit(); - void NextCameraView(); - void PrevCameraView(); - - protected: - // Called when the game starts (spawned) or ends (destroyed) - virtual void BeginPlay() override; - virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override; - virtual void BeginDestroy() override; - - // custom configuration file for vehicle-specific parameters - struct ConfigFile VehicleParams; - - // World variables - class UWorld *World; - - private: - template T *CreateEgoObject(const FString &Name, const FString &Suffix = ""); - FString VehicleType; // initially empty (set in GetVehicleType()) - - private: // camera - UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class USceneComponent *VRCameraRoot; - UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UCameraComponent *FirstPersonCam; - void ConstructCameraRoot(); // needs to be called in the constructor - FTransform CameraPose, CameraPoseOffset; // camera pose (location & rotation) and manual offset - TMap CameraTransforms; // collection of named transforms from params - TArray CameraPoseKeys; // to iterate through them - size_t CurrentCameraTransformIdx = 0; // to index in CameraPoseKeys which indexes into CameraTransforms - bool bCameraFollowHMD = true; // disable this (in params) to replay without following the player's HMD (replay-only) - - private: // sensor - class AEgoSensor *GetSensor(); - void ReplayTick(); - void InitSensor(); - // custom sensor helper that holds logic for extracting useful data - TWeakObjectPtr EgoSensor; // EgoVehicle should have exclusive access (TODO: unique ptr?) - void UpdateSensor(const float DeltaTime); - - private: // pawn - class ADReyeVRPawn *Pawn = nullptr; - - private: // mirrors - void ConstructMirrors(); - struct MirrorParams - { - bool Enabled; - FTransform MirrorTransform, ReflectionTransform; - float ScreenPercentage; - FString Name; - void Initialize(class UStaticMeshComponent *SM, class UPlanarReflectionComponent *Reflection, - class USkeletalMeshComponent *VehicleMesh); - }; - struct MirrorParams RearMirrorParams, LeftMirrorParams, RightMirrorParams; - UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UStaticMeshComponent *RightMirrorSM; - UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UPlanarReflectionComponent *RightReflection; - UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UStaticMeshComponent *LeftMirrorSM; - UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UPlanarReflectionComponent *LeftReflection; - UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UStaticMeshComponent *RearMirrorSM; - UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UPlanarReflectionComponent *RearReflection; - // rear mirror chassis (dynamic) - UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UStaticMeshComponent *RearMirrorChassisSM; - FTransform RearMirrorChassisTransform; - - private: // AI controller - class AWheeledVehicleAIController *AI_Player = nullptr; - void InitAIPlayer(); - bool bAutopilotEnabled = false; - void TickAutopilot(); - - private: // inputs - /// NOTE: since there are so many functions here, they are defined in EgoInputs.cpp - struct DReyeVR::UserInputs VehicleInputs; // struct for user inputs - // Vehicle control functions (additive for multiple input modalities (kbd/logi)) - void AddSteering(float SteeringInput); - void AddThrottle(float ThrottleInput); - void AddBrake(float BrakeInput); - void TickVehicleInputs(); - bool bReverse; - - // "button presses" should have both a "Press" and "Release" function - // And, if using the logitech plugin, should also have an "is rising edge" bool so they can only - // be pressed after being released (cant double press w/ no release) - // Reverse toggle - void PressReverse(); - void ReleaseReverse(); - bool bCanPressReverse = true; - // turn signals - bool bEnableTurnSignalAction = true; // tune with "EnableTurnSignalAction" in config - // left turn signal - void PressTurnSignalL(); - void ReleaseTurnSignalL(); - float LeftSignalTimeToDie; // how long until the blinkers go out - bool bCanPressTurnSignalL = true; - // right turn signal - void PressTurnSignalR(); - void ReleaseTurnSignalR(); - float RightSignalTimeToDie; // how long until the blinkers go out - bool bCanPressTurnSignalR = true; - - // Camera control functions (offset by some amount) - void CameraPositionAdjust(const FVector &Disp); - void CameraFwd(); - void CameraBack(); - void CameraLeft(); - void CameraRight(); - void CameraUp(); - void CameraDown(); - void CameraPositionAdjust(bool bForward, bool bRight, bool bBackwards, bool bLeft, bool bUp, bool bDown); - - // changing camera views - void PressNextCameraView(); - void ReleaseNextCameraView(); - bool bCanPressNextCameraView = true; - void PressPrevCameraView(); - void ReleasePrevCameraView(); - bool bCanPressPrevCameraView = true; - - // Vehicle parameters - float ScaleSteeringInput; - float ScaleThrottleInput; - float ScaleBrakeInput; - - private: // sounds - UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UAudioComponent *GearShiftSound; // nice for toggling reverse - UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UAudioComponent *TurnSignalSound; // good for turn signals - UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UAudioComponent *EgoEngineRevSound; // driver feedback on throttle - UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UAudioComponent *EgoCrashSound; // crashing with another actor - void ConstructEgoSounds(); // needs to be called in the constructor - virtual void TickSounds(float DeltaSeconds) override; - - // manually overriding these from ACarlaWheeledVehicle - void ConstructEgoCollisionHandler(); // needs to be called in the constructor - UFUNCTION() - void OnEgoOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, UPrimitiveComponent *OtherComp, - int32 OtherBodyIndex, bool bFromSweep, const FHitResult &SweepResult); - - private: // gamemode/level - void TickGame(float DeltaSeconds); - class ADReyeVRGameMode *DReyeVRGame; - - private: // dashboard - // Text Render components (Like the HUD but part of the mesh and works in VR) - void ConstructDashText(); // needs to be called in the constructor - UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UTextRenderComponent *Speedometer; - UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UTextRenderComponent *TurnSignals; - float TurnSignalDuration; // time in seconds - UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UTextRenderComponent *GearShifter; - void UpdateDash(); - float SpeedometerScale = CmPerSecondToXPerHour(true); // scale from CM/s to MPH or KPH (default MPH) - - private: // steering wheel - UPROPERTY(Category = Steering, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) - class UStaticMeshComponent *SteeringWheel; - void ConstructSteeringWheel(); // needs to be called in the constructor - void DestroySteeringWheel(); - void TickSteeringWheel(const float DeltaTime); - float MaxSteerAngleDeg; - float MaxSteerVelocity; - float SteeringAnimScale; - bool bWheelFollowAutopilot = true; // disable steering during autopilot and follow AI - // wheel face buttons - void InitWheelButtons(); - void UpdateWheelButton(ADReyeVRCustomActor *Button, bool bEnabled); - class ADReyeVRCustomActor *Button_ABXY_A, *Button_ABXY_B, *Button_ABXY_X, *Button_ABXY_Y; - class ADReyeVRCustomActor *Button_DPad_Up, *Button_DPad_Down, *Button_DPad_Left, *Button_DPad_Right; - bool bInitializedButtons = false; - const FLinearColor ButtonNeutralCol = 0.2f * FLinearColor::White; - const FLinearColor ButtonPressedCol = 1.5f * FLinearColor::White; - // wheel face autopilot indicator - void InitAutopilotIndicator(); - void TickAutopilotIndicator(bool); - class ADReyeVRCustomActor *AutopilotIndicator; - bool bInitializedAutopilotIndicator = false; - - private: // other - void DebugLines() const; - bool bDrawDebugEditor = false; +#pragma once + +#include "Camera/CameraComponent.h" // UCameraComponent +#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor +#include "Carla/Game/CarlaEpisode.h" // CarlaEpisode +#include "Carla/Sensor/DReyeVRData.h" // DReyeVR namespace +#include "Carla/Vehicle/CarlaWheeledVehicle.h" // ACarlaWheeledVehicle +#include "Carla/Vehicle/WheeledVehicleAIController.h" // AWheeledVehicleAIController +#include "Components/AudioComponent.h" // UAudioComponent +#include "Components/InputComponent.h" // InputComponent +#include "Components/PlanarReflectionComponent.h" // Planar Reflection +#include "Components/SceneComponent.h" // USceneComponent +#include "CoreMinimal.h" // Unreal functions +#include "DReyeVRGameMode.h" // ADReyeVRGameMode +#include "DReyeVRUtils.h" // GeneralParams.Get +#include "EgoSensor.h" // AEgoSensor +#include "FlatHUD.h" // ADReyeVRHUD +#include "ImageUtils.h" // CreateTexture2D +#include "WheeledVehicle.h" // VehicleMovementComponent +#include +#include + +#include "EgoVehicle.generated.h" + +class ADReyeVRGameMode; +class ADReyeVRPawn; + +UCLASS() +class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle +{ + GENERATED_BODY() + + friend class ADReyeVRPawn; + + public: + // Sets default values for this pawn's properties + AEgoVehicle(const FObjectInitializer &ObjectInitializer); + + void ReadConfigVariables(); + + virtual void Tick(float DeltaTime) override; // called automatically + + // Setters from external classes + void SetGame(ADReyeVRGameMode *Game); + ADReyeVRGameMode *GetGame(); + void SetPawn(ADReyeVRPawn *Pawn); + void SetVolume(const float VolumeIn); + + // Getters + const FString &GetVehicleType() const; + FVector GetCameraOffset() const; + FVector GetCameraPosn() const; + FVector GetNextCameraPosn(const float DeltaSeconds) const; + FRotator GetCameraRot() const; + const UCameraComponent *GetCamera() const; + UCameraComponent *GetCamera(); + const DReyeVR::UserInputs &GetVehicleInputs() const; + const class AEgoSensor *GetSensor() const; + const struct ConfigFile &GetVehicleParams() const; + + // autopilot API + void SetAutopilot(const bool AutopilotOn); + bool GetAutopilotStatus() const; + /// TODO: add custom routes for autopilot + + // Play sounds + void PlayGearShiftSound(const float DelayBeforePlay = 0.f) const; + void PlayTurnSignalSound(const float DelayBeforePlay = 0.f) const; + + // Camera view + size_t GetNumCameraPoses() const; // how many diff poses? + void SetCameraRootPose(const FTransform &Pose); // give arbitrary FTransform + void SetCameraRootPose(const FString &PoseName); // index into named FTransform + void SetCameraRootPose(size_t PoseIdx); // index into ordered FTransform + const FTransform &GetCameraRootPose() const; + void BeginThirdPersonCameraInit(); + void NextCameraView(); + void PrevCameraView(); + + protected: + // Called when the game starts (spawned) or ends (destroyed) + virtual void BeginPlay() override; + virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override; + virtual void BeginDestroy() override; + + // custom configuration file for vehicle-specific parameters + struct ConfigFile VehicleParams; + + // World variables + class UWorld *World; + + private: + template T *CreateEgoObject(const FString &Name, const FString &Suffix = ""); + FString VehicleType; // initially empty (set in GetVehicleType()) + + private: // camera + UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class USceneComponent *VRCameraRoot; + UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UCameraComponent *FirstPersonCam; + void ConstructCameraRoot(); // needs to be called in the constructor + FTransform CameraPose, CameraPoseOffset; // camera pose (location & rotation) and manual offset + TMap CameraTransforms; // collection of named transforms from params + TArray CameraPoseKeys; // to iterate through them + size_t CurrentCameraTransformIdx = 0; // to index in CameraPoseKeys which indexes into CameraTransforms + bool bCameraFollowHMD = true; // disable this (in params) to replay without following the player's HMD (replay-only) + + private: // sensor + class AEgoSensor *GetSensor(); + void ReplayTick(); + void InitSensor(); + // custom sensor helper that holds logic for extracting useful data + TWeakObjectPtr EgoSensor; // EgoVehicle should have exclusive access (TODO: unique ptr?) + void UpdateSensor(const float DeltaTime); + + private: // pawn + class ADReyeVRPawn *Pawn = nullptr; + + private: // mirrors + void ConstructMirrors(); + struct MirrorParams + { + bool Enabled; + FTransform MirrorTransform, ReflectionTransform; + float ScreenPercentage; + FString Name; + void Initialize(class UStaticMeshComponent *SM, class UPlanarReflectionComponent *Reflection, + class USkeletalMeshComponent *VehicleMesh); + }; + struct MirrorParams RearMirrorParams, LeftMirrorParams, RightMirrorParams; + UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UStaticMeshComponent *RightMirrorSM; + UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UPlanarReflectionComponent *RightReflection; + UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UStaticMeshComponent *LeftMirrorSM; + UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UPlanarReflectionComponent *LeftReflection; + UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UStaticMeshComponent *RearMirrorSM; + UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UPlanarReflectionComponent *RearReflection; + // rear mirror chassis (dynamic) + UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UStaticMeshComponent *RearMirrorChassisSM; + FTransform RearMirrorChassisTransform; + + private: // AI controller + class AWheeledVehicleAIController *AI_Player = nullptr; + void InitAIPlayer(); + bool bAutopilotEnabled = false; + void TickAutopilot(); + + private: // inputs + /// NOTE: since there are so many functions here, they are defined in EgoInputs.cpp + struct DReyeVR::UserInputs VehicleInputs; // struct for user inputs + // Vehicle control functions (additive for multiple input modalities (kbd/logi)) + void AddSteering(float SteeringInput); + void AddThrottle(float ThrottleInput); + void AddBrake(float BrakeInput); + void TickVehicleInputs(); + bool bReverse; + + // "button presses" should have both a "Press" and "Release" function + // And, if using the logitech plugin, should also have an "is rising edge" bool so they can only + // be pressed after being released (cant double press w/ no release) + // Reverse toggle + void PressReverse(); + void ReleaseReverse(); + bool bCanPressReverse = true; + // turn signals + bool bEnableTurnSignalAction = true; // tune with "EnableTurnSignalAction" in config + // left turn signal + void PressTurnSignalL(); + void ReleaseTurnSignalL(); + float LeftSignalTimeToDie; // how long until the blinkers go out + bool bCanPressTurnSignalL = true; + // right turn signal + void PressTurnSignalR(); + void ReleaseTurnSignalR(); + float RightSignalTimeToDie; // how long until the blinkers go out + bool bCanPressTurnSignalR = true; + + // Camera control functions (offset by some amount) + void CameraPositionAdjust(const FVector &Disp); + void CameraFwd(); + void CameraBack(); + void CameraLeft(); + void CameraRight(); + void CameraUp(); + void CameraDown(); + void CameraPositionAdjust(bool bForward, bool bRight, bool bBackwards, bool bLeft, bool bUp, bool bDown); + + // changing camera views + void PressNextCameraView(); + void ReleaseNextCameraView(); + bool bCanPressNextCameraView = true; + void PressPrevCameraView(); + void ReleasePrevCameraView(); + bool bCanPressPrevCameraView = true; + + // Vehicle parameters + float ScaleSteeringInput; + float ScaleThrottleInput; + float ScaleBrakeInput; + + private: // sounds + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *GearShiftSound; // nice for toggling reverse + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *TurnSignalSound; // good for turn signals + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *EgoEngineRevSound; // driver feedback on throttle + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *EgoCrashSound; // crashing with another actor + void ConstructEgoSounds(); // needs to be called in the constructor + virtual void TickSounds(float DeltaSeconds) override; + + // manually overriding these from ACarlaWheeledVehicle + void ConstructEgoCollisionHandler(); // needs to be called in the constructor + UFUNCTION() + void OnEgoOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, UPrimitiveComponent *OtherComp, + int32 OtherBodyIndex, bool bFromSweep, const FHitResult &SweepResult); + + private: // gamemode/level + void TickGame(float DeltaSeconds); + class ADReyeVRGameMode *DReyeVRGame; + + private: // dashboard + // Text Render components (Like the HUD but part of the mesh and works in VR) + void ConstructDashText(); // needs to be called in the constructor + UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UTextRenderComponent *Speedometer; + UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UTextRenderComponent *TurnSignals; + float TurnSignalDuration; // time in seconds + UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UTextRenderComponent *GearShifter; + void UpdateDash(); + float SpeedometerScale = CmPerSecondToXPerHour(true); // scale from CM/s to MPH or KPH (default MPH) + + private: // steering wheel + UPROPERTY(Category = Steering, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UStaticMeshComponent *SteeringWheel; + void ConstructSteeringWheel(); // needs to be called in the constructor + void DestroySteeringWheel(); + void TickSteeringWheel(const float DeltaTime); + float MaxSteerAngleDeg; + float MaxSteerVelocity; + float SteeringAnimScale; + bool bWheelFollowAutopilot = true; // disable steering during autopilot and follow AI + // wheel face buttons + void InitWheelButtons(); + void UpdateWheelButton(ADReyeVRCustomActor *Button, bool bEnabled); + class ADReyeVRCustomActor *Button_ABXY_A, *Button_ABXY_B, *Button_ABXY_X, *Button_ABXY_Y; + class ADReyeVRCustomActor *Button_DPad_Up, *Button_DPad_Down, *Button_DPad_Left, *Button_DPad_Right; + bool bInitializedButtons = false; + const FLinearColor ButtonNeutralCol = 0.2f * FLinearColor::White; + const FLinearColor ButtonPressedCol = 1.5f * FLinearColor::White; + // wheel face autopilot indicator + void InitAutopilotIndicator(); + void TickAutopilotIndicator(bool); + class ADReyeVRCustomActor *AutopilotIndicator; + bool bInitializedAutopilotIndicator = false; + + private: // other + void DebugLines() const; + bool bDrawDebugEditor = false; }; \ No newline at end of file diff --git a/DReyeVR/FlatHUD.cpp b/DReyeVR/FlatHUD.cpp index 9eebf7e..a92a21a 100644 --- a/DReyeVR/FlatHUD.cpp +++ b/DReyeVR/FlatHUD.cpp @@ -1,210 +1,210 @@ -#include "FlatHUD.h" - -#include "DReyeVRUtils.h" // GetTimeSeconds - -// fixing issue described in CarlaHUD.h regarding DrawText on Windows -#ifdef DrawText -#undef DrawText -#endif - -void ADReyeVRHUD::SetPlayer(APlayerController *P) -{ - Player = P; - // Player = GetOwningPlayerController(); - if (Player == nullptr) - { - LOG_ERROR("Can't find player controller!"); - } - check(Player != nullptr); -} - -void ADReyeVRHUD::DrawHUD() -{ - Super::DrawHUD(); - - double Now = FPlatformTime::Seconds(); - int i = 0; - while (i < StaticTextList.Num()) - { - const TimedText &T = StaticTextList[i]; - DrawText(T.HT.Text, T.HT.Colour, T.HT.Screen.X, T.HT.Screen.Y, T.HT.TypeFace, T.HT.Scale); - if (Now >= T.TimeToDie) - { - StaticTextList.RemoveAt(i); - } - else - { - // only increment if this static entity is kept, else all others are pushed to its place - i++; - } - } - - // Draw all dynamic text entities once, then remove them (to be replaced) - for (const HUDText &H : DynamicTextList) - { - DrawText(H.Text, H.Colour, H.Screen.X, H.Screen.Y, H.TypeFace, H.Scale); - } - DynamicTextList.Empty(); // clear to reuse on next DrawHUD - - // Draw texture components - for (const HUDTexture &HT : DynamicTextures) - { - DrawTextureSimple(HT.U, HT.Screen.X, HT.Screen.Y, 1.f, false); - } - DynamicTextures.Empty(); // clear to reuse on next DrawHUD - - // Draw reticle texture - DrawTextureSimple(ReticleTexture.U, ReticleTexture.Screen.X, ReticleTexture.Screen.Y, 1.f, false); - - // Draw line components - for (const HUDLine &L : DynamicLineList) - { - DrawLine(L.Start.X, L.Start.Y, L.End.X, L.End.Y, L.Colour, L.Thickness); - } - DynamicLineList.Empty(); // clear to reuse on next DrawHUD - - // Draw squares - for (const HUDRect &R : DynamicRectList) - { - // DrawRect is a solid rectangle, we are interested in drawing a stroked-rectangle (4 lines) - // if (R.Thickness == 0) - // { - // const FVector2D Dims = R.BottomRight - R.TopLeft; - // const float Width = Dims.X; - // const float Height = Dims.Y; - // DrawRect(R.Colour, R.TopLeft.X + Width / 2.0, R.TopLeft.Y + Height / 2.0, Width, Height); - // } - // else - { - // DrawLine has the ability to have different thicknesses - DrawLine(R.TopLeft.X, R.TopLeft.Y, R.BottomRight.X, R.TopLeft.Y, R.Colour, R.Thickness); // top - DrawLine(R.TopLeft.X, R.BottomRight.Y, R.BottomRight.X, R.BottomRight.Y, R.Colour, R.Thickness); // bottom - DrawLine(R.TopLeft.X, R.TopLeft.Y, R.TopLeft.X, R.BottomRight.Y, R.Colour, R.Thickness); // left - DrawLine(R.BottomRight.X, R.TopLeft.Y, R.BottomRight.X, R.BottomRight.Y, R.Colour, R.Thickness); // right - } - } - DynamicRectList.Empty(); // clear to reuse on next DrawHUD - - // Draw crosshairs - for (const HUDCrosshair &C : DynamicCrosshairList) - { - const float Radius = C.Diameter / 2.f; - FVector2D CirclePt = FVector2D(0, -Radius); // about origin so it can get rotated correctly - const int NumSides = 16; - const float RotAngleDeg = 360.f / NumSides; - for (i = 0; i < NumSides; i++) // draw all the line segments - { - FVector2D NextPt = CirclePt.GetRotated(RotAngleDeg); - DrawLine(C.Center.X + CirclePt.X, C.Center.Y + CirclePt.Y, C.Center.X + NextPt.X, C.Center.Y + NextPt.Y, - C.Colour, C.Thickness); - CirclePt = NextPt; // draw next segment from here - } - if (C.InnerT) // draw the inner cross (+) - { - DrawLine(C.Center.X, C.Center.Y - Radius, C.Center.X, C.Center.Y + Radius, C.Colour, C.Thickness); - DrawLine(C.Center.X - Radius, C.Center.Y, C.Center.X + Radius, C.Center.Y, C.Colour, C.Thickness); - } - } - DynamicCrosshairList.Empty(); // clear to reuse on next DrawHUD -} - -void ADReyeVRHUD::DrawDynamicText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, - const bool bIsRelative, const UFont *Font) -{ - FVector2D Screen; - check(Player != nullptr); - if (Player->ProjectWorldLocationToScreen(Loc, Screen, bIsRelative)) - DrawDynamicText(Str, Screen, Colour, Scale, Font); -} - -void ADReyeVRHUD::DrawDynamicText(const FString &Str, const FVector2D &Screen, const FColor &Colour, const float Scale, - const UFont *Font) -{ - HUDText DText{Str, Screen, Colour, Scale, const_cast(Font)}; - DynamicTextList.Add(std::move(DText)); -} - -void ADReyeVRHUD::DrawReticle(UTexture *U, const FVector2D &Screen) -{ - ReticleTexture.U = U; - ReticleTexture.Screen = Screen; -} - -void ADReyeVRHUD::DrawDynamicTexture(UTexture *U, const FVector2D &Screen) -{ - HUDTexture HTexture{U, Screen}; - DynamicTextures.Add(std::move(HTexture)); -} - -void ADReyeVRHUD::DrawStaticText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, - const float LifeTime, const bool bIsRelative, const UFont *Font) -{ - FVector2D Screen; - check(Player != nullptr); - if (Player->ProjectWorldLocationToScreen(Loc, Screen, bIsRelative)) - DrawStaticText(Str, Screen, Colour, Scale, LifeTime, Font); -} - -void ADReyeVRHUD::DrawStaticText(const FString &Str, const FVector2D &Screen, const FColor &Colour, const float Scale, - const float LifeTime, const UFont *Font) -{ - HUDText SText{Str, Screen, Colour, Scale, const_cast(Font)}; - float Now = FPlatformTime::Seconds(); - TimedText TText{SText, Now + LifeTime}; - StaticTextList.Add(std::move(TText)); -} - -void ADReyeVRHUD::DrawDynamicLine(const FVector &Start, const FVector &End, const FColor &Colour, const float Thickness) -{ - /// TODO: store player rather than re-get - check(Player != nullptr); - FVector2D StartScreen, EndScreen; - if (Player->ProjectWorldLocationToScreen(Start, StartScreen, true) && - Player->ProjectWorldLocationToScreen(End, EndScreen, true)) - DrawDynamicLine(StartScreen, EndScreen, Colour, Thickness); -} - -void ADReyeVRHUD::DrawDynamicLine(const FVector2D &Start, const FVector2D &End, const FColor &Colour, - const float Thickness) -{ - HUDLine DLine{Start, End, Colour, Thickness}; - DynamicLineList.Add(std::move(DLine)); -} - -void ADReyeVRHUD::DrawDynamicSquare(const FVector &Center, const float Size, const FColor &Colour, - const float Thickness) -{ - FVector2D CenterScreen; - if (Player->ProjectWorldLocationToScreen(Center, CenterScreen, true)) - DrawDynamicSquare(CenterScreen, Size, Colour, Thickness); -} - -void ADReyeVRHUD::DrawDynamicSquare(const FVector2D &Center, const float Size, const FColor &Colour, - const float Thickness) -{ - DrawDynamicRect(Center - FVector2D(Size / 2.0, Size / 2.0), // top left - Center + FVector2D(Size / 2.0, Size / 2.0), // bottom right - Colour, Thickness); -} - -void ADReyeVRHUD::DrawDynamicRect(const FVector2D &TopLeft, const FVector2D &BottomRight, const FColor &Colour, - const float Thickness) -{ - HUDRect Square{TopLeft, BottomRight, Colour, Thickness}; - DynamicRectList.Add(std::move(Square)); -} - -void ADReyeVRHUD::DrawDynamicCrosshair(const FVector &Center, const float Diameter, const FColor &Colour, - const bool InnerT, const float Thickness) -{ - FVector2D CenterScreen; - if (Player->ProjectWorldLocationToScreen(Center, CenterScreen, true)) - DrawDynamicCrosshair(CenterScreen, Diameter, Colour, InnerT, Thickness); -} - -void ADReyeVRHUD::DrawDynamicCrosshair(const FVector2D &Center, const float Diameter, const FColor &Colour, - const bool InnerT, const float Thickness) -{ - HUDCrosshair Crosshair{Center, Diameter, Colour, InnerT, Thickness}; - DynamicCrosshairList.Add(std::move(Crosshair)); +#include "FlatHUD.h" + +#include "DReyeVRUtils.h" // GetTimeSeconds + +// fixing issue described in CarlaHUD.h regarding DrawText on Windows +#ifdef DrawText +#undef DrawText +#endif + +void ADReyeVRHUD::SetPlayer(APlayerController *P) +{ + Player = P; + // Player = GetOwningPlayerController(); + if (Player == nullptr) + { + LOG_ERROR("Can't find player controller!"); + } + check(Player != nullptr); +} + +void ADReyeVRHUD::DrawHUD() +{ + Super::DrawHUD(); + + double Now = FPlatformTime::Seconds(); + int i = 0; + while (i < StaticTextList.Num()) + { + const TimedText &T = StaticTextList[i]; + DrawText(T.HT.Text, T.HT.Colour, T.HT.Screen.X, T.HT.Screen.Y, T.HT.TypeFace, T.HT.Scale); + if (Now >= T.TimeToDie) + { + StaticTextList.RemoveAt(i); + } + else + { + // only increment if this static entity is kept, else all others are pushed to its place + i++; + } + } + + // Draw all dynamic text entities once, then remove them (to be replaced) + for (const HUDText &H : DynamicTextList) + { + DrawText(H.Text, H.Colour, H.Screen.X, H.Screen.Y, H.TypeFace, H.Scale); + } + DynamicTextList.Empty(); // clear to reuse on next DrawHUD + + // Draw texture components + for (const HUDTexture &HT : DynamicTextures) + { + DrawTextureSimple(HT.U, HT.Screen.X, HT.Screen.Y, 1.f, false); + } + DynamicTextures.Empty(); // clear to reuse on next DrawHUD + + // Draw reticle texture + DrawTextureSimple(ReticleTexture.U, ReticleTexture.Screen.X, ReticleTexture.Screen.Y, 1.f, false); + + // Draw line components + for (const HUDLine &L : DynamicLineList) + { + DrawLine(L.Start.X, L.Start.Y, L.End.X, L.End.Y, L.Colour, L.Thickness); + } + DynamicLineList.Empty(); // clear to reuse on next DrawHUD + + // Draw squares + for (const HUDRect &R : DynamicRectList) + { + // DrawRect is a solid rectangle, we are interested in drawing a stroked-rectangle (4 lines) + // if (R.Thickness == 0) + // { + // const FVector2D Dims = R.BottomRight - R.TopLeft; + // const float Width = Dims.X; + // const float Height = Dims.Y; + // DrawRect(R.Colour, R.TopLeft.X + Width / 2.0, R.TopLeft.Y + Height / 2.0, Width, Height); + // } + // else + { + // DrawLine has the ability to have different thicknesses + DrawLine(R.TopLeft.X, R.TopLeft.Y, R.BottomRight.X, R.TopLeft.Y, R.Colour, R.Thickness); // top + DrawLine(R.TopLeft.X, R.BottomRight.Y, R.BottomRight.X, R.BottomRight.Y, R.Colour, R.Thickness); // bottom + DrawLine(R.TopLeft.X, R.TopLeft.Y, R.TopLeft.X, R.BottomRight.Y, R.Colour, R.Thickness); // left + DrawLine(R.BottomRight.X, R.TopLeft.Y, R.BottomRight.X, R.BottomRight.Y, R.Colour, R.Thickness); // right + } + } + DynamicRectList.Empty(); // clear to reuse on next DrawHUD + + // Draw crosshairs + for (const HUDCrosshair &C : DynamicCrosshairList) + { + const float Radius = C.Diameter / 2.f; + FVector2D CirclePt = FVector2D(0, -Radius); // about origin so it can get rotated correctly + const int NumSides = 16; + const float RotAngleDeg = 360.f / NumSides; + for (i = 0; i < NumSides; i++) // draw all the line segments + { + FVector2D NextPt = CirclePt.GetRotated(RotAngleDeg); + DrawLine(C.Center.X + CirclePt.X, C.Center.Y + CirclePt.Y, C.Center.X + NextPt.X, C.Center.Y + NextPt.Y, + C.Colour, C.Thickness); + CirclePt = NextPt; // draw next segment from here + } + if (C.InnerT) // draw the inner cross (+) + { + DrawLine(C.Center.X, C.Center.Y - Radius, C.Center.X, C.Center.Y + Radius, C.Colour, C.Thickness); + DrawLine(C.Center.X - Radius, C.Center.Y, C.Center.X + Radius, C.Center.Y, C.Colour, C.Thickness); + } + } + DynamicCrosshairList.Empty(); // clear to reuse on next DrawHUD +} + +void ADReyeVRHUD::DrawDynamicText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, + const bool bIsRelative, const UFont *Font) +{ + FVector2D Screen; + check(Player != nullptr); + if (Player->ProjectWorldLocationToScreen(Loc, Screen, bIsRelative)) + DrawDynamicText(Str, Screen, Colour, Scale, Font); +} + +void ADReyeVRHUD::DrawDynamicText(const FString &Str, const FVector2D &Screen, const FColor &Colour, const float Scale, + const UFont *Font) +{ + HUDText DText{Str, Screen, Colour, Scale, const_cast(Font)}; + DynamicTextList.Add(std::move(DText)); +} + +void ADReyeVRHUD::DrawReticle(UTexture *U, const FVector2D &Screen) +{ + ReticleTexture.U = U; + ReticleTexture.Screen = Screen; +} + +void ADReyeVRHUD::DrawDynamicTexture(UTexture *U, const FVector2D &Screen) +{ + HUDTexture HTexture{U, Screen}; + DynamicTextures.Add(std::move(HTexture)); +} + +void ADReyeVRHUD::DrawStaticText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, + const float LifeTime, const bool bIsRelative, const UFont *Font) +{ + FVector2D Screen; + check(Player != nullptr); + if (Player->ProjectWorldLocationToScreen(Loc, Screen, bIsRelative)) + DrawStaticText(Str, Screen, Colour, Scale, LifeTime, Font); +} + +void ADReyeVRHUD::DrawStaticText(const FString &Str, const FVector2D &Screen, const FColor &Colour, const float Scale, + const float LifeTime, const UFont *Font) +{ + HUDText SText{Str, Screen, Colour, Scale, const_cast(Font)}; + float Now = FPlatformTime::Seconds(); + TimedText TText{SText, Now + LifeTime}; + StaticTextList.Add(std::move(TText)); +} + +void ADReyeVRHUD::DrawDynamicLine(const FVector &Start, const FVector &End, const FColor &Colour, const float Thickness) +{ + /// TODO: store player rather than re-get + check(Player != nullptr); + FVector2D StartScreen, EndScreen; + if (Player->ProjectWorldLocationToScreen(Start, StartScreen, true) && + Player->ProjectWorldLocationToScreen(End, EndScreen, true)) + DrawDynamicLine(StartScreen, EndScreen, Colour, Thickness); +} + +void ADReyeVRHUD::DrawDynamicLine(const FVector2D &Start, const FVector2D &End, const FColor &Colour, + const float Thickness) +{ + HUDLine DLine{Start, End, Colour, Thickness}; + DynamicLineList.Add(std::move(DLine)); +} + +void ADReyeVRHUD::DrawDynamicSquare(const FVector &Center, const float Size, const FColor &Colour, + const float Thickness) +{ + FVector2D CenterScreen; + if (Player->ProjectWorldLocationToScreen(Center, CenterScreen, true)) + DrawDynamicSquare(CenterScreen, Size, Colour, Thickness); +} + +void ADReyeVRHUD::DrawDynamicSquare(const FVector2D &Center, const float Size, const FColor &Colour, + const float Thickness) +{ + DrawDynamicRect(Center - FVector2D(Size / 2.0, Size / 2.0), // top left + Center + FVector2D(Size / 2.0, Size / 2.0), // bottom right + Colour, Thickness); +} + +void ADReyeVRHUD::DrawDynamicRect(const FVector2D &TopLeft, const FVector2D &BottomRight, const FColor &Colour, + const float Thickness) +{ + HUDRect Square{TopLeft, BottomRight, Colour, Thickness}; + DynamicRectList.Add(std::move(Square)); +} + +void ADReyeVRHUD::DrawDynamicCrosshair(const FVector &Center, const float Diameter, const FColor &Colour, + const bool InnerT, const float Thickness) +{ + FVector2D CenterScreen; + if (Player->ProjectWorldLocationToScreen(Center, CenterScreen, true)) + DrawDynamicCrosshair(CenterScreen, Diameter, Colour, InnerT, Thickness); +} + +void ADReyeVRHUD::DrawDynamicCrosshair(const FVector2D &Center, const float Diameter, const FColor &Colour, + const bool InnerT, const float Thickness) +{ + HUDCrosshair Crosshair{Center, Diameter, Colour, InnerT, Thickness}; + DynamicCrosshairList.Add(std::move(Crosshair)); } \ No newline at end of file diff --git a/DReyeVR/FlatHUD.h b/DReyeVR/FlatHUD.h index a74706d..22c45cc 100644 --- a/DReyeVR/FlatHUD.h +++ b/DReyeVR/FlatHUD.h @@ -1,113 +1,113 @@ -#pragma once - -#include "Carla/Game/CarlaHUD.h" // ACarlaHUD -#include "Containers/Array.h" // TArray -#include "Engine/Font.h" // UFont -#include "GameFramework/HUD.h" // AHUD - -#include "FlatHUD.generated.h" - -struct HUDText -{ - FString Text{""}; // Text content - FVector2D Screen; // 2D position on the screen - FColor Colour; // RGBA text colour - float Scale; // size of letters - UFont *TypeFace; // default font chosen if NULL -}; - -struct TimedText -{ - HUDText HT; - float TimeToDie; -}; - -struct HUDTexture -{ - UTexture *U; - FVector2D Screen; -}; - -struct HUDLine -{ - FVector2D Start; // start pt (2d) of line - FVector2D End; // end pt (2d) of line - FColor Colour; // RGBA line colour - float Thickness; // thickness (in px) of the line -}; - -struct HUDRect -{ - FVector2D TopLeft; - FVector2D BottomRight; - FColor Colour; - float Thickness; -}; - -struct HUDCrosshair -{ - FVector2D Center; - float Diameter; - FColor Colour; - bool InnerT; // whether or not to draw the inner "+" cross - float Thickness; -}; - -/// DReyeVR class to draw on HUD -UCLASS() class ADReyeVRHUD : public ACarlaHUD -{ - GENERATED_BODY() - - public: - ADReyeVRHUD(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) - { - LOG("Initializing DReyeVR HUD"); - } - - virtual void DrawHUD() override; - - void SetPlayer(APlayerController *P); - - // drawing text - void DrawDynamicText(const FString &Str, const FVector2D &Screen, const FColor &Colour, const float Scale, - const UFont *Font = nullptr); - void DrawDynamicText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, - const bool bIsRelative, const UFont *Font = nullptr); - - // drawing textures - void DrawReticle(UTexture *U, const FVector2D &Screen); - void DrawDynamicTexture(UTexture *U, const FVector2D &Screen); - - // static (lifetime based) text - void DrawStaticText(const FString &Str, const FVector2D &Loc, const FColor &Colour, const float Scale, - const float LifeTime, const UFont *Font = nullptr); - void DrawStaticText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, - const float LifeTime, const bool bIsRelative, const UFont *Font = nullptr); - - // drawing lines - void DrawDynamicLine(const FVector &Start, const FVector &End, const FColor &Colour, const float Thickness); - void DrawDynamicLine(const FVector2D &Start, const FVector2D &End, const FColor &Colour, const float Thickness); - - // drawing squares/rectangles - void DrawDynamicSquare(const FVector &Center, const float Size, const FColor &Colour, const float Thickness = 0); - void DrawDynamicSquare(const FVector2D &Center, const float Size, const FColor &Colour, const float Thickness = 0); - void DrawDynamicRect(const FVector2D &TopLeft, const FVector2D &BottomRight, const FColor &Colour, - const float Thickness = 0); // 0 thickness is default - - // drawing crosshair for reticule - void DrawDynamicCrosshair(const FVector &Center, const float Diameter, const FColor &Colour, const bool InnerT, - const float Thickness = 0); - void DrawDynamicCrosshair(const FVector2D &Center, const float Diameter, const FColor &Colour, const bool InnerT, - const float Thickness = 0); - - private: - /// TODO: figure out a better way than this to dynamically render - HUDTexture ReticleTexture; - TArray DynamicTextList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicText - TArray DynamicTextures; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicTextures - TArray DynamicLineList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicLine - TArray DynamicRectList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicRect - TArray DynamicCrosshairList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicRect - TArray StaticTextList; // get added and remain until lifetime ends - APlayerController *Player = nullptr; // PlayerComponent in world -}; +#pragma once + +#include "Carla/Game/CarlaHUD.h" // ACarlaHUD +#include "Containers/Array.h" // TArray +#include "Engine/Font.h" // UFont +#include "GameFramework/HUD.h" // AHUD + +#include "FlatHUD.generated.h" + +struct HUDText +{ + FString Text{""}; // Text content + FVector2D Screen; // 2D position on the screen + FColor Colour; // RGBA text colour + float Scale; // size of letters + UFont *TypeFace; // default font chosen if NULL +}; + +struct TimedText +{ + HUDText HT; + float TimeToDie; +}; + +struct HUDTexture +{ + UTexture *U; + FVector2D Screen; +}; + +struct HUDLine +{ + FVector2D Start; // start pt (2d) of line + FVector2D End; // end pt (2d) of line + FColor Colour; // RGBA line colour + float Thickness; // thickness (in px) of the line +}; + +struct HUDRect +{ + FVector2D TopLeft; + FVector2D BottomRight; + FColor Colour; + float Thickness; +}; + +struct HUDCrosshair +{ + FVector2D Center; + float Diameter; + FColor Colour; + bool InnerT; // whether or not to draw the inner "+" cross + float Thickness; +}; + +/// DReyeVR class to draw on HUD +UCLASS() class ADReyeVRHUD : public ACarlaHUD +{ + GENERATED_BODY() + + public: + ADReyeVRHUD(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) + { + LOG("Initializing DReyeVR HUD"); + } + + virtual void DrawHUD() override; + + void SetPlayer(APlayerController *P); + + // drawing text + void DrawDynamicText(const FString &Str, const FVector2D &Screen, const FColor &Colour, const float Scale, + const UFont *Font = nullptr); + void DrawDynamicText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, + const bool bIsRelative, const UFont *Font = nullptr); + + // drawing textures + void DrawReticle(UTexture *U, const FVector2D &Screen); + void DrawDynamicTexture(UTexture *U, const FVector2D &Screen); + + // static (lifetime based) text + void DrawStaticText(const FString &Str, const FVector2D &Loc, const FColor &Colour, const float Scale, + const float LifeTime, const UFont *Font = nullptr); + void DrawStaticText(const FString &Str, const FVector &Loc, const FColor &Colour, const float Scale, + const float LifeTime, const bool bIsRelative, const UFont *Font = nullptr); + + // drawing lines + void DrawDynamicLine(const FVector &Start, const FVector &End, const FColor &Colour, const float Thickness); + void DrawDynamicLine(const FVector2D &Start, const FVector2D &End, const FColor &Colour, const float Thickness); + + // drawing squares/rectangles + void DrawDynamicSquare(const FVector &Center, const float Size, const FColor &Colour, const float Thickness = 0); + void DrawDynamicSquare(const FVector2D &Center, const float Size, const FColor &Colour, const float Thickness = 0); + void DrawDynamicRect(const FVector2D &TopLeft, const FVector2D &BottomRight, const FColor &Colour, + const float Thickness = 0); // 0 thickness is default + + // drawing crosshair for reticule + void DrawDynamicCrosshair(const FVector &Center, const float Diameter, const FColor &Colour, const bool InnerT, + const float Thickness = 0); + void DrawDynamicCrosshair(const FVector2D &Center, const float Diameter, const FColor &Colour, const bool InnerT, + const float Thickness = 0); + + private: + /// TODO: figure out a better way than this to dynamically render + HUDTexture ReticleTexture; + TArray DynamicTextList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicText + TArray DynamicTextures; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicTextures + TArray DynamicLineList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicLine + TArray DynamicRectList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicRect + TArray DynamicCrosshairList; // get drawn once (on DrawHUD) then removed (replaced) by DrawDynamicRect + TArray StaticTextList; // get added and remain until lifetime ends + APlayerController *Player = nullptr; // PlayerComponent in world +}; diff --git a/Docs/Development.md b/Docs/Development.md index 7b4affc..d5db408 100644 --- a/Docs/Development.md +++ b/Docs/Development.md @@ -1,389 +1,389 @@ -# `DReyeVR` Development - -For users who want a deeper dive into the inner workings of DReyeVR and how they can get started with development and writing code, look no further! - -(This guide assumes you've read the [`Usage.md`](../Usage.md) documentation and have `DReyeVR` installed) - -# Getting started -We recommend a development setup where your changes to DReyeVR can be quickly identified compared to our upstream changes. To do this we provide a fork of CARLA with DReyeVR pre-installed (and committed) so you should have a clean starting repository to work with: -```bash -# clone our fork and replace your vanilla CARLA repository - -git clone https://github.com/harplab/carla -b DReyeVR-0.9.13 --depth 1 -cd carla -./Update.sh # on Linux/Mac -Update.bat # on Windows - -cd ../DReyeVR/ # assumed DReyeVR repo is adjacent to carla repo - -# (in DReyeVR repo) -make install CARLA=../carla # install things not tracked by git such as blueprint/binary files - -cd ../carla # switch back to carla dir -git status -# now, git should show changes relative to our upstream DReyeVR branch rather than CARLA 0.9.13 -``` - -## Reverse install - -Once you have made some changes in the Carla codebase that relate to DReyeVR, it is tedious to manually copy all these changes back into the DReyeVR repo (if you wanted to upstream them). As part of our [`make`](../Scripts/README.md) system, we provide a "reverse install" (`r-install`) procedure to mirror the `install` function and copy all the corresponding files that were installed by DReyeVR (from `make install`) back into DReyeVR: - -
- - Click to open example make output - -```bash -make r-install CARLA=../carla # equivalent to "make rev" -make rev CARLA=../carla # alias for r-install - -Proceeding on /PATH/TO/CARLA (git branch) -/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/ -- found -/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/EgoVehicle.h -- found -/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/EgoVehicle.h -> /Users/gustavo/carla/DReyeVR-Dev/DReyeVR/EgoVehicle.h -/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/FlatHUD.cpp -- found -/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/FlatHUD.cpp -> /Users/gustavo/carla/DReyeVR-Dev/DReyeVR/FlatHUD.cpp -...etc. -... -Done Reverse Install! -``` -
-
- -Note that the files that are copied back into DReyeVR follow those defined by the DReyeVR <--> Carla file correspondence defined in [`Paths/*.csv`](../Scripts/Paths/), so if you have modified a completely new file (not tracked by DReyeVR) you'll need to manually add that file to the DReyeVR repo and update the correspondences file (.csv). - -## Typical workflow - -The workflow we have designed for our development process on DReyeVR includes using our fork of carla (`DReyeVR-0.9.13` branch) alongside a cloned `DReyeVR` repo that we can use to both push and pull from upstream. - -
- -Click to open terminal example - -```bash -> ls -carla.harp/ # our HarpLab fork for primary development -DReyeVR # our DReyeVR installation - -cd carla.harp -... # make some changes in carla.harp -make launch && make package # ensure carla still works with these changes - -cd ../DReyeVR -make rev CARLA=../carla.harp # "reverse-install" changes from carla.harp to DReyeVR -git stuff # do all sorts of upstreaming and whatnot. - ------------------ # if changes have been made upstream for you to install -cd DReyeVR/ -git pull # upstream changes -make clean CARLA=../carla.harp # optional to reset carla.harp to a clean git state -make install CARLA=../carla.harp # install new DReyeVR changes over it -cd ../carla.harp && make launch && make package && etc. - -# optionally, you can keep a carla.vanilla around to test that a fresh install of your updated DReyeVR repo works on carla -make install CARLA=../carla.vanilla -``` - -
-
- -![Directories](Figures/Dev/Directories.jpg) - -# Understanding the Carla + DReyeVR codebase whereabouts -These are the main places you'll want to look at when developing atop Carla: - -1. `Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/` - - This contains all our custom DReyeVR C++ code which typically builds off existing Carla code. -2. `Unreal/CarlaUE4/Plugins/Carla/Source/Carla/` - - This is where the main UE4 C++ Carla logic is defined for everything from Sensors to Vehicles to the Recorder/Replayer to the Weather. - - We have some code here, such as for custom sensors and small feature patches. -3. `LibCarla/source/carla/` - - This is where nearly all the `Python` interfacing Carla C++ code is housed. Much of this is reimplementation of the `CarlaUE4/Plugins` code, but without the Unreal C++ API and with a great emphasis on streaming logic to the PythonAPI - - We have a small amount of code here to ensure our sensor data gets properly transmitted to Python -4. `PythonAPI/examples/` - - Here you can find most of the important Python scripts that interact with Carla. - - We have a few files here to improve the experience with DReyeVR and Carla's PythonAPI - -# Inner workings -This section will discuss the inner workings of DReyeVR including design paradigms and corresponding handshakes with Carla. -## EgoVehicle -- Relevant files: [EgoVehicle.h](../DReyeVR/EgoVehicle.h), [EgoVehicle.cpp](../DReyeVR/EgoVehicle.cpp), [EgoInputs.cpp](../DReyeVR/EgoInputs.cpp), [Content/DReyeVR/EgoVehicle/BP_*.uasset](../Content/DReyeVR/EgoVehicle/) - -The EgoVehicle is the main vessel as our "hero vehicle". Following our goal to improve human driver immersion in Carla, the EgoVehicle contains many human-centric features that normal Carla vehicles do not carry. For example, the EgoVehicle defines the logic for the internal mirrors, dynamic steering wheel, dashboard, human inputs, audio, etc. These are all things that an AI-powered vehicle would not care about, so Carla omits them from all their other Vehicles. - -Still, the EgoVehicle is just a wrapper (child of) over a standard [`ACarlaWheeledVehicle`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h), so it automatically inherits all the Carla vehicle operations and is compatible with all CarlaVehicle features. Notably, the EgoVehicle is not possessed by the player, but by the default [`AWheeledVehicleAIController`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.h). This is to enable simultaneous input from the player and from the built-in Carla autopilot. We'll discuss this more in `DReyeVRPawn` below. - -Importantly, we base all our ticking synchronization logic off of the EgoVehicle, whose `Tick` method calls the `Tick` method for many other key components in DReyeVR. This ensures we have a deterministic and consistent sequence of updates in the simulator and can rely on this ordering in the future. - -Here we also manually manage the replay behavior for the EgoVehicle, who follows the values captured from the EgoSensor rather than the Carla default behavior, this is so we can more closely reenact the exact data that we collected from the EgoSensor such as eye gaze, camera orientation, vehicle inputs & pose, etc. - -We also define the logic for spawning and managing the three mirrors in the vehicle, since these are not included by default in the blueprint mesh. It is a good idea to separate these since mirrors in UE4 implemented with planar reflections are a huge performance killer and should be used sparingly. We also can define per-mirror quality settings to dynamically adjust their resolution and corresponding performance impact. - -The EgoVehicle contains pointers to nearly all other major DReyeVR objects so they can communicate seamlessly. These pointers are set up on construction and persist for the lifetime of these objects. Importantly, the EgoVehicle spawns and attaches the EgoSensor, so they are intrinsically linked and one cannot exist without the other. - -Additionally, all the input logic for the EgoVehicle is held in the `EgoInputs.cpp` source file, it is purely to separate this logic from the rest of the EgoVehicle source. - -Finally, how we spawn our EgoVehicle in the Carla world is by creating a copy of an existing Carla vehicle blueprint and [reparenting](https://forums.unrealengine.com/t/how-to-change-parent-class-of-blueprint-asset/281843) the base class to our EgoVehicle in the blueprint. This can be found in our `Content` folder for `EgoVehicle`. All the corresponding blueprints are organized here. - -## EgoSensor - -- Relevant files: [EgoSensor.h](../DReyeVR/EgoSensor.h), [EgoSensor.cpp](../DReyeVR/EgoSensor.cpp), [DReyeVRSensor.h|cpp](../Carla/Sensor/DReyeVRSensor.h), [DReyeVRData.h|cpp](../Carla/Sensor/DReyeVRData.h) - -The EgoSensor is our virtual Carla sensor to track all kinds of human-centric data we might be interested in. It can be thought of as an **invisible data collector that operates in the Carla world**. Unlike most other Carla sensors which have some physical description and mounting to an actor, the EgoSensor is spawned and destroyed automatically with the EgoVehicle and bound to the EgoVehicle instance for its entire lifetime. - -The EgoSensor a child of a `DReyeVRSensor` which is a child of a generic `CarlaSensor` that comes from following Carla's ["add a sensor tutorial"](https://carla.readthedocs.io/en/latest/tuto_D_create_sensor/). The `DReyeVRSensor` parent class is located in the `CarlaUE4/Plugin/Source` region of the codebase as it follows a proper Carla implementation, importantly, this class is `virtual` (abstract) meaning it is supposed to be inherited by another class that provides implementation (enter `EgoSensor`). - -Since DReyeVR introduces several dependencies that Carla has nothing to do with (such as SRanipal for eye tracking and LogitechWheelPlugin for steering wheel hardware), we implement their interface with our Code in `EgoSensor` rather than within the `CarlaUE4/Plugin/Source` region (which is supposed to be just for Carla). The EgoSensor then implements the methods needed to get the data from SRanipal and Logitech and format it nicely into a `DReyeVRData` package for this simulator timestep - -The `DReyeVRData` class is a collection of structures defined in `CarlaUE4/Plugin/Source/Carla/DReyeVRData.h` which defines individual structures for data types that are being tracked by DReyeVR. For instance, we have structures for the eye gaze data, vehicle inputs, other ego-vehicle variables, and more. This is designed this way to encourage future data types to follow a similar struct design and interface with DReyeVR, so everything can be collected together into the `AggregateData` and then sent as a complete package to the PythonAPI for streaming or to the recorder for serialization. - -The EgoSensor also implements other nice features such as screen capture for the Camera and variable rate shading with foveated rendering if enabled. - -### Inheritance map: -To clarify the structure of the inheritance at play here (Older generation to youngest): -1. [`AActor`](https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/GameFramework/AActor/) (UE4): Low-level unreal class for any object that can be spawned into the world -2. [`ASensor`](https://github.com/carla-simulator/carla/blob/0.9.13/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h) (Carla): Carla actor that templates the structure for Sensors acting in the Carla world -3. [`ADReyeVRSensor`](../Carla/Sensor/DReyeVRSensor.h) (DReyeVR): Our sensor instance that contains logic for all Carla related tasks - - Streaming to the PythonAPI - - Receiving data from replayer to reenact - - Contains instance of `DReyeVR::AggregateData` containing ALL the data -4. [`AEgoSensor`](../DReyeVR/EgoSensor.h) (DReyeVR): Our primary actor containing all DReyeVR related logic for custom data variables/functions - - Eye tracking logic (SRanipal), ego vehicle tracking, etc. - -## DReyeVRPawn - -- Relevant files: [DreyeVRPawn.h](../DReyeVR/DReyeVRPawn.h), [DreyeVRPawn.cpp](../DReyeVR/DReyeVRPawn.cpp) - -Getting back to our discussion on the EgoVehicle simultaneous input with player & AI, the DReyeVRPawn is the actual entity that the *human player* possesses during the duration of the level. Unlike EgoVehicle/EgoSensor, the DReyeVRPawn is not tied to any particular object and can be thought of as **an invisible floating camera that defines the viewport of the player**. - -The DReyeVRPawn therefore manages the in-game [`UCameraComponent`](https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Camera/UCameraComponent/) as well as visual and input logic that the player needs. The [SteamVR](https://docs.unrealengine.com/4.27/en-US/SharingAndReleasing/XRDevelopment/VR/VRPlatforms/SteamVR/QuickStart/) integration is managed here, as well as the LogiWheel controls scheme mapping, since this is the object that the player possesses and thus gets first input priority to. We also add some visual eye-candy logic such as a visualization indicator for the eye gaze as a reticle that is drawn on the [SpectatorScreen](https://docs.unrealengine.com/4.26/en-US/SharingAndReleasing/XRDevelopment/VR/DevelopVR/VRSpectatorScreen/) (not visible to the VR player) or flat-screen HUD. - -The EgoVehicle *AI and player* dual-input logic comes from the implementation that the DReyeVRPawn simply forwards commands to the EgoVehicle without directly possessing it, so the Carla AI can still possess and control the EgoVehicle. This enables simultaneous "possession" by the player and the Carla AI controller, since all human player inputs still reach the EgoVehicle and take precedence over the AI. - -## DReyeVRGameMode - -- Relevant files: [DReyeVRGameMode.h](../DReyeVR/DReyeVRGameMode.h), [DReyeVRGameMode.cpp](../DReyeVR/DReyeVRGameMode.cpp) - -A [`GameMode`](https://docs.unrealengine.com/4.27/en-US/InteractiveExperiences/HowTo/SettingUpAGameMode/) in UE4 is used to define game logic across levels, and this can be easily done in code (unlike [`LevelScripts`](https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/ALevelScriptActor/), which are tied to individual level blueprints). - -The gamemode class is useful because **we can rely on it to always persist throughout any level instance**, so we can define logic beyond the lifetime of a single EgoVehicle/EgoSensor and operate on a more global level. - -For instance, we have code to change the volume of the in-world sound effects, spawn the EgoVehicle in a particular location, transfer control to the default floating spectator (detatch from the EgoVehicle), and manage media controls for playback of a recording (play/pause/step/rewind/etc.). - -The most important thing that the DReyeVR gamemode does is spawn the DReyeVRPawn, so the human player can possess some actor and interact with the world at all. - -## DReyeVRFactory - - - Relevant files: [DReyeVRFactory.h](../DReyeVR/DReyeVRFactory.h), [DReyeVRFactory.cpp](../DReyeVR/DReyeVRFactory.cpp) - -Carla uses Factories to spawn all their relevent actors (See [`CarlaActorFactory`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactory.h), [`CarlaActorFactoryBlueprint`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactoryBlueprint.h), [`SensorFactory`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.h), etc.) which spawn everything from vehicles to pedestrians to sensors and props. This design allows Carla to handle all the dirty work of registering the actors with LibCarla so that LibCarla knows about each actor and they can be interacted with in Python. - -We follow suit with a similar design in our `DReyeVRFactory` which defines the important characteristics for our DReyeVR actors and provides the logic necessary to spawn them. For instance, here we define our actors are labeled uniquely such as `"harplab.dreyevr_vehicle.model3"` to avoid conflict with existing Carla `"vehicle.*"` queries. - -This is class you'll want to modify if you're looking to create new DReyeVR actors (such as new vehicle models), walkers, sensors, etc. - ---- - -# Adding custom data to the ego-sensor -While we provide a fairly comprehensive suite of data in our DReyeVRSensor, you may be interested in also tracking other data that we don't currently enable. - -The first file you'll want to look at is `Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/`[`DReyeVRData.h`](../Carla/Sensor/DReyeVRData.h) which contains the data structures that compose the contents of the ego sensor. Here you'll define the variable and its serialization methods (read/write/print). - -```c++ -/// DReyeVRData.h -class AggregateData // all DReyeVR sensor data is held here -{ -public: - ... // existing code - float GetNewVariable() const; - ////////////////////:SETTERS:////////////////////// - - ... - void SetNewVariable(const float NewVariableIn); - - ////////////////////:SERIALIZATION:////////////////////// - void Read(std::ifstream &InFile); - - void Write(std::ofstream &OutFile) const; - - FString ToString() const; // this printing is used when showing recorder info - -private: -... // existing code -float NewVariable; // <-- Your new variable -}; -``` - -Then, you'll want to write the implementation in `Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/`[`DReyeVRData.cpp`](../Carla/Sensor/DReyeVRData.cpp) as inline funcitons. -```c++ -/// DReyeVRData.cpp -... -float AggregateData::GetNewVariable() const -{ - return NewVariable; -} - -... -void AggregateData::SetNewVariable(const float NewVariableIn) -{ -NewVariable = NewVariableIn; -} - -void AggregateData::Read(std::ifstream &InFile) -{ - /// CAUTION: make sure the order of writes/reads is the same - ... // existing code - ReadValue(InFile, NewVariable); -} - -void AggregateData::Write(std::ofstream &OutFile) const -{ - /// CAUTION: make sure the order of writes/reads is the same - ... // existing code - WriteValue(OutFile, GetNewVariable()); -} - -FString AggregateData::ToString() const // this printing is used when showing recorder info -{ - FString print; - ... // existing code - print += FString::Printf(TEXT("[DReyeVR]NewVariable:%.3f,\n"), GetNewVariable()); - return print; -} -... -``` -Notes: -- It is nice to contain collections of relevant variables together in structures so they can be better organized. To facilitate this we designed our DReyeVRData to contain various `DReyeVR::DataSerializer` objects, which each implement their own serialization methods. Our `AggregateData` instance contains all our structs and a lightweight API to access member variables. -- The above is an example of modifying/adding a new variable directly to a `DReyeVR::AggregateData`. But it would be better to either modify an existing `DReyeVR::DReyeVRSerializer` object or create a new one (inheriting from the virtual class) and define all the abstract methods yourself. This enables a more granular sub-class/struct abstraction like most of our variables. - -With this step complete, you are free to read/write to this variable by getting the single global (`static`) instance of the `DReyeVR::AggregateData` class using the `GetData()` function of the EgoSensor as follows: -```c++ -// In some other file, for example EgoVehicle.cpp: -float NewVariable = EgoSensor->GetData()->GetNewVariable(); -... // your code -EgoSensor->GetData()->SetNewVariable(NewVariable + 5.f); // update the new variable -``` - -## [OPTIONAL] Streaming data to a PythonAPI client: -In order to see the new data from a PythonAPI client, you'll need to duplicate the code to the LibCarla serializer. This requires looking at `LibCarla/Sensor/s11n/`[`DReyeVRSerializer.h`](../LibCarla/Sensor/s11n/DReyeVRSerializer.h) and following the same template as all the other variables: -```c++ -class DReyeVRSerializer -{ - public: - struct Data - { - ... // existing code - float NewVariable; - - MSGPACK_DEFINE_ARRAY( - ... // existing code - NewVariable, // <-- New variable - ) - }; -}; -///NOTE: you'll also need to interface with this updated struct: -``` -Then, to actually interface with the DReyeVR sensor, you'll need to modify the call to the LibCarla stream to include your `NewVariable`. -```c++ -// in Carla/Sensor/DReyeVRSensor.cpp -void ADReyeVRSensor::PostPhysTick(UWorld *W, ELevelTick TickType, float DeltaSeconds) -{ - ... // existing code - Stream.Send(*this, - carla::sensor::s11n::DReyeVRSerializer::Data{ - ... // existing code - Data->GetNewVariable(), // <-- New variable - }); -} -``` -And finally, to actually get the data from a PythonAPI call, you'll need to modify the list of available attributes to the DReyeVR sensor object as follows: -```c++ -// in LibCarla/source/carla/sensor/data/DReyeVREvent.h -class DReyeVREvent : public SensorData -{ - ... - - public: - ... // existing code - float GetNewVariable() const // <-- new code - { - return InternalData.NewVariable; - } - - private: - carla::sensor::s11n::DReyeVRSerializer::Data InternalData; -}; -``` -Then finally here you'll define what function to call (the variable getter) to get that data from a PythonAPI client. -```c++ -// in PythonAPI/carla/source/libcarla/SensorData.cpp -class_, boost::noncopyable, boost::shared_ptr>("DReyeVREvent", no_init) - ... // existing code - .add_property("new_variable", CALL_RETURNING_COPY(csd::DReyeVREvent, GetNewVariable)) - .def(self_ns::str(self_ns::self)) -; -``` -After you modify files in `PythonAPI` or `LibCarla` the PythonAPI will need to be rebuilt in order for your changes to take effect: -```bash -conda activate carla13 # if using conda -(carla13) make PythonAPI -# make sure to fix any build errors that may occur! -``` - -# TODO: add more dev notes - -# Tips & Tricks -## 1. Enable logging in shipping mode -It is super useful to see the CarlaUE4.log file in shipping mode and this is not the default in Carla (or Unreal) perhaps for performance reasons? - -If you want to enable these features then you'll need to add the flag for `bUseLoggingInShipping` in the `Carla/Unreal/CarlaUE4/Source/CarlaUE4.Target.cs` file. - -```cs -public class CarlaUE4Target : TargetRules -{ - public CarlaUE4Target(TargetInfo Target) : base(Target) - { - Type = TargetType.Game; - ExtraModuleNames.Add("CarlaUE4"); - bUseLoggingInShipping = true;// <--- added here - } -} -``` - -Then you should be able to find the CarlaUE4.log files (timestamped to avoid overwrite) at `C:\Users\%YOUR_USER_NAME%\AppData\Local\CarlaUE4\Saved\Logs\CarlaUE4.log` (on Windows). Also works for Mac/Linux. See [this](https://forums.unrealengine.com/t/how-to-debug-shipping-build-exclusive-crash/411138) for more information. - ---- - -## 2. How to `LOG` -Logging is useful to track code logic and debug (especially since debugging UE4 code can be a bit rough). By default in Unreal C++ you can always use `UE_LOG(LogTemp, Log, TEXT("some text and %d here"), 55);` but we streamlined this for DReyeVR specific logging. You can use our `LOG` macros (defined in [`CarlaUE4.h`](../CarlaUE4/CarlaUE4.h)) when you are editing `CarlaUE4/DReyeVR/*.[cpp|h]` files. - -The main benefits include: -- Less boilerplate code for the programmer (thats you!) -- All logs have the prefix `DReyeVRLog` so they are easy to filter in the overall `CarlaUE4.log` file -- We also attached neat compile-time prefixes to include `"[{INVOKED_FILE}::{INVOKED_FUNCTION}:{LINE_NUMBER}] {message}"` so you can quickly find where this log was invoked from and differentiate from others - - A typical DReyeVR log using our macros looks like this: - ``` - LogDReyeVR: [DReyeVRUtils.h::ReadConfigValue:141] "your message here" - ``` - -```c++ -... // in CarlaUE4/DReyeVR files -void example() { - LOG("some text and %d (this text is grey)", 55); - FString warning_str("warning"); - LOG_WARN("some %s here (this text is yellow!)", *warning_str); - LOG_ERROR("this text is red!"); -} -... -``` - -If you are working instead in the `CarlaUE4/Plugins/Source/Carla` codebase then you'll be able to use similar macros but prefixed with `DReyeVR_`: `DReyeVR_LOG("blah blah")`, `DReyeVR_LOG_WARN("blah blah warning")`, etc. - ---- - -## 3. Managing multiple Carla/DReyeVR versions -- Having separate `python` environments (such as `conda`) is extremely useful to have different `carla` Python packages on the same machine with different versions (such as `LibCarla`). To do this, you can simply create an individual conda environment for each Carla version as described in [`Install.md`](Install.md). Remember to activate your new `conda` environment on a per-shell basis! -- If you plan on having multiple CARLA's installed, you'll need to keep them updated with the appropriate `Content`. Rather than calling the `Update` script every time to update this, you can save the `Content.tar.gz` file and copy it into new `Unreal/CarlaUE4/Content/Carla` directories whenever you have a new repo. - ---- - +# `DReyeVR` Development + +For users who want a deeper dive into the inner workings of DReyeVR and how they can get started with development and writing code, look no further! + +(This guide assumes you've read the [`Usage.md`](../Usage.md) documentation and have `DReyeVR` installed) + +# Getting started +We recommend a development setup where your changes to DReyeVR can be quickly identified compared to our upstream changes. To do this we provide a fork of CARLA with DReyeVR pre-installed (and committed) so you should have a clean starting repository to work with: +```bash +# clone our fork and replace your vanilla CARLA repository + +git clone https://github.com/harplab/carla -b DReyeVR-0.9.13 --depth 1 +cd carla +./Update.sh # on Linux/Mac +Update.bat # on Windows + +cd ../DReyeVR/ # assumed DReyeVR repo is adjacent to carla repo + +# (in DReyeVR repo) +make install CARLA=../carla # install things not tracked by git such as blueprint/binary files + +cd ../carla # switch back to carla dir +git status +# now, git should show changes relative to our upstream DReyeVR branch rather than CARLA 0.9.13 +``` + +## Reverse install + +Once you have made some changes in the Carla codebase that relate to DReyeVR, it is tedious to manually copy all these changes back into the DReyeVR repo (if you wanted to upstream them). As part of our [`make`](../Scripts/README.md) system, we provide a "reverse install" (`r-install`) procedure to mirror the `install` function and copy all the corresponding files that were installed by DReyeVR (from `make install`) back into DReyeVR: + +
+ + Click to open example make output + +```bash +make r-install CARLA=../carla # equivalent to "make rev" +make rev CARLA=../carla # alias for r-install + +Proceeding on /PATH/TO/CARLA (git branch) +/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/ -- found +/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/EgoVehicle.h -- found +/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/EgoVehicle.h -> /Users/gustavo/carla/DReyeVR-Dev/DReyeVR/EgoVehicle.h +/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/FlatHUD.cpp -- found +/PATH/TO/CARLA/Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/FlatHUD.cpp -> /Users/gustavo/carla/DReyeVR-Dev/DReyeVR/FlatHUD.cpp +...etc. +... +Done Reverse Install! +``` +
+
+ +Note that the files that are copied back into DReyeVR follow those defined by the DReyeVR <--> Carla file correspondence defined in [`Paths/*.csv`](../Scripts/Paths/), so if you have modified a completely new file (not tracked by DReyeVR) you'll need to manually add that file to the DReyeVR repo and update the correspondences file (.csv). + +## Typical workflow + +The workflow we have designed for our development process on DReyeVR includes using our fork of carla (`DReyeVR-0.9.13` branch) alongside a cloned `DReyeVR` repo that we can use to both push and pull from upstream. + +
+ +Click to open terminal example + +```bash +> ls +carla.harp/ # our HarpLab fork for primary development +DReyeVR # our DReyeVR installation + +cd carla.harp +... # make some changes in carla.harp +make launch && make package # ensure carla still works with these changes + +cd ../DReyeVR +make rev CARLA=../carla.harp # "reverse-install" changes from carla.harp to DReyeVR +git stuff # do all sorts of upstreaming and whatnot. + +----------------- # if changes have been made upstream for you to install +cd DReyeVR/ +git pull # upstream changes +make clean CARLA=../carla.harp # optional to reset carla.harp to a clean git state +make install CARLA=../carla.harp # install new DReyeVR changes over it +cd ../carla.harp && make launch && make package && etc. + +# optionally, you can keep a carla.vanilla around to test that a fresh install of your updated DReyeVR repo works on carla +make install CARLA=../carla.vanilla +``` + +
+
+ +![Directories](Figures/Dev/Directories.jpg) + +# Understanding the Carla + DReyeVR codebase whereabouts +These are the main places you'll want to look at when developing atop Carla: + +1. `Unreal/CarlaUE4/Source/CarlaUE4/DReyeVR/` + - This contains all our custom DReyeVR C++ code which typically builds off existing Carla code. +2. `Unreal/CarlaUE4/Plugins/Carla/Source/Carla/` + - This is where the main UE4 C++ Carla logic is defined for everything from Sensors to Vehicles to the Recorder/Replayer to the Weather. + - We have some code here, such as for custom sensors and small feature patches. +3. `LibCarla/source/carla/` + - This is where nearly all the `Python` interfacing Carla C++ code is housed. Much of this is reimplementation of the `CarlaUE4/Plugins` code, but without the Unreal C++ API and with a great emphasis on streaming logic to the PythonAPI + - We have a small amount of code here to ensure our sensor data gets properly transmitted to Python +4. `PythonAPI/examples/` + - Here you can find most of the important Python scripts that interact with Carla. + - We have a few files here to improve the experience with DReyeVR and Carla's PythonAPI + +# Inner workings +This section will discuss the inner workings of DReyeVR including design paradigms and corresponding handshakes with Carla. +## EgoVehicle +- Relevant files: [EgoVehicle.h](../DReyeVR/EgoVehicle.h), [EgoVehicle.cpp](../DReyeVR/EgoVehicle.cpp), [EgoInputs.cpp](../DReyeVR/EgoInputs.cpp), [Content/DReyeVR/EgoVehicle/BP_*.uasset](../Content/DReyeVR/EgoVehicle/) + +The EgoVehicle is the main vessel as our "hero vehicle". Following our goal to improve human driver immersion in Carla, the EgoVehicle contains many human-centric features that normal Carla vehicles do not carry. For example, the EgoVehicle defines the logic for the internal mirrors, dynamic steering wheel, dashboard, human inputs, audio, etc. These are all things that an AI-powered vehicle would not care about, so Carla omits them from all their other Vehicles. + +Still, the EgoVehicle is just a wrapper (child of) over a standard [`ACarlaWheeledVehicle`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h), so it automatically inherits all the Carla vehicle operations and is compatible with all CarlaVehicle features. Notably, the EgoVehicle is not possessed by the player, but by the default [`AWheeledVehicleAIController`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.h). This is to enable simultaneous input from the player and from the built-in Carla autopilot. We'll discuss this more in `DReyeVRPawn` below. + +Importantly, we base all our ticking synchronization logic off of the EgoVehicle, whose `Tick` method calls the `Tick` method for many other key components in DReyeVR. This ensures we have a deterministic and consistent sequence of updates in the simulator and can rely on this ordering in the future. + +Here we also manually manage the replay behavior for the EgoVehicle, who follows the values captured from the EgoSensor rather than the Carla default behavior, this is so we can more closely reenact the exact data that we collected from the EgoSensor such as eye gaze, camera orientation, vehicle inputs & pose, etc. + +We also define the logic for spawning and managing the three mirrors in the vehicle, since these are not included by default in the blueprint mesh. It is a good idea to separate these since mirrors in UE4 implemented with planar reflections are a huge performance killer and should be used sparingly. We also can define per-mirror quality settings to dynamically adjust their resolution and corresponding performance impact. + +The EgoVehicle contains pointers to nearly all other major DReyeVR objects so they can communicate seamlessly. These pointers are set up on construction and persist for the lifetime of these objects. Importantly, the EgoVehicle spawns and attaches the EgoSensor, so they are intrinsically linked and one cannot exist without the other. + +Additionally, all the input logic for the EgoVehicle is held in the `EgoInputs.cpp` source file, it is purely to separate this logic from the rest of the EgoVehicle source. + +Finally, how we spawn our EgoVehicle in the Carla world is by creating a copy of an existing Carla vehicle blueprint and [reparenting](https://forums.unrealengine.com/t/how-to-change-parent-class-of-blueprint-asset/281843) the base class to our EgoVehicle in the blueprint. This can be found in our `Content` folder for `EgoVehicle`. All the corresponding blueprints are organized here. + +## EgoSensor + +- Relevant files: [EgoSensor.h](../DReyeVR/EgoSensor.h), [EgoSensor.cpp](../DReyeVR/EgoSensor.cpp), [DReyeVRSensor.h|cpp](../Carla/Sensor/DReyeVRSensor.h), [DReyeVRData.h|cpp](../Carla/Sensor/DReyeVRData.h) + +The EgoSensor is our virtual Carla sensor to track all kinds of human-centric data we might be interested in. It can be thought of as an **invisible data collector that operates in the Carla world**. Unlike most other Carla sensors which have some physical description and mounting to an actor, the EgoSensor is spawned and destroyed automatically with the EgoVehicle and bound to the EgoVehicle instance for its entire lifetime. + +The EgoSensor a child of a `DReyeVRSensor` which is a child of a generic `CarlaSensor` that comes from following Carla's ["add a sensor tutorial"](https://carla.readthedocs.io/en/latest/tuto_D_create_sensor/). The `DReyeVRSensor` parent class is located in the `CarlaUE4/Plugin/Source` region of the codebase as it follows a proper Carla implementation, importantly, this class is `virtual` (abstract) meaning it is supposed to be inherited by another class that provides implementation (enter `EgoSensor`). + +Since DReyeVR introduces several dependencies that Carla has nothing to do with (such as SRanipal for eye tracking and LogitechWheelPlugin for steering wheel hardware), we implement their interface with our Code in `EgoSensor` rather than within the `CarlaUE4/Plugin/Source` region (which is supposed to be just for Carla). The EgoSensor then implements the methods needed to get the data from SRanipal and Logitech and format it nicely into a `DReyeVRData` package for this simulator timestep + +The `DReyeVRData` class is a collection of structures defined in `CarlaUE4/Plugin/Source/Carla/DReyeVRData.h` which defines individual structures for data types that are being tracked by DReyeVR. For instance, we have structures for the eye gaze data, vehicle inputs, other ego-vehicle variables, and more. This is designed this way to encourage future data types to follow a similar struct design and interface with DReyeVR, so everything can be collected together into the `AggregateData` and then sent as a complete package to the PythonAPI for streaming or to the recorder for serialization. + +The EgoSensor also implements other nice features such as screen capture for the Camera and variable rate shading with foveated rendering if enabled. + +### Inheritance map: +To clarify the structure of the inheritance at play here (Older generation to youngest): +1. [`AActor`](https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/GameFramework/AActor/) (UE4): Low-level unreal class for any object that can be spawned into the world +2. [`ASensor`](https://github.com/carla-simulator/carla/blob/0.9.13/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h) (Carla): Carla actor that templates the structure for Sensors acting in the Carla world +3. [`ADReyeVRSensor`](../Carla/Sensor/DReyeVRSensor.h) (DReyeVR): Our sensor instance that contains logic for all Carla related tasks + - Streaming to the PythonAPI + - Receiving data from replayer to reenact + - Contains instance of `DReyeVR::AggregateData` containing ALL the data +4. [`AEgoSensor`](../DReyeVR/EgoSensor.h) (DReyeVR): Our primary actor containing all DReyeVR related logic for custom data variables/functions + - Eye tracking logic (SRanipal), ego vehicle tracking, etc. + +## DReyeVRPawn + +- Relevant files: [DreyeVRPawn.h](../DReyeVR/DReyeVRPawn.h), [DreyeVRPawn.cpp](../DReyeVR/DReyeVRPawn.cpp) + +Getting back to our discussion on the EgoVehicle simultaneous input with player & AI, the DReyeVRPawn is the actual entity that the *human player* possesses during the duration of the level. Unlike EgoVehicle/EgoSensor, the DReyeVRPawn is not tied to any particular object and can be thought of as **an invisible floating camera that defines the viewport of the player**. + +The DReyeVRPawn therefore manages the in-game [`UCameraComponent`](https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Camera/UCameraComponent/) as well as visual and input logic that the player needs. The [SteamVR](https://docs.unrealengine.com/4.27/en-US/SharingAndReleasing/XRDevelopment/VR/VRPlatforms/SteamVR/QuickStart/) integration is managed here, as well as the LogiWheel controls scheme mapping, since this is the object that the player possesses and thus gets first input priority to. We also add some visual eye-candy logic such as a visualization indicator for the eye gaze as a reticle that is drawn on the [SpectatorScreen](https://docs.unrealengine.com/4.26/en-US/SharingAndReleasing/XRDevelopment/VR/DevelopVR/VRSpectatorScreen/) (not visible to the VR player) or flat-screen HUD. + +The EgoVehicle *AI and player* dual-input logic comes from the implementation that the DReyeVRPawn simply forwards commands to the EgoVehicle without directly possessing it, so the Carla AI can still possess and control the EgoVehicle. This enables simultaneous "possession" by the player and the Carla AI controller, since all human player inputs still reach the EgoVehicle and take precedence over the AI. + +## DReyeVRGameMode + +- Relevant files: [DReyeVRGameMode.h](../DReyeVR/DReyeVRGameMode.h), [DReyeVRGameMode.cpp](../DReyeVR/DReyeVRGameMode.cpp) + +A [`GameMode`](https://docs.unrealengine.com/4.27/en-US/InteractiveExperiences/HowTo/SettingUpAGameMode/) in UE4 is used to define game logic across levels, and this can be easily done in code (unlike [`LevelScripts`](https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/ALevelScriptActor/), which are tied to individual level blueprints). + +The gamemode class is useful because **we can rely on it to always persist throughout any level instance**, so we can define logic beyond the lifetime of a single EgoVehicle/EgoSensor and operate on a more global level. + +For instance, we have code to change the volume of the in-world sound effects, spawn the EgoVehicle in a particular location, transfer control to the default floating spectator (detatch from the EgoVehicle), and manage media controls for playback of a recording (play/pause/step/rewind/etc.). + +The most important thing that the DReyeVR gamemode does is spawn the DReyeVRPawn, so the human player can possess some actor and interact with the world at all. + +## DReyeVRFactory + + - Relevant files: [DReyeVRFactory.h](../DReyeVR/DReyeVRFactory.h), [DReyeVRFactory.cpp](../DReyeVR/DReyeVRFactory.cpp) + +Carla uses Factories to spawn all their relevent actors (See [`CarlaActorFactory`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactory.h), [`CarlaActorFactoryBlueprint`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActorFactoryBlueprint.h), [`SensorFactory`](https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SensorFactory.h), etc.) which spawn everything from vehicles to pedestrians to sensors and props. This design allows Carla to handle all the dirty work of registering the actors with LibCarla so that LibCarla knows about each actor and they can be interacted with in Python. + +We follow suit with a similar design in our `DReyeVRFactory` which defines the important characteristics for our DReyeVR actors and provides the logic necessary to spawn them. For instance, here we define our actors are labeled uniquely such as `"harplab.dreyevr_vehicle.model3"` to avoid conflict with existing Carla `"vehicle.*"` queries. + +This is class you'll want to modify if you're looking to create new DReyeVR actors (such as new vehicle models), walkers, sensors, etc. + +--- + +# Adding custom data to the ego-sensor +While we provide a fairly comprehensive suite of data in our DReyeVRSensor, you may be interested in also tracking other data that we don't currently enable. + +The first file you'll want to look at is `Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/`[`DReyeVRData.h`](../Carla/Sensor/DReyeVRData.h) which contains the data structures that compose the contents of the ego sensor. Here you'll define the variable and its serialization methods (read/write/print). + +```c++ +/// DReyeVRData.h +class AggregateData // all DReyeVR sensor data is held here +{ +public: + ... // existing code + float GetNewVariable() const; + ////////////////////:SETTERS:////////////////////// + + ... + void SetNewVariable(const float NewVariableIn); + + ////////////////////:SERIALIZATION:////////////////////// + void Read(std::ifstream &InFile); + + void Write(std::ofstream &OutFile) const; + + FString ToString() const; // this printing is used when showing recorder info + +private: +... // existing code +float NewVariable; // <-- Your new variable +}; +``` + +Then, you'll want to write the implementation in `Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/`[`DReyeVRData.cpp`](../Carla/Sensor/DReyeVRData.cpp) as inline funcitons. +```c++ +/// DReyeVRData.cpp +... +float AggregateData::GetNewVariable() const +{ + return NewVariable; +} + +... +void AggregateData::SetNewVariable(const float NewVariableIn) +{ +NewVariable = NewVariableIn; +} + +void AggregateData::Read(std::ifstream &InFile) +{ + /// CAUTION: make sure the order of writes/reads is the same + ... // existing code + ReadValue(InFile, NewVariable); +} + +void AggregateData::Write(std::ofstream &OutFile) const +{ + /// CAUTION: make sure the order of writes/reads is the same + ... // existing code + WriteValue(OutFile, GetNewVariable()); +} + +FString AggregateData::ToString() const // this printing is used when showing recorder info +{ + FString print; + ... // existing code + print += FString::Printf(TEXT("[DReyeVR]NewVariable:%.3f,\n"), GetNewVariable()); + return print; +} +... +``` +Notes: +- It is nice to contain collections of relevant variables together in structures so they can be better organized. To facilitate this we designed our DReyeVRData to contain various `DReyeVR::DataSerializer` objects, which each implement their own serialization methods. Our `AggregateData` instance contains all our structs and a lightweight API to access member variables. +- The above is an example of modifying/adding a new variable directly to a `DReyeVR::AggregateData`. But it would be better to either modify an existing `DReyeVR::DReyeVRSerializer` object or create a new one (inheriting from the virtual class) and define all the abstract methods yourself. This enables a more granular sub-class/struct abstraction like most of our variables. + +With this step complete, you are free to read/write to this variable by getting the single global (`static`) instance of the `DReyeVR::AggregateData` class using the `GetData()` function of the EgoSensor as follows: +```c++ +// In some other file, for example EgoVehicle.cpp: +float NewVariable = EgoSensor->GetData()->GetNewVariable(); +... // your code +EgoSensor->GetData()->SetNewVariable(NewVariable + 5.f); // update the new variable +``` + +## [OPTIONAL] Streaming data to a PythonAPI client: +In order to see the new data from a PythonAPI client, you'll need to duplicate the code to the LibCarla serializer. This requires looking at `LibCarla/Sensor/s11n/`[`DReyeVRSerializer.h`](../LibCarla/Sensor/s11n/DReyeVRSerializer.h) and following the same template as all the other variables: +```c++ +class DReyeVRSerializer +{ + public: + struct Data + { + ... // existing code + float NewVariable; + + MSGPACK_DEFINE_ARRAY( + ... // existing code + NewVariable, // <-- New variable + ) + }; +}; +///NOTE: you'll also need to interface with this updated struct: +``` +Then, to actually interface with the DReyeVR sensor, you'll need to modify the call to the LibCarla stream to include your `NewVariable`. +```c++ +// in Carla/Sensor/DReyeVRSensor.cpp +void ADReyeVRSensor::PostPhysTick(UWorld *W, ELevelTick TickType, float DeltaSeconds) +{ + ... // existing code + Stream.Send(*this, + carla::sensor::s11n::DReyeVRSerializer::Data{ + ... // existing code + Data->GetNewVariable(), // <-- New variable + }); +} +``` +And finally, to actually get the data from a PythonAPI call, you'll need to modify the list of available attributes to the DReyeVR sensor object as follows: +```c++ +// in LibCarla/source/carla/sensor/data/DReyeVREvent.h +class DReyeVREvent : public SensorData +{ + ... + + public: + ... // existing code + float GetNewVariable() const // <-- new code + { + return InternalData.NewVariable; + } + + private: + carla::sensor::s11n::DReyeVRSerializer::Data InternalData; +}; +``` +Then finally here you'll define what function to call (the variable getter) to get that data from a PythonAPI client. +```c++ +// in PythonAPI/carla/source/libcarla/SensorData.cpp +class_, boost::noncopyable, boost::shared_ptr>("DReyeVREvent", no_init) + ... // existing code + .add_property("new_variable", CALL_RETURNING_COPY(csd::DReyeVREvent, GetNewVariable)) + .def(self_ns::str(self_ns::self)) +; +``` +After you modify files in `PythonAPI` or `LibCarla` the PythonAPI will need to be rebuilt in order for your changes to take effect: +```bash +conda activate carla13 # if using conda +(carla13) make PythonAPI +# make sure to fix any build errors that may occur! +``` + +# TODO: add more dev notes + +# Tips & Tricks +## 1. Enable logging in shipping mode +It is super useful to see the CarlaUE4.log file in shipping mode and this is not the default in Carla (or Unreal) perhaps for performance reasons? + +If you want to enable these features then you'll need to add the flag for `bUseLoggingInShipping` in the `Carla/Unreal/CarlaUE4/Source/CarlaUE4.Target.cs` file. + +```cs +public class CarlaUE4Target : TargetRules +{ + public CarlaUE4Target(TargetInfo Target) : base(Target) + { + Type = TargetType.Game; + ExtraModuleNames.Add("CarlaUE4"); + bUseLoggingInShipping = true;// <--- added here + } +} +``` + +Then you should be able to find the CarlaUE4.log files (timestamped to avoid overwrite) at `C:\Users\%YOUR_USER_NAME%\AppData\Local\CarlaUE4\Saved\Logs\CarlaUE4.log` (on Windows). Also works for Mac/Linux. See [this](https://forums.unrealengine.com/t/how-to-debug-shipping-build-exclusive-crash/411138) for more information. + +--- + +## 2. How to `LOG` +Logging is useful to track code logic and debug (especially since debugging UE4 code can be a bit rough). By default in Unreal C++ you can always use `UE_LOG(LogTemp, Log, TEXT("some text and %d here"), 55);` but we streamlined this for DReyeVR specific logging. You can use our `LOG` macros (defined in [`CarlaUE4.h`](../CarlaUE4/CarlaUE4.h)) when you are editing `CarlaUE4/DReyeVR/*.[cpp|h]` files. + +The main benefits include: +- Less boilerplate code for the programmer (thats you!) +- All logs have the prefix `DReyeVRLog` so they are easy to filter in the overall `CarlaUE4.log` file +- We also attached neat compile-time prefixes to include `"[{INVOKED_FILE}::{INVOKED_FUNCTION}:{LINE_NUMBER}] {message}"` so you can quickly find where this log was invoked from and differentiate from others + - A typical DReyeVR log using our macros looks like this: + ``` + LogDReyeVR: [DReyeVRUtils.h::ReadConfigValue:141] "your message here" + ``` + +```c++ +... // in CarlaUE4/DReyeVR files +void example() { + LOG("some text and %d (this text is grey)", 55); + FString warning_str("warning"); + LOG_WARN("some %s here (this text is yellow!)", *warning_str); + LOG_ERROR("this text is red!"); +} +... +``` + +If you are working instead in the `CarlaUE4/Plugins/Source/Carla` codebase then you'll be able to use similar macros but prefixed with `DReyeVR_`: `DReyeVR_LOG("blah blah")`, `DReyeVR_LOG_WARN("blah blah warning")`, etc. + +--- + +## 3. Managing multiple Carla/DReyeVR versions +- Having separate `python` environments (such as `conda`) is extremely useful to have different `carla` Python packages on the same machine with different versions (such as `LibCarla`). To do this, you can simply create an individual conda environment for each Carla version as described in [`Install.md`](Install.md). Remember to activate your new `conda` environment on a per-shell basis! +- If you plan on having multiple CARLA's installed, you'll need to keep them updated with the appropriate `Content`. Rather than calling the `Update` script every time to update this, you can save the `Content.tar.gz` file and copy it into new `Unreal/CarlaUE4/Content/Carla` directories whenever you have a new repo. + +--- + ## 4. TODO add more tips & tricks \ No newline at end of file diff --git a/Docs/Install.md b/Docs/Install.md index 33dd046..ef6c0f4 100644 --- a/Docs/Install.md +++ b/Docs/Install.md @@ -1,474 +1,609 @@ -# Installing `DReyeVR` to a working Carla 0.9.13 build -## Prerequisites -- Make sure your machine satisfies the prerequisites required by Carla: [Windows](https://carla.readthedocs.io/en/0.9.13/build_windows), [Linux](https://carla.readthedocs.io/en/0.9.13/build_linux), [Mac*](https://github.com/GustavoSilvera/carla/blob/m1/Docs/build_mac.md) -- **IMPORTANT**: If on **Windows** you will **need** [`Make-3.81`](https://gnuwin32.sourceforge.net/packages/make.htm) as per the [Carla documentation](https://carla.readthedocs.io/en/latest/build_windows/#system-requirements) -- If you have previously installed Carla in your PYTHONPATH, you'll need to remove any prior PythonAPI installations - - For instance, if you [installed carla via pip](https://pypi.org/project/carla/), you'll **need to uninstall** it to proceed. - ```bash - pip uninstall carla - ``` - -## Getting started -- You should first make sure DReyeVR is downloaded: - ```bash - git clone https://github.com/HARPLab/DReyeVR --depth 1 - ``` -- You'll first need to install [Unreal Engine 4.26 (CARLA fork)](https://github.com/CarlaUnreal/UnrealEngine) from source - ```bash - git clone https://github.com/CarlaUnreal/UnrealEngine - # set this location to your $UE4_ROOT environment variable - ``` - - **IMPORTANT** on DReyeVR for Carla 0.9.13 you'll need to revert the UE4 repository to a supported version (for DReyeVR). This is to optimize the DX11 rendering performance which in our testing has been the optimal render backend for VR. - ```bash - # in $UE4_ROOT - git checkout d40ec35474e8793b4eea60dba6c4f051186e458e - # or git reset --hard d40ec35474e8793b4eea60dba6c4f051186e458e - ``` - - - **IMPORTANT:** if the `git clone` link does not work for you, you probably need to [join the Epic Games Organization](https://www.unrealengine.com/en-US/ue4-on-github) to get access to UnrealEngine and all of its forks. - - UE4 build instructions for your system can be found here: [Windows](https://carla.readthedocs.io/en/0.9.13/build_windows/#unreal-engine), [Linux](https://carla.readthedocs.io/en/0.9.13/build_linux/#unreal-engine), [Mac*](https://github.com/GustavoSilvera/carla/blob/m1/Docs/build_mac.md#unreal-engine-fork ) - - - In order to successfully run Setup.sh, you will need to download and replace the Commit.gitdeps.xml file within /Engine/Build. See updated XML file at [Commit.gitdeps.xml](https://github.com/HARPLab/UnrealEngine/blob/DReyeVR-0.9.13/Engine/Build/Commit.gitdeps.xml) - -- You'll then need to clone and build a [vanilla Carla 0.9.13](https://carla.readthedocs.io/en/0.9.13/#building-carla) - ```bash - git clone https://github.com/carla-simulator/carla -b 0.9.13 --depth 1 - ``` - - Use [Building on Linux](https://carla.readthedocs.io/en/0.9.13/build_linux/) for all versions up to Ubuntu 18.04 or [Building on Windows](https://carla.readthedocs.io/en/0.9.13/build_windows/) to follow their instructions on building CARLA 0.9.13. Use [our Ubuntu 20.04 CARLA installation guide](Install_Ubuntu.md) for Ubuntu 20.04. -- (Optional) Similarly, you can install a vanilla [Carla Scenario Runner v0.9.13 ](https://github.com/carla-simulator/scenario_runner/tree/v0.9.13) project to integrate DReyeVR+Carla with Scenario Runner. - ```bash - git clone https://github.com/carla-simulator/scenario-runner -b v0.9.13 --depth 1 - ``` - -(*=The Mac operating system is no longer officially supported by Carla but our development team has made it possible to build both UE4, Carla, and DReyeVR on new Mac machines with Apple Silicon (arm64) hardware. ) - -
- -# DReyeVR installation command summary -
- -**NOTE** You'll need a terminal on Linux/Mac. On Windows you'll be fine with the same x64 Native Tools CMD prompt that you used to build Carla. - Show command lines to install and build DReyeVR - -```bash -mkdir CarlaDReyeVR && cd CarlaDReyeVR # doing everything in this "CarlaDReyeVR" directory - -##################################################### -########### install OUR UnrealEngine fork ########### -##################################################### -# Rather than https://github.com/CarlaUnreal/UnrealEngine UE4, you SHOULD clone https://github.com/HARPLab/UnrealEngine -# but otherwise all instructions remain the same. - -# Linux: https://carla.readthedocs.io/en/0.9.13/build_linux/#unreal-engine -# Windows: https://carla.readthedocs.io/en/0.9.13/build_windows/#unreal-engine - -##################################################### -################### install Carla ################### -##################################################### -# Linux: https://carla.readthedocs.io/en/0.9.13/build_linux/ -# Windows: https://carla.readthedocs.io/en/0.9.13/build_windows/ -git clone https://github.com/carla-simulator/carla -b 0.9.13 --depth 1 -cd carla -./Update.sh # linux/mac -Update.bat # Windows -make PythonAPI && make launch # to build vanilla Carla - -##################################################### -############## install DReyeVR plugins ############## -##################################################### -# (optional) install SRanipal (eye tracking) -mv /PATH/TO/SRANIPALPLUGIN/SDK/03_Unreal/Plugins/SRanipal Unreal/CarlaUE4/Plugins/ - -# (optional) install LogitechWheelPlugin (steering wheel) -git clone https://github.com/HARPLab/LogitechWheelPlugin -mv LogitechWheelPlugin/LogitechWheelPlugin Unreal/CarlaUE4/Plugins/ # install to carla - -cd .. # back to main directory - -##################################################### -############## install scenario_runner ############## -##################################################### -# (optional) while you don't NEED scenario runner, it is certainly useful from a research pov -git clone https://github.com/carla-simulator/scenario_runner -b v0.9.13 - -##################################################### -################## install DReyeVR ################## -##################################################### -git clone https://github.com/HARPLab/DReyeVR -cd DReyeVR -# the CARLA= and SR= variables are optional -make install CARLA=../carla SR=../scenario_runner -# or -make install CARLA=../carla -make install SR=../scenario_runner - -# run filesystem checks after installing -make check CARLA=../carla -cd .. - -##################################################### -################## build everything ################# -##################################################### -cd carla -make PythonAPI # build the PythonAPI (and LibCarla) again -make launch # launch in editor -make package # create an optimized package -make check # run Carla unit tests -``` -
- - -
- -## Simple install -Technically, the above prerequisites are all you really need to install DReyeVR and get a barebones VR ego-vehicle with **no eyetracking** and **no racing wheel integration**. If this suits your needs, simply skip down to the [Install DReyeVR Core](Install.md#installing-dreyevr-core) section of this doc and set the following variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: -```c# -///////////////////////////////////////////////////////////// -// Edit these variables to enable/disable features of DReyeVR -bool UseSRanipalPlugin = true; -bool UseLogitechPlugin = true; -... -///////////////////////////////////////////////////////////// -``` -- NOTE: you only need to install the SRanipal plugin if `UseSRanipalPlugin` is enabled, and similarly you only need to install the Logitech plugin if `UseLogitechPlugin` is enabled. - - -# Installing DReyeVR Plugins -Before installing `DReyeVR`, we'll also need to install the dependencies: -- **SteamVR**: Required for VR -- **SRanipal***: Required for eye tracking (with HTC Vive Pro Eye), optional otherwise -- **LogitechWheelPlugin***: Required for Logitech Steering Wheel, optional otherwise - -(* = optional, depends on the features you are looking for) - -## SteamVR -### **Download Steam and SteamVR** - - You'll need to use [SteamVR](https://store.steampowered.com/app/250820/SteamVR/) for the VR rendering environment, so you should first download the [Steam client application](https://store.steampowered.com/about/). - - From within the steam client, you can browse in store->search "[SteamVR](https://store.steampowered.com/app/250820/SteamVR/)" and download the free-to-install system utility. - - - - - You should be able to launch SteamVR from the client and in the small pop-up window reach both settings and "show VR view" - - Make sure to calibrate the VR system to your setup and preferences! - - Additionally we recommend disabling the "Motion Smoothing" effect within SteamVR Settings to avoid nasty distortion artifacts during rendering. - - SteamVR-settings -*** -## HTC Eye Tracker Plugin -### **Download `SRanipal`** - 0. *What is SRanipal?* - - We are using [HTC's SRanipal plugin](https://developer.vive.com/resources/vive-sense/sdk/vive-eye-tracking-sdk-sranipal/) as the means to communicate between Unreal Engine 4 and the Vive's Eye Tracker. - - To learn more about SRanipal and for **first-time-setup**, see this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC - 1. You'll need a (free-to-create) [Vive developer account](https://hub.vive.com/sso/login) to download the following: - - a) [`VIVE_SRanipalInstaller_1.3.2.0.msi`](https://hub.vive.com/en-US/download/VIVE_SRanipalInstaller_1.3.2.0.msi) -- executable to install Tobii firmware - - b) [`SDK_v1.3.3.0.zip`](https://hub.vive.com/en-US/download/SDK-v1.3.3.0.zip) -- includes the Unreal plugin - - **IMPORTANT**: The SRanipal versions above 1.3.6.0 are NOT supported and cause wild crashes! - - **If the download links above don't work for you, make sure you have a Vive Developer account! (Or [contact](mailto:gustavo@silvera.cloud) us directly to help you)** - 2. Install the Tobii firmware by double-clicking the `.msi` installer - - Once installed, you should see the `SR_runtime.exe` program available from the Start Menu. Launch it as administrator and you should see the robot head icon in the Windows system tray as follows: - - ![SR_runtime](https://mariosbikos.com/wp-content/uploads/2020/02/image-30.png) - - Image Credit: [MariosBikos](https://forum.htc.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine) - -### **Installing SRanipal UE4 Plugin** - - After downloading the `.zip` file, unzipping it should present a directory similar to this - - ``` - SDK - - 01_C/ - - 02_Unity/ - - 03_Unreal/ - - Eye_SRanipal_SDK_Guide.pdf - - Lip_SRanipal_SDK_Guide.pdf - ``` - - Then, unzip the SRanipal unreal plugin and copy over the `03_Unreal/Plugins/SRanipal/` directory to the Carla installation - - ```bash - # in SDK/ - cd 03_Unreal - unzip Vive-SRanipal-Unreal-Plugin.zip # creates the PLugins/SRanipal folder - # assumes CARLA_ROOT is defined, else just use your Carla path - cp -r Plugins/SRanipal $CARLA_ROOT/Unreal/CarlaUE4/Plugins/ - ``` - - It is recommended to re-calibrate the SRanipal eye tracker plugin for every new participant in an experiment. You can do this by entering SteamVR home, and clicking the small icon in the bottom menu bar to calibrate eye tracker to the headset wearer. - - ![Calibration](Figures/Install/steamvr-home.jpg) - - You can find more information by checking out this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC -*** -## Logitech Wheel Plugin -### **Installing Logitech Wheel Plugin** - - This is only for those who have a Logitech steering wheel/pedals driving setup. This hardware is not required to experience the VR experience (you can simply use keyboard/mouse) but greatly adds to the immersion and allows for granular analog controls. - - For reference, we used this [Logitech G923 Racing Wheel & Pedals](https://www.logitechg.com/en-us/products/driving/driving-force-racing-wheel.html). - - We'll be using this [LogitechWheelPlugin](https://github.com/HARPLab/LogitechWheelPlugin) to interact with UE4 and map hardware inputs to actions. - - Clone the repo and move the requisite folder to the Carla plugins folder - - ```bash - git clone https://github.com/HARPLab/LogitechWheelPlugin - mv LogitechWheelPlugin/LogitechWheelPlugin $CARLA_ROOT/Unreal/CarlaUE4/Plugins - ``` - - You should then see a Logitech Plugin enabled when you boot up the editor again: - - ![LogitechPlugin](Figures/Install/LogitechPlugin.jpg) -*** -## Sanity Check - - After installing these plugins, you should see a `Unreal/CarlaUE4/Plugins` that looks like this: - - ``` - Plugins - ├── Carla # unchanged - │ └── ... - ├── CarlaExporter # unchanged - │ └── ... - ├── LogitechWheelPlugin # if installed - │ ├── Binaries - │ ├── Doc - │ ├── Logitech - │ ├── LogitechWheelPlugin.uplugin - │ ├── Resources - │ └── Source - └── SRanipal # if installed - ├── Binaries - ├── Config - ├── Content - ├── Resources - ├── Source - └── SRanipal.uplugin - ``` - - If you still have questions or issues, feel free to post an issue on our [Issues](https://github.com/HARPLab/DReyeVR/issues) page and we'll try our best to help you out. - -
-
- -# Installing `DReyeVR` Core - - -- **IMPORTANT** The installation requires that `make`, `python` and `git` are available on your shell. -- You only need to install to a `CARLA` directory, ScenarioRunner is optional. - - If you don't provide the `make` variables `CARLA=...` or `SR=...` the installation wizard will automatically detect your install destination by looking at the environment variables `CARLA_ROOT` and `SCENARIO_RUNNER_ROOT` required by Carla. - -```bash -# the CARLA= and SR= variables are optional -make install CARLA=../carla SR=../scenario_runner -# or -make install CARLA=../carla -make install SR=../scenario_runner - -# run filesystem checks after installing -make check CARLA=../carla -``` -**NOTE:** to learn more about how the DReyeVR `make` system works, see [`Scripts/README.md`](../Scripts/README.md) - - -# Building `DReyeVR` PythonAPI -## Using [`conda`](https://www.anaconda.com/products/distribution) for the PythonAPI - - While not required for DReyeVR, we highly recommend compartmentalizing Python installations via isolated environments such as [`anaconda`](https://www.anaconda.com/products/distribution) - - First download and install Anaconda to your machine from [here](https://www.anaconda.com/products/distribution). - ```bash - # in /PATH/TO/CARLA/ - conda create --name carla13 python=3.7.2 - conda activate carla13 # will need to run this ONCE before opening a new terminal! - conda install numpy - ``` -- **READ THIS FIRST (Linux)**: You might run into a problem when compiling Boost 1.72.0 (required by `LibCarla`). -
- - Show instructions to get Anaconda working on Linux - - - ```bash - # find anaconda install: - which python3 - ... PATH/TO/ANACONDA/envs/carla/bin/python3 # example output - - # go to carla/install dir from here - cd PATH/TO/ANACONDA/envs/carla/include - - # create a symlink between python3.7 -> python3.7m - ln -s python3.7m python3.7 - ``` - Install `boost_1_72_0.tar.gz` manually from https://github.com/jerry73204/carla/releases/tag/fix-boost and place file in `Build/boost_1_72_0.tar.gz` - Open `Util/BuildTools/Setup.sh` (or `Util/BuildTools/Setup.bat` on Windows) - Find the section named `Get boost` includes and comment out the `wget` lines. - Now when you `make LibCarla` again, the `boost` errors should be resolved. - - For more information see the bottom of this [SO post](https://stackoverflow.com/questions/42839382/failing-to-install-boost-in-python-pyconfig-h-not-found) -
- - - **READ THIS FIRST (Windows)**: Windows anaconda is a bit more of a pain to deal with. -
- - Show instructions to get Anaconda working on Windows - - 1. Enable your environment - ```bat - conda activate carla13 - ``` - 2. Add carla to "path" to locate the PythonAPI and ScenarioRunner. But since Anaconda [does not use the traditional `PYTHONPATH`](https://stackoverflow.com/questions/37006114/anaconda-permanently-include-external-packages-like-in-pythonpath) you'll need to: - - 3.1. Create a file `carla.pth` in `\PATH\TO\ANACONDA\envs\carla\Lib\site-packages\` - - 3.2. Insert the following content into `carla.pth`: - ```bat - C:\PATH\TO\CARLA\PythonAPI\carla\dist - C:\PATH\TO\CARLA\PythonAPI\carla\agents - C:\PATH\TO\CARLA\PythonAPI\carla - C:\PATH\TO\CARLA\PythonAPI - C:\PATH\TO\CARLA\PythonAPI\examples - C:\PATH\TO\SCENARIO_RUNNER\ - ``` - 3. Install the specific carla wheel (`whl`) to Anaconda - ```bash - conda activate carla13 - pip install --no-deps --force-reinstall PATH\TO\CARLA\PythonAPI\carla\dist\carla-0.9.13-cp37-cp37m-win_amd64.whl - - # if applicable (and you installed Scenario runner) - cd %SCENARIO_RUNNER_ROOT% - pip install -r requirements.txt # install all SR dependencies - ``` - 4. Finally, you might run into problems with `shapely` (scenario-runner dependency) and Conda. Luckily the solution is simple: - - Copy the files: - - `PATH\TO\ANACONDA\envs\carla13\Lib\site-packages\shapely\DLLs\geos.dll` - - `PATH\TO\ANACONDA\envs\carla13\Lib\site-packages\shapely\DLLs\geos_c.dll` - - To destination: - - `PATH\TO\ANACONDA\envs\carla13\Library\bin\` - 5. Now finally, you should be able to verify all PythonAPI actions work as expected via: - ```bat - conda activate carla13 - python - >>> Python 3.7.2 (default, Feb 21 2019, 17:35:59) [MSC v.1915 64 bit (AMD64)] :: Anaconda, Inc. on win32 - >>> Type "help", "copyright", "credits" or "license" for more information. - >>> import carla - >>> from DReyeVR_utils import find_ego_vehicle - >>> from scenario_runner import ScenarioRunner - ``` - With all these imports passing (no error/warning messages), you're good to go! - -
- -Now you can finally build the PythonAPI to this isolated conda environment. - ```bash - conda activate carla13 - (carla13) make PythonAPI # builds LibCarla and PythonAPI to your (conda) python environment - ``` - - NOTE: You'll need to run `conda activate carla13` every time you open a new terminal if you want to build DReyeVR since the shell needs to know which python environment to use. Luckily this minor inconvenience saves us from the significant headaches that arise when dealing with multiple `python` projects, Carla installations, and versions, etc. - -## Sanity Check: - -It is nice to verify that the Carla PythonAPI is correctly visible in conda, to do this you should see all the following attributes in the `carla` module once calling `dir` on it. - -
-Show instructions to verify Carla PythonAPI is installed - -```bash -# in your terminal (linux) or cmd (Windows) -conda activate carla13 # (if using conda) -(carla13) python # should default to python3!! -``` - -```python -#in Python -... ->>> import carla ->>> dir(carla) -# the following output means carla is not correctly installed :( ->>> ['__doc__', '__file__', '__loader__', '__name__', '__package__', '__path__', '__spec__'] - -# OR the following output means carla is installed :) ->>> ['Actor', 'ActorAttribute', 'ActorAttributeType', 'ActorBlueprint', 'ActorList', 'ActorSnapshot', 'ActorState', 'AttachmentType', 'BlueprintLibrary', 'BoundingBox', 'CityObjectLabel', 'Client', 'ClientSideSensor', 'CollisionEvent', 'Color', 'ColorConverter', 'DReyeVREvent', 'DVSEvent', 'DVSEventArray', 'DebugHelper', 'EnvironmentObject', 'FakeImage', 'FloatColor', 'GearPhysicsControl', 'GeoLocation', 'GnssMeasurement', 'IMUMeasurement', 'Image', 'Junction', 'LabelledPoint', 'Landmark', 'LandmarkOrientation', 'LandmarkType', 'LaneChange', 'LaneInvasionEvent', 'LaneInvasionSensor', 'LaneMarking', 'LaneMarkingColor', 'LaneMarkingType', 'LaneType', 'LidarDetection', 'LidarMeasurement', 'Light', 'LightGroup', 'LightManager', 'LightState', 'Location', 'Map', 'MapLayer', 'MaterialParameter', 'ObstacleDetectionEvent', 'OpendriveGenerationParameters', 'OpticalFlowImage', 'OpticalFlowPixel', 'Osm2Odr', 'Osm2OdrSettings', 'RadarDetection', 'RadarMeasurement', 'Rotation', 'SemanticLidarDetection', 'SemanticLidarMeasurement', 'Sensor', 'SensorData', 'ServerSideSensor', 'TextureColor', 'TextureFloatColor', 'Timestamp', 'TrafficLight', 'TrafficLightState', 'TrafficManager', 'TrafficSign', 'Transform', 'Vector2D', 'Vector3D', 'Vehicle', 'VehicleControl', 'VehicleDoor', 'VehicleLightState', 'VehiclePhysicsControl', 'VehicleWheelLocation', 'Walker', 'WalkerAIController', 'WalkerBoneControlIn', 'WalkerBoneControlOut', 'WalkerControl', 'Waypoint', 'WeatherParameters', 'WheelPhysicsControl', 'World', 'WorldSettings', 'WorldSnapshot', '__builtins__', '__cached__', '__doc__', '__file__', '__loader__', '__name__', '__package__', '__path__', '__spec__', 'bone_transform', 'bone_transform_out', 'command', 'libcarla', 'vector_of_bones', 'vector_of_bones_out', 'vector_of_gears', 'vector_of_ints', 'vector_of_transform', 'vector_of_vector2D', 'vector_of_wheels'] -``` -
- -
- -## Future modifications - -Additionally, if you make changes to the `PythonAPI` source and need to rebuild (`make PythonAPI` again) when using Conda you should reinstall the `.whl` file to ensure your changes will be reflected in the environment: - - ```bash - conda activate carla - - pip install --no-deps --force-reinstall /PATH/TO/CARLA/PythonAPI/carla/dist/carla-YOUR_VERSION.whl - ``` - - -# Upgrading `DReyeVR` -If you currently have an older version of `DReyeVR` installed and want to upgrade to a newer version, it is best to re-install DReyeVR from a fresh Carla repository. You can manually delete the `carla` repository and re-clone it directly (carefully ensuring the versions match) or use our provided scripts which attempt to reset the repository for you: - -
- Show instructions to use DReyeVR scripts to reset CARLA repo - -**IMPORTANT:** the `DReyeVR` clean script will overwrite and reset the Carla repository you specify, so make your backups now if you have any unstaged code. (`git reset --hard HEAD` and `git clean -fd` will be invoked, so if you commit your local changes they will be safe) - -```bash -# first go to CARLA and clean it so no old DReyeVR builds linger -cd /PATH/TO/Carla/ -make clean - -# it is a good idea to clean the Content/ directory which is not tracked by Carla's git system -rm -rf Unreal/CarlaUE4/Content/ - -# re-install the Content fresh from Carla's servers -./Update.sh # Linux/Mac -Update.bat # Windows - -# next, go to DReyeVR and get the latest updates -cd /PATH/TO/DReyeVR/ -git pull origin main # or dev, or whatever branch - -# next, run the DReyeVR-cleaner to automatically hard-reset the Carla repo -# accept the prompt to hard-clean CARLA, note that this will reset tracked and remove untracked files -make clean CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional - -# now, you can cleanly install DReyeVR over Carla again -make install CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional - -# it's a good idea to check that the Carla repository has all the expected files -make check CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional - -# finally, you can go back to Carla and rebuild -cd /PATH/TO/Carla -make PythonAPI -make launch -make package -``` - -*** - -As long as you have no errors in the previous sections, you should be able to just build the `Carla` project with our `DReyeVR` files as follows: - -
- -
-
- -# Building `DReyeVR` UE4 -If you are not interested in using SRanipal or the LogitechWheelPlugin, you can disable these at compile-time by changing the variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: -```c# - ///////////////////////////////////////////////////////////// - // Edit these variables to enable/disable features of DReyeVR - bool UseSRanipalPlugin = true; - bool UseLogitechPlugin = true; - ... - ///////////////////////////////////////////////////////////// - ``` - -Finally, open the project directory in any terminal (Linux/Mac) or `Windows x64 Native Tools Command Prompt for VS 2019` (Windows) and run: -```bash -make PythonAPI # build the PythonAPI & LibCarla - -make launch # build the development UE4 game in editor - -make package # build the optimized UE4 packaged game (shipping) -``` - -# Running `DReyeVR` - -With the shipping package built, run the Carla (with DReyeVR installed) executable in VR mode with: -```bash -# on Unix -cd /PATH/TO/CARLA/Dist/CARLA_Shipping_0.9.13-dirty/LinuxNoEditor/ # or MacNoEditor on MacOS -./CarlaUE4.sh -vr - -# on Windows x64 Visual C++ Toolset -cd \PATH\TO\CARLA\Build\UE4Carla\0.9.13-dirty\WindowsNoEditor\ -CarlaUE4.exe -vr - -# Optional flag: -quality-level=Low -``` -**NOTE:** To greatly boost the framerates without losing much visual fidelity you can run with the additional argument `-quality-level=Low` which we modified from vanilla Carla to preserve the same rendering distance. - -**NOTE 2** You also don't necessarily NEED to run DReyeVR in VR. If you omit the `-vr` flag then you will be greeted with a flat-screen Carla game with the same features available for DReyeVR, just not in VR. - -
- -# Now what? - -Now that you've successfully installed DReyeVR continue to [`Usage.md`](Usage.md) to learn how to use DReyeVR for your own VR driving research simulator. +# Installing `DReyeVR` to a working Carla 0.9.13 build + +## Part One: Prerequisites + +- Make sure your machine satisfies the prerequisites required by Carla: [Windows](https://carla.readthedocs.io/en/0.9.13/build_windows), [Linux](https://carla.readthedocs.io/en/0.9.13/build_linux), [Mac\*](https://github.com/GustavoSilvera/carla/blob/m1/Docs/build_mac.md) +- **IMPORTANT**: If on **Windows** you will **need** [`Make-3.81`](https://gnuwin32.sourceforge.net/packages/make.htm) as per the [Carla documentation](https://carla.readthedocs.io/en/latest/build_windows/#system-requirements) +- If you have previously installed Carla in your PYTHONPATH, you'll need to remove any prior PythonAPI installations + - For instance, if you [installed carla via pip](https://pypi.org/project/carla/), you'll **need to uninstall** it to proceed. + ```bash + pip uninstall carla + ``` + +### System requirements + +- **x64 system.** The simulator should run in any 64 bits Windows system. +- **165 GB disk space.** CARLA itself will take around 32 GB and the related major software installations (including Unreal Engine) will take around 133 GB. +- **An adequate GPU.** CARLA aims for realistic simulations, so the server needs at least a 6 GB GPU although 8 GB is recommended. A dedicated GPU is highly recommended for machine learning. +- **Two TCP ports and good internet connection.** 2000 and 2001 by default. Make sure that these ports are not blocked by firewalls or any other applications. + +!!! Warning +**If you are upgrading from CARLA 0.9.12 to 0.9.13**: you must first upgrade the CARLA fork of the UE4 engine to the latest version. See the [**Unreal Engine**](#unreal-engine) section for details on upgrading UE4 + +### Software requirements + +#### Minor installations + +- [**CMake**](https://cmake.org/download/) generates standard build files from simple configuration files. **We recommend you use version 3.15+**. +- [**Git**](https://git-scm.com/downloads) is a version control system to manage CARLA repositories. +- [**Make**](http://gnuwin32.sourceforge.net/packages/make.htm) generates the executables. It is necessary to use **Make version 3.81**, otherwise the build may fail. If you have multiple versions of Make installed, check that you are using version 3.81 in your PATH when building CARLA. You can check your default version of Make by running `make --version`. +- [**7Zip**](https://www.7-zip.org/) is a file compression software. This is required for automatic decompression of asset files and prevents errors during build time due to large files being extracted incorrectly or partially. +- [**Python3 x64**](https://www.python.org/downloads/) is the main scripting language in CARLA. Having a x32 version installed may cause conflict, so it is highly advisable to have it uninstalled. + +!!! Important +Be sure that the above programs are added to the [environment path](https://www.java.com/en/download/help/path.xml). Remember that the path added should correspond to the progam's `bin` directory. + +#### Python dependencies + +Starting with CARLA 0.9.12, users have the option to install the CARLA Python API using `pip3`. Version 20.3 or higher is required. To check if you have a suitable version, run the following command: + +```sh +pip3 -V +``` + +Python version should be [3.7](https://www.python.org/downloads/release/python-379/) with numpy version 1.21.6 + +If you need to upgrade: + +```sh +pip3 install --upgrade pip +``` + +You must install the following Python dependencies: + +```sh +pip3 install --user setuptools +pip3 install --user wheel +``` + +#### Major installations + +##### Visual Studio 2019 + +Get the 2019 version of Visual Studio from [here](https://www.techspot.com/downloads/7241-visual-studio-2019.html). Choose **Community** for the free version. Use the _Visual Studio Installer_ to install three additional elements: + +- **Windows 8.1 SDK.**, **Windows 10 SDK (10.0.16xxx.x and 10.0.19xxx.x)** Select it in the _Installation details_ section on the right or go to the _Indivdual Components_ tab and look under the _SDKs, libraries, and frameworks_ heading. +- **x64 Visual C++ Toolset.** In the _Workloads_ section, choose **Desktop development with C++**. This will enable a x64 command prompt that will be used for the build. Check that it has been installed correctly by pressing the `Windows` button and searching for `x64`. Be careful **not to open a `x86_x64` prompt**. +- **.NET framework 4.6.2**. In the _Workloads_ section, choose **.NET desktop development** and then in the _Installation details_ panel on the right, select `.NET Framework 4.6.2 development tools`. This is required to build Unreal Engine. + +!!! Important +Other Visual Studio versions may cause conflict. Even if these have been uninstalled, some registers may persist. To completely clean Visual Studio from the computer, go to `Program Files (x86)\Microsoft Visual Studio\Installer\resources\app\layout` and run `.\InstallCleanup.exe -full` + +!!! Note +It is also possible to use Visual Studio 2022 using the above steps and substituting the Windows 8.1 SDK for the Windows 11/10 SDK. To override the default Visual Studio 2019 Generator in CMake, specify GENERATOR="Visual Studio 17 2022" when using the makefile commands (see [table](build_windows.md#other-make-commands)). You may specify any generator that works with the build commands as specific in the build scripts, for a full list run `cmake -G` (Ninja has been tested to work for building LibCarla so far). + +##### Unreal Engine + +Starting with version 0.9.12, CARLA uses a modified fork of Unreal Engine 4.26. This fork contains patches specific to CARLA. + +Be aware that to download this fork of Unreal Engine, **you need to have a GitHub account linked to Unreal Engine's account**. If you don't have this set up, please follow [this guide](https://www.unrealengine.com/en-US/ue4-on-github) before going any further. + +To build the modified version of Unreal Engine: + +**1.** In a terminal, navigate to the location you want to save Unreal Engine and clone the _carla_ branch: + +```sh + git clone --depth 1 -b carla https://github.com/CarlaUnreal/UnrealEngine.git . +``` + +!!! Note +Keep the Unreal Engine folder as close as `C:\\` as you can because if the path exceeds a certain length then `Setup.bat` will return errors in step 3. E.g. `C:\\UnrealEngine\` + +**2.** Run the configuration scripts: + +```sh + Setup.bat + GenerateProjectFiles.bat +``` + +**3.** Compile the modified engine: + +> 1. Open the `UE4.sln` file inside the source folder with Visual Studio 2019. + +> 2. In the build bar ensure that you have selected '**Development Editor**', '**Win64**' and '**UnrealBuildTool**' options. Check [this guide](https://docs.unrealengine.com/en-US/ProductionPipelines/DevelopmentSetup/BuildingUnrealEngine/index.html) if you need any help. + +> 3. In the solution explorer, right-click `UE4` and select `Build`. + +(It is expected to show 3 succeeded, 0 failed, 0 up-to-date, 0 skipped, otherwise will cause errors later) + +Launch UE and goes to Edit > Plugins > Virtual Reality > Enable SteamVR + +**4.** Once the solution is compiled you can open the engine to check that everything was installed correctly by launching the executable `Engine\Binaries\Win64\UE4Editor.exe`. + +!!! Note +If the installation was successful, this should be recognised by Unreal Engine's version selector. You can check this by right-clicking on any `.uproject` file and selecting `Switch Unreal Engine version`. You should see a pop-up showing `Source Build at PATH` where PATH is the installation path that you have chosen. If you can not see this selector or the `Generate Visual Studio project files` when you right-click on `.uproject` files, something went wrong with the Unreal Engine installation and you will likely need to reinstall it correctly. + +!!! Important +A lot has happened so far. It is highly advisable to restart the computer before continuing. + +## Part Two: Build Carla + +**NOTE** You'll need a terminal on Linux/Mac. On Windows you'll be fine with the same x64 Native Tools CMD prompt that you used to build Carla. + +```bash +mkdir CarlaDReyeVR && cd CarlaDReyeVR # doing everything in this "CarlaDReyeVR" directory + +##################################################### +########### install OUR UnrealEngine fork ########### +##################################################### +# Rather than https://github.com/CarlaUnreal/UnrealEngine UE4, you SHOULD clone https://github.com/HARPLab/UnrealEngine +# but otherwise all instructions remain the same. + +# Linux: https://carla.readthedocs.io/en/0.9.13/build_linux/#unreal-engine +# Windows: https://carla.readthedocs.io/en/0.9.13/build_windows/#unreal-engine + +##################################################### +################### install Carla ################### +##################################################### +# Linux: https://carla.readthedocs.io/en/0.9.13/build_linux/ +# Windows: https://carla.readthedocs.io/en/0.9.13/build_windows/ +git clone https://github.com/carla-simulator/carla +cd carla +git checkout 0.9.13 +# Solution for 404 error: change CONTENT_LINK in Update.bat to https://carla-assets.s3.us-east-005.backblazeb2.com/%CONTENT_ID%.tar.gz +./Update.sh # linux/mac +Update.bat # Windows + +# before continue: +# 1. git clone https://github.com/carla-simulator/carla to other folder +# replace Util/InstallersWin and Util/BuildTools of 0.9.13 with those of 0.9.15 +# 2. In Util/BuildTools/windows.mk remove dowloadplugins in line 74, and all contents from line 87 to end +# 3. In carla\Util\BuildTools\Setup.bat change Carla version (line 378) to 0.9.13 +# 4. In carla\Util\InstallersWin\install_zlib.bat change zlib version (line 51) to 1.2.11 +# 5. Download SDL2 from https://github.com/libsdl-org/SDL/releases/download/release-2.30.8/SDL2-devel-2.30.8-VC.zip , unzip and add those to Path: +# - SDL2_LIBRARY: SDL/src/ +# - SDL2_INCLUDE_DIR: SDL/include/ +# - SDL2_SDLMAIN_LIBRARY: SDL/ + +make PythonAPI +# ERROR with recast:copy SDL/ to ./Build/recast-src/RecastDemo/Contrib +# ERROR with boost: Install boost zip file manually and unzip it, and copy to Build/ +# ERROR with dependencies: mkdir "PythonAPI/carla/dependencies/lib" +# ERROR: & : +# --> at LibCarla/source/test/common/test_streaming.cpp Line 58, 93 Change Server to carla::streaming::low_level::Server | Line 63, 96 change Client to carla::streaming::low_level::Client + +make launch # to build vanilla Carla + +``` + +## Part Three: Install Plugins + +```bash +##################################################### +############## install DReyeVR plugins ############## +##################################################### +# (optional) install SRanipal (eye tracking) +# install SRanipal from: https://github.com/scivi-tools/scivi.ue.board unzip Vive-SRanipal-Unreal-Plugin.zip +mv /PATH/TO/Plugins/SRanipal Unreal/CarlaUE4/Plugins/ + +# (optional) install LogitechWheelPlugin (steering wheel) +git clone https://github.com/HARPLab/LogitechWheelPlugin +mv LogitechWheelPlugin/LogitechWheelPlugin Unreal/CarlaUE4/Plugins/ # install to carla + +cd .. # back to main directory + +##################################################### +############## install scenario_runner ############## +##################################################### +# (optional) while you don't NEED scenario runner, it is certainly useful from a research pov +git clone https://github.com/carla-simulator/scenario_runner -b v0.9.13 + +##################################################### +################## install DReyeVR ################## +##################################################### +git clone https://github.com/HARPLab/DReyeVR +cd DReyeVR +# the CARLA= and SR= variables are optional +make install CARLA=../carla SR=../scenario_runner +# or +make install CARLA=../carla +make install SR=../scenario_runner + +# run filesystem checks after installing +make check CARLA=../carla +cd .. + +##################################################### +################## build everything ################# +##################################################### +cd carla +# ERROR set was unexpected ... --> Change %GENERATOR% to "%GENERATOR%" in rpclib, gtest, recast, proj in Util/InstallersWin/ + +make PythonAPI # build the PythonAPI (and LibCarla) again +make launch # launch in editor +make package # create an optimized package +# (from UE) ERROR: Failed to build "C:/UnrealEngine/Engine/Programs/AutomationTool/Saved\UATTempProj.proj": Open VisualStudio: HoloLens.Automation->References: and in the Browse section, which was initially an empty list, click on browse: and locate the Windows.winmd file from the desired Windows SDK. +make check # run Carla unit tests +# ERROR: Assertion Failed: ResourceTableFrameCounter == INDEX_NONE ... +# --> In Unreal/CarlaUE4/Config/DefaultEngine.ini change DefaultGraphicsRHI_DX11 → DefaultGraphicsRHI_DX12 +``` + +
+ +## Simple install + +Technically, the above prerequisites are all you really need to install DReyeVR and get a barebones VR ego-vehicle with **no eyetracking** and **no racing wheel integration**. If this suits your needs, simply skip down to the [Install DReyeVR Core](Install.md#installing-dreyevr-core) section of this doc and set the following variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: + +```c# +///////////////////////////////////////////////////////////// +// Edit these variables to enable/disable features of DReyeVR +bool UseSRanipalPlugin = true; +bool UseLogitechPlugin = true; +... +///////////////////////////////////////////////////////////// +``` + +- NOTE: you only need to install the SRanipal plugin if `UseSRanipalPlugin` is enabled, and similarly you only need to install the Logitech plugin if `UseLogitechPlugin` is enabled. + +# Installing DReyeVR Plugins + +Before installing `DReyeVR`, we'll also need to install the dependencies: + +- **SteamVR**: Required for VR +- **SRanipal\***: Required for eye tracking (with HTC Vive Pro Eye), optional otherwise +- **LogitechWheelPlugin\***: Required for Logitech Steering Wheel, optional otherwise + +(\* = optional, depends on the features you are looking for) + +## SteamVR + +### **Download Steam and SteamVR** + +- You'll need to use [SteamVR](https://store.steampowered.com/app/250820/SteamVR/) for the VR rendering environment, so you should first download the [Steam client application](https://store.steampowered.com/about/). + - From within the steam client, you can browse in store->search "[SteamVR](https://store.steampowered.com/app/250820/SteamVR/)" and download the free-to-install system utility. + + + +- You should be able to launch SteamVR from the client and in the small pop-up window reach both settings and "show VR view" + - Make sure to calibrate the VR system to your setup and preferences! +- Additionally we recommend disabling the "Motion Smoothing" effect within SteamVR Settings to avoid nasty distortion artifacts during rendering. + - SteamVR-settings + +--- + +## HTC Eye Tracker Plugin + +### **Download `SRanipal`** + +0. _What is SRanipal?_ + - We are using [HTC's SRanipal plugin](https://developer.vive.com/resources/vive-sense/sdk/vive-eye-tracking-sdk-sranipal/) as the means to communicate between Unreal Engine 4 and the Vive's Eye Tracker. + - To learn more about SRanipal and for **first-time-setup**, see this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC +1. You'll need a (free-to-create) [Vive developer account](https://hub.vive.com/sso/login) to download the following: + - a) [`VIVE_SRanipalInstaller_1.3.2.0.msi`](https://hub.vive.com/en-US/download/VIVE_SRanipalInstaller_1.3.2.0.msi) -- executable to install Tobii firmware + - b) [`SDK_v1.3.0s.0.zip`](https://github.com/scivi-tools/scivi.ue.board) -- includes the Unreal plugin + - **IMPORTANT**: The SRanipal versions above 1.3.6.0 are NOT supported and cause wild crashes! + - **If the download links above don't work for you, make sure you have a Vive Developer account! (Or [contact](mailto:gustavo@silvera.cloud) us directly to help you)** +2. Install the Tobii firmware by double-clicking the `.msi` installer + - Once installed, you should see the `SR_runtime.exe` program available from the Start Menu. Launch it as administrator and you should see the robot head icon in the Windows system tray as follows: + - ![SR_runtime](https://mariosbikos.com/wp-content/uploads/2020/02/image-30.png) + - Image Credit: [MariosBikos](https://forum.htc.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine) + +### **Installing SRanipal UE4 Plugin** + +- After downloading the `.zip` file, unzipping it should present a directory similar to this + - ``` + SDK + - 01_C/ + - 02_Unity/ + - 03_Unreal/ + - Eye_SRanipal_SDK_Guide.pdf + - Lip_SRanipal_SDK_Guide.pdf + ``` + - Then, unzip the SRanipal unreal plugin and copy over the `03_Unreal/Plugins/SRanipal/` directory to the Carla installation + - ```bash + # in SDK/ + cd 03_Unreal + unzip Vive-SRanipal-Unreal-Plugin.zip # creates the PLugins/SRanipal folder + # assumes CARLA_ROOT is defined, else just use your Carla path + cp -r Plugins/SRanipal $CARLA_ROOT/Unreal/CarlaUE4/Plugins/ + ``` +- It is recommended to re-calibrate the SRanipal eye tracker plugin for every new participant in an experiment. You can do this by entering SteamVR home, and clicking the small icon in the bottom menu bar to calibrate eye tracker to the headset wearer. + - ![Calibration](Figures/Install/steamvr-home.jpg) + - You can find more information by checking out this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC + +--- + +## Logitech Wheel Plugin + +### **Installing Logitech Wheel Plugin** + +- This is only for those who have a Logitech steering wheel/pedals driving setup. This hardware is not required to experience the VR experience (you can simply use keyboard/mouse) but greatly adds to the immersion and allows for granular analog controls. + - For reference, we used this [Logitech G923 Racing Wheel & Pedals](https://www.logitechg.com/en-us/products/driving/driving-force-racing-wheel.html). +- We'll be using this [LogitechWheelPlugin](https://github.com/HARPLab/LogitechWheelPlugin) to interact with UE4 and map hardware inputs to actions. + - Clone the repo and move the requisite folder to the Carla plugins folder + - ```bash + git clone https://github.com/HARPLab/LogitechWheelPlugin + mv LogitechWheelPlugin/LogitechWheelPlugin $CARLA_ROOT/Unreal/CarlaUE4/Plugins + ``` + - You should then see a Logitech Plugin enabled when you boot up the editor again: + - ![LogitechPlugin](Figures/Install/LogitechPlugin.jpg) + +--- + +## Sanity Check + +- After installing these plugins, you should see a `Unreal/CarlaUE4/Plugins` that looks like this: +- ``` + Plugins + ├── Carla # unchanged + │ └── ... + ├── CarlaExporter # unchanged + │ └── ... + ├── LogitechWheelPlugin # if installed + │ ├── Binaries + │ ├── Doc + │ ├── Logitech + │ ├── LogitechWheelPlugin.uplugin + │ ├── Resources + │ └── Source + └── SRanipal # if installed + ├── Binaries + ├── Config + ├── Content + ├── Resources + ├── Source + └── SRanipal.uplugin + ``` +- If you still have questions or issues, feel free to post an issue on our [Issues](https://github.com/HARPLab/DReyeVR/issues) page and we'll try our best to help you out. + +
+
+ +# Installing `DReyeVR` Core + + + +- **IMPORTANT** The installation requires that `make`, `python` and `git` are available on your shell. +- You only need to install to a `CARLA` directory, ScenarioRunner is optional. + - If you don't provide the `make` variables `CARLA=...` or `SR=...` the installation wizard will automatically detect your install destination by looking at the environment variables `CARLA_ROOT` and `SCENARIO_RUNNER_ROOT` required by Carla. + +```bash +# the CARLA= and SR= variables are optional +make install CARLA=../carla SR=../scenario_runner +# or +make install CARLA=../carla +make install SR=../scenario_runner + +# run filesystem checks after installing +make check CARLA=../carla +``` + +**NOTE:** to learn more about how the DReyeVR `make` system works, see [`Scripts/README.md`](../Scripts/README.md) + +# Building `DReyeVR` PythonAPI + +## Using [`conda`](https://www.anaconda.com/products/distribution) for the PythonAPI + +- While not required for DReyeVR, we highly recommend compartmentalizing Python installations via isolated environments such as [`anaconda`](https://www.anaconda.com/products/distribution) + - First download and install Anaconda to your machine from [here](https://www.anaconda.com/products/distribution). + +```bash +# in /PATH/TO/CARLA/ +conda create --name carla13 python=3.7.2 +conda activate carla13 # will need to run this ONCE before opening a new terminal! +conda install numpy +``` + +- **READ THIS FIRST (Linux)**: You might run into a problem when compiling Boost 1.72.0 (required by `LibCarla`). +
+ + Show instructions to get Anaconda working on Linux + + - ```bash + # find anaconda install: + which python3 + ... PATH/TO/ANACONDA/envs/carla/bin/python3 # example output + + # go to carla/install dir from here + cd PATH/TO/ANACONDA/envs/carla/include + + # create a symlink between python3.7 -> python3.7m + ln -s python3.7m python3.7 + ``` + + Install `boost_1_72_0.tar.gz` manually from https://github.com/jerry73204/carla/releases/tag/fix-boost and place file in `Build/boost_1_72_0.tar.gz` + Open `Util/BuildTools/Setup.sh` (or `Util/BuildTools/Setup.bat` on Windows) + Find the section named `Get boost` includes and comment out the `wget` lines. + Now when you `make LibCarla` again, the `boost` errors should be resolved. + + - For more information see the bottom of this [SO post](https://stackoverflow.com/questions/42839382/failing-to-install-boost-in-python-pyconfig-h-not-found) +
+ + - **READ THIS FIRST (Windows)**: Windows anaconda is a bit more of a pain to deal with. +
+ + Show instructions to get Anaconda working on Windows + + 1. Enable your environment + ```bat + conda activate carla13 + ``` + 2. Add carla to "path" to locate the PythonAPI and ScenarioRunner. But since Anaconda [does not use the traditional `PYTHONPATH`](https://stackoverflow.com/questions/37006114/anaconda-permanently-include-external-packages-like-in-pythonpath) you'll need to: + - 3.1. Create a file `carla.pth` in `\PATH\TO\ANACONDA\envs\carla\Lib\site-packages\` + - 3.2. Insert the following content into `carla.pth`: + ```bat + C:\PATH\TO\CARLA\PythonAPI\carla\dist + C:\PATH\TO\CARLA\PythonAPI\carla\agents + C:\PATH\TO\CARLA\PythonAPI\carla + C:\PATH\TO\CARLA\PythonAPI + C:\PATH\TO\CARLA\PythonAPI\examples + C:\PATH\TO\SCENARIO_RUNNER\ + ``` + 3. Install the specific carla wheel (`whl`) to Anaconda + + ```bash + conda activate carla13 + pip install --no-deps --force-reinstall PATH\TO\CARLA\PythonAPI\carla\dist\carla-0.9.13-cp37-cp37m-win_amd64.whl + + # if applicable (and you installed Scenario runner) + cd %SCENARIO_RUNNER_ROOT% + pip install -r requirements.txt # install all SR dependencies + ``` + + 4. Finally, you might run into problems with `shapely` (scenario-runner dependency) and Conda. Luckily the solution is simple: + - Copy the files: + - `PATH\TO\ANACONDA\envs\carla13\Lib\site-packages\shapely\DLLs\geos.dll` + - `PATH\TO\ANACONDA\envs\carla13\Lib\site-packages\shapely\DLLs\geos_c.dll` + - To destination: + - `PATH\TO\ANACONDA\envs\carla13\Library\bin\` + 5. Now finally, you should be able to verify all PythonAPI actions work as expected via: + ```bat + conda activate carla13 + python + >>> Python 3.7.2 (default, Feb 21 2019, 17:35:59) [MSC v.1915 64 bit (AMD64)] :: Anaconda, Inc. on win32 + >>> Type "help", "copyright", "credits" or "license" for more information. + >>> import carla + >>> from DReyeVR_utils import find_ego_vehicle + >>> from scenario_runner import ScenarioRunner + ``` + With all these imports passing (no error/warning messages), you're good to go! + +
+ +Now you can finally build the PythonAPI to this isolated conda environment. + +```bash +conda activate carla13 +(carla13) make PythonAPI # builds LibCarla and PythonAPI to your (conda) python environment +``` + +- NOTE: You'll need to run `conda activate carla13` every time you open a new terminal if you want to build DReyeVR since the shell needs to know which python environment to use. Luckily this minor inconvenience saves us from the significant headaches that arise when dealing with multiple `python` projects, Carla installations, and versions, etc. + +## Sanity Check: + +It is nice to verify that the Carla PythonAPI is correctly visible in conda, to do this you should see all the following attributes in the `carla` module once calling `dir` on it. + +
+Show instructions to verify Carla PythonAPI is installed + +```bash +# in your terminal (linux) or cmd (Windows) +conda activate carla13 # (if using conda) +(carla13) python # should default to python3!! +``` + +```python +#in Python +... +>>> import carla +>>> dir(carla) +# the following output means carla is not correctly installed :( +>>> ['__doc__', '__file__', '__loader__', '__name__', '__package__', '__path__', '__spec__'] + +# OR the following output means carla is installed :) +>>> ['Actor', 'ActorAttribute', 'ActorAttributeType', 'ActorBlueprint', 'ActorList', 'ActorSnapshot', 'ActorState', 'AttachmentType', 'BlueprintLibrary', 'BoundingBox', 'CityObjectLabel', 'Client', 'ClientSideSensor', 'CollisionEvent', 'Color', 'ColorConverter', 'DReyeVREvent', 'DVSEvent', 'DVSEventArray', 'DebugHelper', 'EnvironmentObject', 'FakeImage', 'FloatColor', 'GearPhysicsControl', 'GeoLocation', 'GnssMeasurement', 'IMUMeasurement', 'Image', 'Junction', 'LabelledPoint', 'Landmark', 'LandmarkOrientation', 'LandmarkType', 'LaneChange', 'LaneInvasionEvent', 'LaneInvasionSensor', 'LaneMarking', 'LaneMarkingColor', 'LaneMarkingType', 'LaneType', 'LidarDetection', 'LidarMeasurement', 'Light', 'LightGroup', 'LightManager', 'LightState', 'Location', 'Map', 'MapLayer', 'MaterialParameter', 'ObstacleDetectionEvent', 'OpendriveGenerationParameters', 'OpticalFlowImage', 'OpticalFlowPixel', 'Osm2Odr', 'Osm2OdrSettings', 'RadarDetection', 'RadarMeasurement', 'Rotation', 'SemanticLidarDetection', 'SemanticLidarMeasurement', 'Sensor', 'SensorData', 'ServerSideSensor', 'TextureColor', 'TextureFloatColor', 'Timestamp', 'TrafficLight', 'TrafficLightState', 'TrafficManager', 'TrafficSign', 'Transform', 'Vector2D', 'Vector3D', 'Vehicle', 'VehicleControl', 'VehicleDoor', 'VehicleLightState', 'VehiclePhysicsControl', 'VehicleWheelLocation', 'Walker', 'WalkerAIController', 'WalkerBoneControlIn', 'WalkerBoneControlOut', 'WalkerControl', 'Waypoint', 'WeatherParameters', 'WheelPhysicsControl', 'World', 'WorldSettings', 'WorldSnapshot', '__builtins__', '__cached__', '__doc__', '__file__', '__loader__', '__name__', '__package__', '__path__', '__spec__', 'bone_transform', 'bone_transform_out', 'command', 'libcarla', 'vector_of_bones', 'vector_of_bones_out', 'vector_of_gears', 'vector_of_ints', 'vector_of_transform', 'vector_of_vector2D', 'vector_of_wheels'] +``` + +
+ +
+ +## Future modifications + +Additionally, if you make changes to the `PythonAPI` source and need to rebuild (`make PythonAPI` again) when using Conda you should reinstall the `.whl` file to ensure your changes will be reflected in the environment: + +- ```bash + conda activate carla + + pip install --no-deps --force-reinstall /PATH/TO/CARLA/PythonAPI/carla/dist/carla-YOUR_VERSION.whl + ``` + +# Upgrading `DReyeVR` + +If you currently have an older version of `DReyeVR` installed and want to upgrade to a newer version, it is best to re-install DReyeVR from a fresh Carla repository. You can manually delete the `carla` repository and re-clone it directly (carefully ensuring the versions match) or use our provided scripts which attempt to reset the repository for you: + +
+ Show instructions to use DReyeVR scripts to reset CARLA repo + +**IMPORTANT:** the `DReyeVR` clean script will overwrite and reset the Carla repository you specify, so make your backups now if you have any unstaged code. (`git reset --hard HEAD` and `git clean -fd` will be invoked, so if you commit your local changes they will be safe) + +```bash +# first go to CARLA and clean it so no old DReyeVR builds linger +cd /PATH/TO/Carla/ +make clean + +# it is a good idea to clean the Content/ directory which is not tracked by Carla's git system +rm -rf Unreal/CarlaUE4/Content/ + +# re-install the Content fresh from Carla's servers +./Update.sh # Linux/Mac +Update.bat # Windows + +# next, go to DReyeVR and get the latest updates +cd /PATH/TO/DReyeVR/ +git pull origin main # or dev, or whatever branch + +# next, run the DReyeVR-cleaner to automatically hard-reset the Carla repo +# accept the prompt to hard-clean CARLA, note that this will reset tracked and remove untracked files +make clean CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional + +# now, you can cleanly install DReyeVR over Carla again +make install CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional + +# it's a good idea to check that the Carla repository has all the expected files +make check CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional + +# finally, you can go back to Carla and rebuild +cd /PATH/TO/Carla +make PythonAPI +make launch +make package +``` + +--- + +As long as you have no errors in the previous sections, you should be able to just build the `Carla` project with our `DReyeVR` files as follows: + +
+ +
+
+ +# Building `DReyeVR` UE4 + +If you are not interested in using SRanipal or the LogitechWheelPlugin, you can disable these at compile-time by changing the variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: + +```c# + ///////////////////////////////////////////////////////////// + // Edit these variables to enable/disable features of DReyeVR + bool UseSRanipalPlugin = true; + bool UseLogitechPlugin = true; + ... + ///////////////////////////////////////////////////////////// +``` + +Finally, open the project directory in any terminal (Linux/Mac) or `Windows x64 Native Tools Command Prompt for VS 2019` (Windows) and run: + +```bash +make PythonAPI # build the PythonAPI & LibCarla + +make launch # build the development UE4 game in editor + +make package # build the optimized UE4 packaged game (shipping), if error with this command, comment lines 151-153, 163-165 in carla/LibCarla/source/test/server/test_benchmark_streaming.cpp +``` + +# Running `DReyeVR` + +With the shipping package built, run the Carla (with DReyeVR installed) executable in VR mode with: + +```bash +# on Unix +cd /PATH/TO/CARLA/Dist/CARLA_Shipping_0.9.13-dirty/LinuxNoEditor/ # or MacNoEditor on MacOS +./CarlaUE4.sh -vr + +# on Windows x64 Visual C++ Toolset +cd \PATH\TO\CARLA\Build\UE4Carla\0.9.13-dirty\WindowsNoEditor\ +CarlaUE4.exe -vr +# CarlaUE4.exe -vr -quality-level=Low +# Optional flag: -quality-level=Low +``` + +**NOTE:** To greatly boost the framerates without losing much visual fidelity you can run with the additional argument `-quality-level=Low` which we modified from vanilla Carla to preserve the same rendering distance. + +**NOTE 2** You also don't necessarily NEED to run DReyeVR in VR. If you omit the `-vr` flag then you will be greeted with a flat-screen Carla game with the same features available for DReyeVR, just not in VR. + +
+ +# Now what? + +Now that you've successfully installed DReyeVR continue to [`Usage.md`](Usage.md) to learn how to use DReyeVR for your own VR driving research simulator. diff --git a/Docs/Install_Ubuntu.md b/Docs/Install_Ubuntu.md index 5dc7d73..f16ccc5 100644 --- a/Docs/Install_Ubuntu.md +++ b/Docs/Install_Ubuntu.md @@ -1,120 +1,120 @@ -# Installing Carla on Ubuntu 20.04 -This guide is for installing Carla 0.9.13 (along with Unreal Engine 4.26) build on Ubuntu 20.04.5 (Focal Fosca). It is largely based on [this tutorial](https://carla.readthedocs.io/en/latest/build_linux/) by Carla, and can be thought of as a shorter updated of it specifically for Ubuntu 20.04 and DReyeVR. Check out the original tutorial tutorial for more detailed explanations of some the commands. Commands themselves, however, slightly differ from the original version. - -## Part One: Prerequisites -- **Ubuntu 20.04** -- **130 GB disk space.** Carla will take around 31 GB and Unreal Engine will take around 91 GB so have about 130 GB free to account for both of these plus additional minor software installations. -- **An adequate GPU**. CARLA aims for realistic simulations, so the server needs at least a 6 GB GPU although 8 GB is recommended. A dedicated GPU is highly recommended for machine learning. -- **Two TCP ports and good internet connection.** 2000 and 2001 by default. Make sure that these ports are not blocked by firewalls or any other applications. -- **IMPORTANT: Proprietary drivers installed.** Please make sure that you are using the latest stable version of proprietary drivers (for instance, Nvidia). Check [this guide](https://linuxconfig.org/how-to-install-the-nvidia-drivers-on-ubuntu-20-04-focal-fossa-linux) for installing and updating the Nvidia driver on Ubuntu 20.04. - -## Installing software requirements -Please use the following set of commands to install the necessary software packages. -**Note**: you might want to go over each of the listed packages separately to ensure that each was installed correctly to avoid issues during the installation. Later on, the missing packages will be harder to track. -```bash -sudo apt-add-repository "deb http://apt.llvm.org/focal/ llvm-toolchain-focal main" -sudo apt-get install build-essential clang-8 lld-8 g++-7 cmake ninja-build libvulkan1 python-dev python3-dev python3-pip libpng-dev libtiff5-dev libjpeg-dev tzdata sed curl unzip autoconf libtool rsync libxml2-dev git -sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-8/bin/clang++ 180 && -sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-8/bin/clang 180 -``` - -#### Clang issue: -One of the issues specific to Ubuntu 20.04 installation is the **clang** compiler. The CARLA team uses clang-8 and LLVM's libc++. while clang-8 can be installed on Ubuntu 20.04, it is rather outdated and does not catch some of the existing bugs within carla. If you want to use a different version of clang and libc++, follow the instructions below: -
-how to use a different clang version -Uninstall clang-8 (installed if you executed the previous command): - -```bash -sudo apt-get remove clang-8 lld-8 -sudo rm /usr/bin/clang /usr/bin/clang++ -``` - -Install version 10: -```bash -sudo apt-get install clang-10 lld-10 -``` -Set up clang and clang++ commands: -```bash -sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-10/bin/clang++ 180 && -sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-10/bin/clang 180 -``` -Create a symbolic link that would tell the system to use version 10 whenever it encounters `usr/bin/clang-8` in one of the CARLA setup or installation scripts: -```bash -sudo ln -s /usr/bin/clang /usr/bin/clang-8 -sudo ln -s /usr/bin/clang++ /usr/bin/clang++-8 -``` -
-
- - -### Python dependencies -Version 20.3 or higher of **pip3** is required. To check if you have a suitable version, run the following command: -```bash -pip3 -V -``` -If you need to upgrade: -```bash -pip3 install --upgrade pip -``` -You might be prompted to add the directory of the newer version to PATH. If yes, do so. - -You must install the following Python dependencies: -``` -pip3 install --user -Iv setuptools==47.3.1 && -pip3 install --user distro && -pip3 install --user wheel auditwheel && -pip3 install nose2 -``` -Some of the installation and setup scripts use the deprecated **python** command. One way to avoid the issues caused by this is with a symbolic link: -``` -sudo ln -s /usr/bin/python3 /usr/bin/python -``` -If your file is named other than **python3**, substitute python 3 for your python version. -
- -### Unreal Engine -This section does not require updates or modifications. Please follow the exact steps from the corresponding section of [this tutorial](https://carla.readthedocs.io/en/latest/build_linux/). -
- -## Part Two: Build CARLA -**Note**: downloading aria2 with `sudo apt-get install aria2` will speed up the following commands. - -Clone the CARLA repository: -```bash -git clone https://github.com/carla-simulator/carla -b 0.9.13 -``` -Once download is finished, from the new **carla** directory, run -```bash -Update.sh -``` - -Navigate to the **carla** directory. Open **./Util/BuildTools/Setup.sh** and replace `XERCESC_VERSION=3.2.3` (line 428) with `XERCESC_VERSION=3.2.4`. Next, open **./Util/BuildTools/BuildOSM2ODR.sh**, and replace all instances of `xerces-c-3.2.3` with `xerces-c-3.2.4`. - - -Follow the rest of the instructions from the [tutorial](https://carla.readthedocs.io/en/latest/build_linux/). - - -Now that you have a working CARLA 0.9.13 build, go back to the [DReyeVR installation guide](https://github.com/HARPLab/DReyeVR/blob/main/Docs/Install.md) and follow the rest of the steps to install DReyeVR on top of it. - -- **READ THIS FIRST (Linux)**: You might run into a problem when compiling Boost 1.72.0 (required by `LibCarla`). -
- - Show instructions to get Anaconda working on Linux - - - ```bash - # find anaconda install: - which python3 - ... PATH/TO/ANACONDA/envs/carla/bin/python3 # example output - - # go to carla/install dir from here - cd PATH/TO/ANACONDA/envs/carla/include - - # create a symlink between python3.7 -> python3.7m - ln -s python3.7m python3.7 - ``` - Install `boost_1_72_0.tar.gz` manually from https://github.com/jerry73204/carla/releases/tag/fix-boost and place file in `Build/boost_1_72_0.tar.gz` - Open `Util/BuildTools/Setup.sh` (or `Util/BuildTools/Setup.bat` on Windows) - Find the section named `Get boost` includes and comment out the `wget` lines. - Now when you `make LibCarla` again, the `boost` errors should be resolved. - - For more information see the bottom of this [SO post](https://stackoverflow.com/questions/42839382/failing-to-install-boost-in-python-pyconfig-h-not-found) -
+# Installing Carla on Ubuntu 20.04 +This guide is for installing Carla 0.9.13 (along with Unreal Engine 4.26) build on Ubuntu 20.04.5 (Focal Fosca). It is largely based on [this tutorial](https://carla.readthedocs.io/en/latest/build_linux/) by Carla, and can be thought of as a shorter updated of it specifically for Ubuntu 20.04 and DReyeVR. Check out the original tutorial tutorial for more detailed explanations of some the commands. Commands themselves, however, slightly differ from the original version. + +## Part One: Prerequisites +- **Ubuntu 20.04** +- **130 GB disk space.** Carla will take around 31 GB and Unreal Engine will take around 91 GB so have about 130 GB free to account for both of these plus additional minor software installations. +- **An adequate GPU**. CARLA aims for realistic simulations, so the server needs at least a 6 GB GPU although 8 GB is recommended. A dedicated GPU is highly recommended for machine learning. +- **Two TCP ports and good internet connection.** 2000 and 2001 by default. Make sure that these ports are not blocked by firewalls or any other applications. +- **IMPORTANT: Proprietary drivers installed.** Please make sure that you are using the latest stable version of proprietary drivers (for instance, Nvidia). Check [this guide](https://linuxconfig.org/how-to-install-the-nvidia-drivers-on-ubuntu-20-04-focal-fossa-linux) for installing and updating the Nvidia driver on Ubuntu 20.04. + +## Installing software requirements +Please use the following set of commands to install the necessary software packages. +**Note**: you might want to go over each of the listed packages separately to ensure that each was installed correctly to avoid issues during the installation. Later on, the missing packages will be harder to track. +```bash +sudo apt-add-repository "deb http://apt.llvm.org/focal/ llvm-toolchain-focal main" +sudo apt-get install build-essential clang-8 lld-8 g++-7 cmake ninja-build libvulkan1 python-dev python3-dev python3-pip libpng-dev libtiff5-dev libjpeg-dev tzdata sed curl unzip autoconf libtool rsync libxml2-dev git +sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-8/bin/clang++ 180 && +sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-8/bin/clang 180 +``` + +#### Clang issue: +One of the issues specific to Ubuntu 20.04 installation is the **clang** compiler. The CARLA team uses clang-8 and LLVM's libc++. while clang-8 can be installed on Ubuntu 20.04, it is rather outdated and does not catch some of the existing bugs within carla. If you want to use a different version of clang and libc++, follow the instructions below: +
+how to use a different clang version +Uninstall clang-8 (installed if you executed the previous command): + +```bash +sudo apt-get remove clang-8 lld-8 +sudo rm /usr/bin/clang /usr/bin/clang++ +``` + +Install version 10: +```bash +sudo apt-get install clang-10 lld-10 +``` +Set up clang and clang++ commands: +```bash +sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-10/bin/clang++ 180 && +sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-10/bin/clang 180 +``` +Create a symbolic link that would tell the system to use version 10 whenever it encounters `usr/bin/clang-8` in one of the CARLA setup or installation scripts: +```bash +sudo ln -s /usr/bin/clang /usr/bin/clang-8 +sudo ln -s /usr/bin/clang++ /usr/bin/clang++-8 +``` +
+
+ + +### Python dependencies +Version 20.3 or higher of **pip3** is required. To check if you have a suitable version, run the following command: +```bash +pip3 -V +``` +If you need to upgrade: +```bash +pip3 install --upgrade pip +``` +You might be prompted to add the directory of the newer version to PATH. If yes, do so. + +You must install the following Python dependencies: +``` +pip3 install --user -Iv setuptools==47.3.1 && +pip3 install --user distro && +pip3 install --user wheel auditwheel && +pip3 install nose2 +``` +Some of the installation and setup scripts use the deprecated **python** command. One way to avoid the issues caused by this is with a symbolic link: +``` +sudo ln -s /usr/bin/python3 /usr/bin/python +``` +If your file is named other than **python3**, substitute python 3 for your python version. +
+ +### Unreal Engine +This section does not require updates or modifications. Please follow the exact steps from the corresponding section of [this tutorial](https://carla.readthedocs.io/en/latest/build_linux/). +
+ +## Part Two: Build CARLA +**Note**: downloading aria2 with `sudo apt-get install aria2` will speed up the following commands. + +Clone the CARLA repository: +```bash +git clone https://github.com/carla-simulator/carla -b 0.9.13 +``` +Once download is finished, from the new **carla** directory, run +```bash +Update.sh +``` + +Navigate to the **carla** directory. Open **./Util/BuildTools/Setup.sh** and replace `XERCESC_VERSION=3.2.3` (line 428) with `XERCESC_VERSION=3.2.4`. Next, open **./Util/BuildTools/BuildOSM2ODR.sh**, and replace all instances of `xerces-c-3.2.3` with `xerces-c-3.2.4`. + + +Follow the rest of the instructions from the [tutorial](https://carla.readthedocs.io/en/latest/build_linux/). + + +Now that you have a working CARLA 0.9.13 build, go back to the [DReyeVR installation guide](https://github.com/HARPLab/DReyeVR/blob/main/Docs/Install.md) and follow the rest of the steps to install DReyeVR on top of it. + +- **READ THIS FIRST (Linux)**: You might run into a problem when compiling Boost 1.72.0 (required by `LibCarla`). +
+ + Show instructions to get Anaconda working on Linux + + - ```bash + # find anaconda install: + which python3 + ... PATH/TO/ANACONDA/envs/carla/bin/python3 # example output + + # go to carla/install dir from here + cd PATH/TO/ANACONDA/envs/carla/include + + # create a symlink between python3.7 -> python3.7m + ln -s python3.7m python3.7 + ``` + Install `boost_1_72_0.tar.gz` manually from https://github.com/jerry73204/carla/releases/tag/fix-boost and place file in `Build/boost_1_72_0.tar.gz` + Open `Util/BuildTools/Setup.sh` (or `Util/BuildTools/Setup.bat` on Windows) + Find the section named `Get boost` includes and comment out the `wget` lines. + Now when you `make LibCarla` again, the `boost` errors should be resolved. + - For more information see the bottom of this [SO post](https://stackoverflow.com/questions/42839382/failing-to-install-boost-in-python-pyconfig-h-not-found) +
diff --git a/Docs/Tutorials/CustomActor.md b/Docs/Tutorials/CustomActor.md index 80645bd..a84b50d 100644 --- a/Docs/Tutorials/CustomActor.md +++ b/Docs/Tutorials/CustomActor.md @@ -1,105 +1,105 @@ -# DReyeVR custom actors - -## What? -We are often interested in spawning arbitrary "AR-like" (Augmented reality) elements in the simulator at runtime that can be completely recorded and reenacted without hassle. - -### Example: 3D Bounding Boxes -- With a translucent (Opacity < 1) material we can simply create an elongated Cube actor and overlay it over any extent as a simple BBOX indicator. - - We can have the actor track the extent, so it can follow a vehicle/pedestrian/anything and not interfere with physics at all (physics simulation is disabled). - - Psst! this is actually already mostly implemented (but disabled) in the code, check out the [example at the bottom](CustomActor.md#bounding-box-example) - -### Example: Gaze lines -- If you want to draw the eye gaze rays in realtime (without using `DrawDebugLine`, which is editor-only), you can simply use an elongated cube as a "ray" from the user gaze origin to the world-space gaze target. - -### Example: Debug trails -- Similar to the debug path in Carla, spawning a trail of dynamic spheres can be useful to draw AR-like guidelines in the world and help direct drivers through the map. - -## Why? -1. Having each "CustomActor" be its own entity (not necessarily tied to the EgoVehicle/EgoSensor) allows it to be recorded with the CARLA recorder easily and without modifying the core DReyeVR data. This is important when we want to change the API of the recorder (which happens quite often) but don't want to lose data from previous experiments that have data recordings (in binary format) that we can't modify easily. -2. Abstracting the "CustomActor"s gives us plenty of flexibility for manipulating the actors in the simulator at runtime and allows for new interesting scenarios to be performed easily without worry of recording/replay. - - -# Usage - -Using these CustomActors is designed to be straightforward and cooperate with UE4/Carla's notion of [AActors](https://docs.unrealengine.com/5.0/en-US/API/Runtime/Engine/GameFramework/AActor/). You can see how we define all the core data for these actors (and what gets recorded/replayed) in [`DReyeVRData.h`](../../Carla/Sensor/DReyeVRData.h)`::CustomActorData` - -We have several basic 3D shapes ready for simple CustomActor usage. Theoretically you can use any static mesh. To access these types (or add your own) you should check out the references in [`DReyeVRCustomActor.h`](../../Carla/Actor/DReyeVRCustomActor.h): -```c++ -#define MAT_OPAQUE "Material'/Game/DReyeVR/Custom/OpaqueParamMaterial.OpaqueParamMaterial'" -#define MAT_TRANSLUCENT "Material'/Game/DReyeVR/Custom/TranslucentParamMaterial.TranslucentParamMaterial'" -#define SM_SPHERE "StaticMesh'/Engine/BasicShapes/Sphere.Sphere'" -#define SM_CUBE "StaticMesh'/Engine/BasicShapes/Cube.Cube'" -#define SM_CONE "StaticMesh'/Engine/BasicShapes/Cone.Cone'" - -// add a new string literal here -#define SM_CUSTOM_MESH "StaticMesh'/Path/To/Your/StaticMesh.StaticMesh'" -``` - -## Spawn a custom actor - -```c++ -#include "Carla/Actor/DReyeVRCustomActor.h" -... -// example parameters, you can change these to whavever you'd like -FString PathToSM = SM_CUBE; -FString PathToMat = MAT_TRANSLUCENT; -FString Name = "NewActorName"; // every actor needs a unique name! -UWorld *World = GetWorld(); -ADReyeVRCustomActor *A = ADReyeVRCustomActor::CreateNew(PathToSM, PathToMaterial, World, Name); -``` - -Implementation wise, the custom actors are all managed by a "global" table (`static std::unordered_map`) that indexes the actors by their `Name` therefore it is critical that they all have unique names. This is often easy to do when spawning many since UE4 `AActor`s themselves have unique names enumerated by their spawn order. To further understand how we use the global table, check out `ADReyeVRCustomActor::ActiveCustomActors` in [`DReyevRCustomActor.h`](../../Carla/Actor/DReyeVRCustomActor.h) - -## Activate/deactivate a custom actor - -To activate (see in the world) simply run -```c++ -A->Activate(); -``` -This will ensure every tick of this actor will be recorded with the Carla recorder. - -Similarly, to deactivate the actor (disable visibility, recording, and tick function) do: -```c++ -A->Deactivate(); -``` - -You can check whether or not an actor is "active" with `A->IsActive()`. While true (the actor is active) the actor will automatically be recorded in the CARLA recorder which will allow replaying without hassle. - -## Update a custom actor -These methods come from the UE4 `AActor` base class, which our class inherits from and extends. -```c++ -// resize the actor -A->SetActorScale3D(FVector(1, 1, 0.5)); - -// move the actor -A->SetActorLocation(FVector(100, 200, 0)); - -// rotate the actor -A->SetActorRotation(FRotator(90, 45, 0)); -``` - -Assuming you are using one of the param-materials we provide for you, you can also modify the material parameters and have them take effect in realtime: -```c++ -// change vector properties -A->MaterialParams.BaseColor = FLinearColor(1, 0, 0, 1); // RGBA -A->MaterialParams.Emissive = 100.f * FLinearColor(1, 0, 0, 1); // RGBA - -// change scalar properties -A->MaterialParams.Metallic = 0.f; -A->MaterialParams.Specular += 0.15f; -A->MaterialParams.Roughness = 1.f; -A->MaterialParams.Anisotropy = 0.5f; -``` - -Note that in order to use the `Opacity` property, the material needs to have a translucent blend mode. So far we only have two material types, opaque and translucent, each with their own set of available properties as follows: -| OpaqueParamMaterial | TranslucentParamMaterial | -| --- | --- | -| ![OpaqueMaterial](../Figures/Actor/OpaqueParamMaterial.jpg) | ![OpaqueMaterial](../Figures/Actor/TranslucentParamMaterial.jpg) | - -## Bounding Box Example - -As an example of the CustomActor bounding boxes in action, checkout [`LevelScript.cpp::DrawBBoxes`](../../DReyeVR/LevelScript.cpp) where some simple logic for drawing translucent bounding boxes is held (coloured based on distance to EgoVehicle). To enable this function, you'll need to manually enable it by removing the `#if 0` and corresponding `#endif` around the function body. - -Here is what it might look like in action: - +# DReyeVR custom actors + +## What? +We are often interested in spawning arbitrary "AR-like" (Augmented reality) elements in the simulator at runtime that can be completely recorded and reenacted without hassle. + +### Example: 3D Bounding Boxes +- With a translucent (Opacity < 1) material we can simply create an elongated Cube actor and overlay it over any extent as a simple BBOX indicator. + - We can have the actor track the extent, so it can follow a vehicle/pedestrian/anything and not interfere with physics at all (physics simulation is disabled). + - Psst! this is actually already mostly implemented (but disabled) in the code, check out the [example at the bottom](CustomActor.md#bounding-box-example) + +### Example: Gaze lines +- If you want to draw the eye gaze rays in realtime (without using `DrawDebugLine`, which is editor-only), you can simply use an elongated cube as a "ray" from the user gaze origin to the world-space gaze target. + +### Example: Debug trails +- Similar to the debug path in Carla, spawning a trail of dynamic spheres can be useful to draw AR-like guidelines in the world and help direct drivers through the map. + +## Why? +1. Having each "CustomActor" be its own entity (not necessarily tied to the EgoVehicle/EgoSensor) allows it to be recorded with the CARLA recorder easily and without modifying the core DReyeVR data. This is important when we want to change the API of the recorder (which happens quite often) but don't want to lose data from previous experiments that have data recordings (in binary format) that we can't modify easily. +2. Abstracting the "CustomActor"s gives us plenty of flexibility for manipulating the actors in the simulator at runtime and allows for new interesting scenarios to be performed easily without worry of recording/replay. + + +# Usage + +Using these CustomActors is designed to be straightforward and cooperate with UE4/Carla's notion of [AActors](https://docs.unrealengine.com/5.0/en-US/API/Runtime/Engine/GameFramework/AActor/). You can see how we define all the core data for these actors (and what gets recorded/replayed) in [`DReyeVRData.h`](../../Carla/Sensor/DReyeVRData.h)`::CustomActorData` + +We have several basic 3D shapes ready for simple CustomActor usage. Theoretically you can use any static mesh. To access these types (or add your own) you should check out the references in [`DReyeVRCustomActor.h`](../../Carla/Actor/DReyeVRCustomActor.h): +```c++ +#define MAT_OPAQUE "Material'/Game/DReyeVR/Custom/OpaqueParamMaterial.OpaqueParamMaterial'" +#define MAT_TRANSLUCENT "Material'/Game/DReyeVR/Custom/TranslucentParamMaterial.TranslucentParamMaterial'" +#define SM_SPHERE "StaticMesh'/Engine/BasicShapes/Sphere.Sphere'" +#define SM_CUBE "StaticMesh'/Engine/BasicShapes/Cube.Cube'" +#define SM_CONE "StaticMesh'/Engine/BasicShapes/Cone.Cone'" + +// add a new string literal here +#define SM_CUSTOM_MESH "StaticMesh'/Path/To/Your/StaticMesh.StaticMesh'" +``` + +## Spawn a custom actor + +```c++ +#include "Carla/Actor/DReyeVRCustomActor.h" +... +// example parameters, you can change these to whavever you'd like +FString PathToSM = SM_CUBE; +FString PathToMat = MAT_TRANSLUCENT; +FString Name = "NewActorName"; // every actor needs a unique name! +UWorld *World = GetWorld(); +ADReyeVRCustomActor *A = ADReyeVRCustomActor::CreateNew(PathToSM, PathToMaterial, World, Name); +``` + +Implementation wise, the custom actors are all managed by a "global" table (`static std::unordered_map`) that indexes the actors by their `Name` therefore it is critical that they all have unique names. This is often easy to do when spawning many since UE4 `AActor`s themselves have unique names enumerated by their spawn order. To further understand how we use the global table, check out `ADReyeVRCustomActor::ActiveCustomActors` in [`DReyevRCustomActor.h`](../../Carla/Actor/DReyeVRCustomActor.h) + +## Activate/deactivate a custom actor + +To activate (see in the world) simply run +```c++ +A->Activate(); +``` +This will ensure every tick of this actor will be recorded with the Carla recorder. + +Similarly, to deactivate the actor (disable visibility, recording, and tick function) do: +```c++ +A->Deactivate(); +``` + +You can check whether or not an actor is "active" with `A->IsActive()`. While true (the actor is active) the actor will automatically be recorded in the CARLA recorder which will allow replaying without hassle. + +## Update a custom actor +These methods come from the UE4 `AActor` base class, which our class inherits from and extends. +```c++ +// resize the actor +A->SetActorScale3D(FVector(1, 1, 0.5)); + +// move the actor +A->SetActorLocation(FVector(100, 200, 0)); + +// rotate the actor +A->SetActorRotation(FRotator(90, 45, 0)); +``` + +Assuming you are using one of the param-materials we provide for you, you can also modify the material parameters and have them take effect in realtime: +```c++ +// change vector properties +A->MaterialParams.BaseColor = FLinearColor(1, 0, 0, 1); // RGBA +A->MaterialParams.Emissive = 100.f * FLinearColor(1, 0, 0, 1); // RGBA + +// change scalar properties +A->MaterialParams.Metallic = 0.f; +A->MaterialParams.Specular += 0.15f; +A->MaterialParams.Roughness = 1.f; +A->MaterialParams.Anisotropy = 0.5f; +``` + +Note that in order to use the `Opacity` property, the material needs to have a translucent blend mode. So far we only have two material types, opaque and translucent, each with their own set of available properties as follows: +| OpaqueParamMaterial | TranslucentParamMaterial | +| --- | --- | +| ![OpaqueMaterial](../Figures/Actor/OpaqueParamMaterial.jpg) | ![OpaqueMaterial](../Figures/Actor/TranslucentParamMaterial.jpg) | + +## Bounding Box Example + +As an example of the CustomActor bounding boxes in action, checkout [`LevelScript.cpp::DrawBBoxes`](../../DReyeVR/LevelScript.cpp) where some simple logic for drawing translucent bounding boxes is held (coloured based on distance to EgoVehicle). To enable this function, you'll need to manually enable it by removing the `#if 0` and corresponding `#endif` around the function body. + +Here is what it might look like in action: + ![BboxExample](../Figures/Actor/Bbox.jpg) \ No newline at end of file diff --git a/Docs/Tutorials/CustomEgo.md b/Docs/Tutorials/CustomEgo.md index b69b85d..1ed3364 100644 --- a/Docs/Tutorials/CustomEgo.md +++ b/Docs/Tutorials/CustomEgo.md @@ -1,129 +1,129 @@ -# How to add your own EgoVehicle - -A guide from how to add your own custom EgoVehicle from an existing Carla vehicle that you can then use in DReyeVR. Showcasing the minimal required steps to add an **ambulance** to be the new DReyeVR EgoVehicle. - -## Prerequisites: -- You should have DReyeVR installed and functioning correctly -- You should probably take a look at [Model.md](Model.md) in case you want to modify the static mesh of your new vehicle: - - Ex. creating high-poly mirror meshes - - Ex. detatching the steering wheel for use as a dynamic prop (moves with the animation) - -## 1. Choose which vehicle to add -1. Since the DReyeVR EgoVehicle is a child-instance of the `ACarlaWheeledVehicle`, you should use a Carla vehicle for the base class of your desired Vehicle. For this tutorial we will use the Ambulance as an example, but any Carla vehicle should do fine. - - For Vehicle `XYZ` - - The blueprint files are located in `Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/XYZ/BP_XYZ.uasset` - - The static mesh files are located in `Unreal/CarlaUE4/Content/Carla/Static/Vehicles/XWheeled/XYZ/` -2. Once you have decided on a vehicle, create this structure by copying (in Unreal Editor) the blueprint file. - - Do the same with any other mesh components that you'll want to add. - - You'll want the file structure to match the existing EgoVehicles: - ``` - CarlaUE4/Content/DReyeVR/ - ├── EgoVehicle - │   ├── Extra - │   ├── Jeep - │   ├── Mustang66 - │   ├── Ambulance # <-- your new EgoVehicle - │   ├── TeslaM3 # <-- default for DReyeVR - │   └── Vespa - ... - ``` - - Inside your `XYZ/` folder, you'll want to copy your new BP_XYZ asset (do this from the editor so that cached paths can be updated) and create any additional folders in here that you might want (ex. `Mesh`, `Mirrors`, `SteeringWheel`, `Tires`, are a few examples). - - It is best to perform these asset file modifications within the Editor. You can copy the files from within the content browser to other folders by click+dragging to get this pop-up: - - ![CopyHere](../Figures/EgoVehicle/CopyHere.jpg) - -**NOTE**: If you want to edit the vehicle mesh at all, this is where you'd want to do it. You will probably want to build off the existing static meshes in the `Static` directory. - -## 2. Reparent the vehicle blueprint -(For the sake of this tutorial, we'll assume the `XYZ=Ambulance`) -1. Open the `Content/DReyeVR/EgoVehicle/Ambulance/BP_Ambulance` asset you just copied from the content browser -2. Select `Class Defaults` then in the top right (`Class Options`) select the `Parent Class` and search for `EgoVehicle` to reparent (as in the figure below). This effectively reorganizes the blueprint's base class from `BaseVehiclePawn` (the Carla default) to `EgoVehicle` (the DReyeVR C++ class, which still inherits from BaseVehiclePawn). - - There will be a warning pop-up regarding data loss, you should proceed (it is purely additive). - - **NOTE** if the blueprint ever gets corrupted, you should first try reparenting back to the `BaseVehiclePawn` (the original parent) and then back to the DReyeVR `EgoVehicle`. - - ![EditClass](../Figures/EgoVehicle/EditClassSettings.jpg) - - Demonstrating class setting button, used to edit this BP's class instance - - ![Reparent](../Figures/EgoVehicle/Reparent.jpg) - - Demonstrating the reparenting button, select the dropdown and search for a compatible class to reparent with `BaseVehiclePawn` (Carla) or `EgoVehicle` (DReyeVR). -3. Now this vehicle is technically a DReyeVR EgoVehicle! - -## 3. Add the new config file and code -Now, to actually register this new blueprint with DReyeVR and have it available to spawn you'll need to add two bits to the code: - -1. Add the name of your new vehicle (for example `"Ambulance"` for the `BP_Ambulance` blueprint we inherited) to the list of available EgoVehicles in [`DReyeVRFactory.h`](../../DReyeVR/DReyeVRFactory.h). - ```c++ - // place the names of all your new custom EgoVehicle types here: - /// IMPORTANT: make sure these match the ConfigFile AND Blueprint!! - // We expect Config/EgoVehicle/XYZ.ini and Content/DReyeVR/EgoVehicles/XYZ/BP_XYZ.uasset - const std::vector VehicleTypes = { - "TeslaM3", // Tesla Model 3 (Default) - "Mustang66", // Mustang66 - "Jeep", // JeepWranglerRubicon - "Vespa" // Vespa (2WheeledVehicles) - "Ambulance", // <-- the new vehicle! (for this tutorial) - // add more here - }; - ``` -2. Add a new config file (to `Unreal/CarlaUE4/Config/EgoVehicles/`) that is used to parameterize this vehicle. This allows DReyeVR to know where to place things such as the camera root location (driver's seat), mirrors, steering wheel, etc. and this [`ConfigFile`](../../DReyeVR/ConfigFile.h) can be extended to support many run-time combinations. - - You'll need to make sure the config file has the EXACT same name as your new EgoVehicle (this is how they are read). We recommend copying an existing config file (default is `TeslaM3.ini` and renaming as follows): - ``` - CarlaUE4/Config/ - ├── ... - ├── DReyeVRConfig.ini - ├── ... - ├── EgoVehicles/ - │   ├── Jeep.ini - │   ├── Mustang66.ini - │   ├── Ambulance.ini # <-- your new file! - │   ├── TeslaM3.ini - │   └── Vespa.ini - ├── ... - ... - ``` - - Then you'll probably want to edit some of the contents of this file to match the EgoVehicle specifications which you can get from the Editor. For instance, the following figure shows that we are going to want to move the VRCameraRoot (head position) to (`108, -40, 158`). - - ![CameraRepos](../Figures/EgoVehicle/CameraReposition.jpg) - - You'll probably also want to move the dashboard elements around to whatever fits your preference. - - **IMPORTANT** You also need to enable the `Start with Tick Enabled` for the Blueprint (`BP_Ambulance` in the Components list) because by default they are disabled for Carla vehicles: - - ![ActorTick](../Figures/EgoVehicle/ActorTick.jpg) - - You should also notice that assets such as the SteeringWheel & Mirrors don't have any assigned static mesh. You can access these by clicking the component (on the left hierarchy) and assigning a new static mesh (on the right details pane). This bakes the asset directly in the blueprint file, so this only needs to be done once. - | Example: Mirrors | Example: Steering wheel | - | --- | --- | - | ![Mirrors](../Figures/EgoVehicle/SM_Mirror.jpg) | ![Wheel](../Figures/EgoVehicle/SM_Wheel.jpg) - - Now, open the `Ambulance.ini` file you just created and begin updating the fields (mostly transforms) to match the parameters you care about. Importantly, for the `[Blueprint]::Path` entry, you'll get this path by right-clicking on the Blueprint in the content viewer and selecting `Copy Reference`. - - ![CopyRef](../Figures/EgoVehicle/CopyRef.jpg) - - Note that transforms are encoded as follows - ```ini - # Format: Location XYZ in CM | Rotation Roll/Pitch/Yaw in Degrees | Scale XYZ percent (1=100%) - ExampleTransform=(X=0.0, Y=0.0, Z=3.0 | R=-45, P=90.0, Y=0 | X=1, Y=1, Z=1) - ``` - -## 4. Set the new vehicle to be the DReyeVR default -In the `DReyeVRConfig.ini` general configuration file (for non-vehicle specific parameters) you should set what Vehicle to spawn in by default. This takes the name of the vehicles, which for this example is `Ambulance`. - -```ini -[EgoVehicle] -VehicleType="Ambulance" -``` - -And thats it! You should now be able to relaunch `make launch` and when you press Play you'll start in your new EgoVehicle. - - -## 4. [Optional] Create a new animation -Sometimes, especially when modifying the meshes in blender and exporting/importing them back into Unreal Engine, the vanilla animation asset can get somewhat mangled and not work properly. You will know if the animation is failing if the tires (and steering wheel, if you added one) are not turning while the EgoVehicle is moving. - -See Carla's corresponding documentation [here](https://carla.readthedocs.io/en/latest/tuto_A_add_vehicle/#import-and-configure-the-vehicle). - -**NOTE** This only works for 4WheeledVehicles as of testing. 2WheeledVehicles are more complicated and not covered in this tutorial. - -### Steps to create a new animation blueprint for Carla/DReyeVR -1. Create a new Animation Blueprint in the Ambulance/Mesh directory (if you have one, else make a new folder `Mesh/` inside `Ambulance`). -- ![CreateAnim](../Figures/EgoVehicle/CreateAnim.jpg) -2. Make sure the parent of the animation mesh is set to `VehicleAnimInstance` and the preview skeleton is set to the skeletal mesh of your new vehicle (ex. `SK_Ambulance_Skeleton`) -- ![CreateAnimBP](../Figures/EgoVehicle/CreateAnimBP.jpg) -3. Name your new asset to something like `Anim_Ambulance` and open it up. Open the AnimationGraph in the bottom right as shown: -- ![AnimGraph](../Figures/EgoVehicle/AnimGraph.jpg) -4. Open another nearby animation blueprint (ex. `Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Animation_model3`) and open its AnimationGraph to copy the first three blueprint nodes that connect to the Output Pose as follows: -- ![CopyAnim](../Figures/EgoVehicle/CopyAnim.jpg) -5. Then, back in `Anim_Ambulance`, paste the three nodes you just copied and connect them to the Output Pose: -- ![PasteAnim](../Figures/EgoVehicle/PasteAnim.jpg) -6. Finally, go back to the vehicle blueprint (BP_Ambulance) and in the components section select Mesh, then in the (right) details panel change the animation class to your new `Anim_Ambulance` like this: -- ![AssignAnim](../Figures/EgoVehicle/AssignAnim.jpg) +# How to add your own EgoVehicle + +A guide from how to add your own custom EgoVehicle from an existing Carla vehicle that you can then use in DReyeVR. Showcasing the minimal required steps to add an **ambulance** to be the new DReyeVR EgoVehicle. + +## Prerequisites: +- You should have DReyeVR installed and functioning correctly +- You should probably take a look at [Model.md](Model.md) in case you want to modify the static mesh of your new vehicle: + - Ex. creating high-poly mirror meshes + - Ex. detatching the steering wheel for use as a dynamic prop (moves with the animation) + +## 1. Choose which vehicle to add +1. Since the DReyeVR EgoVehicle is a child-instance of the `ACarlaWheeledVehicle`, you should use a Carla vehicle for the base class of your desired Vehicle. For this tutorial we will use the Ambulance as an example, but any Carla vehicle should do fine. + - For Vehicle `XYZ` + - The blueprint files are located in `Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/XYZ/BP_XYZ.uasset` + - The static mesh files are located in `Unreal/CarlaUE4/Content/Carla/Static/Vehicles/XWheeled/XYZ/` +2. Once you have decided on a vehicle, create this structure by copying (in Unreal Editor) the blueprint file. + - Do the same with any other mesh components that you'll want to add. + - You'll want the file structure to match the existing EgoVehicles: + ``` + CarlaUE4/Content/DReyeVR/ + ├── EgoVehicle + │   ├── Extra + │   ├── Jeep + │   ├── Mustang66 + │   ├── Ambulance # <-- your new EgoVehicle + │   ├── TeslaM3 # <-- default for DReyeVR + │   └── Vespa + ... + ``` + - Inside your `XYZ/` folder, you'll want to copy your new BP_XYZ asset (do this from the editor so that cached paths can be updated) and create any additional folders in here that you might want (ex. `Mesh`, `Mirrors`, `SteeringWheel`, `Tires`, are a few examples). + - It is best to perform these asset file modifications within the Editor. You can copy the files from within the content browser to other folders by click+dragging to get this pop-up: + + ![CopyHere](../Figures/EgoVehicle/CopyHere.jpg) + +**NOTE**: If you want to edit the vehicle mesh at all, this is where you'd want to do it. You will probably want to build off the existing static meshes in the `Static` directory. + +## 2. Reparent the vehicle blueprint +(For the sake of this tutorial, we'll assume the `XYZ=Ambulance`) +1. Open the `Content/DReyeVR/EgoVehicle/Ambulance/BP_Ambulance` asset you just copied from the content browser +2. Select `Class Defaults` then in the top right (`Class Options`) select the `Parent Class` and search for `EgoVehicle` to reparent (as in the figure below). This effectively reorganizes the blueprint's base class from `BaseVehiclePawn` (the Carla default) to `EgoVehicle` (the DReyeVR C++ class, which still inherits from BaseVehiclePawn). + - There will be a warning pop-up regarding data loss, you should proceed (it is purely additive). + - **NOTE** if the blueprint ever gets corrupted, you should first try reparenting back to the `BaseVehiclePawn` (the original parent) and then back to the DReyeVR `EgoVehicle`. + - ![EditClass](../Figures/EgoVehicle/EditClassSettings.jpg) + - Demonstrating class setting button, used to edit this BP's class instance + - ![Reparent](../Figures/EgoVehicle/Reparent.jpg) + - Demonstrating the reparenting button, select the dropdown and search for a compatible class to reparent with `BaseVehiclePawn` (Carla) or `EgoVehicle` (DReyeVR). +3. Now this vehicle is technically a DReyeVR EgoVehicle! + +## 3. Add the new config file and code +Now, to actually register this new blueprint with DReyeVR and have it available to spawn you'll need to add two bits to the code: + +1. Add the name of your new vehicle (for example `"Ambulance"` for the `BP_Ambulance` blueprint we inherited) to the list of available EgoVehicles in [`DReyeVRFactory.h`](../../DReyeVR/DReyeVRFactory.h). + ```c++ + // place the names of all your new custom EgoVehicle types here: + /// IMPORTANT: make sure these match the ConfigFile AND Blueprint!! + // We expect Config/EgoVehicle/XYZ.ini and Content/DReyeVR/EgoVehicles/XYZ/BP_XYZ.uasset + const std::vector VehicleTypes = { + "TeslaM3", // Tesla Model 3 (Default) + "Mustang66", // Mustang66 + "Jeep", // JeepWranglerRubicon + "Vespa" // Vespa (2WheeledVehicles) + "Ambulance", // <-- the new vehicle! (for this tutorial) + // add more here + }; + ``` +2. Add a new config file (to `Unreal/CarlaUE4/Config/EgoVehicles/`) that is used to parameterize this vehicle. This allows DReyeVR to know where to place things such as the camera root location (driver's seat), mirrors, steering wheel, etc. and this [`ConfigFile`](../../DReyeVR/ConfigFile.h) can be extended to support many run-time combinations. + - You'll need to make sure the config file has the EXACT same name as your new EgoVehicle (this is how they are read). We recommend copying an existing config file (default is `TeslaM3.ini` and renaming as follows): + ``` + CarlaUE4/Config/ + ├── ... + ├── DReyeVRConfig.ini + ├── ... + ├── EgoVehicles/ + │   ├── Jeep.ini + │   ├── Mustang66.ini + │   ├── Ambulance.ini # <-- your new file! + │   ├── TeslaM3.ini + │   └── Vespa.ini + ├── ... + ... + ``` + - Then you'll probably want to edit some of the contents of this file to match the EgoVehicle specifications which you can get from the Editor. For instance, the following figure shows that we are going to want to move the VRCameraRoot (head position) to (`108, -40, 158`). + - ![CameraRepos](../Figures/EgoVehicle/CameraReposition.jpg) + - You'll probably also want to move the dashboard elements around to whatever fits your preference. + - **IMPORTANT** You also need to enable the `Start with Tick Enabled` for the Blueprint (`BP_Ambulance` in the Components list) because by default they are disabled for Carla vehicles: + - ![ActorTick](../Figures/EgoVehicle/ActorTick.jpg) + - You should also notice that assets such as the SteeringWheel & Mirrors don't have any assigned static mesh. You can access these by clicking the component (on the left hierarchy) and assigning a new static mesh (on the right details pane). This bakes the asset directly in the blueprint file, so this only needs to be done once. + | Example: Mirrors | Example: Steering wheel | + | --- | --- | + | ![Mirrors](../Figures/EgoVehicle/SM_Mirror.jpg) | ![Wheel](../Figures/EgoVehicle/SM_Wheel.jpg) + - Now, open the `Ambulance.ini` file you just created and begin updating the fields (mostly transforms) to match the parameters you care about. Importantly, for the `[Blueprint]::Path` entry, you'll get this path by right-clicking on the Blueprint in the content viewer and selecting `Copy Reference`. + - ![CopyRef](../Figures/EgoVehicle/CopyRef.jpg) + - Note that transforms are encoded as follows + ```ini + # Format: Location XYZ in CM | Rotation Roll/Pitch/Yaw in Degrees | Scale XYZ percent (1=100%) + ExampleTransform=(X=0.0, Y=0.0, Z=3.0 | R=-45, P=90.0, Y=0 | X=1, Y=1, Z=1) + ``` + +## 4. Set the new vehicle to be the DReyeVR default +In the `DReyeVRConfig.ini` general configuration file (for non-vehicle specific parameters) you should set what Vehicle to spawn in by default. This takes the name of the vehicles, which for this example is `Ambulance`. + +```ini +[EgoVehicle] +VehicleType="Ambulance" +``` + +And thats it! You should now be able to relaunch `make launch` and when you press Play you'll start in your new EgoVehicle. + + +## 4. [Optional] Create a new animation +Sometimes, especially when modifying the meshes in blender and exporting/importing them back into Unreal Engine, the vanilla animation asset can get somewhat mangled and not work properly. You will know if the animation is failing if the tires (and steering wheel, if you added one) are not turning while the EgoVehicle is moving. + +See Carla's corresponding documentation [here](https://carla.readthedocs.io/en/latest/tuto_A_add_vehicle/#import-and-configure-the-vehicle). + +**NOTE** This only works for 4WheeledVehicles as of testing. 2WheeledVehicles are more complicated and not covered in this tutorial. + +### Steps to create a new animation blueprint for Carla/DReyeVR +1. Create a new Animation Blueprint in the Ambulance/Mesh directory (if you have one, else make a new folder `Mesh/` inside `Ambulance`). +- ![CreateAnim](../Figures/EgoVehicle/CreateAnim.jpg) +2. Make sure the parent of the animation mesh is set to `VehicleAnimInstance` and the preview skeleton is set to the skeletal mesh of your new vehicle (ex. `SK_Ambulance_Skeleton`) +- ![CreateAnimBP](../Figures/EgoVehicle/CreateAnimBP.jpg) +3. Name your new asset to something like `Anim_Ambulance` and open it up. Open the AnimationGraph in the bottom right as shown: +- ![AnimGraph](../Figures/EgoVehicle/AnimGraph.jpg) +4. Open another nearby animation blueprint (ex. `Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Animation_model3`) and open its AnimationGraph to copy the first three blueprint nodes that connect to the Output Pose as follows: +- ![CopyAnim](../Figures/EgoVehicle/CopyAnim.jpg) +5. Then, back in `Anim_Ambulance`, paste the three nodes you just copied and connect them to the Output Pose: +- ![PasteAnim](../Figures/EgoVehicle/PasteAnim.jpg) +6. Finally, go back to the vehicle blueprint (BP_Ambulance) and in the components section select Mesh, then in the (right) details panel change the animation class to your new `Anim_Ambulance` like this: +- ![AssignAnim](../Figures/EgoVehicle/AssignAnim.jpg) diff --git a/Docs/Tutorials/LODs.md b/Docs/Tutorials/LODs.md index 73abc63..62593eb 100644 --- a/Docs/Tutorials/LODs.md +++ b/Docs/Tutorials/LODs.md @@ -1,171 +1,171 @@ -# Level Of Detail modes in UE4 - -## What? -LOD = "Level of Detail" - -Ever noticed how in major video games/3d programs most of the models/textures decrease in quality (polygon count/resolution) when further away? This makes sense as an optimization, far away things can probably use less compute power. This is best explained in this [UE4 documentation](https://docs.unrealengine.com/4.26/en-US/WorkingWithContent/Types/StaticMeshes/HowTo/AutomaticLODGeneration/). - -Here's an example of the `SM_Tesla` static mesh provided by Carla -| LOD 0 (14,406 triangles) | LOD 1 (3,601 triangles) | LOD 2 (1,799 triangles) | LOD 3 (864 triangles) | -| ------------------------------ | ------------------------------ | ------------------------------ | ------------------------------ | -| ![LOD0](../Figures/LODs/lod0.jpg) | ![LOD0](../Figures/LODs/lod1.jpg) | ![LOD0](../Figures/LODs/lod2.jpg) | ![LOD0](../Figures/LODs/lod3.jpg) | - -## Okay so what? -While the default LOD settings are pretty good in Carla, this works because **Carla was not designed for VR** and expects to be run on a flat screen. However, we are using Carla in a VR setting, and it quickly becomes much more pronounced when models transform into lower/higher quality forms. This can be very distracting and immersion-breaking for the person in the headset. - -### Download pre-compiled meshes -If you aren't interested in following the steps on creating your own LODSettings asset and bulk-applying it, skip everything until the **Download Everything Instead** step, else read on. - -## How to fix? -The best "fix" here would be to change the distance thresholds so that the transformations would be much more aggressive and stay in higher-quality for longer. This increase in quality comes at a cost of performance of course. - -One possible workaround we found (which did not work for us unfortunately) was [this comment](https://github.com/carla-simulator/carla/issues/276#issuecomment-374541267) by a Carla contributor who elaborated that "the popping in the vegetation and other models is caused by the Level of Detail. We have various versions of the same model with different polygonal levels to replace the final model depending on the distance from the camera. Ideally, these changes would be imperceptible but more tweaking would be needed to reach that ideal point. You can force the highest LoD on everything by typing `r.forcelod 1` and `foliage.ForceLOD 1` in the Unreal Engine console". Similarly, there is further work to look into texture MipMapping (similar idea but for textures) which uses UE4's TextureStreaming. For this guide we'll mostly focus on changing just the LOD settings of the main vehicles. - -### Important: -Technically, the logic behind LOD picking is not based on "distances from the camera" as is commonly described, but rather by the "screen space" that is being taken up by the model. This is best explained in the [UE4 documentation on LOD Screen Size](https://docs.unrealengine.com/4.26/en-US/WorkingWithContent/Types/StaticMeshes/HowTo/PerPlatformLODScreenSize/) (ignore the per-platform overrides, everything we're doing is on the a desktop client) where they mention "to control when one Level Of Detail (LOD) Static Mesh transitions into another one, Unreal Engine 4 (UE4) uses the current size of the Static Meshes size in Screen Space". - -## Deep dive into UE4 -In order to actually access the LOD's for every blueprint, we're actually going to need to take a step back and look towards the [`SkeletalMesh`](https://docs.unrealengine.com/4.26/en-US/WorkingWithContent/Types/SkeletalMeshes/) of the model rather than the blueprint itself. The skeletal mesh is in-between the `StaticMesh` and the final blueprint since it contains all the animations/rigging/physics/etc. that a static mesh does not, but does not contain any of the control logic for a usable actor. - -For example, for the `SM_TeslaM3_v2` skeletal mesh (note there is also a `SM_Tesla` static mesh, the naming scheme is unfortunately not very consistent), head over to `Content/Carla/Static/Vehicles/4Wheeled/Tesla/` in the Content Browser to see the following folder layout: - -![TeslaContent](../Figures/LODs/tesla_content.jpg) - -Notice how the model underlined in **pink** is the skeletal mesh we are interested in. Double click it to open it in the Editor. - -Then, in the left, in the `Asset Details` pane (highlighted below in **red**) you can see the LOD Picker settings is currently set to Auto (LOD0) this will automatically compute and assign the LOD for this mesh based on your distance. You can see the current LOD settings in action in the top left of the preview window (highlighted below in **yellow**). - -![TeslaSkeletal](../Figures/LODs/tesla_skeletal.jpg) - -From the LOD picker you could check the `"Custom"` box and edit the individual LOD settings manually, but this is a lot of tedious work that would need to be applied to **every** static mesh individually. In this guide we'll try to avoid tedious work. - -## There has to be a better way? -Yes, in fact, there is! ([More documentation](https://docs.unrealengine.com/4.26/en-US/AnimatingObjects/SkeletalMeshAnimation/Persona/MeshDetails/)) - -Under the LOD Picker in Asset Details you might notice the `LOD Settings` section. Open it up and focus on the LODSettings input (currently empty "None"). This means there exists a `.uasset` asset that we can create to generalize LOD settings for all vehicles. We just need to apply this LODSetting asset to each of them once beforehand. - -If you don't have an existing LODSettings asset (we've provided one in [`Tools/LOD/SM_Vehicle_LODSettings.uasset`](Tools/LOD/SM_Vehicle_LODSettings.uasset)) you can create one with the `Generate Asset` button. We moved ours to a new `4Wheeled/DReyeVR/` directory. Then in LODSettings, select the drop-down menu and choose the newly created LODSetting. - -| LODSettings pre application | LODSettings post application | -| ---------------------------------------------- | ----------------------------------------------- | -| ![LODSettings1](../Figures/LODs/lod_settings.jpg) | ![LODSettings1](../Figures/LODs/lod_settings2.jpg) | - -Now you should be able to open up the newly created `LODSettings` asset (`SM_Vehicle_LODSettings`) in the editor and edit all the important LOD parameters from there. Here is where the fine-tuning for screen-size takes place as you can manually tune when transitions happen. -### NOTE -Something to keep in mind is that different vehicles even have different number of LOD's, some (like `SM_TeslaM3_v2` have 4) have more or less than others. So in order to have a singular LODSetting apply for everyone, we'll need to make sure its array is as large as the largest LOD for all requested meshes. Since there should not really be a limit to this, we used an array of size 7 (not all vehicles need to access all 7) for some leg-room (no array-OOB exceptions). - -| LOD | Default (`SM_TeslaM3_v2`) Screen Size | New LODSettings Screen Size | -| --- | ------------------------------------- | --------------------------- | -| 0 | 2.0 | 1.0 (max) | -| 1 | 0.4 | 0.2 | -| 2 | 0.21 | 0.05 | -| 3 | 0.12 | 0.03 | -| 4 | N/A | 0.01 | -| 5 | N/A | 0.005 | -| 6 | N/A | 0.001 | - -This should look something like the following (with LODGroups collapsed): - - - -Theoretically we should be able to have this class completely in C++ since it is a [`USkeletalMeshLODSettings`](https://docs.unrealengine.com/4.26/en-US/API/Runtime/Engine/Engine/USkeletalMeshLODSettings/) class. But it is fairly low on the priority list. - -## Okay now what? -Now we can edit our `SM_Vehicle_LODSettings.uasset` file and all the LOD settings for our `SM_TeslaM3_v2` should respect it. This is great! -- Note sometimes the mesh will use cached LOD's to force regeneration click the `Regenerate` button in the `SM_TeslaM3_v2` editor window in `LODSettings`. This shouldn't be a problem on the next `make launch` of the editor. - -Now it would be great to apply this `SM_Vehicle_LODSettings.uasset` to all the static meshes at once right? Turns out we can do this with a [bulk-edit-via-property-matrix](https://docs.unrealengine.com/4.26/en-US/Basics/UI/PropertyMatrix/) - -The steps we recommend are as follows: -1. Go to the `4Wheeled/` directory in the content browser -2. In the bottom right (View Options) uncheck the `Folders` option -3. In the top left click the `Filters` and check the `SkeletalMesh` option - - Now you should see this (notice all pink underlined): - ![AllSkeletalMeshes](../Figures/LODs/all_skeletal_meshes.jpg) -4. Now select all the meshes **EXCEPT for the following** - - Windows: - 1. SM_Cybertruck_v2 - 2. SM_ETron - - Linux: - 1. SK_Charger2020 - 2. SK_ChargetCop - 3. SK_lincolnv5 - 4. SK_MercedesCCC - ![AllSkeletalMeshesSelected](../Figures/LODs/all_skeletal_meshes_selected.jpg) - - We are still unsure why, but these particular vehicles cause a segmentation fault (something to do with their vertex makeup) upon this application. You will need to manually set the LOD parameters for individual custom LOD's for each of them (ie. do NOT use the `SM_Vehicle_LODSettings.uasset` at all) -5. Right click any of the highlighted vehicles -> `Asset Actions` -> `Bulk Edit via Property Matrix` - ![BulkEditMatrix](../Figures/LODs/bulk_edit_matrix.jpg) -6. In the `Bulk Edit` window that opens up, verify all the correct skeletal meshes on the left, then in `LODSettings` on the right, click the 3x3 grid icon (Pick asset) and choose the newly created `SM_Vehicle_LODSettings.uasset` asset. - 1. To apply this to all the selected skeletal meshes, go to the top bar -> `File` -> `Save` - 2. The end result should look something like this: - ![BulkEdit](../Figures/LODs/bulk_edit.jpg) - -As mentioned in step 4, some particular vehicles cause a seg-fault after giving them this `LODSettings`. We are still investigating why exactly but for now its safer to just manually go into each vehicle and tune the individual `LOD` settings after checking `Custom` and seeing the `LOD0`, `LOD1`, `LOD2`, ... etc. options. - -## Finished -Now, all the static meshes (with some exceptions) will respect any changes made to `SM_Vehicle_LODSettings.uasset` automatically, so you won't have to reapply the settings each time you want to make a change to the LODSettings asset, just make the change. - -Also, if something unfortunate happens and one of your skeletal meshes gets corrupted (its happened to us), then its fairly simple to reclone a `Carla 0.9.13` build, run the `Update.sh` script and copy over the old (new) static meshes to replace the ones in your existing project. - -## Download everything instead -Option 1: (use our script) -```bash -cd DReyeVR/Tools/LOD/ -# installing on Linux -./install_LOD.sh /PATH/TO/CARLA Linux -# installing on Windows -./install_LOD.sh /PATH/TO/CARLA Windows -# installing Original (reset all changes) -./install_LOD.sh /PATH/TO/CARLA Original -``` -Option 2: (manually) -- Follow these simple steps: - 1. Download all the static meshes from this link ([Linux](https://drive.google.com/file/d/1OqDOCAflENnXvbJCogBEmRhHQpEF1aKE/view) or [Windows](https://drive.google.com/file/d/191tiK25MJ9C7-5Q1-sHt1mp4_EaefjqM/view)) - 2. Extract all files - 3. Copy files to the following directories - -These are the important skeleton meshes and directories -```bash -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Toyota_Prius/Vh_Car_ToyotaPrius_Rig.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiA2_/SK_AudiA2.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwGranTourer/SK_BMWGranTourer.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwIsetta/SK_BMWIsetta.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/CarlaCola/SK_CarlaCola.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/SK_Charger2020.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/ChargerCop/SK_ChargerCop.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/SK_ChevroletImpala.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Citroen/SK_Citroen_C3.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Jeep/SK_JeepWranglerRubicon.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2020/SK_lincolnv5.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mercedes/SK_MercedesBenzCoupeC.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MercedesCCC/SK_MercedesCCC.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MIni/SK_MiniCooperS.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/SK_Mustang_OLD.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Micra/SK_NissanMicra.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Patrol/SK_NissanPatrolST.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Leon/SK_SeatLeon.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiTT/SM_AudiTT_v1.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharge/SM_Charger_v2.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/SM_Chevrolet_v2.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Cybertruck/SM_Cybertruck_v2.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiETron/SM_Etron.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2017/SM_Lincoln_v2.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/SM_Mustang_v2.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/SM_TeslaM3_v2.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Truck/SM_TestTruck.uasset -Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/VolkswagenT2/SM_Van_v2.uasset -``` - -### NOTE: Sometimes there are still segfaults with these LOD's on different machines. -For example, the `SM_Cybertruck_v2` and `SM_Etron` skeletal meshes cause seg-faults on Windows, but not on Linux. -- In order to check which ones cause the segfault, open all the skeletal meshes in `4Wheeled` one by one (or select them all) and replace them with the original skeleton meshes. -- Note, we've provided the original models [here](https://drive.google.com/file/d/1Vc4e43xZuXOJF_3-r3n3QU-yE5sjiAfw/view) which you can use to replace any broken skeletons - - But ideally our Windows/Linux downloads should work on those platforms. Summary of broken skeleton mesh: - - Windows: - - SM_Cybertruck_v2 - - SM_Etron - - Linux: - - SK_Charger2020 - - SK_ChargerCop - - SK_lincolnv5 - - SK_MercedesCCC +# Level Of Detail modes in UE4 + +## What? +LOD = "Level of Detail" + +Ever noticed how in major video games/3d programs most of the models/textures decrease in quality (polygon count/resolution) when further away? This makes sense as an optimization, far away things can probably use less compute power. This is best explained in this [UE4 documentation](https://docs.unrealengine.com/4.26/en-US/WorkingWithContent/Types/StaticMeshes/HowTo/AutomaticLODGeneration/). + +Here's an example of the `SM_Tesla` static mesh provided by Carla +| LOD 0 (14,406 triangles) | LOD 1 (3,601 triangles) | LOD 2 (1,799 triangles) | LOD 3 (864 triangles) | +| ------------------------------ | ------------------------------ | ------------------------------ | ------------------------------ | +| ![LOD0](../Figures/LODs/lod0.jpg) | ![LOD0](../Figures/LODs/lod1.jpg) | ![LOD0](../Figures/LODs/lod2.jpg) | ![LOD0](../Figures/LODs/lod3.jpg) | + +## Okay so what? +While the default LOD settings are pretty good in Carla, this works because **Carla was not designed for VR** and expects to be run on a flat screen. However, we are using Carla in a VR setting, and it quickly becomes much more pronounced when models transform into lower/higher quality forms. This can be very distracting and immersion-breaking for the person in the headset. + +### Download pre-compiled meshes +If you aren't interested in following the steps on creating your own LODSettings asset and bulk-applying it, skip everything until the **Download Everything Instead** step, else read on. + +## How to fix? +The best "fix" here would be to change the distance thresholds so that the transformations would be much more aggressive and stay in higher-quality for longer. This increase in quality comes at a cost of performance of course. + +One possible workaround we found (which did not work for us unfortunately) was [this comment](https://github.com/carla-simulator/carla/issues/276#issuecomment-374541267) by a Carla contributor who elaborated that "the popping in the vegetation and other models is caused by the Level of Detail. We have various versions of the same model with different polygonal levels to replace the final model depending on the distance from the camera. Ideally, these changes would be imperceptible but more tweaking would be needed to reach that ideal point. You can force the highest LoD on everything by typing `r.forcelod 1` and `foliage.ForceLOD 1` in the Unreal Engine console". Similarly, there is further work to look into texture MipMapping (similar idea but for textures) which uses UE4's TextureStreaming. For this guide we'll mostly focus on changing just the LOD settings of the main vehicles. + +### Important: +Technically, the logic behind LOD picking is not based on "distances from the camera" as is commonly described, but rather by the "screen space" that is being taken up by the model. This is best explained in the [UE4 documentation on LOD Screen Size](https://docs.unrealengine.com/4.26/en-US/WorkingWithContent/Types/StaticMeshes/HowTo/PerPlatformLODScreenSize/) (ignore the per-platform overrides, everything we're doing is on the a desktop client) where they mention "to control when one Level Of Detail (LOD) Static Mesh transitions into another one, Unreal Engine 4 (UE4) uses the current size of the Static Meshes size in Screen Space". + +## Deep dive into UE4 +In order to actually access the LOD's for every blueprint, we're actually going to need to take a step back and look towards the [`SkeletalMesh`](https://docs.unrealengine.com/4.26/en-US/WorkingWithContent/Types/SkeletalMeshes/) of the model rather than the blueprint itself. The skeletal mesh is in-between the `StaticMesh` and the final blueprint since it contains all the animations/rigging/physics/etc. that a static mesh does not, but does not contain any of the control logic for a usable actor. + +For example, for the `SM_TeslaM3_v2` skeletal mesh (note there is also a `SM_Tesla` static mesh, the naming scheme is unfortunately not very consistent), head over to `Content/Carla/Static/Vehicles/4Wheeled/Tesla/` in the Content Browser to see the following folder layout: + +![TeslaContent](../Figures/LODs/tesla_content.jpg) + +Notice how the model underlined in **pink** is the skeletal mesh we are interested in. Double click it to open it in the Editor. + +Then, in the left, in the `Asset Details` pane (highlighted below in **red**) you can see the LOD Picker settings is currently set to Auto (LOD0) this will automatically compute and assign the LOD for this mesh based on your distance. You can see the current LOD settings in action in the top left of the preview window (highlighted below in **yellow**). + +![TeslaSkeletal](../Figures/LODs/tesla_skeletal.jpg) + +From the LOD picker you could check the `"Custom"` box and edit the individual LOD settings manually, but this is a lot of tedious work that would need to be applied to **every** static mesh individually. In this guide we'll try to avoid tedious work. + +## There has to be a better way? +Yes, in fact, there is! ([More documentation](https://docs.unrealengine.com/4.26/en-US/AnimatingObjects/SkeletalMeshAnimation/Persona/MeshDetails/)) + +Under the LOD Picker in Asset Details you might notice the `LOD Settings` section. Open it up and focus on the LODSettings input (currently empty "None"). This means there exists a `.uasset` asset that we can create to generalize LOD settings for all vehicles. We just need to apply this LODSetting asset to each of them once beforehand. + +If you don't have an existing LODSettings asset (we've provided one in [`Tools/LOD/SM_Vehicle_LODSettings.uasset`](Tools/LOD/SM_Vehicle_LODSettings.uasset)) you can create one with the `Generate Asset` button. We moved ours to a new `4Wheeled/DReyeVR/` directory. Then in LODSettings, select the drop-down menu and choose the newly created LODSetting. + +| LODSettings pre application | LODSettings post application | +| ---------------------------------------------- | ----------------------------------------------- | +| ![LODSettings1](../Figures/LODs/lod_settings.jpg) | ![LODSettings1](../Figures/LODs/lod_settings2.jpg) | + +Now you should be able to open up the newly created `LODSettings` asset (`SM_Vehicle_LODSettings`) in the editor and edit all the important LOD parameters from there. Here is where the fine-tuning for screen-size takes place as you can manually tune when transitions happen. +### NOTE +Something to keep in mind is that different vehicles even have different number of LOD's, some (like `SM_TeslaM3_v2` have 4) have more or less than others. So in order to have a singular LODSetting apply for everyone, we'll need to make sure its array is as large as the largest LOD for all requested meshes. Since there should not really be a limit to this, we used an array of size 7 (not all vehicles need to access all 7) for some leg-room (no array-OOB exceptions). + +| LOD | Default (`SM_TeslaM3_v2`) Screen Size | New LODSettings Screen Size | +| --- | ------------------------------------- | --------------------------- | +| 0 | 2.0 | 1.0 (max) | +| 1 | 0.4 | 0.2 | +| 2 | 0.21 | 0.05 | +| 3 | 0.12 | 0.03 | +| 4 | N/A | 0.01 | +| 5 | N/A | 0.005 | +| 6 | N/A | 0.001 | + +This should look something like the following (with LODGroups collapsed): + + + +Theoretically we should be able to have this class completely in C++ since it is a [`USkeletalMeshLODSettings`](https://docs.unrealengine.com/4.26/en-US/API/Runtime/Engine/Engine/USkeletalMeshLODSettings/) class. But it is fairly low on the priority list. + +## Okay now what? +Now we can edit our `SM_Vehicle_LODSettings.uasset` file and all the LOD settings for our `SM_TeslaM3_v2` should respect it. This is great! +- Note sometimes the mesh will use cached LOD's to force regeneration click the `Regenerate` button in the `SM_TeslaM3_v2` editor window in `LODSettings`. This shouldn't be a problem on the next `make launch` of the editor. + +Now it would be great to apply this `SM_Vehicle_LODSettings.uasset` to all the static meshes at once right? Turns out we can do this with a [bulk-edit-via-property-matrix](https://docs.unrealengine.com/4.26/en-US/Basics/UI/PropertyMatrix/) + +The steps we recommend are as follows: +1. Go to the `4Wheeled/` directory in the content browser +2. In the bottom right (View Options) uncheck the `Folders` option +3. In the top left click the `Filters` and check the `SkeletalMesh` option + - Now you should see this (notice all pink underlined): + ![AllSkeletalMeshes](../Figures/LODs/all_skeletal_meshes.jpg) +4. Now select all the meshes **EXCEPT for the following** + - Windows: + 1. SM_Cybertruck_v2 + 2. SM_ETron + - Linux: + 1. SK_Charger2020 + 2. SK_ChargetCop + 3. SK_lincolnv5 + 4. SK_MercedesCCC + ![AllSkeletalMeshesSelected](../Figures/LODs/all_skeletal_meshes_selected.jpg) + - We are still unsure why, but these particular vehicles cause a segmentation fault (something to do with their vertex makeup) upon this application. You will need to manually set the LOD parameters for individual custom LOD's for each of them (ie. do NOT use the `SM_Vehicle_LODSettings.uasset` at all) +5. Right click any of the highlighted vehicles -> `Asset Actions` -> `Bulk Edit via Property Matrix` + ![BulkEditMatrix](../Figures/LODs/bulk_edit_matrix.jpg) +6. In the `Bulk Edit` window that opens up, verify all the correct skeletal meshes on the left, then in `LODSettings` on the right, click the 3x3 grid icon (Pick asset) and choose the newly created `SM_Vehicle_LODSettings.uasset` asset. + 1. To apply this to all the selected skeletal meshes, go to the top bar -> `File` -> `Save` + 2. The end result should look something like this: + ![BulkEdit](../Figures/LODs/bulk_edit.jpg) + +As mentioned in step 4, some particular vehicles cause a seg-fault after giving them this `LODSettings`. We are still investigating why exactly but for now its safer to just manually go into each vehicle and tune the individual `LOD` settings after checking `Custom` and seeing the `LOD0`, `LOD1`, `LOD2`, ... etc. options. + +## Finished +Now, all the static meshes (with some exceptions) will respect any changes made to `SM_Vehicle_LODSettings.uasset` automatically, so you won't have to reapply the settings each time you want to make a change to the LODSettings asset, just make the change. + +Also, if something unfortunate happens and one of your skeletal meshes gets corrupted (its happened to us), then its fairly simple to reclone a `Carla 0.9.13` build, run the `Update.sh` script and copy over the old (new) static meshes to replace the ones in your existing project. + +## Download everything instead +Option 1: (use our script) +```bash +cd DReyeVR/Tools/LOD/ +# installing on Linux +./install_LOD.sh /PATH/TO/CARLA Linux +# installing on Windows +./install_LOD.sh /PATH/TO/CARLA Windows +# installing Original (reset all changes) +./install_LOD.sh /PATH/TO/CARLA Original +``` +Option 2: (manually) +- Follow these simple steps: + 1. Download all the static meshes from this link ([Linux](https://drive.google.com/file/d/1OqDOCAflENnXvbJCogBEmRhHQpEF1aKE/view) or [Windows](https://drive.google.com/file/d/191tiK25MJ9C7-5Q1-sHt1mp4_EaefjqM/view)) + 2. Extract all files + 3. Copy files to the following directories + +These are the important skeleton meshes and directories +```bash +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Toyota_Prius/Vh_Car_ToyotaPrius_Rig.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiA2_/SK_AudiA2.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwGranTourer/SK_BMWGranTourer.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwIsetta/SK_BMWIsetta.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/CarlaCola/SK_CarlaCola.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/SK_Charger2020.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/ChargerCop/SK_ChargerCop.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/SK_ChevroletImpala.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Citroen/SK_Citroen_C3.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Jeep/SK_JeepWranglerRubicon.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2020/SK_lincolnv5.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mercedes/SK_MercedesBenzCoupeC.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MercedesCCC/SK_MercedesCCC.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MIni/SK_MiniCooperS.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/SK_Mustang_OLD.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Micra/SK_NissanMicra.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Patrol/SK_NissanPatrolST.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Leon/SK_SeatLeon.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiTT/SM_AudiTT_v1.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharge/SM_Charger_v2.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/SM_Chevrolet_v2.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Cybertruck/SM_Cybertruck_v2.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiETron/SM_Etron.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2017/SM_Lincoln_v2.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/SM_Mustang_v2.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/SM_TeslaM3_v2.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Truck/SM_TestTruck.uasset +Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/VolkswagenT2/SM_Van_v2.uasset +``` + +### NOTE: Sometimes there are still segfaults with these LOD's on different machines. +For example, the `SM_Cybertruck_v2` and `SM_Etron` skeletal meshes cause seg-faults on Windows, but not on Linux. +- In order to check which ones cause the segfault, open all the skeletal meshes in `4Wheeled` one by one (or select them all) and replace them with the original skeleton meshes. +- Note, we've provided the original models [here](https://drive.google.com/file/d/1Vc4e43xZuXOJF_3-r3n3QU-yE5sjiAfw/view) which you can use to replace any broken skeletons + - But ideally our Windows/Linux downloads should work on those platforms. Summary of broken skeleton mesh: + - Windows: + - SM_Cybertruck_v2 + - SM_Etron + - Linux: + - SK_Charger2020 + - SK_ChargerCop + - SK_lincolnv5 + - SK_MercedesCCC diff --git a/Docs/Tutorials/Model.md b/Docs/Tutorials/Model.md index c884047..197be36 100644 --- a/Docs/Tutorials/Model.md +++ b/Docs/Tutorials/Model.md @@ -1,125 +1,125 @@ -# Modifying the Vehicle Model - -You may be interested in adding novel features to the vehicle mesh itself, outside of what we have provided with DReyeVR. In this guide, we'll help you get familiar with some of the tools and basic requirements to do so, along with an example of how we modified the vanilla CARLA Tesla static mesh to have a dynamic steering wheel. - -Note that to continue, we assume you have access to the following software: -- Unreal Engine Editor -- Carla (from source) -- Blender ([Download free](https://www.blender.org/download/)) - -## Getting started -The first place to look would definitely be CARLA's own excellent guide on [adding custom vehicles](https://carla.readthedocs.io/en/latest/tuto_A_add_vehicle/) if you already have one in mind. But it is still a good read to understand the underlying mechanisms at play to achieve a viable CARLA/UE4 vehicle: -- [Bones](https://docs.unrealengine.com/4.27/en-US/AnimatingObjects/SkeletalMeshAnimation/Persona/VirtualBones/): A bone can be thought of as a rigging entity, allowing for attachments between entities to be rigid and constrained. -- [Skeleton](https://docs.unrealengine.com/4.26/en-US/AnimatingObjects/SkeletalMeshAnimation/Skeleton/): A skeleton contains the location and orientation of bones and their hierarchy. -- [Physics Mesh](https://docs.unrealengine.com/4.26/en-US/InteractiveExperiences/Physics/PhysicsAssetEditor/): Denotes the bounding boxes around important features of the mesh. Primarily used for collision detection. -- [Animation](https://docs.unrealengine.com/4.27/en-US/AnimatingObjects/SkeletalMeshAnimation/AnimBlueprints/): Animation blueprints control the animation of a skeletal mesh typically through some state-machine logic. -- [Blueprint](https://docs.unrealengine.com/4.27/en-US/ProgrammingAndScripting/Blueprints/UserGuide/Types/ClassBlueprint/): Combines all of the above into a highly dynamic and flexible UObject that can serve as our Vehicle agent. - -With all this in mind, you are probably going to be interested in: -- Blueprints: `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/XYZ` -- Other: `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/XYZ` - -# Example: Adding a dynamic steering wheel -Problen: It is quite jarring to drive without a responsive steering wheel, and since the Carla vehicle meshes were not designed for human drivers, there is no need to separate the steering wheel from the overall vehicle shell. This is problematic since the wheel is now a part of the vehicle mesh and cannot be animated during runtime. - -In our case, we elected to use the TeslaM3 mesh for our base class, so we'll be working with that here too. - -Our plan of action will be: -1. Extract the steering wheel mesh from the vehicle and create its own static mesh -2. Update the vehicle mesh to remove the steering wheel -3. Re-attach the steering wheel back as a code-based dynamic object - -For steps 1 & 2, we will be using the free & open source Blender program for the 3D modeling work: - -## 1. Extract the steering wheel - -### Exporting to FBX -First, go to the static mesh file you wish to export, in our case we wanted to export `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/SM_TeslaM3_v2.uasset` (notice these files should have a pink underline to indicate they are the full static mesh files). - -### One LOD -I recommend using the highest LOD ([Level-Of-Detail](../../LODS.md)) setting for this export, since this vehicle will be so close to the camera all the time it is pointless to have multiple LOD's, and it makes it simpler for the import to blender. - -To do this, simply enter the static mesh by double clicking it, and on the left "Asset Details" pane, down in "LOD Settings" drag the "Number of LODs" slider down to 1, then click "Apply Changes" as follows. -- ![LODs](../Figures/Model/LOD1.jpg) - -### Export to blender -Now, back in the `Content Browser` you can right click the file then select `Asset Actions -> Export` and designate a place for the resulting `.FBX` file to be exported. -- ![Export](../Figures/Model/Export.jpg) - -### Model in Blender -Now, open a fresh Blender window and delete the default spawned cube. Then go to `File -> Import -> FBX (.fbx)` and select the file you just created. - -You should now be presented with a simple Blender window with the vehicle like this: -- ![BlenderSolid](../Figures/Model/BlenderSolid.jpg) - -In order to toggle moving around using `WASD` controls, press `shift + ` `. Move inside the vehicle where you can find the steering wheel. - -The easiest way (I've found) to efficiently extract the steering wheel it so use the wireframe-mode to select all vertices, even those that aren't visible in the solid render. To go to wireframe mode press `z` then select `wireframe` (should be the left-most option). Then you should see something like this: -- ![WireframeWheel](../Figures/Model/WireframeWheel.jpg) - -Then, to actually select the proper vertices, we're going to need to change from `Object Mode` to `Edit Mode` in the top left corner of the viewport. Then we'll need to position our camera in such a way to minimize unwanted vertices being selected, and use whatever selection technique we want (I like the lasso selection) to select the entire steering wheel like this: -- ![SelectedWheel](../Figures/Model/SelectedWheel.jpg) -NOTE: if you have excess vertices selected, you can always undo those with `shift+click` on individual vertices. - -Then, you should be able to move the entire bunch out of the vehicle (or duplicate them all with `shift+d` and clean up the original) to have something like this: -| Wireframe | Rendered | -| --- | --- | -| ![WireFrameGotWheel](../Figures/Model/WheelOut.jpg) | ![SolidOut](../Figures/Model/VehicleAndWheel.jpg) | - -Finally, you should then be able to export the individual selections (need to export both the just-wheel and the just-vehicle models) by selecting all the vertices the same way (in wireframe) and deleting them (then undo-ing the deletion of course). Then selecting `File -> Export -> FBX(.fbx)` for best compatibility. Do this for both the Vehicle mesh as well as the steering wheel (I moved the steering wheel to the origin when exporting but I'm not sure this is necessary). - -## 2. Update the vehicle mesh - -### Back in the Editor -Now, back in the editor, we'll create a new directory for both the Vehicle mesh as well as the steering wheel. Most of the content from this section is a modified version of the [Carla-provided documentation](https://carla.readthedocs.io/en/latest/tuto_A_add_vehicle/). - -Then, in the new `Mesh` directory, we can simply right-click in the content browser and select `Import Asset` then select our FBX model. Make sure to set **Import Content Type** to `Geometry and Skinning Weights`, **Normal Import Method** to `Import Normals`, and **Material Import Method** to `Do not create materials`, and finally uncheck **Import Textures**. - -We should now have a (pink underlined) Skeletal mesh asset, (beige underlined) physics asset, and (baby blue underlined) skeleton asset. Then, right click on the new (pink underlined) skeletal mesh asset and select `Create -> Anim Blueprint` to create a new animation blueprint. - -In this animation blueprint, ensure the following: -- Go to `Class settings -> Details -> Class Options -> Parent Class` and reparent the class to a `VehicleAnimInstance`. -- In the `My Blueprint` section, click on `AnimGraph` and copy over the same graph logic from the existing `TeslaM3` animation to look like this: - -| Reparent | Animation | -| --- | --- | -| ![Reparent](../Figures/Model/AnimClassOption.jpg) | ![AnimGraph](../Figures/Model/AnimGraph.jpg) | - -Now you are done with the animation blueprint. - -In my experience I had to do some additional tweaking to use the right components for my overall mesh (pink underlined) as follows: -- `Asset Details -> Physics Asset`: Replace new with the existing `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/SM_TeslaM3_PhysicsAsset.uasset` physics asset (NOT the `_v2_` model!) -- `Asset Details -> Lighting`: Same as the Physics Asset -- `Preview Scene Settings -> Animation Blueprint`: The new animation blueprint you just created. - -Then finally, you can delete the newly imported PhysicsAsset file since it is no longer being used (I opted to use the vanilla TeslaM3 one instead) - -And in `BP_EgoVehicle_DReyeVR`, you can finally edit the `Mesh (Inherited) -> Details -> Mesh` field to use the new SM we just updated (pink underline). Since this clears the `Animation` section, you'll also need to update the `Mesh (Inherited) -> Animation -> Anim Class` field to use the new animation class we just made. - -Now the DReyeVR EgoVehicle should be fully drivable and operates just as it did before, but now with no steering wheel in the driver's seat! -![NoWheel](../Figures/Model/NoWheel.jpg) - -## 3. Re-attach the steering wheel dynamically -### Import to UE4 -Now we want to import the steering wheel back into the engine so we can dynamically spawn, place, and update it at runtime. - -The easiest way to do this is through importing the SteeringWheel `.fbx` just like with the Vehicle mesh, from there it should have all the original textures pre-applied and be slightly angled. - -To get rotations of the wheel to be in the Roll axis of the wheel itself (not its attachment), I recommend slightly tilting the static mesh wheel so that it is mostly vertical and select `Make Static Mesh`. - -This will allow you to create a plain simple static mesh (cyan underline) from the skeletal mesh (pink underline) as follows: -| Rotated Skeletal Mesh | Resulting Directory | -| --- | --- | -| ![RotWheel](../Figures/Model/WheelRot.jpg) | ![SelectedWheel](../Figures/Model/SelectSMWheel.jpg) | - -### Import in code -Now that we have a reasonable steering wheel model as a simple static mesh, it is easy to spawn it and attach it to the ego-vehicle (currently without a steering wheel) in code. Managing it in code is nice because it will allow us to `SetRelativeRotation` of the mesh dynamically on every tick, allowing it to be responsive to our inputs at runtime. - -The first step to Spawn the steering wheel in code is to find its mesh in the editor. Right click on the static mesh (cyan underline) and select `Copy Reference`. For me it looks like this: -- `"StaticMesh'/Game/DReyeVR/EgoVehicle/TeslaM3/SteeringWheel/Wheel_StaticMeshl_model3.Wheel_StaticMeshl_model3'"` - -(Note that we won't be needing any of the other steering wheel assets anymore, feel free to delete them) - -The general strategy for adding Unreal components in code is to spawn them in the constructor then use their reference alongside their C++ API. For our case we'll only need a constructor and a tick method (See [EgoVehicle::ConstructSteeringWheel & EgoVehicle::TickSteeringWheel](../../DReyeVR/EgoVehicle.cpp)) - +# Modifying the Vehicle Model + +You may be interested in adding novel features to the vehicle mesh itself, outside of what we have provided with DReyeVR. In this guide, we'll help you get familiar with some of the tools and basic requirements to do so, along with an example of how we modified the vanilla CARLA Tesla static mesh to have a dynamic steering wheel. + +Note that to continue, we assume you have access to the following software: +- Unreal Engine Editor +- Carla (from source) +- Blender ([Download free](https://www.blender.org/download/)) + +## Getting started +The first place to look would definitely be CARLA's own excellent guide on [adding custom vehicles](https://carla.readthedocs.io/en/latest/tuto_A_add_vehicle/) if you already have one in mind. But it is still a good read to understand the underlying mechanisms at play to achieve a viable CARLA/UE4 vehicle: +- [Bones](https://docs.unrealengine.com/4.27/en-US/AnimatingObjects/SkeletalMeshAnimation/Persona/VirtualBones/): A bone can be thought of as a rigging entity, allowing for attachments between entities to be rigid and constrained. +- [Skeleton](https://docs.unrealengine.com/4.26/en-US/AnimatingObjects/SkeletalMeshAnimation/Skeleton/): A skeleton contains the location and orientation of bones and their hierarchy. +- [Physics Mesh](https://docs.unrealengine.com/4.26/en-US/InteractiveExperiences/Physics/PhysicsAssetEditor/): Denotes the bounding boxes around important features of the mesh. Primarily used for collision detection. +- [Animation](https://docs.unrealengine.com/4.27/en-US/AnimatingObjects/SkeletalMeshAnimation/AnimBlueprints/): Animation blueprints control the animation of a skeletal mesh typically through some state-machine logic. +- [Blueprint](https://docs.unrealengine.com/4.27/en-US/ProgrammingAndScripting/Blueprints/UserGuide/Types/ClassBlueprint/): Combines all of the above into a highly dynamic and flexible UObject that can serve as our Vehicle agent. + +With all this in mind, you are probably going to be interested in: +- Blueprints: `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/XYZ` +- Other: `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/XYZ` + +# Example: Adding a dynamic steering wheel +Problen: It is quite jarring to drive without a responsive steering wheel, and since the Carla vehicle meshes were not designed for human drivers, there is no need to separate the steering wheel from the overall vehicle shell. This is problematic since the wheel is now a part of the vehicle mesh and cannot be animated during runtime. + +In our case, we elected to use the TeslaM3 mesh for our base class, so we'll be working with that here too. + +Our plan of action will be: +1. Extract the steering wheel mesh from the vehicle and create its own static mesh +2. Update the vehicle mesh to remove the steering wheel +3. Re-attach the steering wheel back as a code-based dynamic object + +For steps 1 & 2, we will be using the free & open source Blender program for the 3D modeling work: + +## 1. Extract the steering wheel + +### Exporting to FBX +First, go to the static mesh file you wish to export, in our case we wanted to export `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/SM_TeslaM3_v2.uasset` (notice these files should have a pink underline to indicate they are the full static mesh files). + +### One LOD +I recommend using the highest LOD ([Level-Of-Detail](../../LODS.md)) setting for this export, since this vehicle will be so close to the camera all the time it is pointless to have multiple LOD's, and it makes it simpler for the import to blender. + +To do this, simply enter the static mesh by double clicking it, and on the left "Asset Details" pane, down in "LOD Settings" drag the "Number of LODs" slider down to 1, then click "Apply Changes" as follows. +- ![LODs](../Figures/Model/LOD1.jpg) + +### Export to blender +Now, back in the `Content Browser` you can right click the file then select `Asset Actions -> Export` and designate a place for the resulting `.FBX` file to be exported. +- ![Export](../Figures/Model/Export.jpg) + +### Model in Blender +Now, open a fresh Blender window and delete the default spawned cube. Then go to `File -> Import -> FBX (.fbx)` and select the file you just created. + +You should now be presented with a simple Blender window with the vehicle like this: +- ![BlenderSolid](../Figures/Model/BlenderSolid.jpg) + +In order to toggle moving around using `WASD` controls, press `shift + ` `. Move inside the vehicle where you can find the steering wheel. + +The easiest way (I've found) to efficiently extract the steering wheel it so use the wireframe-mode to select all vertices, even those that aren't visible in the solid render. To go to wireframe mode press `z` then select `wireframe` (should be the left-most option). Then you should see something like this: +- ![WireframeWheel](../Figures/Model/WireframeWheel.jpg) + +Then, to actually select the proper vertices, we're going to need to change from `Object Mode` to `Edit Mode` in the top left corner of the viewport. Then we'll need to position our camera in such a way to minimize unwanted vertices being selected, and use whatever selection technique we want (I like the lasso selection) to select the entire steering wheel like this: +- ![SelectedWheel](../Figures/Model/SelectedWheel.jpg) +NOTE: if you have excess vertices selected, you can always undo those with `shift+click` on individual vertices. + +Then, you should be able to move the entire bunch out of the vehicle (or duplicate them all with `shift+d` and clean up the original) to have something like this: +| Wireframe | Rendered | +| --- | --- | +| ![WireFrameGotWheel](../Figures/Model/WheelOut.jpg) | ![SolidOut](../Figures/Model/VehicleAndWheel.jpg) | + +Finally, you should then be able to export the individual selections (need to export both the just-wheel and the just-vehicle models) by selecting all the vertices the same way (in wireframe) and deleting them (then undo-ing the deletion of course). Then selecting `File -> Export -> FBX(.fbx)` for best compatibility. Do this for both the Vehicle mesh as well as the steering wheel (I moved the steering wheel to the origin when exporting but I'm not sure this is necessary). + +## 2. Update the vehicle mesh + +### Back in the Editor +Now, back in the editor, we'll create a new directory for both the Vehicle mesh as well as the steering wheel. Most of the content from this section is a modified version of the [Carla-provided documentation](https://carla.readthedocs.io/en/latest/tuto_A_add_vehicle/). + +Then, in the new `Mesh` directory, we can simply right-click in the content browser and select `Import Asset` then select our FBX model. Make sure to set **Import Content Type** to `Geometry and Skinning Weights`, **Normal Import Method** to `Import Normals`, and **Material Import Method** to `Do not create materials`, and finally uncheck **Import Textures**. + +We should now have a (pink underlined) Skeletal mesh asset, (beige underlined) physics asset, and (baby blue underlined) skeleton asset. Then, right click on the new (pink underlined) skeletal mesh asset and select `Create -> Anim Blueprint` to create a new animation blueprint. + +In this animation blueprint, ensure the following: +- Go to `Class settings -> Details -> Class Options -> Parent Class` and reparent the class to a `VehicleAnimInstance`. +- In the `My Blueprint` section, click on `AnimGraph` and copy over the same graph logic from the existing `TeslaM3` animation to look like this: + +| Reparent | Animation | +| --- | --- | +| ![Reparent](../Figures/Model/AnimClassOption.jpg) | ![AnimGraph](../Figures/Model/AnimGraph.jpg) | + +Now you are done with the animation blueprint. + +In my experience I had to do some additional tweaking to use the right components for my overall mesh (pink underlined) as follows: +- `Asset Details -> Physics Asset`: Replace new with the existing `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/SM_TeslaM3_PhysicsAsset.uasset` physics asset (NOT the `_v2_` model!) +- `Asset Details -> Lighting`: Same as the Physics Asset +- `Preview Scene Settings -> Animation Blueprint`: The new animation blueprint you just created. + +Then finally, you can delete the newly imported PhysicsAsset file since it is no longer being used (I opted to use the vanilla TeslaM3 one instead) + +And in `BP_EgoVehicle_DReyeVR`, you can finally edit the `Mesh (Inherited) -> Details -> Mesh` field to use the new SM we just updated (pink underline). Since this clears the `Animation` section, you'll also need to update the `Mesh (Inherited) -> Animation -> Anim Class` field to use the new animation class we just made. + +Now the DReyeVR EgoVehicle should be fully drivable and operates just as it did before, but now with no steering wheel in the driver's seat! +![NoWheel](../Figures/Model/NoWheel.jpg) + +## 3. Re-attach the steering wheel dynamically +### Import to UE4 +Now we want to import the steering wheel back into the engine so we can dynamically spawn, place, and update it at runtime. + +The easiest way to do this is through importing the SteeringWheel `.fbx` just like with the Vehicle mesh, from there it should have all the original textures pre-applied and be slightly angled. + +To get rotations of the wheel to be in the Roll axis of the wheel itself (not its attachment), I recommend slightly tilting the static mesh wheel so that it is mostly vertical and select `Make Static Mesh`. + +This will allow you to create a plain simple static mesh (cyan underline) from the skeletal mesh (pink underline) as follows: +| Rotated Skeletal Mesh | Resulting Directory | +| --- | --- | +| ![RotWheel](../Figures/Model/WheelRot.jpg) | ![SelectedWheel](../Figures/Model/SelectSMWheel.jpg) | + +### Import in code +Now that we have a reasonable steering wheel model as a simple static mesh, it is easy to spawn it and attach it to the ego-vehicle (currently without a steering wheel) in code. Managing it in code is nice because it will allow us to `SetRelativeRotation` of the mesh dynamically on every tick, allowing it to be responsive to our inputs at runtime. + +The first step to Spawn the steering wheel in code is to find its mesh in the editor. Right click on the static mesh (cyan underline) and select `Copy Reference`. For me it looks like this: +- `"StaticMesh'/Game/DReyeVR/EgoVehicle/TeslaM3/SteeringWheel/Wheel_StaticMeshl_model3.Wheel_StaticMeshl_model3'"` + +(Note that we won't be needing any of the other steering wheel assets anymore, feel free to delete them) + +The general strategy for adding Unreal components in code is to spawn them in the constructor then use their reference alongside their C++ API. For our case we'll only need a constructor and a tick method (See [EgoVehicle::ConstructSteeringWheel & EgoVehicle::TickSteeringWheel](../../DReyeVR/EgoVehicle.cpp)) + Now enjoy a responsive steering wheel asset attached to the EgoVehicle as you drive around! \ No newline at end of file diff --git a/Docs/Tutorials/SetupVR.md b/Docs/Tutorials/SetupVR.md index 37c0bbf..96105f6 100644 --- a/Docs/Tutorials/SetupVR.md +++ b/Docs/Tutorials/SetupVR.md @@ -1,109 +1,109 @@ -# Setting up VR Mode -### Installing Carla -Follow Carla's own installation guide [here for Linux](https://carla.readthedocs.io/en/latest/build_linux/) and [here for Windows](https://carla.readthedocs.io/en/latest/build_windows/). This will also provide the information to build [Unreal Engine 4.26](https://github.com/carlaunreal/unrealengine) which is required to build Carla. - -## Setting up Carla for VR mode - -Assuming Carla is installed and runnable (you can test this with `make launch`) we can begin the process for configuring Carla to work in VR! - -### Windows users can skip *section III* below, as it is for configuring the `opengl` mode for Linux rendering - -### I. Prerequisites -We'll need [SteamVR](https://store.steampowered.com/app/250820/SteamVR/) to be installed and working with your VR headset. For both Linux & Windows this application should be installable through the native [Steam](https://store.steampowered.com/about/) application. - -For the remainder of my guides I used a [HTC Vive Pro Eye](https://enterprise.vive.com/us/product/vive-pro-eye-office/) headset with [Valve's lighthouse trackers](https://www.valvesoftware.com/en/index/base-stations). Note that for this study we only need one tracker since this is primarily a seated VR experience and we won't be needing all 360° of motion. - -This setup makes my SteamVR overlay look like this: - -![SteamVR](https://docs.google.com/drawings/d/e/2PACX-1vQofGTS8pATT58UxHzcVeWjhkYAqGw6PyrKpQ8GmK34p_1S1MehrKeUxNIpkAYB_D3T-s6v3d1_BMCl/pub?w=574&h=261) - -Additionally, note that for the best experience in this driving simulator we will be using the **Standing Only** environment setup for the SteamVR play area. This should be calibrated each time by right clicking the pop-up indicator from above and selecting `"Run Room Setup"` for the standing-only mode you'll need calibrate two main features: -1. Place the headset in the forward-facing direction of your posture, this will define the default forward orientation. -2. Place the headset on a stable surface off the ground and measure its relative position from the ground to get a sense of scale. - -With the SteamVR seated mode we should be ready to go to the next step. - -### II. UE4 SteamVR plugin -In order for SteamVR to communicate with Unreal Engine, we'll need to use Valve's [SteamVR plugins](https://github.com/ValveSoftware/steamvr_unreal_plugin). -- On Linux download the latest version (as of writing this guide is for UE4.23) and place the unzipped folder in `carla/Unreal/CarlaUE4/Plugins/` as explained in the [section I of Valve's README](https://github.com/ValveSoftware/steamvr_unreal_plugin#i-how-to-add-this-plugin-to-your-ue4-project) -- On Windows you can install SteamVR from within the [UE4 Marketplace](https://www.unrealengine.com/marketplace/en-US/product/steamvr-input-for-unreal), again the latest version is advised. - -As mentioned before, the current latest available version of SteamVR is for UE4.23 but our installation is for UE4.26. This is fine and will still function for our purposes, we'll simply have a skippable warning upon launching the editor. It will look something like this, just click `Yes` -![SteamVRWarning](https://docs.google.com/drawings/d/e/2PACX-1vRmJfEeP6SmlzxgBhottJYmfrb72O7J3lztErcpmd97iBKFVAZe7DxPCGzBjyeqIfyRkeCyvafh1fTJ/pub?w=913&h=205) - - -### III. Configuring `opengl` rendering -**Note this is not required if you're on Windows. The Windows version of Carla/UE4 works with Vulkan and DX11/12* - -Unfortunately, we've had little success getting Vulkan VR support on Linux with UE4. Specifically due to this [bug](https://github.com/ValveSoftware/SteamVR-for-Linux/issues/404). There are supposedly workarounds but we haven't tested them. Note that if you don't want to use VR then using Vulkan on Linux is perfectly fine. - -Here's some information provided by Carla on [Vulkan vs OpenGL rendering options](https://carla.readthedocs.io/en/latest/adv_rendering_options/) - -In the *Release* version of Carla, they provide an executable `CarlaUE4.sh` which can toggle `opengl` mode with a simple flag `./CarlaUE4.sh -opengl`. - -However, since we want to build Carla from source we'll need do the following: -1. In `carla/Util/BuildTools/BuildCarlaUE4.sh` on line 29 we'll want to change `RHI="-vulkan"` to `RHI="-opengl"` to default to `opengl` mode. [Source](https://github.com/carla-simulator/carla/issues/2063) - 1. You should be able `make launch` now and the `opengl` mode should be applied by default - 1. If you are getting a `Trying to force OpenGL RHI but the project does not have it in TargetedRHIs list.` error then you should look at this [guide](https://rhycesmith.com/2020/06/12/enable-opengl-and-disable-vulkan-in-unreal-engine-4-25/) to reenable OpenGL. -2. You should now be able to simply `make launch` and have a working OpenGL backend renderer. There may be additional shader/texture compilation required after booting into the editor for the first time. - -Also note that since `openGL` is technically deprecated you'll get another harmless warning when launching the editor, again you can just click `Ok`: - -![openGL](https://docs.google.com/drawings/d/e/2PACX-1vSn72GkhBOvmfa_vMnjTwvv9KPk34i6ZpHgMgpBjRPp_1_k0kF55TgjZHvGw2CfdJtckqENuNbNilhr/pub?w=556&h=205) - -## Running Carla in VR mode - -With all the installations done, we can move on to actually using Carla+UE4 with VR mode. These are the instructions to run it from scratch. - -1. Plug in VR headset to your computer. - 1. Make sure the headset is supported by UE4 (Officially supported: Oculus Rift, Samsung Gear VR, HTC Vive, PSVR, Google VR, Windows Mixed Reality, etc.). More info can be found in the [UE4 documentation](https://www.unrealengine.com/en-US/vr). -2. Start SteamVR and make sure the headset is detected and active -3. After running `make launch` and loading the editor, you should be able to see this dropdown menu: - -| Dropdown Menu | Resulting Play Button | -| --- | --- | -|
UE4DropDown
|
UE4DropDown
| - -1. From here we can compile a binary of Carla with VR support. To do so, run `make package` and locate the resulting executable in: - 1. Linux: `carla/Dist/CARLA_Shipping_*/LinuxNoEditor/CarlaUE4.sh` - 2. Windows: `carla\Build\UE4Carla\0.9.13-*\WindowsNoEditor\CarlaUE4.exe` -2. Then run the binary with VR mode enabled with `-vr` flags: - 1. Linux: `./CarlaUE4.sh -vr` (from any terminal) - 2. Windows: `CarlaUE4.exe -vr` (from the `x64 Visual C++ Toolset` command prompt) - -## More like this -If you liked this style of guide and are fine with using UE4 blueprints before diving straight into C++, we recommend taking a look at [these older guides](https://github.com/GustavoSilvera/VR-Carla-Docs) published for an earlier version of this project. (Most of the guide information is on setting up a VR ego-vehicle using blueprints and is still accurate) - -## Other Tips -### Performance -Note that in some cases the VR mode under Linux and OpenGL takes a big performance hit and may have poor frametimes even with powerful GPU's. - -To get a much smoother experience you can run Carla with the flag `-quality-level=Low` instead of the default `-quality-level=Epic`. More information can be found in the [Carla Rendering Documentation](https://carla.readthedocs.io/en/latest/adv_rendering_options/). - -For our later purposes, we'd want to keep the **full rendering distance** which is provided in the `Epic` quality but not `Low`. But for improved performance we may want to tone down the graphical fidelity like `Low`, so we'll need to modify some source code and recompile the project. - -You can modify the `C++` file at `carla/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp` on line 99 with: -```c++ -case EQualityLevel::Low: -{ - // execute tweaks for quality - LaunchLowQualityCommands(InWorld); - // iterate all directional lights, deactivate shadows - SetAllLights(InWorld, CarlaSettings->LowLightFadeDistance, false, true); - // Set all the roads the low quality materials - SetAllRoads(InWorld, CarlaSettings->LowRoadPieceMeshMaxDrawDistance, CarlaSettings->LowRoadMaterials); - // Set all actors with static meshes a max distance configured in the - // global settings for the low quality - SetAllActorsDrawDistance(InWorld, CarlaSettings->LowStaticMeshMaxDrawDistance); - // Disable all post process volumes - SetPostProcessEffectsEnabled(InWorld, false); - break; -} -``` -Simply change the `SetAllActorsDrawDistance` to match the case for `Epic` quality: -```c++ - // Set all actors with static meshes a max distance configured in the - // global settings for the low quality - SetAllActorsDrawDistance(InWorld, 0); // Full render distance -``` +# Setting up VR Mode +### Installing Carla +Follow Carla's own installation guide [here for Linux](https://carla.readthedocs.io/en/latest/build_linux/) and [here for Windows](https://carla.readthedocs.io/en/latest/build_windows/). This will also provide the information to build [Unreal Engine 4.26](https://github.com/carlaunreal/unrealengine) which is required to build Carla. + +## Setting up Carla for VR mode + +Assuming Carla is installed and runnable (you can test this with `make launch`) we can begin the process for configuring Carla to work in VR! + +### Windows users can skip *section III* below, as it is for configuring the `opengl` mode for Linux rendering + +### I. Prerequisites +We'll need [SteamVR](https://store.steampowered.com/app/250820/SteamVR/) to be installed and working with your VR headset. For both Linux & Windows this application should be installable through the native [Steam](https://store.steampowered.com/about/) application. + +For the remainder of my guides I used a [HTC Vive Pro Eye](https://enterprise.vive.com/us/product/vive-pro-eye-office/) headset with [Valve's lighthouse trackers](https://www.valvesoftware.com/en/index/base-stations). Note that for this study we only need one tracker since this is primarily a seated VR experience and we won't be needing all 360° of motion. + +This setup makes my SteamVR overlay look like this: + +![SteamVR](https://docs.google.com/drawings/d/e/2PACX-1vQofGTS8pATT58UxHzcVeWjhkYAqGw6PyrKpQ8GmK34p_1S1MehrKeUxNIpkAYB_D3T-s6v3d1_BMCl/pub?w=574&h=261) + +Additionally, note that for the best experience in this driving simulator we will be using the **Standing Only** environment setup for the SteamVR play area. This should be calibrated each time by right clicking the pop-up indicator from above and selecting `"Run Room Setup"` for the standing-only mode you'll need calibrate two main features: +1. Place the headset in the forward-facing direction of your posture, this will define the default forward orientation. +2. Place the headset on a stable surface off the ground and measure its relative position from the ground to get a sense of scale. + +With the SteamVR seated mode we should be ready to go to the next step. + +### II. UE4 SteamVR plugin +In order for SteamVR to communicate with Unreal Engine, we'll need to use Valve's [SteamVR plugins](https://github.com/ValveSoftware/steamvr_unreal_plugin). +- On Linux download the latest version (as of writing this guide is for UE4.23) and place the unzipped folder in `carla/Unreal/CarlaUE4/Plugins/` as explained in the [section I of Valve's README](https://github.com/ValveSoftware/steamvr_unreal_plugin#i-how-to-add-this-plugin-to-your-ue4-project) +- On Windows you can install SteamVR from within the [UE4 Marketplace](https://www.unrealengine.com/marketplace/en-US/product/steamvr-input-for-unreal), again the latest version is advised. + +As mentioned before, the current latest available version of SteamVR is for UE4.23 but our installation is for UE4.26. This is fine and will still function for our purposes, we'll simply have a skippable warning upon launching the editor. It will look something like this, just click `Yes` +![SteamVRWarning](https://docs.google.com/drawings/d/e/2PACX-1vRmJfEeP6SmlzxgBhottJYmfrb72O7J3lztErcpmd97iBKFVAZe7DxPCGzBjyeqIfyRkeCyvafh1fTJ/pub?w=913&h=205) + + +### III. Configuring `opengl` rendering +**Note this is not required if you're on Windows. The Windows version of Carla/UE4 works with Vulkan and DX11/12* + +Unfortunately, we've had little success getting Vulkan VR support on Linux with UE4. Specifically due to this [bug](https://github.com/ValveSoftware/SteamVR-for-Linux/issues/404). There are supposedly workarounds but we haven't tested them. Note that if you don't want to use VR then using Vulkan on Linux is perfectly fine. + +Here's some information provided by Carla on [Vulkan vs OpenGL rendering options](https://carla.readthedocs.io/en/latest/adv_rendering_options/) + +In the *Release* version of Carla, they provide an executable `CarlaUE4.sh` which can toggle `opengl` mode with a simple flag `./CarlaUE4.sh -opengl`. + +However, since we want to build Carla from source we'll need do the following: +1. In `carla/Util/BuildTools/BuildCarlaUE4.sh` on line 29 we'll want to change `RHI="-vulkan"` to `RHI="-opengl"` to default to `opengl` mode. [Source](https://github.com/carla-simulator/carla/issues/2063) + 1. You should be able `make launch` now and the `opengl` mode should be applied by default + 1. If you are getting a `Trying to force OpenGL RHI but the project does not have it in TargetedRHIs list.` error then you should look at this [guide](https://rhycesmith.com/2020/06/12/enable-opengl-and-disable-vulkan-in-unreal-engine-4-25/) to reenable OpenGL. +2. You should now be able to simply `make launch` and have a working OpenGL backend renderer. There may be additional shader/texture compilation required after booting into the editor for the first time. + +Also note that since `openGL` is technically deprecated you'll get another harmless warning when launching the editor, again you can just click `Ok`: + +![openGL](https://docs.google.com/drawings/d/e/2PACX-1vSn72GkhBOvmfa_vMnjTwvv9KPk34i6ZpHgMgpBjRPp_1_k0kF55TgjZHvGw2CfdJtckqENuNbNilhr/pub?w=556&h=205) + +## Running Carla in VR mode + +With all the installations done, we can move on to actually using Carla+UE4 with VR mode. These are the instructions to run it from scratch. + +1. Plug in VR headset to your computer. + 1. Make sure the headset is supported by UE4 (Officially supported: Oculus Rift, Samsung Gear VR, HTC Vive, PSVR, Google VR, Windows Mixed Reality, etc.). More info can be found in the [UE4 documentation](https://www.unrealengine.com/en-US/vr). +2. Start SteamVR and make sure the headset is detected and active +3. After running `make launch` and loading the editor, you should be able to see this dropdown menu: + +| Dropdown Menu | Resulting Play Button | +| --- | --- | +|
UE4DropDown
|
UE4DropDown
| + +1. From here we can compile a binary of Carla with VR support. To do so, run `make package` and locate the resulting executable in: + 1. Linux: `carla/Dist/CARLA_Shipping_*/LinuxNoEditor/CarlaUE4.sh` + 2. Windows: `carla\Build\UE4Carla\0.9.13-*\WindowsNoEditor\CarlaUE4.exe` +2. Then run the binary with VR mode enabled with `-vr` flags: + 1. Linux: `./CarlaUE4.sh -vr` (from any terminal) + 2. Windows: `CarlaUE4.exe -vr` (from the `x64 Visual C++ Toolset` command prompt) + +## More like this +If you liked this style of guide and are fine with using UE4 blueprints before diving straight into C++, we recommend taking a look at [these older guides](https://github.com/GustavoSilvera/VR-Carla-Docs) published for an earlier version of this project. (Most of the guide information is on setting up a VR ego-vehicle using blueprints and is still accurate) + +## Other Tips +### Performance +Note that in some cases the VR mode under Linux and OpenGL takes a big performance hit and may have poor frametimes even with powerful GPU's. + +To get a much smoother experience you can run Carla with the flag `-quality-level=Low` instead of the default `-quality-level=Epic`. More information can be found in the [Carla Rendering Documentation](https://carla.readthedocs.io/en/latest/adv_rendering_options/). + +For our later purposes, we'd want to keep the **full rendering distance** which is provided in the `Epic` quality but not `Low`. But for improved performance we may want to tone down the graphical fidelity like `Low`, so we'll need to modify some source code and recompile the project. + +You can modify the `C++` file at `carla/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp` on line 99 with: +```c++ +case EQualityLevel::Low: +{ + // execute tweaks for quality + LaunchLowQualityCommands(InWorld); + // iterate all directional lights, deactivate shadows + SetAllLights(InWorld, CarlaSettings->LowLightFadeDistance, false, true); + // Set all the roads the low quality materials + SetAllRoads(InWorld, CarlaSettings->LowRoadPieceMeshMaxDrawDistance, CarlaSettings->LowRoadMaterials); + // Set all actors with static meshes a max distance configured in the + // global settings for the low quality + SetAllActorsDrawDistance(InWorld, CarlaSettings->LowStaticMeshMaxDrawDistance); + // Disable all post process volumes + SetPostProcessEffectsEnabled(InWorld, false); + break; +} +``` +Simply change the `SetAllActorsDrawDistance` to match the case for `Epic` quality: +```c++ + // Set all actors with static meshes a max distance configured in the + // global settings for the low quality + SetAllActorsDrawDistance(InWorld, 0); // Full render distance +``` Now, recompiling the project with `make package` will have a `Low` quality preset with full rendering distance. \ No newline at end of file diff --git a/Docs/Tutorials/Signs.md b/Docs/Tutorials/Signs.md index 040d5e5..197cdba 100644 --- a/Docs/Tutorials/Signs.md +++ b/Docs/Tutorials/Signs.md @@ -1,155 +1,155 @@ -# Adding custom signs in the Carla world - -## What is this? -It is often useful to have participants in an experiment know what directions to take in a natural manner without manual intervention. In Carla this is not a problem since all the drivers are AI controllers, but for humans we can't simply ingest a text file denoting waypoints and directions. This is where in-environment directional signs can be of use. Unfortunately, Carla does not provide any (since this is not a problem for them) and there were enough steps to warrant a guide, so here you go. - -This guide will show you how to create your own custom signs and place them in any Carla level (*Technically, the guide can work to add any custom props in Carla, not just signs*) -- The steps are as follows: - 1. Create the sign textures (rgb/normals) - 2. Create the sign mesh/material - 3. Apply the materials onto a blueprint - 4. Manually place the blueprint into the world - 5. **Optional:** Register the new sign with the blueprint library - -## Getting started -Sign textures can be found in Carla in the `carla/Unreal/CarlaUE4/Content/Carla/Static/TrafficSign/` directory. - -For example, you should see a directory that looks like this: - -![SignDirectory](../Figures/Signs/directory.jpg) - -Notice how all the models have a corresponding directory (some are cut off in the screenshot). These are where the static meshes and textures are defined so they can be used on these sign-shaped blueprints. - -- For the rest of this guide, we'll focus on using the `NoTurn` directory that looks like this when opened in the content browser: -![NoTurnDir](../Figures/Signs/no_turn_dir.jpg) - -- From left to right these are the **Material Instance** (`M_` prefix), **Static Mesh** (`SM_` prefix), **Texture RGB** (`__0` suffix), and **Texture Normals** (`_n` suffix) - -## Step 1: Creating the sign textures -The "NO TURN" sign serves as a good baseline for creating our custom signs, though any signs can be used as a starting point. - -Now, you can screenshot the image (or find its source file in Details->File Path) to get a `.jpg` of the desired texture, then clear out the original text ("NO TURN") so it is a blank canvas. For your convenience we have a blank "NO TURN" sign already provided in [`Content/Static/DefaultSign.jpg`](../../Content/Static/DefaultSign.jpg) -- Notice how the bottom right corner of these images has is a small gray-ish region. This is actually for the rear of the sign so that when it is applied on to the models, the rear has this metallic surface. - - This means we want to do most of our sign content editing in the region within the black perimeter - -It is useful to have a powerful image editing tool for this, we used [GIMP](https://www.gimp.org/) (free & open source) and the rest of this section will reference it as the image editing tool. - -From within Gimp you should be able to add whatever static components you like (text, images, etc.) within the designated region. Once you are finished with your new sign image, export it as a `.jpg`. - -Next, you'll want GIMP to create the normals map for you. This can be done easily by going through `Filters -> Generic -> Normal Map` and applying the default normal generation to the newly created image. Export this file with the suffix `_n.jpg` to indicate that it is the normal map. - -For example, if we wanted our sign to say "RIGHT TO CITY A", then after this process you should see something that looks like this: - -![SignTextures](../Figures/Signs/textures_no_turn.jpg) - -Now we are done with image manipulation and using GIMP. - -Now back in UE4, it'll be easiest if you duplicate the `TrafficSign/NoTurn/` directory into your custom directory (such as `DReyeVR_Signs/` with all the same 4 elements (material, static mesh, texture RGB, and texture normals)). -- Note: there are some reports of users not being able to copy/paste/duplicate directly in the editor. In this case, just do so in your file manager and reopen the editor again. - - ```bash - cd $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/TrafficSign/ - cp -r NoTurn/ RightCityA/ - ``` - - ```bash - # now RightCityA contains the following - RightCityA - - M_NoTurns.uasset - - SM_noTurn.uasset - - SM_noTurn_n.uasset - - SM_noTurn_.uasset - ``` - -| | | -| ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------ | -| Now, in your new custom directory, you can easily reimport a new `.jpg` source file by clicking the `Reimport` button at the top.

Locate your rgb `.jpg` image for the `SM_noTurn` reimport, and use the normals `.jpg` image for the `SM_noTurn_n` reimport. | Reimport | - -Feel free to rename the `SM_noTurn_*` asset files **within the editor** (right click in content browser -> rename) and keep the naming scheme. Something like `SM_RightCityA` and `SM_RightCityA_n`. - -## Step 2: Creating the sign meshes & materials -Now, you should make sure that the **Material** (`M_noTurns`) asset file is updated with the new textures. This may occur automatically, but just in case you should open it up in the editor and select the newly created `SM_RightCityA` and `SM_RightCityA_n` as the Texture parameter values for `SpeedSign_d` and `SpeedSign_n` respectively. -- To do this, click the dropdown menu box which say `SM_noTurn` and `SM_noTurn_n` and search for the new `RightCityA` variants -- The parameters should then look something like this - ![Parameters](../Figures/Signs/parameters.jpg) - -Save it and rename it (**in the editor**) as well: `M_RightCityA` should suffice. - -Now, finally open up the `SM_noTurn_` (static mesh) asset file and ensure it uses our newly created `M_RightCityA` material by editing the Material element in the Material Slots: -- Similarly to before, this is done in the Details pane by clicking the dropdown, searching for "RightCity", and selecting our new material - ![SignMaterial](../Figures/Signs/material.jpg) - -Save it and rename it (always **in the editor**): `SM_RightCityA_` works. - -At this point you should have a `RightCityA` directory that looks like the following: - -![RightCityDir](../Figures/Signs/rightcity_directory.jpg) - -## Step 3: Applying the new materials onto a blueprint - -Once all the desired materials/static meshes are ready, duplicate a sign blueprint (from the parent `TrafficSign` directory) and place it in `RightCityA` -- This should be doable from within the editor. Right click `BP_NoTurns` -> Duplicate -> Enter new name -> Drag to `RightCityA/` -> select move - -Open up the blueprint to the `Viewport` tab and select the sign component (not the pole) - -In the Details pane you should again see a `Static Mesh` component that is still the `SM_noTurn_`, replace that with out new `SM_RightCityA_` asset, Recompile & Save, and you should be done. - -Now it should look like this: - -![SignBP](../Figures/Signs/bp.jpg) - -## Step 4: Placing the new sign in the world - -With our new sign blueprint, we can place it into the world fairly easily. Simply drag and drop it into the world, then edit its transform, rotation, and scale parameters to fine tune the result. - -The end result should look pretty decent, here's an example of our new sign in `Town03` - -| Front of the sign | Rear of the sign | -| ------------------------------------------- | ----------------------------------------- | -| ![FrontSign](../Figures/Signs/right_front.jpg) | ![RearSign](../Figures/Signs/right_rear.jpg) | - -Notice how both the front and rear look good, this is because the rear is given the metallic region from the bottom-right of the texture. - -## Step 5: (Optional) Registering with the BP library - -Registering our new sign with Carla's blueprint library allows us to spawn the sign from the PythonAPI and hence allows for dynamic placement at runtime. - -This is slightly more in-depth than the existing Carla signs since they were not designed to be spawned dynamically, rather they were placed into the world statically at compile-time. This becomes frustrating if we'd like to place different signs around the map for various scenarios without recompiling everything again. - -As per [this issue](https://github.com/carla-simulator/carla/issues/4363), the usual way of using custom props on Carla 0.9.11 is currently broken and unreliable. We found a [workaround](https://github.com/carla-simulator/carla/issues/4363#issuecomment-924140532) and included it in the issue. - -Essentially you'll need to edit the `carla/Unreal/CarlaUE4/Content/Carla/Config/Default.Package.json` file to include your new sign prop as follows: - -```json - { - "name": "YOUR_SIGN_NAME", - "path": "/PATH/TO/YOUR/SM_SIGN.SM_SIGN", - "size": "Medium" - } -``` -Note that the `"path"` source is looking for a UE4 static mesh object, which will be stored as a `.uasset` file. Still denote it as `SM_name.SM_name` in the `json`. - -Importantly, if you want to include a custom prop directory in `Content/` (instead of using our `DReyeVR/DReyeVR_Signs/` content) you should add this to the list of cooked assets in `Config/DefaultGame.ini` such as: - -```ini -+DirectoriesToAlwaysCook=(Path="/Game/DReyeVR/DReyeVR_Signs") # what we include -+DirectoriesToAlwaysCook=(Path="/Game/YOUR_PROP_DIR/") # any desired prop directory -``` -This ensures your custom props are properly cooked during shipping (`make package`). - -Once this change is imported in the map you will be able to spawn your sign as follows: -```python -bp = blueprint_library.filter(("static.prop.YOUR_SIGN_NAME").lower()) # filter is lowercase! -assert len(bp) == 1 # you should only have one prop of this name -transform = world.get_map().get_spawn_points()[0] # or choose any other spawn point -world.spawn_actor(bp[0], transform) # should succeed with no errors -``` - -**NOTE** In constructing our (and Carla's) signs, we unlink the sign itself from the pole it connects to. Therefore, if you want to spawn the sign *with* the pole you'll need to combine these static meshes. -- This is supported within the editor by placing both actors into the world, selecting both, then using the Window -> Developer -> MergeActors button as described in [this guide](https://docs.unrealengine.com/4.27/en-US/Basics/Actors/Merging/). -- We have already provided a baseline with the [`Content/DReyeVR_Signs/FullSign/`](Content/DReyeVR_Signs/FullSign/) directory where we combined the signs with the poles as a single static mesh. - - With this baseline, assuming you have a compatible material (using the same sign template as ours) you can just update the material for the sign component without further modification. - - -# Automatic Sign Placement -When using our [scenario-runner fork](https://github.com/HARPLab/scenario_runner/tree/DReyeVR-0.9.13), there is logic to enable spawning the corresponding directional signs automatically according to the route features (straight, turn left, turn right, and goal). The logic for this can be found in the [route_scenario's nav sign code](https://github.com/HARPLab/scenario_runner/blob/3b5e60f15fd97de00332f80610051f9f39d7db8c/srunner/scenarios/route_scenario.py#L284-L355). Since this is automatically applied to all routes, you can disable it manually by commenting the `self._setup_nav_signs(self.route)` method call. - +# Adding custom signs in the Carla world + +## What is this? +It is often useful to have participants in an experiment know what directions to take in a natural manner without manual intervention. In Carla this is not a problem since all the drivers are AI controllers, but for humans we can't simply ingest a text file denoting waypoints and directions. This is where in-environment directional signs can be of use. Unfortunately, Carla does not provide any (since this is not a problem for them) and there were enough steps to warrant a guide, so here you go. + +This guide will show you how to create your own custom signs and place them in any Carla level (*Technically, the guide can work to add any custom props in Carla, not just signs*) +- The steps are as follows: + 1. Create the sign textures (rgb/normals) + 2. Create the sign mesh/material + 3. Apply the materials onto a blueprint + 4. Manually place the blueprint into the world + 5. **Optional:** Register the new sign with the blueprint library + +## Getting started +Sign textures can be found in Carla in the `carla/Unreal/CarlaUE4/Content/Carla/Static/TrafficSign/` directory. + +For example, you should see a directory that looks like this: + +![SignDirectory](../Figures/Signs/directory.jpg) + +Notice how all the models have a corresponding directory (some are cut off in the screenshot). These are where the static meshes and textures are defined so they can be used on these sign-shaped blueprints. + +- For the rest of this guide, we'll focus on using the `NoTurn` directory that looks like this when opened in the content browser: +![NoTurnDir](../Figures/Signs/no_turn_dir.jpg) + +- From left to right these are the **Material Instance** (`M_` prefix), **Static Mesh** (`SM_` prefix), **Texture RGB** (`__0` suffix), and **Texture Normals** (`_n` suffix) + +## Step 1: Creating the sign textures +The "NO TURN" sign serves as a good baseline for creating our custom signs, though any signs can be used as a starting point. + +Now, you can screenshot the image (or find its source file in Details->File Path) to get a `.jpg` of the desired texture, then clear out the original text ("NO TURN") so it is a blank canvas. For your convenience we have a blank "NO TURN" sign already provided in [`Content/Static/DefaultSign.jpg`](../../Content/Static/DefaultSign.jpg) +- Notice how the bottom right corner of these images has is a small gray-ish region. This is actually for the rear of the sign so that when it is applied on to the models, the rear has this metallic surface. + - This means we want to do most of our sign content editing in the region within the black perimeter + +It is useful to have a powerful image editing tool for this, we used [GIMP](https://www.gimp.org/) (free & open source) and the rest of this section will reference it as the image editing tool. + +From within Gimp you should be able to add whatever static components you like (text, images, etc.) within the designated region. Once you are finished with your new sign image, export it as a `.jpg`. + +Next, you'll want GIMP to create the normals map for you. This can be done easily by going through `Filters -> Generic -> Normal Map` and applying the default normal generation to the newly created image. Export this file with the suffix `_n.jpg` to indicate that it is the normal map. + +For example, if we wanted our sign to say "RIGHT TO CITY A", then after this process you should see something that looks like this: + +![SignTextures](../Figures/Signs/textures_no_turn.jpg) + +Now we are done with image manipulation and using GIMP. + +Now back in UE4, it'll be easiest if you duplicate the `TrafficSign/NoTurn/` directory into your custom directory (such as `DReyeVR_Signs/` with all the same 4 elements (material, static mesh, texture RGB, and texture normals)). +- Note: there are some reports of users not being able to copy/paste/duplicate directly in the editor. In this case, just do so in your file manager and reopen the editor again. + - ```bash + cd $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/TrafficSign/ + cp -r NoTurn/ RightCityA/ + ``` + - ```bash + # now RightCityA contains the following + RightCityA + - M_NoTurns.uasset + - SM_noTurn.uasset + - SM_noTurn_n.uasset + - SM_noTurn_.uasset + ``` + +| | | +| ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------ | +| Now, in your new custom directory, you can easily reimport a new `.jpg` source file by clicking the `Reimport` button at the top.

Locate your rgb `.jpg` image for the `SM_noTurn` reimport, and use the normals `.jpg` image for the `SM_noTurn_n` reimport. | Reimport | + +Feel free to rename the `SM_noTurn_*` asset files **within the editor** (right click in content browser -> rename) and keep the naming scheme. Something like `SM_RightCityA` and `SM_RightCityA_n`. + +## Step 2: Creating the sign meshes & materials +Now, you should make sure that the **Material** (`M_noTurns`) asset file is updated with the new textures. This may occur automatically, but just in case you should open it up in the editor and select the newly created `SM_RightCityA` and `SM_RightCityA_n` as the Texture parameter values for `SpeedSign_d` and `SpeedSign_n` respectively. +- To do this, click the dropdown menu box which say `SM_noTurn` and `SM_noTurn_n` and search for the new `RightCityA` variants +- The parameters should then look something like this + ![Parameters](../Figures/Signs/parameters.jpg) + +Save it and rename it (**in the editor**) as well: `M_RightCityA` should suffice. + +Now, finally open up the `SM_noTurn_` (static mesh) asset file and ensure it uses our newly created `M_RightCityA` material by editing the Material element in the Material Slots: +- Similarly to before, this is done in the Details pane by clicking the dropdown, searching for "RightCity", and selecting our new material + ![SignMaterial](../Figures/Signs/material.jpg) + +Save it and rename it (always **in the editor**): `SM_RightCityA_` works. + +At this point you should have a `RightCityA` directory that looks like the following: + +![RightCityDir](../Figures/Signs/rightcity_directory.jpg) + +## Step 3: Applying the new materials onto a blueprint + +Once all the desired materials/static meshes are ready, duplicate a sign blueprint (from the parent `TrafficSign` directory) and place it in `RightCityA` +- This should be doable from within the editor. Right click `BP_NoTurns` -> Duplicate -> Enter new name -> Drag to `RightCityA/` -> select move + +Open up the blueprint to the `Viewport` tab and select the sign component (not the pole) + +In the Details pane you should again see a `Static Mesh` component that is still the `SM_noTurn_`, replace that with out new `SM_RightCityA_` asset, Recompile & Save, and you should be done. + +Now it should look like this: + +![SignBP](../Figures/Signs/bp.jpg) + +## Step 4: Placing the new sign in the world + +With our new sign blueprint, we can place it into the world fairly easily. Simply drag and drop it into the world, then edit its transform, rotation, and scale parameters to fine tune the result. + +The end result should look pretty decent, here's an example of our new sign in `Town03` + +| Front of the sign | Rear of the sign | +| ------------------------------------------- | ----------------------------------------- | +| ![FrontSign](../Figures/Signs/right_front.jpg) | ![RearSign](../Figures/Signs/right_rear.jpg) | + +Notice how both the front and rear look good, this is because the rear is given the metallic region from the bottom-right of the texture. + +## Step 5: (Optional) Registering with the BP library + +Registering our new sign with Carla's blueprint library allows us to spawn the sign from the PythonAPI and hence allows for dynamic placement at runtime. + +This is slightly more in-depth than the existing Carla signs since they were not designed to be spawned dynamically, rather they were placed into the world statically at compile-time. This becomes frustrating if we'd like to place different signs around the map for various scenarios without recompiling everything again. + +As per [this issue](https://github.com/carla-simulator/carla/issues/4363), the usual way of using custom props on Carla 0.9.11 is currently broken and unreliable. We found a [workaround](https://github.com/carla-simulator/carla/issues/4363#issuecomment-924140532) and included it in the issue. + +Essentially you'll need to edit the `carla/Unreal/CarlaUE4/Content/Carla/Config/Default.Package.json` file to include your new sign prop as follows: + +```json + { + "name": "YOUR_SIGN_NAME", + "path": "/PATH/TO/YOUR/SM_SIGN.SM_SIGN", + "size": "Medium" + } +``` +Note that the `"path"` source is looking for a UE4 static mesh object, which will be stored as a `.uasset` file. Still denote it as `SM_name.SM_name` in the `json`. + +Importantly, if you want to include a custom prop directory in `Content/` (instead of using our `DReyeVR/DReyeVR_Signs/` content) you should add this to the list of cooked assets in `Config/DefaultGame.ini` such as: + +```ini ++DirectoriesToAlwaysCook=(Path="/Game/DReyeVR/DReyeVR_Signs") # what we include ++DirectoriesToAlwaysCook=(Path="/Game/YOUR_PROP_DIR/") # any desired prop directory +``` +This ensures your custom props are properly cooked during shipping (`make package`). + +Once this change is imported in the map you will be able to spawn your sign as follows: +```python +bp = blueprint_library.filter(("static.prop.YOUR_SIGN_NAME").lower()) # filter is lowercase! +assert len(bp) == 1 # you should only have one prop of this name +transform = world.get_map().get_spawn_points()[0] # or choose any other spawn point +world.spawn_actor(bp[0], transform) # should succeed with no errors +``` + +**NOTE** In constructing our (and Carla's) signs, we unlink the sign itself from the pole it connects to. Therefore, if you want to spawn the sign *with* the pole you'll need to combine these static meshes. +- This is supported within the editor by placing both actors into the world, selecting both, then using the Window -> Developer -> MergeActors button as described in [this guide](https://docs.unrealengine.com/4.27/en-US/Basics/Actors/Merging/). +- We have already provided a baseline with the [`Content/DReyeVR_Signs/FullSign/`](Content/DReyeVR_Signs/FullSign/) directory where we combined the signs with the poles as a single static mesh. + - With this baseline, assuming you have a compatible material (using the same sign template as ours) you can just update the material for the sign component without further modification. + + +# Automatic Sign Placement +When using our [scenario-runner fork](https://github.com/HARPLab/scenario_runner/tree/DReyeVR-0.9.13), there is logic to enable spawning the corresponding directional signs automatically according to the route features (straight, turn left, turn right, and goal). The logic for this can be found in the [route_scenario's nav sign code](https://github.com/HARPLab/scenario_runner/blob/3b5e60f15fd97de00332f80610051f9f39d7db8c/srunner/scenarios/route_scenario.py#L284-L355). Since this is automatically applied to all routes, you can disable it manually by commenting the `self._setup_nav_signs(self.route)` method call. + There is also a file method in case you want to manually place signs for specific routes (see [here](https://github.com/HARPLab/scenario_runner/blob/DReyeVR-0.9.13/srunner/data/all_routes_signs.json)), but we found that the automatic sign placement works fine most of the time and is much more convenient. So the automatic method is recommended and you don't have to do anything to enable it. \ No newline at end of file diff --git a/Docs/Tutorials/Sounds.md b/Docs/Tutorials/Sounds.md index 11b5ffe..a5c4fff 100644 --- a/Docs/Tutorials/Sounds.md +++ b/Docs/Tutorials/Sounds.md @@ -1,140 +1,140 @@ -# Adding and using sound in Carla+`DReyeVR` - -One of the first things you might notice when trying out `Carla` (all versions) is that there is absolutely no sound in the simulator. However, for our purposes, we are striving for an immersive experience with lots of feedback to a user about the world, and sound is a great way to add that. - -In this doc we'll go over how we added sound of the following: -1. Vehicle engine revving -2. Other vehicle sounds (gears/turn signals) -3. Ambient world noise -4. Acknowledgements - -## Engine revving -One of the best feedback mechanisms for a user applying throttle is the roar of an engine as the RPM increases. -- Yes, we know, we're using a Tesla model for our ego-vehicle but giving it engine/gear noises... blasphemy! - -[**CREDITS**]Most of this section comes from this [very helpful guide on youtube](https://www.youtube.com/watch?v=-c-f1aaIOnU) which is also available in [written form as an article](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/). We highly recommend taking a look at it to get step-by-step instructions and visuals for the following steps. -### Creating the sounds -(skip this step if you already have desired sound files for your engine) -1. Download requisite software: - - [LMMS](https://lmms.io/) (download for [Linux](https://lmms.io/download#linux)/[Windows](https://lmms.io/download#windows)/[Mac](https://lmms.io/download#mac)) for creating music tracks -2. Create 4 sounds, these correspond to when the engine is idle (1), running slowly (2), running normally (3), and running at max RPM (4) - - For all these tracks, we'll start with a sole TripleOscillator playing a constant C2 octave (4 beats should be fine). - | Configuration | Visually | - | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------- | - | PM value for OSC1+OSC2
PM value for OSC2+OSC3
OSC1 volume of 60
OSC1 CRS of -4
OSC1 to use triangle wave
OSC2 CRS of -24
OSC3 CRS of -24

Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) | ![TripleOscillator](../Figures/Sounds/triple_oscillator.jpg) | - - Then we'll want to amplify this effect by adding an LMMS-type Amplifier from the FX-Mixer window and crank the volume to the max. - 1. This works for the idle engine sound, nothing more to do here. The remaining drive sounds will gradually increase their CRS values. - 2. For Drive1 change OSC1 CRS to 0, OSC2 CRS to -20, OSC3 CRS to -20. - 3. For Drive2 change OSC1 CRS to 2, OSC2 CRS to -18, OSC3 CRS to -18. - 4. For Drive3 change OSC1 CRS to 2, OSC2 CRS to -16, OSC3 CRS to -16. - - Feel free to tune the sounds however you'd like, these are the recommended numbers from the [guide mentioned earlier](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) -3. Export all the sounds as `.wav` and make sure to enable the "Export as loop" to remove end silence. - -### Looping the sounds in Audacity -(skip this step if your tracks already loop without discontinuities) -1. Download requisite software - - [Audacity](https://www.audacityteam.org/) (download for [Linux](https://www.audacityteam.org/download/linux/)/[Windows](https://www.audacityteam.org/download/windows/)/[Mac](https://www.audacityteam.org/download/mac/)) for editing the audio tracks in post (ensure looping) -2. Import each sound track individually to Audacity (we'll do this one-at-a-time) - 1. When looping, you'll probably hear a sudden snap/click sound on every repeat, this is due to wave discontinuities -3. We'll want to find where the sound starts/ends and make sure the wave approximately matches so as to have a continuous transition between repetitions. - 1. This can be done by finding patterns from the beginning and cutting off the minimum amount from the track such that a new pattern would fit in as soon as the track ended. -![Audacity](../Figures/Sounds/audacity_wave.jpg) -Image source: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) -1. After you cut all the tracks to be seamlessly loopable, export them to new `.wav`'s and these are ready to be taken in to the UE4 and used as vehicle noises. -### Applying the sounds in UE4 -1. With all the desired tracks at our disposal, we'll import them all to the engine (big Import button in content-browser) -2. Create a **SoundCue** asset (right-click in content browser -> Sounds -> SoundCue) - 1. Open the SoundCue blueprint asset in the editor (opens new window) - 1. Import all tracks to the blueprint, and check the **"Looping"** checkbox - 2. Attach a **Continuous Modulator** node to each output from the Looping Wave Player's - 1. The parameters for these Continuous Modulators define the range of input/output for these tracks (value min/max) - 2. **NOTE** all the params have the same name `"RPM"` it is very important this is consistent as it will be used in the `C++` code - ![SoundCue](../Figures/Sounds/sound_cue.jpg) - - Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) - - - These are the recommended parameter values from the guide. - | Parameter | Idle | Drive1 | Drive2 | Drive3 | - | ---------- | -------- | -------- | -------- | -------- | - | Name | RPM | RPM | RPM | RPM | - | Default | 1 | 1 | 1 | 1 | - | Min Input | 0 | 20 | 500 | 2200 | - | Max Input | 200 | 600 | 2800 | 5700 | - | Min Output | 0.65 | 0.8 | 1.25 | 1.9 | - | Max Output | 1.1 | 1.0 | 1.25 | 1.9 | - | Param Mode | Absolute | Absolute | Absolute | Absolute | - 3. Add a **Crossfade by Param** with 4 parameters to handle the input/output transitions - 1. The parameters for these Continuous Modulators define how transitions are dealt with (fade in/out for each track) - - These are the recommended parameter values from the guide - | Parameter | Idle | Drive1 | Drive2 | Drive3 | - | ------------------------ | ---- | ------ | ------ | ------ | - | Fade In RPM Value Start | 0 | 150 | 550 | 2290 | - | Fade In RPM Value End | 0 | 350 | 750 | 2340 | - | Fade Out RPM Value Start | 200 | 600 | 2300 | 5800 | - | Fade Out RPM Value End | 400 | 800 | 2350 | 5800 | - | Volume | 1.0 | 0.6 | 0.6 | 0.6 | -3. Finally, you'll likely want some sort of attenuation device to fade out the noise of far away objects - 1. Create a **Sound Attenuation** asset (right-click in content browser -> Sounds -> SoundAttenuation) - 1. Change the **Inner Radius** to 1500 - 2. Change the **Falloff Distance** 3000 - 2. Back in the **Sound Cue** asset from step 2, scroll down in the Details pane and use the newly created **Sound Attenuation** asset as its Attenuation Settings: - - ![SoundAttenuation](../Figures/Sounds/sound_attenuation.jpg) - - Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) - -## Other vehicle noises -Generally, adding sounds can get complicated like the above, or they can be very simple for something quick. -- For example, adding sound for **gear shifting** is much simpler: - - We only need to import a clean (allowed) `.wav` file to create a **SoundWave** instance - - Then we can directly play that SoundWave asset from within the Ego-Vehicle -- Similarly, adding sounds for **turn-signals** is essentially the same: - - Just need to import the sounds, find them in code, and play them on our desired events - -To see how we implemented our audio components in DReyeVR (for both the ego-vehicle as well as the baseline CarlaWheeledVehicle) check out [`EgoVehicle.h`](../../DReyeVR/EgoVehicle.h) and [`CarlaWheeledVehicle.h`](../../Carla/Vehicle/CarlaWheeledVehicle.h) - -## Ambient noise in the World -It's also doable (and fairly easy) to have ambient noise in the world that attenuates based on the distance to the source. - -For reference, our provided Town03 has sound cues like this: -![WorldSound](../Figures/Sounds/sound_selected.jpg) - -Notice that once you drag & drop the sounds into the world, make sure to enable the **Override Attenuation** checkbox so you can edit the attenuation function, shape, and radius. -- The Inner Radius denotes the region where the volume is maximized -- The FallOff Distance denotes the region where the attenuation function gets executed and fades in/out - - -Our general strategy for simple ambient noise in the world follows these basic rules: -1. Wind is universal, so always have a big box covering the entire map that is the `Starter_Wind05`, usually we set its default volume to 70% -2. Birds are a indicator of green/trees/suburbs, so usually wherever there is green, we add a region of `Starter_Birds01` -3. Smoke is a good indicator for industry/city/buildings, so usually where there are lots of buildings/downtown, we'll use `Starter_Smoke01` -4. Steam works well for underground/dirty situations, so tunnels/railroads work well with `Starter_Steam01` -5. Water is very useful whenever there is water in the scene (`Water`), but it is much nicer to keep 3D sound enabled - 1. ie. don't uncheck `Enable Spatialization` (so the birds are audible entirely within this region) - -For custom tuning the attenuation parameters, see the `Details` pane after spawning an AmbientSound instance. It is also recommended to see this [Unreal Engine documentation on Audio Attenuation](https://docs.unrealengine.com/en-US/WorkingWithMedia/Audio/DistanceModelAttenuation/index.html) -| Example attenuation parameter settings | Bird sounds selected | -| --- | --- | -| ![BirdAttenuation](../Figures/Sounds/bird_attenuation.jpg) | ![BirdAttenuation](../Figures/Sounds/bird_selected.jpg)
In the World Outliner simply searching for "Sound" returns all AmbientSound instances | - -For reference, our birds ambient noise for Town03 looks like the following: -![BirdAttenuation](../Figures/Sounds/bird_world.jpg) -It is difficult to see the orange lines denoting our attenuation spheres, but all three are selected and displayed (generally over all grassy patches). - -We also added other custom sounds such as slight water splashing (works well with the fountain in the middle). - -Additionally, some maps are surrounded by water, this poses a challenge because often the coasts are very curvy and keeping a 3D sound spatialization only works if the sound is general enough to be emitting from the general body of water. This works great for the fountain where the water is symmetric, but require more granularly placed AmbientSounds in the world as follows (Town04): - -![WaterWorld](../Figures/Sounds/water_world.jpg) - -It is more tedious to place these smaller & more granular sound components in the world, but they make for a much better experience and are relatively quick to edit (just copy & paste & move around). - -**NOTE** there is probably a better way (such as [audio splines](https://blog.audiokinetic.com/volumetric_audio_emitter_for_custom_shapes_in_ue4/)) to do this so we don't need to place a bunch of small sound sources. - -## Acknowledgements -- We used the Arthur Ontuzhan's [ContinueBreak guide](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12) for developing our engine revving sound. -- These are the sources from which we obtained our audio files. Some files have been modified to better suit DReyeVR's needs. - - Light01, Light02, Smoke01, Starter_Birds01, Starter_Wind05, Starter_Wind06, Steam01 - - These all come from the [UE4 starter content pack](https://docs.unrealengine.com/4.27/en-US/Basics/Projects/Browser/Packs/) - - Water ([source](https://www.youtube.com/watch?v=QCvnqJz-qIo)) - - Crash ([source](https://www.youtube.com/watch?v=flMN4ME3isU)) - - Turn signals ([source](https://www.youtube.com/watch?v=EYIw9-pnScQ)) +# Adding and using sound in Carla+`DReyeVR` + +One of the first things you might notice when trying out `Carla` (all versions) is that there is absolutely no sound in the simulator. However, for our purposes, we are striving for an immersive experience with lots of feedback to a user about the world, and sound is a great way to add that. + +In this doc we'll go over how we added sound of the following: +1. Vehicle engine revving +2. Other vehicle sounds (gears/turn signals) +3. Ambient world noise +4. Acknowledgements + +## Engine revving +One of the best feedback mechanisms for a user applying throttle is the roar of an engine as the RPM increases. +- Yes, we know, we're using a Tesla model for our ego-vehicle but giving it engine/gear noises... blasphemy! + +[**CREDITS**]Most of this section comes from this [very helpful guide on youtube](https://www.youtube.com/watch?v=-c-f1aaIOnU) which is also available in [written form as an article](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/). We highly recommend taking a look at it to get step-by-step instructions and visuals for the following steps. +### Creating the sounds +(skip this step if you already have desired sound files for your engine) +1. Download requisite software: + - [LMMS](https://lmms.io/) (download for [Linux](https://lmms.io/download#linux)/[Windows](https://lmms.io/download#windows)/[Mac](https://lmms.io/download#mac)) for creating music tracks +2. Create 4 sounds, these correspond to when the engine is idle (1), running slowly (2), running normally (3), and running at max RPM (4) + - For all these tracks, we'll start with a sole TripleOscillator playing a constant C2 octave (4 beats should be fine). + | Configuration | Visually | + | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------- | + | PM value for OSC1+OSC2
PM value for OSC2+OSC3
OSC1 volume of 60
OSC1 CRS of -4
OSC1 to use triangle wave
OSC2 CRS of -24
OSC3 CRS of -24

Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) | ![TripleOscillator](../Figures/Sounds/triple_oscillator.jpg) | + - Then we'll want to amplify this effect by adding an LMMS-type Amplifier from the FX-Mixer window and crank the volume to the max. + 1. This works for the idle engine sound, nothing more to do here. The remaining drive sounds will gradually increase their CRS values. + 2. For Drive1 change OSC1 CRS to 0, OSC2 CRS to -20, OSC3 CRS to -20. + 3. For Drive2 change OSC1 CRS to 2, OSC2 CRS to -18, OSC3 CRS to -18. + 4. For Drive3 change OSC1 CRS to 2, OSC2 CRS to -16, OSC3 CRS to -16. + - Feel free to tune the sounds however you'd like, these are the recommended numbers from the [guide mentioned earlier](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) +3. Export all the sounds as `.wav` and make sure to enable the "Export as loop" to remove end silence. + +### Looping the sounds in Audacity +(skip this step if your tracks already loop without discontinuities) +1. Download requisite software + - [Audacity](https://www.audacityteam.org/) (download for [Linux](https://www.audacityteam.org/download/linux/)/[Windows](https://www.audacityteam.org/download/windows/)/[Mac](https://www.audacityteam.org/download/mac/)) for editing the audio tracks in post (ensure looping) +2. Import each sound track individually to Audacity (we'll do this one-at-a-time) + 1. When looping, you'll probably hear a sudden snap/click sound on every repeat, this is due to wave discontinuities +3. We'll want to find where the sound starts/ends and make sure the wave approximately matches so as to have a continuous transition between repetitions. + 1. This can be done by finding patterns from the beginning and cutting off the minimum amount from the track such that a new pattern would fit in as soon as the track ended. +![Audacity](../Figures/Sounds/audacity_wave.jpg) +Image source: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) +1. After you cut all the tracks to be seamlessly loopable, export them to new `.wav`'s and these are ready to be taken in to the UE4 and used as vehicle noises. +### Applying the sounds in UE4 +1. With all the desired tracks at our disposal, we'll import them all to the engine (big Import button in content-browser) +2. Create a **SoundCue** asset (right-click in content browser -> Sounds -> SoundCue) + 1. Open the SoundCue blueprint asset in the editor (opens new window) + 1. Import all tracks to the blueprint, and check the **"Looping"** checkbox + 2. Attach a **Continuous Modulator** node to each output from the Looping Wave Player's + 1. The parameters for these Continuous Modulators define the range of input/output for these tracks (value min/max) + 2. **NOTE** all the params have the same name `"RPM"` it is very important this is consistent as it will be used in the `C++` code + ![SoundCue](../Figures/Sounds/sound_cue.jpg) + - Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) + + - These are the recommended parameter values from the guide. + | Parameter | Idle | Drive1 | Drive2 | Drive3 | + | ---------- | -------- | -------- | -------- | -------- | + | Name | RPM | RPM | RPM | RPM | + | Default | 1 | 1 | 1 | 1 | + | Min Input | 0 | 20 | 500 | 2200 | + | Max Input | 200 | 600 | 2800 | 5700 | + | Min Output | 0.65 | 0.8 | 1.25 | 1.9 | + | Max Output | 1.1 | 1.0 | 1.25 | 1.9 | + | Param Mode | Absolute | Absolute | Absolute | Absolute | + 3. Add a **Crossfade by Param** with 4 parameters to handle the input/output transitions + 1. The parameters for these Continuous Modulators define how transitions are dealt with (fade in/out for each track) + - These are the recommended parameter values from the guide + | Parameter | Idle | Drive1 | Drive2 | Drive3 | + | ------------------------ | ---- | ------ | ------ | ------ | + | Fade In RPM Value Start | 0 | 150 | 550 | 2290 | + | Fade In RPM Value End | 0 | 350 | 750 | 2340 | + | Fade Out RPM Value Start | 200 | 600 | 2300 | 5800 | + | Fade Out RPM Value End | 400 | 800 | 2350 | 5800 | + | Volume | 1.0 | 0.6 | 0.6 | 0.6 | +3. Finally, you'll likely want some sort of attenuation device to fade out the noise of far away objects + 1. Create a **Sound Attenuation** asset (right-click in content browser -> Sounds -> SoundAttenuation) + 1. Change the **Inner Radius** to 1500 + 2. Change the **Falloff Distance** 3000 + 2. Back in the **Sound Cue** asset from step 2, scroll down in the Details pane and use the newly created **Sound Attenuation** asset as its Attenuation Settings: + + ![SoundAttenuation](../Figures/Sounds/sound_attenuation.jpg) + - Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) + +## Other vehicle noises +Generally, adding sounds can get complicated like the above, or they can be very simple for something quick. +- For example, adding sound for **gear shifting** is much simpler: + - We only need to import a clean (allowed) `.wav` file to create a **SoundWave** instance + - Then we can directly play that SoundWave asset from within the Ego-Vehicle +- Similarly, adding sounds for **turn-signals** is essentially the same: + - Just need to import the sounds, find them in code, and play them on our desired events + +To see how we implemented our audio components in DReyeVR (for both the ego-vehicle as well as the baseline CarlaWheeledVehicle) check out [`EgoVehicle.h`](../../DReyeVR/EgoVehicle.h) and [`CarlaWheeledVehicle.h`](../../Carla/Vehicle/CarlaWheeledVehicle.h) + +## Ambient noise in the World +It's also doable (and fairly easy) to have ambient noise in the world that attenuates based on the distance to the source. + +For reference, our provided Town03 has sound cues like this: +![WorldSound](../Figures/Sounds/sound_selected.jpg) + +Notice that once you drag & drop the sounds into the world, make sure to enable the **Override Attenuation** checkbox so you can edit the attenuation function, shape, and radius. +- The Inner Radius denotes the region where the volume is maximized +- The FallOff Distance denotes the region where the attenuation function gets executed and fades in/out + + +Our general strategy for simple ambient noise in the world follows these basic rules: +1. Wind is universal, so always have a big box covering the entire map that is the `Starter_Wind05`, usually we set its default volume to 70% +2. Birds are a indicator of green/trees/suburbs, so usually wherever there is green, we add a region of `Starter_Birds01` +3. Smoke is a good indicator for industry/city/buildings, so usually where there are lots of buildings/downtown, we'll use `Starter_Smoke01` +4. Steam works well for underground/dirty situations, so tunnels/railroads work well with `Starter_Steam01` +5. Water is very useful whenever there is water in the scene (`Water`), but it is much nicer to keep 3D sound enabled + 1. ie. don't uncheck `Enable Spatialization` (so the birds are audible entirely within this region) + +For custom tuning the attenuation parameters, see the `Details` pane after spawning an AmbientSound instance. It is also recommended to see this [Unreal Engine documentation on Audio Attenuation](https://docs.unrealengine.com/en-US/WorkingWithMedia/Audio/DistanceModelAttenuation/index.html) +| Example attenuation parameter settings | Bird sounds selected | +| --- | --- | +| ![BirdAttenuation](../Figures/Sounds/bird_attenuation.jpg) | ![BirdAttenuation](../Figures/Sounds/bird_selected.jpg)
In the World Outliner simply searching for "Sound" returns all AmbientSound instances | + +For reference, our birds ambient noise for Town03 looks like the following: +![BirdAttenuation](../Figures/Sounds/bird_world.jpg) +It is difficult to see the orange lines denoting our attenuation spheres, but all three are selected and displayed (generally over all grassy patches). + +We also added other custom sounds such as slight water splashing (works well with the fountain in the middle). + +Additionally, some maps are surrounded by water, this poses a challenge because often the coasts are very curvy and keeping a 3D sound spatialization only works if the sound is general enough to be emitting from the general body of water. This works great for the fountain where the water is symmetric, but require more granularly placed AmbientSounds in the world as follows (Town04): + +![WaterWorld](../Figures/Sounds/water_world.jpg) + +It is more tedious to place these smaller & more granular sound components in the world, but they make for a much better experience and are relatively quick to edit (just copy & paste & move around). + +**NOTE** there is probably a better way (such as [audio splines](https://blog.audiokinetic.com/volumetric_audio_emitter_for_custom_shapes_in_ue4/)) to do this so we don't need to place a bunch of small sound sources. + +## Acknowledgements +- We used the Arthur Ontuzhan's [ContinueBreak guide](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12) for developing our engine revving sound. +- These are the sources from which we obtained our audio files. Some files have been modified to better suit DReyeVR's needs. + - Light01, Light02, Smoke01, Starter_Birds01, Starter_Wind05, Starter_Wind06, Steam01 + - These all come from the [UE4 starter content pack](https://docs.unrealengine.com/4.27/en-US/Basics/Projects/Browser/Packs/) + - Water ([source](https://www.youtube.com/watch?v=QCvnqJz-qIo)) + - Crash ([source](https://www.youtube.com/watch?v=flMN4ME3isU)) + - Turn signals ([source](https://www.youtube.com/watch?v=EYIw9-pnScQ)) - Gear shift ([source](https://www.youtube.com/watch?v=g_Gfkgfbz20)) \ No newline at end of file diff --git a/Docs/Usage.md b/Docs/Usage.md index 7c240f8..f20551a 100644 --- a/Docs/Usage.md +++ b/Docs/Usage.md @@ -1,332 +1,332 @@ -# Using `DReyeVR` - -Now that you have DReyeVR up and running, this guide will highlight some useful features for researchers using DReyeVR: -- [Maneuvering the Ego-vehicle](Usage.md#maneuvering-the-ego-vehicle) -- [Using the PythonAPI](Usage.md#using-the-pythonapi) -- [Recording/replaying a scenario](Usage.md#recordingreplaying-a-scenario) -- [Switching control from manual to AI (handoff)](Usage.md#control-handoff-to-ai) -- [Using our config file to modify DReyeVR params](Usage.md#using-our-custom-config-file) -- [Synchronized replay with frame capture](Usage.md#synchronized-replay-frame-capture) -- [Other guides](Usage.md#other-guides) - -![UsageSchematic](Figures/Usage/UsageSchematic.jpg) - -# Maneuvering the Ego-vehicle -These control schemes work both in VR and non-VR. With the main difference being that in VR you can move the camera pose and orientation with your head tracking, but in flat-screen-mode (non-VR) you'll need to use a mouse like in a first-person game. -- Keyboard vehicle control scheme: - - **Camera Gaze** - When in the 2D (flat/non-VR) view, turn the camera by clicking and dragging - - **Throttle** - Is done by pressing and holding `W` - - **Steering** - Is done with `A` to steer left and `D` to steer right - - **Brake** - Is done by pressing and holding `S` - - **Toggle Reverse** - Is done by pressing `LAlt` - - **Turn Signals** - Are both done by pressing `Q` (left) or `E` (right) - - **Camera Adjust** - Is done in X and Y with the arrow keys (`up`, `down`, `left`, `right`) and in Z with the `pg-up`/`pg-down` buttons - - **Change Camera View Position** - Is done with `Tab` to switch to the next camera position defined in `DReyeVRParams.ini`. Press `Shift+Tab` to switch back to the previous camera position - - **Change Camera Shader** - Is done with `.` (period) to switch to the next shader and `,` (comma) to the previous shader -- Logitech control scheme: - - **Throttle** - Is done by pushing down on the accelerator pedal - - **Steering** - Is done by turning the steering wheel - - **Brake** - Is done by pushing down on the brake pedal - - **Toggle Reverse** - Is done by pressing any of the `ABXY` (7 in the image) buttons - - **Turn Signals** - Are both done by the left (4) and right (6) bumpers - - **Camera Adjust** - Is done in X and Y with the 4 d-pad buttons (2) on the face of the wheel, and in Z with the +/- buttons (5) -- ![LogiWheel](Figures/Usage/g923.jpg) Image source: [Logitech g923 manual](https://www.logitech.com/assets/65932/2/g923-racing-wheel-qsg.pdf) - -Note that all the keyboard inputs are defined in [`DefaultInput.ini`](../Configs/DefaultInput.ini) where all DReyeVR-specific controls have been suffixed with "`_DReyeVR`". Feel free to change any of the controls if you'd like. - -However, the logitech wheel inputs are hardcoded into the source since they are checked for on every tick (instead of through the UE4 keyboard events). To see the values and modify them, see [`DReyeVRPawn.cpp`](../DReyeVR/DReyeVRPawn.cpp) - -# Using the PythonAPI -With the main Carla server running you should now be able to run all Carla provided `PythonAPI` scripts. -- Note that not all scripts in the original [`Carla 0.9.13` PythonAPI](https://github.com/carla-simulator/carla/tree/0.9.13/PythonAPI) repo have been tested. We created some new scripts in place of others, such as `schematic_mode.py` which inherits from `no_rendering_mode.py` but adds support for our ego-vehicle and eye tracker. -- In some cases, we replace the old python scripts with newer ones, such as the [`no_rendering_mode.py`](https://github.com/carla-simulator/scenario_runner/blob/v0.9.13/no_rendering_mode.py) in `scenario-runner-v0.9.13` which is actually from release 0.9.5. - -### Visualize in schematic mode -```bash -cd $CARLA_ROOT/PythonAPI/examples/ # go to carla/ - -./schematic_mode.py -``` - -### Logging DReyeVR sensor data to PythonAPI -```bash -cd $CARLA_ROOT/PythonAPI/examples/ - -# see all the DReyeVR sensor data -./DReyeVR_logging.py # prints directly in stdout - -# or if you have a running roscore (with rospy) -./DReyeVR_logging.py --rh '192.168.X.Y' --rp 11311 # pass in roscore host & ports -``` -- We support ROS data streaming using `rospy` on an Ubuntu 20.04 LTS host. If you are interested in using a VM for this purpose, we'd recommend checking out [`VirtualMachine/README.md`](../Tools/VirtualMachine/README.md) as the setup is fairly involved. - -### Start the DReyeVR AI controller -```bash -cd $CARLA_ROOT/PythonAPI/examples/ - -# DReyeVR AI controller requires this script to be running -./DReyeVR_AI.py -n 0 # won't control vehicle unless control is handoff to AI (press 3) -``` - -### Start recording/replaying -```bash -cd $CARLA_ROOT/PythonAPI/examples/ - -# start a recording with no other agents -./start_recording.py -n 0 -... -^C - -# replay the file just recorded -./start_replaying.py - -# dump the replay file in a human-readable manner to replay.txt -./show_recorder_file_info.py -a > replay.txt -``` - -### Run a ScenarioRunner instance and record -```bash -cd $SCENARIO_RUNNER_ROOT # go to scenario-runner/ - -./run_experiment.py --title name_of_experiment --route srunner/data/routes_debug.xml srunner/data/all_towns_traffic_scenarios1_3_4.json 0 --output --reloadWorld -... -^C -``` - -## Using our new DReyeVR PythonAPI -For your own custom scripts, we recommend taking a look at the [`DReyeVR_utils.py`](../PythonAPI/DReyeVR_utils.py) file, specifically the two functions: -- `find_ego_vehicle` which takes in the `carla.libcarla.World` instance and returns the DReyeVR ego-vehicle (`carla.libcarla.Vehicle`) present in the world or spawns one in if there is none. -- `find_ego_sensor` which takes in the `carla.libcarla.World` instance and returns the DReyeVR eye tracker (`carla.libcarla.Sensor`) present in the world, which should be attached to the spawned EgoVehicle (if the EgoVehicle is spawned) - -Then, in your script, you can follow the technique we used in `schematic_mode.py` such as: -```python - world = self.client.get_world() - - # find ego vehicle - self.hero_actor = find_ego_vehicle(world) - self.hero_transform = self.hero_actor.get_transform() - - # find ego sensor - # DReyeVRSensor implicitly calls find_ego_sensor, then wraps it with a custom class - self.sensor = DReyeVRSensor(world) - self.sensor.ego_sensor.listen(self.sensor.update) # subscribe to readout -``` -Now you can proceed to use `self.sensor.ego_sensor` as a standard [`carla.libcarla.Sensor`](https://github.com/carla-simulator/carla/blob/master/Docs/python_api.md#carlasensor) object and `self.hero_actor` as a standard [`carla.libcarla.Vehicle`](https://github.com/carla-simulator/carla/blob/master/Docs/python_api.md#carlavehicle) object. - -# Recording/Replaying a scenario -## Motivations -It is often useful to record a scenario of an experiment in order to reenact it in post and perform further analysis. We had to slightly augment the recorder and replayer to respect our ego-vehicle being persistent in the world, but all other functionality is maintained. We additionally reenact the ego-sensor data (including HMD pose and orientation) so an experimenter could see what the participant was looking at on every tick. For the full explanation of the Carla recorder see their [documentation](https://carla.readthedocs.io/en/0.9.13/adv_recorder/). - -## Recording -The easiest way to start recording is with the handy `PythonAPI` scripts. -```bash -cd $CARLA_ROOT/PythonAPI/examples/ -# this starts a recording session with 10 autonomous vehicles -./start_recording.py -n 10 # change -n param to change number of vehicles (default 10) -... -^C # stop recording with a SIGINT (interrupt) -``` -- Note that the recording halts if a new world is loaded, so if you want to change the world make sure to restart the recording after the world has loaded. -- The recording saves the default file as a `test1.log` file in the default saved directory of your project: - - If recording from editor: `carla/Unreal/CarlaUE4/Saved/test1.log` - - If recording from package: `${PACKAGE}/Unreal/Saved/test1.log` -- The recording should have relatively minimal impact on the performance of the simulator, but this likely varies by machine. The experience should be essentially the same. -- Note that the recorder saves everything in binary, so it the raw `test1.log` file is not human-readable. It is often nice to read it however, in that case use: - - ```bash - # saves output (stdout) to recorder.txt - ./show_recorder_file_info.py -a -f /PATH/TO/RECORDER-FILE > recorder.txt - ``` - - With this `recorder.txt` file (which holds a human-readable dump of the entire recording log) you can parse this file into useful python data structures (numpy arrays/pandas dataframes) by using our [DReyeVR parser](https://github.com/harplab/dreyevr-parser). -## Replaying -Begin a replay session through the PythonAPI as follows: -```bash -# note this does not rely on being in VR mode or not. -./start_replaying.py # this starts the replaying session -``` -- Note that in the replaying mode, all user inputs will be ignored in favour of the replay inputs. However, you may still use the following level controls: - 1. **Toggle Play/Pause** - Is done by pressing `SpaceBar` - 2. **Advance** - Is done by holding `Alt` and pressing `Left` arrow (backwards) or `Right` arrow (forwards) - 3. **Change Playback Speed** - Is done by holding `Alt` and pressing `Up` arrow (increase) or `Down` arrow (decrease) - 4. **Restart** - Is done by holding `Alt` and pressing `BackSpace` - 6. **Possess Spectator** - Is done by pressing `1` (then use `WASDEQ+mouse` to fly around) - 7. **Re-possess Vehicle** - Is done by pressing `2` - -To get accurate screenshots for every frame of the recording, see below with [synchronized replay frame capture](#synchronized-replay-frame-capture) - -**NOTE** We use custom config files for global and vehicle parameters in the simulator (see [below](Usage.md#using-our-custom-config-file)) and we also store these parameters in the recording file so that we can verify they are the same as the replay. For instance, we will automatically compare the recording's parameters versus the live parameters when performing a replay. Then if we detect any differences, we will print these as warnings so you can be aware. For instance, if you recorded with a particular vehicle and replay the simulator with a different vehicle loaded, we will let you know that the replay may be inaccurate and you are in uncharted territory. - -## Scenarios -It is usually ideal to have curated experiments in the form of scenarios parsed through [ScenarioRunner](https://carla-scenariorunner.readthedocs.io/en/latest/). - -For this purpose, we created a handy script that should be robust to some of the quirks of the existing implementation. This script ([`run_experiment.py`](../ScenarioRunner/run_experiment.py)) will automatically start recording for you AFTER the new map has been loaded, with a unique filename, all on a single client instance, so that you don't need to worry about a faulty recording or overwriting existing files. - -With `scenario_runner` v0.9.13, you should have already set these environment variables: -```bash -# on bash (Linux) -export CARLA_ROOT=/PATH/TO/carla/ -export SCENARIO_RUNNER_ROOT=/PATH/TO/scenario_runner/ -export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-0.9.13-py3.7-linux-x86_64.egg -export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/agents -export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla -export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI - -# on Windows x64 Visual C++ Toolset -set CARLA_ROOT=C:PATH\TO\carla\ -set SCENARIO_RUNNER_ROOT=C:PATH\TO\scenario_runner\ -set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla\dist\carla-0.9.13-py3.7-win-amd64.egg -set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla\agents -set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla -set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI -``` -Then to run our demo examples, use this command: -```bash -# on bash (Linux) -cd $SCENARIO_RUNNER_ROOT # go to scenario-runner -./run_experiment.py --title "dreyevr_experiment" --route $SCENARIO_RUNNER_ROOT/srunner/data/routes_custom.xml $SCENARIO_RUNNER_ROOT/srunner/data/town05_scenarios.json 0 - -# on Windows x64 Visual C++ Toolset -cd %SCENARIO_RUNNER_ROOT% # go to scenario-runner -python run_experiment.py --title "dreyevr_experiment" --route %SCENARIO_RUNNER_ROOT%\srunner\data\routes_custom.xml %SCENARIO_RUNNER_ROOT%\srunner\data\town05_scenarios.json 0 -``` -Note that you can rename the experiment to anything with `--title "your_experiment"`, and the resulting recording file will include this title in its filename. - -# Control handoff to AI -Sometimes it is useful to have an AI takeover of the ego-vehicle during an experiment for research purposes. This becomes easy to do in our simulator with the help of Carla's existing [TrafficManager-based autopilot](https://carla.readthedocs.io/en/0.9.13/adv_traffic_manager/) which can pilot our ego-vehicle just like any other carla Vehicle. - -However, in order to start the autopilot, we currently only support using the PythonAPI for this task, so we created `DReyeVR_AI.py` which will do the job: -```bash -cd $CARLA_ROOT/PythonAPI/examples # go to carla PythonAPI -./DReyeVR_AI.py -n 0 # spawn no other vehicles, enable autopilot on EgoVehicle -``` - -Internally, the AI system is using the Carla vehicle autopilot system, so this can be enabled in your custom PythonAPI scripts without the use of `DReyeVR_AI.py` by performing: -```python -from DReyeVR_utils import find_ego_vehicle -... - -world = client.get_world() -traffic_manager = client.get_trafficmanager(args.tm_port) -... - -DReyeVR_vehicle = find_ego_vehicle(world) -if DReyeVR_vehicle is not None: - DReyeVR_vehicle.set_autopilot(True, traffic_manager.get_port()) - print("Successfully set autopilot on ego vehicle") -``` - -Currently we only support manual handoff by pressing `3` on the keyboard. This gives input priority to the Carla [WheeledVehicleAIController](https://github.com/carla-simulator/carla/blob/0.9.13/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp) which will follow some route defined by Carla's TrafficManager. - -In order to re-possess the vehicle (handoff control back to the player), simply press `1`. Keyboard inputs are automatically higher priority than the autopilot. - -[OPTIONAL]Using this same approach, there is a third option where you can press `2` to possess a "spectator" that can no-clip and fly around the map using `WASDEQ+mouse` controls. - -You can press any of the control options: `1`(human driver), `2`(spectator), `3`(AI driver) at any time. -Summary: - -| Press `1` | Press `2` | Press `3` | -| --- | --- | --- | -| Human driving | Spectator mode | AI driving | - - -# Using our custom config file -Throughout development, we found that modifying even small things in DReyeVR have a LONG cycle time for recompilation/re-linking/re-cooking/etc. so we wanted an approach that could greatly ease this burden while still providing flexibility. - -This is why we developed the [`ConfigFile`](../DReyeVR/ConfigFile.h) class and corresponding [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) (and per-vehicle) "params" so we could read the file at runtime to set variables in the simulator without recompilation. - -The procedure to use our params API is simple: -```c++ -// in, any class, say EgoVehicle.h -#include "DReyeVRUtils.h" // make sure to include our local header file! - -class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle -{ - ... // existing code - - float MyFavouriteNumber; // <--Your new param -} -``` - -Then, choose which type of config file this variable falls into, currently we have two kinds of primary config files: simulator-wide `GeneralParams`, and per-vehicle `VehicleParams`. - -The `GeneralParams` can be thought of as a global simulator-wide configuration file that can be accessed from anywhere, while the `VehicleParams` are specifically for a particular EgoVehicle (such as locations/specifications) that can be found in [`Config/EgoVehicles/`](../Config/EgoVehicles/) that matches the available DReyeVR EgoVehicles. To learn more about these see [EgoVehicle.md](EgoVehicles.md). - -(For general params) -```ini -[MyFavourites] -Number=867.5309 # You can also write comments! -``` -Then, anywhere you want, you can get the parameter by specifying both the section and variable name: - -```c++ -void AEgoVehicle::SomeFunction() -{ - // can use this format to assign directly into a variable - MyFavouriteNumber = GeneralParams.Get("MyFavourites", "Number"); - - // or pass the variable by reference and get whether or not the Get operation was successful - bool bSuccess = GeneralParams.Get("MyFavourites", "Number", MyFavouriteNumber); - -} -``` - -If you are using vehicle-specific params, then this needs to be in the context of some EgoVehicle -```c++ - -void SomeClass::SomeOtherFunction(AEgoVehicle *Vehicle){ - // VehicleParams is a public member of - const ConfigFile &VehicleSpecificParams = Vehicle->GetVehicleParams(); - int VehicleParam = VehicleSpecificParams.Get("VehicleParamSection", "VariableName"); -} -``` - - -And, just like the other variables in the file, you can bunch and organize them together under the same section header. - -Another useful feature we built-in is to import, export, and compare the config files. This is useful because we can track the config file(s) that were used while a particular example was recorded, then if you are trying to replay this scenario with *different* configuration parameters (ex. using a different vehicle, or with mirrors enabled when they werent in the recording), some warnings will be presented when comparing (diff) the recorded config file (saved in the .log file) and the live one (what is currently running). - -# Synchronized replay frame capture -## Motivations -After performing (and recording) an [experiment](../ScenarioRunner/run_experiment.py), we are provided with a log of everything that happened in the simulator that we can use for live reenactment and post-hoc analysis. It is often the case that after some postprocessing on the data, we might be interested in overlaying something on the simulator view to match what a participant was seeing/doing and what the world looked like. Unfortunately, it is difficult to get the exact image frame corresponding to an exact recording event using an asynchronous screen recorder such as OBS, therefore we baked in this functionality within the engine itself, so it can directly go to any recorded event and take a high quality screenshot. The end result is the exact frame-by-frame views corresponding to the recorded world conditions without interpolation. - -### Synchronized replay -To have this functionality, disable the `ReplayInterpolation` flag in [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) under the `[Replayer]` section. Disabling replay interpolation will allow for frame-by-frame reenactment of what was captured (otherwise the replay will respect wall-clock-time and introduce interpolation between frames). - -### Frame capture -While replaying (so, after the experiment was conducted) we can additionally perform frame capture during this replay. Since taking high-res screnshots is expensive, this is a slow process that is done during replays when real-time performance is less important. To enable this feature, enable the `RecordFrames` flag in the `[Replayer]` section as well. There are several other frame capture options below such as resolution and gamma parameters. - -The resulting frame capture images (`.png` or `.jpg` depending on the `FileFormatJPG` flag) will be found in `Unreal/CarlaUE4/{FrameDir}/{DateTimeNow}/{FrameName}*` where `{FrameDir}` and `{FrameName}` are both determined in the [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini). The `{DateTimeNow}` string is uniquely based on your machine's local current time so you can run multiple recordings without overwriting old files. - -**NOTE**: Depending on whether you are running the Editor mode or package mode of DReyeVR will place the FrameCapture directory in the following: -- Editor (debug): `%CARLA_ROOT%\Unreal\CarlaUE4\FrameCap\` -- Package (shipping): `%CARLA_ROOT%\Build\UE4Carla\0.9.13-dirty\WindowsNoEditor\CarlaUE4\FrameCap\` - -(Showing Windows paths for convenience, but the desinations are similar for Linux/Mac) - -With these flags enabled, any time you initiate a replay such as: -```bash -# in PythonAPI/examples -./start_replaying.py -f /PATH/TO/RECORDING/FILE # unix - -python start_replaying.py -f /PATH/TO/RECORDING/FILE # windows -``` - - - -# Other guides -We have written other guides as well that serve more particular needs: -- See [`F.A.Q. wiki`](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) for our Frequently Asked Questions wiki page. -- See [`SetupVR.md`](Tutorials/SetupVR.md) to learn how to quickly and minimally set up VR with Carla -- See [`Sounds.md`](Tutorials/Sounds.md) to see how we added custom sounds and how you can add your own custom sounds -- See [`Signs.md`](Tutorials/Signs.md) to add custom in-world directional signs and dynamically spawn them into the world at runtime -- See [`Shaders/README.md`](../Shaders/README.md) to view our post-processing shaders and learn how to use them -- See [`CustomActor.md`](Tutorials/CustomActor.md) to use our CustomActor classes to use fully-recordable 3D dynamic elements in your scene -- See [`Model.md`](Tutorials/Model.md) to see how we added a responsive steering wheel to the vehicle mesh -- See [`CustomEgo.md`](Tutorials/CustomEgo.md) to add your own custom EgoVehicle model to DReyeVR -- See [`LODs.md`](Tutorials/LODs.md) to learn how we tune the Level-Of-Detail modes for vehicles for a more enjoyable VR experience - - -# Quirks: -- On Windows you're going to want to use the `Windows x64 Visual C++ Toolset` and call all the python files with `python SCRIPT.py` rather than just `./SCRIPT.py` - - Additionally, environment variables are accessed `%LIKE_THIS%` instead of `$LIKE_THIS`. - - And remember that file paths use a backwards slash to `LOCATE\FILES\THIS\WAY\` instead of `THE/NORMAL/WAY/` +# Using `DReyeVR` + +Now that you have DReyeVR up and running, this guide will highlight some useful features for researchers using DReyeVR: +- [Maneuvering the Ego-vehicle](Usage.md#maneuvering-the-ego-vehicle) +- [Using the PythonAPI](Usage.md#using-the-pythonapi) +- [Recording/replaying a scenario](Usage.md#recordingreplaying-a-scenario) +- [Switching control from manual to AI (handoff)](Usage.md#control-handoff-to-ai) +- [Using our config file to modify DReyeVR params](Usage.md#using-our-custom-config-file) +- [Synchronized replay with frame capture](Usage.md#synchronized-replay-frame-capture) +- [Other guides](Usage.md#other-guides) + +![UsageSchematic](Figures/Usage/UsageSchematic.jpg) + +# Maneuvering the Ego-vehicle +These control schemes work both in VR and non-VR. With the main difference being that in VR you can move the camera pose and orientation with your head tracking, but in flat-screen-mode (non-VR) you'll need to use a mouse like in a first-person game. +- Keyboard vehicle control scheme: + - **Camera Gaze** - When in the 2D (flat/non-VR) view, turn the camera by clicking and dragging + - **Throttle** - Is done by pressing and holding `W` + - **Steering** - Is done with `A` to steer left and `D` to steer right + - **Brake** - Is done by pressing and holding `S` + - **Toggle Reverse** - Is done by pressing `LAlt` + - **Turn Signals** - Are both done by pressing `Q` (left) or `E` (right) + - **Camera Adjust** - Is done in X and Y with the arrow keys (`up`, `down`, `left`, `right`) and in Z with the `pg-up`/`pg-down` buttons + - **Change Camera View Position** - Is done with `Tab` to switch to the next camera position defined in `DReyeVRParams.ini`. Press `Shift+Tab` to switch back to the previous camera position + - **Change Camera Shader** - Is done with `.` (period) to switch to the next shader and `,` (comma) to the previous shader +- Logitech control scheme: + - **Throttle** - Is done by pushing down on the accelerator pedal + - **Steering** - Is done by turning the steering wheel + - **Brake** - Is done by pushing down on the brake pedal + - **Toggle Reverse** - Is done by pressing any of the `ABXY` (7 in the image) buttons + - **Turn Signals** - Are both done by the left (4) and right (6) bumpers + - **Camera Adjust** - Is done in X and Y with the 4 d-pad buttons (2) on the face of the wheel, and in Z with the +/- buttons (5) +- ![LogiWheel](Figures/Usage/g923.jpg) Image source: [Logitech g923 manual](https://www.logitech.com/assets/65932/2/g923-racing-wheel-qsg.pdf) + +Note that all the keyboard inputs are defined in [`DefaultInput.ini`](../Configs/DefaultInput.ini) where all DReyeVR-specific controls have been suffixed with "`_DReyeVR`". Feel free to change any of the controls if you'd like. + +However, the logitech wheel inputs are hardcoded into the source since they are checked for on every tick (instead of through the UE4 keyboard events). To see the values and modify them, see [`DReyeVRPawn.cpp`](../DReyeVR/DReyeVRPawn.cpp) + +# Using the PythonAPI +With the main Carla server running you should now be able to run all Carla provided `PythonAPI` scripts. +- Note that not all scripts in the original [`Carla 0.9.13` PythonAPI](https://github.com/carla-simulator/carla/tree/0.9.13/PythonAPI) repo have been tested. We created some new scripts in place of others, such as `schematic_mode.py` which inherits from `no_rendering_mode.py` but adds support for our ego-vehicle and eye tracker. +- In some cases, we replace the old python scripts with newer ones, such as the [`no_rendering_mode.py`](https://github.com/carla-simulator/scenario_runner/blob/v0.9.13/no_rendering_mode.py) in `scenario-runner-v0.9.13` which is actually from release 0.9.5. + +### Visualize in schematic mode +```bash +cd $CARLA_ROOT/PythonAPI/examples/ # go to carla/ + +./schematic_mode.py +``` + +### Logging DReyeVR sensor data to PythonAPI +```bash +cd $CARLA_ROOT/PythonAPI/examples/ + +# see all the DReyeVR sensor data +./DReyeVR_logging.py # prints directly in stdout + +# or if you have a running roscore (with rospy) +./DReyeVR_logging.py --rh '192.168.X.Y' --rp 11311 # pass in roscore host & ports +``` +- We support ROS data streaming using `rospy` on an Ubuntu 20.04 LTS host. If you are interested in using a VM for this purpose, we'd recommend checking out [`VirtualMachine/README.md`](../Tools/VirtualMachine/README.md) as the setup is fairly involved. + +### Start the DReyeVR AI controller +```bash +cd $CARLA_ROOT/PythonAPI/examples/ + +# DReyeVR AI controller requires this script to be running +./DReyeVR_AI.py -n 0 # won't control vehicle unless control is handoff to AI (press 3) +``` + +### Start recording/replaying +```bash +cd $CARLA_ROOT/PythonAPI/examples/ + +# start a recording with no other agents +./start_recording.py -n 0 +... +^C + +# replay the file just recorded +./start_replaying.py + +# dump the replay file in a human-readable manner to replay.txt +./show_recorder_file_info.py -a > replay.txt +``` + +### Run a ScenarioRunner instance and record +```bash +cd $SCENARIO_RUNNER_ROOT # go to scenario-runner/ + +./run_experiment.py --title name_of_experiment --route srunner/data/routes_debug.xml srunner/data/all_towns_traffic_scenarios1_3_4.json 0 --output --reloadWorld +... +^C +``` + +## Using our new DReyeVR PythonAPI +For your own custom scripts, we recommend taking a look at the [`DReyeVR_utils.py`](../PythonAPI/DReyeVR_utils.py) file, specifically the two functions: +- `find_ego_vehicle` which takes in the `carla.libcarla.World` instance and returns the DReyeVR ego-vehicle (`carla.libcarla.Vehicle`) present in the world or spawns one in if there is none. +- `find_ego_sensor` which takes in the `carla.libcarla.World` instance and returns the DReyeVR eye tracker (`carla.libcarla.Sensor`) present in the world, which should be attached to the spawned EgoVehicle (if the EgoVehicle is spawned) + +Then, in your script, you can follow the technique we used in `schematic_mode.py` such as: +```python + world = self.client.get_world() + + # find ego vehicle + self.hero_actor = find_ego_vehicle(world) + self.hero_transform = self.hero_actor.get_transform() + + # find ego sensor + # DReyeVRSensor implicitly calls find_ego_sensor, then wraps it with a custom class + self.sensor = DReyeVRSensor(world) + self.sensor.ego_sensor.listen(self.sensor.update) # subscribe to readout +``` +Now you can proceed to use `self.sensor.ego_sensor` as a standard [`carla.libcarla.Sensor`](https://github.com/carla-simulator/carla/blob/master/Docs/python_api.md#carlasensor) object and `self.hero_actor` as a standard [`carla.libcarla.Vehicle`](https://github.com/carla-simulator/carla/blob/master/Docs/python_api.md#carlavehicle) object. + +# Recording/Replaying a scenario +## Motivations +It is often useful to record a scenario of an experiment in order to reenact it in post and perform further analysis. We had to slightly augment the recorder and replayer to respect our ego-vehicle being persistent in the world, but all other functionality is maintained. We additionally reenact the ego-sensor data (including HMD pose and orientation) so an experimenter could see what the participant was looking at on every tick. For the full explanation of the Carla recorder see their [documentation](https://carla.readthedocs.io/en/0.9.13/adv_recorder/). + +## Recording +The easiest way to start recording is with the handy `PythonAPI` scripts. +```bash +cd $CARLA_ROOT/PythonAPI/examples/ +# this starts a recording session with 10 autonomous vehicles +./start_recording.py -n 10 # change -n param to change number of vehicles (default 10) +... +^C # stop recording with a SIGINT (interrupt) +``` +- Note that the recording halts if a new world is loaded, so if you want to change the world make sure to restart the recording after the world has loaded. +- The recording saves the default file as a `test1.log` file in the default saved directory of your project: + - If recording from editor: `carla/Unreal/CarlaUE4/Saved/test1.log` + - If recording from package: `${PACKAGE}/Unreal/Saved/test1.log` +- The recording should have relatively minimal impact on the performance of the simulator, but this likely varies by machine. The experience should be essentially the same. +- Note that the recorder saves everything in binary, so it the raw `test1.log` file is not human-readable. It is often nice to read it however, in that case use: + - ```bash + # saves output (stdout) to recorder.txt + ./show_recorder_file_info.py -a -f /PATH/TO/RECORDER-FILE > recorder.txt + ``` + - With this `recorder.txt` file (which holds a human-readable dump of the entire recording log) you can parse this file into useful python data structures (numpy arrays/pandas dataframes) by using our [DReyeVR parser](https://github.com/harplab/dreyevr-parser). +## Replaying +Begin a replay session through the PythonAPI as follows: +```bash +# note this does not rely on being in VR mode or not. +./start_replaying.py # this starts the replaying session +``` +- Note that in the replaying mode, all user inputs will be ignored in favour of the replay inputs. However, you may still use the following level controls: + 1. **Toggle Play/Pause** - Is done by pressing `SpaceBar` + 2. **Advance** - Is done by holding `Alt` and pressing `Left` arrow (backwards) or `Right` arrow (forwards) + 3. **Change Playback Speed** - Is done by holding `Alt` and pressing `Up` arrow (increase) or `Down` arrow (decrease) + 4. **Restart** - Is done by holding `Alt` and pressing `BackSpace` + 6. **Possess Spectator** - Is done by pressing `1` (then use `WASDEQ+mouse` to fly around) + 7. **Re-possess Vehicle** - Is done by pressing `2` + +To get accurate screenshots for every frame of the recording, see below with [synchronized replay frame capture](#synchronized-replay-frame-capture) + +**NOTE** We use custom config files for global and vehicle parameters in the simulator (see [below](Usage.md#using-our-custom-config-file)) and we also store these parameters in the recording file so that we can verify they are the same as the replay. For instance, we will automatically compare the recording's parameters versus the live parameters when performing a replay. Then if we detect any differences, we will print these as warnings so you can be aware. For instance, if you recorded with a particular vehicle and replay the simulator with a different vehicle loaded, we will let you know that the replay may be inaccurate and you are in uncharted territory. + +## Scenarios +It is usually ideal to have curated experiments in the form of scenarios parsed through [ScenarioRunner](https://carla-scenariorunner.readthedocs.io/en/latest/). + +For this purpose, we created a handy script that should be robust to some of the quirks of the existing implementation. This script ([`run_experiment.py`](../ScenarioRunner/run_experiment.py)) will automatically start recording for you AFTER the new map has been loaded, with a unique filename, all on a single client instance, so that you don't need to worry about a faulty recording or overwriting existing files. + +With `scenario_runner` v0.9.13, you should have already set these environment variables: +```bash +# on bash (Linux) +export CARLA_ROOT=/PATH/TO/carla/ +export SCENARIO_RUNNER_ROOT=/PATH/TO/scenario_runner/ +export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-0.9.13-py3.7-linux-x86_64.egg +export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/agents +export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla +export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI + +# on Windows x64 Visual C++ Toolset +set CARLA_ROOT=C:PATH\TO\carla\ +set SCENARIO_RUNNER_ROOT=C:PATH\TO\scenario_runner\ +set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla\dist\carla-0.9.13-py3.7-win-amd64.egg +set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla\agents +set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla +set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI +``` +Then to run our demo examples, use this command: +```bash +# on bash (Linux) +cd $SCENARIO_RUNNER_ROOT # go to scenario-runner +./run_experiment.py --title "dreyevr_experiment" --route $SCENARIO_RUNNER_ROOT/srunner/data/routes_custom.xml $SCENARIO_RUNNER_ROOT/srunner/data/town05_scenarios.json 0 + +# on Windows x64 Visual C++ Toolset +cd %SCENARIO_RUNNER_ROOT% # go to scenario-runner +python run_experiment.py --title "dreyevr_experiment" --route %SCENARIO_RUNNER_ROOT%\srunner\data\routes_custom.xml %SCENARIO_RUNNER_ROOT%\srunner\data\town05_scenarios.json 0 +``` +Note that you can rename the experiment to anything with `--title "your_experiment"`, and the resulting recording file will include this title in its filename. + +# Control handoff to AI +Sometimes it is useful to have an AI takeover of the ego-vehicle during an experiment for research purposes. This becomes easy to do in our simulator with the help of Carla's existing [TrafficManager-based autopilot](https://carla.readthedocs.io/en/0.9.13/adv_traffic_manager/) which can pilot our ego-vehicle just like any other carla Vehicle. + +However, in order to start the autopilot, we currently only support using the PythonAPI for this task, so we created `DReyeVR_AI.py` which will do the job: +```bash +cd $CARLA_ROOT/PythonAPI/examples # go to carla PythonAPI +./DReyeVR_AI.py -n 0 # spawn no other vehicles, enable autopilot on EgoVehicle +``` + +Internally, the AI system is using the Carla vehicle autopilot system, so this can be enabled in your custom PythonAPI scripts without the use of `DReyeVR_AI.py` by performing: +```python +from DReyeVR_utils import find_ego_vehicle +... + +world = client.get_world() +traffic_manager = client.get_trafficmanager(args.tm_port) +... + +DReyeVR_vehicle = find_ego_vehicle(world) +if DReyeVR_vehicle is not None: + DReyeVR_vehicle.set_autopilot(True, traffic_manager.get_port()) + print("Successfully set autopilot on ego vehicle") +``` + +Currently we only support manual handoff by pressing `3` on the keyboard. This gives input priority to the Carla [WheeledVehicleAIController](https://github.com/carla-simulator/carla/blob/0.9.13/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp) which will follow some route defined by Carla's TrafficManager. + +In order to re-possess the vehicle (handoff control back to the player), simply press `1`. Keyboard inputs are automatically higher priority than the autopilot. + +[OPTIONAL]Using this same approach, there is a third option where you can press `2` to possess a "spectator" that can no-clip and fly around the map using `WASDEQ+mouse` controls. + +You can press any of the control options: `1`(human driver), `2`(spectator), `3`(AI driver) at any time. +Summary: + +| Press `1` | Press `2` | Press `3` | +| --- | --- | --- | +| Human driving | Spectator mode | AI driving | + + +# Using our custom config file +Throughout development, we found that modifying even small things in DReyeVR have a LONG cycle time for recompilation/re-linking/re-cooking/etc. so we wanted an approach that could greatly ease this burden while still providing flexibility. + +This is why we developed the [`ConfigFile`](../DReyeVR/ConfigFile.h) class and corresponding [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) (and per-vehicle) "params" so we could read the file at runtime to set variables in the simulator without recompilation. + +The procedure to use our params API is simple: +```c++ +// in, any class, say EgoVehicle.h +#include "DReyeVRUtils.h" // make sure to include our local header file! + +class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle +{ + ... // existing code + + float MyFavouriteNumber; // <--Your new param +} +``` + +Then, choose which type of config file this variable falls into, currently we have two kinds of primary config files: simulator-wide `GeneralParams`, and per-vehicle `VehicleParams`. + +The `GeneralParams` can be thought of as a global simulator-wide configuration file that can be accessed from anywhere, while the `VehicleParams` are specifically for a particular EgoVehicle (such as locations/specifications) that can be found in [`Config/EgoVehicles/`](../Config/EgoVehicles/) that matches the available DReyeVR EgoVehicles. To learn more about these see [EgoVehicle.md](EgoVehicles.md). + +(For general params) +```ini +[MyFavourites] +Number=867.5309 # You can also write comments! +``` +Then, anywhere you want, you can get the parameter by specifying both the section and variable name: + +```c++ +void AEgoVehicle::SomeFunction() +{ + // can use this format to assign directly into a variable + MyFavouriteNumber = GeneralParams.Get("MyFavourites", "Number"); + + // or pass the variable by reference and get whether or not the Get operation was successful + bool bSuccess = GeneralParams.Get("MyFavourites", "Number", MyFavouriteNumber); + +} +``` + +If you are using vehicle-specific params, then this needs to be in the context of some EgoVehicle +```c++ + +void SomeClass::SomeOtherFunction(AEgoVehicle *Vehicle){ + // VehicleParams is a public member of + const ConfigFile &VehicleSpecificParams = Vehicle->GetVehicleParams(); + int VehicleParam = VehicleSpecificParams.Get("VehicleParamSection", "VariableName"); +} +``` + + +And, just like the other variables in the file, you can bunch and organize them together under the same section header. + +Another useful feature we built-in is to import, export, and compare the config files. This is useful because we can track the config file(s) that were used while a particular example was recorded, then if you are trying to replay this scenario with *different* configuration parameters (ex. using a different vehicle, or with mirrors enabled when they werent in the recording), some warnings will be presented when comparing (diff) the recorded config file (saved in the .log file) and the live one (what is currently running). + +# Synchronized replay frame capture +## Motivations +After performing (and recording) an [experiment](../ScenarioRunner/run_experiment.py), we are provided with a log of everything that happened in the simulator that we can use for live reenactment and post-hoc analysis. It is often the case that after some postprocessing on the data, we might be interested in overlaying something on the simulator view to match what a participant was seeing/doing and what the world looked like. Unfortunately, it is difficult to get the exact image frame corresponding to an exact recording event using an asynchronous screen recorder such as OBS, therefore we baked in this functionality within the engine itself, so it can directly go to any recorded event and take a high quality screenshot. The end result is the exact frame-by-frame views corresponding to the recorded world conditions without interpolation. + +### Synchronized replay +To have this functionality, disable the `ReplayInterpolation` flag in [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) under the `[Replayer]` section. Disabling replay interpolation will allow for frame-by-frame reenactment of what was captured (otherwise the replay will respect wall-clock-time and introduce interpolation between frames). + +### Frame capture +While replaying (so, after the experiment was conducted) we can additionally perform frame capture during this replay. Since taking high-res screnshots is expensive, this is a slow process that is done during replays when real-time performance is less important. To enable this feature, enable the `RecordFrames` flag in the `[Replayer]` section as well. There are several other frame capture options below such as resolution and gamma parameters. + +The resulting frame capture images (`.png` or `.jpg` depending on the `FileFormatJPG` flag) will be found in `Unreal/CarlaUE4/{FrameDir}/{DateTimeNow}/{FrameName}*` where `{FrameDir}` and `{FrameName}` are both determined in the [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini). The `{DateTimeNow}` string is uniquely based on your machine's local current time so you can run multiple recordings without overwriting old files. + +**NOTE**: Depending on whether you are running the Editor mode or package mode of DReyeVR will place the FrameCapture directory in the following: +- Editor (debug): `%CARLA_ROOT%\Unreal\CarlaUE4\FrameCap\` +- Package (shipping): `%CARLA_ROOT%\Build\UE4Carla\0.9.13-dirty\WindowsNoEditor\CarlaUE4\FrameCap\` + +(Showing Windows paths for convenience, but the desinations are similar for Linux/Mac) + +With these flags enabled, any time you initiate a replay such as: +```bash +# in PythonAPI/examples +./start_replaying.py -f /PATH/TO/RECORDING/FILE # unix + +python start_replaying.py -f /PATH/TO/RECORDING/FILE # windows +``` + + + +# Other guides +We have written other guides as well that serve more particular needs: +- See [`F.A.Q. wiki`](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) for our Frequently Asked Questions wiki page. +- See [`SetupVR.md`](Tutorials/SetupVR.md) to learn how to quickly and minimally set up VR with Carla +- See [`Sounds.md`](Tutorials/Sounds.md) to see how we added custom sounds and how you can add your own custom sounds +- See [`Signs.md`](Tutorials/Signs.md) to add custom in-world directional signs and dynamically spawn them into the world at runtime +- See [`Shaders/README.md`](../Shaders/README.md) to view our post-processing shaders and learn how to use them +- See [`CustomActor.md`](Tutorials/CustomActor.md) to use our CustomActor classes to use fully-recordable 3D dynamic elements in your scene +- See [`Model.md`](Tutorials/Model.md) to see how we added a responsive steering wheel to the vehicle mesh +- See [`CustomEgo.md`](Tutorials/CustomEgo.md) to add your own custom EgoVehicle model to DReyeVR +- See [`LODs.md`](Tutorials/LODs.md) to learn how we tune the Level-Of-Detail modes for vehicles for a more enjoyable VR experience + + +# Quirks: +- On Windows you're going to want to use the `Windows x64 Visual C++ Toolset` and call all the python files with `python SCRIPT.py` rather than just `./SCRIPT.py` + - Additionally, environment variables are accessed `%LIKE_THIS%` instead of `$LIKE_THIS`. + - And remember that file paths use a backwards slash to `LOCATE\FILES\THIS\WAY\` instead of `THE/NORMAL/WAY/` - There is a bug (we are not sure why, occurs in base carla too), where `Town06/07/10HD` are not present in the `package`d release. Some documentation [here](https://carla.readthedocs.io/en/0.9.13/start_quickstart/#import-additional-assets). \ No newline at end of file diff --git a/LICENSE b/LICENSE index b4e7116..8c6e79e 100644 --- a/LICENSE +++ b/LICENSE @@ -1,21 +1,21 @@ -MIT License - -Copyright (c) 2022 HARPLab - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +MIT License + +Copyright (c) 2022 HARPLab + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. \ No newline at end of file diff --git a/LibCarla/source/carla/client/Vehicle.cpp b/LibCarla/source/carla/client/Vehicle.cpp index fabc9b8..feb990f 100644 --- a/LibCarla/source/carla/client/Vehicle.cpp +++ b/LibCarla/source/carla/client/Vehicle.cpp @@ -1,137 +1,137 @@ -// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "carla/client/Vehicle.h" - -#include "carla/client/ActorList.h" -#include "carla/client/detail/Simulator.h" -#include "carla/client/TrafficLight.h" -#include "carla/Memory.h" -#include "carla/rpc/TrafficLightState.h" - -#include "carla/trafficmanager/TrafficManager.h" - -namespace carla { - -using TM = traffic_manager::TrafficManager; - -namespace client { - - - template - static bool GetControlIsSticky(const AttributesT &attributes) { - for (auto &&attribute : attributes) { - if (attribute.GetId() == "sticky_control") { - return attribute.template As(); - } - } - return true; - } - - Vehicle::Vehicle(ActorInitializer init) - : Actor(std::move(init)), - _is_control_sticky(GetControlIsSticky(GetAttributes())) {} - - void Vehicle::SetAutopilot(bool enabled, uint16_t tm_port) { - GetEpisode().Lock()->SetVehicleAutopilot(*this, enabled); - TM tm(GetEpisode(), tm_port); - if (enabled) { - tm.RegisterVehicles({shared_from_this()}); - } else { - tm.UnregisterVehicles({shared_from_this()}); - } - } - - void Vehicle::ShowDebugTelemetry(bool enabled) { - GetEpisode().Lock()->ShowVehicleDebugTelemetry(*this, enabled); - } - - void Vehicle::ApplyControl(const Control &control) { - if (!_is_control_sticky || (control != _control)) { - GetEpisode().Lock()->ApplyControlToVehicle(*this, control); - _control = control; - } - } - - void Vehicle::ApplyPhysicsControl(const PhysicsControl &physics_control) { - GetEpisode().Lock()->ApplyPhysicsControlToVehicle(*this, physics_control); - } - - void Vehicle::OpenDoor(const VehicleDoor door_idx) { - GetEpisode().Lock()->OpenVehicleDoor(*this, rpc::VehicleDoor(door_idx)); - } - - void Vehicle::CloseDoor(const VehicleDoor door_idx) { - GetEpisode().Lock()->CloseVehicleDoor(*this, rpc::VehicleDoor(door_idx)); - } - - void Vehicle::SetLightState(const LightState &light_state) { - GetEpisode().Lock()->SetLightStateToVehicle(*this, rpc::VehicleLightState(light_state)); - } - - void Vehicle::SetWheelSteerDirection(WheelLocation wheel_location, float angle_in_deg) { - GetEpisode().Lock()->SetWheelSteerDirection(*this, wheel_location, angle_in_deg); - } - - float Vehicle::GetWheelSteerAngle(WheelLocation wheel_location) { - return GetEpisode().Lock()->GetWheelSteerAngle(*this, wheel_location); - } - - Vehicle::Control Vehicle::GetControl() const { - return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.control; - } - - Vehicle::PhysicsControl Vehicle::GetPhysicsControl() const { - return GetEpisode().Lock()->GetVehiclePhysicsControl(*this); - } - - Vehicle::LightState Vehicle::GetLightState() const { - return GetEpisode().Lock()->GetVehicleLightState(*this).GetLightStateEnum(); - } - - float Vehicle::GetSpeedLimit() const { - return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.speed_limit; - } - - rpc::TrafficLightState Vehicle::GetTrafficLightState() const { - return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.traffic_light_state; - } - - bool Vehicle::IsAtTrafficLight() { - return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.has_traffic_light; - } - - SharedPtr Vehicle::GetTrafficLight() const { - auto id = GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.traffic_light_id; - return boost::static_pointer_cast(GetWorld().GetActor(id)); - } - - void Vehicle::EnableCarSim(std::string simfile_path) { - GetEpisode().Lock()->EnableCarSim(*this, simfile_path); - } - - void Vehicle::UseCarSimRoad(bool enabled) { - GetEpisode().Lock()->UseCarSimRoad(*this, enabled); - } - - void Vehicle::EnableChronoPhysics( - uint64_t MaxSubsteps, - float MaxSubstepDeltaTime, - std::string VehicleJSON, - std::string PowertrainJSON, - std::string TireJSON, - std::string BaseJSONPath) { - GetEpisode().Lock()->EnableChronoPhysics(*this, - MaxSubsteps, - MaxSubstepDeltaTime, - VehicleJSON, - PowertrainJSON, - TireJSON, - BaseJSONPath); - } - -} // namespace client -} // namespace carla +// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/client/Vehicle.h" + +#include "carla/client/ActorList.h" +#include "carla/client/detail/Simulator.h" +#include "carla/client/TrafficLight.h" +#include "carla/Memory.h" +#include "carla/rpc/TrafficLightState.h" + +#include "carla/trafficmanager/TrafficManager.h" + +namespace carla { + +using TM = traffic_manager::TrafficManager; + +namespace client { + + + template + static bool GetControlIsSticky(const AttributesT &attributes) { + for (auto &&attribute : attributes) { + if (attribute.GetId() == "sticky_control") { + return attribute.template As(); + } + } + return true; + } + + Vehicle::Vehicle(ActorInitializer init) + : Actor(std::move(init)), + _is_control_sticky(GetControlIsSticky(GetAttributes())) {} + + void Vehicle::SetAutopilot(bool enabled, uint16_t tm_port) { + GetEpisode().Lock()->SetVehicleAutopilot(*this, enabled); + TM tm(GetEpisode(), tm_port); + if (enabled) { + tm.RegisterVehicles({shared_from_this()}); + } else { + tm.UnregisterVehicles({shared_from_this()}); + } + } + + void Vehicle::ShowDebugTelemetry(bool enabled) { + GetEpisode().Lock()->ShowVehicleDebugTelemetry(*this, enabled); + } + + void Vehicle::ApplyControl(const Control &control) { + if (!_is_control_sticky || (control != _control)) { + GetEpisode().Lock()->ApplyControlToVehicle(*this, control); + _control = control; + } + } + + void Vehicle::ApplyPhysicsControl(const PhysicsControl &physics_control) { + GetEpisode().Lock()->ApplyPhysicsControlToVehicle(*this, physics_control); + } + + void Vehicle::OpenDoor(const VehicleDoor door_idx) { + GetEpisode().Lock()->OpenVehicleDoor(*this, rpc::VehicleDoor(door_idx)); + } + + void Vehicle::CloseDoor(const VehicleDoor door_idx) { + GetEpisode().Lock()->CloseVehicleDoor(*this, rpc::VehicleDoor(door_idx)); + } + + void Vehicle::SetLightState(const LightState &light_state) { + GetEpisode().Lock()->SetLightStateToVehicle(*this, rpc::VehicleLightState(light_state)); + } + + void Vehicle::SetWheelSteerDirection(WheelLocation wheel_location, float angle_in_deg) { + GetEpisode().Lock()->SetWheelSteerDirection(*this, wheel_location, angle_in_deg); + } + + float Vehicle::GetWheelSteerAngle(WheelLocation wheel_location) { + return GetEpisode().Lock()->GetWheelSteerAngle(*this, wheel_location); + } + + Vehicle::Control Vehicle::GetControl() const { + return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.control; + } + + Vehicle::PhysicsControl Vehicle::GetPhysicsControl() const { + return GetEpisode().Lock()->GetVehiclePhysicsControl(*this); + } + + Vehicle::LightState Vehicle::GetLightState() const { + return GetEpisode().Lock()->GetVehicleLightState(*this).GetLightStateEnum(); + } + + float Vehicle::GetSpeedLimit() const { + return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.speed_limit; + } + + rpc::TrafficLightState Vehicle::GetTrafficLightState() const { + return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.traffic_light_state; + } + + bool Vehicle::IsAtTrafficLight() { + return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.has_traffic_light; + } + + SharedPtr Vehicle::GetTrafficLight() const { + auto id = GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.traffic_light_id; + return boost::static_pointer_cast(GetWorld().GetActor(id)); + } + + void Vehicle::EnableCarSim(std::string simfile_path) { + GetEpisode().Lock()->EnableCarSim(*this, simfile_path); + } + + void Vehicle::UseCarSimRoad(bool enabled) { + GetEpisode().Lock()->UseCarSimRoad(*this, enabled); + } + + void Vehicle::EnableChronoPhysics( + uint64_t MaxSubsteps, + float MaxSubstepDeltaTime, + std::string VehicleJSON, + std::string PowertrainJSON, + std::string TireJSON, + std::string BaseJSONPath) { + GetEpisode().Lock()->EnableChronoPhysics(*this, + MaxSubsteps, + MaxSubstepDeltaTime, + VehicleJSON, + PowertrainJSON, + TireJSON, + BaseJSONPath); + } + +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/client/detail/ActorFactory.cpp b/LibCarla/source/carla/client/detail/ActorFactory.cpp index f875c13..d19ea23 100644 --- a/LibCarla/source/carla/client/detail/ActorFactory.cpp +++ b/LibCarla/source/carla/client/detail/ActorFactory.cpp @@ -1,106 +1,106 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "carla/client/detail/ActorFactory.h" - -#include "carla/Logging.h" -#include "carla/StringUtil.h" -#include "carla/client/Actor.h" -#include "carla/client/LaneInvasionSensor.h" -#include "carla/client/ServerSideSensor.h" -#ifdef RSS_ENABLED -#include "carla/rss/RssSensor.h" -#endif -#include "carla/client/TrafficLight.h" -#include "carla/client/TrafficSign.h" -#include "carla/client/Vehicle.h" -#include "carla/client/Walker.h" -#include "carla/client/WalkerAIController.h" -#include "carla/client/World.h" -#include "carla/client/detail/Client.h" - -#include -#include - -#include - -namespace carla { -namespace client { -namespace detail { - - // A deleter cannot throw exceptions; and unlike std::unique_ptr, the deleter - // of (std|boost)::shared_ptr is invoked even if the managed pointer is null. - struct GarbageCollector { - void operator()(::carla::client::Actor *ptr) const noexcept { - if ((ptr != nullptr) && ptr->IsAlive()) { - try { - ptr->Destroy(); - delete ptr; - } catch (const ::rpc::timeout &timeout) { - log_error(timeout.what()); - log_error( - "timeout while trying to garbage collect Actor", - ptr->GetDisplayId(), - "actor hasn't been removed from the simulation"); - } catch (const std::exception &e) { - log_critical( - "exception thrown while trying to garbage collect Actor", - ptr->GetDisplayId(), - e.what()); - std::terminate(); - } catch (...) { - log_critical( - "unknown exception thrown while trying to garbage collect an Actor :", - ptr->GetDisplayId()); - std::terminate(); - } - } - } - }; - - template - static auto MakeActorImpl(ActorInitializer init, GarbageCollectionPolicy gc) { - if (gc == GarbageCollectionPolicy::Enabled) { - return SharedPtr{new ActorT(std::move(init)), GarbageCollector()}; - } - DEBUG_ASSERT(gc == GarbageCollectionPolicy::Disabled); - return SharedPtr{new ActorT(std::move(init))}; - } - - SharedPtr ActorFactory::MakeActor( - EpisodeProxy episode, - rpc::Actor description, - GarbageCollectionPolicy gc) { - auto init = ActorInitializer{description, episode}; - if (description.description.id == "sensor.other.lane_invasion") { - return MakeActorImpl(std::move(init), gc); -#ifdef RSS_ENABLED - } else if (description.description.id == "sensor.other.rss") { - return MakeActorImpl(std::move(init), gc); -#endif - } else if (description.HasAStream()) { - return MakeActorImpl(std::move(init), gc); - } else if (StringUtil::StartsWith(description.description.id, "vehicle.")) { - return MakeActorImpl(std::move(init), gc); - } else if (StringUtil::StartsWith(description.description.id, "harplab.dreyevr_vehicle.")) { - return MakeActorImpl(std::move(init), gc); // for DReyeVR vehicles! - } else if (StringUtil::StartsWith(description.description.id, "harplab.dreyevr_sensor.")) { - return MakeActorImpl(std::move(init), gc); // for DReyeVR sensors! - } else if (StringUtil::StartsWith(description.description.id, "walker.")) { - return MakeActorImpl(std::move(init), gc); - } else if (StringUtil::StartsWith(description.description.id, "traffic.traffic_light")) { - return MakeActorImpl(std::move(init), gc); - } else if (StringUtil::StartsWith(description.description.id, "traffic.")) { - return MakeActorImpl(std::move(init), gc); - } else if (description.description.id == "controller.ai.walker") { - return MakeActorImpl(std::move(init), gc); - } - return MakeActorImpl(std::move(init), gc); - } - -} // namespace detail -} // namespace client -} // namespace carla +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/client/detail/ActorFactory.h" + +#include "carla/Logging.h" +#include "carla/StringUtil.h" +#include "carla/client/Actor.h" +#include "carla/client/LaneInvasionSensor.h" +#include "carla/client/ServerSideSensor.h" +#ifdef RSS_ENABLED +#include "carla/rss/RssSensor.h" +#endif +#include "carla/client/TrafficLight.h" +#include "carla/client/TrafficSign.h" +#include "carla/client/Vehicle.h" +#include "carla/client/Walker.h" +#include "carla/client/WalkerAIController.h" +#include "carla/client/World.h" +#include "carla/client/detail/Client.h" + +#include +#include + +#include + +namespace carla { +namespace client { +namespace detail { + + // A deleter cannot throw exceptions; and unlike std::unique_ptr, the deleter + // of (std|boost)::shared_ptr is invoked even if the managed pointer is null. + struct GarbageCollector { + void operator()(::carla::client::Actor *ptr) const noexcept { + if ((ptr != nullptr) && ptr->IsAlive()) { + try { + ptr->Destroy(); + delete ptr; + } catch (const ::rpc::timeout &timeout) { + log_error(timeout.what()); + log_error( + "timeout while trying to garbage collect Actor", + ptr->GetDisplayId(), + "actor hasn't been removed from the simulation"); + } catch (const std::exception &e) { + log_critical( + "exception thrown while trying to garbage collect Actor", + ptr->GetDisplayId(), + e.what()); + std::terminate(); + } catch (...) { + log_critical( + "unknown exception thrown while trying to garbage collect an Actor :", + ptr->GetDisplayId()); + std::terminate(); + } + } + } + }; + + template + static auto MakeActorImpl(ActorInitializer init, GarbageCollectionPolicy gc) { + if (gc == GarbageCollectionPolicy::Enabled) { + return SharedPtr{new ActorT(std::move(init)), GarbageCollector()}; + } + DEBUG_ASSERT(gc == GarbageCollectionPolicy::Disabled); + return SharedPtr{new ActorT(std::move(init))}; + } + + SharedPtr ActorFactory::MakeActor( + EpisodeProxy episode, + rpc::Actor description, + GarbageCollectionPolicy gc) { + auto init = ActorInitializer{description, episode}; + if (description.description.id == "sensor.other.lane_invasion") { + return MakeActorImpl(std::move(init), gc); +#ifdef RSS_ENABLED + } else if (description.description.id == "sensor.other.rss") { + return MakeActorImpl(std::move(init), gc); +#endif + } else if (description.HasAStream()) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "vehicle.")) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "harplab.dreyevr_vehicle.")) { + return MakeActorImpl(std::move(init), gc); // for DReyeVR vehicles! + } else if (StringUtil::StartsWith(description.description.id, "harplab.dreyevr_sensor.")) { + return MakeActorImpl(std::move(init), gc); // for DReyeVR sensors! + } else if (StringUtil::StartsWith(description.description.id, "walker.")) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "traffic.traffic_light")) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "traffic.")) { + return MakeActorImpl(std::move(init), gc); + } else if (description.description.id == "controller.ai.walker") { + return MakeActorImpl(std::move(init), gc); + } + return MakeActorImpl(std::move(init), gc); + } + +} // namespace detail +} // namespace client +} // namespace carla diff --git a/LibCarla/source/carla/sensor/SensorRegistry.h b/LibCarla/source/carla/sensor/SensorRegistry.h index 0a9b003..7c2c6d6 100644 --- a/LibCarla/source/carla/sensor/SensorRegistry.h +++ b/LibCarla/source/carla/sensor/SensorRegistry.h @@ -1,106 +1,106 @@ -// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#ifndef LIBCARLA_SENSOR_REGISTRY_INCLUDE_H -#define LIBCARLA_SENSOR_REGISTRY_INCLUDE_H - -#include "carla/sensor/CompositeSerializer.h" - -// ============================================================================= -// Follow the 4 steps to register a new sensor. -// ============================================================================= - -// 1. Include the serializer here. -#include "carla/sensor/s11n/CollisionEventSerializer.h" -#include "carla/sensor/s11n/DVSEventArraySerializer.h" -#include "carla/sensor/s11n/EpisodeStateSerializer.h" -#include "carla/sensor/s11n/GnssSerializer.h" -#include "carla/sensor/s11n/ImageSerializer.h" -#include "carla/sensor/s11n/OpticalFlowImageSerializer.h" -#include "carla/sensor/s11n/IMUSerializer.h" -#include "carla/sensor/s11n/LidarSerializer.h" -#include "carla/sensor/s11n/NoopSerializer.h" -#include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h" -#include "carla/sensor/s11n/RadarSerializer.h" -#include "carla/sensor/s11n/SemanticLidarSerializer.h" -#include "carla/sensor/s11n/DReyeVRSerializer.h" // DReyeVR serializer header - -// 2. Add a forward-declaration of the sensor here. -class ACollisionSensor; -class ADepthCamera; -class ADVSCamera; -class AGnssSensor; -class AInertialMeasurementUnit; -class ALaneInvasionSensor; -class AObstacleDetectionSensor; -class AOpticalFlowCamera; -class ARadar; -class ARayCastSemanticLidar; -class ARayCastLidar; -class ASceneCaptureCamera; -class ASemanticSegmentationCamera; -class AInstanceSegmentationCamera; -class ARssSensor; -class FWorldObserver; -class ADReyeVRSensor; // DReyeVR forward declaration - -namespace carla { -namespace sensor { - - // 3. Register the sensor and its serializer in the SensorRegistry. - - /// Contains a registry of all the sensors available and allows serializing - /// and deserializing sensor data for the types registered. - /// - /// Use s11n::NoopSerializer if the sensor does not send data (sensors that - /// work only on client-side). - using SensorRegistry = CompositeSerializer< - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair - >; - -} // namespace sensor -} // namespace carla - -#endif // LIBCARLA_SENSOR_REGISTRY_INCLUDE_H - -#ifdef LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES - -// 4. Include the sensor here. -#include "Carla/Sensor/CollisionSensor.h" -#include "Carla/Sensor/DepthCamera.h" -#include "Carla/Sensor/DVSCamera.h" -#include "Carla/Sensor/GnssSensor.h" -#include "Carla/Sensor/InertialMeasurementUnit.h" -#include "Carla/Sensor/LaneInvasionSensor.h" -#include "Carla/Sensor/ObstacleDetectionSensor.h" -#include "Carla/Sensor/OpticalFlowCamera.h" -#include "Carla/Sensor/Radar.h" -#include "Carla/Sensor/RayCastLidar.h" -#include "Carla/Sensor/RayCastSemanticLidar.h" -#include "Carla/Sensor/RssSensor.h" -#include "Carla/Sensor/SceneCaptureCamera.h" -#include "Carla/Sensor/SemanticSegmentationCamera.h" -#include "Carla/Sensor/InstanceSegmentationCamera.h" -#include "Carla/Sensor/WorldObserver.h" -#include "Carla/Sensor/DReyeVRSensor.h" // DReyeVRSensor header file - -#endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES +// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#ifndef LIBCARLA_SENSOR_REGISTRY_INCLUDE_H +#define LIBCARLA_SENSOR_REGISTRY_INCLUDE_H + +#include "carla/sensor/CompositeSerializer.h" + +// ============================================================================= +// Follow the 4 steps to register a new sensor. +// ============================================================================= + +// 1. Include the serializer here. +#include "carla/sensor/s11n/CollisionEventSerializer.h" +#include "carla/sensor/s11n/DVSEventArraySerializer.h" +#include "carla/sensor/s11n/EpisodeStateSerializer.h" +#include "carla/sensor/s11n/GnssSerializer.h" +#include "carla/sensor/s11n/ImageSerializer.h" +#include "carla/sensor/s11n/OpticalFlowImageSerializer.h" +#include "carla/sensor/s11n/IMUSerializer.h" +#include "carla/sensor/s11n/LidarSerializer.h" +#include "carla/sensor/s11n/NoopSerializer.h" +#include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h" +#include "carla/sensor/s11n/RadarSerializer.h" +#include "carla/sensor/s11n/SemanticLidarSerializer.h" +#include "carla/sensor/s11n/DReyeVRSerializer.h" // DReyeVR serializer header + +// 2. Add a forward-declaration of the sensor here. +class ACollisionSensor; +class ADepthCamera; +class ADVSCamera; +class AGnssSensor; +class AInertialMeasurementUnit; +class ALaneInvasionSensor; +class AObstacleDetectionSensor; +class AOpticalFlowCamera; +class ARadar; +class ARayCastSemanticLidar; +class ARayCastLidar; +class ASceneCaptureCamera; +class ASemanticSegmentationCamera; +class AInstanceSegmentationCamera; +class ARssSensor; +class FWorldObserver; +class ADReyeVRSensor; // DReyeVR forward declaration + +namespace carla { +namespace sensor { + + // 3. Register the sensor and its serializer in the SensorRegistry. + + /// Contains a registry of all the sensors available and allows serializing + /// and deserializing sensor data for the types registered. + /// + /// Use s11n::NoopSerializer if the sensor does not send data (sensors that + /// work only on client-side). + using SensorRegistry = CompositeSerializer< + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair, + std::pair + >; + +} // namespace sensor +} // namespace carla + +#endif // LIBCARLA_SENSOR_REGISTRY_INCLUDE_H + +#ifdef LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES + +// 4. Include the sensor here. +#include "Carla/Sensor/CollisionSensor.h" +#include "Carla/Sensor/DepthCamera.h" +#include "Carla/Sensor/DVSCamera.h" +#include "Carla/Sensor/GnssSensor.h" +#include "Carla/Sensor/InertialMeasurementUnit.h" +#include "Carla/Sensor/LaneInvasionSensor.h" +#include "Carla/Sensor/ObstacleDetectionSensor.h" +#include "Carla/Sensor/OpticalFlowCamera.h" +#include "Carla/Sensor/Radar.h" +#include "Carla/Sensor/RayCastLidar.h" +#include "Carla/Sensor/RayCastSemanticLidar.h" +#include "Carla/Sensor/RssSensor.h" +#include "Carla/Sensor/SceneCaptureCamera.h" +#include "Carla/Sensor/SemanticSegmentationCamera.h" +#include "Carla/Sensor/InstanceSegmentationCamera.h" +#include "Carla/Sensor/WorldObserver.h" +#include "Carla/Sensor/DReyeVRSensor.h" // DReyeVRSensor header file + +#endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES diff --git a/LibCarla/source/carla/sensor/data/DReyeVREvent.h b/LibCarla/source/carla/sensor/data/DReyeVREvent.h index 31187aa..321b01c 100644 --- a/LibCarla/source/carla/sensor/data/DReyeVREvent.h +++ b/LibCarla/source/carla/sensor/data/DReyeVREvent.h @@ -1,164 +1,164 @@ -#pragma once - -#include "carla/geom/Vector3D.h" -#include "carla/sensor/SensorData.h" -#include "carla/sensor/s11n/DReyeVRSerializer.h" - -#include - -namespace carla -{ -namespace sensor -{ -namespace data -{ -class DReyeVREvent : public SensorData -{ - friend s11n::DReyeVRSerializer; - - protected: - explicit DReyeVREvent(const RawData &data) : SensorData(data) - { - InternalData = s11n::DReyeVRSerializer::DeserializeRawData(data); - } - - public: - int64_t GetTimestampCarla() const - { - return InternalData.TimestampCarla; - } - int64_t GetTimestampDevice() const - { - return InternalData.TimestampDevice; - } - int64_t GetFrameSequence() const - { - return InternalData.FrameSequence; - } - const geom::Vector3D &GetGazeDir() const - { - return InternalData.GazeDir; - } - const geom::Vector3D &GetGazeOrigin() const - { - return InternalData.GazeOrigin; - } - bool GetGazeValid() const - { - return InternalData.GazeValid; - } - float GetGazeVergence() const - { - return InternalData.GazeVergence; - } - const geom::Vector3D &GetCameraLocation() const - { - return InternalData.CameraLocation; - } - const geom::Vector3D &GetCameraRotation() const - { - return InternalData.CameraRotation; - } - const geom::Vector3D &GetLGazeDir() const - { - return InternalData.LGazeDir; - } - const geom::Vector3D &GetLGazeOrigin() const - { - return InternalData.LGazeOrigin; - } - bool GetLGazeValid() const - { - return InternalData.LGazeValid; - } - const geom::Vector3D &GetRGazeDir() const - { - return InternalData.RGazeDir; - } - const geom::Vector3D &GetRGazeOrigin() const - { - return InternalData.RGazeOrigin; - } - bool GetRGazeValid() const - { - return InternalData.RGazeValid; - } - float GetLEyeOpenness() const - { - return InternalData.LEyeOpenness; - } - bool GetLEyeOpenValid() const - { - return InternalData.LEyeOpenValid; - } - float GetREyeOpenness() const - { - return InternalData.REyeOpenness; - } - bool GetREyeOpenValid() const - { - return InternalData.REyeOpenValid; - } - const geom::Vector2D &GetLPupilPos() const - { - return InternalData.LPupilPos; - } - bool GetLPupilPosValid() const - { - return InternalData.LPupilPosValid; - } - const geom::Vector2D &GetRPupilPos() const - { - return InternalData.RPupilPos; - } - bool GetRPupilPosValid() const - { - return InternalData.RPupilPosValid; - } - float GetLPupilDiam() const - { - return InternalData.LPupilDiameter; - } - float GetRPupilDiam() const - { - return InternalData.RPupilDiameter; - } - const std::string &GetFocusActorName() const - { - return InternalData.FocusActorName; - } - const geom::Vector3D &GetFocusActorPoint() const - { - return InternalData.FocusActorPoint; - } - float GetFocusActorDist() const - { - return InternalData.FocusActorDist; - } - float GetThrottle() const - { - return InternalData.Throttle; - } - float GetSteering() const - { - return InternalData.Steering; - } - float GetBrake() const - { - return InternalData.Brake; - } - bool GetToggledReverse() const - { - return InternalData.ToggledReverse; - } - bool GetHandbrake() const - { - return InternalData.HoldHandbrake; - } - - private: - carla::sensor::s11n::DReyeVRSerializer::Data InternalData; -}; -} // namespace data -} // namespace sensor +#pragma once + +#include "carla/geom/Vector3D.h" +#include "carla/sensor/SensorData.h" +#include "carla/sensor/s11n/DReyeVRSerializer.h" + +#include + +namespace carla +{ +namespace sensor +{ +namespace data +{ +class DReyeVREvent : public SensorData +{ + friend s11n::DReyeVRSerializer; + + protected: + explicit DReyeVREvent(const RawData &data) : SensorData(data) + { + InternalData = s11n::DReyeVRSerializer::DeserializeRawData(data); + } + + public: + int64_t GetTimestampCarla() const + { + return InternalData.TimestampCarla; + } + int64_t GetTimestampDevice() const + { + return InternalData.TimestampDevice; + } + int64_t GetFrameSequence() const + { + return InternalData.FrameSequence; + } + const geom::Vector3D &GetGazeDir() const + { + return InternalData.GazeDir; + } + const geom::Vector3D &GetGazeOrigin() const + { + return InternalData.GazeOrigin; + } + bool GetGazeValid() const + { + return InternalData.GazeValid; + } + float GetGazeVergence() const + { + return InternalData.GazeVergence; + } + const geom::Vector3D &GetCameraLocation() const + { + return InternalData.CameraLocation; + } + const geom::Vector3D &GetCameraRotation() const + { + return InternalData.CameraRotation; + } + const geom::Vector3D &GetLGazeDir() const + { + return InternalData.LGazeDir; + } + const geom::Vector3D &GetLGazeOrigin() const + { + return InternalData.LGazeOrigin; + } + bool GetLGazeValid() const + { + return InternalData.LGazeValid; + } + const geom::Vector3D &GetRGazeDir() const + { + return InternalData.RGazeDir; + } + const geom::Vector3D &GetRGazeOrigin() const + { + return InternalData.RGazeOrigin; + } + bool GetRGazeValid() const + { + return InternalData.RGazeValid; + } + float GetLEyeOpenness() const + { + return InternalData.LEyeOpenness; + } + bool GetLEyeOpenValid() const + { + return InternalData.LEyeOpenValid; + } + float GetREyeOpenness() const + { + return InternalData.REyeOpenness; + } + bool GetREyeOpenValid() const + { + return InternalData.REyeOpenValid; + } + const geom::Vector2D &GetLPupilPos() const + { + return InternalData.LPupilPos; + } + bool GetLPupilPosValid() const + { + return InternalData.LPupilPosValid; + } + const geom::Vector2D &GetRPupilPos() const + { + return InternalData.RPupilPos; + } + bool GetRPupilPosValid() const + { + return InternalData.RPupilPosValid; + } + float GetLPupilDiam() const + { + return InternalData.LPupilDiameter; + } + float GetRPupilDiam() const + { + return InternalData.RPupilDiameter; + } + const std::string &GetFocusActorName() const + { + return InternalData.FocusActorName; + } + const geom::Vector3D &GetFocusActorPoint() const + { + return InternalData.FocusActorPoint; + } + float GetFocusActorDist() const + { + return InternalData.FocusActorDist; + } + float GetThrottle() const + { + return InternalData.Throttle; + } + float GetSteering() const + { + return InternalData.Steering; + } + float GetBrake() const + { + return InternalData.Brake; + } + bool GetToggledReverse() const + { + return InternalData.ToggledReverse; + } + bool GetHandbrake() const + { + return InternalData.HoldHandbrake; + } + + private: + carla::sensor::s11n::DReyeVRSerializer::Data InternalData; +}; +} // namespace data +} // namespace sensor } // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.cpp b/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.cpp index 0f93602..1c070ea 100644 --- a/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.cpp @@ -1,16 +1,16 @@ -#include "carla/sensor/s11n/DReyeVRSerializer.h" -#include "carla/sensor/data/DReyeVREvent.h" - -namespace carla -{ - namespace sensor - { - namespace s11n - { - SharedPtr DReyeVRSerializer::Deserialize(RawData &&data) - { - return SharedPtr(new data::DReyeVREvent(std::move(data))); - } - } // namespace s11n - } // namespace sensor +#include "carla/sensor/s11n/DReyeVRSerializer.h" +#include "carla/sensor/data/DReyeVREvent.h" + +namespace carla +{ + namespace sensor + { + namespace s11n + { + SharedPtr DReyeVRSerializer::Deserialize(RawData &&data) + { + return SharedPtr(new data::DReyeVREvent(std::move(data))); + } + } // namespace s11n + } // namespace sensor } // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h b/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h index f686eb0..e63742e 100644 --- a/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h @@ -1,96 +1,96 @@ - -#pragma once - -#include "carla/Buffer.h" -#include "carla/Memory.h" -#include "carla/geom/Vector2D.h" -#include "carla/geom/Vector3D.h" -#include "carla/sensor/RawData.h" - -#include -#include - -namespace carla -{ -namespace sensor -{ -class SensorData; - -namespace s11n -{ -class DReyeVRSerializer -{ - public: - struct Data - { - /// TODO: refactor this struct to contain smaller structs similar to DReyeVR::AggregateData - /// NOTE: this is missing some fields that can totally be added, but you get the idea. - // Step 1: add new field field here in Data struct - // Step 2: add new field in MSGPACK_DEFINE_ARRAY) in the SAME ORDER - // Step 3: go to LibCarla/source/carla/sensor/data/DReyeVREvent.h and add a const getter - // Step 4: go to PythonAPI/carla/source/libcarla/SensorData.cpp and add the getter to the list of available attributes just like the others - int64_t TimestampCarla; - int64_t TimestampDevice; - int64_t FrameSequence; - // camera - geom::Vector3D CameraLocation; - geom::Vector3D CameraRotation; - // combined gaze - geom::Vector3D GazeDir; - geom::Vector3D GazeOrigin; - bool GazeValid; - float GazeVergence; - // left gaze/eye - geom::Vector3D LGazeDir; - geom::Vector3D LGazeOrigin; - bool LGazeValid; - float LEyeOpenness; - bool LEyeOpenValid; - geom::Vector2D LPupilPos; - bool LPupilPosValid; - float LPupilDiameter; - // right gaze/eye - geom::Vector3D RGazeDir; - geom::Vector3D RGazeOrigin; - bool RGazeValid; - float REyeOpenness; - bool REyeOpenValid; - geom::Vector2D RPupilPos; - bool RPupilPosValid; - float RPupilDiameter; - // focus - std::string FocusActorName; - geom::Vector3D FocusActorPoint; - float FocusActorDist; - // inputs - float Throttle; - float Steering; - float Brake; - bool ToggledReverse; - bool HoldHandbrake; - - MSGPACK_DEFINE_ARRAY(TimestampCarla, TimestampDevice, FrameSequence, // timings - CameraLocation, CameraRotation, // camera - GazeDir, GazeOrigin, GazeValid, GazeVergence, // combined gaze - LGazeDir, LGazeOrigin, LGazeValid, LEyeOpenness, LEyeOpenValid, LPupilPos, LPupilPosValid, LPupilDiameter, // left gaze/eye - RGazeDir, RGazeOrigin, RGazeValid, REyeOpenness, REyeOpenValid, RPupilPos, RPupilPosValid, RPupilDiameter, // right gaze/eye - FocusActorName, FocusActorPoint, FocusActorDist, // focus info - Throttle, Steering, Brake, ToggledReverse, HoldHandbrake // user inputs - ) - }; - - static Data DeserializeRawData(const RawData &message) - { - return MsgPack::UnPack(message.begin(), message.size()); - } - - template static Buffer Serialize(const SensorT &, struct Data &&DataIn) - { - return MsgPack::Pack(DataIn); - } - static SharedPtr Deserialize(RawData &&data); -}; - -} // namespace s11n -} // namespace sensor + +#pragma once + +#include "carla/Buffer.h" +#include "carla/Memory.h" +#include "carla/geom/Vector2D.h" +#include "carla/geom/Vector3D.h" +#include "carla/sensor/RawData.h" + +#include +#include + +namespace carla +{ +namespace sensor +{ +class SensorData; + +namespace s11n +{ +class DReyeVRSerializer +{ + public: + struct Data + { + /// TODO: refactor this struct to contain smaller structs similar to DReyeVR::AggregateData + /// NOTE: this is missing some fields that can totally be added, but you get the idea. + // Step 1: add new field field here in Data struct + // Step 2: add new field in MSGPACK_DEFINE_ARRAY) in the SAME ORDER + // Step 3: go to LibCarla/source/carla/sensor/data/DReyeVREvent.h and add a const getter + // Step 4: go to PythonAPI/carla/source/libcarla/SensorData.cpp and add the getter to the list of available attributes just like the others + int64_t TimestampCarla; + int64_t TimestampDevice; + int64_t FrameSequence; + // camera + geom::Vector3D CameraLocation; + geom::Vector3D CameraRotation; + // combined gaze + geom::Vector3D GazeDir; + geom::Vector3D GazeOrigin; + bool GazeValid; + float GazeVergence; + // left gaze/eye + geom::Vector3D LGazeDir; + geom::Vector3D LGazeOrigin; + bool LGazeValid; + float LEyeOpenness; + bool LEyeOpenValid; + geom::Vector2D LPupilPos; + bool LPupilPosValid; + float LPupilDiameter; + // right gaze/eye + geom::Vector3D RGazeDir; + geom::Vector3D RGazeOrigin; + bool RGazeValid; + float REyeOpenness; + bool REyeOpenValid; + geom::Vector2D RPupilPos; + bool RPupilPosValid; + float RPupilDiameter; + // focus + std::string FocusActorName; + geom::Vector3D FocusActorPoint; + float FocusActorDist; + // inputs + float Throttle; + float Steering; + float Brake; + bool ToggledReverse; + bool HoldHandbrake; + + MSGPACK_DEFINE_ARRAY(TimestampCarla, TimestampDevice, FrameSequence, // timings + CameraLocation, CameraRotation, // camera + GazeDir, GazeOrigin, GazeValid, GazeVergence, // combined gaze + LGazeDir, LGazeOrigin, LGazeValid, LEyeOpenness, LEyeOpenValid, LPupilPos, LPupilPosValid, LPupilDiameter, // left gaze/eye + RGazeDir, RGazeOrigin, RGazeValid, REyeOpenness, REyeOpenValid, RPupilPos, RPupilPosValid, RPupilDiameter, // right gaze/eye + FocusActorName, FocusActorPoint, FocusActorDist, // focus info + Throttle, Steering, Brake, ToggledReverse, HoldHandbrake // user inputs + ) + }; + + static Data DeserializeRawData(const RawData &message) + { + return MsgPack::UnPack(message.begin(), message.size()); + } + + template static Buffer Serialize(const SensorT &, struct Data &&DataIn) + { + return MsgPack::Pack(DataIn); + } + static SharedPtr Deserialize(RawData &&data); +}; + +} // namespace s11n +} // namespace sensor } // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/trafficmanager/ALSM.cpp b/LibCarla/source/carla/trafficmanager/ALSM.cpp index eee90c2..78c72f3 100644 --- a/LibCarla/source/carla/trafficmanager/ALSM.cpp +++ b/LibCarla/source/carla/trafficmanager/ALSM.cpp @@ -1,403 +1,403 @@ - -#include "boost/pointer_cast.hpp" - -#include "carla/client/Actor.h" -#include "carla/client/Vehicle.h" -#include "carla/client/Walker.h" - -#include "carla/trafficmanager/Constants.h" -#include "carla/trafficmanager/LocalizationUtils.h" -#include "carla/trafficmanager/SimpleWaypoint.h" - -#include "carla/trafficmanager/ALSM.h" - -namespace carla { -namespace traffic_manager { - -ALSM::ALSM( - AtomicActorSet ®istered_vehicles, - BufferMap &buffer_map, - TrackTraffic &track_traffic, - std::vector& marked_for_removal, - const Parameters ¶meters, - const cc::World &world, - const LocalMapPtr &local_map, - SimulationState &simulation_state, - LocalizationStage &localization_stage, - CollisionStage &collision_stage, - TrafficLightStage &traffic_light_stage, - MotionPlanStage &motion_plan_stage, - VehicleLightStage &vehicle_light_stage, - RandomGeneratorMap &random_devices) - : registered_vehicles(registered_vehicles), - buffer_map(buffer_map), - track_traffic(track_traffic), - marked_for_removal(marked_for_removal), - parameters(parameters), - world(world), - local_map(local_map), - simulation_state(simulation_state), - localization_stage(localization_stage), - collision_stage(collision_stage), - traffic_light_stage(traffic_light_stage), - motion_plan_stage(motion_plan_stage), - vehicle_light_stage(vehicle_light_stage), - random_devices(random_devices) {} - -void ALSM::Update() { - - bool hybrid_physics_mode = parameters.GetHybridPhysicsMode(); - - std::set world_vehicle_ids; - std::set world_pedestrian_ids; - std::vector unregistered_list_to_be_deleted; - - current_timestamp = world.GetSnapshot().GetTimestamp(); - ActorList world_actors = world.GetActors(); - - // Find destroyed actors and perform clean up. - const ALSM::DestroyeddActors destroyed_actors = IdentifyDestroyedActors(world_actors); - - const ActorIdSet &destroyed_registered = destroyed_actors.first; - for (const auto &deletion_id: destroyed_registered) { - RemoveActor(deletion_id, true); - } - - const ActorIdSet &destroyed_unregistered = destroyed_actors.second; - for (auto deletion_id : destroyed_unregistered) { - RemoveActor(deletion_id, false); - } - - // Invalidate hero actor if it is not alive anymore. - if (hero_actors.size() != 0u) { - ActorIdSet hero_actors_to_delete; - for (auto &hero_actor_info: hero_actors) { - if (destroyed_unregistered.find(hero_actor_info.first) != destroyed_unregistered.end()) { - hero_actors_to_delete.insert(hero_actor_info.first); - } - if (destroyed_registered.find(hero_actor_info.first) != destroyed_registered.end()) { - hero_actors_to_delete.insert(hero_actor_info.first); - } - } - - for (auto &deletion_id: hero_actors_to_delete) { - hero_actors.erase(deletion_id); - } - } - - // Scan for new unregistered actors. - IdentifyNewActors(world_actors); - - // Update dynamic state and static attributes for all registered vehicles. - ALSM::IdleInfo max_idle_time = std::make_pair(0u, current_timestamp.elapsed_seconds); - UpdateRegisteredActorsData(hybrid_physics_mode, max_idle_time); - - // Destroy registered vehicle if stuck at a location for too long. - if (IsVehicleStuck(max_idle_time.first) - && (current_timestamp.elapsed_seconds - elapsed_last_actor_destruction) > DELTA_TIME_BETWEEN_DESTRUCTIONS - && hero_actors.find(max_idle_time.first) == hero_actors.end()) { - registered_vehicles.Destroy(max_idle_time.first); - RemoveActor(max_idle_time.first, true); - elapsed_last_actor_destruction = current_timestamp.elapsed_seconds; - } - - // Destorying vehicles for marked for removal by stages. - if (parameters.GetOSMMode()) { - for (const ActorId& actor_id: marked_for_removal) { - registered_vehicles.Destroy(actor_id); - RemoveActor(actor_id, true); - } - marked_for_removal.clear(); - } - - // Update dynamic state and static attributes for unregistered actors. - UpdateUnregisteredActorsData(); -} - -void ALSM::IdentifyNewActors(const ActorList &actor_list) { - for (auto iter = actor_list->begin(); iter != actor_list->end(); ++iter) { - ActorPtr actor = *iter; - ActorId actor_id = actor->GetId(); - // Identify any new hero vehicle - if (actor->GetTypeId().front() == 'v' || actor->GetTypeId().rfind("harplab.dreyevr_vehicle.") == 0) { - if (hero_actors.size() == 0u || hero_actors.find(actor_id) == hero_actors.end()) { - for (auto&& attribute: actor->GetAttributes()) { - if (attribute.GetId() == "role_name" && attribute.GetValue() == "hero") { - hero_actors.insert({actor_id, actor}); - } - } - } - } - if (!registered_vehicles.Contains(actor_id) - && unregistered_actors.find(actor_id) == unregistered_actors.end()) { - - unregistered_actors.insert({actor_id, actor}); - } - } -} - -ALSM::DestroyeddActors ALSM::IdentifyDestroyedActors(const ActorList &actor_list) { - - ALSM::DestroyeddActors destroyed_actors; - ActorIdSet &deleted_registered = destroyed_actors.first; - ActorIdSet &deleted_unregistered = destroyed_actors.second; - - // Building hash set of actors present in current frame. - ActorIdSet current_actors; - for (auto iter = actor_list->begin(); iter != actor_list->end(); ++iter) { - current_actors.insert((*iter)->GetId()); - } - - // Searching for destroyed registered actors. - std::vector registered_ids = registered_vehicles.GetIDList(); - for (const ActorId &actor_id : registered_ids) { - if (current_actors.find(actor_id) == current_actors.end()) { - deleted_registered.insert(actor_id); - } - } - - // Searching for destroyed unregistered actors. - for (const auto &actor_info: unregistered_actors) { - const ActorId &actor_id = actor_info.first; - if (current_actors.find(actor_id) == current_actors.end() - || registered_vehicles.Contains(actor_id)) { - deleted_unregistered.insert(actor_id); - } - } - - return destroyed_actors; -} - -void ALSM::UpdateRegisteredActorsData(const bool hybrid_physics_mode, ALSM::IdleInfo &max_idle_time) { - - std::vector vehicle_list = registered_vehicles.GetList(); - bool hero_actor_present = hero_actors.size() != 0u; - float physics_radius = parameters.GetHybridPhysicsRadius(); - float physics_radius_square = SQUARE(physics_radius); - bool is_respawn_vehicles = parameters.GetRespawnDormantVehicles(); - if (is_respawn_vehicles && !hero_actor_present) { - track_traffic.SetHeroLocation(cg::Location(0,0,0)); - } - // Update first the information regarding any hero vehicle. - for (auto &hero_actor_info: hero_actors){ - if (is_respawn_vehicles) { - track_traffic.SetHeroLocation(hero_actor_info.second->GetTransform().location); - } - UpdateData(hybrid_physics_mode, max_idle_time, hero_actor_info.second, hero_actor_present, physics_radius_square); - } - // Update information for all other registered vehicles. - for (const Actor &vehicle : vehicle_list) { - ActorId actor_id = vehicle->GetId(); - if (hero_actors.find(actor_id) == hero_actors.end()) { - UpdateData(hybrid_physics_mode, max_idle_time, vehicle, hero_actor_present, physics_radius_square); - } - } -} - -void ALSM::UpdateData(const bool hybrid_physics_mode, - ALSM::IdleInfo &max_idle_time, const Actor &vehicle, - const bool hero_actor_present, const float physics_radius_square) { - - ActorId actor_id = vehicle->GetId(); - cg::Transform vehicle_transform = vehicle->GetTransform(); - cg::Location vehicle_location = vehicle_transform.location; - cg::Rotation vehicle_rotation = vehicle_transform.rotation; - cg::Vector3D vehicle_velocity = vehicle->GetVelocity(); - - // Initializing idle times. - if (idle_time.find(actor_id) == idle_time.end() && current_timestamp.elapsed_seconds != 0.0) { - idle_time.insert({actor_id, current_timestamp.elapsed_seconds}); - } - - // Check if current actor is in range of hero actor and enable physics in hybrid mode. - bool in_range_of_hero_actor = false; - if (hero_actor_present && hybrid_physics_mode) { - for (auto &hero_actor_info: hero_actors) { - const ActorId &hero_actor_id = hero_actor_info.first; - if (simulation_state.ContainsActor(hero_actor_id)) { - const cg::Location &hero_location = simulation_state.GetLocation(hero_actor_id); - if (cg::Math::DistanceSquared(vehicle_location, hero_location) < physics_radius_square) { - in_range_of_hero_actor = true; - break; - } - } - } - } - - bool enable_physics = hybrid_physics_mode ? in_range_of_hero_actor : true; - if (!has_physics_enabled.count(actor_id) || has_physics_enabled[actor_id] != enable_physics) { - if (hero_actors.find(actor_id) == hero_actors.end()) { - vehicle->SetSimulatePhysics(enable_physics); - has_physics_enabled[actor_id] = enable_physics; - if (enable_physics == true && simulation_state.ContainsActor(actor_id)) { - vehicle->SetTargetVelocity(simulation_state.GetVelocity(actor_id)); - } - } - } - - bool state_entry_present = simulation_state.ContainsActor(actor_id); - // If physics is disabled, calculate velocity based on change in position. - if (!enable_physics) { - cg::Location previous_location; - if (state_entry_present) { - previous_location = simulation_state.GetLocation(actor_id); - } else { - previous_location = vehicle_location; - } - cg::Vector3D displacement = (vehicle_location - previous_location); - vehicle_velocity = displacement * INV_HYBRID_DT; - } - - // Updated kinematic state object. - auto vehicle_ptr = boost::static_pointer_cast(vehicle); - KinematicState kinematic_state{vehicle_location, vehicle_rotation, - vehicle_velocity, vehicle_ptr->GetSpeedLimit(), - enable_physics, vehicle->IsDormant()}; - - // Updated traffic light state object. - TrafficLightState tl_state = {vehicle_ptr->GetTrafficLightState(), vehicle_ptr->IsAtTrafficLight()}; - - // Update simulation state. - if (state_entry_present) { - simulation_state.UpdateKinematicState(actor_id, kinematic_state); - simulation_state.UpdateTrafficLightState(actor_id, tl_state); - } - else { - cg::Vector3D dimensions = vehicle_ptr->GetBoundingBox().extent; - StaticAttributes attributes{ActorType::Vehicle, dimensions.x, dimensions.y, dimensions.z}; - - simulation_state.AddActor(actor_id, kinematic_state, attributes, tl_state); - } - - // Updating idle time when necessary. - UpdateIdleTime(max_idle_time, actor_id); -} - - -void ALSM::UpdateUnregisteredActorsData() { - for (auto &actor_info: unregistered_actors) { - - const ActorId actor_id = actor_info.first; - const ActorPtr actor_ptr = actor_info.second; - const std::string type_id = actor_ptr->GetTypeId(); - - const cg::Transform actor_transform = actor_ptr->GetTransform(); - const cg::Location actor_location = actor_transform.location; - const cg::Rotation actor_rotation = actor_transform.rotation; - const cg::Vector3D actor_velocity = actor_ptr->GetVelocity(); - const bool actor_is_dormant = actor_ptr->IsDormant(); - KinematicState kinematic_state {actor_location, actor_rotation, actor_velocity, -1.0f, true, actor_is_dormant}; - - TrafficLightState tl_state; - ActorType actor_type = ActorType::Any; - cg::Vector3D dimensions; - std::vector nearest_waypoints; - - bool state_entry_not_present = !simulation_state.ContainsActor(actor_id); - if (type_id.front() == 'v' || type_id.rfind("harplab.dreyevr_vehicle.") == 0) { // include DReyeVR vehicle - auto vehicle_ptr = boost::static_pointer_cast(actor_ptr); - kinematic_state.speed_limit = vehicle_ptr->GetSpeedLimit(); - - tl_state = {vehicle_ptr->GetTrafficLightState(), vehicle_ptr->IsAtTrafficLight()}; - - if (state_entry_not_present) { - dimensions = vehicle_ptr->GetBoundingBox().extent; - actor_type = ActorType::Vehicle; - StaticAttributes attributes {actor_type, dimensions.x, dimensions.y, dimensions.z}; - - simulation_state.AddActor(actor_id, kinematic_state, attributes, tl_state); - } else { - simulation_state.UpdateKinematicState(actor_id, kinematic_state); - simulation_state.UpdateTrafficLightState(actor_id, tl_state); - } - - // Identify occupied waypoints. - cg::Vector3D extent = vehicle_ptr->GetBoundingBox().extent; - cg::Vector3D heading_vector = vehicle_ptr->GetTransform().GetForwardVector(); - std::vector corners = {actor_location + cg::Location(extent.x * heading_vector), - actor_location, - actor_location + cg::Location(-extent.x * heading_vector)}; - for (cg::Location &vertex: corners) { - SimpleWaypointPtr nearest_waypoint = local_map->GetWaypoint(vertex); - nearest_waypoints.push_back(nearest_waypoint); - } - } - else if (type_id.front() == 'w') { - auto walker_ptr = boost::static_pointer_cast(actor_ptr); - - if (state_entry_not_present) { - dimensions = walker_ptr->GetBoundingBox().extent; - actor_type = ActorType::Pedestrian; - StaticAttributes attributes {actor_type, dimensions.x, dimensions.y, dimensions.z}; - - simulation_state.AddActor(actor_id, kinematic_state, attributes, tl_state); - } else { - simulation_state.UpdateKinematicState(actor_id, kinematic_state); - } - - // Identify occupied waypoints. - SimpleWaypointPtr nearest_waypoint = local_map->GetWaypoint(actor_location); - nearest_waypoints.push_back(nearest_waypoint); - } - - track_traffic.UpdateUnregisteredGridPosition(actor_id, nearest_waypoints); - } -} - -void ALSM::UpdateIdleTime(std::pair& max_idle_time, const ActorId& actor_id) { - if (idle_time.find(actor_id) != idle_time.end()) { - double &idle_duration = idle_time.at(actor_id); - if (simulation_state.GetVelocity(actor_id).SquaredLength() > SQUARE(STOPPED_VELOCITY_THRESHOLD)) { - idle_duration = current_timestamp.elapsed_seconds; - } - - // Checking maximum idle time. - if (max_idle_time.first == 0u || max_idle_time.second > idle_duration) { - max_idle_time = std::make_pair(actor_id, idle_duration); - } - } -} - -bool ALSM::IsVehicleStuck(const ActorId& actor_id) { - if (idle_time.find(actor_id) != idle_time.end()) { - double delta_idle_time = current_timestamp.elapsed_seconds - idle_time.at(actor_id); - TrafficLightState tl_state = simulation_state.GetTLS(actor_id); - if ((!tl_state.at_traffic_light && tl_state.tl_state != TLS::Red && delta_idle_time >= BLOCKED_TIME_THRESHOLD) - || (delta_idle_time >= RED_TL_BLOCKED_TIME_THRESHOLD)) { - return true; - } - } - return false; -} - -void ALSM::RemoveActor(const ActorId actor_id, const bool registered_actor) { - if (registered_actor) { - registered_vehicles.Remove({actor_id}); - buffer_map.erase(actor_id); - idle_time.erase(actor_id); - random_devices.erase(actor_id); - localization_stage.RemoveActor(actor_id); - collision_stage.RemoveActor(actor_id); - traffic_light_stage.RemoveActor(actor_id); - motion_plan_stage.RemoveActor(actor_id); - vehicle_light_stage.RemoveActor(actor_id); - } - else { - unregistered_actors.erase(actor_id); - hero_actors.erase(actor_id); - } - - track_traffic.DeleteActor(actor_id); - simulation_state.RemoveActor(actor_id); -} - -void ALSM::Reset() { - unregistered_actors.clear(); - idle_time.clear(); - hero_actors.clear(); - elapsed_last_actor_destruction = 0.0; - current_timestamp = world.GetSnapshot().GetTimestamp(); -} - -} // namespace traffic_manager -} // namespace carla + +#include "boost/pointer_cast.hpp" + +#include "carla/client/Actor.h" +#include "carla/client/Vehicle.h" +#include "carla/client/Walker.h" + +#include "carla/trafficmanager/Constants.h" +#include "carla/trafficmanager/LocalizationUtils.h" +#include "carla/trafficmanager/SimpleWaypoint.h" + +#include "carla/trafficmanager/ALSM.h" + +namespace carla { +namespace traffic_manager { + +ALSM::ALSM( + AtomicActorSet ®istered_vehicles, + BufferMap &buffer_map, + TrackTraffic &track_traffic, + std::vector& marked_for_removal, + const Parameters ¶meters, + const cc::World &world, + const LocalMapPtr &local_map, + SimulationState &simulation_state, + LocalizationStage &localization_stage, + CollisionStage &collision_stage, + TrafficLightStage &traffic_light_stage, + MotionPlanStage &motion_plan_stage, + VehicleLightStage &vehicle_light_stage, + RandomGeneratorMap &random_devices) + : registered_vehicles(registered_vehicles), + buffer_map(buffer_map), + track_traffic(track_traffic), + marked_for_removal(marked_for_removal), + parameters(parameters), + world(world), + local_map(local_map), + simulation_state(simulation_state), + localization_stage(localization_stage), + collision_stage(collision_stage), + traffic_light_stage(traffic_light_stage), + motion_plan_stage(motion_plan_stage), + vehicle_light_stage(vehicle_light_stage), + random_devices(random_devices) {} + +void ALSM::Update() { + + bool hybrid_physics_mode = parameters.GetHybridPhysicsMode(); + + std::set world_vehicle_ids; + std::set world_pedestrian_ids; + std::vector unregistered_list_to_be_deleted; + + current_timestamp = world.GetSnapshot().GetTimestamp(); + ActorList world_actors = world.GetActors(); + + // Find destroyed actors and perform clean up. + const ALSM::DestroyeddActors destroyed_actors = IdentifyDestroyedActors(world_actors); + + const ActorIdSet &destroyed_registered = destroyed_actors.first; + for (const auto &deletion_id: destroyed_registered) { + RemoveActor(deletion_id, true); + } + + const ActorIdSet &destroyed_unregistered = destroyed_actors.second; + for (auto deletion_id : destroyed_unregistered) { + RemoveActor(deletion_id, false); + } + + // Invalidate hero actor if it is not alive anymore. + if (hero_actors.size() != 0u) { + ActorIdSet hero_actors_to_delete; + for (auto &hero_actor_info: hero_actors) { + if (destroyed_unregistered.find(hero_actor_info.first) != destroyed_unregistered.end()) { + hero_actors_to_delete.insert(hero_actor_info.first); + } + if (destroyed_registered.find(hero_actor_info.first) != destroyed_registered.end()) { + hero_actors_to_delete.insert(hero_actor_info.first); + } + } + + for (auto &deletion_id: hero_actors_to_delete) { + hero_actors.erase(deletion_id); + } + } + + // Scan for new unregistered actors. + IdentifyNewActors(world_actors); + + // Update dynamic state and static attributes for all registered vehicles. + ALSM::IdleInfo max_idle_time = std::make_pair(0u, current_timestamp.elapsed_seconds); + UpdateRegisteredActorsData(hybrid_physics_mode, max_idle_time); + + // Destroy registered vehicle if stuck at a location for too long. + if (IsVehicleStuck(max_idle_time.first) + && (current_timestamp.elapsed_seconds - elapsed_last_actor_destruction) > DELTA_TIME_BETWEEN_DESTRUCTIONS + && hero_actors.find(max_idle_time.first) == hero_actors.end()) { + registered_vehicles.Destroy(max_idle_time.first); + RemoveActor(max_idle_time.first, true); + elapsed_last_actor_destruction = current_timestamp.elapsed_seconds; + } + + // Destorying vehicles for marked for removal by stages. + if (parameters.GetOSMMode()) { + for (const ActorId& actor_id: marked_for_removal) { + registered_vehicles.Destroy(actor_id); + RemoveActor(actor_id, true); + } + marked_for_removal.clear(); + } + + // Update dynamic state and static attributes for unregistered actors. + UpdateUnregisteredActorsData(); +} + +void ALSM::IdentifyNewActors(const ActorList &actor_list) { + for (auto iter = actor_list->begin(); iter != actor_list->end(); ++iter) { + ActorPtr actor = *iter; + ActorId actor_id = actor->GetId(); + // Identify any new hero vehicle + if (actor->GetTypeId().front() == 'v' || actor->GetTypeId().rfind("harplab.dreyevr_vehicle.") == 0) { + if (hero_actors.size() == 0u || hero_actors.find(actor_id) == hero_actors.end()) { + for (auto&& attribute: actor->GetAttributes()) { + if (attribute.GetId() == "role_name" && attribute.GetValue() == "hero") { + hero_actors.insert({actor_id, actor}); + } + } + } + } + if (!registered_vehicles.Contains(actor_id) + && unregistered_actors.find(actor_id) == unregistered_actors.end()) { + + unregistered_actors.insert({actor_id, actor}); + } + } +} + +ALSM::DestroyeddActors ALSM::IdentifyDestroyedActors(const ActorList &actor_list) { + + ALSM::DestroyeddActors destroyed_actors; + ActorIdSet &deleted_registered = destroyed_actors.first; + ActorIdSet &deleted_unregistered = destroyed_actors.second; + + // Building hash set of actors present in current frame. + ActorIdSet current_actors; + for (auto iter = actor_list->begin(); iter != actor_list->end(); ++iter) { + current_actors.insert((*iter)->GetId()); + } + + // Searching for destroyed registered actors. + std::vector registered_ids = registered_vehicles.GetIDList(); + for (const ActorId &actor_id : registered_ids) { + if (current_actors.find(actor_id) == current_actors.end()) { + deleted_registered.insert(actor_id); + } + } + + // Searching for destroyed unregistered actors. + for (const auto &actor_info: unregistered_actors) { + const ActorId &actor_id = actor_info.first; + if (current_actors.find(actor_id) == current_actors.end() + || registered_vehicles.Contains(actor_id)) { + deleted_unregistered.insert(actor_id); + } + } + + return destroyed_actors; +} + +void ALSM::UpdateRegisteredActorsData(const bool hybrid_physics_mode, ALSM::IdleInfo &max_idle_time) { + + std::vector vehicle_list = registered_vehicles.GetList(); + bool hero_actor_present = hero_actors.size() != 0u; + float physics_radius = parameters.GetHybridPhysicsRadius(); + float physics_radius_square = SQUARE(physics_radius); + bool is_respawn_vehicles = parameters.GetRespawnDormantVehicles(); + if (is_respawn_vehicles && !hero_actor_present) { + track_traffic.SetHeroLocation(cg::Location(0,0,0)); + } + // Update first the information regarding any hero vehicle. + for (auto &hero_actor_info: hero_actors){ + if (is_respawn_vehicles) { + track_traffic.SetHeroLocation(hero_actor_info.second->GetTransform().location); + } + UpdateData(hybrid_physics_mode, max_idle_time, hero_actor_info.second, hero_actor_present, physics_radius_square); + } + // Update information for all other registered vehicles. + for (const Actor &vehicle : vehicle_list) { + ActorId actor_id = vehicle->GetId(); + if (hero_actors.find(actor_id) == hero_actors.end()) { + UpdateData(hybrid_physics_mode, max_idle_time, vehicle, hero_actor_present, physics_radius_square); + } + } +} + +void ALSM::UpdateData(const bool hybrid_physics_mode, + ALSM::IdleInfo &max_idle_time, const Actor &vehicle, + const bool hero_actor_present, const float physics_radius_square) { + + ActorId actor_id = vehicle->GetId(); + cg::Transform vehicle_transform = vehicle->GetTransform(); + cg::Location vehicle_location = vehicle_transform.location; + cg::Rotation vehicle_rotation = vehicle_transform.rotation; + cg::Vector3D vehicle_velocity = vehicle->GetVelocity(); + + // Initializing idle times. + if (idle_time.find(actor_id) == idle_time.end() && current_timestamp.elapsed_seconds != 0.0) { + idle_time.insert({actor_id, current_timestamp.elapsed_seconds}); + } + + // Check if current actor is in range of hero actor and enable physics in hybrid mode. + bool in_range_of_hero_actor = false; + if (hero_actor_present && hybrid_physics_mode) { + for (auto &hero_actor_info: hero_actors) { + const ActorId &hero_actor_id = hero_actor_info.first; + if (simulation_state.ContainsActor(hero_actor_id)) { + const cg::Location &hero_location = simulation_state.GetLocation(hero_actor_id); + if (cg::Math::DistanceSquared(vehicle_location, hero_location) < physics_radius_square) { + in_range_of_hero_actor = true; + break; + } + } + } + } + + bool enable_physics = hybrid_physics_mode ? in_range_of_hero_actor : true; + if (!has_physics_enabled.count(actor_id) || has_physics_enabled[actor_id] != enable_physics) { + if (hero_actors.find(actor_id) == hero_actors.end()) { + vehicle->SetSimulatePhysics(enable_physics); + has_physics_enabled[actor_id] = enable_physics; + if (enable_physics == true && simulation_state.ContainsActor(actor_id)) { + vehicle->SetTargetVelocity(simulation_state.GetVelocity(actor_id)); + } + } + } + + bool state_entry_present = simulation_state.ContainsActor(actor_id); + // If physics is disabled, calculate velocity based on change in position. + if (!enable_physics) { + cg::Location previous_location; + if (state_entry_present) { + previous_location = simulation_state.GetLocation(actor_id); + } else { + previous_location = vehicle_location; + } + cg::Vector3D displacement = (vehicle_location - previous_location); + vehicle_velocity = displacement * INV_HYBRID_DT; + } + + // Updated kinematic state object. + auto vehicle_ptr = boost::static_pointer_cast(vehicle); + KinematicState kinematic_state{vehicle_location, vehicle_rotation, + vehicle_velocity, vehicle_ptr->GetSpeedLimit(), + enable_physics, vehicle->IsDormant()}; + + // Updated traffic light state object. + TrafficLightState tl_state = {vehicle_ptr->GetTrafficLightState(), vehicle_ptr->IsAtTrafficLight()}; + + // Update simulation state. + if (state_entry_present) { + simulation_state.UpdateKinematicState(actor_id, kinematic_state); + simulation_state.UpdateTrafficLightState(actor_id, tl_state); + } + else { + cg::Vector3D dimensions = vehicle_ptr->GetBoundingBox().extent; + StaticAttributes attributes{ActorType::Vehicle, dimensions.x, dimensions.y, dimensions.z}; + + simulation_state.AddActor(actor_id, kinematic_state, attributes, tl_state); + } + + // Updating idle time when necessary. + UpdateIdleTime(max_idle_time, actor_id); +} + + +void ALSM::UpdateUnregisteredActorsData() { + for (auto &actor_info: unregistered_actors) { + + const ActorId actor_id = actor_info.first; + const ActorPtr actor_ptr = actor_info.second; + const std::string type_id = actor_ptr->GetTypeId(); + + const cg::Transform actor_transform = actor_ptr->GetTransform(); + const cg::Location actor_location = actor_transform.location; + const cg::Rotation actor_rotation = actor_transform.rotation; + const cg::Vector3D actor_velocity = actor_ptr->GetVelocity(); + const bool actor_is_dormant = actor_ptr->IsDormant(); + KinematicState kinematic_state {actor_location, actor_rotation, actor_velocity, -1.0f, true, actor_is_dormant}; + + TrafficLightState tl_state; + ActorType actor_type = ActorType::Any; + cg::Vector3D dimensions; + std::vector nearest_waypoints; + + bool state_entry_not_present = !simulation_state.ContainsActor(actor_id); + if (type_id.front() == 'v' || type_id.rfind("harplab.dreyevr_vehicle.") == 0) { // include DReyeVR vehicle + auto vehicle_ptr = boost::static_pointer_cast(actor_ptr); + kinematic_state.speed_limit = vehicle_ptr->GetSpeedLimit(); + + tl_state = {vehicle_ptr->GetTrafficLightState(), vehicle_ptr->IsAtTrafficLight()}; + + if (state_entry_not_present) { + dimensions = vehicle_ptr->GetBoundingBox().extent; + actor_type = ActorType::Vehicle; + StaticAttributes attributes {actor_type, dimensions.x, dimensions.y, dimensions.z}; + + simulation_state.AddActor(actor_id, kinematic_state, attributes, tl_state); + } else { + simulation_state.UpdateKinematicState(actor_id, kinematic_state); + simulation_state.UpdateTrafficLightState(actor_id, tl_state); + } + + // Identify occupied waypoints. + cg::Vector3D extent = vehicle_ptr->GetBoundingBox().extent; + cg::Vector3D heading_vector = vehicle_ptr->GetTransform().GetForwardVector(); + std::vector corners = {actor_location + cg::Location(extent.x * heading_vector), + actor_location, + actor_location + cg::Location(-extent.x * heading_vector)}; + for (cg::Location &vertex: corners) { + SimpleWaypointPtr nearest_waypoint = local_map->GetWaypoint(vertex); + nearest_waypoints.push_back(nearest_waypoint); + } + } + else if (type_id.front() == 'w') { + auto walker_ptr = boost::static_pointer_cast(actor_ptr); + + if (state_entry_not_present) { + dimensions = walker_ptr->GetBoundingBox().extent; + actor_type = ActorType::Pedestrian; + StaticAttributes attributes {actor_type, dimensions.x, dimensions.y, dimensions.z}; + + simulation_state.AddActor(actor_id, kinematic_state, attributes, tl_state); + } else { + simulation_state.UpdateKinematicState(actor_id, kinematic_state); + } + + // Identify occupied waypoints. + SimpleWaypointPtr nearest_waypoint = local_map->GetWaypoint(actor_location); + nearest_waypoints.push_back(nearest_waypoint); + } + + track_traffic.UpdateUnregisteredGridPosition(actor_id, nearest_waypoints); + } +} + +void ALSM::UpdateIdleTime(std::pair& max_idle_time, const ActorId& actor_id) { + if (idle_time.find(actor_id) != idle_time.end()) { + double &idle_duration = idle_time.at(actor_id); + if (simulation_state.GetVelocity(actor_id).SquaredLength() > SQUARE(STOPPED_VELOCITY_THRESHOLD)) { + idle_duration = current_timestamp.elapsed_seconds; + } + + // Checking maximum idle time. + if (max_idle_time.first == 0u || max_idle_time.second > idle_duration) { + max_idle_time = std::make_pair(actor_id, idle_duration); + } + } +} + +bool ALSM::IsVehicleStuck(const ActorId& actor_id) { + if (idle_time.find(actor_id) != idle_time.end()) { + double delta_idle_time = current_timestamp.elapsed_seconds - idle_time.at(actor_id); + TrafficLightState tl_state = simulation_state.GetTLS(actor_id); + if ((!tl_state.at_traffic_light && tl_state.tl_state != TLS::Red && delta_idle_time >= BLOCKED_TIME_THRESHOLD) + || (delta_idle_time >= RED_TL_BLOCKED_TIME_THRESHOLD)) { + return true; + } + } + return false; +} + +void ALSM::RemoveActor(const ActorId actor_id, const bool registered_actor) { + if (registered_actor) { + registered_vehicles.Remove({actor_id}); + buffer_map.erase(actor_id); + idle_time.erase(actor_id); + random_devices.erase(actor_id); + localization_stage.RemoveActor(actor_id); + collision_stage.RemoveActor(actor_id); + traffic_light_stage.RemoveActor(actor_id); + motion_plan_stage.RemoveActor(actor_id); + vehicle_light_stage.RemoveActor(actor_id); + } + else { + unregistered_actors.erase(actor_id); + hero_actors.erase(actor_id); + } + + track_traffic.DeleteActor(actor_id); + simulation_state.RemoveActor(actor_id); +} + +void ALSM::Reset() { + unregistered_actors.clear(); + idle_time.clear(); + hero_actors.clear(); + elapsed_last_actor_destruction = 0.0; + current_timestamp = world.GetSnapshot().GetTimestamp(); +} + +} // namespace traffic_manager +} // namespace carla diff --git a/LibCarla/source/test/common/test_streaming.cpp b/LibCarla/source/test/common/test_streaming.cpp index e5183e4..8141f77 100644 --- a/LibCarla/source/test/common/test_streaming.cpp +++ b/LibCarla/source/test/common/test_streaming.cpp @@ -1,261 +1,261 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "test.h" - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -using namespace std::chrono_literals; - -// This is required for low level to properly stop the threads in case of -// exception/assert. -class io_context_running { -public: - - boost::asio::io_context service; - - explicit io_context_running(size_t threads = 2u) - : _work_to_do(service) { - _threads.CreateThreads(threads, [this]() { service.run(); }); - } - - ~io_context_running() { - service.stop(); - } - -private: - - boost::asio::io_context::work _work_to_do; - - carla::ThreadGroup _threads; -}; - -TEST(streaming, low_level_sending_strings) { - using namespace util::buffer; - using namespace carla::streaming; - using namespace carla::streaming::detail; - using namespace carla::streaming::low_level; - - constexpr auto number_of_messages = 100u; - const std::string message_text = "Hello client!"; - - std::atomic_size_t message_count{0u}; - - io_context_running io; - - carla::streaming::low_level::Server srv(io.service, TESTING_PORT); - srv.SetTimeout(1s); - - auto stream = srv.MakeStream(); - - carla::streaming::low_level::Client c; - c.Subscribe(io.service, stream.token(), [&](auto message) { - ++message_count; - ASSERT_EQ(message.size(), message_text.size()); - const std::string msg = as_string(message); - ASSERT_EQ(msg, message_text); - }); - - for (auto i = 0u; i < number_of_messages; ++i) { - std::this_thread::sleep_for(2ms); - stream << message_text; - } - - std::this_thread::sleep_for(2ms); - ASSERT_GE(message_count, number_of_messages - 3u); - - io.service.stop(); -} - -TEST(streaming, low_level_unsubscribing) { - using namespace util::buffer; - using namespace carla::streaming; - using namespace carla::streaming::detail; - using namespace carla::streaming::low_level; - - constexpr auto number_of_messages = 50u; - const std::string message_text = "Hello client!"; - - io_context_running io; - - carla::streaming::low_level::Server srv(io.service, TESTING_PORT); - srv.SetTimeout(1s); - - carla::streaming::low_level::Client c; - for (auto n = 0u; n < 10u; ++n) { - auto stream = srv.MakeStream(); - std::atomic_size_t message_count{0u}; - - c.Subscribe(io.service, stream.token(), [&](auto message) { - ++message_count; - ASSERT_EQ(message.size(), message_text.size()); - const std::string msg = as_string(message); - ASSERT_EQ(msg, message_text); - }); - - for (auto i = 0u; i < number_of_messages; ++i) { - std::this_thread::sleep_for(4ms); - stream << message_text; - } - - std::this_thread::sleep_for(4ms); - c.UnSubscribe(stream.token()); - - for (auto i = 0u; i < number_of_messages; ++i) { - std::this_thread::sleep_for(2ms); - stream << message_text; - } - - ASSERT_GE(message_count, number_of_messages - 3u); - } - - io.service.stop(); -} - -TEST(streaming, low_level_tcp_small_message) { - using namespace carla::streaming; - using namespace carla::streaming::detail; - - boost::asio::io_context io_context; - tcp::Server::endpoint ep(boost::asio::ip::tcp::v4(), TESTING_PORT); - - tcp::Server srv(io_context, ep); - srv.SetTimeout(1s); - std::atomic_bool done{false}; - std::atomic_size_t message_count{0u}; - - const std::string msg = "Hola!"; - - srv.Listen([&](std::shared_ptr session) { - ASSERT_EQ(session->get_stream_id(), 1u); - while (!done) { - session->Write(carla::Buffer(msg)); - std::this_thread::sleep_for(1ns); - } - std::cout << "done!\n"; - }, [](std::shared_ptr) { std::cout << "session closed!\n"; }); - - Dispatcher dispatcher{make_endpoint(srv.GetLocalEndpoint())}; - auto stream = dispatcher.MakeStream(); - auto c = std::make_shared(io_context, stream.token(), [&](carla::Buffer message) { - ++message_count; - ASSERT_FALSE(message.empty()); - ASSERT_EQ(message.size(), 5u); - const std::string received = util::buffer::as_string(message); - ASSERT_EQ(received, msg); - }); - c->Connect(); - - // We need at least two threads because this server loop consumes one. - carla::ThreadGroup threads; - threads.CreateThreads( - std::max(2u, std::thread::hardware_concurrency()), - [&]() { io_context.run(); }); - - std::this_thread::sleep_for(2s); - io_context.stop(); - done = true; - std::cout << "client received " << message_count << " messages\n"; - ASSERT_GT(message_count, 10u); - c->Stop(); -} - -struct DoneGuard { - ~DoneGuard() { done = true; }; - std::atomic_bool &done; -}; - -TEST(streaming, stream_outlives_server) { - using namespace carla::streaming; - using namespace util::buffer; - constexpr size_t iterations = 10u; - std::atomic_bool done{false}; - const std::string message = "Hello client, how are you?"; - std::shared_ptr stream; - - carla::ThreadGroup sender; - DoneGuard g = {done}; - sender.CreateThread([&]() { - while (!done) { - std::this_thread::sleep_for(1ms); - auto s = std::atomic_load_explicit(&stream, std::memory_order_relaxed); - if (s != nullptr) { - (*s) << message; - } - } - }); - - for (auto i = 0u; i < iterations; ++i) { - Server srv(TESTING_PORT); - srv.AsyncRun(2u); - { - auto s = std::make_shared(srv.MakeStream()); - std::atomic_store_explicit(&stream, s, std::memory_order_relaxed); - } - std::atomic_size_t messages_received{0u}; - { - Client c; - c.AsyncRun(2u); - c.Subscribe(stream->token(), [&](auto buffer) { - const std::string result = as_string(buffer); - ASSERT_EQ(result, message); - ++messages_received; - }); - std::this_thread::sleep_for(20ms); - } // client dies here. - ASSERT_GT(messages_received, 0u); - } // server dies here. - std::this_thread::sleep_for(20ms); - done = true; -} // stream dies here. - -TEST(streaming, multi_stream) { - using namespace carla::streaming; - using namespace util::buffer; - constexpr size_t number_of_messages = 100u; - constexpr size_t number_of_clients = 6u; - constexpr size_t iterations = 10u; - const std::string message = "Hi y'all!"; - - Server srv(TESTING_PORT); - srv.AsyncRun(number_of_clients); - auto stream = srv.MakeStream(); - - for (auto i = 0u; i < iterations; ++i) { - std::vector>> v(number_of_clients); - - for (auto &pair : v) { - pair.first = 0u; - pair.second = std::make_unique(); - pair.second->AsyncRun(1u); - pair.second->Subscribe(stream.token(), [&](auto buffer) { - const std::string result = as_string(buffer); - ASSERT_EQ(result, message); - ++pair.first; - }); - } - - std::this_thread::sleep_for(6ms); - for (auto j = 0u; j < number_of_messages; ++j) { - std::this_thread::sleep_for(6ms); - stream << message; - } - std::this_thread::sleep_for(6ms); - - for (auto &pair : v) { - ASSERT_GE(pair.first, number_of_messages - 3u); - } - } -} +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "test.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std::chrono_literals; + +// This is required for low level to properly stop the threads in case of +// exception/assert. +class io_context_running { +public: + + boost::asio::io_context service; + + explicit io_context_running(size_t threads = 2u) + : _work_to_do(service) { + _threads.CreateThreads(threads, [this]() { service.run(); }); + } + + ~io_context_running() { + service.stop(); + } + +private: + + boost::asio::io_context::work _work_to_do; + + carla::ThreadGroup _threads; +}; + +TEST(streaming, low_level_sending_strings) { + using namespace util::buffer; + using namespace carla::streaming; + using namespace carla::streaming::detail; + using namespace carla::streaming::low_level; + + constexpr auto number_of_messages = 100u; + const std::string message_text = "Hello client!"; + + std::atomic_size_t message_count{0u}; + + io_context_running io; + + carla::streaming::low_level::Server srv(io.service, TESTING_PORT); + srv.SetTimeout(1s); + + auto stream = srv.MakeStream(); + + carla::streaming::low_level::Client c; + c.Subscribe(io.service, stream.token(), [&](auto message) { + ++message_count; + ASSERT_EQ(message.size(), message_text.size()); + const std::string msg = as_string(message); + ASSERT_EQ(msg, message_text); + }); + + for (auto i = 0u; i < number_of_messages; ++i) { + std::this_thread::sleep_for(2ms); + stream << message_text; + } + + std::this_thread::sleep_for(2ms); + ASSERT_GE(message_count, number_of_messages - 3u); + + io.service.stop(); +} + +TEST(streaming, low_level_unsubscribing) { + using namespace util::buffer; + using namespace carla::streaming; + using namespace carla::streaming::detail; + using namespace carla::streaming::low_level; + + constexpr auto number_of_messages = 50u; + const std::string message_text = "Hello client!"; + + io_context_running io; + + carla::streaming::low_level::Server srv(io.service, TESTING_PORT); + srv.SetTimeout(1s); + + carla::streaming::low_level::Client c; + for (auto n = 0u; n < 10u; ++n) { + auto stream = srv.MakeStream(); + std::atomic_size_t message_count{0u}; + + c.Subscribe(io.service, stream.token(), [&](auto message) { + ++message_count; + ASSERT_EQ(message.size(), message_text.size()); + const std::string msg = as_string(message); + ASSERT_EQ(msg, message_text); + }); + + for (auto i = 0u; i < number_of_messages; ++i) { + std::this_thread::sleep_for(4ms); + stream << message_text; + } + + std::this_thread::sleep_for(4ms); + c.UnSubscribe(stream.token()); + + for (auto i = 0u; i < number_of_messages; ++i) { + std::this_thread::sleep_for(2ms); + stream << message_text; + } + + ASSERT_GE(message_count, number_of_messages - 3u); + } + + io.service.stop(); +} + +TEST(streaming, low_level_tcp_small_message) { + using namespace carla::streaming; + using namespace carla::streaming::detail; + + boost::asio::io_context io_context; + tcp::Server::endpoint ep(boost::asio::ip::tcp::v4(), TESTING_PORT); + + tcp::Server srv(io_context, ep); + srv.SetTimeout(1s); + std::atomic_bool done{false}; + std::atomic_size_t message_count{0u}; + + const std::string msg = "Hola!"; + + srv.Listen([&](std::shared_ptr session) { + ASSERT_EQ(session->get_stream_id(), 1u); + while (!done) { + session->Write(carla::Buffer(msg)); + std::this_thread::sleep_for(1ns); + } + std::cout << "done!\n"; + }, [](std::shared_ptr) { std::cout << "session closed!\n"; }); + + Dispatcher dispatcher{make_endpoint(srv.GetLocalEndpoint())}; + auto stream = dispatcher.MakeStream(); + auto c = std::make_shared(io_context, stream.token(), [&](carla::Buffer message) { + ++message_count; + ASSERT_FALSE(message.empty()); + ASSERT_EQ(message.size(), 5u); + const std::string received = util::buffer::as_string(message); + ASSERT_EQ(received, msg); + }); + c->Connect(); + + // We need at least two threads because this server loop consumes one. + carla::ThreadGroup threads; + threads.CreateThreads( + std::max(2u, std::thread::hardware_concurrency()), + [&]() { io_context.run(); }); + + std::this_thread::sleep_for(2s); + io_context.stop(); + done = true; + std::cout << "client received " << message_count << " messages\n"; + ASSERT_GT(message_count, 10u); + c->Stop(); +} + +struct DoneGuard { + ~DoneGuard() { done = true; }; + std::atomic_bool &done; +}; + +TEST(streaming, stream_outlives_server) { + using namespace carla::streaming; + using namespace util::buffer; + constexpr size_t iterations = 10u; + std::atomic_bool done{false}; + const std::string message = "Hello client, how are you?"; + std::shared_ptr stream; + + carla::ThreadGroup sender; + DoneGuard g = {done}; + sender.CreateThread([&]() { + while (!done) { + std::this_thread::sleep_for(1ms); + auto s = std::atomic_load_explicit(&stream, std::memory_order_relaxed); + if (s != nullptr) { + (*s) << message; + } + } + }); + + for (auto i = 0u; i < iterations; ++i) { + Server srv(TESTING_PORT); + srv.AsyncRun(2u); + { + auto s = std::make_shared(srv.MakeStream()); + std::atomic_store_explicit(&stream, s, std::memory_order_relaxed); + } + std::atomic_size_t messages_received{0u}; + { + Client c; + c.AsyncRun(2u); + c.Subscribe(stream->token(), [&](auto buffer) { + const std::string result = as_string(buffer); + ASSERT_EQ(result, message); + ++messages_received; + }); + std::this_thread::sleep_for(20ms); + } // client dies here. + ASSERT_GT(messages_received, 0u); + } // server dies here. + std::this_thread::sleep_for(20ms); + done = true; +} // stream dies here. + +TEST(streaming, multi_stream) { + using namespace carla::streaming; + using namespace util::buffer; + constexpr size_t number_of_messages = 100u; + constexpr size_t number_of_clients = 6u; + constexpr size_t iterations = 10u; + const std::string message = "Hi y'all!"; + + Server srv(TESTING_PORT); + srv.AsyncRun(number_of_clients); + auto stream = srv.MakeStream(); + + for (auto i = 0u; i < iterations; ++i) { + std::vector>> v(number_of_clients); + + for (auto &pair : v) { + pair.first = 0u; + pair.second = std::make_unique(); + pair.second->AsyncRun(1u); + pair.second->Subscribe(stream.token(), [&](auto buffer) { + const std::string result = as_string(buffer); + ASSERT_EQ(result, message); + ++pair.first; + }); + } + + std::this_thread::sleep_for(6ms); + for (auto j = 0u; j < number_of_messages; ++j) { + std::this_thread::sleep_for(6ms); + stream << message; + } + std::this_thread::sleep_for(6ms); + + for (auto &pair : v) { + ASSERT_GE(pair.first, number_of_messages - 3u); + } + } +} diff --git a/Makefile b/Makefile index 433fe20..ee6fd20 100644 --- a/Makefile +++ b/Makefile @@ -1,25 +1,25 @@ -default: help - -help: - @less Scripts/DReyeVR.mk.help - -DReyeVR: install - -install: - python Scripts/install.py --carla ${CARLA} --scenario-runner ${SR} - -clean: - python Scripts/clean.py --carla ${CARLA} --scenario-runner ${SR} --verbose - -test: - python Scripts/tests.py - -check: # TODO: make better DReyeVR unit tests! - python Scripts/check_install.py --carla ${CARLA} --scenario-runner ${SR} --verbose - -rev: r-install - -r-install: - python Scripts/r-install.py --carla ${CARLA} --scenario-runner ${SR} - +default: help + +help: + @less Scripts/DReyeVR.mk.help + +DReyeVR: install + +install: + python Scripts/install.py --carla ${CARLA} --scenario-runner ${SR} + +clean: + python Scripts/clean.py --carla ${CARLA} --scenario-runner ${SR} --verbose + +test: + python Scripts/tests.py + +check: # TODO: make better DReyeVR unit tests! + python Scripts/check_install.py --carla ${CARLA} --scenario-runner ${SR} --verbose + +rev: r-install + +r-install: + python Scripts/r-install.py --carla ${CARLA} --scenario-runner ${SR} + all: install check \ No newline at end of file diff --git a/PythonAPI/carla/source/libcarla/SensorData.cpp b/PythonAPI/carla/source/libcarla/SensorData.cpp index 2383247..471389f 100644 --- a/PythonAPI/carla/source/libcarla/SensorData.cpp +++ b/PythonAPI/carla/source/libcarla/SensorData.cpp @@ -1,619 +1,619 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include // DReyeVR sensor event - -#include - -#include - -#include -#include -#include -#include -#include -#include - -namespace carla { -namespace sensor { -namespace data { - - std::ostream &operator<<(std::ostream &out, const Image &image) { - out << "Image(frame=" << std::to_string(image.GetFrame()) - << ", timestamp=" << std::to_string(image.GetTimestamp()) - << ", size=" << std::to_string(image.GetWidth()) << 'x' << std::to_string(image.GetHeight()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const OpticalFlowImage &image) { - out << "OpticalFlowImage(frame=" << std::to_string(image.GetFrame()) - << ", timestamp=" << std::to_string(image.GetTimestamp()) - << ", size=" << std::to_string(image.GetWidth()) << 'x' << std::to_string(image.GetHeight()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const LidarMeasurement &meas) { - out << "LidarMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", number_of_points=" << std::to_string(meas.size()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const SemanticLidarMeasurement &meas) { - out << "SemanticLidarMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", number_of_points=" << std::to_string(meas.size()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const CollisionEvent &meas) { - out << "CollisionEvent(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", other_actor=" << meas.GetOtherActor() - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) { - out << "ObstacleDetectionEvent(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", other_actor=" << meas.GetOtherActor() - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) { - out << "LaneInvasionEvent(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const GnssMeasurement &meas) { - out << "GnssMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", lat=" << std::to_string(meas.GetLatitude()) - << ", lon=" << std::to_string(meas.GetLongitude()) - << ", alt=" << std::to_string(meas.GetAltitude()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const IMUMeasurement &meas) { - out << "IMUMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", accelerometer=" << meas.GetAccelerometer() - << ", gyroscope=" << meas.GetGyroscope() - << ", compass=" << std::to_string(meas.GetCompass()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const RadarMeasurement &meas) { - out << "RadarMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", point_count=" << std::to_string(meas.GetDetectionAmount()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const DVSEvent &event) { - out << "Event(x=" << std::to_string(event.x) - << ", y=" << std::to_string(event.y) - << ", t=" << std::to_string(event.t) - << ", pol=" << std::to_string(event.pol) << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const DVSEventArray &events) { - out << "EventArray(frame=" << std::to_string(events.GetFrame()) - << ", timestamp=" << std::to_string(events.GetTimestamp()) - << ", dimensions=" << std::to_string(events.GetWidth()) << 'x' << std::to_string(events.GetHeight()) - << ", number_of_events=" << std::to_string(events.size()) - << ')'; - return out; - } - - - std::ostream &operator<<(std::ostream &out, const RadarDetection &det) { - out << "RadarDetection(velocity=" << std::to_string(det.velocity) - << ", azimuth=" << std::to_string(det.azimuth) - << ", altitude=" << std::to_string(det.altitude) - << ", depth=" << std::to_string(det.depth) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const LidarDetection &det) { - out << "LidarDetection(x=" << std::to_string(det.point.x) - << ", y=" << std::to_string(det.point.y) - << ", z=" << std::to_string(det.point.z) - << ", intensity=" << std::to_string(det.intensity) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const SemanticLidarDetection &det) { - out << "SemanticLidarDetection(x=" << std::to_string(det.point.x) - << ", y=" << std::to_string(det.point.y) - << ", z=" << std::to_string(det.point.z) - << ", cos_inc_angle=" << std::to_string(det.cos_inc_angle) - << ", object_idx=" << std::to_string(det.object_idx) - << ", object_tag=" << std::to_string(det.object_tag) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const DReyeVREvent &event) { - // what is used when printing the data streamed to the PythonAPI (converting to string) - auto &GazeDir = event.GetGazeDir(); - auto &GazeOrigin = event.GetGazeOrigin(); - auto &CameraLocn = event.GetCameraLocation(); - auto &CameraRotn = event.GetCameraRotation(); - const std::string sep = ", "; - out << "DReyeVR(frame=" << event.GetFrame() << sep - << "t=" << event.GetTimestamp() << sep - << "GazeDir(" << event.GetGazeValid() << ")={" << GazeDir.x << ", " << GazeDir.y << ", " << GazeDir.z<< "}" << sep - << "GazeOrigin={" << GazeOrigin.x << ", " << GazeOrigin.y << ", " << GazeOrigin.z << "}" << sep - << "Vergence=" << event.GetGazeVergence() << sep - << "CameraLoc={" << CameraLocn.x << ", " << CameraLocn.y << ", " << CameraLocn.z<< "}" << sep - << "CameraRot={" << CameraRotn.x << ", " << CameraRotn.y << ", " << CameraRotn.z<< "}" << sep - << ')'; - return out; - } -} // namespace s11n -} // namespace sensor -} // namespace carla - -enum class EColorConverter { - Raw, - Depth, - LogarithmicDepth, - CityScapesPalette -}; - -template -static auto GetRawDataAsBuffer(T &self) { - auto *data = reinterpret_cast(self.data()); - auto size = static_cast(sizeof(typename T::value_type) * self.size()); -#if PY_MAJOR_VERSION >= 3 - auto *ptr = PyMemoryView_FromMemory(reinterpret_cast(data), size, PyBUF_READ); -#else - auto *ptr = PyBuffer_FromMemory(data, size); -#endif - return boost::python::object(boost::python::handle<>(ptr)); -} - -template -static void ConvertImage(T &self, EColorConverter cc) { - carla::PythonUtil::ReleaseGIL unlock; - using namespace carla::image; - auto view = ImageView::MakeView(self); - switch (cc) { - case EColorConverter::Depth: - ImageConverter::ConvertInPlace(view, ColorConverter::Depth()); - break; - case EColorConverter::LogarithmicDepth: - ImageConverter::ConvertInPlace(view, ColorConverter::LogarithmicDepth()); - break; - case EColorConverter::CityScapesPalette: - ImageConverter::ConvertInPlace(view, ColorConverter::CityScapesPalette()); - break; - case EColorConverter::Raw: - break; // ignore. - default: - throw std::invalid_argument("invalid color converter!"); - } -} - -// image object resturned from optical flow to color conversion -class FakeImage : public std::vector { - public: - unsigned int Width = 0; - unsigned int Height = 0; - float FOV = 0; -}; -// method to convert optical flow images to rgb -static FakeImage ColorCodedFlow ( - carla::sensor::data::OpticalFlowImage& image) { - namespace bp = boost::python; - namespace csd = carla::sensor::data; - constexpr float pi = 3.1415f; - constexpr float rad2ang = 360.f/(2.f*pi); - FakeImage result; - result.Width = image.GetWidth(); - result.Height = image.GetHeight(); - result.FOV = image.GetFOVAngle(); - result.resize(image.GetHeight()*image.GetWidth()* 4); - - // lambda for computing batches of pixels - auto command = [&] (size_t min_index, size_t max_index) { - for (size_t index = min_index; index < max_index; index++) { - const csd::OpticalFlowPixel& pixel = image[index]; - float vx = pixel.x; - float vy = pixel.y; - - float angle = 180.f + std::atan2(vy, vx)*rad2ang; - if (angle < 0) angle = 360.f + angle; - angle = std::fmod(angle, 360.f); - - float norm = std::sqrt(vx*vx + vy*vy); - const float shift = 0.999f; - const float a = 1.f/std::log(0.1f + shift); - float intensity = carla::geom::Math::Clamp(a*std::log(norm + shift), 0.f, 1.f); - - float& H = angle; - float S = 1.f; - float V = intensity; - float H_60 = H*(1.f/60.f); - - float C = V * S; - float X = C*(1.f - std::abs(std::fmod(H_60, 2.f) - 1.f)); - float m = V - C; - - float r = 0,g = 0,b = 0; - unsigned int angle_case = static_cast(H_60); - switch (angle_case) { - case 0: - r = C; - g = X; - b = 0; - break; - case 1: - r = X; - g = C; - b = 0; - break; - case 2: - r = 0; - g = C; - b = X; - break; - case 3: - r = 0; - g = X; - b = C; - break; - case 4: - r = X; - g = 0; - b = C; - break; - case 5: - r = C; - g = 0; - b = X; - break; - default: - r = 1; - g = 1; - b = 1; - break; - } - - uint8_t R = static_cast((r+m)*255.f); - uint8_t G = static_cast((g+m)*255.f); - uint8_t B = static_cast((b+m)*255.f); - result[4*index] = B; - result[4*index + 1] = G; - result[4*index + 2] = R; - result[4*index + 3] = 0; - } - }; - size_t num_threads = std::max(8u, std::thread::hardware_concurrency()); - size_t batch_size = image.size() / num_threads; - std::vector t(num_threads+1); - - for(size_t n = 0; n < num_threads; n++) { - t[n] = new std::thread(command, n * batch_size, (n+1) * batch_size); - } - t[num_threads] = new std::thread(command, num_threads * batch_size, image.size()); - - for(size_t n = 0; n <= num_threads; n++) { - if(t[n]->joinable()){ - t[n]->join(); - } - delete t[n]; - } - return result; -} - -template -static std::string SaveImageToDisk(T &self, std::string path, EColorConverter cc) { - carla::PythonUtil::ReleaseGIL unlock; - using namespace carla::image; - auto view = ImageView::MakeView(self); - switch (cc) { - case EColorConverter::Raw: - return ImageIO::WriteView( - std::move(path), - view); - case EColorConverter::Depth: - return ImageIO::WriteView( - std::move(path), - ImageView::MakeColorConvertedView(view, ColorConverter::Depth())); - case EColorConverter::LogarithmicDepth: - return ImageIO::WriteView( - std::move(path), - ImageView::MakeColorConvertedView(view, ColorConverter::LogarithmicDepth())); - case EColorConverter::CityScapesPalette: - return ImageIO::WriteView( - std::move(path), - ImageView::MakeColorConvertedView(view, ColorConverter::CityScapesPalette())); - default: - throw std::invalid_argument("invalid color converter!"); - } -} - -template -static std::string SavePointCloudToDisk(T &self, std::string path) { - carla::PythonUtil::ReleaseGIL unlock; - return carla::pointcloud::PointCloudIO::SaveToDisk(std::move(path), self.begin(), self.end()); -} - -void export_sensor_data() { - using namespace boost::python; - namespace cc = carla::client; - namespace cr = carla::rpc; - namespace cs = carla::sensor; - namespace csd = carla::sensor::data; - namespace css = carla::sensor::s11n; - - // Fake image returned from optical flow to color conversion - // fakes the regular image object. Only used for visual purposes - class_("FakeImage", no_init) - .def(vector_indexing_suite>()) - .add_property("width", &FakeImage::Width) - .add_property("height", &FakeImage::Height) - .add_property("fov", &FakeImage::FOV) - .add_property("raw_data", &GetRawDataAsBuffer); - - class_>("SensorData", no_init) - .add_property("frame", &cs::SensorData::GetFrame) - .add_property("frame_number", &cs::SensorData::GetFrame) // deprecated. - .add_property("timestamp", &cs::SensorData::GetTimestamp) - .add_property("transform", CALL_RETURNING_COPY(cs::SensorData, GetSensorTransform)) - ; - - enum_("ColorConverter") - .value("Raw", EColorConverter::Raw) - .value("Depth", EColorConverter::Depth) - .value("LogarithmicDepth", EColorConverter::LogarithmicDepth) - .value("CityScapesPalette", EColorConverter::CityScapesPalette) - ; - - class_, boost::noncopyable, boost::shared_ptr>("Image", no_init) - .add_property("width", &csd::Image::GetWidth) - .add_property("height", &csd::Image::GetHeight) - .add_property("fov", &csd::Image::GetFOVAngle) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("convert", &ConvertImage, (arg("color_converter"))) - .def("save_to_disk", &SaveImageToDisk, (arg("path"), arg("color_converter")=EColorConverter::Raw)) - .def("__len__", &csd::Image::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::Image &self, size_t pos) -> csd::Color { - return self.at(pos); - }) - .def("__setitem__", +[](csd::Image &self, size_t pos, csd::Color color) { - self.at(pos) = color; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("OpticalFlowImage", no_init) - .add_property("width", &csd::OpticalFlowImage::GetWidth) - .add_property("height", &csd::OpticalFlowImage::GetHeight) - .add_property("fov", &csd::OpticalFlowImage::GetFOVAngle) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_color_coded_flow", &ColorCodedFlow) - .def("__len__", &csd::OpticalFlowImage::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::OpticalFlowImage &self, size_t pos) -> csd::OpticalFlowPixel { - return self.at(pos); - }) - .def("__setitem__", +[](csd::OpticalFlowImage &self, size_t pos, csd::OpticalFlowPixel color) { - self.at(pos) = color; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("LidarMeasurement", no_init) - .add_property("horizontal_angle", &csd::LidarMeasurement::GetHorizontalAngle) - .add_property("channels", &csd::LidarMeasurement::GetChannelCount) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_point_count", &csd::LidarMeasurement::GetPointCount, (arg("channel"))) - .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) - .def("__len__", &csd::LidarMeasurement::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::LidarMeasurement &self, size_t pos) -> csd::LidarDetection { - return self.at(pos); - }) - .def("__setitem__", +[](csd::LidarMeasurement &self, size_t pos, const csd::LidarDetection &detection) { - self.at(pos) = detection; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("SemanticLidarMeasurement", no_init) - .add_property("horizontal_angle", &csd::SemanticLidarMeasurement::GetHorizontalAngle) - .add_property("channels", &csd::SemanticLidarMeasurement::GetChannelCount) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_point_count", &csd::SemanticLidarMeasurement::GetPointCount, (arg("channel"))) - .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) - .def("__len__", &csd::SemanticLidarMeasurement::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::SemanticLidarMeasurement &self, size_t pos) -> csd::SemanticLidarDetection { - return self.at(pos); - }) - .def("__setitem__", +[](csd::SemanticLidarMeasurement &self, size_t pos, const csd::SemanticLidarDetection &detection) { - self.at(pos) = detection; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("CollisionEvent", no_init) - .add_property("actor", &csd::CollisionEvent::GetActor) - .add_property("other_actor", &csd::CollisionEvent::GetOtherActor) - .add_property("normal_impulse", CALL_RETURNING_COPY(csd::CollisionEvent, GetNormalImpulse)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("ObstacleDetectionEvent", no_init) - .add_property("actor", &csd::ObstacleDetectionEvent::GetActor) - .add_property("other_actor", &csd::ObstacleDetectionEvent::GetOtherActor) - .add_property("distance", CALL_RETURNING_COPY(csd::ObstacleDetectionEvent, GetDistance)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("LaneInvasionEvent", no_init) - .add_property("actor", &csd::LaneInvasionEvent::GetActor) - .add_property("crossed_lane_markings", CALL_RETURNING_LIST(csd::LaneInvasionEvent, GetCrossedLaneMarkings)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("GnssMeasurement", no_init) - .add_property("latitude", &csd::GnssMeasurement::GetLatitude) - .add_property("longitude", &csd::GnssMeasurement::GetLongitude) - .add_property("altitude", &csd::GnssMeasurement::GetAltitude) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("IMUMeasurement", no_init) - .add_property("accelerometer", &csd::IMUMeasurement::GetAccelerometer) - .add_property("gyroscope", &csd::IMUMeasurement::GetGyroscope) - .add_property("compass", &csd::IMUMeasurement::GetCompass) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("RadarMeasurement", no_init) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_detection_count", &csd::RadarMeasurement::GetDetectionAmount) - .def("__len__", &csd::RadarMeasurement::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::RadarMeasurement &self, size_t pos) -> csd::RadarDetection { - return self.at(pos); - }) - .def("__setitem__", +[](csd::RadarMeasurement &self, size_t pos, const csd::RadarDetection &detection) { - self.at(pos) = detection; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_("RadarDetection") - .def_readwrite("velocity", &csd::RadarDetection::velocity) - .def_readwrite("azimuth", &csd::RadarDetection::azimuth) - .def_readwrite("altitude", &csd::RadarDetection::altitude) - .def_readwrite("depth", &csd::RadarDetection::depth) - .def(self_ns::str(self_ns::self)) - ; - - class_("LidarDetection") - .def_readwrite("point", &csd::LidarDetection::point) - .def_readwrite("intensity", &csd::LidarDetection::intensity) - .def(self_ns::str(self_ns::self)) - ; - - class_("SemanticLidarDetection") - .def_readwrite("point", &csd::SemanticLidarDetection::point) - .def_readwrite("cos_inc_angle", &csd::SemanticLidarDetection::cos_inc_angle) - .def_readwrite("object_idx", &csd::SemanticLidarDetection::object_idx) - .def_readwrite("object_tag", &csd::SemanticLidarDetection::object_tag) - .def(self_ns::str(self_ns::self)) - ; - - class_("DVSEvent") - .add_property("x", &csd::DVSEvent::x) - .add_property("y", &csd::DVSEvent::y) - .add_property("t", &csd::DVSEvent::t) - .add_property("pol", &csd::DVSEvent::pol) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("DVSEventArray", no_init) - .add_property("width", &csd::DVSEventArray::GetWidth) - .add_property("height", &csd::DVSEventArray::GetHeight) - .add_property("fov", &csd::DVSEventArray::GetFOVAngle) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("__len__", &csd::DVSEventArray::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::DVSEventArray &self, size_t pos) -> csd::DVSEvent { - return self.at(pos); - }) - .def("__setitem__", +[](csd::DVSEventArray &self, size_t pos, csd::DVSEvent event) { - self.at(pos) = event; - }) - .def("to_image", CALL_RETURNING_LIST(csd::DVSEventArray, ToImage)) - .def("to_array", CALL_RETURNING_LIST(csd::DVSEventArray, ToArray)) - .def("to_array_x", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayX)) - .def("to_array_y", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayY)) - .def("to_array_t", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayT)) - .def("to_array_pol", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayPol)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("DReyeVREvent", no_init) - .add_property("timestamp_carla", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestampCarla)) - .add_property("timestamp_device", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestampDevice)) - .add_property("framesequence", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFrameSequence)) - .add_property("timestamp_stream", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestamp)) // Stream timestamp - .add_property("camera_location", CALL_RETURNING_COPY(csd::DReyeVREvent, GetCameraLocation)) - .add_property("camera_rotation", CALL_RETURNING_COPY(csd::DReyeVREvent, GetCameraRotation)) - // combined gaze attributes - .add_property("gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeDir)) - .add_property("gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeOrigin)) - .add_property("gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeValid)) - .add_property("gaze_vergence", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeVergence)) - // left gaze attributes - .add_property("left_gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeDir)) - .add_property("left_gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeOrigin)) - .add_property("left_gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeValid)) - .add_property("left_eye_openness", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLEyeOpenness)) - .add_property("left_eye_openness_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLEyeOpenValid)) - .add_property("left_pupil_posn", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilPos)) - .add_property("left_pupil_posn_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilPosValid)) - .add_property("left_pupil_diam", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilDiam)) - // right gaze attributes - .add_property("right_gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeDir)) - .add_property("right_gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeOrigin)) - .add_property("right_gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeValid)) - .add_property("right_eye_openness", CALL_RETURNING_COPY(csd::DReyeVREvent, GetREyeOpenness)) - .add_property("right_eye_openness_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetREyeOpenValid)) - .add_property("right_pupil_posn", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilPos)) - .add_property("right_pupil_posn_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilPosValid)) - .add_property("right_pupil_diam", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilDiam)) - // focus info attributes - .add_property("focus_actor_name", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorName)) - .add_property("focus_actor_pt", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorPoint)) - .add_property("focus_actor_dist", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorDist)) - // user inputs attributes - .add_property("throttle_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetThrottle)) - .add_property("steering_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetSteering)) - .add_property("brake_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetBrake)) - .add_property("current_gear_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetToggledReverse)) - .add_property("handbrake_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetHandbrake)) - .def(self_ns::str(self_ns::self)) - ; -} +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // DReyeVR sensor event + +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace carla { +namespace sensor { +namespace data { + + std::ostream &operator<<(std::ostream &out, const Image &image) { + out << "Image(frame=" << std::to_string(image.GetFrame()) + << ", timestamp=" << std::to_string(image.GetTimestamp()) + << ", size=" << std::to_string(image.GetWidth()) << 'x' << std::to_string(image.GetHeight()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const OpticalFlowImage &image) { + out << "OpticalFlowImage(frame=" << std::to_string(image.GetFrame()) + << ", timestamp=" << std::to_string(image.GetTimestamp()) + << ", size=" << std::to_string(image.GetWidth()) << 'x' << std::to_string(image.GetHeight()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const LidarMeasurement &meas) { + out << "LidarMeasurement(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ", number_of_points=" << std::to_string(meas.size()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const SemanticLidarMeasurement &meas) { + out << "SemanticLidarMeasurement(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ", number_of_points=" << std::to_string(meas.size()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const CollisionEvent &meas) { + out << "CollisionEvent(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ", other_actor=" << meas.GetOtherActor() + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) { + out << "ObstacleDetectionEvent(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ", other_actor=" << meas.GetOtherActor() + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) { + out << "LaneInvasionEvent(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const GnssMeasurement &meas) { + out << "GnssMeasurement(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ", lat=" << std::to_string(meas.GetLatitude()) + << ", lon=" << std::to_string(meas.GetLongitude()) + << ", alt=" << std::to_string(meas.GetAltitude()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const IMUMeasurement &meas) { + out << "IMUMeasurement(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ", accelerometer=" << meas.GetAccelerometer() + << ", gyroscope=" << meas.GetGyroscope() + << ", compass=" << std::to_string(meas.GetCompass()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const RadarMeasurement &meas) { + out << "RadarMeasurement(frame=" << std::to_string(meas.GetFrame()) + << ", timestamp=" << std::to_string(meas.GetTimestamp()) + << ", point_count=" << std::to_string(meas.GetDetectionAmount()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const DVSEvent &event) { + out << "Event(x=" << std::to_string(event.x) + << ", y=" << std::to_string(event.y) + << ", t=" << std::to_string(event.t) + << ", pol=" << std::to_string(event.pol) << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const DVSEventArray &events) { + out << "EventArray(frame=" << std::to_string(events.GetFrame()) + << ", timestamp=" << std::to_string(events.GetTimestamp()) + << ", dimensions=" << std::to_string(events.GetWidth()) << 'x' << std::to_string(events.GetHeight()) + << ", number_of_events=" << std::to_string(events.size()) + << ')'; + return out; + } + + + std::ostream &operator<<(std::ostream &out, const RadarDetection &det) { + out << "RadarDetection(velocity=" << std::to_string(det.velocity) + << ", azimuth=" << std::to_string(det.azimuth) + << ", altitude=" << std::to_string(det.altitude) + << ", depth=" << std::to_string(det.depth) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const LidarDetection &det) { + out << "LidarDetection(x=" << std::to_string(det.point.x) + << ", y=" << std::to_string(det.point.y) + << ", z=" << std::to_string(det.point.z) + << ", intensity=" << std::to_string(det.intensity) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const SemanticLidarDetection &det) { + out << "SemanticLidarDetection(x=" << std::to_string(det.point.x) + << ", y=" << std::to_string(det.point.y) + << ", z=" << std::to_string(det.point.z) + << ", cos_inc_angle=" << std::to_string(det.cos_inc_angle) + << ", object_idx=" << std::to_string(det.object_idx) + << ", object_tag=" << std::to_string(det.object_tag) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const DReyeVREvent &event) { + // what is used when printing the data streamed to the PythonAPI (converting to string) + auto &GazeDir = event.GetGazeDir(); + auto &GazeOrigin = event.GetGazeOrigin(); + auto &CameraLocn = event.GetCameraLocation(); + auto &CameraRotn = event.GetCameraRotation(); + const std::string sep = ", "; + out << "DReyeVR(frame=" << event.GetFrame() << sep + << "t=" << event.GetTimestamp() << sep + << "GazeDir(" << event.GetGazeValid() << ")={" << GazeDir.x << ", " << GazeDir.y << ", " << GazeDir.z<< "}" << sep + << "GazeOrigin={" << GazeOrigin.x << ", " << GazeOrigin.y << ", " << GazeOrigin.z << "}" << sep + << "Vergence=" << event.GetGazeVergence() << sep + << "CameraLoc={" << CameraLocn.x << ", " << CameraLocn.y << ", " << CameraLocn.z<< "}" << sep + << "CameraRot={" << CameraRotn.x << ", " << CameraRotn.y << ", " << CameraRotn.z<< "}" << sep + << ')'; + return out; + } +} // namespace s11n +} // namespace sensor +} // namespace carla + +enum class EColorConverter { + Raw, + Depth, + LogarithmicDepth, + CityScapesPalette +}; + +template +static auto GetRawDataAsBuffer(T &self) { + auto *data = reinterpret_cast(self.data()); + auto size = static_cast(sizeof(typename T::value_type) * self.size()); +#if PY_MAJOR_VERSION >= 3 + auto *ptr = PyMemoryView_FromMemory(reinterpret_cast(data), size, PyBUF_READ); +#else + auto *ptr = PyBuffer_FromMemory(data, size); +#endif + return boost::python::object(boost::python::handle<>(ptr)); +} + +template +static void ConvertImage(T &self, EColorConverter cc) { + carla::PythonUtil::ReleaseGIL unlock; + using namespace carla::image; + auto view = ImageView::MakeView(self); + switch (cc) { + case EColorConverter::Depth: + ImageConverter::ConvertInPlace(view, ColorConverter::Depth()); + break; + case EColorConverter::LogarithmicDepth: + ImageConverter::ConvertInPlace(view, ColorConverter::LogarithmicDepth()); + break; + case EColorConverter::CityScapesPalette: + ImageConverter::ConvertInPlace(view, ColorConverter::CityScapesPalette()); + break; + case EColorConverter::Raw: + break; // ignore. + default: + throw std::invalid_argument("invalid color converter!"); + } +} + +// image object resturned from optical flow to color conversion +class FakeImage : public std::vector { + public: + unsigned int Width = 0; + unsigned int Height = 0; + float FOV = 0; +}; +// method to convert optical flow images to rgb +static FakeImage ColorCodedFlow ( + carla::sensor::data::OpticalFlowImage& image) { + namespace bp = boost::python; + namespace csd = carla::sensor::data; + constexpr float pi = 3.1415f; + constexpr float rad2ang = 360.f/(2.f*pi); + FakeImage result; + result.Width = image.GetWidth(); + result.Height = image.GetHeight(); + result.FOV = image.GetFOVAngle(); + result.resize(image.GetHeight()*image.GetWidth()* 4); + + // lambda for computing batches of pixels + auto command = [&] (size_t min_index, size_t max_index) { + for (size_t index = min_index; index < max_index; index++) { + const csd::OpticalFlowPixel& pixel = image[index]; + float vx = pixel.x; + float vy = pixel.y; + + float angle = 180.f + std::atan2(vy, vx)*rad2ang; + if (angle < 0) angle = 360.f + angle; + angle = std::fmod(angle, 360.f); + + float norm = std::sqrt(vx*vx + vy*vy); + const float shift = 0.999f; + const float a = 1.f/std::log(0.1f + shift); + float intensity = carla::geom::Math::Clamp(a*std::log(norm + shift), 0.f, 1.f); + + float& H = angle; + float S = 1.f; + float V = intensity; + float H_60 = H*(1.f/60.f); + + float C = V * S; + float X = C*(1.f - std::abs(std::fmod(H_60, 2.f) - 1.f)); + float m = V - C; + + float r = 0,g = 0,b = 0; + unsigned int angle_case = static_cast(H_60); + switch (angle_case) { + case 0: + r = C; + g = X; + b = 0; + break; + case 1: + r = X; + g = C; + b = 0; + break; + case 2: + r = 0; + g = C; + b = X; + break; + case 3: + r = 0; + g = X; + b = C; + break; + case 4: + r = X; + g = 0; + b = C; + break; + case 5: + r = C; + g = 0; + b = X; + break; + default: + r = 1; + g = 1; + b = 1; + break; + } + + uint8_t R = static_cast((r+m)*255.f); + uint8_t G = static_cast((g+m)*255.f); + uint8_t B = static_cast((b+m)*255.f); + result[4*index] = B; + result[4*index + 1] = G; + result[4*index + 2] = R; + result[4*index + 3] = 0; + } + }; + size_t num_threads = std::max(8u, std::thread::hardware_concurrency()); + size_t batch_size = image.size() / num_threads; + std::vector t(num_threads+1); + + for(size_t n = 0; n < num_threads; n++) { + t[n] = new std::thread(command, n * batch_size, (n+1) * batch_size); + } + t[num_threads] = new std::thread(command, num_threads * batch_size, image.size()); + + for(size_t n = 0; n <= num_threads; n++) { + if(t[n]->joinable()){ + t[n]->join(); + } + delete t[n]; + } + return result; +} + +template +static std::string SaveImageToDisk(T &self, std::string path, EColorConverter cc) { + carla::PythonUtil::ReleaseGIL unlock; + using namespace carla::image; + auto view = ImageView::MakeView(self); + switch (cc) { + case EColorConverter::Raw: + return ImageIO::WriteView( + std::move(path), + view); + case EColorConverter::Depth: + return ImageIO::WriteView( + std::move(path), + ImageView::MakeColorConvertedView(view, ColorConverter::Depth())); + case EColorConverter::LogarithmicDepth: + return ImageIO::WriteView( + std::move(path), + ImageView::MakeColorConvertedView(view, ColorConverter::LogarithmicDepth())); + case EColorConverter::CityScapesPalette: + return ImageIO::WriteView( + std::move(path), + ImageView::MakeColorConvertedView(view, ColorConverter::CityScapesPalette())); + default: + throw std::invalid_argument("invalid color converter!"); + } +} + +template +static std::string SavePointCloudToDisk(T &self, std::string path) { + carla::PythonUtil::ReleaseGIL unlock; + return carla::pointcloud::PointCloudIO::SaveToDisk(std::move(path), self.begin(), self.end()); +} + +void export_sensor_data() { + using namespace boost::python; + namespace cc = carla::client; + namespace cr = carla::rpc; + namespace cs = carla::sensor; + namespace csd = carla::sensor::data; + namespace css = carla::sensor::s11n; + + // Fake image returned from optical flow to color conversion + // fakes the regular image object. Only used for visual purposes + class_("FakeImage", no_init) + .def(vector_indexing_suite>()) + .add_property("width", &FakeImage::Width) + .add_property("height", &FakeImage::Height) + .add_property("fov", &FakeImage::FOV) + .add_property("raw_data", &GetRawDataAsBuffer); + + class_>("SensorData", no_init) + .add_property("frame", &cs::SensorData::GetFrame) + .add_property("frame_number", &cs::SensorData::GetFrame) // deprecated. + .add_property("timestamp", &cs::SensorData::GetTimestamp) + .add_property("transform", CALL_RETURNING_COPY(cs::SensorData, GetSensorTransform)) + ; + + enum_("ColorConverter") + .value("Raw", EColorConverter::Raw) + .value("Depth", EColorConverter::Depth) + .value("LogarithmicDepth", EColorConverter::LogarithmicDepth) + .value("CityScapesPalette", EColorConverter::CityScapesPalette) + ; + + class_, boost::noncopyable, boost::shared_ptr>("Image", no_init) + .add_property("width", &csd::Image::GetWidth) + .add_property("height", &csd::Image::GetHeight) + .add_property("fov", &csd::Image::GetFOVAngle) + .add_property("raw_data", &GetRawDataAsBuffer) + .def("convert", &ConvertImage, (arg("color_converter"))) + .def("save_to_disk", &SaveImageToDisk, (arg("path"), arg("color_converter")=EColorConverter::Raw)) + .def("__len__", &csd::Image::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::Image &self, size_t pos) -> csd::Color { + return self.at(pos); + }) + .def("__setitem__", +[](csd::Image &self, size_t pos, csd::Color color) { + self.at(pos) = color; + }) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("OpticalFlowImage", no_init) + .add_property("width", &csd::OpticalFlowImage::GetWidth) + .add_property("height", &csd::OpticalFlowImage::GetHeight) + .add_property("fov", &csd::OpticalFlowImage::GetFOVAngle) + .add_property("raw_data", &GetRawDataAsBuffer) + .def("get_color_coded_flow", &ColorCodedFlow) + .def("__len__", &csd::OpticalFlowImage::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::OpticalFlowImage &self, size_t pos) -> csd::OpticalFlowPixel { + return self.at(pos); + }) + .def("__setitem__", +[](csd::OpticalFlowImage &self, size_t pos, csd::OpticalFlowPixel color) { + self.at(pos) = color; + }) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("LidarMeasurement", no_init) + .add_property("horizontal_angle", &csd::LidarMeasurement::GetHorizontalAngle) + .add_property("channels", &csd::LidarMeasurement::GetChannelCount) + .add_property("raw_data", &GetRawDataAsBuffer) + .def("get_point_count", &csd::LidarMeasurement::GetPointCount, (arg("channel"))) + .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) + .def("__len__", &csd::LidarMeasurement::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::LidarMeasurement &self, size_t pos) -> csd::LidarDetection { + return self.at(pos); + }) + .def("__setitem__", +[](csd::LidarMeasurement &self, size_t pos, const csd::LidarDetection &detection) { + self.at(pos) = detection; + }) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("SemanticLidarMeasurement", no_init) + .add_property("horizontal_angle", &csd::SemanticLidarMeasurement::GetHorizontalAngle) + .add_property("channels", &csd::SemanticLidarMeasurement::GetChannelCount) + .add_property("raw_data", &GetRawDataAsBuffer) + .def("get_point_count", &csd::SemanticLidarMeasurement::GetPointCount, (arg("channel"))) + .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) + .def("__len__", &csd::SemanticLidarMeasurement::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::SemanticLidarMeasurement &self, size_t pos) -> csd::SemanticLidarDetection { + return self.at(pos); + }) + .def("__setitem__", +[](csd::SemanticLidarMeasurement &self, size_t pos, const csd::SemanticLidarDetection &detection) { + self.at(pos) = detection; + }) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("CollisionEvent", no_init) + .add_property("actor", &csd::CollisionEvent::GetActor) + .add_property("other_actor", &csd::CollisionEvent::GetOtherActor) + .add_property("normal_impulse", CALL_RETURNING_COPY(csd::CollisionEvent, GetNormalImpulse)) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("ObstacleDetectionEvent", no_init) + .add_property("actor", &csd::ObstacleDetectionEvent::GetActor) + .add_property("other_actor", &csd::ObstacleDetectionEvent::GetOtherActor) + .add_property("distance", CALL_RETURNING_COPY(csd::ObstacleDetectionEvent, GetDistance)) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("LaneInvasionEvent", no_init) + .add_property("actor", &csd::LaneInvasionEvent::GetActor) + .add_property("crossed_lane_markings", CALL_RETURNING_LIST(csd::LaneInvasionEvent, GetCrossedLaneMarkings)) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("GnssMeasurement", no_init) + .add_property("latitude", &csd::GnssMeasurement::GetLatitude) + .add_property("longitude", &csd::GnssMeasurement::GetLongitude) + .add_property("altitude", &csd::GnssMeasurement::GetAltitude) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("IMUMeasurement", no_init) + .add_property("accelerometer", &csd::IMUMeasurement::GetAccelerometer) + .add_property("gyroscope", &csd::IMUMeasurement::GetGyroscope) + .add_property("compass", &csd::IMUMeasurement::GetCompass) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("RadarMeasurement", no_init) + .add_property("raw_data", &GetRawDataAsBuffer) + .def("get_detection_count", &csd::RadarMeasurement::GetDetectionAmount) + .def("__len__", &csd::RadarMeasurement::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::RadarMeasurement &self, size_t pos) -> csd::RadarDetection { + return self.at(pos); + }) + .def("__setitem__", +[](csd::RadarMeasurement &self, size_t pos, const csd::RadarDetection &detection) { + self.at(pos) = detection; + }) + .def(self_ns::str(self_ns::self)) + ; + + class_("RadarDetection") + .def_readwrite("velocity", &csd::RadarDetection::velocity) + .def_readwrite("azimuth", &csd::RadarDetection::azimuth) + .def_readwrite("altitude", &csd::RadarDetection::altitude) + .def_readwrite("depth", &csd::RadarDetection::depth) + .def(self_ns::str(self_ns::self)) + ; + + class_("LidarDetection") + .def_readwrite("point", &csd::LidarDetection::point) + .def_readwrite("intensity", &csd::LidarDetection::intensity) + .def(self_ns::str(self_ns::self)) + ; + + class_("SemanticLidarDetection") + .def_readwrite("point", &csd::SemanticLidarDetection::point) + .def_readwrite("cos_inc_angle", &csd::SemanticLidarDetection::cos_inc_angle) + .def_readwrite("object_idx", &csd::SemanticLidarDetection::object_idx) + .def_readwrite("object_tag", &csd::SemanticLidarDetection::object_tag) + .def(self_ns::str(self_ns::self)) + ; + + class_("DVSEvent") + .add_property("x", &csd::DVSEvent::x) + .add_property("y", &csd::DVSEvent::y) + .add_property("t", &csd::DVSEvent::t) + .add_property("pol", &csd::DVSEvent::pol) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("DVSEventArray", no_init) + .add_property("width", &csd::DVSEventArray::GetWidth) + .add_property("height", &csd::DVSEventArray::GetHeight) + .add_property("fov", &csd::DVSEventArray::GetFOVAngle) + .add_property("raw_data", &GetRawDataAsBuffer) + .def("__len__", &csd::DVSEventArray::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::DVSEventArray &self, size_t pos) -> csd::DVSEvent { + return self.at(pos); + }) + .def("__setitem__", +[](csd::DVSEventArray &self, size_t pos, csd::DVSEvent event) { + self.at(pos) = event; + }) + .def("to_image", CALL_RETURNING_LIST(csd::DVSEventArray, ToImage)) + .def("to_array", CALL_RETURNING_LIST(csd::DVSEventArray, ToArray)) + .def("to_array_x", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayX)) + .def("to_array_y", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayY)) + .def("to_array_t", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayT)) + .def("to_array_pol", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayPol)) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("DReyeVREvent", no_init) + .add_property("timestamp_carla", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestampCarla)) + .add_property("timestamp_device", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestampDevice)) + .add_property("framesequence", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFrameSequence)) + .add_property("timestamp_stream", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestamp)) // Stream timestamp + .add_property("camera_location", CALL_RETURNING_COPY(csd::DReyeVREvent, GetCameraLocation)) + .add_property("camera_rotation", CALL_RETURNING_COPY(csd::DReyeVREvent, GetCameraRotation)) + // combined gaze attributes + .add_property("gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeDir)) + .add_property("gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeOrigin)) + .add_property("gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeValid)) + .add_property("gaze_vergence", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeVergence)) + // left gaze attributes + .add_property("left_gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeDir)) + .add_property("left_gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeOrigin)) + .add_property("left_gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeValid)) + .add_property("left_eye_openness", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLEyeOpenness)) + .add_property("left_eye_openness_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLEyeOpenValid)) + .add_property("left_pupil_posn", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilPos)) + .add_property("left_pupil_posn_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilPosValid)) + .add_property("left_pupil_diam", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilDiam)) + // right gaze attributes + .add_property("right_gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeDir)) + .add_property("right_gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeOrigin)) + .add_property("right_gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeValid)) + .add_property("right_eye_openness", CALL_RETURNING_COPY(csd::DReyeVREvent, GetREyeOpenness)) + .add_property("right_eye_openness_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetREyeOpenValid)) + .add_property("right_pupil_posn", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilPos)) + .add_property("right_pupil_posn_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilPosValid)) + .add_property("right_pupil_diam", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilDiam)) + // focus info attributes + .add_property("focus_actor_name", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorName)) + .add_property("focus_actor_pt", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorPoint)) + .add_property("focus_actor_dist", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorDist)) + // user inputs attributes + .add_property("throttle_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetThrottle)) + .add_property("steering_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetSteering)) + .add_property("brake_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetBrake)) + .add_property("current_gear_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetToggledReverse)) + .add_property("handbrake_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetHandbrake)) + .def(self_ns::str(self_ns::self)) + ; +} diff --git a/PythonAPI/data/path_logs/log1.txt b/PythonAPI/data/path_logs/log1.txt new file mode 100644 index 0000000..67c2b7b --- /dev/null +++ b/PythonAPI/data/path_logs/log1.txt @@ -0,0 +1,137 @@ +1.155076026916504,-18.188518524169922,49.95619201660156,2.9905172831675326e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.8036320559964814e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0614421138934214e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.103770656318439e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,1.212135167857618e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9202783300510886e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0716718098012236e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.122502807329866e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.004012927417798e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.928276199625688e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.991036879227926e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0902374014715124e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.447486471483175e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9886274981578425e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.8024360610945063e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.983734572258911e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.320370630847926e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9766666436029037e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.7476766934410785e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9883684528858427e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.886401681755551e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1835312437319873e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.107233253609904e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.196973055042809e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.919496117122324e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.96374751966606e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.129023293852463e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1304135225800315e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0946129733468464e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.303579761041933e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.280022998828408e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.3516767309767905e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.148092160691779e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.8392088195546183e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1707601150153584e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.8708436899620466e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1777000860161014e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.846520700827878e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.2646869339741084e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.346153400893746e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.3301994282962256e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1123652156992072e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1603438222992457e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.974580378539704e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.915325576245055e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.328031725623153e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.057087836109485e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.983021754569918e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.91520942465028e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.712505710071782e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0496671832943705e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0994504415580772e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0844868677688977e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.2828562095976938e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1125862316815703e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.597696797910837e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.935289611969478e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9338527615194193e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.661064173146706e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9595075609672694e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.959575156127526e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.010228919889934e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1653904345025053e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0076881568247774e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.210381331697721e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1687558441723356e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.057460794261362e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1057212674351767e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0844048535676326e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0856220897966e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9930066824432353e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0739790408368456e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9516032011810396e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0365715840081676e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.039716472899712e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.931246190633721e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.5527936019323563e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.6255452721962975e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.868470920908648e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9615844596400535e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1144084854987304e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.035110927030659e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0764256336799676e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1247674601779674e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1565453152008645e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.067085088567947e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.021634664292639e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.036348972482784e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1344164438061437e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.9344637922761505e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.794366810367249e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.906181861212086e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.058548918115935e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0004465005594524e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.357136564515894e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.438651294881671e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,1.3252640655755017e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.2440190784767984e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1039271348840098e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.0461048449194828e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.2299081961312557e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.137283588462078e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.8913371601842067e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.872063619514777e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1504526164163372e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.171655442700716e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.3629338148087005e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,2.672441260677635e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.1494186141348183e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.043772199007625e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.369060782372325e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.845735375648266e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.4916294159836147e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,4.237472176079572e-06 +1.155076026916504,-18.188518524169922,49.95619201660156,3.163284324287788e-06 +1.1533966064453125,-18.191463470458984,49.92850875854492,0.023815881561707608 +1.143597960472107,-18.20855140686035,49.77822494506836,0.042807139932988035 +1.021026611328125,-18.413665771484375,48.027565002441406,0.4385254558565315 +0.7905785441398621,-18.764747619628906,44.950157165527344,0.40446120239813776 +0.503892183303833,-19.150978088378906,41.442447662353516,0.43267252637627795 +0.23111814260482788,-19.47739601135254,38.36570739746094,0.4767363462362568 +-0.1578654795885086,-19.887664794921875,34.278377532958984,0.6375630765586165 +-0.673306941986084,-20.352991104125977,29.189231872558594,0.646395181687787 +-1.231654167175293,-20.77328872680664,24.100399017333984,0.6334177318553972 +-1.802610158920288,-21.129812240600586,19.135393142700195,0.5987883307204707 +-2.394656181335449,-21.43246078491211,14.196869850158691,0.5695939132054688 +-3.122493028640747,-21.723705291748047,8.445655822753906,0.6676693758965924 +-3.790029287338257,-21.91963005065918,3.2494325637817383,0.7091613409187916 +-4.4794793128967285,-22.055328369140625,-1.9707642793655396,0.6754227793805486 +-5.060588359832764,-22.121173858642578,-6.374823093414307,0.4260516780188948 +-5.442233562469482,-22.137847900390625,-9.16969108581543,0.3361543571750928 +-6.1081461906433105,-22.124263763427734,-14.14915943145752,0.6701785279775757 +-6.683298587799072,-22.063671112060547,-18.373817443847656,0.4359113497986297 +-6.869481086730957,-22.035261154174805,-19.772003173828125,1.1950509542295682e-05 +-6.869500637054443,-22.03526496887207,-19.77199935913086,3.601899678827046e-06 +-6.869500637054443,-22.03526496887207,-19.77199935913086,2.5789849677079823e-06 +-6.869500637054443,-22.03526496887207,-19.77199935913086,2.9858966330570384e-06 diff --git a/PythonAPI/data/path_logs/log2.txt b/PythonAPI/data/path_logs/log2.txt new file mode 100644 index 0000000..f99aba2 --- /dev/null +++ b/PythonAPI/data/path_logs/log2.txt @@ -0,0 +1,57 @@ +0.40436530113220215,-18.471620559692383,51.994937896728516,3.552096876096281e-06 +0.40436965227127075,-18.471620559692383,51.994937896728516,4.189752693619349e-06 +0.4043741226196289,-18.471620559692383,51.994937896728516,4.250823182253465e-06 +0.40437835454940796,-18.471620559692383,51.994937896728516,4.336564840983384e-06 +0.4043833911418915,-18.471620559692383,51.994937896728516,4.83213887844682e-06 +0.4043881595134735,-18.471620559692383,51.994937896728516,5.333680230245779e-06 +0.40439268946647644,-18.471620559692383,51.994937896728516,1.8606805101929713e-06 +0.4043969213962555,-18.471620559692383,51.994937896728516,4.420297758417399e-06 +0.40440070629119873,-18.471620559692383,51.994937896728516,4.255899562752267e-06 +0.4044056534767151,-18.471620559692383,51.994937896728516,4.578770151061793e-06 +0.40441039204597473,-18.471620559692383,51.994937896728516,4.500663274397787e-06 +0.40441465377807617,-18.471620559692383,51.994937896728516,4.146104187358633e-06 +0.40441930294036865,-18.471620559692383,51.994937896728516,4.440475565457707e-06 +0.4044235646724701,-18.471620559692383,51.994937896728516,4.141279382640211e-06 +0.4044281244277954,-18.471620559692383,51.994937896728516,4.165220272866397e-06 +0.40443283319473267,-18.471620559692383,51.994937896728516,4.761537390574418e-06 +0.40443769097328186,-18.471620559692383,51.994937896728516,4.202574458116234e-06 +0.4044418931007385,-18.471620559692383,51.994937896728516,4.973363393582503e-06 +0.4044467508792877,-18.471620559692383,51.994937896728516,4.393979539036073e-06 +0.404451847076416,-18.471620559692383,51.994937896728516,4.621618537029514e-06 +0.4044567048549652,-18.471620559692383,51.994937896728516,4.33408520250552e-06 +0.40446174144744873,-18.471620559692383,51.994937896728516,4.154301006699537e-06 +0.40446650981903076,-18.471620559692383,51.994937896728516,4.39740782857732e-06 +0.4044707119464874,-18.471620559692383,51.994937896728516,4.330190516547763e-06 +0.40447521209716797,-18.471620559692383,51.994937896728516,4.389974685666132e-06 +0.4044797122478485,-18.471620559692383,51.994937896728516,4.12073107488552e-06 +0.4044845998287201,-18.471620559692383,51.994937896728516,4.723785961849931e-06 +0.4044892489910126,-18.471620559692383,51.994937896728516,4.4988700122489035e-06 +0.40449434518814087,-18.471620559692383,51.994937896728516,4.7416137761918975e-06 +0.4044993817806244,-18.471620559692383,51.994937896728516,3.958177004119419e-06 +0.4045034348964691,-18.471620559692383,51.994937896728516,5.98396887850054e-06 +0.40450844168663025,-18.471620559692383,51.994937896728516,4.738902225130856e-06 +0.40451353788375854,-18.471620559692383,51.994937896728516,4.279966008850873e-06 +0.40451839566230774,-18.471620559692383,51.994937896728516,4.512500802222719e-06 +0.40452349185943604,-18.471620559692383,51.994937896728516,5.373009471409016e-06 +0.40452826023101807,-18.471620559692383,51.994937896728516,4.323851459749223e-06 +0.40453338623046875,-18.471620559692383,51.994937896728516,5.531944611008325e-06 +0.4045386016368866,-18.471620559692383,51.994937896728516,5.256680174040376e-06 +0.4045437276363373,-18.471620559692383,51.994937896728516,4.82460448931441e-06 +0.4045488238334656,-18.471620559692383,51.994937896728516,3.7600870964324882e-06 +0.4045535624027252,-18.471620559692383,51.994937896728516,4.9274263494731325e-06 +0.40153229236602783,-18.4774112701416,51.95127487182617,0.010283055886037005 +0.3685793876647949,-18.538372039794922,51.43287658691406,0.31898206952015273 +0.16208241879940033,-18.897626876831055,48.44056701660156,0.3062436343708868 +-0.1078888401389122,-19.308740615844727,44.94672393798828,0.5571614731332268 +-0.5459542870521545,-19.88347625732422,39.60797119140625,0.7797022503170842 +-1.2353742122650146,-20.60205841064453,32.41643524169922,0.9400981032793722 +-1.9913431406021118,-21.217693328857422,25.300111770629883,0.9406837044757467 +-2.8480632305145264,-21.751483917236328,17.912019729614258,0.9533570960702125 +-3.827090263366699,-22.195775985717773,9.944085121154785,0.9467609294480435 +-4.861904144287109,-22.500505447387695,1.9045978784561157,1.02231896895622 +-6.077081203460693,-22.669010162353516,-7.380134105682373,1.1513233639952782 +-7.128157615661621,-22.654752731323242,-15.229203224182129,0.6078544805116227 +-7.183380126953125,-22.65022850036621,-15.649277687072754,0.02450875945097867 +-7.19438362121582,-22.649215698242188,-15.733416557312012,2.4078144221459277e-06 +-7.194385051727295,-22.649215698242188,-15.733416557312012,2.4322855552899163e-06 +-7.194385051727295,-22.649215698242188,-15.733416557312012,2.3958903508356075e-06 diff --git a/PythonAPI/data/path_logs/log2_2.txt b/PythonAPI/data/path_logs/log2_2.txt new file mode 100644 index 0000000..7666329 --- /dev/null +++ b/PythonAPI/data/path_logs/log2_2.txt @@ -0,0 +1,9111 @@ +0.4042755365371704,-18.471723556518555,51.997589111328125,3.3207046593670582e-06 +0.40428027510643005,-18.471723556518555,51.997589111328125,4.577228020336707e-06 +0.4042850136756897,-18.471723556518555,51.997589111328125,4.978717434158321e-06 +0.4042898714542389,-18.471723556518555,51.997589111328125,4.3582706880587585e-06 +0.40429431200027466,-18.471723556518555,51.997589111328125,4.700698832400627e-06 +0.40429919958114624,-18.471723556518555,51.997589111328125,3.429211444987545e-06 +0.4043736159801483,-18.471723556518555,51.997589111328125,2.758015024350165e-06 +0.40437838435173035,-18.471723556518555,51.997589111328125,3.6110215175253356e-06 +0.40438351035118103,-18.471723556518555,51.997589111328125,3.5437705211894355e-06 +0.40438827872276306,-18.471723556518555,51.997589111328125,2.91785414647286e-06 +0.4043934941291809,-18.471723556518555,51.997589111328125,5.5912580701361215e-06 +0.4043985605239868,-18.471723556518555,51.997589111328125,4.668919570581191e-06 +0.40440356731414795,-18.471723556518555,51.997589111328125,5.286007929819494e-06 +0.40440860390663147,-18.471723556518555,51.997589111328125,3.68567044451007e-06 +0.40441370010375977,-18.471723556518555,51.997589111328125,4.665498873406325e-06 +0.4044187366962433,-18.471723556518555,51.997589111328125,5.080749595921772e-06 +0.4044235646724701,-18.471723556518555,51.997589111328125,4.763664007379169e-06 +0.4044288098812103,-18.471723556518555,51.997589111328125,3.463024009444623e-06 +0.4044339656829834,-18.471723556518555,51.997589111328125,3.8066679444366447e-06 +0.40443888306617737,-18.471723556518555,51.997589111328125,5.611844632079377e-06 +0.4044439494609833,-18.471723556518555,51.997589111328125,3.6171940042359996e-06 +0.40444910526275635,-18.471723556518555,51.997589111328125,5.299067918401622e-06 +0.40445417165756226,-18.471723556518555,51.997589111328125,4.675546479077085e-06 +0.4044591784477234,-18.471723556518555,51.997589111328125,4.759175663542726e-06 +0.404464453458786,-18.471723556518555,51.997589111328125,4.81102728482918e-06 +0.40446925163269043,-18.471723556518555,51.997589111328125,5.365666711705297e-06 +0.40447428822517395,-18.471723556518555,51.997589111328125,4.6994490116696535e-06 +0.40447962284088135,-18.471723556518555,51.997589111328125,5.375903499742464e-06 +0.40448492765426636,-18.471723556518555,51.997589111328125,4.579689244139848e-06 +0.40448999404907227,-18.471723556518555,51.997589111328125,3.251281375177171e-06 +0.40449509024620056,-18.471723556518555,51.997589111328125,5.202305990672735e-06 +0.4045003056526184,-18.471723556518555,51.997589111328125,2.7257153394824613e-06 +0.40450549125671387,-18.471723556518555,51.997589111328125,5.43501779883716e-06 +0.4045104384422302,-18.471723556518555,51.997589111328125,5.021455774487405e-06 +0.40451547503471375,-18.471723556518555,51.997589111328125,5.224351016305227e-06 +0.4045202434062958,-18.471723556518555,51.997589111328125,5.013545442589976e-06 +0.40452560782432556,-18.471723556518555,51.997589111328125,4.842324258993949e-06 +0.4045308828353882,-18.471723556518555,51.997589111328125,5.112187355540561e-06 +0.40453585982322693,-18.471723556518555,51.997589111328125,4.075164919589718e-06 +0.4045407474040985,-18.471723556518555,51.997589111328125,5.264857677241663e-06 +0.40454578399658203,-18.471723556518555,51.997589111328125,4.831619541035486e-06 +0.4045509696006775,-18.471723556518555,51.997589111328125,5.10750552263217e-06 +0.40141603350639343,-18.47772979736328,51.94782638549805,0.035967389896186176 +0.19471894204616547,-18.848411560058594,48.76779556274414,0.5505052403581293 +-0.08255764842033386,-19.276418685913086,45.0999755859375,0.3995905238710922 +-0.36886316537857056,-19.66910171508789,41.435821533203125,0.41216355782095404 +-0.642798900604248,-19.99677848815918,38.364051818847656,0.4458282102536995 +-0.957830011844635,-20.33550453186035,34.901885986328125,0.38390891842326347 +-1.3484231233596802,-20.605436325073242,34.78701400756836,0.4622787923585671 +-1.8146494626998901,-20.843488693237305,38.327144622802734,0.48548404563775166 +-2.184364080429077,-21.060245513916016,41.19384002685547,0.34953768891368286 +-2.555774688720703,-21.305021286010742,44.18498229980469,0.37488305669780214 +-2.8852450847625732,-21.547033309936523,46.845298767089844,0.35435033116022513 +-3.182832956314087,-21.786378860473633,49.40449523925781,0.3955204241604141 +-3.4588825702667236,-22.030054092407227,51.846187591552734,0.2871271172963106 +-3.6942567825317383,-22.25408172607422,54.01523971557617,0.332870996981447 +-3.9293391704559326,-22.49820899963379,56.223907470703125,0.31931036067867435 +-4.149867057800293,-22.742860794067383,58.435333251953125,0.29171495855992385 +-4.389076232910156,-23.034208297729492,60.869632720947266,0.4581176241954632 +-4.701077461242676,-23.45053482055664,64.37017059326172,0.5145407779608275 +-4.994288444519043,-23.89220428466797,67.94232940673828,0.0570403570191493 +-5.010418891906738,-23.88770866394043,68.333740234375,0.0034571902870682986 +-5.010854721069336,-23.887130737304688,68.35498046875,2.0475896229910723e-05 +-5.0107622146606445,-23.886962890625,68.35526275634766,4.059301372802903e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,6.1133938494354594e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,6.6389200682555935e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.847831299797629e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,3.752742080222976e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.870992672021231e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.932861946867657e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.6430816479640745e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,3.901745525257307e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.963148214236333e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.652536031118081e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.901555038915007e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.741981283427154e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.266584344890633e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.209486144957176e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.908136489908705e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.586537428289463e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.2912752982171865e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.340935207799456e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.877250406533175e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.198396889317837e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,3.4729677370588326e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,3.32031376099713e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.089436133803025e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,3.623948613078532e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,3.908164573109926e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.118167740979536e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.850402091772591e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,5.123329482065815e-06 +-5.0107622146606445,-23.886959075927734,68.35526275634766,4.189722822123892e-06 +0.40498003363609314,-18.471450805664062,51.995086669921875,3.4548785979648983e-06 +0.40498003363609314,-18.471450805664062,51.995086669921875,3.451059844798889e-06 +0.40498003363609314,-18.471450805664062,51.995086669921875,3.945630491327284e-06 +0.40498003363609314,-18.471450805664062,51.995086669921875,3.956129077119763e-06 +0.40498003363609314,-18.471450805664062,51.995086669921875,4.166496008683869e-06 +0.4049808084964752,-18.471450805664062,51.995086669921875,3.7143472945948564e-06 +0.40498122572898865,-18.471450805664062,51.995086669921875,2.6024785027508975e-06 +0.4049816131591797,-18.471450805664062,51.995086669921875,3.5354724112810386e-06 +0.4049827456474304,-18.471452713012695,51.995086669921875,3.3090731836352273e-06 +0.4049827456474304,-18.471452713012695,51.995086669921875,3.5755317586878366e-06 +0.40498313307762146,-18.471450805664062,51.995086669921875,3.445332900091579e-06 +0.4049839377403259,-18.471450805664062,51.995086669921875,3.6760928268711872e-06 +0.4049839377403259,-18.471450805664062,51.995086669921875,3.458660401266982e-06 +0.40498507022857666,-18.471452713012695,51.995086669921875,3.6285024324363736e-06 +0.4049854874610901,-18.471450805664062,51.995086669921875,3.44458417556163e-06 +0.4049854874610901,-18.471450805664062,51.995086669921875,3.6766770747198157e-06 +0.4049854874610901,-18.471450805664062,51.995086669921875,3.4477155224730385e-06 +0.4049854874610901,-18.471450805664062,51.995086669921875,3.6989132581430205e-06 +0.4049862325191498,-18.471450805664062,51.995086669921875,3.4882249319653294e-06 +0.40498775243759155,-18.471450805664062,51.995086669921875,3.6881709615408637e-06 +0.40498775243759155,-18.471450805664062,51.995086669921875,3.614682264945273e-06 +0.4049888551235199,-18.471452713012695,51.995086669921875,3.70831395290414e-06 +0.40498998761177063,-18.471450805664062,51.995086669921875,4.101533904069809e-06 +0.40498998761177063,-18.471450805664062,51.995086669921875,3.969949374774485e-06 +0.40498998761177063,-18.471450805664062,51.995086669921875,4.119320786292224e-06 +0.4049907624721527,-18.471450805664062,51.995086669921875,3.548540822663811e-06 +0.4049907624721527,-18.471450805664062,51.995086669921875,2.7628277685760887e-06 +0.4049907624721527,-18.471450805664062,51.995086669921875,3.4497626629288647e-06 +0.4049907624721527,-18.471450805664062,51.995086669921875,3.272160485323829e-06 +0.4049907624721527,-18.471450805664062,51.995086669921875,3.456498888971452e-06 +0.4049907624721527,-18.471450805664062,51.995086669921875,3.2322299974175153e-06 +0.40499147772789,-18.471450805664062,51.995086669921875,3.4242874231904894e-06 +0.4049926698207855,-18.471450805664062,51.995086669921875,3.281031403839727e-06 +0.4049926698207855,-18.471450805664062,51.995086669921875,3.6574189595028633e-06 +0.4049926698207855,-18.471450805664062,51.995086669921875,3.3208041780219315e-06 +0.40399831533432007,-18.47267723083496,51.99934005737305,0.04700641902894239 +0.4049571752548218,-18.471431732177734,51.99991226196289,0.059046607850947834 +0.4093843698501587,-18.4661922454834,51.993961334228516,0.07699832704411126 +0.45663729310035706,-18.401023864746094,52.09430694580078,0.3160592491690844 +0.5743792653083801,-18.260988235473633,51.87605667114258,0.5749952045389196 +0.7501200437545776,-18.010780334472656,52.42557907104492,0.9225059063819331 +0.9907233119010925,-17.716503143310547,52.01839065551758,0.9961160474748706 +1.1965302228927612,-17.413768768310547,52.85664367675781,0.8536169810945232 +1.3894963264465332,-17.16968536376953,52.63645553588867,0.7249436456804763 +1.5334099531173706,-16.949390411376953,53.35435104370117,0.6158060337918247 +1.6675045490264893,-16.770538330078125,53.339378356933594,0.5221483447896385 +1.753163456916809,-16.605085372924805,54.5309944152832,0.43716426818481585 +1.800040602684021,-16.459684371948242,56.35821533203125,0.36643362703611265 +1.8378520011901855,-16.33427619934082,57.854225158691406,0.3187386792850568 +1.8869109153747559,-16.229482650756836,58.40895462036133,0.277159459847606 +1.9436681270599365,-16.148235321044922,58.170040130615234,0.23178018498840502 +1.9958643913269043,-16.08162498474121,57.80484390258789,0.20008753153821265 +2.039952278137207,-16.02372932434082,57.54365158081055,0.1714135739431519 +2.081529378890991,-15.978407859802246,57.10908508300781,0.14747474747089845 +2.1004996299743652,-15.958489418029785,56.90394973754883,0.01361324199932799 +2.1015942096710205,-15.95759105682373,56.88747787475586,0.008334135083340357 +2.10195255279541,-15.957320213317871,56.88228988647461,0.007815105434975623 +2.1022844314575195,-15.957053184509277,56.87791442871094,0.007384510430000764 +2.1028974056243896,-15.956525802612305,56.869659423828125,0.017762322107776955 +2.1032187938690186,-15.956461906433105,56.865596771240234,0.014698623255683925 +2.0958120822906494,-15.963319778442383,56.97643280029297,0.04409361576370151 +1.9001668691635132,-16.149320602416992,59.80851364135742,0.860935286239187 +1.6543385982513428,-16.411218643188477,63.6328125,1.2914700696516013 +1.2487369775772095,-16.929304122924805,70.55994415283203,1.872613044504588 +0.9017951488494873,-17.50139045715332,77.62548065185547,1.4331783331387689 +0.7184231877326965,-17.887149810791016,82.07743072509766,0.7950612245493622 +0.636549174785614,-18.0975284576416,84.34342956542969,0.4038873064850751 +0.5911338925361633,-18.244091033935547,85.68173217773438,0.3082051519149281 +0.5657582879066467,-18.329294204711914,86.48429870605469,0.16451499397527786 +0.5529431104660034,-18.374343872070312,86.9051513671875,0.08741189195978737 +0.5469539761543274,-18.39820098876953,87.1014404296875,0.04687189347411062 +0.5444207191467285,-18.4107608795166,87.18162536621094,0.025423275791416775 +0.5433732271194458,-18.417234420776367,87.21360778808594,0.014155298669468715 +0.5427954792976379,-18.420391082763672,87.23323059082031,0.008962796752237531 +0.5424599647521973,-18.421772003173828,87.24664306640625,0.008096471336575518 +0.5423609614372253,-18.4222354888916,87.2517318725586,0.006503546335485221 +0.5424051284790039,-18.422239303588867,87.25198364257812,0.005683799249622456 +0.542511522769928,-18.422021865844727,87.25003051757812,0.005742200876885182 +0.5426306128501892,-18.4217586517334,87.2476806640625,0.005799128831892054 +0.5427495241165161,-18.42149543762207,87.24528503417969,0.00572358204974419 +0.5428680181503296,-18.421249389648438,87.24288177490234,0.005735167786126737 +0.5429834723472595,-18.42098045349121,87.24060821533203,0.005173516132099367 +0.5430770516395569,-18.420804977416992,87.23902130126953,0.008992449378672523 +0.542963445186615,-18.422269821166992,87.24337768554688,0.009306335318758603 +0.5416462421417236,-18.444847106933594,87.25531005859375,0.00856279444180093 +0.5416682958602905,-18.445146560668945,87.25589752197266,0.004039889717900627 +0.5416831970214844,-18.44550132751465,87.25643920898438,0.0029411134182858586 +0.5417301058769226,-18.445556640625,87.256591796875,0.0022179894136279505 +0.5417913198471069,-18.44538688659668,87.25641632080078,0.0021543582100374977 +0.5418376326560974,-18.445215225219727,87.25694274902344,0.002145770659405028 +0.5419053435325623,-18.444950103759766,87.25660705566406,0.0021578548867084266 +0.5419502854347229,-18.444774627685547,87.2572021484375,0.002147232115072262 +0.541892945766449,-18.4470157623291,87.2580337524414,0.017383685847524026 +0.5388047695159912,-18.53664779663086,87.1778793334961,0.8864851486327696 +0.5074415802955627,-19.08504867553711,87.4532699584961,1.8208461934213431 +0.5055699348449707,-19.952436447143555,85.15778350830078,2.5786897198949803 +0.4086385667324066,-21.09071922302246,85.5830307006836,3.0482038345254567 +0.42181602120399475,-22.09449005126953,78.98670196533203,2.3196072737734568 +0.3918757438659668,-22.58136749267578,72.302490234375,0.4799632754953933 +0.3404318690299988,-22.76821517944336,70.36409759521484,0.6492584406892553 +0.21454426646232605,-23.097978591918945,70.08989715576172,1.4329730978343933 +-0.13118061423301697,-23.845563888549805,73.8088607788086,2.714873338513177 +-0.597616970539093,-25.202417373657227,80.22431945800781,4.343596586246292 +-0.9380961656570435,-27.032100677490234,81.36380767822266,4.548988488366281 +-1.2355889081954956,-28.552019119262695,87.10914611816406,3.2980671143428153 +-1.3006880283355713,-29.662057876586914,87.36061096191406,2.3316018035924384 +-1.383065938949585,-30.438547134399414,90.22471618652344,1.6365604153016606 +-1.3799231052398682,-30.984516143798828,90.09492492675781,1.1608958076325486 +-1.4072272777557373,-31.39385414123535,91.44205474853516,0.9243477037739826 +-1.3948341608047485,-31.7293701171875,91.25273895263672,0.7705994768714886 +-1.4044159650802612,-32.02131652832031,92.00374603271484,0.688879967988244 +-1.3889461755752563,-32.28935623168945,91.69798278808594,0.6629328081142615 +-1.392540693283081,-32.542755126953125,92.24156188964844,0.6237723544966993 +-1.377363920211792,-32.7580451965332,91.94728088378906,0.6233162389958451 +-1.3788824081420898,-32.970340728759766,92.34666442871094,0.4042930306529395 +-1.3692882061004639,-33.067100524902344,92.09900665283203,8.612320035798007e-05 +-1.3692680597305298,-33.067195892333984,92.09896850585938,9.279837432218338e-06 +-1.3692660331726074,-33.06720733642578,92.09894561767578,5.321626821972957e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.0416996394154515e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.2119508051690716e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.142857538837707e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.1225217960256655e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.096996208638015e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.178443166441321e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.017409764062403e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.155766702004051e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,4.974725756725092e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.129601120418882e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,4.927547297915943e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,3.4472709560240813e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,4.054641900736865e-06 +-1.3692659139633179,-33.06721115112305,92.09894561767578,5.1858328966599525e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,3.4554915604402328e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,3.7223133185662214e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,3.961930814499926e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,4.065783112581749e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.787861906190817e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.4682075542160027e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2144679830052086e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.23363028737441e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2439816744460863e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.211029045908151e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2254451051285397e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.1728595735682267e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2281122830976892e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.20852312016144e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.215395476654872e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2190831070606203e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2155768214718318e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2297168740441707e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.226132555387815e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2624347717709374e-06 +0.4045790433883667,-18.471384048461914,51.9969482421875,2.2334285776977627e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.1960641688819016e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.285328752810324e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.250592857071802e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.5823429023947654e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3396605909154527e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.309159308469446e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.305457957820082e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3075603553273575e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.288792175208613e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3437756288322438e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.394301780300716e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3919590540956974e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3041644354606146e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.300176874739259e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3110855859371974e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3052789447789044e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.2770273060038075e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.2399576573958725e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.243583026837534e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.281902600555218e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3381169394694526e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3347985368576033e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.300338376606595e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.2455119186859364e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3213646423643324e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.3598878507255784e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.274781161159259e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.2479329035438135e-06 +0.40457990765571594,-18.471384048461914,51.9969482421875,2.254957373549143e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.6573028417086527e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.3498722421097683e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.237261978293278e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2575335354421887e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.205436455542088e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2160933880872067e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.235023305259442e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2283444177132182e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2246582034611393e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.246009135088905e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2351027435838673e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.1956123945130797e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2865407812102934e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.261011890735629e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.242527344203026e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2322396665230014e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.226360176792674e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2444767129825973e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2658580435046226e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.273140927583816e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2618579603886525e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2059564122212734e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.3352792822007904e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2124782613442687e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.254365231813162e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.268466083260708e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2772580486821724e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.235075175059026e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2591307086314513e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.178423912257727e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.191495306599379e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.218016149894455e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2280604657353148e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2150174588862696e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.2568807819521455e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.3804140837463644e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.302464697937956e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.3800139315985087e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.3554882221003797e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.20089126304785e-06 +0.40458106994628906,-18.471384048461914,51.9969482421875,2.3615866269824857e-06 +0.4045814871788025,-18.471384048461914,51.9969482421875,2.2951213214923714e-06 +0.4045822322368622,-18.471384048461914,51.9969482421875,2.3151098388701235e-06 +0.4045822322368622,-18.471384048461914,51.9969482421875,2.353089922991083e-06 +0.4045822322368622,-18.471384048461914,51.9969482421875,2.250625218343398e-06 +0.4045822322368622,-18.471384048461914,51.9969482421875,2.2549168603335294e-06 +0.4045822322368622,-18.471384048461914,51.9969482421875,2.4301187062294465e-06 +0.4045826196670532,-18.471384048461914,51.9969482421875,2.53331347546693e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.2592760707069916e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.244193613478411e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.2614668295207988e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.2180540922246576e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.230620624924346e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.236263260715838e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.223639724043103e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.2158954718199093e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.1830957222185098e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.287153337047605e-06 +0.40458354353904724,-18.471384048461914,51.9969482421875,2.224206503409139e-06 +5.340589268598706e-07,7.232623744357625e-08,0.0,1.0630752174275842e-08 +5.340590405467083e-07,6.733425550464744e-08,0.0,1.964252299478099e-08 +5.34059154233546e-07,7.176744531989243e-08,0.0,6.322212536914473e-09 +5.340592110769649e-07,6.345985781308627e-08,0.0,2.725319292133492e-08 +5.34059154233546e-07,6.755310977268891e-08,0.0,4.343493937852964e-08 +5.34059154233546e-07,6.225843662832631e-08,0.0,6.485926371200541e-08 +5.340592110769649e-07,6.668230412287812e-08,0.0,4.637293499973294e-08 +5.340592110769649e-07,6.68126887148901e-08,0.0,1.3371090089510954e-08 +5.340590973901271e-07,6.556934550872029e-08,0.0,7.24133191385036e-08 +5.34059154233546e-07,6.771605853828078e-08,0.0,5.882342763652235e-09 +5.340590405467083e-07,5.902198552121263e-08,0.0,4.885142992043399e-08 +5.340590405467083e-07,5.9571473087771665e-08,0.0,3.0448038283918178e-09 +5.34059154233546e-07,5.2712223919115786e-08,0.0,4.2725702648459625e-08 +5.34059154233546e-07,5.532925584361692e-08,0.0,1.1402077561780851e-08 +5.34059154233546e-07,5.989742390966057e-08,0.0,6.944374536209866e-09 +5.34059154233546e-07,6.167626764863599e-08,0.0,1.0278334949480342e-08 +5.34059154233546e-07,5.914305134524511e-08,0.0,4.611850729785466e-08 +5.34059154233546e-07,5.521284762721734e-08,0.0,6.450083474389114e-08 +5.340592110769649e-07,5.70894691520607e-08,0.0,3.1271229004962044e-08 +5.340592110769649e-07,5.540375269674769e-08,0.0,6.623075009501982e-09 +5.34059154233546e-07,6.494525450762012e-08,0.0,6.327521169431591e-08 +5.34059154233546e-07,5.614418085997386e-08,0.0,3.0128862952956694e-08 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.6335552333566124e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.549939531768553e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.574760700868836e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.7166217801816374e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.8838848879822404e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.124663631585692e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,2.4543040065013265e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.567827609187974e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,5.209636396751915e-06 +1.0360757112503052,-18.329959869384766,49.97121047973633,4.037025474050734e-06 +1.0543509721755981,-18.302043914794922,50.14319610595703,0.1454052062843066 +1.1251689195632935,-18.18881607055664,50.867958068847656,0.26433862560443794 +1.1943706274032593,-18.084280014038086,51.36591339111328,0.2124397664093132 +1.24530029296875,-17.99735450744629,51.93801498413086,0.17415920241678154 +1.2793183326721191,-17.945453643798828,52.15904235839844,6.30038345682986e-06 +1.27932870388031,-17.945411682128906,52.159603118896484,4.340549227950205e-06 +1.2793288230895996,-17.94540786743164,52.159603118896484,5.1137109672714016e-06 +1.27932870388031,-17.94540786743164,52.159603118896484,4.922029727367376e-06 +1.27932870388031,-17.94540786743164,52.159603118896484,4.9280058659692645e-06 +1.27932870388031,-17.94540786743164,52.159603118896484,4.375956715382882e-06 +1.279328465461731,-17.94540786743164,52.159603118896484,4.759598866496848e-06 +1.2793282270431519,-17.94540786743164,52.159603118896484,4.893081449257164e-06 +1.2793283462524414,-17.94540786743164,52.159603118896484,4.896182755469216e-06 +1.279511570930481,-17.945100784301758,52.16185760498047,0.00217774038254904 +1.2623165845870972,-17.971599578857422,52.0598030090332,0.15306279162264005 +1.1303026676177979,-18.168167114257812,51.300193786621094,0.5816898740468809 +0.9642094969749451,-18.422637939453125,49.92036819458008,0.7306323010665557 +0.6947327256202698,-18.790048599243164,48.47605895996094,0.9778990049904647 +0.34507179260253906,-19.261112213134766,45.752323150634766,1.2364773502264057 +-0.09997137635946274,-19.78015899658203,43.52305603027344,1.373629012078098 +-0.608962893486023,-20.349239349365234,39.87071990966797,1.4809957461119563 +-1.2075462341308594,-20.914358139038086,37.174808502197266,1.5625258781325357 +-1.8158891201019287,-21.458263397216797,33.20348358154297,1.5567496825922744 +-2.4598469734191895,-21.938617706298828,30.579479217529297,1.2835920503687892 +-2.8237457275390625,-22.210189819335938,28.159170150756836,0.5535093244449814 +-2.968207359313965,-22.310331344604492,27.27973747253418,0.12243636074569499 +-3.0386412143707275,-22.360498428344727,26.7528076171875,0.34772163369481796 +-3.3141565322875977,-22.53919219970703,25.06383514404297,0.9402524978795765 +-3.872474193572998,-22.851224899291992,22.493364334106445,1.4025428895610061 +-4.578173637390137,-23.218873977661133,18.72344207763672,1.6088433811039091 +-5.370508193969727,-23.58475112915039,13.102208137512207,1.729916631058977 +-6.26175594329834,-23.86363410949707,9.008124351501465,1.7770321527782453 +-6.958566665649414,-24.02180290222168,6.337547779083252,0.8842112602957258 +-7.262685298919678,-24.083786010742188,5.062718391418457,0.36916380435579965 +-7.389921188354492,-24.114498138427734,4.21846866607666,0.15665526879745112 +-7.443975448608398,-24.12392234802246,3.9905827045440674,0.06514184581840174 +-7.457219123840332,-24.126386642456055,3.9261581897735596,8.6541353372446e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.146493786410277e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.716134246084972e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.4073345263713753e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.777650687262494e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.939260791912348e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,2.4876114643259935e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.039987086361768e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.5481178896264507e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.53698942080643e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.082183738869913e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.754140468140065e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.706415326281371e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,2.377688329086469e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.674117248722145e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.969929176089084e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6427685580192884e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.922560759629176e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.351224940657489e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.7293118705550883e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.921287811318975e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.645554847300531e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.4720572738141012e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.786680706199994e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.7968362358539207e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.4359009523937455e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.837121009540976e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.901258509848338e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.869668634692778e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.848060057116931e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.921796209380772e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.945958217943865e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.961078947495578e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.0112241801307555e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.002155170811674e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.0684523790429524e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,2.6179804454884977e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,1.7461492384628404e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6738326624057546e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.171981222204457e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.00019778779617e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.854247212778948e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.06027489931409e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.129635793358169e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,1.5925930669278416e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,1.040641427769561e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6396541712212195e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6943725481794046e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6884228420712018e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.152563537455506e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6505069669099888e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.972701384050199e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.008710559392241e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.703403511930729e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6286479346724255e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,2.2151884332293704e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.8751302016261405e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,4.0776147141158575e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.909573940758281e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.6677652099563266e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.921805513989164e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,1.907968387247092e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.2937911246530456e-06 +-7.457222938537598,-24.12639045715332,3.9261581897735596,3.5574384971582594e-06 +4.193424701690674,-15.940959930419922,55.325252532958984,4.301216945573202e-06 +4.193424701690674,-15.940959930419922,55.325252532958984,4.556841468201689e-06 +4.193424701690674,-15.940959930419922,55.325252532958984,5.005943722951963e-06 +4.193424701690674,-15.940959930419922,55.325252532958984,4.854351535881276e-06 +4.193424701690674,-15.940959930419922,55.325252532958984,4.881324339822206e-06 +4.193424701690674,-15.940959930419922,55.325252532958984,4.954357017892052e-06 +4.193424701690674,-15.940959930419922,55.325252532958984,4.7338339448534795e-06 +4.192629814147949,-15.942140579223633,55.325172424316406,0.04222723494604075 +4.024398326873779,-16.184782028198242,55.33586502075195,1.2965738805105165 +3.9744956493377686,-16.25674057006836,55.33262634277344,0.11668968605138227 +4.006849765777588,-16.21016502380371,55.33118438720703,0.09949265590202604 +3.9538683891296387,-16.286907196044922,55.33726501464844,0.8129786404572763 +3.8259053230285645,-16.47161293029785,55.346168518066406,0.20602162386968764 +3.887113332748413,-16.383390426635742,55.34430694580078,0.1849201461082884 +3.917558193206787,-16.33955192565918,55.34381103515625,0.031537648796603625 +3.713296413421631,-16.634235382080078,55.34542465209961,1.342719047127019 +3.346789836883545,-17.16301155090332,55.34403610229492,0.09147918316232616 +3.363215208053589,-17.139362335205078,55.342498779296875,0.0743878474834515 +3.3803248405456543,-17.114723205566406,55.34214782714844,4.521521280330116e-06 +3.3806862831115723,-17.11421775817871,55.34214782714844,0.001083015872715897 +3.278599977493286,-17.26169204711914,55.347503662109375,0.9202785382149323 +2.8293960094451904,-17.909889221191406,55.34742736816406,1.9350469210170058 +2.1788971424102783,-18.78734016418457,57.17797088623047,1.7621860943829744 +1.7786023616790771,-19.260967254638672,61.167598724365234,0.7417482589137351 +1.604164958000183,-19.450353622436523,63.9330940246582,0.31366460825399295 +1.5332107543945312,-19.53410530090332,65.0887222290039,0.13202764801980005 +1.5042228698730469,-19.569618225097656,65.5644302368164,0.05517518467234727 +1.5012637376785278,-19.573301315307617,65.6124038696289,0.004236182751715894 +1.4879335165023804,-19.590574264526367,65.84268188476562,0.19546372692562464 +1.3876317739486694,-19.72052001953125,67.5486831665039,0.47653140805751215 +1.227081298828125,-19.9466609954834,70.36858367919922,0.6090525867760015 +1.0522955656051636,-20.224334716796875,73.65511322021484,0.6777775628869425 +0.870030403137207,-20.562091827392578,77.4148178100586,0.8018918846717229 +0.6965667605400085,-20.950992584228516,81.46533966064453,0.6425211405850916 +0.6372789740562439,-21.092641830444336,82.98524475097656,0.010993182138462307 +0.6364448666572571,-21.092302322387695,83.00325775146484,0.000234595888530109 +0.6303551197052002,-21.09583854675293,83.10611724853516,0.09800005925303808 +0.5771534442901611,-21.121131896972656,84.24445343017578,0.15691346397233727 +0.5068454146385193,-21.152284622192383,85.76966094970703,0.1234182182247612 +0.49262312054634094,-21.15304183959961,86.11453247070312,0.00592479041146174 +0.4913184344768524,-21.152381896972656,86.13402557373047,0.007151214841629958 +0.4676378071308136,-21.163822174072266,86.69598388671875,0.1266139114743249 +0.38314321637153625,-21.196218490600586,89.0518798828125,0.26125441796306675 +0.27567800879478455,-21.238542556762695,92.01126098632812,0.2723654041494451 +0.21250155568122864,-21.26099395751953,93.6823501586914,0.01842075876595171 +0.20755647122859955,-21.259342193603516,93.73863220214844,0.0016638172297391504 +0.2071460336446762,-21.25900650024414,93.74043273925781,0.000142782887814692 +0.20708611607551575,-21.25899887084961,93.74043273925781,6.286625909525314e-05 +0.20705477893352509,-21.25897979736328,93.74067687988281,1.094259424914462e-05 +0.20703883469104767,-21.258975982666016,93.74069213867188,1.789442812072716e-05 +0.2070244401693344,-21.258974075317383,93.74077606201172,2.955670425228196e-06 +0.20699264109134674,-21.25898551940918,93.7396469116211,0.0028549264352730665 +0.23204831779003143,-21.076976776123047,92.28631591796875,0.9109687647185031 +0.3941722512245178,-20.32636260986328,85.95099639892578,1.9916513645252139 +0.8754971623420715,-19.121328353881836,74.35143280029297,2.8883219113586596 +1.9394011497497559,-17.711977005004883,57.00663375854492,3.6273019782149873 +3.6227996349334717,-16.62835693359375,35.59043502807617,3.9897529519138506 +5.470696449279785,-16.290847778320312,14.316024780273438,3.2299758514146784 +6.908921241760254,-16.525575637817383,-2.3553473949432373,1.1340660941191543 +6.941554546356201,-16.516748428344727,-2.493804931640625,0.005543276755498472 +6.940162658691406,-16.515798568725586,-2.478058338165283,0.002486606572541136 +6.940152645111084,-16.51575469970703,-2.47705078125,1.798086879297911e-06 +6.930522441864014,-16.512454986572266,-2.358581781387329,0.07015542257052794 +6.741755962371826,-16.450695037841797,0.030815158039331436,0.8006357214342346 +6.227162837982178,-16.322675704956055,6.5399041175842285,1.1985323124907155 +5.530994892120361,-16.24359893798828,15.040165901184082,1.5885414053810278 +4.661620616912842,-16.290388107299805,25.386882781982422,1.7922332019144727 +3.7239506244659424,-16.52610206604004,36.74148941040039,1.9044810386970694 +2.7834365367889404,-16.987878799438477,48.7613410949707,2.0268454036493613 +1.9472566843032837,-17.655357360839844,60.62724304199219,2.1363041898399224 +1.2160178422927856,-18.57150650024414,73.16017150878906,2.3386558118489384 +0.6906713843345642,-19.68052101135254,85.64089965820312,2.134147536443502 +0.4270414113998413,-20.6326904296875,97.05975341796875,1.8258146164090556 +0.35491621494293213,-20.953569412231445,101.42303466796875,0.03333932906356503 +0.3486842215061188,-20.955469131469727,101.5584487915039,0.004768690053104723 +0.6373315453529358,-12.291378021240234,81.5373764038086,0.021057673551052123 +0.638270914554596,-12.289386749267578,81.55389404296875,0.00028689382145986013 +0.6383023858070374,-12.289386749267578,81.55392456054688,7.994205789220606e-05 +0.6383064985275269,-12.28940200805664,81.55392456054688,7.128687423182044e-06 +0.6284221410751343,-12.356148719787598,81.55343627929688,0.7148664562819904 +0.5581919550895691,-12.825271606445312,81.546630859375,0.02659508431406015 +0.5652808547019958,-12.77837085723877,81.54500579833984,0.02531507484380617 +0.5602063536643982,-12.812816619873047,81.5455093383789,0.2663567679409298 +0.51005619764328,-13.14747142791748,81.53783416748047,0.9419093639122383 +0.42802542448043823,-13.694791793823242,81.53601837158203,1.1359792362863481 +0.34111487865448,-14.274354934692383,81.53509521484375,1.148638560637224 +0.33033958077430725,-14.34638500213623,81.5341567993164,0.05680734418564194 +0.3308089077472687,-14.343758583068848,81.53385925292969,0.06318588858984141 +0.3099508285522461,-14.483599662780762,81.53443908691406,0.6296996375054844 +0.24214386940002441,-14.93580150604248,81.52976989746094,1.1140184535304576 +0.17676305770874023,-15.371851921081543,81.52860260009766,0.025238387513769167 +0.1793479323387146,-15.35491943359375,81.52752685546875,0.04001280818388808 +0.17699186503887177,-15.371216773986816,81.52912902832031,0.19665164380685465 +0.13686314225196838,-15.638946533203125,81.52196502685547,0.8292944446998101 +0.0495874397456646,-16.220233917236328,81.50972747802734,1.1355502846934982 +0.0404360368847847,-16.281566619873047,81.51217651367188,0.05652739003908715 +0.04452119767665863,-16.2546443939209,81.51177215576172,0.048620625654001104 +0.037554703652858734,-16.30143165588379,81.50895690917969,0.5649664128764657 +-0.053858861327171326,-16.909955978393555,81.50536346435547,1.694023198705867 +-0.15567563474178314,-17.78458023071289,80.03715515136719,1.224299563252237 +-0.1968422830104828,-18.217060089111328,78.31461334228516,0.5158604820673816 +-0.21602974832057953,-18.329986572265625,78.13386535644531,0.1133332986343217 +-0.22053422033786774,-18.369754791259766,77.96853637695312,0.04755562213392959 +-0.22145846486091614,-18.374340057373047,77.96609497070312,6.745948711266681e-06 +-0.22260142862796783,-18.3820743560791,77.94043731689453,0.05238844299255731 +-0.25454166531562805,-18.599878311157227,77.24819946289062,0.8117417554623484 +-0.34847989678382874,-19.20232391357422,74.9317855834961,1.4041627387837532 +-0.5166134238243103,-19.961645126342773,73.1016616821289,1.5407839482060137 +-0.707314133644104,-20.772172927856445,69.78962707519531,1.6160145500943237 +-0.966145932674408,-21.58660125732422,67.7527084350586,1.6455319177557601 +-1.2424383163452148,-22.413700103759766,64.14112091064453,1.6722745613108916 +-1.5898971557617188,-23.22942352294922,61.82601547241211,1.5967696617366764 +-1.9234588146209717,-23.977197647094727,58.23606872558594,1.54522809741392 +-2.3174867630004883,-24.69686508178711,55.909934997558594,1.5381697988143577 +-2.7174575328826904,-25.397367477416992,52.2244758605957,1.5388871059385931 +-3.1812539100646973,-26.07181739807129,49.75362014770508,1.5522514155957954 +-3.3295674324035645,-26.357330322265625,47.070533752441406,0.048879716987232556 +-3.3235814571380615,-26.364341735839844,46.8792724609375,0.005217370044558828 +-3.3220558166503906,-26.364187240600586,46.85588455200195,0.0004937110299910364 +-3.321918249130249,-26.364093780517578,46.853973388671875,2.0732620037323467e-05 +-3.3219149112701416,-26.364076614379883,46.853904724121094,1.1976829466198067e-05 +-3.321915626525879,-26.364076614379883,46.853904724121094,1.8888767183862695e-05 +-3.321916341781616,-26.364076614379883,46.853904724121094,2.4427050409422945e-05 +-3.3219149112701416,-26.364078521728516,46.8538703918457,6.957129481586862e-05 +3.454590082168579,-18.18596839904785,51.70869064331055,3.319389063347811e-06 +3.454590082168579,-18.18596839904785,51.70869064331055,3.407338836384618e-06 +3.454590082168579,-18.18596839904785,51.70869064331055,3.239362279307173e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.072562202995489e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.446785263875391e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,3.75894337283499e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.9325609526624465e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.226781829522402e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.87602653610305e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.22071498678839e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.447298086459209e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.304210835432846e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.114623864016355e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.99225656818841e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.089617506795725e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.805563725188196e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.742403783187633e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.068660954338988e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.0668359500588126e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.092823485093084e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.912062369733485e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.362448134832295e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.861493556796565e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.132031177915417e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.901933690292847e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.534603762271976e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.741617552343472e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.808661568640653e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.1131188804305995e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.071555243698305e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.926759625063395e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.785234354853673e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.130963469448168e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.035588377500717e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.1738833746515654e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,3.0260687628549914e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.141879943815767e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.176796968020485e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.521132494687781e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.212745090476693e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.22619208933144e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.0211951260229815e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.061725012783938e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.321790046473135e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.026372013915301e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.074979008803659e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,3.6907633528714422e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.3240570850609165e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.348668720156874e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,4.867072248467594e-06 +2.8173482418060303,-18.992937088012695,51.7804069519043,5.01380867318144e-06 +2.8173646926879883,-18.992965698242188,51.779075622558594,0.00507224322897109 +2.817304849624634,-18.992998123168945,51.78120422363281,0.0035268792639906506 +2.8171606063842773,-18.993274688720703,51.779327392578125,0.01052406966132847 +2.8169448375701904,-18.993682861328125,51.77446746826172,0.022650354809981454 +2.8163628578186035,-18.994626998901367,51.76564407348633,0.01576044646859933 +2.8155553340911865,-18.995975494384766,51.76367950439453,0.04436530039329267 +2.8146681785583496,-18.997404098510742,51.75572204589844,0.0424781789108923 +2.8124585151672363,-19.0008487701416,51.74504852294922,0.10738592900725663 +2.8095877170562744,-19.005298614501953,51.722965240478516,0.1124137118474543 +2.8066976070404053,-19.009933471679688,51.69916534423828,0.12322565142923969 +2.8031015396118164,-19.015697479248047,51.66390609741211,0.16193096980865637 +2.798065185546875,-19.0239315032959,51.613037109375,0.25671524062152706 +2.7920753955841064,-19.033689498901367,51.54652404785156,0.2676094355175323 +2.7837448120117188,-19.047088623046875,51.47212600708008,0.3710943156499199 +2.7743475437164307,-19.061771392822266,51.39543151855469,0.4494880667530876 +2.7609732151031494,-19.082408905029297,51.29344177246094,0.5015117348541445 +2.748969554901123,-19.100507736206055,51.2120361328125,0.5504796592524016 +2.732386827468872,-19.1253604888916,51.09907150268555,0.6352407377364389 +2.7154738903045654,-19.151031494140625,50.97245407104492,0.6912721032631463 +2.6976876258850098,-19.17841339111328,50.825096130371094,0.7508818966712417 +2.677337884902954,-19.210317611694336,50.63636779785156,0.8042004281012048 +2.656237840652466,-19.24382781982422,50.42452621459961,0.8635422467772902 +2.6345362663269043,-19.278104782104492,50.20761489868164,0.9392000144054525 +2.6090688705444336,-19.317474365234375,49.97224426269531,1.02598435829688 +2.583333730697632,-19.355934143066406,49.7580451965332,1.0606143983623708 +2.554699420928955,-19.397489547729492,49.54684829711914,1.113765421772413 +2.5238330364227295,-19.44108009338379,49.34403610229492,1.1658572716384872 +2.492661476135254,-19.48465347290039,49.14137649536133,1.2249621572348932 +2.458209276199341,-19.53311538696289,48.897953033447266,1.2593409727968443 +2.4240810871124268,-19.581628799438477,48.63215637207031,1.3016137348811219 +2.388737678527832,-19.63252067565918,48.3265495300293,1.3379638829430098 +2.3533177375793457,-19.684003829956055,47.99385070800781,1.3745213243402628 +2.3147761821746826,-19.739484786987305,47.631980895996094,1.4163654094879783 +2.2759809494018555,-19.793790817260742,47.296630859375,1.4445798721685246 +2.2351911067962646,-19.84908103942871,46.979759216308594,1.4766051950753571 +2.1935958862304688,-19.903789520263672,46.688167572021484,1.5075325180045795 +2.1507906913757324,-19.959426879882812,46.389503479003906,1.5347602447511568 +2.106808662414551,-20.01675796508789,46.05986022949219,1.5394165793205443 +2.059293508529663,-20.079174041748047,45.66986846923828,1.553808247239216 +2.0159780979156494,-20.136432647705078,45.28424072265625,1.5952053046040062 +1.9732940196990967,-20.19223403930664,44.90619659423828,1.6140931887980121 +1.9231821298599243,-20.256000518798828,44.49240493774414,1.6403239555169111 +1.8788360357284546,-20.310640335083008,44.160675048828125,1.6562960231934383 +1.8262228965759277,-20.373504638671875,43.80393600463867,1.6823691725442085 +1.7757714986801147,-20.4329833984375,43.46290969848633,1.6975976073506684 +1.7277320623397827,-20.489643096923828,43.1181640625,1.7072323705846983 +1.675455927848816,-20.551753997802734,42.70942687988281,1.7204664872679571 +1.6229714155197144,-20.614336013793945,42.2628173828125,1.7330955253558804 +1.5733500719070435,-20.673797607421875,41.809146881103516,1.747947434657142 +1.5170806646347046,-20.740219116210938,41.2978515625,1.7530775918075223 +1.470742106437683,-20.793603897094727,40.90168762207031,1.764228184441952 +1.4061514139175415,-20.865375518798828,40.3992919921875,1.7776601604682765 +1.353446125984192,-20.92177391052246,40.032161712646484,1.7898519539030224 +1.2902671098709106,-20.987098693847656,39.6367073059082,1.807480827039549 +1.2334694862365723,-21.044857025146484,39.285743713378906,1.818806703820793 +1.175480604171753,-21.10378074645996,38.90486145019531,1.827594121190017 +1.1170316934585571,-21.16341781616211,38.48902893066406,1.8318958879568161 +1.057562232017517,-21.224437713623047,38.0286979675293,1.8365397197426483 +0.9948011636734009,-21.288925170898438,37.51163864135742,1.841112838040163 +0.9348889589309692,-21.349401473999023,37.0264892578125,1.852429832442088 +0.8717984557151794,-21.4111328125,36.55132293701172,1.863801826819622 +0.8111720681190491,-21.468441009521484,36.13509750366211,1.8716354738982752 +0.747210681438446,-21.527103424072266,35.728572845458984,1.877420995043547 +0.6823169589042664,-21.585817337036133,35.31387710571289,1.8814786737645268 +0.6174244284629822,-21.64447021484375,34.87185287475586,1.8854102741312897 +0.5518062710762024,-21.70393943786621,34.39155960083008,1.8892717734311688 +0.48592641949653625,-21.76299285888672,33.90359115600586,1.8951659578064677 +0.4223855435848236,-21.818483352661133,33.45779037475586,1.9015851666363448 +0.3476898968219757,-21.881494522094727,32.97788619995117,1.9042510901161702 +0.28215351700782776,-21.934961318969727,32.59307861328125,1.907782039403526 +0.2087024450302124,-21.993967056274414,32.16187286376953,1.914629002360818 +0.142167866230011,-22.047311782836914,31.746109008789062,1.918504784493579 +0.06967445462942123,-22.105600357055664,31.257474899291992,1.9192913994727379 +0.0027535902336239815,-22.15892791748047,30.7980899810791,1.905862973795668 +-0.0720045194029808,-22.216955184936523,30.31007194519043,1.910213360908608 +-0.14072714745998383,-22.268495559692383,29.89794921875,1.9017777793970985 +-0.2168441116809845,-22.32369041442871,29.48065185546875,1.8966732782139732 +-0.2881244421005249,-22.374469757080078,29.0931453704834,1.887226580693833 +-0.35367992520332336,-22.421077728271484,28.715728759765625,1.8761295094015022 +-0.4252195954322815,-22.47212791442871,28.270524978637695,1.864666539760494 +-0.49806055426597595,-22.52402114868164,27.792827606201172,1.8547341019860615 +-0.5755917429924011,-22.57802963256836,27.299739837646484,1.8481582707697715 +-0.645548939704895,-22.625112533569336,26.890018463134766,1.8421173168947238 +-0.7178667187690735,-22.672040939331055,26.505517959594727,1.8353594603218442 +-0.784631609916687,-22.714054107666016,26.176820755004883,1.827365211683744 +-0.8598839640617371,-22.760841369628906,25.80183219909668,1.8103247832575358 +-0.9331886768341064,-22.80646514892578,25.408647537231445,1.8065630789102898 +-1.0037769079208374,-22.85066032409668,24.996225357055664,1.7827506315968809 +-1.0754339694976807,-22.895545959472656,24.552734375,1.763657172714262 +-1.1455384492874146,-22.938549041748047,24.13050079345703,1.7820178015629888 +-1.2156535387039185,-22.980140686035156,23.73940658569336,1.7854711021648582 +-1.2910101413726807,-23.023149490356445,23.358461380004883,1.7838866188776636 +-1.3617522716522217,-23.06210708618164,23.03365135192871,1.7828853685690502 +-1.4369195699691772,-23.10289192199707,22.68629264831543,1.776452683283162 +-1.5076202154159546,-23.141321182250977,22.33591079711914,1.7664220117677643 +-1.5805110931396484,-23.181232452392578,21.94075584411621,1.7616366986920098 +-1.6514524221420288,-23.220226287841797,21.528003692626953,1.7549774226830988 +-1.7268807888031006,-23.260950088500977,21.094627380371094,1.7292705220151408 +-1.7960734367370605,-23.29706573486328,20.724937438964844,1.6956348921667643 +-1.864540457725525,-23.331445693969727,20.392881393432617,1.6578038536105 +-1.9323999881744385,-23.364261627197266,20.094797134399414,1.6551673917514644 +-2.0059521198272705,-23.39923858642578,19.771896362304688,1.661270905243047 +-2.075173854827881,-23.432247161865234,19.44388198852539,1.6945426101835068 +-2.1475484371185303,-23.46706771850586,19.06797218322754,1.7247462193363665 +-2.2224137783050537,-23.50328826904297,18.648527145385742,1.7557602583906653 +-2.287458896636963,-23.534265518188477,18.28643798828125,1.7731732280078862 +-2.369945526123047,-23.572200775146484,17.858047485351562,1.8142521609296642 +-2.4511022567749023,-23.60783576965332,17.477802276611328,1.8427512273165323 +-2.5261294841766357,-23.639415740966797,17.1588077545166,1.8703988089010062 +-2.6054768562316895,-23.672183990478516,16.822654724121094,1.8973083934947141 +-2.704738140106201,-23.71319007873535,16.36909294128418,1.8417731416165002 +-2.7957091331481934,-23.75111961364746,15.905965805053711,1.8569970507246303 +-2.8729727268218994,-23.78346061706543,15.48182201385498,1.8842975859365416 +-2.9564757347106934,-23.817672729492188,15.030352592468262,1.8426619106163094 +-3.0373988151550293,-23.849462509155273,14.623570442199707,1.7581137396417506 +-3.1054515838623047,-23.874969482421875,14.311781883239746,1.6660504243522432 +-3.1765081882476807,-23.90038299560547,14.017657279968262,1.5584089945672754 +-3.2405319213867188,-23.92255973815918,13.765670776367188,1.4546834747889057 +-3.3017919063568115,-23.94371795654297,13.512412071228027,1.3515273652896436 +-3.35870623588562,-23.963640213012695,13.254386901855469,1.2536053015182824 +-3.4118361473083496,-23.982519149780273,12.991644859313965,1.161547090328866 +-3.460120439529419,-23.999496459960938,12.752564430236816,1.0786463210264925 +-3.50498366355896,-24.014726638793945,12.545341491699219,1.0019020952487843 +-3.547145366668701,-24.028427124023438,12.369124412536621,0.9299452542561693 +-3.588334798812866,-24.04127311706543,12.212750434875488,0.8593518039464547 +-3.625654458999634,-24.0528507232666,12.067828178405762,0.7948045800081576 +-3.6589925289154053,-24.063398361206055,11.926030158996582,0.7368635537097608 +-3.690216541290283,-24.073543548583984,11.778462409973145,0.6823269245143112 +-3.719747304916382,-24.08336067199707,11.627368927001953,0.631124028782487 +-3.745223045349121,-24.091718673706055,11.499526977539062,0.5875329686381913 +-3.771474838256836,-24.10003089904785,11.377758026123047,0.5428175974219465 +-3.793288230895996,-24.10664939880371,11.286377906799316,0.5057269484583954 +-3.8168752193450928,-24.11351776123047,11.19754695892334,0.465543160174896 +-3.8362033367156982,-24.119117736816406,11.12417221069336,0.43230064376940364 +-3.854151725769043,-24.124435424804688,11.05000114440918,0.4012614058089586 +-3.8714683055877686,-24.12973403930664,10.970715522766113,0.37119376290080336 +-3.8877317905426025,-24.134845733642578,10.88977336883545,0.34308639370381555 +-3.90228533744812,-24.139379501342773,10.818501472473145,0.31822581563447727 +-3.9164538383483887,-24.143646240234375,10.754424095153809,0.2941452456185459 +-3.9290149211883545,-24.14727783203125,10.703320503234863,0.27283944119914655 +-3.9406025409698486,-24.150508880615234,10.660687446594238,0.2530981773100315 +-3.9514729976654053,-24.15354347229004,10.619684219360352,0.23439007318090807 +-3.9618802070617676,-24.15654182434082,10.57646656036377,0.21637463195640091 +-3.9713287353515625,-24.159374237060547,10.532793998718262,0.19993567202264265 +-3.9793522357940674,-24.161840438842773,10.492568016052246,0.18605676359912915 +-3.987630605697632,-24.164363861083984,10.451869010925293,0.17190405790354502 +-3.995246171951294,-24.166608810424805,10.41739273071289,0.15893230849980636 +-4.001948833465576,-24.16849708557129,10.390142440795898,0.147533117697683 +-4.008233547210693,-24.170217514038086,10.366969108581543,0.13678415646441092 +-4.013938903808594,-24.171781539916992,10.345512390136719,0.1269238261319837 +-4.019732475280762,-24.17342185974121,10.321659088134766,0.11685476713660366 +-4.02474308013916,-24.17490005493164,10.298704147338867,0.10809422769899049 +-4.028907775878906,-24.17617416381836,10.278189659118652,0.07423352806611556 +-4.031922340393066,-24.17709732055664,10.26382064819336,0.06501425457397852 +-4.034049987792969,-24.177711486816406,10.25298023223877,0.032189006977271964 +-4.035891532897949,-24.178239822387695,10.245654106140137,0.050917618998766075 +-4.037550926208496,-24.17868995666504,10.239013671875,0.01874983153092606 +-4.039291858673096,-24.17915916442871,10.232425689697266,0.04974394822983402 +-4.041110515594482,-24.17966079711914,10.22476863861084,0.025240247820159666 +-4.042971611022949,-24.18023109436035,10.218814849853516,0.05322146054098613 +-4.044921875,-24.1807804107666,10.206483840942383,0.04889517649169798 +-4.047163486480713,-24.181373596191406,10.188740730285645,0.08751066949727254 +-4.051187515258789,-24.182533264160156,10.170693397521973,0.08087969260562733 +-4.056458473205566,-24.18389320373535,10.138103485107422,0.14449912653507047 +-4.06461238861084,-24.18605613708496,10.110977172851562,0.2025915537329522 +-4.073638916015625,-24.188493728637695,10.082808494567871,0.26531685680684913 +-4.088762283325195,-24.192663192749023,10.02735424041748,0.36902759294407655 +-4.104351997375488,-24.196996688842773,9.950422286987305,0.3570396855364762 +-4.123240947723389,-24.202531814575195,9.860949516296387,0.3854947926442701 +-4.139398574829102,-24.207260131835938,9.782224655151367,0.40185619804258366 +-4.159069538116455,-24.212820053100586,9.690324783325195,0.474552297384872 +-4.182494640350342,-24.21919822692871,9.591592788696289,0.49901452313211725 +-4.206181526184082,-24.22535514831543,9.502346992492676,0.5465567240204229 +-4.230787754058838,-24.23166275024414,9.410720825195312,0.591008670937619 +-4.260349750518799,-24.23937225341797,9.293686866760254,0.6624566140858315 +-4.292945384979248,-24.248138427734375,9.148272514343262,0.7091706515796788 +-4.323844909667969,-24.25666618347168,8.998213768005371,0.7381419903809465 +-4.357935905456543,-24.265975952148438,8.835312843322754,0.7805256541228957 +-4.395599365234375,-24.27584457397461,8.668499946594238,0.8063694435640073 +-4.430506229400635,-24.284547805786133,8.528986930847168,0.8035642878371003 +-4.469738483428955,-24.29381561279297,8.387897491455078,0.8456163581339988 +-4.506221294403076,-24.302276611328125,8.257957458496094,0.8892968893464788 +-4.548532485961914,-24.312252044677734,8.09490966796875,0.9309083422537303 +-4.595370292663574,-24.32363510131836,7.893754959106445,0.9822548749075638 +-4.640315055847168,-24.33485984802246,7.682167053222656,1.0180645560761379 +-4.687265396118164,-24.346446990966797,7.461416244506836,1.0476467514591379 +-4.735307693481445,-24.35778045654297,7.250972747802734,1.0770373206991686 +-4.7818284034729,-24.368127822875977,7.06612491607666,1.0966820845072638 +-4.833702087402344,-24.37897491455078,6.881049633026123,1.1214597549607608 +-4.889867782592773,-24.390478134155273,6.680459499359131,1.1523026518073227 +-4.942326068878174,-24.40141487121582,6.4768853187561035,1.1585434677330513 +-4.990912914276123,-24.411823272705078,6.268248081207275,1.1801447225849375 +-5.046659469604492,-24.424083709716797,6.006409645080566,1.1967128974517458 +-5.100921630859375,-24.43589973449707,5.749212265014648,1.1990776065499142 +-5.157573699951172,-24.447601318359375,5.497859001159668,1.2260164834399907 +-5.215151309967041,-24.458675384521484,5.266669750213623,1.2487641854031284 +-5.26939582824707,-24.46837615966797,5.07057523727417,1.2640890526091946 +-5.329972267150879,-24.4788761138916,4.853471755981445,1.2778719051207603 +-5.391584396362305,-24.489715576171875,4.612275123596191,1.2824513893526994 +-5.449153423309326,-24.50017547607422,4.363137245178223,1.2686756666981112 +-5.50676155090332,-24.510936737060547,4.09088659286499,1.2602879824814546 +-5.565390110015869,-24.521684646606445,3.8124923706054688,1.2107918509403879 +-5.619035720825195,-24.53089714050293,3.5752906799316406,1.1883499634705166 +-5.669421672821045,-24.538881301879883,3.37253475189209,1.1490696245532193 +-5.723443508148193,-24.54672622680664,3.176236629486084,1.0950839972854722 +-5.773857116699219,-24.553781509399414,2.9939873218536377,1.027000847396116 +-5.8180460929870605,-24.56011199951172,2.8213281631469727,0.9543464450736949 +-5.860605239868164,-24.566503524780273,2.6375813484191895,0.864084080412578 +-5.89902400970459,-24.572534561157227,2.454925298690796,0.7904061316870911 +-5.932097434997559,-24.57769012451172,2.297891855239868,0.7156285304373727 +-5.9640045166015625,-24.582408905029297,2.1567158699035645,0.6331925550484296 +-5.993639945983887,-24.58641815185547,2.0383388996124268,0.5894201238958475 +-6.022618770599365,-24.589845657348633,1.9365317821502686,0.6260050044659466 +-6.051544189453125,-24.593141555786133,1.8370102643966675,0.6193849279998377 +-6.07899808883667,-24.59639549255371,1.7352204322814941,0.5942372725285537 +-6.104956150054932,-24.599660873413086,1.628556728363037,0.5254891530665148 +-6.127753257751465,-24.60274314880371,1.5283560752868652,0.43430884861960506 +-6.145346164703369,-24.605175018310547,1.4512969255447388,0.3750760335759959 +-6.162285804748535,-24.6074161529541,1.3814663887023926,0.325066437007935 +-6.175771236419678,-24.60906219482422,1.3321133852005005,0.29485609232159715 +-6.189050197601318,-24.610490798950195,1.2782953977584839,0.2662933020012526 +-6.20139217376709,-24.611745834350586,1.226525068283081,0.2813834763435498 +-6.21169900894165,-24.6129093170166,1.1927030086517334,0.26135506217963805 +-6.2277655601501465,-24.61482810974121,1.123085618019104,0.23502497532336772 +-6.24492073059082,-24.61698341369629,1.036115050315857,0.29397765226118167 +-6.2568230628967285,-24.61849594116211,0.9799736142158508,0.2792504458204181 +-6.269655704498291,-24.62003517150879,0.9262572526931763,0.2845633655228253 +-6.283536434173584,-24.621517181396484,0.8714669346809387,0.28611341412743696 +-6.296827793121338,-24.62281036376953,0.8245203495025635,0.29854802753694515 +-6.311770915985107,-24.62421417236328,0.7735827565193176,0.30421268816475716 +-6.32969856262207,-24.62602996826172,0.7047760486602783,0.44307780219761034 +-6.350906848907471,-24.628366470336914,0.6149119734764099,0.49324703667186703 +-6.375515460968018,-24.631269454956055,0.5017512440681458,0.5001731005877955 +-6.3976664543151855,-24.63382339477539,0.40195396542549133,0.48553028652903973 +-6.418871879577637,-24.63606071472168,0.3136012554168701,0.4620227406558798 +-6.441091060638428,-24.638139724731445,0.2307913601398468,0.43189508086221334 +-6.460279941558838,-24.639738082885742,0.16627156734466553,0.4031224708507715 +-6.478092670440674,-24.641231536865234,0.10463585704565048,0.3749609037706953 +-6.495153427124023,-24.642791748046875,0.03955157846212387,0.3472377293471655 +-6.510589599609375,-24.644344329833984,-0.026153564453125,0.32178168120836936 +-6.52384090423584,-24.645790100097656,-0.0876159518957138,0.2998961178033524 +-6.538036823272705,-24.647306442260742,-0.1525573581457138,0.2766671936712372 +-6.550079822540283,-24.64849090576172,-0.2036437690258026,0.25694680549666304 +-6.561429500579834,-24.649477005004883,-0.247039794921875,0.23834924733008256 +-6.57207727432251,-24.650297164916992,-0.28387451171875,0.22078578483248232 +-6.582433700561523,-24.651107788085938,-0.3204955756664276,0.20353485341216815 +-6.590869426727295,-24.651824951171875,-0.3532714545726776,0.18943481269590545 +-6.599375247955322,-24.65263557434082,-0.389801025390625,0.17517897919106787 +-6.607278347015381,-24.65345001220703,-0.4265136420726776,0.16201615110214143 +-6.61420202255249,-24.654144287109375,-0.45806875824928284,0.15060098488241558 +-6.621242523193359,-24.654794692993164,-0.48782339692115784,0.13900464377507118 +-6.627496719360352,-24.655302047729492,-0.511444091796875,0.12870517041603352 +-6.633181095123291,-24.65570831298828,-0.5309142470359802,0.11927261736356938 +-6.638544082641602,-24.65610122680664,-0.549896240234375,0.11028614908037052 +-6.643178939819336,-24.656484603881836,-0.5679625868797302,0.102485619999928 +-6.648092269897461,-24.65693473815918,-0.58917236328125,0.09418887264255431 +-6.652180194854736,-24.657344818115234,-0.6081237196922302,0.08733935369973818 +-6.656144142150879,-24.657724380493164,-0.6259766221046448,0.08074990902448462 +-6.6598663330078125,-24.65804672241211,-0.641357421875,0.0745653525756779 +-6.663083553314209,-24.658288955688477,-0.653228759765625,0.06920708199433397 +-6.666031837463379,-24.658493041992188,-0.6631469130516052,0.06425487404895756 +-6.668821811676025,-24.658687591552734,-0.6727600693702698,0.05952449498335128 +-6.671548366546631,-24.658903121948242,-0.6830443739891052,0.054878026350349066 +-6.67383337020874,-24.659101486206055,-0.692596435546875,0.0509649501577556 +-6.676220417022705,-24.65932846069336,-0.70343017578125,0.04689065799595478 +-6.678228378295898,-24.659513473510742,-0.7123717665672302,0.04349293661789628 +-6.680212020874023,-24.659687042236328,-0.7205504775047302,0.040166173516053415 +-6.6802802085876465,-24.659685134887695,-0.7214965224266052,2.1971302654013095e-05 +-6.6802802085876465,-24.659685134887695,-0.7214965224266052,7.974256771378921e-06 +-6.680281162261963,-24.659687042236328,-0.7214965224266052,1.0726585251881873e-05 +-6.680283069610596,-24.65968894958496,-0.7214965224266052,1.0606864067417775e-05 +-6.6802849769592285,-24.65968894958496,-0.7214965224266052,9.282086530010232e-06 +-6.680285930633545,-24.65968894958496,-0.7214965224266052,7.866050334140553e-06 +-6.6802873611450195,-24.659692764282227,-0.7214965224266052,6.408824697045821e-06 +-6.680288314819336,-24.659692764282227,-0.7214965224266052,6.399594392699264e-06 +-6.680289268493652,-24.659692764282227,-0.7214965224266052,5.813029502280846e-06 +-6.6802897453308105,-24.659692764282227,-0.7214965224266052,5.269419458922348e-06 +-6.6802897453308105,-24.659692764282227,-0.7214965224266052,4.661756219038743e-06 +-6.6802897453308105,-24.659692764282227,-0.7214965224266052,4.664968830550933e-06 +-6.6802897453308105,-24.659692764282227,-0.7214965224266052,4.077505060444136e-06 +-6.6802897453308105,-24.659692764282227,-0.7214965224266052,4.246998871771977e-06 +-6.6802897453308105,-24.659692764282227,-0.7214965224266052,4.343510055457155e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.950711759109512e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.130311273354063e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.6812038942647486e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.822642011618812e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.961332332602393e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.5948041119232486e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.4410767257035233e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.1735317799236225e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.855009187047146e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,4.0596237005396126e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.7869323273288417e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.4039457470527432e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.4204805363482244e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.8497204308547566e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,4.092022530643433e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.951958157886545e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.1957296975736317e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.171163376648024e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.2831260345413957e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,2.858112162389725e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.6270646279942795e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,4.071019051852974e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.999326268588749e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.3719976946353856e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.7628570853495613e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.916830041812058e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.8300330282882755e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.834936456894055e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.2605605580151776e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.501159200079774e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.523095408737704e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.7166528028939455e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.6854644822916163e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.4499364949614635e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.5339763085692366e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.651002833646259e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.541592155579457e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.1233703441368335e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,2.6957513567611745e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,2.267056053953093e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.9943266348185894e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,2.7210556677050176e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,4.292578337607997e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.7754158322574325e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.4903300707992775e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.930232066980359e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.643555207604843e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,2.6785539608097723e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,9.066986151126535e-07 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,4.919628523768845e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,1.548609713354891e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,4.66569733157279e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.924922754278775e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,4.415724993157912e-06 +-6.680290222167969,-24.659692764282227,-0.7214965224266052,3.537902596790962e-06 +-6.680294036865234,-24.65968132019043,-0.7231138944625854,0.0006270072920922254 +-6.680294036865234,-24.65972900390625,-0.7161864638328552,0.0007131011513346137 +-6.680263996124268,-24.659759521484375,-0.713409423828125,0.0008150448591076609 +-6.680233001708984,-24.659740447998047,-0.7164915800094604,0.0006708448123653507 +-6.680207252502441,-24.659772872924805,-0.7121581435203552,0.0007143249559555297 +-6.680202007293701,-24.659791946411133,-0.7112730145454407,0.00012812302841678922 +-6.68019437789917,-24.659820556640625,-0.7082518339157104,0.0003383885145540086 +-6.680190086364746,-24.65981101989746,-0.7101134657859802,0.00012396913222145783 +-6.6801886558532715,-24.659807205200195,-0.7114562392234802,0.00012141093840727472 +-6.680195331573486,-24.65984344482422,-0.7070922255516052,0.0005323844933376221 +-6.68022346496582,-24.65984344482422,-0.7083433270454407,0.0004817966428514313 +-6.680366516113281,-24.659914016723633,-0.702056884765625,0.00547149054935719 +3.5865566730499268,-12.266300201416016,76.80830383300781,0.001296792900925909 +3.5865917205810547,-12.266300201416016,76.80882263183594,0.0006782823688311171 +3.586618185043335,-12.266302108764648,76.80886840820312,0.0005875033581233764 +3.586636543273926,-12.266302108764648,76.80886840820312,0.00029128262022784144 +3.586644172668457,-12.266302108764648,76.80886840820312,0.000258776441559565 +3.5866472721099854,-12.266301155090332,76.80886840820312,0.00020430172827158125 +3.586650848388672,-12.266300201416016,76.80886840820312,0.00019496985370004175 +3.5866551399230957,-12.266297340393066,76.80886840820312,0.00017385972188864102 +3.586660623550415,-12.266294479370117,76.80886840820312,0.00014162496084598383 +3.586662769317627,-12.266292572021484,76.80886840820312,7.843707394903598e-05 +3.5866661071777344,-12.266291618347168,76.80886840820312,0.00020075218840045946 +3.5866682529449463,-12.266288757324219,76.80886840820312,7.156789365992215e-05 +3.586669921875,-12.266287803649902,76.80886840820312,0.00010990381574451157 +3.5866715908050537,-12.26628589630127,76.80886840820312,0.0002094589977626339 +3.586674928665161,-12.266284942626953,76.80886840820312,0.00018266858419775035 +3.586676597595215,-12.266283988952637,76.80886840820312,7.506145043490939e-05 +3.586676597595215,-12.266283988952637,76.80886840820312,0.0001769268342517243 +3.586679220199585,-12.26628303527832,76.80886840820312,0.0001175482386950452 +3.586679697036743,-12.266281127929688,76.80886840820312,0.00015381551703391955 +3.586681842803955,-12.266279220581055,76.80886840820312,0.00017338917770648142 +3.5866830348968506,-12.266278266906738,76.80886840820312,0.00011132107821443558 +3.5866847038269043,-12.266278266906738,76.80886840820312,8.252314152023198e-05 +3.5866854190826416,-12.266276359558105,76.80886840820312,0.0001529626648778132 +3.586686611175537,-12.266275405883789,76.80886840820312,0.0001083330604507203 +3.586688756942749,-12.266275405883789,76.80886840820312,6.252519176517551e-06 +3.586688756942749,-12.266275405883789,76.80886840820312,6.048277987808386e-06 +3.5866894721984863,-12.266276359558105,76.80886840820312,6.836342561725126e-06 +3.5866894721984863,-12.266276359558105,76.80886840820312,6.330314885496245e-06 +3.586688995361328,-12.266278266906738,76.80886840820312,6.107811738412447e-06 +3.586688995361328,-12.266278266906738,76.80886840820312,6.353331007178996e-06 +3.586688995361328,-12.266278266906738,76.80886840820312,5.431499615053055e-06 +3.586688995361328,-12.266278266906738,76.80886840820312,5.619491236303582e-06 +3.586688995361328,-12.266278266906738,76.80886840820312,5.9551447215398275e-06 +3.586688995361328,-12.266278266906738,76.80886840820312,6.038448554032687e-06 +3.5866894721984863,-12.266278266906738,76.80886840820312,6.030963233213203e-06 +3.5866894721984863,-12.266278266906738,76.80886840820312,6.0866956780276254e-06 +3.5866897106170654,-12.266278266906738,76.80886840820312,5.717804749027711e-06 +3.5866901874542236,-12.266278266906738,76.80886840820312,6.13642900655261e-06 +3.5866940021514893,-12.266278266906738,76.80886840820312,0.0016636224906478323 +3.5866987705230713,-12.266304969787598,76.80886840820312,0.00035781722842235326 +3.586707353591919,-12.266315460205078,76.80886840820312,0.00018823409494950983 +3.586664915084839,-12.266528129577637,76.80886840820312,0.005828157886437969 +3.58660626411438,-12.266801834106445,76.80886840820312,0.011564635058425967 +3.5865185260772705,-12.267204284667969,76.80886840820312,0.007881712015055865 +3.586378335952759,-12.267841339111328,76.80886840820312,0.010933978125468998 +3.586204767227173,-12.268617630004883,76.80882263183594,0.04542903111379707 +3.5857396125793457,-12.270642280578613,76.80876922607422,0.0443857383557257 +3.5853147506713867,-12.272489547729492,76.80876922607422,0.0405521071870541 +3.584927558898926,-12.274178504943848,76.80876922607422,0.04302027381285408 +3.5843515396118164,-12.276680946350098,76.80876922607422,0.04934112450841894 +3.5838098526000977,-12.279034614562988,76.80876922607422,0.05196457177764093 +3.583179473876953,-12.28176498413086,76.80874633789062,0.09505477307626851 +3.581951141357422,-12.287052154541016,76.80824279785156,0.14771698766385716 +3.5796337127685547,-12.29710578918457,76.81095123291016,0.2710030787461032 +3.5759854316711426,-12.31265640258789,76.80658721923828,0.41916697137182657 +3.5704729557037354,-12.336183547973633,76.80393981933594,0.5564793864382286 +3.563856840133667,-12.36436939239502,76.7979736328125,0.6938897250838669 +3.5555810928344727,-12.399807929992676,76.79741668701172,0.8009344952364574 +3.546694040298462,-12.437859535217285,76.7972640991211,0.9062434793580286 +3.5364482402801514,-12.481730461120605,76.79719543457031,1.0281290827337297 +3.5246825218200684,-12.532095909118652,76.7969741821289,1.1496159049853607 +3.511808395385742,-12.587203025817871,76.79679870605469,1.2630990211542195 +3.4977996349334717,-12.647162437438965,76.79679870605469,1.3702386591357834 +3.486954927444458,-12.693574905395508,76.79679870605469,1.431101392131906 +3.4723775386810303,-12.755961418151855,76.7964859008789,1.503559417916622 +3.4606142044067383,-12.806302070617676,76.7964859008789,1.5599639784104422 +3.4435982704162598,-12.879117965698242,76.79592895507812,1.6250071808091284 +3.4253573417663574,-12.957172393798828,76.79507446289062,1.689185985293975 +3.407402515411377,-13.034001350402832,76.79419708251953,1.742728766887152 +3.38885760307312,-13.113353729248047,76.79342651367188,1.7818461271600712 +3.370098829269409,-13.193618774414062,76.7925033569336,1.8048278574904353 +3.351651906967163,-13.272543907165527,76.79149627685547,1.8175925314225976 +3.337808847427368,-13.331770896911621,76.79084777832031,1.8235748905009805 +3.3184776306152344,-13.414474487304688,76.7898941040039,1.8195753103897347 +3.29978609085083,-13.494441986083984,76.7890625,1.7818163190160656 +3.2869515419006348,-13.549348831176758,76.7885971069336,1.4415445962252904 +3.275557518005371,-13.598088264465332,76.78816986083984,0.8222416727922888 +3.2710626125335693,-13.617318153381348,76.78802490234375,0.5761246347688864 +3.266312599182129,-13.637642860412598,76.78746032714844,0.3134694458532435 +3.264599323272705,-13.644978523254395,76.78712463378906,0.22739764831330173 +3.2624731063842773,-13.654109001159668,76.78665924072266,0.17525465037670546 +3.2609176635742188,-13.660797119140625,76.78624725341797,0.1359205454175897 +3.2596042156219482,-13.666451454162598,76.78596496582031,0.1093789732442982 +3.258450746536255,-13.671412467956543,76.7855453491211,0.1018105882066522 +3.2572805881500244,-13.67638111114502,76.78289031982422,0.11296562700921614 +3.2562403678894043,-13.68067455291748,76.78008270263672,0.09119529788892089 +3.2553486824035645,-13.684324264526367,76.7762680053711,0.08675067325393104 +3.254488945007324,-13.688010215759277,76.77664947509766,0.08378126003308313 +3.2534801959991455,-13.692378997802734,76.7769546508789,0.1080111395483584 +3.2525415420532227,-13.696429252624512,76.77682495117188,0.12539196592315122 +3.251236915588379,-13.70202350616455,76.77566528320312,0.12459547215876207 +3.2497026920318604,-13.708614349365234,76.7755355834961,0.13986922474436927 +3.2482473850250244,-13.714885711669922,76.77581024169922,0.14237274587507479 +3.2465946674346924,-13.721951484680176,76.77433013916016,0.22230957162144416 +3.24440336227417,-13.731446266174316,76.77723693847656,0.34156415668552054 +3.2416021823883057,-13.7434663772583,76.77770233154297,0.38422664567164067 +3.2371037006378174,-13.762723922729492,76.77666473388672,0.4833279912844458 +3.2315919399261475,-13.78615665435791,76.77092742919922,0.5600339698378831 +3.2252135276794434,-13.813356399536133,76.76890563964844,0.608016649566179 +3.219228506088257,-13.838991165161133,76.77131652832031,0.6720364941332309 +3.2139031887054443,-13.861690521240234,76.76979064941406,0.7229442772269443 +3.2084078788757324,-13.88512897491455,76.7698745727539,0.7628572172665321 +3.2002322673797607,-13.919983863830566,76.77264404296875,0.7979279141705992 +3.190796136856079,-13.960092544555664,76.77629852294922,0.8811338949645401 +3.1809659004211426,-14.001720428466797,76.7786865234375,0.9699597097423491 +3.1701884269714355,-14.04738998413086,76.78365325927734,1.0469787140638207 +3.161783456802368,-14.083003997802734,76.7870101928711,1.0936599465203611 +3.1506569385528564,-14.130168914794922,76.79114532470703,1.1316036817568138 +3.1415657997131348,-14.168754577636719,76.79354858398438,1.1601763322824996 +3.1287550926208496,-14.22324275970459,76.79368591308594,1.1884665918897706 +3.1166818141937256,-14.274807929992676,76.79302215576172,1.2186372531300715 +3.1029741764068604,-14.333338737487793,76.78800201416016,1.2619057765494768 +3.089390277862549,-14.391490936279297,76.7892074584961,1.3017494789774657 +3.075932502746582,-14.449089050292969,76.78959655761719,1.342497867392276 +3.060683488845825,-14.514362335205078,76.78999328613281,1.3769631676319907 +3.046637535095215,-14.57447624206543,76.7896957397461,1.3944679027936917 +3.032609462738037,-14.634510040283203,76.78926849365234,1.4196975595633476 +3.020892858505249,-14.684746742248535,76.79222869873047,1.4358707405741722 +3.005972146987915,-14.748613357543945,76.79164123535156,1.4595323519707044 +2.9908061027526855,-14.813573837280273,76.79267883300781,1.474740880832587 +2.979370355606079,-14.862510681152344,76.7915267944336,1.4792516609726425 +2.964219093322754,-14.92742919921875,76.79188537597656,1.12295231732472 +2.958085298538208,-14.953737258911133,76.79191589355469,0.7694635728383008 +2.9534695148468018,-14.973526000976562,76.79154205322266,0.4935103168386 +2.949754476547241,-14.989458084106445,76.79106903076172,0.25831324478742135 +2.947885274887085,-14.997478485107422,76.79061126708984,0.12678350964132107 +2.947018623352051,-15.001205444335938,76.7901382446289,0.051443527096195964 +2.9467670917510986,-15.002293586730957,76.78963470458984,0.017991825662802337 +2.946739673614502,-15.002424240112305,76.78909301757812,0.009381556724878604 +2.9468419551849365,-15.001993179321289,76.7888412475586,0.020109402935186194 +2.947096109390259,-15.000920295715332,76.78839874267578,0.02989538114173644 +2.947453260421753,-14.999406814575195,76.78789520263672,0.035585295819238034 +2.9478392601013184,-14.99776840209961,76.78740692138672,0.03834399824932677 +2.9482500553131104,-14.996024131774902,76.786865234375,0.039632676543989956 +2.948582887649536,-14.994617462158203,76.78638458251953,0.020600171095224613 +2.9486968517303467,-14.99415111541748,76.78602600097656,0.01028195352541902 +2.9488062858581543,-14.993711471557617,76.78557586669922,0.006760369701085813 +2.9488580226898193,-14.99351978302002,76.78515625,0.00044901975658971004 +2.9488165378570557,-14.99372386932373,76.78504180908203,0.011525032808654353 +2.948582649230957,-14.994756698608398,76.78484344482422,0.04099381997678346 +2.948132038116455,-14.99671459197998,76.7846908569336,0.04324591958096612 +2.947589635848999,-14.99907112121582,76.7846908569336,0.054023374105954265 +2.9464809894561768,-15.003886222839355,76.78517150878906,0.15532752298726624 +2.9448678493499756,-15.010866165161133,76.78572082519531,0.15875817553128138 +2.942389488220215,-15.021272659301758,76.77718353271484,0.28852725363098414 +2.938552141189575,-15.037768363952637,76.77935791015625,0.4239118042644404 +2.935059070587158,-15.052727699279785,76.77916717529297,0.4759085731747578 +2.931703805923462,-15.067110061645508,76.77836608886719,0.498625046064909 +2.9259233474731445,-15.091952323913574,76.78114318847656,0.5606517524517206 +2.9196887016296387,-15.11861515045166,76.7787094116211,0.658890343438466 +2.912569284439087,-15.14897632598877,76.77367401123047,0.7032917985631687 +2.906721353530884,-15.174057006835938,76.77507781982422,0.7629360618872751 +2.898514747619629,-15.209158897399902,76.77305603027344,0.828694763054745 +2.8896493911743164,-15.247175216674805,76.77449035644531,0.8673044870400936 +2.879641056060791,-15.28999137878418,76.77271270751953,0.9645699397780555 +2.8684799671173096,-15.33777141571045,76.77257537841797,1.0728333743760414 +2.8570621013641357,-15.386690139770508,76.77410888671875,1.1167002453193335 +2.845323085784912,-15.436901092529297,76.7723388671875,1.1829925789762477 +2.831942319869995,-15.494194984436035,76.77251434326172,1.2363240347421673 +2.818983316421509,-15.549689292907715,76.77287292480469,1.2774561226342405 +2.809504985809326,-15.590250968933105,76.7720718383789,1.3096964459439162 +2.795874834060669,-15.648591041564941,76.77143096923828,1.3403984316903237 +2.7803194522857666,-15.715185165405273,76.77096557617188,1.3509627476483204 +2.766791582107544,-15.773355484008789,76.77188110351562,1.2537809539826366 +2.756913900375366,-15.81537914276123,76.76925659179688,0.676293446100167 +2.7518770694732666,-15.836915016174316,76.76881408691406,0.35630715907250066 +2.749826669692993,-15.845698356628418,76.7684555053711,0.2120773897190801 +2.7483744621276855,-15.85192584991455,76.76809692382812,0.09018692731856842 +2.747859239578247,-15.854143142700195,76.76775360107422,0.021814249048810862 +2.747872829437256,-15.854098320007324,76.7671890258789,0.018118521550306153 +2.7481727600097656,-15.852823257446289,76.76670837402344,0.038333447462689 +2.7485952377319336,-15.851028442382812,76.7663803100586,0.039105621811408205 +2.748922109603882,-15.849651336669922,76.7659683227539,0.02247991969702081 +2.7490646839141846,-15.849055290222168,76.76570892333984,0.014956599471307805 +2.7490196228027344,-15.849268913269043,76.76536560058594,0.019997001358091834 +2.7488162517547607,-15.8501615524292,76.76466369628906,0.02332466906219712 +2.748441696166992,-15.851811408996582,76.76496887207031,0.036138120579505086 +2.7477095127105713,-15.854995727539062,76.76461791992188,0.10488092621865089 +2.7467916011810303,-15.858932495117188,76.76422882080078,0.1926112468648006 +2.744560480117798,-15.868582725524902,76.76549530029297,0.22251289973590374 +2.7415003776550293,-15.881546020507812,76.75933074951172,0.36201884938808737 +2.738372325897217,-15.894965171813965,76.76028442382812,0.42307654308208237 +2.7330985069274902,-15.9174222946167,76.75409698486328,0.5460411937406128 +2.726762533187866,-15.944537162780762,76.75288391113281,0.6661112745975016 +2.721691131591797,-15.966142654418945,76.74850463867188,0.753002129297716 +2.712550640106201,-16.00497817993164,76.74554443359375,0.9019168782363702 +2.702653408050537,-16.047475814819336,76.74404907226562,1.0175006146644114 +2.690896511077881,-16.097848892211914,76.7445068359375,1.1293455000736192 +2.678229570388794,-16.15196990966797,76.74384307861328,1.2597194931536242 +2.668663263320923,-16.19300079345703,76.74748229980469,1.3450838557987839 +2.654087543487549,-16.25532341003418,76.74628448486328,1.4546994913005573 +2.6435818672180176,-16.300222396850586,76.74519348144531,1.5243555629635712 +2.6314408779144287,-16.352134704589844,76.7451400756836,1.5933768825941006 +2.6200597286224365,-16.400835037231445,76.7450180053711,1.6495529983536006 +2.602179765701294,-16.47725486755371,76.74504852294922,1.7283292303627615 +2.589193344116211,-16.532773971557617,76.74504089355469,1.7799420493108757 +2.5697081089019775,-16.616092681884766,76.74506378173828,1.8503592740909387 +2.54988956451416,-16.700849533081055,76.7450942993164,1.8894195536967608 +2.5320558547973633,-16.77713966369629,76.74484252929688,1.3183858476321018 +2.522066593170166,-16.81989860534668,76.7444076538086,0.7480906971309269 +2.516322612762451,-16.84449577331543,76.743896484375,0.4034824412188218 +2.513353109359741,-16.857215881347656,76.7433090209961,0.21312604939197693 +2.51212739944458,-16.862468719482422,76.74315643310547,0.12667935595423205 +2.5112287998199463,-16.8663330078125,76.74271392822266,0.05084537069411234 +2.5109429359436035,-16.867570877075195,76.74232482910156,0.01203019015645298 +2.5109550952911377,-16.867530822753906,76.74178314208984,0.011814361655087206 +2.511152505874634,-16.86669921875,76.7413558959961,0.02438173318967784 +2.511453151702881,-16.865428924560547,76.7408218383789,0.031148496110801924 +2.5116608142852783,-16.86454963684082,76.74050903320312,0.03350353761818927 +2.5120420455932617,-16.86293601989746,76.74008178710938,0.03578430981611697 +2.5124399662017822,-16.86125373840332,76.73965454101562,0.03676242632739536 +2.5128445625305176,-16.859540939331055,76.73925018310547,0.03704068745957516 +2.5132269859313965,-16.857919692993164,76.73880767822266,0.03695626992167851 +2.5136024951934814,-16.856327056884766,76.73834991455078,0.03669419305792285 +2.513991117477417,-16.854679107666016,76.73806762695312,0.0363183985868192 +2.514392614364624,-16.852977752685547,76.73806762695312,0.03587041543189169 +2.514772891998291,-16.851364135742188,76.73806762695312,0.03541629470730517 +2.515042304992676,-16.850223541259766,76.73806762695312,0.03508572814450554 +2.515378475189209,-16.848800659179688,76.73806762695312,0.03466718043464071 +2.515666961669922,-16.847578048706055,76.73806762695312,0.04175283947362055 +2.5160348415374756,-16.846036911010742,76.73806762695312,0.03128887472770868 +2.5162618160247803,-16.845094680786133,76.73798370361328,0.014164025601953631 +2.5164146423339844,-16.84447479248047,76.73798370361328,0.009623219904153974 +2.516453266143799,-16.844329833984375,76.73798370361328,0.0021057272804942836 +2.5164692401885986,-16.84429168701172,76.73798370361328,0.004017820658540215 +2.5164172649383545,-16.84453773498535,76.73798370361328,0.009395730373179098 +2.516221046447754,-16.845415115356445,76.73795318603516,0.012887506204123707 +2.5160365104675293,-16.84623908996582,76.73795318603516,0.025029459463755777 +2.5157055854797363,-16.84768295288086,76.73795318603516,0.04352252638605551 +2.5153656005859375,-16.849159240722656,76.73795318603516,0.04625537762056787 +2.514707326889038,-16.852006912231445,76.73783111572266,0.08812640066112568 +2.5131053924560547,-16.858951568603516,76.7382583618164,0.19869888485649395 +2.5101068019866943,-16.871774673461914,76.73638916015625,0.3354457671127759 +2.5074567794799805,-16.883243560791016,76.74056243896484,0.40061727450767726 +2.5032830238342285,-16.901147842407227,76.74134826660156,0.4519927509523999 +2.497384786605835,-16.926355361938477,76.73966979980469,0.5826680880903807 +2.490924835205078,-16.954010009765625,76.7394790649414,0.6546761800724877 +2.485954523086548,-16.97528648376465,76.73944854736328,0.7226088628583882 +2.4773309230804443,-17.012197494506836,76.73932647705078,0.8189462913869374 +2.468179225921631,-17.051212310791016,76.74058532714844,0.9008729378402508 +2.457209825515747,-17.096837997436523,76.75428771972656,1.011849820580722 +2.445624828338623,-17.143199920654297,76.78739929199219,1.06815724087629 +2.4327006340026855,-17.19287109375,76.84544372558594,1.1681862883686527 +2.41694974899292,-17.25086784362793,76.94312286376953,1.2588639469383742 +2.4007408618927,-17.308269500732422,77.069091796875,1.2997984170665289 +2.3841590881347656,-17.364912033081055,77.22221374511719,1.3149723757129839 +2.3658578395843506,-17.42534637451172,77.41707611083984,1.2757808410117601 +2.34909725189209,-17.479028701782227,77.61759948730469,1.2133921702210915 +2.332564115524292,-17.530494689941406,77.83638000488281,1.140069810302857 +2.316692352294922,-17.578611373901367,78.0655288696289,1.0644133357898549 +2.3010993003845215,-17.624675750732422,78.30906677246094,0.988040884420619 +2.2873647212982178,-17.664270401000977,78.53857421875,0.9204350810116941 +2.272608995437622,-17.70579719543457,78.80113220214844,0.8482514227324219 +2.260516881942749,-17.739038467407227,79.02880096435547,0.7897084184487587 +2.2476303577423096,-17.77366828918457,79.28410339355469,0.7282994664383631 +2.2368969917297363,-17.80188751220703,79.50662231445312,0.6779338147050014 +2.2258005142211914,-17.830429077148438,79.7464370727539,0.626727118333647 +2.2160942554473877,-17.854854583740234,79.96461486816406,0.5827059815362672 +2.2058093547821045,-17.880170822143555,80.20439910888672,0.5369426741346811 +2.19675874710083,-17.90195083618164,80.42280578613281,0.49741982981173793 +2.188734769821167,-17.92093276977539,80.62165069580078,0.4631748636147365 +2.1803293228149414,-17.940921783447266,80.8316879272461,0.4279164863574825 +2.1734726428985596,-17.957683563232422,81.002197265625,0.39862175334302385 +2.1669692993164062,-17.974130630493164,81.162353515625,0.3698327590698243 +2.1613004207611084,-17.988792419433594,81.30186462402344,0.3437450467392364 +2.1558706760406494,-18.002784729003906,81.43761444091797,0.31853997086937014 +2.1506965160369873,-18.01596450805664,81.56935119628906,0.2949402398717112 +2.1458017826080322,-18.028484344482422,81.6946029663086,0.2728838651932177 +2.1414248943328857,-18.039875030517578,81.806396484375,0.25290186194272396 +2.137441635131836,-18.05045509338379,81.90772247314453,0.2343156407480835 +2.133780002593994,-18.060287475585938,82.00114440917969,0.21686416448711024 +2.1303579807281494,-18.06941795349121,82.08928680419922,0.20055822871214032 +2.1273422241210938,-18.077415466308594,82.16775512695312,0.18639201402255356 +2.124295711517334,-18.085567474365234,82.24710845947266,0.1720760559315728 +2.1218085289001465,-18.092321395874023,82.31185150146484,0.16021854552214249 +2.1193416118621826,-18.099071502685547,82.3760757446289,0.14827351072821496 +2.1170713901519775,-18.105276107788086,82.43543243408203,0.137264186786052 +2.115070343017578,-18.11073875427246,82.48808288574219,0.12758930629444992 +2.1130616664886475,-18.11624526977539,82.54098510742188,0.11787148887581221 +2.111306667327881,-18.12108039855957,82.58726501464844,0.10932445056078118 +2.1096913814544678,-18.12553596496582,82.62991333007812,0.10142777540098194 +2.1081278324127197,-18.129854202270508,82.67134857177734,0.09377869186968216 +2.1067025661468506,-18.133800506591797,82.70919799804688,0.08678468309028056 +2.1054306030273438,-18.1373348236084,82.74284362792969,0.08053355338018811 +2.104264736175537,-18.140602111816406,82.77363586425781,0.07476879428759771 +2.1030964851379395,-18.143888473510742,82.80445861816406,0.06891858750374798 +2.1021389961242676,-18.146574020385742,82.829833984375,0.06411679776583247 +2.101179361343384,-18.14924430847168,82.85538482666016,0.059338927723637615 +2.1002750396728516,-18.15176773071289,82.87944030761719,0.05486096924863183 +2.0994184017181396,-18.1541805267334,82.9021987915039,0.05057737187844386 +2.098757028579712,-18.156064987182617,82.91967010498047,0.0472227575360067 +2.0985584259033203,-18.156644821166992,82.92622375488281,0.00038997035256300994 +2.0985543727874756,-18.156654357910156,82.92622375488281,5.33476713367658e-05 +2.0985515117645264,-18.156658172607422,82.92622375488281,1.7160001462082918e-05 +2.09854793548584,-18.156660079956055,82.92622375488281,1.371056897523031e-05 +2.0985453128814697,-18.15666389465332,82.92622375488281,1.0226722780523197e-05 +2.098543405532837,-18.156665802001953,82.92622375488281,9.666057619139744e-06 +2.0985419750213623,-18.156667709350586,82.92622375488281,8.843294922455857e-06 +2.098541259765625,-18.15666961669922,82.92622375488281,7.286353901918717e-06 +2.0985405445098877,-18.15667152404785,82.92622375488281,5.59720328919744e-06 +2.0985400676727295,-18.15667152404785,82.92622375488281,6.052178834412621e-06 +2.0985395908355713,-18.15667152404785,82.92622375488281,6.2846812638503834e-06 +2.098538875579834,-18.156673431396484,82.92622375488281,6.267268326359795e-06 +2.098538875579834,-18.156673431396484,82.92622375488281,5.305999717462146e-06 +2.098538875579834,-18.156673431396484,82.92622375488281,5.6446832958865364e-06 +2.098538637161255,-18.156673431396484,82.92622375488281,5.190297206409413e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.217803275024628e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.293496407109716e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.173282615662774e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.330061145407824e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.037977148900511e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,4.141191460324711e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.186868077377051e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.534524592009113e-06 +2.098538637161255,-18.156675338745117,82.92622375488281,5.263793093894395e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.829644697455715e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.993836146349212e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,3.4197257614942452e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.630838540854539e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.639557659073222e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.175846102787967e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.918723158878564e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.833432225965406e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.2138999422518925e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.365214518733655e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.1943522357464506e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.866336825182007e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.871145145457616e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.1213963915813195e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.41161903939524e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.38577753296264e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.92759618040467e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.735045350697049e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.604979921484948e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.307942362360267e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.379019513886474e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.97931279042091e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.0287895985540545e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.89565992140001e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.3191694322536795e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.380066399033005e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.4190325218243806e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.370654752718072e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,3.1816868082933084e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,6.573668480191794e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.806709070873665e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.478231212551932e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.738316749991584e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.5304768614335365e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.238260799280769e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.243223394744191e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.538539061587981e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.276111038333353e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.092948301539821e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.337401986991017e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.374076109120341e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.696506355731002e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.248291547462753e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.116398941098988e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.26742938941546e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.4354924293021445e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.238234846898804e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.8088123428042295e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.357095792753729e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.142604903133988e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.117986576681713e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.403712663751088e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.002668596726903e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,4.8091753217668615e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.362976956969357e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,2.425062720712594e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.336392485920799e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.02556362129789e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.02585498030166e-06 +2.098538398742676,-18.156675338745117,82.92622375488281,5.272597626368591e-06 +2.0985419750213623,-18.15666389465332,82.92533874511719,0.0034208603339910583 +2.098507881164551,-18.156803131103516,82.92684936523438,0.00851094751008746 +2.098503828048706,-18.15684700012207,82.92605590820312,0.01384298065925131 +2.098505735397339,-18.1568546295166,82.92462921142578,0.009943336926074542 +2.098423719406128,-18.157115936279297,82.92833709716797,0.01591865006176935 +2.0982511043548584,-18.15765380859375,82.9381332397461,0.026117040133139046 +2.0978634357452393,-18.158720016479492,82.9446792602539,0.012602995306463133 +2.0975353717803955,-18.159740447998047,82.95526885986328,0.03734242867904699 +2.0972208976745605,-18.160768508911133,82.96631622314453,0.013450575048733029 +2.096898078918457,-18.16170310974121,82.97509002685547,0.030075392768206012 +2.0961432456970215,-18.16390609741211,82.99578857421875,0.06236964301361094 +2.0950725078582764,-18.1669921875,83.02484893798828,0.07624042123838104 +2.093820333480835,-18.170583724975586,83.0586929321289,0.0800987101376688 +2.0925967693328857,-18.174089431762695,83.09180450439453,0.07881279576188603 +2.0914111137390137,-18.177490234375,83.12384033203125,0.07527521294046219 +2.090327024459839,-18.180604934692383,83.1531753540039,0.07097228976910118 +2.0892512798309326,-18.183698654174805,83.18233489990234,0.06613019709592487 +2.0882740020751953,-18.186513900756836,83.20890045166016,0.06143894145247357 +2.087446451187134,-18.188901901245117,83.23126983642578,0.05733295455948907 +2.0865840911865234,-18.19139289855957,83.25473022460938,0.05297187066063549 +2.085845708847046,-18.193532943725586,83.27486419677734,0.049190893849289555 +2.085106372833252,-18.195676803588867,83.2950439453125,0.045379580649938536 +2.0844790935516357,-18.19749641418457,83.31211853027344,0.04212737876391237 +2.0838494300842285,-18.19932746887207,83.32933807373047,0.038849495295660154 +2.0832812786102295,-18.20098304748535,83.34485626220703,0.0358785479212506 +2.0827674865722656,-18.202478408813477,83.35887145996094,0.03318261674115562 +2.082310676574707,-18.20380973815918,83.37129974365234,0.030774417756884404 +2.081878900527954,-18.2050724029541,83.38312530517578,0.028489342438702277 +2.081472396850586,-18.206262588500977,83.39427947998047,0.0263290910987862 +2.081082820892334,-18.20741081237793,83.40496063232422,0.024248835573686893 +2.08075213432312,-18.208398818969727,83.41395568847656,0.02245761149760103 +2.08064866065979,-18.20870018005371,83.4173583984375,0.0041549189783537345 +2.080589771270752,-18.208866119384766,83.41680145263672,0.004112146845008486 +2.08052396774292,-18.209108352661133,83.41838836669922,0.005906090210341562 +2.0804550647735596,-18.209430694580078,83.42323303222656,0.00964571520125049 +2.0802619457244873,-18.210063934326172,83.4254379272461,0.018597357235263644 +2.080010414123535,-18.211111068725586,83.43568420410156,0.026601788646033086 +2.0796334743499756,-18.21246910095215,83.44065856933594,0.03668649302463393 +2.078752040863037,-18.216163635253906,83.4692611694336,0.09802515062405566 +2.0771734714508057,-18.222938537597656,83.51725769042969,0.2184593654944376 +2.0738673210144043,-18.237192153930664,83.60330963134766,0.3079326814868511 +2.0702264308929443,-18.253257751464844,83.69454956054688,0.4441856641125493 +2.0650477409362793,-18.276817321777344,83.81204986572266,0.5919662100296444 +2.058150291442871,-18.309024810791016,83.95144653320312,0.7533942967231857 +2.0503995418548584,-18.347126007080078,84.1166000366211,0.9277022320751892 +2.041090488433838,-18.393829345703125,84.30268096923828,1.1210505026492654 +2.0293984413146973,-18.454837799072266,84.54255676269531,1.3527129392805195 +2.017692804336548,-18.518558502197266,84.78119659423828,1.5174285553222195 +2.0044467449188232,-18.59441375732422,85.05218505859375,1.6499607555348372 +1.992066740989685,-18.668420791625977,85.30555725097656,1.693686951226583 +1.9798667430877686,-18.745256423950195,85.55488586425781,1.6896934735316562 +1.9677842855453491,-18.826208114624023,85.79900360107422,1.6275302726760785 +1.9592957496643066,-18.887466430664062,85.97067260742188,1.5571255398616244 +1.9488574266433716,-18.966503143310547,86.1776351928711,1.4476535433527242 +1.9383033514022827,-19.05228042602539,86.38536834716797,1.316828716491015 +1.9312381744384766,-19.11391258239746,86.51889038085938,1.2185310618087573 +1.9256184101104736,-19.16783332824707,86.62141418457031,1.131311157810729 +1.9209210872650146,-19.21608543395996,86.70231628417969,1.0529977171211713 +1.9164903163909912,-19.264734268188477,86.77383422851562,0.9737683640493712 +1.9129072427749634,-19.307373046875,86.82608032226562,0.9041807125880307 +1.9098594188690186,-19.347341537475586,86.86347961425781,0.8388474549426348 +1.9073786735534668,-19.384357452392578,86.88607025146484,0.7214060623380699 +1.9060015678405762,-19.41042709350586,86.88972473144531,0.42557384293841427 +1.905191421508789,-19.42609214782715,86.88961791992188,0.26336767907298536 +1.9048105478286743,-19.437456130981445,86.88064575195312,0.22803022586979974 +1.904670238494873,-19.447246551513672,86.86529541015625,0.2035408062126009 +1.9045429229736328,-19.458681106567383,86.84595489501953,0.17965667053983456 +1.9044290781021118,-19.4674072265625,86.83194732666016,0.16350841183301384 +1.904338002204895,-19.47420883178711,86.82102966308594,0.1516356443139878 +1.9042408466339111,-19.480995178222656,86.81037139892578,0.14015163039052547 +1.904136061668396,-19.48769760131836,86.8001937866211,0.1290191781906995 +1.904029369354248,-19.49311637878418,86.79263305664062,0.12011930113172685 +1.9039008617401123,-19.498586654663086,86.78585052490234,0.1111770974779326 +1.9037597179412842,-19.50366973876953,86.7804183959961,0.10287927022875869 +1.9036037921905518,-19.508344650268555,86.77643585205078,0.09525318500175638 +1.903414249420166,-19.512624740600586,86.77476501464844,0.07513298247952457 +1.9032779932022095,-19.515140533447266,86.77476501464844,0.04609639935291263 +1.903189778327942,-19.516786575317383,86.77476501464844,0.02831111555406421 +1.9031341075897217,-19.51783561706543,86.77476501464844,0.018114743210892632 +1.903097152709961,-19.518529891967773,86.77476501464844,0.012394772765835352 +1.9030779600143433,-19.519020080566406,86.77476501464844,0.009341817185479278 +1.90306556224823,-19.5194149017334,86.77476501464844,0.00753042192107951 +1.903056025505066,-19.51976776123047,86.77476501464844,0.006338390805404437 +1.9030474424362183,-19.520036697387695,86.77476501464844,0.005631643234297587 +1.903036117553711,-19.520282745361328,86.77476501464844,0.004060049108432226 +1.9030290842056274,-19.520427703857422,86.77476501464844,0.0023775470139625336 +1.9030249118804932,-19.520511627197266,86.77476501464844,0.0014206778845748695 +1.903024673461914,-19.52051544189453,86.77476501464844,6.47128847796273e-06 +1.9030249118804932,-19.52051544189453,86.77476501464844,7.030249940737782e-06 +1.9030249118804932,-19.520517349243164,86.77476501464844,6.762337571856438e-06 +1.9030250310897827,-19.520519256591797,86.77476501464844,6.5478704255725555e-06 +1.9030250310897827,-19.520519256591797,86.77476501464844,5.480251473527919e-06 +1.9030250310897827,-19.520519256591797,86.77476501464844,6.7289398381516654e-06 +1.9030250310897827,-19.520519256591797,86.77476501464844,6.689461175331779e-06 +1.9030250310897827,-19.520519256591797,86.77476501464844,6.498174957027576e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.332610465437968e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.12399762528834e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,5.761772069038652e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.539648600642528e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.429748411220847e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.586015856380475e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.099801798664155e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,5.6130106138957566e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.4239034906479025e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.33297959376325e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,4.83053509262728e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.506492576623639e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,5.491717795116453e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.144407274768378e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.417680668211266e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.562091697756859e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.578227763485529e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,4.7520522934330814e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.1248107851965886e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,5.269654712365213e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,5.686186693339504e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.606688643272328e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.2597876179575835e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.608468964373798e-06 +1.9030250310897827,-19.52052116394043,86.77476501464844,6.279298995897825e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.257600566069732e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.00165381132452e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.136678130725691e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.4954689590441224e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.996009543328327e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,4.469272678215116e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.098537300521195e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.291208271011122e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.911246135375871e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.8721682585253274e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.066357462888098e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,6.091019578095631e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.905500989392857e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.87123993025164e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.759984649920618e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.223660897971592e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.280329399109475e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.2846668436611385e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.416584705944524e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.3971678464406285e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.694628002724665e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.205308650673993e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.238692391724465e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.42813111277179e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.523730446205259e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.650979552759885e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.608243024605693e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.68445385894745e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.3104470093557206e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.208021066113616e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.6480765060869025e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.981800608552784e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.989012883385076e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,4.8816196378682155e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.540525897367984e-06 +1.9030251502990723,-19.52052116394043,86.77476501464844,5.673865391828921e-06 +1.9030323028564453,-19.520545959472656,86.77522277832031,0.012252307005737918 +1.902897596359253,-19.521160125732422,86.78086853027344,0.026655300484336484 +1.9028265476226807,-19.521503448486328,86.78337860107422,0.014484609654479143 +1.9029040336608887,-19.52127456665039,86.7811050415039,0.014526689488786602 +1.9032707214355469,-19.519838333129883,86.76681518554688,0.028514834747865977 +1.904256820678711,-19.516042709350586,86.73033142089844,0.11672810280661312 +1.9061208963394165,-19.5087890625,86.66124725341797,0.21161231978469833 +1.9087324142456055,-19.498905181884766,86.57495880126953,0.29500231401259874 +1.913773775100708,-19.480205535888672,86.41146087646484,0.3569061426224236 +1.919973611831665,-19.4576358795166,86.20433044433594,0.47310311613460543 +1.9267148971557617,-19.433774948120117,85.99121856689453,0.5814239961529142 +1.934828281402588,-19.405261993408203,85.73031616210938,0.69105337270451 +1.9440034627914429,-19.373653411865234,85.44463348388672,0.7884134567052753 +1.955910325050354,-19.333635330200195,85.08026885986328,0.8948060808272641 +1.967863917350769,-19.294784545898438,84.72063446044922,0.9855946635986644 +1.9822531938552856,-19.24946403503418,84.29295349121094,1.083479290806407 +1.9995156526565552,-19.196590423583984,83.79603576660156,1.1889134447021452 +2.016637086868286,-19.145610809326172,83.31492614746094,1.27334668368572 +2.03643536567688,-19.088455200195312,82.77213287353516,1.3722855805400496 +2.0579288005828857,-19.02863121032715,82.2002182006836,1.4613386494377592 +2.0825488567352295,-18.963022232055664,81.56214904785156,1.5425585346445152 +2.1099727153778076,-18.892440795898438,80.8619384765625,1.6387144252628443 +2.1400489807128906,-18.818248748779297,80.11707305908203,1.724781715627415 +2.1715242862701416,-18.7435359954834,79.3623046875,1.7688634112633266 +2.2034664154052734,-18.670591354370117,78.61663818359375,1.7785816512462345 +2.2388908863067627,-18.59297752380371,77.81510925292969,1.7686441561199757 +2.2726712226867676,-18.52139663696289,77.07532501220703,1.7494232461517487 +2.309357166290283,-18.445819854736328,76.29833221435547,1.7230492581345558 +2.34567928314209,-18.372785568237305,75.55628967285156,1.6943823920355345 +2.3809006214141846,-18.303464889526367,74.86469268798828,1.6658028730885819 +2.4127771854400635,-18.24146270751953,74.2636489868164,1.639879810627995 +2.4492409229278564,-18.170879364013672,73.60919189453125,1.6102098640830573 +2.4830398559570312,-18.105478286743164,73.03510284423828,1.5821620151785583 +2.515690326690674,-18.04239273071289,72.50736999511719,1.5544535407647073 +2.54754376411438,-17.98097801208496,72.01629638671875,1.5273982493190776 +2.5800137519836426,-17.918289184570312,71.5417709350586,1.4998096477684626 +2.6126339435577393,-17.8550968170166,71.09173583984375,1.471825735897316 +2.6428542137145996,-17.796367645263672,70.69725799560547,1.4456375982954635 +2.673473834991455,-17.736555099487305,70.32097625732422,1.4190422056064913 +2.702613353729248,-17.679197311401367,69.98558044433594,1.3934788841742942 +2.730910539627075,-17.62308692932129,69.68030548095703,1.3683135244943718 +2.7585854530334473,-17.567813873291016,69.40047454833984,1.3434390958253375 +2.7893788814544678,-17.505849838256836,69.11004638671875,1.3154899456683056 +2.815345048904419,-17.45319175720215,68.88229370117188,1.291689552834842 +2.8421967029571533,-17.398332595825195,68.6626968383789,1.2668314721385407 +2.8664186000823975,-17.34859275817871,68.47627258300781,1.2441535802313757 +2.890702486038208,-17.298635482788086,68.29779052734375,1.2212667389230798 +2.917018175125122,-17.24457550048828,68.11100769042969,1.1963620016094487 +2.941634178161621,-17.194326400756836,67.93827819824219,1.1730307678719258 +2.964498281478882,-17.148035049438477,67.77810668945312,1.1515667855594454 +2.987997055053711,-17.100635528564453,67.61736297607422,1.1297601561693098 +3.017251491546631,-17.041364669799805,67.43064880371094,1.10276405776745 +3.041823625564575,-16.99086570739746,67.29237365722656,1.0798763192655385 +3.0628597736358643,-16.946910858154297,67.18999481201172,1.059985192082493 +3.0820260047912598,-16.906179428100586,67.11036682128906,1.022940258212906 +3.1022069454193115,-16.862462997436523,67.04316711425781,1.0312070627084275 +3.122741937637329,-16.8168888092041,66.99461364746094,1.0217361445621107 +3.1439101696014404,-16.768657684326172,66.96634674072266,1.0665220774485056 +3.1641674041748047,-16.721332550048828,66.95885467529297,1.1307759031012752 +3.182704210281372,-16.677091598510742,66.9671859741211,1.18753628696911 +3.204963207244873,-16.62273597717285,66.99662780761719,1.244989587277826 +3.228034019470215,-16.564172744750977,67.06291198730469,1.313294552465979 +3.2492904663085938,-16.507631301879883,67.16239929199219,1.363440050656093 +3.2722420692443848,-16.444353103637695,67.30059051513672,1.4237191845250339 +3.2947912216186523,-16.38054656982422,67.45419311523438,1.4820218651544643 +3.3170418739318848,-16.315879821777344,67.62510681152344,1.532293880704522 +3.3402035236358643,-16.246538162231445,67.82608032226562,1.5873049471277945 +3.3630526065826416,-16.176225662231445,68.04020690917969,1.6349579407766572 +3.3886539936065674,-16.09650993347168,68.27877807617188,1.6890662952965556 +3.4134418964385986,-16.01897621154785,68.50373077392578,1.7431204898776713 +3.4387505054473877,-15.939590454101562,68.72470092773438,1.7942569267583053 +3.4640514850616455,-15.860038757324219,68.93608856201172,1.8481977482985688 +3.490711212158203,-15.775054931640625,69.15833282470703,1.9028943592898127 +3.5167558193206787,-15.691075325012207,69.37743377685547,1.9549467004376326 +3.5448379516601562,-15.599005699157715,69.61813354492188,2.008662552568182 +3.5693469047546387,-15.51786994934082,69.83059692382812,2.0515384827302308 +3.6003944873809814,-15.41330623626709,70.10391235351562,2.0707391022907364 +3.6263210773468018,-15.324506759643555,70.33563995361328,2.061911630565524 +3.652156352996826,-15.23463249206543,70.56999206542969,2.040139425703284 +3.6784050464630127,-15.141834259033203,70.81170654296875,2.0099309547963005 +3.7030465602874756,-15.053288459777832,71.04222106933594,1.9769179085542337 +3.727691888809204,-14.963288307189941,71.27640533447266,1.9409913994212857 +3.7507033348083496,-14.877901077270508,71.49839782714844,1.9056489964709986 +3.7731218338012695,-14.793375015258789,71.71788024902344,1.86135610273145 +3.7961010932922363,-14.70536994934082,71.9497299194336,1.7794482734333277 +3.8158178329467773,-14.628541946411133,72.1497573852539,1.7088208020877607 +3.8347883224487305,-14.553520202636719,72.34434509277344,1.6465525243066241 +3.853302240371704,-14.47927188873291,72.5368881225586,1.5836788763662424 +4.471732139587402,-13.8590087890625,69.36817932128906,0.009769031521579931 +4.471998691558838,-13.85831069946289,69.36817932128906,0.0244713478827367 +4.4725341796875,-13.856895446777344,69.36817932128906,0.06334061072607466 +4.473565578460693,-13.854153633117676,69.36817932128906,0.07254662358009763 +4.474843502044678,-13.850791931152344,69.37112426757812,0.12202251978943802 +4.47711181640625,-13.844761848449707,69.37284851074219,0.1523666760419336 +4.478782653808594,-13.840274810791016,69.3726806640625,0.18685558339433941 +4.481098651885986,-13.834054946899414,69.37156677246094,0.2398392962491228 +4.485377311706543,-13.82258129119873,69.3696517944336,0.2974620320847745 +4.490234375,-13.809597969055176,69.37004852294922,0.3026795540704853 +4.496462345123291,-13.792991638183594,69.37216186523438,0.3856787474429188 +4.503407001495361,-13.774559020996094,69.37918090820312,0.43857884171557693 +4.510702133178711,-13.755105972290039,69.38198852539062,0.49686562483155833 +4.519593238830566,-13.73132038116455,69.38198852539062,0.5325909713537036 +4.528144836425781,-13.708438873291016,69.38198852539062,0.5462259041534928 +4.537312984466553,-13.683907508850098,69.38198852539062,0.5495165489540811 +4.545633792877197,-13.66164493560791,69.38198852539062,0.5469548512133605 +4.554481029510498,-13.63797378540039,69.38198852539062,0.5403679265627166 +4.560883522033691,-13.620842933654785,69.38200378417969,0.5354102157460741 +4.569089889526367,-13.598886489868164,69.38200378417969,0.5273287250910216 +4.57560920715332,-13.58144474029541,69.38198852539062,0.5204319486507578 +4.583155155181885,-13.56125545501709,69.38198852539062,0.5121239896052258 +4.591978549957275,-13.53764820098877,69.38198852539062,0.5021392059513052 +4.600086688995361,-13.515958786010742,69.38198852539062,0.4928168913531657 +4.608048439025879,-13.494657516479492,69.38198852539062,0.4835869256274102 +4.613292217254639,-13.48062515258789,69.38198852539062,0.4774830719946154 +4.620947360992432,-13.460144996643066,69.38198852539062,0.4685541876513983 +4.628430366516113,-13.440126419067383,69.38198852539062,0.45981476885261574 +4.633928298950195,-13.425419807434082,69.38198852539062,0.45339159361850123 +4.641308784484863,-13.40567398071289,69.38198852539062,0.44476621482535245 +4.6487345695495605,-13.385809898376465,69.38198852539062,0.4360919998557905 +4.6534223556518555,-13.373269081115723,69.38198852539062,0.43061595077225623 +4.660166263580322,-13.355226516723633,69.38198852539062,0.42274188535698404 +4.666738510131836,-13.337647438049316,69.38198852539062,0.4150723400368983 +4.673628330230713,-13.319215774536133,69.38198852539062,0.4070367545519245 +4.6800971031188965,-13.301908493041992,69.38198852539062,0.39949574051493447 +4.686613082885742,-13.284476280212402,69.38198852539062,0.39190393229325116 +4.69260835647583,-13.268437385559082,69.38198852539062,0.3849188492915184 +4.699124336242676,-13.251005172729492,69.38198852539062,0.3773268800817952 +4.705079078674316,-13.235076904296875,69.38198852539062,0.370394198599682 +4.709653377532959,-13.222843170166016,69.38198852539062,0.3650715542853978 +4.715339183807373,-13.207633018493652,69.38198852539062,0.3584600671509354 +4.721335411071777,-13.191596031188965,69.38198852539062,0.3514921899887415 +4.726973056793213,-13.176519393920898,69.38198852539062,0.3449456246502287 +4.732321262359619,-13.162214279174805,69.38198852539062,0.33873925599288257 +4.736330986022949,-13.151490211486816,69.38198852539062,0.3340891631754445 +4.741618633270264,-13.137347221374512,69.38198852539062,0.32795985304784697 +4.74527645111084,-13.1275634765625,69.38198852539062,0.32372192174615316 +4.750685691833496,-13.113093376159668,69.38198852539062,0.31745947377562483 +4.755634784698486,-13.099858283996582,69.38198852539062,0.31173431190634115 +4.759239673614502,-13.090216636657715,69.38198852539062,0.3075671434793834 +4.764055252075195,-13.077336311340332,69.38198852539062,0.30200303339432594 +4.768791675567627,-13.064666748046875,69.38198852539062,0.2965342556872873 +4.772238731384277,-13.055447578430176,69.38198852539062,0.29255719516369927 +4.777002334594727,-13.042705535888672,69.38198852539062,0.287064989424151 +4.781467437744141,-13.030762672424316,69.38198852539062,0.28192125784318034 +4.785968780517578,-13.018722534179688,69.38198852539062,0.27673963901895254 +4.790547847747803,-13.006476402282715,69.38198852539062,0.2714737389673091 +4.7947540283203125,-12.99522876739502,69.38198852539062,0.2503097095567729 +4.797700881958008,-12.987348556518555,69.38198852539062,0.2468416413466503 +4.801611423492432,-12.976893424987793,69.38198852539062,0.24228662865150588 +4.805611610412598,-12.966196060180664,69.38198852539062,0.23766648290397113 +4.808047294616699,-12.95968246459961,69.38198852539062,0.23486712351562397 +4.8106207847595215,-12.952799797058105,69.38198852539062,0.2319176018074218 +4.81447172164917,-12.94250202178955,69.38198852539062,0.22751518816126118 +4.818081855773926,-12.932846069335938,69.38198852539062,0.22339719545192524 +4.82064151763916,-12.92600154876709,69.38198852539062,0.22048283786277598 +4.824187278747559,-12.916519165039062,69.38198852539062,0.2164504909609099 +4.827771186828613,-12.906936645507812,69.38198852539062,0.2123800809300984 +4.831067085266113,-12.89812183380127,69.38198852539062,0.20864107548720864 +4.834522724151611,-12.888882637023926,69.38198852539062,0.20472628657923522 +4.837836265563965,-12.880022048950195,69.38198852539062,0.20097621107134797 +4.841006278991699,-12.871540069580078,69.38198852539062,0.19739133711471202 +4.844179153442383,-12.863046646118164,69.38198852539062,0.19380573132298032 +4.84640645980835,-12.857084274291992,69.38198852539062,0.19129150988283633 +4.8494110107421875,-12.849044799804688,69.38198852539062,0.14259691650806922 +4.850663185119629,-12.845701217651367,69.38198852539062,0.10216835367646217 +4.851955413818359,-12.842255592346191,69.38195037841797,0.05974961949694131 +4.8528289794921875,-12.839926719665527,69.38195037841797,0.059330786376279344 +4.8535614013671875,-12.837973594665527,69.38195037841797,0.06508041726300968 +4.854668140411377,-12.83502197265625,69.3819351196289,0.06952678932941418 +4.855445861816406,-12.832944869995117,69.3819351196289,0.071042477390179 +4.856289386749268,-12.830693244934082,69.3819351196289,0.07183523733710083 +4.857431888580322,-12.827643394470215,69.3819351196289,0.07205028179856794 +4.858575344085693,-12.824593544006348,69.3819351196289,0.07168329783865557 +4.859806060791016,-12.821308135986328,69.3819351196289,0.07092424626585131 +4.860912799835205,-12.818354606628418,69.3819351196289,0.07005930538483292 +4.861745357513428,-12.816132545471191,69.3819351196289,0.0693419184755891 +4.862885475158691,-12.813090324401855,69.3819351196289,0.06830408256109255 +4.863719463348389,-12.810869216918945,69.3819351196289,0.039553951749354666 +4.864287376403809,-12.809367179870605,69.3819351196289,0.03153606803691508 +4.864700794219971,-12.808279991149902,69.3819351196289,0.02259325887831115 +4.864970684051514,-12.807576179504395,69.3819351196289,0.012891159681286186 +4.865052223205566,-12.807376861572266,69.3819351196289,0.002185464347107949 +4.864928722381592,-12.807723999023438,69.3819351196289,0.016089938650941056 +4.864565849304199,-12.8087158203125,69.3819351196289,0.03461045250436261 +4.8639140129089355,-12.810481071472168,69.3819351196289,0.04232243040348109 +4.863089084625244,-12.812708854675293,69.3819351196289,0.06412398711553192 +4.8621416091918945,-12.815264701843262,69.3819808959961,0.10225388812611634 +4.859139442443848,-12.823323249816895,69.38007354736328,0.21475000914460027 +4.8560791015625,-12.831530570983887,69.37907409667969,0.30854739904782996 +4.852615833282471,-12.840743064880371,69.37609100341797,0.3103358935231879 +4.847074508666992,-12.855588912963867,69.37605285644531,0.38079141371920017 +4.840962886810303,-12.87197494506836,69.37606811523438,0.39624272392341664 +4.836051940917969,-12.885137557983398,69.37606811523438,0.44787422541481975 +4.828280925750732,-12.90599250793457,69.37737274169922,0.5323788598565242 +4.822328090667725,-12.921846389770508,69.3719711303711,0.5891642370659886 +4.814718723297119,-12.94221305847168,69.37074279785156,0.6229426184555406 +4.804047584533691,-12.97078800201416,69.36955261230469,0.6810789180351956 +4.792578220367432,-13.001513481140137,69.3690414428711,0.742714907256495 +4.779184341430664,-13.037419319152832,69.370361328125,0.8111011208454716 +4.765252113342285,-13.074783325195312,69.37262725830078,0.8643048519621875 +4.750983238220215,-13.112972259521484,69.37027740478516,0.9217899385999965 +4.735368728637695,-13.154865264892578,69.37411499023438,0.9658865372991138 +4.718412399291992,-13.200236320495605,69.37078857421875,1.0243050927899628 +4.7020063400268555,-13.244169235229492,69.36997985839844,1.0679729406889151 +4.684844970703125,-13.290101051330566,69.36808013916016,1.10722955190678 +4.671728610992432,-13.32523250579834,69.36817932128906,1.1341246138215404 +4.653008460998535,-13.375374794006348,69.36856842041016,1.160625130090949 +4.634003639221191,-13.426258087158203,69.36769104003906,1.1665704411104478 +4.614081859588623,-13.47958755493164,69.36634063720703,1.1879539372047427 +4.595033645629883,-13.53058910369873,69.36590576171875,1.207647219667739 +4.5808329582214355,-13.568622589111328,69.36618041992188,1.2140115788489054 +4.561408042907715,-13.620657920837402,69.3670425415039,1.2109904768150375 +4.542691230773926,-13.670702934265137,69.36260986328125,1.205923841733958 +4.52186918258667,-13.726463317871094,69.36312103271484,1.2212291789411949 +4.502472877502441,-13.778365135192871,69.36140441894531,1.2199378653047788 +4.483267784118652,-13.829733848571777,69.3583984375,1.2282722745337555 +4.468238830566406,-13.869951248168945,69.35765838623047,1.2437918552037164 +4.448995590209961,-13.921448707580566,69.35697937011719,1.2540435872511309 +4.433230400085449,-13.963597297668457,69.35429382324219,1.2628297276407807 +4.413564205169678,-14.01622200012207,69.3538818359375,1.2682593267452256 +4.392126560211182,-14.073569297790527,69.35265350341797,1.2773723894511204 +4.371053695678711,-14.129902839660645,69.34966278076172,1.2957085870483858 +4.357010841369629,-14.167487144470215,69.35040283203125,1.3045790167315752 +4.342945575714111,-14.205110549926758,69.3497314453125,1.3131688948987241 +4.320450782775879,-14.265252113342285,69.34744262695312,1.318361426393833 +4.298813819885254,-14.323168754577637,69.34954071044922,1.331208974381713 +4.277333736419678,-14.380655288696289,69.3508529663086,1.3416461408470204 +4.261351585388184,-14.423405647277832,69.3503189086914,1.3504587061633018 +4.239103317260742,-14.482902526855469,69.34860229492188,1.3552147948741076 +4.218301296234131,-14.538531303405762,69.34718322753906,1.3429295911100958 +4.196042060852051,-14.598048210144043,69.34534454345703,1.343917356372777 +4.179684162139893,-14.641812324523926,69.34563446044922,1.3619727868355087 +4.164801120758057,-14.681602478027344,69.3443832397461,1.371678514713522 +4.15128755569458,-14.717727661132812,69.34329986572266,1.3736932253123364 +4.1349406242370605,-14.761444091796875,69.343017578125,1.3854071210711218 +4.11197566986084,-14.822793006896973,69.33917236328125,1.393120847882379 +4.08937406539917,-14.883209228515625,69.33820343017578,1.399158193308538 +4.0658183097839355,-14.946186065673828,69.33779907226562,1.410140300943868 +4.043153762817383,-15.006767272949219,69.33679962158203,1.4000014647775012 +4.020363807678223,-15.06770133972168,69.33679962158203,1.4091313041716762 +4.003537654876709,-15.112676620483398,69.33628845214844,1.4165583807700834 +3.9803783893585205,-15.174600601196289,69.33656311035156,1.419743125213754 +3.9574697017669678,-15.23583698272705,69.33590698242188,1.4244745954959694 +3.9400625228881836,-15.282336235046387,69.33367919921875,1.4257101004979331 +3.919050931930542,-15.338506698608398,69.3336181640625,1.4312973532201576 +3.8967161178588867,-15.398117065429688,69.32778930664062,1.3575429417718066 +3.8748342990875244,-15.45659065246582,69.3268051147461,1.3190906283726873 +3.8507866859436035,-15.520872116088867,69.32764434814453,1.370413037121092 +3.834467649459839,-15.564471244812012,69.32697296142578,1.4105935303466692 +3.8116395473480225,-15.625484466552734,69.32769775390625,1.4327849711933027 +3.79620361328125,-15.666708946228027,69.3261947631836,1.4390554391606574 +3.7803797721862793,-15.709237098693848,69.32626342773438,1.4395781030360844 +3.7580156326293945,-15.768731117248535,69.32215118408203,1.4057572501874405 +3.733722686767578,-15.833502769470215,69.32221984863281,1.3853694119037487 +3.710024118423462,-15.896742820739746,69.32006072998047,1.4203682972072247 +3.6948113441467285,-15.937251091003418,69.318603515625,1.4400311095578384 +3.6777074337005615,-15.982858657836914,69.31843566894531,1.4499231644312323 +3.6540141105651855,-16.046306610107422,69.31836700439453,1.4545238885938645 +3.6303296089172363,-16.10963249206543,69.3189468383789,1.4519888485966421 +3.609998941421509,-16.164113998413086,69.32711029052734,1.0031169051189224 +3.5978951454162598,-16.19646644592285,69.32807922363281,0.5391500416166505 +3.5918822288513184,-16.2125301361084,69.32807159423828,0.2933011403411268 +3.5885262489318848,-16.22149658203125,69.32807159423828,0.1403421593490921 +3.5869991779327393,-16.225584030151367,69.32807159423828,0.054202493385320204 +3.5865325927734375,-16.226837158203125,69.32807922363281,0.006686828630768927 +3.5866262912750244,-16.226594924926758,69.32807922363281,0.01644801972275619 +3.5870275497436523,-16.225534439086914,69.32807922363281,0.030351075926604368 +3.5876259803771973,-16.22394561767578,69.32807922363281,0.037913118035839244 +3.588200092315674,-16.222423553466797,69.32807159423828,0.04119457446243431 +3.588674306869507,-16.22116470336914,69.32807159423828,0.04262763049568505 +3.589421510696411,-16.21918296813965,69.32809448242188,0.04420140224934093 +3.5900027751922607,-16.2176513671875,69.32818603515625,0.030433872538728042 +3.5903594493865967,-16.21671485900879,69.32835388183594,0.016745153392103664 +3.590562582015991,-16.216190338134766,69.32833862304688,0.005429467811427416 +3.5905985832214355,-16.21611213684082,69.32835388183594,0.0038070954593208595 +3.5904736518859863,-16.21646499633789,69.32835388183594,0.015039672369117482 +3.5901060104370117,-16.21746253967285,69.32835388183594,0.03100335979790851 +3.5895795822143555,-16.218889236450195,69.32835388183594,0.03460573537983701 +3.5888445377349854,-16.22087287902832,69.32835388183594,0.04822918453508885 +3.588005304336548,-16.223133087158203,69.32835388183594,0.05506715861644442 +3.5869195461273193,-16.226051330566406,69.3283920288086,0.12250504832217736 +3.5846028327941895,-16.23224639892578,69.32743072509766,0.2113233665899399 +3.579488754272461,-16.245887756347656,69.32403564453125,0.34514714999500096 +3.5729784965515137,-16.26336669921875,69.32726287841797,0.4057445455868572 +3.5656914710998535,-16.282888412475586,69.33212280273438,0.48764036570344077 +3.5576796531677246,-16.304380416870117,69.33303833007812,0.601564048254991 +3.5465450286865234,-16.334117889404297,69.33171844482422,0.6389280029617347 +3.5368058681488037,-16.360063552856445,69.32757568359375,0.48732125610366556 +3.5320515632629395,-16.372739791870117,69.32660675048828,0.15929040197604524 +3.531277656555176,-16.37481117248535,69.32679748535156,0.024718113752660476 +3.5326576232910156,-16.371135711669922,69.32706451416016,0.12516761568149484 +3.53517746925354,-16.364421844482422,69.32706451416016,0.1796271661676689 +3.537350654602051,-16.35862922668457,69.32706451416016,0.20202091578217884 +3.541055202484131,-16.348751068115234,69.32711791992188,0.22109596862533448 +3.544473171234131,-16.33963394165039,69.3273696899414,0.22857527307261025 +3.547269582748413,-16.332178115844727,69.32762145996094,0.23096775776611797 +3.5507543087005615,-16.322887420654297,69.32801818847656,0.2312589965527404 +3.553278684616089,-16.31615447998047,69.32823944091797,0.192348310640536 +3.555974006652832,-16.308971405029297,69.32835388183594,0.11536973694215515 +3.557337522506714,-16.305341720581055,69.32848358154297,0.07299685251817911 +3.558100461959839,-16.30331802368164,69.3287353515625,0.03939221593163342 +3.55841326713562,-16.30249786376953,69.3287582397461,0.0031492544279808684 +3.5583291053771973,-16.302734375,69.32876586914062,0.012578322711674726 +3.558070182800293,-16.30344009399414,69.32876586914062,0.022883160392470136 +3.5575151443481445,-16.30493927001953,69.32876586914062,0.05090734196626981 +3.556663990020752,-16.30722427368164,69.32876586914062,0.05765000555266174 +3.5549020767211914,-16.312009811401367,69.33079528808594,0.16785550900534052 +3.5510265827178955,-16.322460174560547,69.3308334350586,0.27410193028206914 +3.5454869270324707,-16.337127685546875,69.32283782958984,0.39215022779890035 +3.5385429859161377,-16.35565948486328,69.32072448730469,0.4684974685207962 +3.529848337173462,-16.37895965576172,69.325439453125,0.575821609544546 +3.5202934741973877,-16.404508590698242,69.32600402832031,0.6508255733197852 +3.5091347694396973,-16.43425941467285,69.32254791259766,0.7290944941273736 +3.5000898838043213,-16.45844841003418,69.32414245605469,0.7835002831751072 +3.4872918128967285,-16.492570877075195,69.32046508789062,0.8442718137236865 +3.4726181030273438,-16.531816482543945,69.31897735595703,0.9287306061459331 +3.4564030170440674,-16.575061798095703,69.31900787353516,0.9978405462151678 +3.439671754837036,-16.619722366333008,69.3196029663086,1.0510437137070623 +3.4288766384124756,-16.648473739624023,69.31553649902344,0.952600526380173 +3.4205033779144287,-16.67084503173828,69.31643676757812,0.6044603221905025 +3.415062427520752,-16.68536376953125,69.31654357910156,0.33184221761163624 +3.411882162094116,-16.693857192993164,69.31655883789062,0.12038634081289346 +3.4111814498901367,-16.695730209350586,69.31658172607422,0.029099782418980754 +3.411604166030884,-16.694610595703125,69.31658172607422,0.05971725658234005 +3.413045644760132,-16.690773010253906,69.31658172607422,0.10494398845469186 +3.414886951446533,-16.685871124267578,69.31658172607422,0.1275911891427286 +3.417065382003784,-16.680070877075195,69.31661987304688,0.13977660149468024 +3.4196176528930664,-16.673276901245117,69.31661224365234,0.1457675995763452 +3.4212121963500977,-16.669029235839844,69.31661224365234,0.1472021659703563 +3.4233925342559814,-16.663223266601562,69.31661224365234,0.1475566259452341 +3.425577402114868,-16.657411575317383,69.31664276123047,0.09738342241128052 +3.426302671432495,-16.655485153198242,69.31668090820312,0.07138008415577718 +3.426804542541504,-16.654157638549805,69.31668090820312,0.030194912569986333 +3.4270777702331543,-16.6534423828125,69.31680297851562,0.014829059683178374 +3.427210569381714,-16.653100967407227,69.31682586669922,0.011621281157278354 +3.4273037910461426,-16.65286636352539,69.31686401367188,0.009045406941461798 +3.427271842956543,-16.65296745300293,69.31686401367188,0.002876080191308608 +3.4269609451293945,-16.65381622314453,69.31686401367188,0.04099799409355111 +3.4259865283966064,-16.65643310546875,69.31685638427734,0.0762369169543036 +3.424569845199585,-16.660234451293945,69.31685638427734,0.09393645243223152 +3.4228782653808594,-16.66477394104004,69.31685638427734,0.11809713373455695 +3.421002149581909,-16.669803619384766,69.31692504882812,0.12323619730911618 +3.4189627170562744,-16.675241470336914,69.31529235839844,0.16178527107284757 +3.4165706634521484,-16.681766510009766,69.32006072998047,0.2132939572446666 +3.41341495513916,-16.690227508544922,69.32006072998047,0.20035724933300106 +3.4091548919677734,-16.701597213745117,69.31800079345703,0.3187325988908093 +3.4051294326782227,-16.71233558654785,69.31797790527344,0.38103416953843977 +3.398420572280884,-16.730344772338867,69.32115173339844,0.39726820827707177 +3.3923397064208984,-16.746599197387695,69.32115173339844,0.4156701458183678 +3.3866395950317383,-16.761829376220703,69.32111358642578,0.46430937390126653 +3.3787689208984375,-16.782854080200195,69.32111358642578,0.5234157853401386 +3.369788408279419,-16.806846618652344,69.32109069824219,0.5844670819781258 +3.358870506286621,-16.83601188659668,69.32109069824219,0.649087697893801 +3.3485281467437744,-16.86363983154297,69.3210678100586,0.6750940087281017 +3.3367271423339844,-16.895156860351562,69.32103729248047,0.7583908391265318 +3.323965072631836,-16.92923927307129,69.32103729248047,0.8200523683744798 +3.314810037612915,-16.953689575195312,69.32103729248047,0.8603242011940738 +3.299961566925049,-16.99334144592285,69.32103729248047,0.9105561623780354 +3.2898473739624023,-17.020349502563477,69.32103729248047,0.9439318252860149 +3.2790071964263916,-17.049293518066406,69.32099914550781,0.9688420734633414 +3.2682223320007324,-17.07809066772461,69.32099914550781,1.0032462592595557 +3.2568557262420654,-17.108440399169922,69.32099914550781,1.030581088047249 +3.239335060119629,-17.155221939086914,69.32093048095703,1.072552666795155 +3.2211625576019287,-17.2037410736084,69.32093048095703,1.1103166558896125 +3.2025856971740723,-17.253339767456055,69.32093048095703,1.1494914608048792 +3.183427095413208,-17.304485321044922,69.32093048095703,1.1835868376600833 +3.163578510284424,-17.357471466064453,69.32093048095703,1.2159204724964379 +3.143850326538086,-17.410137176513672,69.32093048095703,1.2487694052804639 +3.1233534812927246,-17.46485137939453,69.32074737548828,1.2445453535381552 +3.1078734397888184,-17.50615882873535,69.3205795288086,0.6457515939073158 +3.100641965866089,-17.52545738220215,69.32060241699219,0.329949703390844 +3.0971078872680664,-17.534893035888672,69.32064056396484,0.1458095785996872 +3.09576153755188,-17.53849220275879,69.32064056396484,0.042758272140493 +3.0955758094787598,-17.53899574279785,69.32064056396484,0.0036797689256672615 +3.096001148223877,-17.537870407104492,69.32064819335938,0.041935881470286825 +3.09684419631958,-17.53563117980957,69.32064819335938,0.06197725139318195 +3.0979738235473633,-17.532629013061523,69.32066345214844,0.07315041669783083 +3.099233388900757,-17.52928352355957,69.32071685791016,0.07867935556634367 +3.1004703044891357,-17.5259952545166,69.3207015991211,0.08101193671677052 +3.101400375366211,-17.52351951599121,69.3207015991211,0.08169385990932967 +3.102795362472534,-17.51980972290039,69.3207015991211,0.0817426926248713 +3.104118824005127,-17.51628875732422,69.32071685791016,0.08116433759461737 +3.1054069995880127,-17.512861251831055,69.32071685791016,0.08027869835265611 +3.1067287921905518,-17.509349822998047,69.32071685791016,0.07918577529444323 +3.108018398284912,-17.505918502807617,69.32071685791016,0.07801859414048336 +3.1093225479125977,-17.502452850341797,69.32071685791016,0.0767838462241155 +3.110635280609131,-17.49896240234375,69.32071685791016,0.07551162588620712 +3.1118459701538086,-17.49574089050293,69.32071685791016,0.07432622808220668 +3.113068103790283,-17.492490768432617,69.32071685791016,0.07312470073677674 +3.1141951084136963,-17.489492416381836,69.32071685791016,0.07201640409887522 +3.1147470474243164,-17.48802947998047,69.32074737548828,0.04436068460966019 +3.1151673793792725,-17.486919403076172,69.32078552246094,0.03485709028938606 +3.1154842376708984,-17.486087799072266,69.32078552246094,0.01583540198581937 +3.1156182289123535,-17.485742568969727,69.32078552246094,0.007822071383052569 +3.1157329082489014,-17.485454559326172,69.32078552246094,0.0012101520545099882 +3.115722894668579,-17.485498428344727,69.32078552246094,0.008059900246985077 +3.1155216693878174,-17.486053466796875,69.32078552246094,0.01783366708862095 +3.115330696105957,-17.486576080322266,69.32078552246094,0.02224878340800623 +3.1148738861083984,-17.487812042236328,69.32078552246094,0.043776951541592383 +3.1138668060302734,-17.490516662597656,69.32079315185547,0.0646702048138995 +3.1121602058410645,-17.495094299316406,69.32093048095703,0.1365588429696426 +3.1098153591156006,-17.50136947631836,69.32099151611328,0.15413995899220187 +3.106644868850708,-17.509918212890625,69.3243637084961,0.2676437073513059 +3.1021535396575928,-17.52189826965332,69.3218994140625,0.31852917896215327 +3.098515748977661,-17.53158950805664,69.3201904296875,0.3540684300744701 +3.0923776626586914,-17.547985076904297,69.32005310058594,0.36812218803998603 +3.0858116149902344,-17.565521240234375,69.31935119628906,0.4390115694476877 +3.0784106254577637,-17.58523941040039,69.31494903564453,0.5292904424796908 +3.07177734375,-17.602935791015625,69.31472778320312,0.5820709387333013 +3.061464786529541,-17.630531311035156,69.31816864013672,0.6334619888913853 +3.0502769947052,-17.660400390625,69.31816864013672,0.6976570915756152 +3.0422911643981934,-17.681718826293945,69.31816864013672,0.7356205665308566 +3.0301175117492676,-17.714218139648438,69.31816864013672,0.7938247375393878 +3.0173721313476562,-17.748239517211914,69.31816864013672,0.8457085611719529 +3.0076208114624023,-17.774269104003906,69.31816864013672,0.8953931245118182 +2.991374969482422,-17.817626953125,69.31816864013672,0.950680364550647 +2.9809558391571045,-17.845436096191406,69.31816864013672,0.994069561717286 +2.9642348289489746,-17.890058517456055,69.31816864013672,1.0426839387907423 +2.947986602783203,-17.933420181274414,69.31803894042969,1.0810052296708925 +2.930194139480591,-17.980981826782227,69.31626892089844,1.101920913990577 +2.913442611694336,-18.026357650756836,69.30480194091797,1.122239281274153 +2.890171527862549,-18.091222763061523,69.25753021240234,1.044595080320743 +2.8728182315826416,-18.1416015625,69.19174194335938,1.0360656463719913 +2.856680154800415,-18.190343856811523,69.10006713867188,1.1106020094041709 +2.841187000274658,-18.23890495300293,68.9831771850586,1.1401703793802358 +2.825413227081299,-18.290090560913086,68.83436584472656,1.1128560499492446 +2.8105812072753906,-18.339628219604492,68.66870880126953,1.058701163243939 +2.796358346939087,-18.386695861816406,68.51280212402344,0.9942210575180024 +2.783494710922241,-18.427892684936523,68.3901596069336,0.9307872145317329 +2.770237922668457,-18.468402862548828,68.28680419921875,0.8654390592580777 +2.7579522132873535,-18.504749298095703,68.20844268798828,0.8061175481355352 +2.746941566467285,-18.536970138549805,68.13736724853516,0.7511989034304969 +2.73690128326416,-18.567028045654297,68.06143188476562,0.6993257038003518 +2.726623058319092,-18.598752975463867,67.96748352050781,0.6444057040876823 +2.7181084156036377,-18.625986099243164,67.87315368652344,0.5973063039051356 +2.709747552871704,-18.653438568115234,67.76679992675781,0.5507777767454481 +2.7026758193969727,-18.6766414642334,67.67813110351562,0.511460310456723 +2.695666551589966,-18.69882583618164,67.6009292602539,0.4733658613755076 +2.6889095306396484,-18.719266891479492,67.53878021240234,0.4372090987627823 +2.683105945587158,-18.736339569091797,67.49492645263672,0.407567345537902 +2.6769561767578125,-18.753719329833984,67.45756530761719,0.37759270218612767 +2.6710875034332275,-18.770246505737305,67.42164611816406,0.3489488341133619 +2.6659321784973145,-18.785106658935547,67.38396453857422,0.3231506164702586 +2.661850929260254,-18.797231674194336,67.3481674194336,0.30210372776527133 +2.657381296157837,-18.810972213745117,67.3011474609375,0.278236176833593 +2.6537234783172607,-18.82258415222168,67.25663757324219,0.2582295311141327 +2.650099039077759,-18.834043502807617,67.21324920654297,0.23865100634642036 +2.646580219268799,-18.84483528137207,67.17621612548828,0.2201727954166144 +2.643662929534912,-18.853464126586914,67.15039825439453,0.20530989829851723 +2.640531301498413,-18.862342834472656,67.12816619873047,0.18994292846095387 +2.637674570083618,-18.870203018188477,67.1116943359375,0.17620629143482086 +2.6350319385528564,-18.877532958984375,67.09566497802734,0.16334386949140448 +2.632587194442749,-18.884489059448242,67.07794189453125,0.15114442152926144 +2.6307525634765625,-18.889854431152344,67.06183624267578,0.09397861774983969 +2.6296019554138184,-18.893474578857422,67.05332946777344,0.07859105444582738 +2.6286091804504395,-18.89654541015625,67.03820037841797,0.06295486712263809 +2.6276965141296387,-18.899438858032227,67.02819061279297,0.05499805409903498 +2.626957893371582,-18.901653289794922,67.01848602294922,0.04646210143327436 +2.626335382461548,-18.903446197509766,67.00971221923828,0.040232347456477545 +2.6257379055023193,-18.905160903930664,67.00552368164062,0.05528244386671022 +2.6251790523529053,-18.906824111938477,67.00641632080078,0.04399193094301757 +2.6238815784454346,-18.91040802001953,66.99828338623047,0.09331092027002169 +2.6222801208496094,-18.914958953857422,66.98655700683594,0.11051753216030259 +2.6205649375915527,-18.919994354248047,66.97117614746094,0.11461575585690124 +2.6189677715301514,-18.92485237121582,66.95401000976562,0.11241362987073548 +2.6175038814544678,-18.92945671081543,66.9358901977539,0.10762102195421347 +2.615915536880493,-18.934438705444336,66.91661834716797,0.10088367534994876 +2.6145873069763184,-18.938491821289062,66.90238189697266,0.094685737344143 +2.6131036281585693,-18.94286346435547,66.88902282714844,0.08755784016674649 +2.611860990524292,-18.946388244628906,66.88005065917969,0.08159097249562287 +2.6107401847839355,-18.94947624206543,66.87322235107422,0.07623559765711181 +2.6095476150512695,-18.95277976989746,66.86573791503906,0.07042873523346263 +2.6084041595458984,-18.956037521362305,66.8570785522461,0.06467669488814295 +2.6075222492218018,-18.958641052246094,66.84905242919922,0.060082628489146875 +2.6066505908966064,-18.961315155029297,66.83956146240234,0.0553632354535734 +2.605882167816162,-18.9637508392334,66.82991027832031,0.05110133448467582 +2.60518217086792,-18.96595573425293,66.82128143310547,0.04726255687193378 +2.604560375213623,-18.967863082885742,66.81461334228516,0.04393127550488891 +2.6039257049560547,-18.969745635986328,66.8088150024414,0.04061557307085035 +2.603375196456909,-18.97132110595703,66.80474090576172,0.037819183502623976 +2.602781057357788,-18.97296905517578,66.8011245727539,0.034862477418948504 +2.6022613048553467,-18.974409103393555,66.79798889160156,0.03226274782218617 +2.6020796298980713,-18.974918365478516,66.79692840576172,1.0870849360488691e-05 +2.6020805835723877,-18.974918365478516,66.79692840576172,7.234592587225203e-06 +2.6020805835723877,-18.97492027282715,66.79692840576172,9.338555512491072e-06 +2.6020805835723877,-18.97492218017578,66.79692840576172,9.328410082257768e-06 +2.6020805835723877,-18.974956512451172,66.79714965820312,0.0058239907007968 +2.6020474433898926,-18.975065231323242,66.79737854003906,0.004535068013915945 +2.6019928455352783,-18.97520637512207,66.79759979248047,0.0029431808221931036 +2.601916790008545,-18.975431442260742,66.79740905761719,0.005091548315077869 +2.601768732070923,-18.97589874267578,66.79582214355469,0.022427841061045978 +2.6013972759246826,-18.9769229888916,66.7933578491211,0.02470256023403559 +2.6010470390319824,-18.97793197631836,66.79072570800781,0.022828645600523837 +2.6006431579589844,-18.97911262512207,66.78746032714844,0.03351216509541128 +2.6001617908477783,-18.980558395385742,66.7834701538086,0.030175632515099162 +2.5997233390808105,-18.981935501098633,66.77880859375,0.03428603770725718 +2.59895920753479,-18.98438835144043,66.77067565917969,0.046423401477722226 +2.5979933738708496,-18.987354278564453,66.76327514648438,0.09201290447213385 +2.59689998626709,-18.990550994873047,66.7524642944336,0.053006852993043696 +2.595913887023926,-18.993330001831055,66.74346923828125,0.07528675157657413 +2.5948305130004883,-18.996299743652344,66.73606872558594,0.07024966749865089 +2.593597650527954,-18.999597549438477,66.7271728515625,0.08606791254368429 +2.5916640758514404,-19.005002975463867,66.71717834472656,0.1482439957210756 +2.589215040206909,-19.012128829956055,66.69932556152344,0.19095745607808606 +2.585695743560791,-19.02252960205078,66.65803527832031,0.24461227224541396 +2.5818252563476562,-19.034408569335938,66.61151885986328,0.30772513775912136 +2.576695203781128,-19.050081253051758,66.54725646972656,0.3813173369594673 +2.570528268814087,-19.068532943725586,66.47990417480469,0.42708331176194636 +2.5628623962402344,-19.090373992919922,66.404052734375,0.5478205890656507 +2.5531115531921387,-19.117355346679688,66.33000946044922,0.6316777831537617 +2.5423896312713623,-19.146028518676758,66.25929260253906,0.7086521718037795 +2.5296740531921387,-19.179828643798828,66.1787109375,0.7909850548216887 +2.5189268589019775,-19.20878028869629,66.09895324707031,0.8268819653632639 +2.499537706375122,-19.262283325195312,65.91708374023438,0.8067328256489347 +2.4815309047698975,-19.314434051513672,65.71612548828125,0.9531369845016232 +2.4664714336395264,-19.35930824279785,65.5206069946289,1.0949892780067172 +2.4487786293029785,-19.41122817993164,65.3042221069336,1.2016346664401891 +2.4296319484710693,-19.46540641784668,65.08871459960938,1.281743270652933 +2.408634662628174,-19.52255630493164,64.88977813720703,1.3369479731345772 +2.386502504348755,-19.580307006835938,64.71293640136719,1.3728300389820942 +2.3618340492248535,-19.641965866088867,64.54842376708984,1.3936024665177105 +2.3372437953948975,-19.7011661529541,64.41860961914062,1.420090471147084 +2.3099513053894043,-19.766218185424805,64.27503967285156,1.4453919268713191 +2.284015417098999,-19.82883071899414,64.11634063720703,1.4612673226567083 +2.2586472034454346,-19.891258239746094,63.929569244384766,1.4632201530217888 +2.2345023155212402,-19.952011108398438,63.72383117675781,1.4727493829280156 +2.2083749771118164,-20.018922805786133,63.46204376220703,1.4718817665541095 +2.182772397994995,-20.08401107788086,63.20753860473633,1.5157489439628171 +2.1551403999328613,-20.152036666870117,62.9620475769043,1.5450531448692184 +2.127284288406372,-20.218252182006836,62.75726318359375,1.565897964798886 +2.0986573696136475,-20.283740997314453,62.57498550415039,1.5832454048078186 +2.0681850910186768,-20.352401733398438,62.386199951171875,1.6169799485697913 +2.0355284214019775,-20.426515579223633,62.162025451660156,1.6498271134898588 +2.0052428245544434,-20.496341705322266,61.91900634765625,1.6755674015854771 +1.9749643802642822,-20.56734848022461,61.638702392578125,1.6965809191362107 +1.9443639516830444,-20.64006805419922,61.32181930541992,1.7161228905366144 +1.9152764081954956,-20.708498001098633,61.02336502075195,1.733658362185486 +1.8790665864944458,-20.79090118408203,60.68094253540039,1.7500409553331702 +1.848296880722046,-20.85845947265625,60.441802978515625,1.4881517442934096 +1.8447011709213257,-20.859874725341797,60.50395584106445,0.04194334449719154 +1.8430217504501343,-20.860633850097656,60.53340148925781,0.036212512920210174 +1.8414275646209717,-20.861125946044922,60.56752014160156,0.02924363887407382 +1.8402262926101685,-20.86125373840332,60.59172439575195,0.02140487058293114 +1.8393306732177734,-20.861291885375977,60.61027526855469,0.019674125264442257 +1.8385634422302246,-20.861251831054688,60.62774658203125,0.006518108659678686 +1.8381696939468384,-20.861141204833984,60.63603973388672,0.015165582063094294 +1.8378260135650635,-20.86101531982422,60.642364501953125,0.012287187868155289 +1.8376004695892334,-20.860641479492188,60.65312957763672,0.007889142727620584 +1.8375202417373657,-20.86029052734375,60.659446716308594,0.006388373240380798 +1.8374536037445068,-20.859874725341797,60.666297912597656,0.006112982157455592 +1.8374090194702148,-20.85950469970703,60.67204284667969,0.00602646732230074 +1.8374006748199463,-20.85911750793457,60.67702102661133,0.004648434597788672 +1.8374085426330566,-20.858800888061523,60.68085861206055,0.0047039423623651015 +1.8374395370483398,-20.858484268188477,60.68391799926758,0.0033588656490766825 +1.837479829788208,-20.858217239379883,60.68620681762695,0.002906210712531809 +1.8375239372253418,-20.85798454284668,60.6880989074707,0.00237359307825041 +1.83756422996521,-20.8577823638916,60.689517974853516,0.002178651277948886 +1.8376020193099976,-20.857601165771484,60.69076156616211,0.0020428363956356737 +1.8376336097717285,-20.857450485229492,60.69193649291992,0.001511960802152911 +1.837659239768982,-20.857324600219727,60.69279861450195,0.0011085044577560594 +1.8376820087432861,-20.857213973999023,60.693748474121094,0.0009427841641356329 +1.837702751159668,-20.857126235961914,60.69435501098633,0.0008515891842180092 +1.8377207517623901,-20.85704803466797,60.694698333740234,0.0007489246951404785 +1.8377366065979004,-20.856990814208984,60.694969177246094,0.0006713843433872499 +1.8377511501312256,-20.856935501098633,60.69525146484375,0.00039318542750760527 +1.837756633758545,-20.856897354125977,60.69550323486328,0.00017815924694870468 +1.8377671241760254,-20.856874465942383,60.69550323486328,0.0001824057133717273 +1.8377774953842163,-20.856849670410156,60.69550323486328,8.542207782081718e-05 +1.83778977394104,-20.856830596923828,60.69544219970703,6.257645176428794e-05 +1.8378132581710815,-20.856815338134766,60.69528579711914,3.441226070930984e-05 +1.8378623723983765,-20.856788635253906,60.69546127319336,0.0002755137852477875 +1.8378900289535522,-20.85679817199707,60.69558334350586,2.6157386512771052e-05 +1.8379014730453491,-20.856796264648438,60.69558334350586,2.602579852069525e-05 +1.8379130363464355,-20.856794357299805,60.69565200805664,3.3627096085392886e-05 +1.837917447090149,-20.85678482055664,60.695640563964844,3.518691435558948e-05 +1.837931513786316,-20.856781005859375,60.69569396972656,3.4322309191826826e-05 +1.8379409313201904,-20.856781005859375,60.69578170776367,2.5394559055999798e-05 +1.8379474878311157,-20.856781005859375,60.69578170776367,1.3920995610674692e-05 +1.8379522562026978,-20.856781005859375,60.6957893371582,4.169300760427927e-05 +1.8379535675048828,-20.85677719116211,60.6957893371582,5.305092124226608e-05 +1.8379584550857544,-20.85677719116211,60.69581604003906,1.5508877413008048e-05 +1.8379566669464111,-20.856775283813477,60.695831298828125,1.74599374021312e-05 +1.8379573822021484,-20.85677146911621,60.69584274291992,4.679065797436235e-05 +1.8379592895507812,-20.856767654418945,60.695858001708984,2.1433391925675256e-05 +1.8379584550857544,-20.856767654418945,60.695858001708984,2.2568193962940684e-05 +1.837958812713623,-20.856761932373047,60.695884704589844,3.6715773124254385e-05 +1.8379557132720947,-20.856760025024414,60.69590759277344,6.336199927329449e-05 +1.8379555940628052,-20.856760025024414,60.69590759277344,5.551932496938424e-05 +1.8379572629928589,-20.856760025024414,60.69590759277344,1.9396017356402226e-05 +1.8379576206207275,-20.856760025024414,60.69590759277344,1.9969712189420364e-05 +1.837956190109253,-20.856760025024414,60.69590759277344,2.488184213307307e-05 +1.8379565477371216,-20.856760025024414,60.69590759277344,2.1135664395869315e-05 +1.837957739830017,-20.856760025024414,60.69590759277344,3.886037848745751e-05 +1.8379473686218262,-20.85676383972168,60.69587326049805,4.349626578001866e-05 +1.8379380702972412,-20.856754302978516,60.69580841064453,0.00010799741797182416 +1.8379381895065308,-20.85674285888672,60.69587326049805,9.251821854666312e-05 +1.8379361629486084,-20.856735229492188,60.69587326049805,5.5772203732175174e-05 +1.8379347324371338,-20.85673713684082,60.69587326049805,3.6024515688654694e-05 +1.8379294872283936,-20.856733322143555,60.69587326049805,5.160774594171636e-05 +1.837931513786316,-20.856733322143555,60.695884704589844,1.642434806943981e-05 +1.837931513786316,-20.856733322143555,60.695884704589844,2.968623894609694e-05 +1.8379316329956055,-20.856733322143555,60.695884704589844,1.045215258913888e-05 +1.8379319906234741,-20.856733322143555,60.695884704589844,3.7749531872360737e-05 +1.8379333019256592,-20.856733322143555,60.69590759277344,1.605508837727686e-05 +1.8379334211349487,-20.856733322143555,60.69590759277344,4.15316895073922e-05 +1.8379327058792114,-20.856733322143555,60.69590759277344,1.6529942790355385e-05 +1.8379337787628174,-20.85673713684082,60.69593811035156,3.551896609060777e-05 +1.8379262685775757,-20.856733322143555,60.69593811035156,5.841299899777109e-05 +1.8379288911819458,-20.856733322143555,60.69593811035156,1.3570875493216198e-05 +1.837929129600525,-20.856733322143555,60.69593811035156,8.883756446211846e-06 +1.837929129600525,-20.856733322143555,60.69593811035156,1.2499056706185703e-05 +1.837929606437683,-20.856733322143555,60.69593811035156,4.880223216116072e-06 +1.8379300832748413,-20.856733322143555,60.69593811035156,1.0287209266914973e-05 +1.8379626274108887,-20.856502532958984,60.69352340698242,0.018994161952029222 +1.8381370306015015,-20.856008529663086,60.69148635864258,0.018799123101459973 +1.838458776473999,-20.855323791503906,60.69322967529297,0.009218168689419083 +1.8386130332946777,-20.854965209960938,60.6950798034668,0.007178566333968599 +1.8385202884674072,-20.855104446411133,60.69603729248047,0.00992677573238216 +1.8382031917572021,-20.85582733154297,60.693111419677734,0.023340818282639477 +1.8378490209579468,-20.85667610168457,60.68937683105469,0.0026456522750694655 +1.8378499746322632,-20.856647491455078,60.69133758544922,0.0011546093860035724 +1.8377773761749268,-20.856645584106445,60.6931037902832,0.0014782959454483996 +1.8377221822738647,-20.856657028198242,60.69502639770508,0.0020803427515428694 +1.837557315826416,-20.856679916381836,60.69830322265625,0.0011717838715257938 +1.8372817039489746,-20.85675048828125,60.702880859375,0.010564316316500991 +1.836977481842041,-20.8568115234375,60.70783233642578,0.005409581941028442 +1.836717128753662,-20.856924057006836,60.711978912353516,0.004064463204728662 +1.8365119695663452,-20.85702896118164,60.71520233154297,0.0030425712553010975 +1.8363802433013916,-20.857086181640625,60.71759033203125,0.0022446204690477283 +1.8362771272659302,-20.857091903686523,60.72018814086914,0.0015731035978955026 +1.8362293243408203,-20.857067108154297,60.72185516357422,0.0016489942386471346 +1.8362023830413818,-20.85698890686035,60.72334289550781,0.001530169559804348 +1.836181402206421,-20.856910705566406,60.724857330322266,0.0014437684161698302 +1.8361687660217285,-20.856840133666992,60.726192474365234,0.001537757133664006 +1.8361670970916748,-20.856754302978516,60.727256774902344,0.0009400754166851742 +1.8361713886260986,-20.8566837310791,60.728084564208984,0.001244188944831122 +1.836181879043579,-20.856611251831055,60.72878646850586,0.0005797748496835591 +1.836193323135376,-20.856557846069336,60.729122161865234,0.00044538829118920124 +1.8362051248550415,-20.85650062561035,60.729408264160156,0.0005552122859715817 +1.8362183570861816,-20.856449127197266,60.72974395751953,0.0005663383752159425 +1.8362284898757935,-20.85640525817871,60.73014450073242,0.00039914820520355667 +1.836236834526062,-20.856367111206055,60.73036575317383,0.0005155029130610605 +1.836245059967041,-20.856342315673828,60.73062515258789,0.0002765005149161738 +1.836250901222229,-20.856319427490234,60.73065185546875,0.0005482079851707686 +1.8362579345703125,-20.85629653930664,60.73065185546875,0.0002447889701726562 +1.8362640142440796,-20.856279373168945,60.730594635009766,3.1570989323111624e-05 +1.836271047592163,-20.856264114379883,60.73063659667969,1.5671437547258865e-05 +1.8362798690795898,-20.85625457763672,60.73065185546875,0.00021829789610749742 +1.8362995386123657,-20.856243133544922,60.73075485229492,0.00024248833745970378 +1.836313009262085,-20.85623550415039,60.73079299926758,6.299965832656597e-05 +1.8363227844238281,-20.856231689453125,60.73082733154297,2.9566504765558583e-05 +1.8363274335861206,-20.856231689453125,60.73084259033203,8.834922379063162e-06 +1.8363289833068848,-20.856231689453125,60.73088455200195,1.4239190622414589e-05 +1.8363323211669922,-20.85623550415039,60.73093795776367,1.755844014709405e-05 +1.8363310098648071,-20.85623550415039,60.73093795776367,4.5567849619369795e-06 +1.8363304138183594,-20.85623550415039,60.730953216552734,9.62359968395352e-06 +1.8363338708877563,-20.85623550415039,60.730979919433594,1.8106950362761658e-05 +1.8363358974456787,-20.856237411499023,60.73101806640625,9.674632792446356e-06 +1.8363317251205444,-20.856231689453125,60.731014251708984,4.8351882226929747e-05 +1.8363338708877563,-20.856231689453125,60.73102569580078,9.2260581830652e-06 +1.8363358974456787,-20.85623550415039,60.73103332519531,1.033319347251017e-05 +1.8363358974456787,-20.856231689453125,60.73103332519531,1.9608725195753545e-05 +1.836337685585022,-20.85623550415039,60.73100662231445,1.911227627307701e-05 +1.8363380432128906,-20.85623550415039,60.73100662231445,2.604741474912768e-05 +1.8363364934921265,-20.85623550415039,60.73100662231445,1.866217871899837e-05 +1.8363384008407593,-20.85623550415039,60.73100662231445,1.17389203929006e-05 +1.8363378047943115,-20.85623550415039,60.73100662231445,1.51712620709998e-05 +1.836336612701416,-20.856231689453125,60.73100662231445,3.93975842440686e-05 +1.8363325595855713,-20.856231689453125,60.73099136352539,3.745242837763396e-05 +1.8363338708877563,-20.856229782104492,60.73100662231445,1.0311343391365935e-05 +1.8363358974456787,-20.856231689453125,60.73100662231445,1.1210812907196846e-05 +1.8363369703292847,-20.85623550415039,60.73100662231445,6.35809294455792e-06 +1.8363360166549683,-20.85623550415039,60.73100662231445,1.6093105524043205e-05 +1.8363326787948608,-20.85623550415039,60.731014251708984,8.89888928653041e-06 +1.8363293409347534,-20.856231689453125,60.731014251708984,2.193978783220216e-06 +1.8363306522369385,-20.856229782104492,60.731014251708984,4.232247324145074e-06 +1.83633291721344,-20.856237411499023,60.731075286865234,3.475275085670488e-05 +1.8363323211669922,-20.856237411499023,60.731109619140625,5.286988975044737e-05 +1.836325764656067,-20.85623550415039,60.73114776611328,1.0726061642687347e-05 +1.8363268375396729,-20.85622787475586,60.7312126159668,2.288721854538581e-05 +1.8363277912139893,-20.85622787475586,60.7312126159668,9.092883841344136e-06 +1.8363279104232788,-20.85622787475586,60.7312126159668,1.2955617803995923e-05 +1.8363279104232788,-20.85622787475586,60.7312126159668,6.757445145293623e-06 +1.8363276720046997,-20.85622787475586,60.7312126159668,1.0388295004510403e-05 +1.836328387260437,-20.85622787475586,60.7312126159668,1.2879667168123303e-05 +1.8363299369812012,-20.85622787475586,60.7312126159668,7.954088825736356e-06 +1.836329460144043,-20.85622787475586,60.7312126159668,9.622261877466386e-06 +1.836329460144043,-20.85622787475586,60.7312126159668,9.71942897382026e-06 +1.836329460144043,-20.85622787475586,60.7312126159668,8.381500784963587e-06 +1.8363304138183594,-20.856229782104492,60.7312126159668,2.4145711107335976e-05 +1.8363311290740967,-20.856229782104492,60.73121643066406,5.119896526699822e-06 +1.8363287448883057,-20.856229782104492,60.73121643066406,9.10508754005671e-06 +1.8363263607025146,-20.856229782104492,60.73121643066406,6.756892808188015e-06 +1.8363276720046997,-20.856229782104492,60.731239318847656,4.355314301867914e-06 +1.8363289833068848,-20.856231689453125,60.73127365112305,3.354915461952196e-06 +1.8363317251205444,-20.856231689453125,60.73127365112305,9.910007473101937e-06 +1.8363310098648071,-20.856229782104492,60.73127365112305,1.5782176367779074e-05 +1.8363306522369385,-20.856229782104492,60.73127365112305,1.6365735242259504e-05 +1.836336374282837,-20.856225967407227,60.731346130371094,0.0034729694025567187 +1.8363806009292603,-20.856159210205078,60.73182678222656,0.005730401862725007 +1.83643639087677,-20.856021881103516,60.73336410522461,0.004314498250534043 +1.836475133895874,-20.855939865112305,60.734134674072266,0.005039765893118571 +1.8365141153335571,-20.855852127075195,60.734893798828125,0.002386823810988332 +1.8365033864974976,-20.855865478515625,60.7354736328125,0.0022275636341441657 +1.8364113569259644,-20.855976104736328,60.737571716308594,0.009966225940230408 +1.8363574743270874,-20.85599136352539,60.73662567138672,0.014928709882487779 +1.8363288640975952,-20.855995178222656,60.73554229736328,0.008096960329903433 +1.836288571357727,-20.8560791015625,60.73487091064453,0.01157665386134493 +1.8362990617752075,-20.855873107910156,60.73186492919922,0.01583170468960339 +1.8360062837600708,-20.856142044067383,60.73462677001953,0.015452904144983527 +1.8360825777053833,-20.856054306030273,60.737831115722656,0.006634024505674776 +1.835994839668274,-20.85601806640625,60.74222183227539,0.0033729911137623976 +1.8360004425048828,-20.856014251708984,60.74298095703125,0.003142212557784478 +1.835999846458435,-20.855981826782227,60.744407653808594,0.003956576984302003 +1.835969090461731,-20.856035232543945,60.742645263671875,0.0037996532654345477 +1.8359049558639526,-20.856046676635742,60.74272155761719,0.004027367203411556 +1.8358176946640015,-20.85610008239746,60.74229049682617,0.0033087977506819524 +1.8356077671051025,-20.856204986572266,60.74427032470703,0.005251553744416899 +1.8353476524353027,-20.856353759765625,60.745582580566406,0.004045104878300851 +1.8352724313735962,-20.85646629333496,60.74490737915039,0.0011144703469687387 +1.8352203369140625,-20.856508255004883,60.7435188293457,0.0031953784797728734 +1.834929347038269,-20.85659408569336,60.745689392089844,0.00136573924841315 +1.834637999534607,-20.856731414794922,60.748191833496094,0.0032620880470898054 +1.8344988822937012,-20.856815338134766,60.74607467651367,0.004165254904402623 +1.8343579769134521,-20.856855392456055,60.74897003173828,0.008389997053445257 +1.8341236114501953,-20.85692596435547,60.753116607666016,0.005014187991934341 +1.8340874910354614,-20.8569278717041,60.75395584106445,0.003569191685447076 +1.8339693546295166,-20.857046127319336,60.74868392944336,0.0051946657679642115 +1.8336750268936157,-20.857269287109375,60.74147033691406,0.0048617796097043505 +1.8333369493484497,-20.857463836669922,60.736976623535156,0.005000945774826 +1.8333165645599365,-20.857431411743164,60.738189697265625,0.0035249543030590916 +1.8331339359283447,-20.857385635375977,60.74231719970703,0.00765029422866089 +1.8330276012420654,-20.85735321044922,60.74439239501953,0.0041778721132889225 +1.8329715728759766,-20.857311248779297,60.74607467651367,0.0017070745038794645 +1.8328895568847656,-20.85731315612793,60.74708557128906,0.0014579053634417869 +1.8328243494033813,-20.85732650756836,60.748069763183594,0.0011395309032516433 +1.8327845335006714,-20.857303619384766,60.748355865478516,0.001003683579785861 +1.8327628374099731,-20.857267379760742,60.74953079223633,0.00183763609224448 +1.8327605724334717,-20.857194900512695,60.75051498413086,0.0015812523321261178 +1.8327693939208984,-20.85710906982422,60.7514762878418,0.001055280980000148 +1.8327856063842773,-20.857011795043945,60.75246810913086,0.001041932442665947 +1.8330254554748535,-20.856409072875977,60.75633239746094,0.030553040733689817 +1.8338631391525269,-20.854272842407227,60.76961135864258,0.05900711438783544 +1.8351200819015503,-20.851003646850586,60.790252685546875,0.07500936352334456 +1.8364717960357666,-20.847463607788086,60.812721252441406,0.08249961655769303 +1.8379062414169312,-20.84367561340332,60.837135314941406,0.0859825155028779 +1.839316725730896,-20.839929580688477,60.86158752441406,0.0871834652494594 +1.8407059907913208,-20.83621597290039,60.8859748840332,0.08720734240347437 +1.842192530632019,-20.83222770690918,60.91223907470703,0.0865300662149073 +1.8435354232788086,-20.828624725341797,60.935951232910156,0.08555464399360753 +1.8449891805648804,-20.824718475341797,60.96173095703125,0.08427726197307457 +1.8463244438171387,-20.821125030517578,60.985511779785156,0.08298664027554226 +1.847686767578125,-20.817455291748047,61.00977325439453,0.0816069344481295 +1.8489606380462646,-20.814022064208984,61.032257080078125,0.0802913365563836 +1.8503342866897583,-20.81033706665039,61.05624771118164,0.07886542090791916 +1.8515931367874146,-20.80696678161621,61.077938079833984,0.07755356994425733 +1.852837324142456,-20.803659439086914,61.098880767822266,0.07626216965314943 +1.8541332483291626,-20.800233840942383,61.12018966674805,0.07492553662019502 +1.8541617393493652,-20.80020523071289,61.12038040161133,5.541453625379099e-05 +1.8541606664657593,-20.800207138061523,61.12038040161133,6.7355714336941685e-06 +1.8541605472564697,-20.80020523071289,61.12038040161133,1.0448203300430793e-05 +1.8541613817214966,-20.80019760131836,61.12038040161133,1.0511248848467696e-05 +1.8541615009307861,-20.80019187927246,61.12038040161133,8.949783728046091e-06 +1.8541617393493652,-20.800189971923828,61.12038040161133,7.948138494255746e-06 +1.8541617393493652,-20.80018424987793,61.12038040161133,6.9703403600092715e-06 +1.8541616201400757,-20.800182342529297,61.12038040161133,6.110539326943032e-06 +1.8541620969772339,-20.800182342529297,61.12038040161133,5.915000833598379e-06 +1.8541628122329712,-20.800180435180664,61.12038040161133,5.473947966784764e-06 +1.8541632890701294,-20.800180435180664,61.12038040161133,5.358661648622047e-06 +1.8541637659072876,-20.80017852783203,61.12038040161133,5.444918559468412e-06 +1.8541637659072876,-20.80017852783203,61.12038040161133,5.585390955957884e-06 +1.8541642427444458,-20.80017852783203,61.12038040161133,5.625462451471793e-06 +1.8541643619537354,-20.80017852783203,61.12038040161133,5.361148121162315e-06 +1.8541642427444458,-20.80017852783203,61.12038040161133,5.368540388047977e-06 +1.8541643619537354,-20.80017852783203,61.12038040161133,5.214211748324913e-06 +1.8541648387908936,-20.80017852783203,61.12038040161133,5.397734880341344e-06 +1.8542159795761108,-20.800079345703125,61.121009826660156,0.001991417964899964 +1.8543181419372559,-20.799894332885742,61.12102508544922,0.003832325025287078 +1.8544645309448242,-20.799623489379883,61.121639251708984,0.009864176623705208 +1.8546775579452515,-20.799232482910156,61.12236785888672,0.010030780457769605 +1.8549823760986328,-20.79866600036621,61.12299728393555,0.01770771024831478 +1.8553966283798218,-20.797916412353516,61.12299728393555,0.018933169352211808 +1.855925440788269,-20.796964645385742,61.12299728393555,0.027846561926671547 +1.8565959930419922,-20.7957763671875,61.122657775878906,0.0287525578182354 +1.857439637184143,-20.794296264648438,61.12187194824219,0.0375842994621809 +1.8583577871322632,-20.792682647705078,61.12152862548828,0.04422744467348202 +1.8595527410507202,-20.79056167602539,61.12152862548828,0.061986833319006555 +1.8609102964401245,-20.788110733032227,61.12152862548828,0.060981543167425795 +1.8627979755401611,-20.784664154052734,61.121952056884766,0.10474922415024071 +1.8654112815856934,-20.779909133911133,61.12322235107422,0.12366929828636945 +1.8675150871276855,-20.77614402770996,61.121612548828125,0.11324835859416305 +1.8709553480148315,-20.7701358795166,61.120506286621094,0.16209287550174772 +1.875285267829895,-20.762603759765625,61.114768981933594,0.21213649451006364 +1.8810105323791504,-20.7525577545166,61.102867126464844,0.2687407995172613 +1.887908697128296,-20.740407943725586,61.095001220703125,0.34017729129147817 +1.8962247371673584,-20.725709915161133,61.093082427978516,0.3721237381967233 +1.9061897993087769,-20.707876205444336,61.088157653808594,0.45548178493324987 +1.9166148900985718,-20.688955307006836,61.088157653808594,0.4993237069924281 +1.928288221359253,-20.667749404907227,61.088157653808594,0.5207502702512637 +1.9409615993499756,-20.64519500732422,61.07805633544922,0.5279369770987956 +1.953872799873352,-20.62282943725586,61.05611038208008,0.5269226514242485 +1.9656420946121216,-20.60265350341797,61.03265380859375,0.5222185233870986 +1.9782055616378784,-20.580995559692383,61.010894775390625,0.5149441248892835 +1.9896034002304077,-20.56112289428711,60.996002197265625,0.5070879261413194 +2.001343250274658,-20.54049301147461,60.984004974365234,0.4982418824893249 +2.0131967067718506,-20.519622802734375,60.972679138183594,0.4888818978191946 +2.0240390300750732,-20.500558853149414,60.96189880371094,0.4801211746004868 +2.034839630126953,-20.481618881225586,60.95027542114258,0.47130047873280706 +2.045732021331787,-20.462604522705078,60.93699264526367,0.46237043235243913 +2.0558745861053467,-20.444982528686523,60.923126220703125,0.4540529855511383 +2.0673205852508545,-20.42519760131836,60.90580368041992,0.4446854828809068 +2.077653408050537,-20.407421112060547,60.888675689697266,0.43625125696527345 +2.0884053707122803,-20.389015197753906,60.86928939819336,0.42750659468260815 +2.0986876487731934,-20.371498107910156,60.84930419921875,0.4191759060653824 +2.107560634613037,-20.356435775756836,60.831233978271484,0.4120118814732392 +2.117988348007202,-20.338794708251953,60.80900573730469,0.4036194321377984 +2.1268420219421387,-20.323869705200195,60.790122985839844,0.35557835894791806 +2.135791063308716,-20.308853149414062,60.771278381347656,0.33952262933140126 +2.1440048217773438,-20.295101165771484,60.75309371948242,0.37211850253939416 +2.15248966217041,-20.280908584594727,60.73279571533203,0.3630764723720478 +2.1626806259155273,-20.263824462890625,60.70314025878906,0.44405095307823106 +2.173444986343384,-20.245832443237305,60.675865173339844,0.4803726789664567 +2.1870079040527344,-20.22319793701172,60.64353942871094,0.552967996883275 +2.200819492340088,-20.20015525817871,60.610877990722656,0.65275120107506 +2.2168047428131104,-20.173513412475586,60.57318878173828,0.7126555158566511 +2.2364935874938965,-20.14075469970703,60.526981353759766,0.8145081756376978 +2.2583165168762207,-20.10450553894043,60.4759521484375,0.9273738892711655 +2.2817800045013428,-20.065608978271484,60.4212646484375,1.0091390744219086 +2.3058202266693115,-20.025814056396484,60.36589813232422,1.0920513877627365 +2.33550763130188,-19.976726531982422,60.29887390136719,1.2025544692122814 +2.3663768768310547,-19.92580223083496,60.229671478271484,1.3103883704229884 +2.3980870246887207,-19.873640060424805,60.15963363647461,1.4082527474464916 +2.435447931289673,-19.812389373779297,60.07575988769531,1.5098063792098892 +2.47487735748291,-19.74802589416504,59.98583984375,1.6098864181241548 +2.511793613433838,-19.68796730041504,59.90073013305664,1.6961469113426042 +2.5556693077087402,-19.61685562133789,59.80057144165039,1.7939799820934716 +2.602224349975586,-19.541690826416016,59.694847106933594,1.8897661139791837 +2.6489572525024414,-19.466516494750977,59.58961486816406,1.979459995138396 +2.6993846893310547,-19.38558006286621,59.47977066040039,2.053006440454141 +2.7508058547973633,-19.302852630615234,59.37775421142578,2.0782943930859625 +2.7999367713928223,-19.223663330078125,59.29468536376953,2.0747571047432922 +2.8532891273498535,-19.137065887451172,59.22412872314453,2.054002424977937 +2.901235818862915,-19.05860710144043,59.18097686767578,2.0266123434028818 +2.9525821208953857,-18.97258186340332,59.1754035949707,1.9915894864348385 +2.9985647201538086,-18.895219802856445,59.174964904785156,1.957386779345052 +3.0423758029937744,-18.82210922241211,59.15996551513672,1.9232825592116243 +3.0920169353485107,-18.74105453491211,59.10637664794922,1.8845739164364514 +3.1359283924102783,-18.670063018798828,59.048866271972656,1.8502585579849036 +3.1824593544006348,-18.595073699951172,58.99049758911133,1.813903652383834 +3.229138135910034,-18.519451141357422,58.940799713134766,1.7770340293913416 +3.2674343585968018,-18.456567764282227,58.92815017700195,1.675869323395002 +3.295053005218506,-18.410972595214844,58.923622131347656,0.68824014828811 +3.299128532409668,-18.404138565063477,58.917598724365234,0.0006044312744194597 +3.2991223335266113,-18.404144287109375,58.91722106933594,0.00012053729539476057 +3.299163341522217,-18.404081344604492,58.91688919067383,0.00023539103246137752 +3.2992098331451416,-18.404008865356445,58.916587829589844,0.00023211735520751865 +3.2992520332336426,-18.403947830200195,58.91630554199219,0.00019589122493004316 +3.2992894649505615,-18.403892517089844,58.91603469848633,0.0010076528118651614 +3.2994143962860107,-18.4036865234375,58.9156379699707,0.005711054772742401 +3.2996108531951904,-18.403364181518555,58.91530990600586,0.008219670568396207 +3.2998406887054443,-18.402978897094727,58.915077209472656,0.009591138523021247 +3.300082206726074,-18.402576446533203,58.91477584838867,0.01032711722622975 +3.300342082977295,-18.402143478393555,58.91439437866211,0.010737768125430073 +3.30055832862854,-18.401790618896484,58.913997650146484,0.006095746243994444 +3.300668478012085,-18.401611328125,58.91376495361328,0.0028878038397932306 +3.3007192611694336,-18.40152931213379,58.91373825073242,0.0014504565353904081 +3.3007562160491943,-18.40146827697754,58.91373825073242,0.001544191698035749 +3.300797700881958,-18.401397705078125,58.91373825073242,0.0017326867343849578 +3.30084490776062,-18.40131950378418,58.91373825073242,0.0018926412571275994 +3.300895929336548,-18.401235580444336,58.91373825073242,0.002034302881381549 +3.3009493350982666,-18.40114974975586,58.91373825073242,0.0021613296693950936 +3.3010013103485107,-18.40106201171875,58.91373825073242,0.0022708351753845755 +3.301060676574707,-18.400964736938477,58.91373825073242,0.002385070254178546 +3.3011088371276855,-18.4008846282959,58.91373825073242,1.664153420661185e-05 +3.3008980751037598,-18.401233673095703,58.91371154785156,0.02974243187865342 +3.3003149032592773,-18.402204513549805,58.91366958618164,0.0014313590221338714 +3.2998721599578857,-18.402952194213867,58.91352081298828,0.002049185901741383 +3.299863815307617,-18.402965545654297,58.91371154785156,0.032741079882618394 +3.3009462356567383,-18.401124954223633,58.918731689453125,0.021256202247223088 +3.3043107986450195,-18.395160675048828,58.935001373291016,0.20737651309281732 +3.3103888034820557,-18.383792877197266,58.968597412109375,0.3628315270295299 +3.3198299407958984,-18.365262985229492,59.02397918701172,0.5269480042379039 +3.333590269088745,-18.337921142578125,59.11874008178711,0.7550664731436836 +3.3543941974639893,-18.295759201049805,59.280887603759766,1.0447785253371111 +3.37721586227417,-18.248332977294922,59.47150421142578,1.2930554937036634 +3.406182289123535,-18.186193466186523,59.73925018310547,1.5787284981722907 +3.439347743988037,-18.1136531829834,60.06892776489258,1.8463942163598783 +3.4795358180999756,-18.02385902404785,60.477928161621094,2.125068377696716 +3.519092559814453,-17.933921813964844,60.883853912353516,2.367541907081158 +3.567294120788574,-17.822439193725586,61.37928771972656,2.6338434600461107 +3.616191864013672,-17.707319259643555,61.879981994628906,2.876388264556668 +3.6734776496887207,-17.569740295410156,62.46482849121094,3.1085570816035224 +3.7300875186920166,-17.43056869506836,63.04357147216797,3.2414260418181735 +3.7868189811706543,-17.28746223449707,63.62761306762695,3.287135361807275 +3.8392562866210938,-17.15167236328125,64.17325592041016,3.284781410375532 +3.8929100036621094,-17.008970260620117,64.73844146728516,3.2559407637889923 +3.9449877738952637,-16.866455078125,65.29667663574219,3.211954092807639 +3.997464418411255,-16.718456268310547,65.87198638916016,3.157350457329757 +4.040513038635254,-16.593360900878906,66.35655975341797,3.1071720321819547 +4.086299419403076,-16.456079483032227,66.88736724853516,3.0498652884409796 +4.1308746337890625,-16.318370819091797,67.41859436035156,2.9908627129171172 +4.168521404266357,-16.19855499267578,67.88034057617188,2.9388057698515966 +4.216267108917236,-16.040409088134766,68.48456573486328,2.862881452140323 +4.258617877960205,-15.894801139831543,69.05036926269531,2.777658801520892 +4.292882442474365,-15.772238731384277,69.53073120117188,2.706684134779436 +4.324746131896973,-15.65333366394043,70.00006103515625,2.6344083450712894 +4.355129718780518,-15.536208152770996,70.46391296386719,2.55703804546045 +4.381564140319824,-15.43126106262207,70.87825012207031,2.4875282674422823 +4.408544063568115,-15.320898056030273,71.30795288085938,2.425242643378365 +4.43729829788208,-15.200191497802734,71.7654800415039,2.3776835684017623 +4.460346698760986,-15.101004600524902,72.13358306884766,2.336692676434912 +4.483340740203857,-14.99937629699707,72.50714111328125,2.2939726067043256 +4.505251884460449,-14.899659156799316,72.8720474243164,2.2516988099476887 +4.528591632843018,-14.790120124816895,73.27031707763672,2.2051166571176726 +4.549142837524414,-14.690618515014648,73.62957763671875,2.1627282614871626 +4.569309711456299,-14.589897155761719,73.99156188964844,2.119750327185602 +4.588140964508057,-14.49271011352539,74.34020233154297,2.0782942405038485 +4.605117321014404,-14.402318954467773,74.66321563720703,2.0397906388386757 +4.622328281402588,-14.307748794555664,74.9999008178711,1.9995095413968216 +4.634849548339844,-14.235621452331543,75.2564697265625,1.2178337883719013 +4.641530513763428,-14.195034980773926,75.40319061279297,0.700661152718584 +4.645434379577637,-14.170503616333008,75.49494171142578,0.3743755310547938 +4.647434234619141,-14.157597541809082,75.54359436035156,0.2108878292547741 +4.648611068725586,-14.14966869354248,75.57552337646484,0.15081316417185653 +4.64946174621582,-14.143768310546875,75.600341796875,0.10351463010264934 +4.6500043869018555,-14.139893531799316,75.61677551269531,0.061327199723396765 +4.650091171264648,-14.13895034790039,75.62004852294922,0.007900789448422782 +4.650046348571777,-14.139473915100098,75.61875915527344,0.01968395524464014 +4.649372577667236,-14.144184112548828,75.59320068359375,0.17903583170550497 +4.64802360534668,-14.154241561889648,75.53369903564453,0.2586521478342106 +4.645706653594971,-14.171637535095215,75.43852996826172,0.4506774295434706 +4.64298152923584,-14.193923950195312,75.31485748291016,0.5515485170343112 +4.639723300933838,-14.220986366271973,75.1569595336914,0.655853648235981 +4.635463237762451,-14.256938934326172,74.94979095458984,0.8023084099309534 +4.630886077880859,-14.295145034790039,74.72389221191406,0.8853353410928174 +4.625190734863281,-14.341282844543457,74.45114135742188,1.062927551026947 +4.618522644042969,-14.393338203430176,74.14408874511719,1.1956185112920075 +4.611036777496338,-14.449394226074219,73.81288146972656,1.32168737228648 +4.601502895355225,-14.517598152160645,73.40904235839844,1.4412237601600852 +4.591484069824219,-14.585850715637207,73.00282287597656,1.5423357780152245 +4.580073833465576,-14.660025596618652,72.55775451660156,1.6360741991743557 +4.567349433898926,-14.739319801330566,72.07604217529297,1.72927560604946 +4.55443811416626,-14.816818237304688,71.59716796875,1.8033574697230113 +4.54046630859375,-14.897677421569824,71.08938598632812,1.87142042040453 +4.523714065551758,-14.990595817565918,70.4977798461914,1.9425032954971322 +4.50691556930542,-15.07918930053711,69.93008422851562,2.0030660257279918 +4.487431526184082,-15.176584243774414,69.3051986694336,2.0440508896389047 +4.471059799194336,-15.25462532043457,68.80371856689453,2.0260588925409535 +4.450323104858398,-15.349122047424316,68.19557189941406,1.9457561219588646 +4.429664611816406,-15.438980102539062,67.6158676147461,1.8336707829782262 +4.410417556762695,-15.519222259521484,67.09635162353516,1.7171220177556878 +4.393216133117676,-15.588353157043457,66.64707946777344,1.6092529950029806 +4.375141143798828,-15.658608436584473,66.18865966796875,1.4952453427960883 +4.358016490936279,-15.723325729370117,65.7650375366211,1.386194651192728 +4.340494155883789,-15.787163734436035,65.34501647949219,1.278956564656815 +4.3248820304870605,-15.842679023742676,64.97859191894531,1.1852666778282077 +4.310328006744385,-15.893275260925293,64.64361572265625,1.0993879391434342 +4.297230243682861,-15.937664031982422,64.34856414794922,1.0250243699682935 +4.28384256362915,-15.98261547088623,64.04948425292969,0.9481400859851791 +4.271941661834717,-16.021753311157227,63.788333892822266,0.8804092287166841 +4.260311603546143,-16.059356689453125,63.53684616088867,0.8152537499638366 +4.24925422668457,-16.094568252563477,63.30071258544922,0.7542737461170027 +4.239189624786377,-16.126184463500977,63.08820724487305,0.6995669753737279 +4.230044841766357,-16.154783248901367,62.89842987060547,0.5871210286769981 +4.222012042999268,-16.179819107055664,62.730960845947266,0.4945214392223788 +4.215207576751709,-16.200748443603516,62.58870315551758,0.43589706929811944 +4.209583759307861,-16.217906951904297,62.4742546081543,0.3943824681055752 +4.204163551330566,-16.234375,62.366111755371094,0.36090072173195586 +4.198599338531494,-16.251068115234375,62.25273132324219,0.35136058506977197 +4.193312644958496,-16.26679801940918,62.14584732055664,0.3437643696320899 +4.1884846687316895,-16.281078338623047,62.047523498535156,0.37458665189605855 +4.181551933288574,-16.301101684570312,61.90552520751953,0.4241958654839665 +4.1753668785095215,-16.319011688232422,61.78273391723633,0.42700277545202797 +4.168843746185303,-16.337726593017578,61.652099609375,0.4507321839971604 +4.161806106567383,-16.35795783996582,61.51927947998047,0.4757211376837014 +4.153767108917236,-16.380720138549805,61.364288330078125,0.503904981840124 +4.145766258239746,-16.40325927734375,61.20806121826172,0.5340925090829457 +4.136951446533203,-16.427886962890625,61.03915786743164,0.5595228936902293 +4.128196716308594,-16.45204734802246,60.87398910522461,0.57225168415035 +4.1186933517456055,-16.47795295715332,60.69540786743164,0.6253802381368458 +4.108529090881348,-16.505645751953125,60.50546646118164,0.649435921290562 +4.096948623657227,-16.536808013916016,60.289913177490234,0.6908493883079949 +4.0854411125183105,-16.567556381225586,60.07477569580078,0.7272850711583554 +4.0734968185424805,-16.598899841308594,59.8582649230957,0.7698136945641126 +4.060098648071289,-16.633705139160156,59.615848541259766,0.8027292104459521 +4.0467529296875,-16.66795539855957,59.37590408325195,0.8244424551015426 +4.0318427085876465,-16.705671310424805,59.111656188964844,0.8647448119212556 +4.016895771026611,-16.742897033691406,58.851051330566406,0.8870012176939608 +4.002048969268799,-16.77949333190918,58.594112396240234,0.9188326585846665 +3.985691547393799,-16.81879234313965,58.31538772583008,0.9564407820986255 +3.967904806137085,-16.861244201660156,58.02239990234375,0.9799069425740835 +3.949000120162964,-16.905733108520508,57.71467208862305,1.0183103704967102 +3.929960250854492,-16.949901580810547,57.407745361328125,1.0307392177494639 +3.9095823764801025,-16.99651527404785,57.082332611083984,1.0599356477368824 +3.889763355255127,-17.04118537902832,56.769527435302734,1.0793062503557238 +3.8707542419433594,-17.08350372314453,56.47134017944336,1.0636999834193235 +3.8492648601531982,-17.13067626953125,56.13808822631836,1.0634444183744605 +3.8292629718780518,-17.173994064331055,55.829986572265625,1.090044736327389 +3.8058574199676514,-17.2238712310791,55.47553634643555,1.135145580946632 +3.7827978134155273,-17.272216796875,55.13140869140625,1.181961359760557 +3.759855031967163,-17.31960678100586,54.792457580566406,1.2041477200159745 +3.734450578689575,-17.37127685546875,54.421810150146484,1.2131713839063145 +3.708465576171875,-17.423276901245117,54.048072814941406,1.2380328788862012 +3.6814582347869873,-17.4764347076416,53.664669036865234,1.246081039838761 +3.657292604446411,-17.52329444885254,53.32469940185547,1.2365826729782659 +3.63004469871521,-17.575359344482422,52.944515228271484,1.1994534905727778 +3.6033124923706055,-17.62559700012207,52.577667236328125,1.1674005449034168 +3.5774974822998047,-17.673418045043945,52.22724533081055,1.1085672473159554 +3.5533857345581055,-17.71748161315918,51.90311050415039,1.041094207460656 +3.5305354595184326,-17.758716583251953,51.59873962402344,0.9712864873181515 +3.5111324787139893,-17.7933349609375,51.342281341552734,0.9096458000584227 +3.490147829055786,-17.830371856689453,51.06683349609375,0.8417634898779004 +3.4714457988739014,-17.863037109375,50.82303237915039,0.7808537435374064 +3.453707218170166,-17.893728256225586,50.5931282043457,0.723034911821926 +3.4391844272613525,-17.918643951416016,50.40587615966797,0.6757587847191906 +3.423114776611328,-17.945999145507812,50.19961166381836,0.6235892319598774 +3.408623695373535,-17.97047996520996,50.014495849609375,0.5767859480882191 +3.3952975273132324,-17.99295997619629,49.844112396240234,0.5348108878291984 +3.382884979248047,-18.01350212097168,49.68794250488281,0.49531264558952065 +3.371074676513672,-18.033035278320312,49.53911590576172,0.4574940352150589 +3.361154317855835,-18.049381256103516,49.4143180847168,0.4258288231883451 +3.351229429244995,-18.065664291381836,49.289676666259766,0.39428686305196914 +3.3420825004577637,-18.080604553222656,49.17520523071289,0.36537831604611354 +3.334120750427246,-18.093658447265625,49.074668884277344,0.2900301407766643 +3.3278818130493164,-18.104032516479492,48.99158477783203,0.25642644449677177 +3.3223021030426025,-18.11313819885254,48.91968536376953,0.22301343251443764 +3.317894458770752,-18.12030792236328,48.86310577392578,0.1968197679560048 +3.313124418258667,-18.1280574798584,48.80264663696289,0.17896966781770687 +3.308772563934326,-18.135040283203125,48.74776077270508,0.19516235594275674 +3.3021953105926514,-18.14546775817871,48.670684814453125,0.29564728200919255 +3.293396472930908,-18.15924835205078,48.5635986328125,0.40789458582259486 +3.2827718257904053,-18.175981521606445,48.43254089355469,0.45269857637724636 +3.2702224254608154,-18.195486068725586,48.28288650512695,0.5513690736165889 +3.254737138748169,-18.21983528137207,48.09556579589844,0.6610555043366559 +3.237042188644409,-18.247329711914062,47.88404083251953,0.7273134177709316 +3.216689348220825,-18.278615951538086,47.64226150512695,0.8244184455921596 +3.196141481399536,-18.30989646911621,47.400390625,0.9236925179307947 +3.170186996459961,-18.3490047454834,47.098140716552734,1.0251245402504818 +3.1428990364074707,-18.389650344848633,46.78349304199219,1.096778258864354 +3.1125688552856445,-18.434377670288086,46.43726348876953,1.165395756518674 +3.0781571865081787,-18.48421859741211,46.050533294677734,1.2523132271931912 +3.045379877090454,-18.530975341796875,45.6886100769043,1.3152244552018186 +3.0136449337005615,-18.57561492919922,45.342185974121094,1.3145639607807327 +2.9735586643218994,-18.631179809570312,44.91032409667969,1.30040756815038 +2.9401729106903076,-18.676721572875977,44.55256271362305,1.2731576081970104 +2.904477834701538,-18.72482681274414,44.171592712402344,1.2159113480861359 +2.8710641860961914,-18.769306182861328,43.816043853759766,1.1427504134649051 +2.8412468433380127,-18.808536529541016,43.50029754638672,1.0599271379554358 +2.8126378059387207,-18.845706939697266,43.202327728271484,1.029636083493325 +2.7852089405059814,-18.880977630615234,42.918827056884766,0.9799675669184826 +2.7558367252349854,-18.918373107910156,42.61663818359375,0.915360358274524 +2.7314915657043457,-18.949079513549805,42.36729431152344,0.8569318504469329 +2.7071118354797363,-18.979488372802734,42.11886215209961,0.7966174489447225 +2.6843535900115967,-19.00775909423828,41.887630462646484,0.7394355659746865 +2.6633241176605225,-19.03367042541504,41.6746826171875,0.6850676436538511 +2.6450157165527344,-19.05604362487793,41.490013122558594,0.6375592006462654 +2.6263983249664307,-19.078643798828125,41.30287551879883,0.5893538800926987 +2.609452247619629,-19.09908103942871,41.132957458496094,0.5456409542690165 +2.593414545059204,-19.118310928344727,40.97252655029297,0.5044315533432485 +2.580207347869873,-19.134122848510742,40.84334945678711,0.43003475209531655 +2.5682930946350098,-19.148387908935547,40.72657012939453,0.34925599570381344 +2.5594334602355957,-19.159011840820312,40.64427947998047,0.30362698598334004 +2.5501699447631836,-19.16998291015625,40.54890823364258,0.26094087751839895 +2.542825222015381,-19.178665161132812,40.47462463378906,0.23493757577269908 +2.5359091758728027,-19.18682861328125,40.41144561767578,0.25040523842298695 +2.527461051940918,-19.1966495513916,40.331600189208984,0.2928970434733084 +2.5180864334106445,-19.207632064819336,40.242733001708984,0.3454751726309727 +2.506516933441162,-19.220882415771484,40.136390686035156,0.4322749237791943 +2.4918766021728516,-19.237680435180664,39.99107360839844,0.537860715420968 +2.47430419921875,-19.257715225219727,39.81767272949219,0.6543768014589811 +2.450817823410034,-19.284317016601562,39.589900970458984,0.7556204630787762 +2.4247560501098633,-19.3137149810791,39.34077453613281,0.8693286892787988 +2.399472951889038,-19.342016220092773,39.09779357910156,0.9594519292970803 +2.366931438446045,-19.37807273864746,38.787689208984375,1.0693843850227678 +2.3302955627441406,-19.418184280395508,38.442344665527344,1.1708295751750204 +2.291505813598633,-19.46014404296875,38.07987976074219,1.2706968123904299 +2.251255750656128,-19.503156661987305,37.70600128173828,1.3463670533896688 +2.210531711578369,-19.54610824584961,37.331607818603516,1.4197462671821597 +2.1613609790802,-19.59724998474121,36.882747650146484,1.4959340350289039 +2.110969066619873,-19.64883041381836,36.42906188964844,1.5623114878111155 +2.058164119720459,-19.7020263671875,35.95726776123047,1.6216510352851732 +2.0027804374694824,-19.756898880004883,35.467716217041016,1.6627340816877851 +1.9496865272521973,-19.808656692504883,35.002044677734375,1.709717078225334 +1.8886396884918213,-19.867176055908203,34.471561431884766,1.7429627212759917 +1.8272762298583984,-19.924882888793945,33.942771911621094,1.8048815900345894 +1.7688970565795898,-19.978776931762695,33.44428634643555,1.8577462606582291 +1.7026766538619995,-20.038793563842773,32.88362503051758,1.9044239457754963 +1.638715147972107,-20.09566879272461,32.347023010253906,1.9429666811249764 +1.5709813833236694,-20.154842376708984,31.783321380615234,1.979936101688327 +1.5014301538467407,-20.214298248291016,31.209932327270508,2.0108902009750413 +1.424054503440857,-20.27900505065918,30.57840347290039,2.047612360048861 +1.3501780033111572,-20.339448928833008,29.980669021606445,2.081970188162594 +1.270612120628357,-20.40325164794922,29.34018325805664,2.1142439513391196 +1.1971653699874878,-20.46101188659668,28.751440048217773,2.1423149975095783 +1.1161400079727173,-20.523326873779297,28.10684585571289,2.171378524801173 +1.0326135158538818,-20.586063385009766,27.448183059692383,2.199193323443083 +0.9504637718200684,-20.64631462097168,26.805967330932617,2.2247080400833066 +0.8659303188323975,-20.706857681274414,26.15069007873535,2.2492614828824453 +0.7803569436073303,-20.76668357849121,25.49276351928711,2.272538287873495 +0.6916906833648682,-20.827157974243164,24.816614151000977,2.295163380050941 +0.6038655042648315,-20.885570526123047,24.152450561523438,2.3162033575423346 +0.5144051909446716,-20.943603515625,23.48063087463379,2.3362921391462432 +0.42131057381629944,-21.00247573852539,22.784910202026367,2.3558948932317447 +0.33669355511665344,-21.05469512939453,22.155061721801758,2.372719234570189 +0.23278579115867615,-21.117143630981445,21.385622024536133,2.3922496618863756 +0.14269651472568512,-21.169790267944336,20.723339080810547,2.408237700799733 +0.04182641953229904,-21.227094650268555,19.987276077270508,2.4250956050130488 +-0.06436048448085785,-21.28560447692871,19.218074798583984,2.4417562999304767 +-0.1592644304037094,-21.33635139465332,18.535429000854492,2.455798939273144 +-0.2655435800552368,-21.3914794921875,17.776086807250977,2.4706064562335075 +-0.36584967374801636,-21.44192123413086,17.062822341918945,2.4837678875128923 +-0.47247806191444397,-21.493881225585938,16.30778694152832,2.4978914053280414 +-0.5815405249595642,-21.54528045654297,15.539504051208496,2.512096695786728 +-0.68663090467453,-21.593164443969727,14.80273151397705,2.525233101548173 +-0.800762414932251,-21.64335823059082,14.006650924682617,2.5388108055362424 +-0.8998849391937256,-21.68545913696289,13.318448066711426,2.549937073262765 +-1.0156214237213135,-21.732913970947266,12.516254425048828,2.5621681465011252 +-1.1262574195861816,-21.776607513427734,11.750707626342773,2.5732763725047376 +-1.2379051446914673,-21.819042205810547,10.9793701171875,2.583847609586247 +-1.350262999534607,-21.86009407043457,10.20427417755127,2.5939894809906785 +-1.4619953632354736,-21.899267196655273,9.43615436553955,2.603629107232516 +-1.5795506238937378,-21.938695907592773,8.631266593933105,2.6132025796555283 +-1.6932421922683716,-21.97511100769043,7.8558125495910645,2.6220442679060367 +-1.7911252975463867,-22.00511932373047,7.190646648406982,2.629959911030863 +-1.9136157035827637,-22.04092025756836,6.360904216766357,2.6399034795171876 +-2.042954921722412,-22.076705932617188,5.486379146575928,2.6500952734260643 +-2.1606671810150146,-22.107501983642578,4.692062854766846,2.6590425518343057 +-2.287520170211792,-22.138763427734375,3.8387043476104736,2.6682717266607816 +-2.403557062149048,-22.165618896484375,3.0607898235321045,2.6763012941551687 +-2.515429973602295,-22.189924240112305,2.3131537437438965,2.6836794939930186 +-2.6721413135528564,-22.221412658691406,1.268926739692688,2.6886123365575294 +-2.8199825286865234,-22.248458862304688,0.2880634665489197,2.69936594695946 +-2.9412920475006104,-22.268701553344727,-0.5147705078125,2.7076193131432404 +-3.050987720489502,-22.285682678222656,-1.2378538846969604,2.710551944993355 +-3.183704137802124,-22.30396270751953,-2.110412359237671,2.7129964368967467 +-3.301734447479248,-22.318500518798828,-2.882964849472046,2.711477315051194 +-3.4303548336029053,-22.332475662231445,-3.720001697540283,2.7058119148892312 +-3.555870532989502,-22.34419059753418,-4.530488967895508,2.697946134696794 +-3.679241895675659,-22.35384750366211,-5.321413993835449,2.6893058667476915 +-3.801320791244507,-22.361644744873047,-6.100528240203857,2.680489435598156 +-3.9244496822357178,-22.367794036865234,-6.885412693023682,2.67170325012725 +-4.057381629943848,-22.372528076171875,-7.732306480407715,2.664694811240313 +-4.179182529449463,-22.375118255615234,-8.507424354553223,2.6635523260562843 +-4.296031475067139,-22.37592315673828,-9.244730949401855,2.6642645394884834 +-4.425757884979248,-22.374650955200195,-10.044508934020996,2.6582865298752036 +-4.543076515197754,-22.371288299560547,-10.739182472229004,2.6391820571463036 +-4.6717939376831055,-22.364986419677734,-11.459124565124512,2.570472809429327 +-4.789525032043457,-22.35672950744629,-12.07158374786377,2.4555192296608217 +-4.8995232582092285,-22.34664535522461,-12.598804473876953,2.31657454744625 +-5.0048017501831055,-22.33502197265625,-13.058063507080078,2.1654221508846474 +-5.101335048675537,-22.32246208190918,-13.435564994812012,2.016988792237337 +-5.1929779052734375,-22.308780670166016,-13.750449180603027,1.8710307934786736 +-5.271684646606445,-22.295658111572266,-13.984183311462402,1.7431756753896568 +-5.35010290145874,-22.281217575073242,-14.176594734191895,1.6143433080994816 +-5.422577857971191,-22.26651382446289,-14.310169219970703,1.4941680614634776 +-5.4883646965026855,-22.251895904541016,-14.38676643371582,1.3842469286520551 +-5.541170120239258,-22.23897933959961,-14.411700248718262,0.911055629000251 +-5.578179359436035,-22.2291259765625,-14.399250030517578,0.7533238411300188 +-5.609768390655518,-22.219938278198242,-14.351828575134277,0.6874278110112129 +-5.639056205749512,-22.210905075073242,-14.28685474395752,0.6307601807935943 +-5.665004253387451,-22.202777862548828,-14.22392749786377,0.5831882199963455 +-5.691264629364014,-22.194625854492188,-14.162373542785645,0.5365475750678408 +-5.714567184448242,-22.18750762939453,-14.111226081848145,0.4959350675417436 +-5.73671293258667,-22.18084144592285,-14.06602954864502,0.45773661444040126 +-5.756556987762451,-22.174978256225586,-14.029072761535645,0.42373700181262464 +-5.772455215454102,-22.170366287231445,-13.99992847442627,0.3341191214762303 +-5.786307334899902,-22.16643524169922,-13.978750228881836,0.30055947604355737 +-5.798032760620117,-22.16319465637207,-13.960591316223145,0.25225357893174777 +-5.809123516082764,-22.16010856628418,-13.950519561767578,0.2768300185479957 +-5.823321342468262,-22.156158447265625,-13.937825202941895,0.3160217736718429 +-5.844509601593018,-22.15032958984375,-13.91594409942627,0.48674325154614845 +-5.867832660675049,-22.143903732299805,-13.88878345489502,0.5399111971898766 +-5.891807556152344,-22.13730239868164,-13.859333992004395,0.6022466888612404 +-5.92198371887207,-22.128963470458984,-13.820636749267578,0.711966309146078 +-5.961208820343018,-22.11805534362793,-13.765707969665527,0.8797280866005928 +-6.001656532287598,-22.106731414794922,-13.70421314239502,0.9771238122234842 +-6.049650192260742,-22.09318733215332,-13.624226570129395,1.055758812955266 +-6.0963287353515625,-22.079936981201172,-13.540453910827637,1.132549066969926 +-6.149772644042969,-22.064687728881836,-13.438008308410645,1.221971351798268 +-6.208320140838623,-22.047914505004883,-13.318286895751953,1.30264056049017 +-6.270431995391846,-22.030073165893555,-13.183734893798828,1.368787106775995 +-6.329221725463867,-22.013158798217773,-13.049518585205078,1.4319242391500675 +-6.399888038635254,-21.99277114868164,-12.878438949584961,1.460121337511694 +-6.463494300842285,-21.974428176879883,-12.716204643249512,1.4516773003369834 +-6.527612209320068,-21.956039428710938,-12.546375274658203,1.473238810696894 +-6.594266891479492,-21.936906814575195,-12.364582061767578,1.450331238158151 +-6.660219192504883,-21.917938232421875,-12.180438995361328,1.3920982651647604 +-6.717342853546143,-21.901691436767578,-12.018144607543945,1.3370080940939697 +-6.772653579711914,-21.886152267456055,-11.860796928405762,1.2838400274991815 +-6.832086086273193,-21.86965560913086,-11.692399978637695,1.2065124725987266 +-6.886223793029785,-21.854833602905273,-11.540575981140137,1.1260060896570696 +-6.934071063995361,-21.841899871826172,-11.408161163330078,1.05032648326031 +1.8467841148376465,-12.912968635559082,80.66455841064453,0.001060550294390238 +1.846779465675354,-12.913028717041016,80.66455841064453,0.0007782031421679642 +1.8467684984207153,-12.913140296936035,80.66455841064453,0.0014426239638963324 +1.8468412160873413,-12.91274642944336,80.6644287109375,0.012357713375813774 +1.8468824625015259,-12.912543296813965,80.6644287109375,0.0011387338421597728 +1.846872091293335,-12.912651062011719,80.6644287109375,0.0011642367327111835 +1.8468573093414307,-12.912776947021484,80.6644287109375,0.007518848854258271 +1.8468226194381714,-12.913021087646484,80.6644287109375,0.010769902981714432 +1.8467633724212646,-12.913431167602539,80.6644287109375,0.012441150421523777 +1.8467023372650146,-12.913853645324707,80.6644287109375,0.011432573274299527 +1.8466466665267944,-12.914238929748535,80.6644287109375,0.011013114127661566 +1.8465960025787354,-12.914586067199707,80.6644287109375,0.008712247567707266 +1.8465157747268677,-12.915127754211426,80.6644287109375,0.01514261804734417 +1.8465511798858643,-12.914939880371094,80.66429901123047,0.027493858943781566 +1.8469158411026,-12.912707328796387,80.6640396118164,0.061156708745204166 +1.8474562168121338,-12.909395217895508,80.66385650634766,0.07887879913812637 +1.848066806793213,-12.905648231506348,80.66385650634766,0.08777172811780194 +1.8485267162322998,-12.90282154083252,80.66385650634766,0.09117726959684333 +1.8492199182510376,-12.898564338684082,80.66385650634766,0.09359086431086111 +1.8497270345687866,-12.895448684692383,80.66385650634766,0.09414977638217807 +1.8504095077514648,-12.891255378723145,80.66385650634766,0.0939840115476083 +1.8511240482330322,-12.886863708496094,80.66385650634766,0.09314548290394566 +1.8518458604812622,-12.882431030273438,80.66385650634766,0.09191212447277965 +1.8523011207580566,-12.879634857177734,80.66385650634766,0.09101570959225071 +1.8527600765228271,-12.87681770324707,80.66385650634766,0.09005451806536688 +1.8534432649612427,-12.872621536254883,80.66385650634766,0.08855275337841709 +1.8541232347488403,-12.868444442749023,80.66385650634766,0.08700869890842147 +1.8547260761260986,-12.86474323272705,80.66385650634766,0.08561825973772966 +1.8553310632705688,-12.861028671264648,80.66385650634766,0.08421106794896498 +1.8557970523834229,-12.858165740966797,80.66385650634766,0.08312345121280151 +1.8564096689224243,-12.854405403137207,80.66385650634766,0.08169181213569542 +1.856833577156067,-12.85180377960205,80.66385650634766,0.08070039794341345 +1.8574378490447998,-12.848094940185547,80.66385650634766,0.07928939220667608 +1.8579719066619873,-12.84481430053711,80.66385650634766,0.07804296349952111 +1.8585773706436157,-12.841096878051758,80.66385650634766,0.07663328435614229 +1.8591102361679077,-12.837830543518066,80.66385650634766,0.0753958724239535 +1.8594766855239868,-12.83558464050293,80.66378021240234,0.0007387540783401231 +1.8594741821289062,-12.835599899291992,80.66346740722656,1.694392173859087e-05 +1.8594741821289062,-12.835601806640625,80.66346740722656,6.780881098100855e-06 +1.8594743013381958,-12.83559799194336,80.66346740722656,9.717294281161382e-06 +1.859474778175354,-12.835594177246094,80.66346740722656,9.641896481052893e-06 +1.8594754934310913,-12.835589408874512,80.66346740722656,8.495309681619325e-06 +1.85947585105896,-12.835586547851562,80.66346740722656,7.513463411411733e-06 +1.8594759702682495,-12.83558464050293,80.66346740722656,7.153898980900425e-06 +1.859476089477539,-12.835582733154297,80.66346740722656,6.751512740608398e-06 +1.8594763278961182,-12.83558177947998,80.66346740722656,6.269873879855717e-06 +1.8594764471054077,-12.835580825805664,80.66346740722656,6.086976232841164e-06 +1.8594764471054077,-12.835579872131348,80.66346740722656,6.175082758013285e-06 +1.8594764471054077,-12.835579872131348,80.66346740722656,6.0608287709256796e-06 +1.8594765663146973,-12.835577964782715,80.66346740722656,5.8389081463538495e-06 +1.8594765663146973,-12.835577964782715,80.66346740722656,5.90649438323245e-06 +1.8594765663146973,-12.835577011108398,80.66346740722656,5.5665210679828634e-06 +1.8594765663146973,-12.835577011108398,80.66346740722656,5.907760261552636e-06 +1.8594765663146973,-12.835577011108398,80.66346740722656,5.927254166796151e-06 +1.8594765663146973,-12.835577011108398,80.66346740722656,6.062354326951993e-06 +1.8594765663146973,-12.835577011108398,80.66346740722656,5.769758886781878e-06 +1.8594765663146973,-12.835576057434082,80.66346740722656,5.3541045680647105e-06 +1.8595205545425415,-12.835331916809082,80.66346740722656,0.004895012377108553 +1.8595778942108154,-12.835023880004883,80.66346740722656,0.004089655390412644 +1.8596044778823853,-12.834892272949219,80.66346740722656,0.001888370442213866 +1.8596271276474,-12.834795951843262,80.66346740722656,0.0031617874733040232 +1.859631896018982,-12.83481502532959,80.66346740722656,0.0004053018711117936 +1.8596084117889404,-12.835006713867188,80.66346740722656,0.0040804124091789445 +1.859575867652893,-12.835237503051758,80.66346740722656,0.006566281253041927 +1.859363317489624,-12.83659553527832,80.66333770751953,0.03640876829859534 +1.8590731620788574,-12.8384370803833,80.66333770751953,0.03681575308097815 +1.8585779666900635,-12.841541290283203,80.66323852539062,0.09094294959723498 +1.8580231666564941,-12.845009803771973,80.66323852539062,0.07572034987110986 +1.8575713634490967,-12.8478364944458,80.66323852539062,0.08586198470025257 +1.8569704294204712,-12.851554870605469,80.6622085571289,0.10691185360904112 +1.8555365800857544,-12.860454559326172,80.66192626953125,0.24951362505818864 +1.854244351387024,-12.868484497070312,80.66268920898438,0.27503465183225045 +1.852038860321045,-12.881975173950195,80.65772247314453,0.33353089158247645 +1.8492324352264404,-12.899397850036621,80.65837097167969,0.3745282339950554 +1.8462154865264893,-12.91805648803711,80.65849304199219,0.4995581288275905 +1.8434407711029053,-12.935184478759766,80.65653228759766,0.5315959724242845 +1.840469479560852,-12.953593254089355,80.65776824951172,0.5650714623020365 +1.837515115737915,-12.971749305725098,80.65644073486328,0.6201902559415001 +1.8343819379806519,-12.991063117980957,80.65620422363281,0.6547198944732907 +1.8291807174682617,-13.023141860961914,80.65432739257812,0.7083908486644229 +1.823498010635376,-13.058218955993652,80.6536865234375,0.7552196065057092 +1.819785714149475,-13.081170082092285,80.65433502197266,0.8043331625144877 +1.8136696815490723,-13.118998527526855,80.65477752685547,0.8658614036597362 +1.8069911003112793,-13.160326957702637,80.6542739868164,0.9220969333137355 +1.8000129461288452,-13.203588485717773,80.65518188476562,0.9799472798771214 +1.7949343919754028,-13.235064506530762,80.6555404663086,1.006063023341284 +1.7869967222213745,-13.284163475036621,80.6532974243164,1.0480252236471197 +1.7786810398101807,-13.335641860961914,80.65238189697266,1.112495510451861 +1.7703434228897095,-13.387161254882812,80.6490478515625,1.1549978911215262 +1.7618086338043213,-13.439939498901367,80.6472396850586,1.1955864447892883 +1.7526963949203491,-13.496211051940918,80.64351654052734,1.2246505011769786 +1.7434003353118896,-13.553730010986328,80.64331817626953,1.2610234522664119 +1.7335212230682373,-13.614826202392578,80.6420669555664,1.3006667165942405 +1.7236777544021606,-13.675822257995605,80.64353942871094,1.321421106022215 +1.717914342880249,-13.711435317993164,80.63992309570312,1.3264658288129105 +1.7115108966827393,-13.751379013061523,80.64498138427734,0.9527558121459423 +1.707676649093628,-13.775164604187012,80.64588165283203,0.6177339559135887 +1.704408049583435,-13.795377731323242,80.6455307006836,0.30876493376447445 +1.7029293775558472,-13.80453109741211,80.6452407836914,0.14591110842305924 +1.7022595405578613,-13.808691024780273,80.64495849609375,0.04247832309735828 +1.7021735906600952,-13.809244155883789,80.64462280273438,0.010218089784508257 +1.7023653984069824,-13.808080673217773,80.6444320678711,0.03849360705593467 +1.7025705575942993,-13.80683708190918,80.64429473876953,0.031125467037867182 +1.7027465105056763,-13.805791854858398,80.64393615722656,0.019909690340507293 +1.7028084993362427,-13.805441856384277,80.64373779296875,0.006674866278143753 +1.7028295993804932,-13.805356979370117,80.6434555053711,0.005028832248263893 +1.7026939392089844,-13.806243896484375,80.6434555053711,0.023014205355793918 +1.7025154829025269,-13.807395935058594,80.64330291748047,0.03424471084506854 +1.7023296356201172,-13.808576583862305,80.64299774169922,0.03993267536893911 +1.7018319368362427,-13.81167221069336,80.6420669555664,0.11736870589288358 +1.7008671760559082,-13.817747116088867,80.64215087890625,0.21116101511347235 +1.6988506317138672,-13.83053207397461,80.64752960205078,0.32744538620226943 +1.6963865756988525,-13.845820426940918,80.64671325683594,0.3409283546418368 +1.6946877241134644,-13.856368064880371,80.64647674560547,0.3392161701368411 +1.692986249923706,-13.866924285888672,80.64604949951172,0.35455711670614887 +1.6897612810134888,-13.8868989944458,80.64505004882812,0.4362954475310043 +1.6860686540603638,-13.909815788269043,80.64454650878906,0.534380414611001 +1.683403730392456,-13.926359176635742,80.6445541381836,0.5844651141752539 +1.6788229942321777,-13.954740524291992,80.6440200805664,0.6501470803761579 +1.6736607551574707,-13.986716270446777,80.64390563964844,0.7167418791498399 +1.6699987649917603,-14.009387969970703,80.64390563964844,0.7689971499639253 +1.6639798879623413,-14.046639442443848,80.64390563964844,0.8462419720761863 +1.6573641300201416,-14.087538719177246,80.64390563964844,0.9200225387977831 +1.6522141695022583,-14.119340896606445,80.64390563964844,0.9791064960883349 +1.6447968482971191,-14.165109634399414,80.64390563964844,1.0478933337760523 +1.6367897987365723,-14.214488983154297,80.64390563964844,1.10677301484423 +1.628605604171753,-14.264937400817871,80.64408111572266,1.1565555758718031 +1.6221669912338257,-14.304579734802246,80.64453125,1.1804674115936975 +1.6128458976745605,-14.361825942993164,80.64680480957031,1.236813254087428 +1.6032334566116333,-14.420604705810547,80.6511459350586,1.2917678735123628 +1.593272089958191,-14.48119831085205,80.65818786621094,1.3414624610541288 +1.5859438180923462,-14.525545120239258,80.66497802734375,1.3817268147577606 +1.5752754211425781,-14.589780807495117,80.67753601074219,1.3836722164328588 +1.5644184350967407,-14.654837608337402,80.69293212890625,1.4235081601103112 +1.5528011322021484,-14.7241849899292,80.71185302734375,1.4718804293081582 +1.5448466539382935,-14.77163314819336,80.72557830810547,1.501352644287284 +1.537163496017456,-14.817496299743652,80.73897552490234,1.5304878314279715 +1.5254853963851929,-14.88732624053955,80.75933074951172,1.5661580026294075 +1.516648530960083,-14.940260887145996,80.77477264404297,1.5881333071422494 +1.5095329284667969,-14.982915878295898,80.78753662109375,1.602961945187842 +1.5000983476638794,-15.039396286010742,80.80561065673828,1.6221797523297414 +1.4888553619384766,-15.106459617614746,80.8299789428711,1.6396511255772093 +1.4795867204666138,-15.161455154418945,80.85307312011719,1.655437504552346 +1.470136284828186,-15.217228889465332,80.87960052490234,1.6751164957946127 +1.4566009044647217,-15.296640396118164,80.92254638671875,1.699339897880953 +1.4439533948898315,-15.370498657226562,80.96707153320312,1.7189773538127364 +1.4307054281234741,-15.447628021240234,81.01777648925781,1.7355438905149023 +1.4202245473861694,-15.508481979370117,81.06109619140625,1.736117599856447 +1.4110349416732788,-15.561763763427734,81.10084533691406,1.729347051891774 +1.3975549936294556,-15.639819145202637,81.16272735595703,1.6827373167610367 +1.3844619989395142,-15.7156400680542,81.22589111328125,1.6011672726845145 +1.3726561069488525,-15.784247398376465,81.28469848632812,1.5092800809655418 +1.3610693216323853,-15.85181999206543,81.34317779541016,1.4089626908145236 +1.3503869771957397,-15.914387702941895,81.39745330810547,1.3113638469781903 +1.3408033847808838,-15.970748901367188,81.44745635986328,1.2209765417585394 +1.33452570438385,-16.00764274597168,81.48170471191406,1.1609978361761497 +1.3255388736724854,-16.060211181640625,81.53331756591797,1.0749961446057978 +1.3171387910842896,-16.109365463256836,81.58454132080078,0.9939070664734381 +1.3101823329925537,-16.150043487548828,81.62814331054688,0.9265325477453338 +1.3052661418914795,-16.178861618041992,81.65926361083984,0.8787276523833358 +1.2987945079803467,-16.2169132232666,81.70057678222656,0.815558976525222 +1.2922509908676147,-16.255491256713867,81.7428970336914,0.7515267579316784 +1.2867785692214966,-16.287723541259766,81.77945709228516,0.6980272109420453 +1.2817027568817139,-16.31765365600586,81.81383514404297,0.648366868635801 +1.2773804664611816,-16.343225479125977,81.84342193603516,0.6058410415988082 +1.2728546857833862,-16.370086669921875,81.87451934814453,0.5612302596341748 +1.268141508102417,-16.398040771484375,81.90777587890625,0.5148152503962059 +1.2641397714614868,-16.4211483001709,81.94035339355469,0.47638878432598347 +1.2602051496505737,-16.443058013916016,81.97755432128906,0.43987841012532003 +1.2573121786117554,-16.4588680267334,82.01004791259766,0.35578119804653235 +1.2543437480926514,-16.474817276000977,82.04493713378906,0.2792169168205704 +1.252013921737671,-16.48714828491211,82.07269287109375,0.23651696407467634 +1.2500245571136475,-16.49766731262207,82.0965347290039,0.20544798113144352 +1.2482701539993286,-16.50686264038086,82.11526489257812,0.16684238961709824 +1.246949315071106,-16.513957977294922,82.13410186767578,0.15570358416920393 +1.2458409070968628,-16.519739151000977,82.1477279663086,0.13837695457271706 +1.2447268962860107,-16.525604248046875,82.16500854492188,0.11423040980897543 +1.2438387870788574,-16.530216217041016,82.17823028564453,0.09591451119761651 +1.2431325912475586,-16.533832550048828,82.1867904663086,0.06439325678170581 +1.2424719333648682,-16.53715705871582,82.19127655029297,0.06951895039924375 +1.2419229745864868,-16.53997802734375,82.1995849609375,0.0603915093652936 +1.2414569854736328,-16.54237937927246,82.20545959472656,0.05166453168027454 +1.2409523725509644,-16.544872283935547,82.21244812011719,0.04734648657207358 +1.240485429763794,-16.54706573486328,82.2198486328125,0.04794432169007291 +1.2401070594787598,-16.548978805541992,82.22474670410156,0.04321922369594721 +1.2397465705871582,-16.550729751586914,82.2299575805664,0.03638079208442082 +1.239371657371521,-16.55255126953125,82.23509979248047,0.036488452512808196 +1.2390121221542358,-16.554264068603516,82.24048614501953,0.04325881202606702 +1.238546371459961,-16.556379318237305,82.24845886230469,0.0450603478187859 +1.2380335330963135,-16.55876350402832,82.2567138671875,0.06076854681497074 +1.2374366521835327,-16.56145668029785,82.26647186279297,0.06079350346783094 +1.2368148565292358,-16.564237594604492,82.27759552001953,0.06294922403316801 +1.2361831665039062,-16.56710433959961,82.28829956054688,0.0565120080892738 +1.2352737188339233,-16.571199417114258,82.30121612548828,0.10725246368182491 +1.2342300415039062,-16.576053619384766,82.32286834716797,0.13346732241771764 +1.2328331470489502,-16.582273483276367,82.34209442138672,0.13739116192682432 +1.2314242124557495,-16.58854866027832,82.36511993408203,0.1304746546708139 +1.230021595954895,-16.59488296508789,82.38897705078125,0.14242469776918487 +1.2284382581710815,-16.60204315185547,82.41561126708984,0.1911270094186772 +1.2265704870224,-16.610525131225586,82.44606018066406,0.18728135155363926 +1.22452712059021,-16.61998176574707,82.48450469970703,0.2324885057018761 +1.2220079898834229,-16.631372451782227,82.5291748046875,0.23497845775317833 +1.2192505598068237,-16.643856048583984,82.57310485839844,0.29775261918734397 +1.2161473035812378,-16.658100128173828,82.6252670288086,0.3258519924473092 +1.2130391597747803,-16.67243766784668,82.67863464355469,0.33937446449742725 +1.2096147537231445,-16.688196182250977,82.73880767822266,0.3289038686261245 +1.2066622972488403,-16.701772689819336,82.79096221923828,0.31906458111792557 +1.2037955522537231,-16.71502113342285,82.84175872802734,0.3086558088949651 +1.1999659538269043,-16.732412338256836,82.9108657836914,0.39559721648996526 +1.195500373840332,-16.752714157104492,82.99935150146484,0.4527386088846896 +1.1905574798583984,-16.774810791015625,83.09368896484375,0.4584175532015664 +1.1861201524734497,-16.794912338256836,83.17715454101562,0.5120503730028181 +1.1805893182754517,-16.82016372680664,83.2868881225586,0.5545034674770207 +1.174704670906067,-16.847253799438477,83.40213775634766,0.5856779186722909 +1.1692020893096924,-16.872661590576172,83.51228332519531,0.5891478161690927 +1.1629807949066162,-16.901458740234375,83.63937377929688,0.6236850223434949 +1.1565371751785278,-16.930908203125,83.7758560180664,0.6314835835610099 +1.1504690647125244,-16.95840072631836,83.90816497802734,0.6462535217826753 +1.1439000368118286,-16.98790168762207,84.05531311035156,0.6725787235716172 +1.1364613771438599,-17.021076202392578,84.22578430175781,0.6964960076424953 +1.129090428352356,-17.05371856689453,84.40036010742188,0.7214515495993252 +1.121787428855896,-17.085973739624023,84.57711791992188,0.7540873549838967 +1.1141119003295898,-17.119762420654297,84.7679672241211,0.7761639467722131 +1.10536789894104,-17.158048629760742,84.99238586425781,0.8078091513042289 +1.0968992710113525,-17.195140838623047,85.21588134765625,0.83903780630744 +1.088063359260559,-17.234088897705078,85.4537124633789,0.8644092131739375 +1.0795750617980957,-17.27206802368164,85.68647766113281,0.8956481641000436 +1.0704591274261475,-17.313623428344727,85.94082641601562,0.9181277229518788 +1.0611305236816406,-17.357017517089844,86.20750427246094,0.9168268639041901 +1.0526520013809204,-17.39743423461914,86.4542465209961,0.933598872083856 +1.0440490245819092,-17.439584732055664,86.70915985107422,0.9281956676261184 +1.035959243774414,-17.48040199279785,86.95269012451172,0.8930898370357356 +1.0280190706253052,-17.521987915039062,87.19522857666016,0.8417539295537276 +1.021362543106079,-17.558534622192383,87.40106201171875,0.7895286904993071 +1.0153214931488037,-17.59352684020996,87.58942413330078,0.7360231277861743 +1.0102508068084717,-17.62479019165039,87.74833679199219,0.6865318664841529 +1.0055198669433594,-17.655893325805664,87.8970718383789,0.6363511582207774 +1.0015586614608765,-17.68367576599121,88.02189636230469,0.5910977036858004 +0.9979243278503418,-17.710859298706055,88.13658905029297,0.5466000165967612 +0.9949772953987122,-17.734365463256836,88.22966003417969,0.5080485428896795 +0.9922152757644653,-17.757871627807617,88.31674194335938,0.46946923640584914 +0.9900123476982117,-17.77785301208496,88.38592529296875,0.4366589669230201 +0.9880001544952393,-17.797306060791016,88.44886779785156,0.40473745109991954 +0.9862595200538635,-17.815378189086914,88.50285339355469,0.37510557060545263 +0.9847866892814636,-17.832075119018555,88.5477523803711,0.3477691859053125 +0.9835445880889893,-17.847806930541992,88.5845947265625,0.3220349845030157 +0.982539713382721,-17.8625545501709,88.61282348632812,0.29791580745214324 +0.981794536113739,-17.875450134277344,88.6322250366211,0.24193711039834645 +0.981350839138031,-17.884763717651367,88.64225006103516,0.18884844130029368 +0.9810560941696167,-17.892425537109375,88.64653015136719,0.1441746272077895 +0.980871319770813,-17.89921760559082,88.6481704711914,0.13080736060195133 +0.9807600975036621,-17.90546226501465,88.6468505859375,0.13425887953088325 +0.9807228446006775,-17.911401748657227,88.64340209960938,0.10642805577992494 +0.9807738065719604,-17.91592788696289,88.63748931884766,0.09630076442063235 +0.9808670878410339,-17.919940948486328,88.6308364868164,0.083568641019967 +0.9809987545013428,-17.924633026123047,88.62174987792969,0.09690636025414917 +0.981160581111908,-17.930376052856445,88.6109390258789,0.1482421435413292 +0.9813675284385681,-17.937808990478516,88.59274291992188,0.16729957039464166 +0.9816251397132874,-17.9465274810791,88.56914520263672,0.21192918189843946 +0.9819459915161133,-17.955305099487305,88.54859924316406,0.20460036286753192 +0.9823615550994873,-17.965930938720703,88.52023315429688,0.23530451600792596 +0.9829175472259521,-17.980356216430664,88.4776382446289,0.3045375170619962 +0.9835576415061951,-17.99566078186035,88.43456268310547,0.3413502471711543 +0.9842607378959656,-18.0111083984375,88.38345336914062,0.44442332612155167 +0.9851991534233093,-18.03196907043457,88.3305435180664,0.4935996231603515 +0.98638916015625,-18.057777404785156,88.2538070678711,0.5907961985076309 +0.9877846837043762,-18.087932586669922,88.16332244873047,0.6456088812968789 +0.989295244216919,-18.12161636352539,88.05830383300781,0.7837878105278571 +0.9911402463912964,-18.1632080078125,87.92752838134766,0.8703876627494251 +0.9928233027458191,-18.202375411987305,87.80223846435547,0.9347946433485192 +0.9946722388267517,-18.246906280517578,87.65846252441406,1.0278473917955462 +0.9968839883804321,-18.301969528198242,87.47760772705078,1.1491628153429312 +0.9990856051445007,-18.358015060424805,87.2912368774414,1.2143713686166657 +1.0013904571533203,-18.41963768005371,87.08309936523438,1.2996564082378153 +1.0032708644866943,-18.47381591796875,86.89664459228516,1.3556302445525983 +1.0058873891830444,-18.555908203125,86.61207580566406,1.3063582665925275 +1.0078200101852417,-18.625513076782227,86.37200164794922,1.3824338499396982 +1.009250521659851,-18.690013885498047,86.14887237548828,1.5312473807684654 +1.0106239318847656,-18.765472412109375,85.88834381103516,1.6099541822983103 +1.0116199254989624,-18.836048126220703,85.64494323730469,1.660831743592656 +1.0123932361602783,-18.916622161865234,85.36732482910156,1.7004420805178682 +1.0127644538879395,-19.00000762939453,85.08199310302734,1.7407043125278139 +1.0126491785049438,-19.081430435180664,84.80492401123047,1.7819127630231062 +1.0120912790298462,-19.165273666381836,84.52299499511719,1.8186248920973598 +1.0110304355621338,-19.249929428100586,84.24230194091797,1.852565288750024 +1.0095704793930054,-19.330270767211914,83.97834777832031,1.878525608836739 +1.0073493719100952,-19.425235748291016,83.66696166992188,1.9041790211998237 +1.004921793937683,-19.510814666748047,83.38555908203125,1.9221482793545843 +1.0018434524536133,-19.605615615844727,83.06936645507812,1.9239022113480406 +0.9989027380943298,-19.68738555908203,82.79122161865234,1.8906801160592137 +0.995155394077301,-19.782386779785156,82.46175384521484,1.8174155611885614 +0.9917348027229309,-19.861543655395508,82.18241119384766,1.7273533482541732 +0.9878726005554199,-19.94282341003418,81.89385986328125,1.616529101143358 +0.9841933250427246,-20.013097763061523,81.64449310302734,1.5119628066517399 +0.9803412556648254,-20.080385208129883,81.40697479248047,1.4073054195087633 +0.9762780666351318,-20.145675659179688,81.17850494384766,1.303232342547608 +0.9724521636962891,-20.202669143676758,80.98146057128906,1.211151707150505 +0.9686115980148315,-20.25614356994629,80.79917907714844,1.1241322699366398 +0.9650533199310303,-20.301780700683594,80.6332015991211,0.8404459106777116 +0.96396803855896,-20.3131103515625,80.56199645996094,0.0009366583830869178 +0.9639816284179688,-20.313068389892578,80.56181335449219,0.00034002482589126865 +0.9639842510223389,-20.313121795654297,80.56150817871094,0.00048452292172190115 +0.963982880115509,-20.313194274902344,80.56111145019531,0.0004314223563971487 +0.9639806747436523,-20.313249588012695,80.56097412109375,0.00036241794728216967 +0.963978111743927,-20.31330108642578,80.56067657470703,0.00028875284351507206 +0.9639762043952942,-20.3133487701416,80.56063079833984,0.00022242137529750088 +0.9639748334884644,-20.313385009765625,80.5603256225586,0.00016507009810281536 +0.9639742970466614,-20.313411712646484,80.55987548828125,0.0001145813701965308 +0.9639749526977539,-20.313434600830078,80.55952453613281,6.892025240609263e-05 +0.963916540145874,-20.313867568969727,80.55890655517578,0.029076373977813333 +0.9636083841323853,-20.3161563873291,80.55606079101562,0.06233634745381617 +0.9631879925727844,-20.3194637298584,80.55110931396484,0.07590261364046062 +0.9627686738967896,-20.322906494140625,80.54524993896484,0.07942287351708595 +0.9622849822044373,-20.326780319213867,80.53911590576172,0.0782378534696913 +0.9618440866470337,-20.33017349243164,80.53429412841797,0.07499220803810265 +0.961391806602478,-20.33352279663086,80.53024291992188,0.07070466087070254 +0.9609302878379822,-20.33682632446289,80.52674102783203,0.06588379877921514 +0.9605607390403748,-20.339420318603516,80.5241928100586,0.06185365265237588 +0.9601340293884277,-20.34250259399414,80.520751953125,0.056902875630018473 +0.9597994089126587,-20.345048904418945,80.51715087890625,0.05274903746410236 +0.9595324397087097,-20.347164154052734,80.51315307617188,0.009064192638777772 +0.959531843662262,-20.34715461730957,80.51290893554688,9.828984642374242e-06 +0.959531843662262,-20.34715461730957,80.51290893554688,7.729175136763195e-06 +0.9595316052436829,-20.347156524658203,80.51290893554688,9.598029135509257e-06 +0.9595319628715515,-20.3471622467041,80.51290893554688,1.0016135922919403e-05 +0.9595321416854858,-20.347164154052734,80.51290893554688,9.308831704169366e-06 +0.9595317840576172,-20.347166061401367,80.51290893554688,8.306303207845758e-06 +0.9595317840576172,-20.34716796875,80.51290893554688,7.608929817559255e-06 +0.9595319628715515,-20.347169876098633,80.51290893554688,7.0748051290115e-06 +0.9595321416854858,-20.347171783447266,80.51290893554688,6.595372936414136e-06 +0.9595320820808411,-20.347171783447266,80.51290893554688,6.218173051216056e-06 +0.9595321416854858,-20.347171783447266,80.51290893554688,6.623321187350618e-06 +0.9595544338226318,-20.347036361694336,80.51296997070312,0.026842548513172276 +0.9596215486526489,-20.346643447875977,80.51298522949219,0.001865149415648502 +0.959745466709137,-20.34589195251465,80.51303100585938,0.010644009862476595 +0.9598580002784729,-20.345233917236328,80.51303100585938,0.03629721741790656 +0.9600168466567993,-20.344308853149414,80.51295471191406,0.04350928558393981 +0.9602923393249512,-20.342702865600586,80.51264953613281,0.02456304742010719 +0.9607361555099487,-20.340139389038086,80.51193237304688,0.0847305902206417 +0.961247980594635,-20.337230682373047,80.51068878173828,0.0954574578526085 +0.9621163606643677,-20.332416534423828,80.50801086425781,0.12139135089939428 +0.9631560444831848,-20.3267879486084,80.50482177734375,0.12718327906605656 +0.964404821395874,-20.320106506347656,80.49835205078125,0.16450105526688463 +0.9659240245819092,-20.312164306640625,80.49276733398438,0.18682585159920384 +0.967884361743927,-20.301971435546875,80.48495483398438,0.2230499076924719 +0.9700176119804382,-20.290847778320312,80.47320556640625,0.25627184382143703 +0.9724442362785339,-20.27820587158203,80.45903015136719,0.31547074794717556 +0.9751742482185364,-20.263912200927734,80.43962097167969,0.3640991369255409 +0.9786353707313538,-20.24601936340332,80.41543579101562,0.4026758417152095 +0.9821949005126953,-20.227596282958984,80.38851165771484,0.4747022714876669 +0.9867417216300964,-20.204286575317383,80.35802459716797,0.5268719630877498 +0.9920355677604675,-20.177331924438477,80.3253402709961,0.5943341221789377 +0.9981862902641296,-20.146137237548828,80.28719329833984,0.6971014365064975 +1.0043268203735352,-20.115333557128906,80.24695587158203,0.7663488158015468 +1.0120534896850586,-20.077259063720703,80.1924819946289,0.8503172648307709 +1.0205172300338745,-20.036272048950195,80.12975311279297,0.9131056533911859 +1.029474139213562,-19.993663787841797,80.05998229980469,1.001802703772478 +1.0401428937911987,-19.944135665893555,79.97098541259766,1.0806606930478337 +1.0514583587646484,-19.89306640625,79.86965942382812,1.1162747223649423 +1.0635666847229004,-19.8399658203125,79.75424194335938,1.2038836595398004 +1.0764820575714111,-19.784873962402344,79.62486267089844,1.2724180717597926 +1.091378092765808,-19.722942352294922,79.4705581665039,1.344382801845057 +1.10661780834198,-19.661014556884766,79.30937194824219,1.4073459788105718 +1.1233454942703247,-19.594314575195312,79.1313705444336,1.4762507099679982 +1.14033043384552,-19.527551651000977,78.9525375366211,1.5392030996399026 +1.1584490537643433,-19.457372665405273,78.76322174072266,1.6040203517916072 +1.177024483680725,-19.386756896972656,78.56837463378906,1.6620988570398987 +1.1988502740859985,-19.305686950683594,78.3368911743164,1.7289612475222906 +1.220739483833313,-19.226137161254883,78.10433959960938,1.7900774374601294 +1.2439172267913818,-19.14334487915039,77.86101531982422,1.8506399783128693 +1.2664272785186768,-19.06416893005371,77.62821960449219,1.9054046227847872 +1.293406367301941,-18.97079849243164,77.35367584228516,1.9666770223429695 +1.319616675376892,-18.881786346435547,77.09193420410156,2.021644663194829 +1.3455305099487305,-18.794902801513672,76.8365249633789,2.068485153861765 +1.3737542629241943,-18.701814651489258,76.56327819824219,2.105660075602498 +1.4115917682647705,-18.579214096069336,76.20620727539062,2.1147704633124143 +1.4430707693099976,-18.479185104370117,75.91775512695312,2.0966080838775607 +1.472748041152954,-18.386133193969727,75.65142059326172,2.06888724331979 +1.5008741617202759,-18.299293518066406,75.40384674072266,2.03777309987686 +1.5295137166976929,-18.212047576904297,75.15614318847656,2.0034884409912244 +1.560441255569458,-18.119157791137695,74.89270782470703,1.9650069310705556 +1.5901862382888794,-18.031145095825195,74.6425552368164,1.927433567534906 +1.6185822486877441,-17.94830322265625,74.40672302246094,1.8914834638206246 +1.6478947401046753,-17.863956451416016,74.16609191894531,1.854523174398422 +1.6766576766967773,-17.782302856445312,73.93258666992188,1.8170456951709386 +1.7042028903961182,-17.705116271972656,73.7115249633789,1.7695957864016645 +1.7326737642288208,-17.626312255859375,73.48474884033203,1.7154245736427887 +1.7583727836608887,-17.55605125427246,73.2837905883789,1.6653762904507137 +1.785573959350586,-17.482494354248047,73.0718994140625,1.6118941062582268 +1.812102198600769,-17.411598205566406,72.86784362792969,1.5509726968685937 +1.8366721868515015,-17.34660530090332,72.67868041992188,1.4850374986706263 +1.8620551824569702,-17.280189514160156,72.48697662353516,1.4113268654577946 +1.884546160697937,-17.221921920776367,72.32000732421875,1.3410645856392862 +1.9061243534088135,-17.16645622253418,72.1577377319336,1.2640211192047737 +1.9256420135498047,-17.115882873535156,71.96833801269531,0.9935245795937794 +1.9342466592788696,-17.08932113647461,71.67028045654297,0.08928329847213534 +1.9341790676116943,-17.089397430419922,71.66839599609375,7.069788648535098e-05 +1.9342014789581299,-17.089372634887695,71.66826629638672,0.0001321501689394771 +1.9342395067214966,-17.08931541442871,71.66825866699219,0.00016786638875588135 +1.9342752695083618,-17.089252471923828,71.66805267333984,0.00015217166943114706 +1.9343068599700928,-17.08919334411621,71.66788482666016,0.00012414806371246226 +1.9343308210372925,-17.08914566040039,71.66780853271484,9.674765547486726e-05 +1.9343494176864624,-17.089109420776367,71.66755676269531,7.345497770854607e-05 +1.9343621730804443,-17.08908462524414,71.66706848144531,5.773183298395295e-05 +1.9343856573104858,-17.089035034179688,71.66656494140625,0.0015230151971333294 +1.9344379901885986,-17.088909149169922,71.66590118408203,0.003148809555612022 +1.9345039129257202,-17.08875274658203,71.66511535644531,0.004075658540575376 +1.93458890914917,-17.088542938232422,71.66432189941406,0.0047328429475986394 +1.9346771240234375,-17.08832550048828,71.66370391845703,0.005150328755350992 +1.9347796440124512,-17.088071823120117,71.66361999511719,0.005477723358895966 +1.9348745346069336,-17.08783721923828,71.66350555419922,0.00570142415762979 +1.9349781274795532,-17.08757972717285,71.66350555419922,0.00589901873918206 +1.935088038444519,-17.087303161621094,71.66337585449219,0.006077209169363781 +1.9351950883865356,-17.087039947509766,71.66291809082031,0.006231259485080561 +1.9353041648864746,-17.086769104003906,71.66291809082031,0.006375595142325746 +1.9354220628738403,-17.086477279663086,71.66291809082031,0.006520947105111463 +1.9355329275131226,-17.086200714111328,71.66291809082031,0.00665053844591491 +1.9355823993682861,-17.086074829101562,71.66291809082031,7.32052606335867e-06 +1.9355822801589966,-17.086074829101562,71.66291809082031,5.43882810762661e-06 +1.9355822801589966,-17.086074829101562,71.66291809082031,4.727311254245605e-06 +1.9355823993682861,-17.08607292175293,71.66291809082031,4.870264075241675e-06 +1.93558669090271,-17.086076736450195,71.66304016113281,0.015360512829619291 +1.9354270696640015,-17.086498260498047,71.6639633178711,0.02801550383835956 +1.9352364540100098,-17.087003707885742,71.66500854492188,0.025039605775062597 +1.9352198839187622,-17.087068557739258,71.66474151611328,0.023459108272683788 +1.935312032699585,-17.086864471435547,71.6638412475586,0.022810128364278308 +1.9360134601593018,-17.085115432739258,71.65777587890625,0.05420048998866326 +1.9372341632843018,-17.082056045532227,71.64888000488281,0.07623825385935593 +1.9386545419692993,-17.07847785949707,71.63903045654297,0.08707690092279481 +1.9401752948760986,-17.07459831237793,71.62913513183594,0.09239282726268719 +1.9416444301605225,-17.070781707763672,71.62053680419922,0.09460443478138172 +1.9437894821166992,-17.065046310424805,71.61026763916016,0.09520884168465102 +1.945330023765564,-17.0607852935791,71.60464477539062,0.0945929422835179 +1.9467909336090088,-17.05663299560547,71.60079956054688,0.09354816314237303 +1.9481321573257446,-17.05265998840332,71.59967041015625,0.09230372387191342 +1.9495147466659546,-17.048463821411133,71.59967041015625,0.09086724032670312 +1.9508037567138672,-17.04448699951172,71.60044860839844,0.08940821669901332 +1.951944351196289,-17.04071044921875,71.60453033447266,0.08796736459316554 +1.9531159400939941,-17.03652000427246,71.61261749267578,0.08631017302399836 +1.9541083574295044,-17.032678604125977,71.62321472167969,0.08478006050216505 +1.9550243616104126,-17.02896499633789,71.63499450683594,0.0833550575013511 +1.955832600593567,-17.025665283203125,71.64568328857422,0.08211247552798438 +1.956781268119812,-17.02178955078125,71.65818786621094,0.08065336742325145 +1.9576517343521118,-17.018230438232422,71.66957092285156,0.07931653087022895 +1.9585282802581787,-17.0146484375,71.68098449707031,0.0779714251276631 +1.959403395652771,-17.01106834411621,71.69252014160156,0.0766305208667861 +1.9602317810058594,-17.00767707824707,71.70340728759766,0.07536407780902815 +1.9608982801437378,-17.004962921142578,71.7119140625,0.00011473398021593866 +1.9608983993530273,-17.00497817993164,71.71172332763672,1.5197691954003282e-05 +1.9608980417251587,-17.00497817993164,71.71172332763672,6.310656406981687e-06 +1.9608980417251587,-17.004974365234375,71.71172332763672,9.357788625235047e-06 +1.9608982801437378,-17.004968643188477,71.71172332763672,9.095465898385852e-06 +1.9608983993530273,-17.00496482849121,71.71172332763672,8.034671353479268e-06 +1.9608983993530273,-17.004962921142578,71.71172332763672,6.929002682318099e-06 +1.960898518562317,-17.004959106445312,71.71172332763672,6.157125223702125e-06 +1.960898518562317,-17.00495719909668,71.71172332763672,5.086543204700806e-06 +1.960898756980896,-17.00495719909668,71.71172332763672,5.252009109372197e-06 +1.960898756980896,-17.004955291748047,71.71172332763672,5.483502771808429e-06 +1.960898756980896,-17.004955291748047,71.71172332763672,5.780330388055906e-06 +1.960898518562317,-17.004953384399414,71.71172332763672,5.630320472828844e-06 +1.960898756980896,-17.004953384399414,71.71172332763672,3.3689705336232045e-06 +1.960898756980896,-17.004953384399414,71.71172332763672,5.56485644904377e-06 +1.960898756980896,-17.004953384399414,71.71172332763672,5.962343864298479e-06 +1.9608914852142334,-17.004966735839844,71.7104263305664,0.012612106514796356 +1.9609919786453247,-17.004581451416016,71.71636199951172,0.032769352646972234 +1.9612902402877808,-17.00327491760254,71.72139739990234,0.045247665904944286 +1.961645483970642,-17.001665115356445,71.72848510742188,0.06049145626338774 +1.9620729684829712,-16.99970054626465,71.7371826171875,0.01897792611124597 +1.962297797203064,-16.998626708984375,71.74168395996094,0.00812383937981612 +1.962619423866272,-16.997087478637695,71.74931335449219,0.05458627910219021 +1.9630082845687866,-16.995187759399414,71.75863647460938,0.06130117402342474 +1.9633604288101196,-16.99342918395996,71.76712799072266,0.05797462121241576 +1.9637517929077148,-16.991432189941406,71.7769546508789,0.0221158460927637 +1.9642890691757202,-16.988767623901367,71.79084014892578,0.08190146441841858 +1.965211272239685,-16.98389434814453,71.81220245361328,0.1296297679583641 +1.966689109802246,-16.976348876953125,71.85114288330078,0.1866708902910131 +1.9688825607299805,-16.96485710144043,71.9098129272461,0.2627159017485469 +1.9713085889816284,-16.95193862915039,71.97501373291016,0.3242988713529716 +1.9744764566421509,-16.934894561767578,72.0652084350586,0.3898897768737557 +1.9785003662109375,-16.912702560424805,72.18709564208984,0.5037078721181794 +1.982786774635315,-16.88832664489746,72.3214111328125,0.568609371812252 +1.9876519441604614,-16.859952926635742,72.4832763671875,0.6609452820416364 +1.9931720495224,-16.826976776123047,72.67300415039062,0.7828121296481209 +1.9994899034500122,-16.788311004638672,72.89517974853516,0.861790790866203 +2.0059549808502197,-16.747512817382812,73.13075256347656,0.9732408635895502 +2.012171983718872,-16.706787109375,73.36933135986328,1.0918573203977233 +2.023831367492676,-16.62555694580078,73.85567474365234,1.198604204244741 +2.0341243743896484,-16.547773361206055,74.32950592041016,1.3717043919683256 +2.0426900386810303,-16.478214263916016,74.75252532958984,1.5123364432540862 +2.0505666732788086,-16.41029930114746,75.16504669189453,1.6308126618541678 +2.0595955848693848,-16.326873779296875,75.67159271240234,1.7650194519589224 +2.0676238536834717,-16.246049880981445,76.16388702392578,1.8847631690602749 +2.0760319232940674,-16.15176773071289,76.7422103881836,2.0148154755678798 +2.0829029083251953,-16.06418228149414,77.28335571289062,2.124517025517659 +2.089799642562866,-15.963234901428223,77.90836334228516,2.2207747390444332 +2.0956978797912598,-15.85948657989502,78.54903411865234,2.2683314294104613 +2.100644826889038,-15.751323699951172,79.21304321289062,2.2750774929134314 +2.1045944690704346,-15.638422966003418,79.89888000488281,2.257466406158896 +2.107203245162964,-15.538554191589355,80.49688720703125,2.2307272900108144 +2.1090829372406006,-15.430265426635742,81.13414764404297,2.194890497388626 +2.1099355220794678,-15.33471393585205,81.68779754638672,2.159677056186318 +2.1099510192871094,-15.23213005065918,82.27689361572266,2.1194781230290136 +2.1090104579925537,-15.134597778320312,82.8362808227539,2.079893473870764 +2.1072092056274414,-15.042032241821289,83.36807250976562,2.0416625538012285 +2.104423999786377,-14.9470796585083,83.91509246826172,2.0020789512381825 +2.100738286972046,-14.852958679199219,84.45832824707031,1.962677362634791 +2.0963711738586426,-14.763185501098633,84.976806640625,1.9249789692298511 +2.091270923614502,-14.67500114440918,85.48677062988281,1.8878625699841076 +2.0851380825042725,-14.583685874938965,86.01554870605469,1.8493719937520894 +2.0785608291625977,-14.497554779052734,86.51500701904297,1.813026369045488 +2.071258544921875,-14.411957740783691,87.01205444335938,1.77687132611898 +2.0636425018310547,-14.330941200256348,87.48321533203125,1.7426158815490274 +2.0558602809906006,-14.254838943481445,87.92636108398438,1.7104025980462552 +2.046489715576172,-14.170183181762695,88.42010498046875,1.6745363886445583 +2.0381133556365967,-14.099740982055664,88.8315200805664,1.6446620013990025 +2.0289623737335205,-14.027363777160645,89.25487518310547,1.6139420895852687 +2.0183799266815186,-13.94863510131836,89.71598052978516,1.5804927922284226 +2.008094549179077,-13.876792907714844,90.13728332519531,1.3225163227867542 +2.0008060932159424,-13.830485343933105,90.41059112548828,0.7389725584105246 +1.9966261386871338,-13.805234909057617,90.5626449584961,0.39764845225012296 +1.9944143295288086,-13.792393684387207,90.64332580566406,0.22369118141908062 +1.9931615591049194,-13.785062789916992,90.69043731689453,0.13113225452980054 +1.9923135042190552,-13.780322074890137,90.72191619873047,0.07492706026579322 +1.9918125867843628,-13.777653694152832,90.73982238769531,0.04292956497553553 +1.9915087223052979,-13.77609920501709,90.7503433227539,0.024297581819323687 +1.9913265705108643,-13.775203704833984,90.7562255859375,0.013468718361407065 +1.9912203550338745,-13.774699211120605,90.75943756103516,0.007441209928719984 +1.9911613464355469,-13.774431228637695,90.76111602783203,0.004239250398107219 +1.9911202192306519,-13.774253845214844,90.76202392578125,0.0021528870972874416 +1.9910967350006104,-13.774163246154785,90.76235961914062,0.0010755323303299185 +1.9910831451416016,-13.774114608764648,90.76240539550781,0.0005207797740354462 +1.9910743236541748,-13.774087905883789,90.76235961914062,0.00020441539374039432 +1.9910694360733032,-13.774075508117676,90.76235961914062,5.26019705894478e-05 +1.9910666942596436,-13.774067878723145,90.76235961914062,1.1876952504498612e-05 +1.9910646677017212,-13.774063110351562,90.76235961914062,3.344197215508072e-05 +1.991062879562378,-13.77405834197998,90.76235961914062,3.38795984945466e-05 +1.9910709857940674,-13.774147987365723,90.760986328125,0.006813120152560646 +1.9911452531814575,-13.774409294128418,90.7606430053711,0.00845860004098973 +1.991228461265564,-13.774758338928223,90.7586669921875,0.014273774002553072 +1.9912550449371338,-13.774947166442871,90.75643920898438,0.003977527445373044 +1.9913872480392456,-13.775506019592285,90.75382232666016,0.022388296950669653 +1.9917869567871094,-13.777474403381348,90.74346160888672,0.041848662174560874 +1.992236852645874,-13.779816627502441,90.72364044189453,0.06427544972711488 +1.9927092790603638,-13.782402038574219,90.7069320678711,0.06829461493086772 +1.9933236837387085,-13.785511016845703,90.68379211425781,0.07499620986976652 +1.994232177734375,-13.79050064086914,90.64694213867188,0.16779758570849457 +1.9960880279541016,-13.80115795135498,90.56306457519531,0.26961051200239855 +1.9989172220230103,-13.815309524536133,90.45277404785156,0.3171343591543403 +2.002704620361328,-13.834291458129883,90.30658721923828,0.42527205417125546 +2.0070905685424805,-13.85612678527832,90.13093566894531,0.5117262422332467 +2.0121264457702637,-13.88090705871582,89.92939758300781,0.6094999001478679 +2.0178709030151367,-13.909193992614746,89.69303894042969,0.6278093147149234 +2.0240983963012695,-13.940147399902344,89.4317626953125,0.6916462727187856 +2.030531883239746,-13.972814559936523,89.1553726196289,0.7808572830394593 +2.0380635261535645,-14.01204776763916,88.8240737915039,0.8467976334249228 +2.045036792755127,-14.049477577209473,88.50878143310547,0.9135135037799224 +2.0532355308532715,-14.095098495483398,88.12637329101562,0.9825396995041566 +2.060713052749634,-14.138312339782715,87.76512145996094,1.020717554529127 +2.0690879821777344,-14.18889331817627,87.34431457519531,1.0885316235519233 +2.0767436027526855,-14.237366676330566,86.94255065917969,1.1555786881143475 +2.084981679916382,-14.292132377624512,86.48938751220703,1.211258176146807 +2.093327522277832,-14.350889205932617,86.00394439697266,1.2601895086505825 +2.1012654304504395,-14.410490036010742,85.51251220703125,1.2906439490334758 +2.1086626052856445,-14.47007942199707,85.02342987060547,1.3302690614046726 +2.1149442195892334,-14.524575233459473,84.57767486572266,1.3428111785238532 +2.1232428550720215,-14.601720809936523,83.94703674316406,1.2704312272055172 +2.1296446323394775,-14.667054176330566,83.41266632080078,1.2575472802472962 +2.135214328765869,-14.731935501098633,82.8853988647461,1.3643050538360872 +2.1402266025543213,-14.798274993896484,82.3493423461914,1.4542977320684098 +2.1448826789855957,-14.8692626953125,81.77513122558594,1.5240009156347227 +2.1489222049713135,-14.942327499389648,81.18441772460938,1.5676824561783251 +2.1520047187805176,-15.010787963867188,80.63280487060547,1.5961160570564397 +2.154672622680664,-15.088324546813965,80.01014709472656,1.6202741820645679 +2.156449317932129,-15.16344928741455,79.4063491821289,1.639491285663014 +2.1574084758758545,-15.235759735107422,78.82600402832031,1.6340392186340988 +2.1576616764068604,-15.318769454956055,78.15740203857422,1.605393408684487 +2.1571035385131836,-15.391529083251953,77.57170867919922,1.5540210445937401 +2.15604829788208,-15.453883171081543,77.06964874267578,1.4855371994436604 +2.154268503189087,-15.5228271484375,76.51325988769531,1.3931620522596062 +2.1519205570220947,-15.589669227600098,75.97249603271484,1.2939254381497578 +2.1493682861328125,-15.647905349731445,75.49988555908203,1.2029145576348153 +2.146547317504883,-15.702546119689941,75.05509948730469,1.1152626413764188 +2.1439270973205566,-15.747844696044922,74.68528747558594,1.0409705775266644 +2.1406726837158203,-15.79745101928711,74.27894592285156,0.9597466773366702 +2.137716054916382,-15.838773727416992,73.93962097167969,0.8920168283602065 +2.134730100631714,-15.877565383911133,73.62025451660156,0.8282300992825646 +2.131599187850952,-15.915640830993652,73.30583953857422,0.765466020100441 +2.128728151321411,-15.948567390441895,73.0334243774414,0.7111269056222843 +2.1258387565612793,-15.979893684387207,72.77403259277344,0.6600221712102232 +2.1228630542755127,-16.010953903198242,72.51664733886719,0.6084602262066529 +2.1201283931732178,-16.0382022857666,72.29054260253906,0.5630913830092403 +2.1176698207855225,-16.061805725097656,72.09444427490234,0.5238160176567043 +2.115079402923584,-16.08587646484375,71.89431762695312,0.4838095393005335 +2.112811803817749,-16.10633659362793,71.72398376464844,0.4498304036048772 +2.1104660034179688,-16.126953125,71.55223083496094,0.41561656257080315 +2.1082468032836914,-16.14597511291504,71.39364624023438,0.38404415099796213 +2.1062216758728027,-16.16295623779297,71.25194549560547,0.35586136995058076 +2.104400396347046,-16.177936553955078,71.12683868408203,0.33097212881580185 +2.102588415145874,-16.192590713500977,71.0044937133789,0.30664412072579694 +2.100954055786133,-16.20559310913086,70.89580535888672,0.2850322471036875 +2.099318265914917,-16.218425750732422,70.78846740722656,0.26370760388413245 +2.0977954864501953,-16.230207443237305,70.68985748291016,0.2441210779794608 +2.0963454246520996,-16.241275787353516,70.59717559814453,0.22570369721205316 +2.095048666000366,-16.25104331970215,70.51525115966797,0.20944886572391444 +2.0938754081726074,-16.259763717651367,70.44221496582031,0.1949440213451302 +2.0926425457000732,-16.268836975097656,70.3662338256836,0.17983066431279152 +2.0916452407836914,-16.276119232177734,70.3051528930664,0.16767991001304086 +2.090590000152588,-16.2838134765625,70.2403335571289,0.15481563126273343 +2.089735746383667,-16.290090560913086,70.18696594238281,0.14431363593229768 +2.0887949466705322,-16.297073364257812,70.12702178955078,0.13263028020530432 +2.088054656982422,-16.302616119384766,70.0789566040039,0.12337120570617503 +2.087360382080078,-16.307952880859375,70.03687286376953,0.10343100477032371 +2.086850881576538,-16.312023162841797,70.00437927246094,0.082974248623761 +2.086400032043457,-16.315196990966797,69.97026824951172,0.060912604449603516 +2.0860676765441895,-16.31770133972168,69.94759368896484,0.0466051169375938 +2.085822105407715,-16.31953239440918,69.92865753173828,0.05112280565815858 +2.085486650466919,-16.321958541870117,69.906494140625,0.07077975160828032 +2.0851359367370605,-16.324533462524414,69.88539123535156,0.044675915103798355 +2.084895133972168,-16.32680892944336,69.86725616455078,0.05853251234937629 +2.084665536880493,-16.328550338745117,69.85103607177734,0.028313994437016057 +2.0844504833221436,-16.329971313476562,69.8365249633789,0.015388822813810767 +2.0842039585113525,-16.33180809020996,69.820556640625,0.02636412664820334 +2.0840086936950684,-16.333311080932617,69.8084945678711,0.019801940568385048 +2.0837788581848145,-16.33511734008789,69.79071807861328,0.04886967384485139 +2.0834712982177734,-16.33724021911621,69.77379608154297,0.043678428799890576 +2.0831756591796875,-16.339702606201172,69.75116729736328,0.07983805265411384 +2.0825726985931396,-16.3436279296875,69.71607208251953,0.08647221135185681 +2.082097291946411,-16.347076416015625,69.6838150024414,0.07871996899078204 +2.0815489292144775,-16.351152420043945,69.64827728271484,0.14505599857238696 +2.0802090167999268,-16.360300064086914,69.56424713134766,0.19749165521451112 +2.0789175033569336,-16.36992073059082,69.47797393798828,0.2327893223151533 +2.0773558616638184,-16.380281448364258,69.40149688720703,0.2514656948899815 +2.075068235397339,-16.39562225341797,69.26242065429688,0.3562143773073972 +2.0727150440216064,-16.4121036529541,69.11457824707031,0.40295512782399073 +2.0695347785949707,-16.432706832885742,68.92526245117188,0.4764482768813834 +2.0660910606384277,-16.45591163635254,68.71540832519531,0.4979323982033567 +2.062422037124634,-16.479923248291016,68.49829864501953,0.5572952147468684 +2.0582261085510254,-16.50689697265625,68.25577545166016,0.5994863458722307 +2.053934335708618,-16.53408432006836,68.00982666015625,0.6195616356035263 +2.0488533973693848,-16.564863204956055,67.73217010498047,0.6917891520448731 +2.0435373783111572,-16.596242904663086,67.44914245605469,0.7349535508048571 +2.0371298789978027,-16.632986068725586,67.1159439086914,0.7931174356083684 +2.0304629802703857,-16.66972541809082,66.7827377319336,0.8425397796280537 +2.0228958129882812,-16.70980453491211,66.42249298095703,0.8890554873008235 +2.0145423412323,-16.752655029296875,66.03570556640625,0.9622620232679377 +2.0053837299346924,-16.79799461364746,65.62676239013672,1.0140208675026683 +1.9960377216339111,-16.84267807006836,65.22314453125,1.051302241480645 +1.9853724241256714,-16.891904830932617,64.7781982421875,1.0782405981193113 +1.9743274450302124,-16.941030502319336,64.33409118652344,1.1245871247492976 +1.9618589878082275,-16.99441146850586,63.85066604614258,1.1699384465258662 +1.9489749670028687,-17.047523498535156,63.368858337402344,1.2134718903943107 +1.9349157810211182,-17.1033935546875,62.860958099365234,1.2475577304468424 +1.9207899570465088,-17.157562255859375,62.367061614990234,1.2653449142421278 +1.9046632051467896,-17.217212677001953,61.8221549987793,1.2822750451440275 +1.8885568380355835,-17.274585723876953,61.29670333862305,1.3029885704695423 +1.8727320432662964,-17.3291015625,60.79557800292969,1.3125249617970998 +1.8542770147323608,-17.390567779541016,60.22873306274414,1.3185915334267402 +1.8364919424057007,-17.447803497314453,59.699893951416016,1.3239481044817154 +1.8176058530807495,-17.506614685058594,59.15468215942383,1.3285896734184959 +1.7994446754455566,-17.561391830444336,58.64592742919922,1.3435443117258565 +1.7778775691986084,-17.62443733215332,58.05790328979492,1.3465852433715515 +1.7580628395080566,-17.680574417114258,57.53252410888672,1.3584381134816421 +1.7364583015441895,-17.739999771118164,56.97502136230469,1.3586667360499933 +1.714989423751831,-17.797327041625977,56.43513488769531,1.349980621197766 +1.692682147026062,-17.855390548706055,55.88479995727539,1.3220650309363593 +1.6688932180404663,-17.915468215942383,55.3149528503418,1.341346512429559 +1.6449209451675415,-17.97417640686035,54.75695037841797,1.367515488406209 +1.620065689086914,-18.033382415771484,54.19089889526367,1.3632086543209403 +1.59653639793396,-18.088058471679688,53.66437530517578,1.3199770117271248 +1.5736730098724365,-18.140085220336914,53.16070556640625,1.2855485351864586 +1.5506463050842285,-18.190954208374023,52.66762924194336,1.2333077676507707 +1.5265765190124512,-18.2430419921875,52.160221099853516,1.1608393704339464 +1.504341959953308,-18.29008674621582,51.699485778808594,1.0858732878050263 +1.4839547872543335,-18.332469940185547,51.28247833251953,1.0133572326815377 +1.4642913341522217,-18.372695922851562,50.88472366333008,0.9422987452359576 +1.4482450485229492,-18.405214309692383,50.56373596191406,0.8216609352965887 +1.430936574935913,-18.43985366821289,50.218605041503906,0.7223684491623378 +1.417589783668518,-18.466337203979492,49.96297836303711,0.6526441154667538 +1.4027252197265625,-18.495330810546875,49.671695709228516,0.5786877162054627 +1.3915241956710815,-18.516908645629883,49.45612716674805,0.5314447023635059 +1.3803982734680176,-18.53804588317871,49.24103546142578,0.4854062643067227 +1.3704612255096436,-18.556886672973633,49.048683166503906,0.4505733374240152 +1.3609870672225952,-18.574609756469727,48.86969757080078,0.4325043668542944 +1.3514307737350464,-18.59235954284668,48.689842224121094,0.41618324782860344 +1.34263014793396,-18.608503341674805,48.526607513427734,0.4146858964917065 +1.3328361511230469,-18.62638282775879,48.341697692871094,0.4336981393603706 +1.3236045837402344,-18.643239974975586,48.17085647583008,0.40686584051505786 +1.3140559196472168,-18.66054916381836,48.001060485839844,0.42382034199054297 +1.3042075634002686,-18.678123474121094,47.822532653808594,0.42136726065842095 +1.295424461364746,-18.693756103515625,47.6614875793457,0.40979661685977053 +1.2861711978912354,-18.71005630493164,47.494537353515625,0.4279141103659693 +1.2767542600631714,-18.726585388183594,47.32359313964844,0.4132248706500178 +1.2669322490692139,-18.743757247924805,47.14573669433594,0.4052753293753769 +1.2576223611831665,-18.759925842285156,46.97693634033203,0.40322828951589407 +1.2479124069213867,-18.77669906616211,46.800537109375,0.4127513699047548 +1.239046335220337,-18.791858673095703,46.641998291015625,0.40593015901626867 +1.2293062210083008,-18.80841827392578,46.469242095947266,0.39686003125589453 +1.2198963165283203,-18.824304580688477,46.3033447265625,0.3967857646244214 +1.2102992534637451,-18.84037971496582,46.13581466674805,0.3984663932929012 +1.201253890991211,-18.85545539855957,45.97747802734375,0.39235567387682746 +1.1914433240890503,-18.871667861938477,45.807579040527344,0.38982688988266717 +1.1826270818710327,-18.886157989501953,45.65443420410156,0.40960477222700814 +1.1724474430084229,-18.902780532836914,45.47891616821289,0.4093728789676799 +1.1627994775772095,-18.9184513092041,45.3131103515625,0.4000524370714433 +1.152300238609314,-18.935407638549805,45.132808685302734,0.3994453500446774 +1.1439107656478882,-18.948883056640625,44.989646911621094,0.39660434803585237 +1.1339657306671143,-18.964754104614258,44.82048797607422,0.4020140817030134 +1.1228693723678589,-18.9823055267334,44.632503509521484,0.4333562186208684 +1.1116188764572144,-18.99997901916504,44.442543029785156,0.4429298074980999 +1.100193738937378,-19.01766586303711,44.25709915161133,0.49368776236626893 +1.0868488550186157,-19.038244247436523,44.03691101074219,0.50614791501486 +1.0739805698394775,-19.05792999267578,43.8243408203125,0.5340512617603387 +1.0603358745574951,-19.078716278076172,43.599037170410156,0.5471525266249584 +1.0453234910964966,-19.101295471191406,43.35570526123047,0.5973762449367912 +1.0300530195236206,-19.12401580810547,43.11084747314453,0.6162580323694872 +1.0133339166641235,-19.14866828918457,42.843692779541016,0.6469518450886304 +0.9953587055206299,-19.174890518188477,42.5585823059082,0.6785854128830837 +0.9776405692100525,-19.200286865234375,42.27874755859375,0.7184348670234015 +0.9571086764335632,-19.22945213317871,41.9583854675293,0.768541128607741 +0.9363415837287903,-19.258684158325195,41.63685989379883,0.79680352855418 +0.913825511932373,-19.289945602416992,41.284873962402344,0.8316157158629041 +0.890885055065155,-19.321435928344727,40.92757034301758,0.825231779554726 +0.8677728176116943,-19.352834701538086,40.5739631652832,0.8671120559778112 +0.8427236676216125,-19.38628578186035,40.1943244934082,0.9302372217559121 +0.8158187866210938,-19.421716690063477,39.79227066040039,0.988698593328486 +0.7883235216140747,-19.457500457763672,39.38850402832031,1.008582271514715 +0.7579618692398071,-19.496355056762695,38.94446563720703,1.0644080472592137 +0.7292971014976501,-19.532470703125,38.52750015258789,1.087938707151075 +0.6963169574737549,-19.5733585357666,38.05249786376953,1.1450379831176132 +0.6606220602989197,-19.61688232421875,37.549217224121094,1.1890039813633462 +0.6263519525527954,-19.6579647064209,37.072410583496094,1.2228833182855294 +0.5894743800163269,-19.70140838623047,36.5614013671875,1.2478069761679105 +0.5501056909561157,-19.74691390991211,36.02275848388672,1.283319086580981 +0.5104190707206726,-19.79192352294922,35.48562240600586,1.3185275869187674 +0.468546599149704,-19.83852767944336,34.92729949951172,1.3467265847525036 +0.4254702031612396,-19.88553237915039,34.35911178588867,1.3708985059458048 +0.3841192424297333,-19.929767608642578,33.81720733642578,1.3891851047018229 +0.33880844712257385,-19.977291107177734,33.22975540161133,1.413971373872888 +0.2921706438064575,-20.025238037109375,32.63505554199219,1.4337133163065674 +0.24408464133739471,-20.07362937927246,32.02680587768555,1.453002973715734 +0.1966227889060974,-20.120397567749023,31.431224822998047,1.4631782728657041 +0.1468372792005539,-20.168468475341797,30.814342498779297,1.4856522389551974 +0.10040001571178436,-20.212316513061523,30.2437686920166,1.4927975541550225 +0.048725664615631104,-20.260120391845703,29.613479614257812,1.5013149017868366 +-0.0021795365028083324,-20.30623435974121,29.003618240356445,1.521030184204183 +-0.059913791716098785,-20.357316970825195,28.31848907470703,1.5438505622980305 +-0.11116372048854828,-20.401689529418945,27.716272354125977,1.5529545239280418 +-0.16932958364486694,-20.45093536376953,27.038537979125977,1.5565860367302213 +-0.2193223387002945,-20.492321014404297,26.462419509887695,1.5647158239386363 +-0.279615581035614,-20.541175842285156,25.773332595825195,1.5692653698027061 +-0.33615782856941223,-20.585851669311523,25.133188247680664,1.5857075261758289 +-0.3955077528953552,-20.631649017333984,24.46845245361328,1.6027428277884705 +-0.4557684361934662,-20.677043914794922,23.799633026123047,1.6150948551913822 +-0.5129719376564026,-20.71912956237793,23.169403076171875,1.6211397752792494 +-0.5774523019790649,-20.76544952392578,22.464834213256836,1.6285287194137883 +-0.6380760073661804,-20.807903289794922,21.80708885192871,1.6353185972190454 +-0.7032896876335144,-20.852399826049805,21.107765197753906,1.6359548685371084 +-0.7636814713478088,-20.892494201660156,20.46956443786621,1.6386915534672726 +-0.8266624808311462,-20.933101654052734,19.816795349121094,1.626761260001404 +-0.8943787217140198,-20.975261688232422,19.13641357421875,1.6138132391115771 +-0.9556290507316589,-21.011981964111328,18.542699813842773,1.6017019598804045 +-1.020587682723999,-21.04947280883789,17.9386043548584,1.583214257621856 +-1.0835239887237549,-21.084436416625977,17.37656593322754,1.5716576036110943 +-1.145189881324768,-21.11743927001953,16.847864151000977,1.5602473858176367 +-1.2080800533294678,-21.14986801147461,16.329317092895508,1.5474692132598677 +-1.2722930908203125,-21.18170928955078,15.82453441619873,1.5333940447438394 +-1.3407145738601685,-21.214210510253906,15.315189361572266,1.5199448372819693 +-1.4042103290557861,-21.243011474609375,14.872159004211426,1.491624761406692 +-1.4612202644348145,-21.267641067504883,14.505390167236328,1.4493967174698175 +-1.520922064781189,-21.292177200317383,14.155367851257324,1.37846913976247 +-1.5799789428710938,-21.31509780883789,13.847620964050293,1.293765548784352 +-1.6373319625854492,-21.33600616455078,13.58981704711914,1.2040371365908216 +-1.6899539232254028,-21.353927612304688,13.393817901611328,1.1183114671731187 +-1.7330262660980225,-21.36766242980957,13.265131950378418,1.0468038602953003 +-1.780527949333191,-21.381784439086914,13.159175872802734,0.9672298949612299 +-1.8226155042648315,-21.39336395263672,13.099477767944336,0.8964634359067186 +-1.8603538274765015,-21.40297508239746,13.07546329498291,0.7445796933683718 +-1.8875410556793213,-21.409454345703125,13.075325965881348,0.4297861903354229 +-1.9041919708251953,-21.413225173950195,13.083250999450684,0.3538800793656663 +-1.91933012008667,-21.41640281677246,13.100329399108887,0.31933959666573986 +-1.933450698852539,-21.41922378540039,13.122055053710938,0.2908418708447971 +-1.9465601444244385,-21.42184829711914,13.141865730285645,0.2665001498619449 +-1.9584896564483643,-21.42432403564453,13.156547546386719,0.24535068681448557 +-1.9688700437545776,-21.426538467407227,13.167091369628906,0.22739490598450354 +-1.9794267416000366,-21.4288272857666,13.17647933959961,0.20937869080627275 +-1.9878841638565063,-21.430673599243164,13.183755874633789,0.1950415668458533 +-1.9968891143798828,-21.432634353637695,13.191789627075195,0.17983390023310555 +-2.004241704940796,-21.434228897094727,13.198569297790527,0.16740106978401056 +-2.0137765407562256,-21.4362735748291,13.20817756652832,0.1513035377777554 +-2.020745038986206,-21.437747955322266,13.216268539428711,0.13955370860890023 +-2.0267632007598877,-21.43899917602539,13.224262237548828,0.12940219189763683 +-2.032482147216797,-21.440166473388672,13.232890129089355,0.11974002257613318 +-2.0379130840301514,-21.441240310668945,13.242366790771484,0.11056316651690598 +-2.0427398681640625,-21.442167282104492,13.251938819885254,0.10239259596483667 +-2.0470404624938965,-21.442977905273438,13.262434959411621,0.06989137172107482 +-2.050029754638672,-21.44355583190918,13.273411750793457,0.040218598039720395 +-2.0515127182006836,-21.44379425048828,13.277091026306152,0.014154527208475662 +-2.052500009536743,-21.443952560424805,13.280468940734863,0.009163976220484909 +-2.05338978767395,-21.444091796875,13.282609939575195,0.025545775398905318 +-2.0541749000549316,-21.444232940673828,13.28577995300293,0.006609625361586466 +-2.0551342964172363,-21.44436264038086,13.28557014465332,0.03277750284573196 +-2.056468963623047,-21.444623947143555,13.292373657226562,0.015319883354856586 +-2.0576462745666504,-21.444820404052734,13.293932914733887,0.040222011697703744 +-2.059633255004883,-21.445232391357422,13.2990140914917,0.04708681443754642 +-2.0615932941436768,-21.445627212524414,13.302380561828613,0.036617388855947154 +-2.0632283687591553,-21.44597625732422,13.304301261901855,0.034128515095808755 +-2.0647783279418945,-21.44634437561035,13.304505348205566,0.040781429282586774 +-2.0666019916534424,-21.44681167602539,13.3037748336792,0.039765344761951316 +-2.0684988498687744,-21.447330474853516,13.301912307739258,0.0443786619010845 +-2.070474863052368,-21.44788360595703,13.299758911132812,0.041973725958025225 +-2.0720787048339844,-21.448322296142578,13.298201560974121,0.022496311971752194 +-2.0743165016174316,-21.448904037475586,13.297096252441406,0.04409143492221484 +-2.076359987258911,-21.449438095092773,13.296114921569824,0.043020580484573176 +-2.078000068664551,-21.449853897094727,13.295969009399414,0.03631995174579139 +-2.079463005065918,-21.45021629333496,13.295969009399414,0.029010464590165673 +-2.0804879665374756,-21.45046043395996,13.296516418457031,0.019181502895506984 +-2.081390380859375,-21.450666427612305,13.297476768493652,0.015532318129649508 +-2.0822207927703857,-21.45085334777832,13.298224449157715,0.022376675876473802 +-2.0832252502441406,-21.451087951660156,13.29833698272705,0.019620098700667304 +-2.084644317626953,-21.45144271850586,13.298105239868164,0.0435715363295551 +-2.0863921642303467,-21.451889038085938,13.29745101928711,0.03449956077106011 +-2.088029623031616,-21.452316284179688,13.29683780670166,0.037818416327498015 +-2.0894417762756348,-21.452672958374023,13.296708106994629,0.03124118806897643 +-2.090594530105591,-21.452953338623047,13.296708106994629,0.027248328247246607 +-2.091953754425049,-21.453275680541992,13.297085762023926,0.03560003536151516 +-2.0935676097869873,-21.453649520874023,13.297897338867188,0.03003458929358705 +-2.094900369644165,-21.453962326049805,13.298234939575195,0.03183862875587091 +-2.0965869426727295,-21.45436668395996,13.298264503479004,0.05056722470148771 +-2.098837375640869,-21.454931259155273,13.29782772064209,0.047984615564132575 +-2.1008620262145996,-21.4554386138916,13.29782772064209,0.05209594021785834 +-2.102881669998169,-21.455936431884766,13.29782772064209,0.04137200681969704 +-2.104707717895508,-21.456371307373047,13.298044204711914,0.04244055525395922 +-2.1065256595611572,-21.45680046081543,13.29871940612793,0.038790098813333986 +-2.1082212924957275,-21.45720672607422,13.29871940612793,0.03926889708855453 +-2.1100125312805176,-21.45764923095703,13.29871940612793,0.036637796843544505 +-2.1118295192718506,-21.458106994628906,13.298378944396973,0.042297462442518384 +-2.1138834953308105,-21.45863151550293,13.297815322875977,0.04423378104178208 +-2.116635799407959,-21.45931053161621,13.2977294921875,0.06901959987691705 +-2.1194870471954346,-21.459985733032227,13.298300743103027,0.05909856315212638 +-2.1223413944244385,-21.46063232421875,13.300450325012207,0.062490736308138894 +-2.125471591949463,-21.461341857910156,13.302689552307129,0.07916212108906998 +-2.129038095474243,-21.46217155456543,13.30400276184082,0.08246373640375068 +-2.132364511489868,-21.462970733642578,13.30400276184082,0.0679406042915601 +-2.1361424922943115,-21.46392059326172,13.302722930908203,0.08217275250574961 +-2.1399154663085938,-21.46487045288086,13.302755355834961,0.0843926427340166 +-2.143672227859497,-21.465797424316406,13.304587364196777,0.07561576502068378 +-2.14711594581604,-21.466594696044922,13.306807518005371,0.06861780136963877 +-2.150129556655884,-21.467248916625977,13.310212135314941,0.06738450138785511 +-2.152764081954956,-21.467819213867188,13.313156127929688,0.06300537540475878 +-2.15651535987854,-21.468664169311523,13.315559387207031,0.08284782027441183 +-2.160339832305908,-21.469568252563477,13.316855430603027,0.07314260794842882 +-2.163860321044922,-21.4704532623291,13.316267967224121,0.07860261589026463 +-2.1672778129577637,-21.47134017944336,13.314356803894043,0.07302530637742369 +-2.1721060276031494,-21.4725284576416,13.303186416625977,0.11798178848063039 +-2.1792073249816895,-21.474315643310547,13.299480438232422,0.18457401771806797 +-2.187791585922241,-21.47642707824707,13.304102897644043,0.1735373486902122 +-2.1952567100524902,-21.478160858154297,13.309432983398438,0.16336814637759178 +-2.201870918273926,-21.4796085357666,13.315448760986328,0.16007235986382135 +-2.2132863998413086,-21.48214340209961,13.3305082321167,0.26285297665763724 +-2.2247650623321533,-21.484737396240234,13.337428092956543,0.25494869882350524 +-2.237328052520752,-21.487714767456055,13.33751106262207,0.30191288394944227 +-2.25321888923645,-21.491680145263672,13.328357696533203,0.36796691362036577 +-2.271149158477783,-21.496376037597656,13.312626838684082,0.3820464630531932 +-2.287141799926758,-21.500587463378906,13.298171997070312,0.3791649433842594 +-2.3072164058685303,-21.505714416503906,13.288883209228516,0.4664503740634607 +-2.3301565647125244,-21.511308670043945,13.287196159362793,0.50979575311632 +-2.3546204566955566,-21.516969680786133,13.29742431640625,0.53298586033917 +-2.379032611846924,-21.522340774536133,13.31875228881836,0.5781590319724859 +-2.406007766723633,-21.528249740600586,13.342617988586426,0.6083411543670796 +-2.4347190856933594,-21.534748077392578,13.358667373657227,0.6460570831657378 +-2.464021921157837,-21.541723251342773,13.361287117004395,0.6864475447394399 +-2.497755765914917,-21.5501651763916,13.347386360168457,0.7297233401759539 +-2.5280404090881348,-21.558063507080078,13.321439743041992,0.7565821395543579 +-2.5631959438323975,-21.5672550201416,13.291729927062988,0.7778938378911404 +-2.598940372467041,-21.576324462890625,13.27348804473877,0.7972560247935353 +-2.6376559734344482,-21.58570671081543,13.271768569946289,0.8303979875469132 +-2.6726205348968506,-21.593759536743164,13.287296295166016,0.8416153982753715 +-2.714231014251709,-21.6029052734375,13.32358169555664,0.8381919245050405 +-2.7526793479919434,-21.611328125,13.35693645477295,0.8497501192085937 +-2.787724018096924,-21.619266510009766,13.376144409179688,0.8200869570118847 +-2.8287417888641357,-21.62901496887207,13.380769729614258,0.8203913674650033 +-2.866215229034424,-21.63842010498047,13.364346504211426,0.825082817957827 +-2.904045343399048,-21.648345947265625,13.330055236816406,0.8604587013132659 +-2.9433741569519043,-21.658716201782227,13.293742179870605,0.8809969843061618 +-2.983384370803833,-21.6689453125,13.269864082336426,0.9026332252438435 +-3.0250887870788574,-21.679149627685547,13.263349533081055,0.909330751808376 +-3.064225435256958,-21.68826675415039,13.276005744934082,0.9151923989297785 +-3.1100986003875732,-21.69843292236328,13.312045097351074,0.940593884162192 +-3.1496739387512207,-21.7071475982666,13.344377517700195,0.9585239474579955 +-3.1952877044677734,-21.717531204223633,13.367446899414062,0.97558694511433 +-3.239649772644043,-21.728130340576172,13.36951732635498,1.0013485128638613 +-3.2861361503601074,-21.73995590209961,13.348469734191895,1.0205836702826678 +-3.335108757019043,-21.752695083618164,13.304189682006836,1.027907685975929 +-3.3813014030456543,-21.764739990234375,13.262182235717773,1.0353913952489886 +-3.4285528659820557,-21.776723861694336,13.235883712768555,1.0673111671790794 +-3.4802119731903076,-21.789220809936523,13.231861114501953,1.099784984582876 +-3.528168201446533,-21.80024528503418,13.251791954040527,1.1033775758989937 +-3.577115774154663,-21.811019897460938,13.29172420501709,1.1294861428828655 +-3.6244561672210693,-21.82141876220703,13.330224990844727,1.1169094557986154 +-3.6956489086151123,-21.837690353393555,13.360987663269043,1.0343550645981547 +-3.74287748336792,-21.84917640686035,13.353426933288574,1.0653395317144596 +-3.794104814529419,-21.862274169921875,13.319683074951172,1.1281308894428974 +-3.8456554412841797,-21.875577926635742,13.282154083251953,1.1826068946060704 +-3.898867130279541,-21.888927459716797,13.259485244750977,1.216771423287789 +-3.95518159866333,-21.90245246887207,13.260080337524414,1.2442949688834246 +-4.016947269439697,-21.91651153564453,13.29253101348877,1.270697331084646 +-4.073148250579834,-21.928728103637695,13.345935821533203,1.2792837614558137 +-4.131863117218018,-21.941511154174805,13.400424003601074,1.3019266369233178 +-4.190351963043213,-21.954736709594727,13.435233116149902,1.3289268131425496 +-4.250057220458984,-21.968900680541992,13.444186210632324,1.3274046860763944 +-4.312228202819824,-21.984416961669922,13.422324180603027,1.3233083948765598 +-4.371850490570068,-21.999889373779297,13.37285327911377,1.3674274100943178 +-4.432651996612549,-22.015975952148438,13.318336486816406,1.3974083803901214 +-4.4985198974609375,-22.032861709594727,13.278458595275879,1.404791192193221 +-4.562638282775879,-22.048540115356445,13.268908500671387,1.4237630626225715 +-4.627676010131836,-22.06365203857422,13.29084300994873,1.4391081191701194 +-4.693876266479492,-22.078338623046875,13.341569900512695,1.4552144777499 +-4.763890743255615,-22.09386444091797,13.39499282836914,1.4681683410921795 +-4.824816703796387,-22.10783576965332,13.42285442352295,1.478838228281928 +-4.89760160446167,-22.125333786010742,13.423629760742188,1.4806710071351816 +-4.9596638679504395,-22.141021728515625,13.39281177520752,1.4952131715360075 +-5.034374237060547,-22.160734176635742,13.320663452148438,1.5088113689741591 +-5.096763610839844,-22.177288055419922,13.256875038146973,1.521868538343639 +-5.170295238494873,-22.19621467590332,13.204258918762207,1.5367912256842924 +-5.239294528961182,-22.213171005249023,13.185924530029297,1.543487226899131 +-5.30994987487793,-22.229660034179688,13.202218055725098,1.5513051791619479 +-5.379530906677246,-22.24513816833496,13.249275207519531,1.5621274903135844 +-5.453967094421387,-22.261659622192383,13.300156593322754,1.5634724316129915 +-5.519782543182373,-22.27679443359375,13.323613166809082,1.570613300379247 +-5.5914788246154785,-22.294042587280273,13.318489074707031,1.5780140741147106 +-5.668379306793213,-22.31337547302246,13.279067993164062,1.5880979523369787 +-5.740101337432861,-22.33144187927246,13.242377281188965,1.5948615682031728 +-5.814927101135254,-22.349706649780273,13.228448867797852,1.5974733230052123 +-5.887167930603027,-22.36652946472168,13.248190879821777,1.606145537201885 +-5.957065105438232,-22.38211441040039,13.296181678771973,1.6129958097822203 +-6.031288146972656,-22.398611068725586,13.348494529724121,1.6144486466850314 +-6.1049933433532715,-22.41557502746582,13.376684188842773,1.617093161615916 +-6.180325031280518,-22.433773040771484,13.371009826660156,1.6189947840904046 +-6.252228736877441,-22.45208168029785,13.33560562133789,1.6306276250452754 +-6.325619220733643,-22.47041130065918,13.299967765808105,1.6359215894343715 +-6.401814937591553,-22.48894500732422,13.2884521484375,1.6311324459681569 +-6.477789878845215,-22.506610870361328,13.312882423400879,1.63368229886713 +-6.548222541809082,-22.52229118347168,13.364923477172852,1.6363667675297713 +-6.6244964599609375,-22.539257049560547,13.421662330627441,1.6401678721846753 +-6.701333999633789,-22.556974411010742,13.453634262084961,1.6446882351073326 +-6.767412185668945,-22.57292366027832,13.45258617401123,1.6503324905133108 +-6.845407009124756,-22.592668533325195,13.413647651672363,1.6492128825331622 +-6.926027297973633,-22.613956451416016,13.336133003234863,1.653741916467105 +-6.994439125061035,-22.632028579711914,13.269815444946289,1.6567244908905074 +-7.069721698760986,-22.65130615234375,13.220236778259277,1.6591653895945333 +-7.14583158493042,-22.66990089416504,13.204808235168457,1.66066964209038 +-7.223627090454102,-22.687795639038086,13.228103637695312,1.6624765620020112 +-7.301461219787598,-22.705013275146484,13.287574768066406,1.662180110332713 +-7.378665447235107,-22.722131729125977,13.346576690673828,1.6638678446948874 +-7.44655179977417,-22.737634658813477,13.378091812133789,1.6679836335298552 +-7.528255462646484,-22.757177352905273,13.379776954650879,1.6616435594826977 +-7.600832462310791,-22.775447845458984,13.343656539916992,1.6261657584044042 +-7.666999816894531,-22.79279327392578,13.28219223022461,1.5617137162189243 +-7.737099647521973,-22.811176300048828,13.21639633178711,1.4711803679741793 +-7.7973246574401855,-22.826406478881836,13.182884216308594,1.200316690756629 +-7.839100360870361,-22.836376190185547,13.171549797058105,0.7182337059605093 +-7.866199016571045,-22.842676162719727,13.168471336364746,0.4956497079950651 +-7.886260032653809,-22.847002029418945,13.185994148254395,0.28580049362384785 +-7.886959552764893,-22.847150802612305,13.186739921569824,0.00025305663669652914 +-7.886991500854492,-22.847164154052734,13.187175750732422,0.00021102525910313708 +-7.887052059173584,-22.847187042236328,13.187710762023926,0.00018325011835986665 +-7.887107849121094,-22.847206115722656,13.188159942626953,0.00014415852014472595 +-7.887156009674072,-22.84722137451172,13.188613891601562,0.00010788574796232954 +-7.8871917724609375,-22.847232818603516,13.189038276672363,8.306318496188596e-05 +-7.887221336364746,-22.84724235534668,13.189457893371582,6.612977556193877e-05 +-7.887246608734131,-22.84724998474121,13.1898775100708,5.154750673234522e-05 +-7.887265682220459,-22.84725570678711,13.190330505371094,3.970199841776362e-05 +-7.887279510498047,-22.847259521484375,13.190781593322754,3.057967408507578e-05 +-7.887290954589844,-22.84726333618164,13.191195487976074,2.346634928452651e-05 +-7.887297630310059,-22.847265243530273,13.191240310668945,2.05693919028302e-05 +-7.887303829193115,-22.847267150878906,13.19128131866455,2.032250404812536e-05 +-7.88730525970459,-22.847267150878906,13.19128131866455,2.1457825969459564e-05 +-7.887307167053223,-22.84726905822754,13.19128131866455,9.407551533919199e-06 +-7.887308120727539,-22.84726905822754,13.19128131866455,7.266781149940127e-06 +-7.887308120727539,-22.84726905822754,13.19128131866455,6.289633022064737e-06 +-7.887308120727539,-22.847272872924805,13.19128131866455,5.53737951600437e-06 +-7.88723087310791,-22.84725570678711,13.19128131866455,0.0017497218783600972 +-7.887242794036865,-22.847257614135742,13.19128131866455,0.0014483217570541843 +-7.887344837188721,-22.847280502319336,13.19128131866455,0.0028269278539261606 +-7.887423992156982,-22.847293853759766,13.19128131866455,2.585487403546379e-06 +-7.887423992156982,-22.847293853759766,13.19128131866455,3.198189290304047e-06 +-7.887423992156982,-22.847293853759766,13.19128131866455,3.8123738056340714e-06 +-7.887423992156982,-22.84729766845703,13.19128131866455,3.7218637162313836e-06 +-7.887423992156982,-22.84729766845703,13.19128131866455,3.672645096966474e-06 +-7.887423992156982,-22.84729766845703,13.19128131866455,3.4561743235761567e-06 +-7.887423992156982,-22.84729766845703,13.19128131866455,2.1483414512832236e-06 +-7.887423992156982,-22.84729766845703,13.19128131866455,3.5492510448908855e-06 +-7.887478351593018,-22.847299575805664,13.189742088317871,0.008241187440234762 +-7.887554168701172,-22.84732437133789,13.190068244934082,0.003555621068041785 +-7.887823104858398,-22.847360610961914,13.187599182128906,0.017091534656031405 +-7.888238906860352,-22.847442626953125,13.1878080368042,0.017675387153060232 +-7.888495922088623,-22.84752655029297,13.19131088256836,0.015510883967271396 +-7.889745235443115,-22.84779930114746,13.186848640441895,0.03927422838924459 +-7.892009735107422,-22.848363876342773,13.18583869934082,0.05910405465367144 +-7.8945207595825195,-22.849000930786133,13.184863090515137,0.05649998172938851 +-7.8967604637146,-22.84955596923828,13.184863090515137,0.04545860383975913 +-7.898989200592041,-22.85007667541504,13.185491561889648,0.059799934032707946 +-7.901515960693359,-22.85063934326172,13.187166213989258,0.05722539504360378 +-7.904211044311523,-22.851242065429688,13.18945026397705,0.06182974294511585 +-7.907783508300781,-22.852096557617188,13.192557334899902,0.07906406700392664 +-7.913570404052734,-22.853534698486328,13.195871353149414,0.1921093848824857 +-7.924596786499023,-22.85634994506836,13.192513465881348,0.28212263543321375 +-7.941703796386719,-22.86066436767578,13.17957878112793,0.4480702776201287 +-7.961174964904785,-22.86545181274414,13.175405502319336,0.4847356906056536 +-7.982651233673096,-22.870494842529297,13.178389549255371,0.5635475819150519 +-8.017118453979492,-22.878246307373047,13.197159767150879,0.7155680588274088 +-8.048429489135742,-22.885292053222656,13.213362693786621,0.7814029023648777 +-8.084440231323242,-22.893651962280273,13.220026969909668,0.7752919244415585 +-8.126067161560059,-22.903833389282227,13.20598316192627,0.8803904516949564 +-8.172101020812988,-22.915668487548828,13.167469024658203,1.0272358641127473 +-8.219697952270508,-22.927928924560547,13.126335144042969,1.1015177935350386 +-8.266376495361328,-22.939571380615234,13.103052139282227,0.9128892035928605 +-8.297170639038086,-22.946882247924805,13.102481842041016,0.4303918466821971 +-8.312335968017578,-22.950345993041992,13.107542991638184,0.3520973966543176 +-8.328929901123047,-22.95384979248047,13.124733924865723,0.3735607273731745 +-8.346477508544922,-22.957365036010742,13.150371551513672,0.36952424767986847 +-8.363869667053223,-22.96086883544922,13.174981117248535,0.35319200766972697 +-8.377969741821289,-22.963815689086914,13.190767288208008,0.33518388484115064 +-8.393538475036621,-22.967226028442383,13.201926231384277,0.3047131467150007 +-8.403884887695312,-22.969667434692383,13.202690124511719,0.1794951555660492 +-8.409798622131348,-22.971073150634766,13.203060150146484,0.11075057745233276 +-8.413920402526855,-22.97205352783203,13.203166961669922,0.06630705906608944 +-8.416217803955078,-22.97258949279785,13.203712463378906,0.047913975727540116 +-8.418231964111328,-22.973026275634766,13.20588207244873,0.03966497343956075 +-8.419917106628418,-22.973379135131836,13.208296775817871,0.034396993101130424 +-8.421439170837402,-22.973697662353516,13.210379600524902,0.030558614389786694 +-8.422873497009277,-22.97401237487793,13.211865425109863,0.026821385808046785 +-8.423794746398926,-22.974233627319336,13.211917877197266,0.015262533330036592 +-8.424298286437988,-22.97435188293457,13.211917877197266,0.008960645225023947 +-8.424600601196289,-22.97442054748535,13.211917877197266,0.005078686158813532 +-8.42478084564209,-22.97446632385254,13.211917877197266,0.002649619635159653 +-8.424884796142578,-22.97449493408203,13.211917877197266,0.0020409625437399744 +-8.424973487854004,-22.974523544311523,13.211917877197266,0.0016048283448186049 +-8.42503547668457,-22.974538803100586,13.211917877197266,0.0013198208411006232 +-8.425091743469238,-22.97454261779785,13.211917877197266,0.00105759551961052 +-8.42513656616211,-22.97454261779785,13.211917877197266,0.0005973502392675978 +-8.425142288208008,-22.97454261779785,13.211917877197266,0.0002863851292250417 +-8.425113677978516,-22.974544525146484,13.211917877197266,0.0009232417468247882 +-8.425060272216797,-22.974533081054688,13.211917877197266,0.001428608993931116 +-8.424989700317383,-22.974506378173828,13.211917877197266,0.0014127783710249956 +-8.424930572509766,-22.97449493408203,13.211917877197266,0.0010762222434603677 +-8.4249267578125,-22.97449493408203,13.211917877197266,5.310934451313739e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.316845543893659e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.646287078901789e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.587261689794546e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.193670082715371e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,3.2720356465908077e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.253945104460761e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,3.5694735621684934e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.0879784585028835e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.545597664995844e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.065183357753847e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,3.894487462091445e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,3.900501033948012e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.1203178546856324e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.279781658551077e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.0151987859332485e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.05673202133274e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.038588859548018e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,2.8781489672843353e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,3.980351231113913e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.022625463419237e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.429076701565019e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,1.564518710927073e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.367304765695042e-06 +-8.4249267578125,-22.97449493408203,13.211917877197266,4.245303450155577e-06 +-8.42488956451416,-22.97447967529297,13.2114896774292,0.0005724334178985069 +-8.42481517791748,-22.974464416503906,13.21255111694336,0.0011915377070198213 +-8.424581527709961,-22.97442054748535,13.212788581848145,0.007103062142001839 +-8.424208641052246,-22.974340438842773,13.212788581848145,0.006247583806963649 +-8.423088073730469,-22.974084854125977,13.212908744812012,0.044764856478289844 +-8.421659469604492,-22.973739624023438,13.2134370803833,0.023765832860646773 +-8.418464660644531,-22.97295570373535,13.216631889343262,0.08284065051680124 +-8.412803649902344,-22.971567153930664,13.221280097961426,0.1455741633254017 +-8.403939247131348,-22.969449996948242,13.22292709350586,0.2425824985109552 +-8.391074180603027,-22.96651268005371,13.217339515686035,0.3180732585256614 +-8.373912811279297,-22.962772369384766,13.200483322143555,0.404879131622213 +-8.35336685180664,-22.95827865600586,13.183882713317871,0.47980889645462066 +-8.329509735107422,-22.952856063842773,13.169243812561035,0.5828420579222465 +-8.300908088684082,-22.946046829223633,13.163299560546875,0.6682393092428164 +-8.265180587768555,-22.93709945678711,13.176704406738281,0.7684623905097454 +-8.23010540008545,-22.92793083190918,13.20943546295166,0.8583544782526301 +-8.187224388122559,-22.916671752929688,13.251883506774902,0.9835242001526221 +-8.139389991760254,-22.904462814331055,13.284400939941406,1.057511189773064 +-8.09092903137207,-22.892587661743164,13.297953605651855,1.1409447691587176 +-8.032774925231934,-22.879058837890625,13.285172462463379,1.236772978500705 +-7.975909233093262,-22.866483688354492,13.248074531555176,1.3043299406875213 +-7.91157865524292,-22.85234260559082,13.206485748291016,1.38808781846219 +-7.846428871154785,-22.837541580200195,13.184983253479004,1.4606587812040692 +-7.780369281768799,-22.821842193603516,13.193643569946289,1.5359615152778732 +-7.706562519073486,-22.803503036499023,13.238490104675293,1.6054462584405291 +-7.638354301452637,-22.786300659179688,13.279052734375,1.682050452351363 +-7.555602073669434,-22.76595687866211,13.302308082580566,1.7669125409440234 +-7.4717631340026855,-22.74622917175293,13.28754711151123,1.84360034709196 +-7.388657093048096,-22.72756004333496,13.238821029663086,1.9190605406020864 +-7.300968647003174,-22.70805549621582,13.186694145202637,1.9941679973133755 +-7.203314781188965,-22.685733795166016,13.15945816040039,2.072394972442575 +-7.1048784255981445,-22.662378311157227,13.176718711853027,2.1459962769627206 +-7.01448392868042,-22.639631271362305,13.23216438293457,2.2110971886333224 +-6.904452323913574,-22.61161994934082,13.307228088378906,2.2876794950880615 +-6.804717063903809,-22.586767196655273,13.346161842346191,2.354242462187306 +-6.695140838623047,-22.56049346923828,13.342901229858398,2.4240651970120317 +-6.583003520965576,-22.53488540649414,13.287653923034668,2.4924387976753257 +-6.4587931632995605,-22.508026123046875,13.17253589630127,2.5655061259004848 +-6.347357273101807,-22.484352111816406,13.065877914428711,2.6292582495769303 +-6.2266669273376465,-22.45832061767578,12.979866981506348,2.6954028491315385 +-6.096304416656494,-22.42970085144043,12.907502174377441,2.7562877387309026 +-5.969062805175781,-22.402069091796875,12.835741996765137,2.792978366442929 +-5.842311859130859,-22.375112533569336,12.753178596496582,2.792969139066542 +-5.717331409454346,-22.34903335571289,12.654508590698242,2.769564851480737 +-5.585047245025635,-22.322145462036133,12.529290199279785,2.7307272925789197 +-5.470123767852783,-22.2994327545166,12.404074668884277,2.690320094208413 +-5.336726188659668,-22.273883819580078,12.239538192749023,2.639036405799873 +-5.214787006378174,-22.251317977905273,12.071941375732422,2.5898246487701777 +-5.096739768981934,-22.230209350585938,11.894746780395508,2.5410022589847188 +-4.988415718078613,-22.21149444580078,11.71943473815918,2.4956401414396434 +-4.8628716468811035,-22.190576553344727,11.503302574157715,2.4427428897424823 +-4.760902404785156,-22.174171447753906,11.318949699401855,2.3996421753070165 +-4.663815498352051,-22.159053802490234,11.136281967163086,2.358549338686319 +-4.540772914886475,-22.14061164855957,10.894966125488281,2.3064163889524756 +-4.402695178985596,-22.12090301513672,10.610494613647461,2.2478984957905013 +-4.301750183105469,-22.107194900512695,10.392293930053711,2.205141159726848 +-4.204288482666016,-22.09453582763672,10.173579216003418,2.163901658664073 +-4.1010236740112305,-22.08176040649414,9.933631896972656,2.120242592548253 +-4.006280899047852,-22.07061004638672,9.706181526184082,2.0802229215365453 +-3.9061434268951416,-22.059606552124023,9.45765495300293,2.0382789009257962 +-3.813995599746704,-22.049821853637695,9.220619201660156,1.9992554914535292 +-3.7245562076568604,-22.040929794311523,8.983381271362305,1.9613483214199245 +-3.634056568145752,-22.03252601623535,8.737046241760254,1.923053838710229 +-3.5430569648742676,-22.024639129638672,8.483372688293457,1.8846284182710777 +-3.453038454055786,-22.017370223999023,8.22740364074707,1.8467144388703538 +-3.3684256076812744,-22.011005401611328,7.9833526611328125,1.8111544351468338 +-3.2917404174804688,-22.005596160888672,7.760740756988525,1.7790204253853905 +-3.202134609222412,-21.999664306640625,7.500389099121094,1.7415154952011938 +-3.122809410095215,-21.9947509765625,7.270555019378662,1.7083846945180654 +-3.0399653911590576,-21.98975372314453,7.0340471267700195,1.6735083183079875 +-2.963944911956787,-21.98561668395996,6.821254730224609,1.6419697721594273 +-2.8917837142944336,-21.981746673583984,6.625300407409668,1.612243601094374 +-2.8179380893707275,-21.977779388427734,6.4342427253723145,1.5819016579840621 +-2.7465808391571045,-21.973894119262695,6.261605262756348,1.5525738534517932 +-2.673834800720215,-21.969806671142578,6.099765300750732,1.5226733866672408 +-2.6061809062957764,-21.9658145904541,5.964931011199951,1.4948602040983823 +-2.5346593856811523,-21.96129608154297,5.841738224029541,1.4654085491054445 +-2.469001293182373,-21.95680809020996,5.748226642608643,1.4383380324424107 +-2.4008419513702393,-21.95170783996582,5.6741414070129395,1.4101500799423716 +-2.3374063968658447,-21.946489334106445,5.6275715827941895,1.38382779778682 +-2.2688238620758057,-21.939889907836914,5.6200761795043945,1.3550362632508293 +-2.2084925174713135,-21.933856964111328,5.620103359222412,1.3298672849316882 +-2.149657964706421,-21.927963256835938,5.620180130004883,1.305325031619098 +-2.0894148349761963,-21.921932220458984,5.619942665100098,1.2801871092761683 +-2.0302586555480957,-21.916704177856445,5.588609218597412,1.255108274319647 +-1.968769907951355,-21.911945343017578,5.531430244445801,1.229396616830568 +-1.9116759300231934,-21.907541275024414,5.482059478759766,1.2057799072859912 +-1.858489990234375,-21.90300178527832,5.457588195800781,1.1835726277869647 +-1.802243947982788,-21.89759063720703,5.456757545471191,1.1601611620187098 +-1.7502871751785278,-21.89253807067871,5.456757545471191,1.1385472051120107 +-1.69776451587677,-21.887432098388672,5.456757545471191,1.116701073917775 +-1.6475090980529785,-21.882537841796875,5.456757545471191,1.095805693259402 +-1.5974801778793335,-21.878154754638672,5.434736251831055,1.0745984044310377 +-1.548095941543579,-21.874521255493164,5.386336326599121,1.0539622983552215 +-1.497390866279602,-21.87083625793457,5.338578224182129,1.033065377742511 +-1.4488487243652344,-21.866859436035156,5.3143696784973145,1.0128879690031207 +-1.4073458909988403,-21.862972259521484,5.3136887550354,0.995664698997056 +-1.3587664365768433,-21.858379364013672,5.3136887550354,0.9755186352227283 +-1.31290864944458,-21.85403823852539,5.3136887550354,0.9565061835608019 +-1.2717705965042114,-21.850139617919922,5.3136887550354,0.9394550265745241 +-1.2258716821670532,-21.84636116027832,5.288306713104248,0.9200666410561402 +-1.1848933696746826,-21.843496322631836,5.246417045593262,0.8796896073624911 +-1.1565622091293335,-21.841014862060547,5.144937992095947,0.28749261754409555 +-1.1558476686477661,-21.84088897705078,5.137330532073975,0.00011748511341333198 +-1.1558449268341064,-21.84088897705078,5.1373820304870605,6.948087081157426e-05 +-1.1558037996292114,-21.840885162353516,5.137448787689209,0.0001098466326407947 +-1.155754804611206,-21.840883255004883,5.137515544891357,0.00010442681678009003 +-1.1557093858718872,-21.84088134765625,5.137595176696777,8.663480634038044e-05 +-1.1556755304336548,-21.840877532958984,5.137670516967773,6.728197899826891e-05 +-1.1556479930877686,-21.84087562561035,5.137740135192871,5.072833084499e-05 +-1.1556264162063599,-21.84087562561035,5.137808799743652,3.8227581185315014e-05 +-1.1556117534637451,-21.84087371826172,5.137872219085693,2.9425549339987236e-05 +-1.155603289604187,-21.84087371826172,5.137923717498779,1.986542828121817e-05 +-1.1556017398834229,-21.84087371826172,5.137938499450684,1.4089589650294356e-05 +-1.15559983253479,-21.84087371826172,5.137945652008057,1.0582274326807614e-05 +-1.1555976867675781,-21.84087371826172,5.137945652008057,7.293099828200531e-06 +-1.1555976867675781,-21.84087371826172,5.137945652008057,4.708509339294743e-06 +-1.1555966138839722,-21.840871810913086,5.137945652008057,2.8780188447215683e-06 +-1.1555956602096558,-21.840871810913086,5.137945652008057,1.92912163802052e-06 +-1.155595064163208,-21.840871810913086,5.137945652008057,1.7642003220043818e-06 +-1.1555947065353394,-21.840871810913086,5.137945652008057,1.8056860987183872e-06 +-1.1555927991867065,-21.840871810913086,5.137945652008057,0.00018796249441316822 +-1.15557062625885,-21.840871810913086,5.137945652008057,0.0006319171933654547 +-1.155531406402588,-21.840871810913086,5.137945652008057,0.0010101793548822533 +-1.1555098295211792,-21.840871810913086,5.137945652008057,3.791443359227364e-06 +-1.1555097103118896,-21.840871810913086,5.137945652008057,3.040026550780428e-06 +-1.1555095911026,-21.840871810913086,5.137945652008057,3.50118240809995e-06 +-1.1555095911026,-21.840871810913086,5.137945652008057,3.5468030342560283e-06 +-1.1555095911026,-21.840871810913086,5.137945652008057,3.2772026455511918e-06 +-1.1555094718933105,-21.840871810913086,5.137945652008057,3.5610563684829043e-06 +-1.1555094718933105,-21.840871810913086,5.137945652008057,3.5074163956515343e-06 +-1.155509352684021,-21.840871810913086,5.137945652008057,4.183352288688768e-06 +-1.155509352684021,-21.840871810913086,5.137945652008057,4.119528957732611e-06 +-1.155509352684021,-21.840871810913086,5.137945652008057,3.8772197220430836e-06 +-1.155509352684021,-21.840871810913086,5.137945652008057,4.092938834650519e-06 +-1.155509352684021,-21.840871810913086,5.137945652008057,3.450833090346126e-06 +-1.1559391021728516,-21.840919494628906,5.140854835510254,0.03449853107803271 +-1.1565558910369873,-21.840961456298828,5.141347408294678,0.02608499480603286 +-1.156140923500061,-21.84092903137207,5.140647888183594,0.03889695685521646 +-1.1549068689346313,-21.84083366394043,5.139942646026611,0.050472972024489575 +-1.1543455123901367,-21.840787887573242,5.139864921569824,0.0019053968936858195 +-1.1536897420883179,-21.840723037719727,5.140175819396973,0.03596029617755241 +-1.1526306867599487,-21.840606689453125,5.140917778015137,0.0034347834119841415 +-1.151275873184204,-21.84046745300293,5.143104553222656,0.030635477896039306 +-1.1481224298477173,-21.840150833129883,5.143526554107666,0.0792242155116063 +-1.143157958984375,-21.839691162109375,5.142795085906982,0.12095720208454964 +-1.1369818449020386,-21.839197158813477,5.138321399688721,0.12818781855405478 +-1.1304073333740234,-21.838764190673828,5.135097503662109,0.15417419146386754 +-1.1221580505371094,-21.838197708129883,5.125956058502197,0.1873267145954201 +-1.1131600141525269,-21.837560653686523,5.124849796295166,0.20980955965190046 +-1.103247880935669,-21.836734771728516,5.125649929046631,0.21788423341285668 +-1.0934208631515503,-21.835783004760742,5.128548622131348,0.23779173129658274 +-1.0821086168289185,-21.834575653076172,5.139918804168701,0.2550616958651679 +-1.071808099746704,-21.833459854125977,5.149527549743652,0.2597418993700948 +-1.0602651834487915,-21.832279205322266,5.155064582824707,0.2501225666669533 +-1.0488460063934326,-21.831228256225586,5.154216766357422,0.2585065477042054 +-1.0363596677780151,-21.830228805541992,5.147885322570801,0.2588186919692694 +-1.024162769317627,-21.829387664794922,5.135679244995117,0.27527831288511984 +-1.0103756189346313,-21.828449249267578,5.122723579406738,0.28432298802201605 +-0.9969174861907959,-21.8273868560791,5.11659049987793,0.32114296467979564 +-0.9808450937271118,-21.825929641723633,5.116574764251709,0.3456173756729812 +-0.9649358987808228,-21.824481964111328,5.116574764251709,0.35557246993432107 +-0.9480022192001343,-21.822938919067383,5.116574764251709,0.3583875727603718 +-0.932144045829773,-21.821491241455078,5.116574764251709,0.3567930813804134 +-0.9164941906929016,-21.820234298706055,5.109047889709473,0.3535956578600651 +-0.8991011381149292,-21.81906509399414,5.091818332672119,0.3484206577702614 +-0.8842214941978455,-21.818058013916016,5.077833652496338,0.34339440448935854 +-0.862300455570221,-21.816293716430664,5.0695414543151855,0.3353209659863138 +-0.8470332622528076,-21.81491470336914,5.069879531860352,0.0003926693013225378 +-0.8470847010612488,-21.814918518066406,5.069943904876709,4.36405591962156e-05 +-0.8470830917358398,-21.814918518066406,5.069968223571777,2.039777335254989e-05 +-0.8470677137374878,-21.814918518066406,5.07004451751709,3.727410657161331e-05 +-0.8470500111579895,-21.814916610717773,5.070116996765137,3.706781853165949e-05 +-0.8470359444618225,-21.814916610717773,5.070184230804443,3.333778234890722e-05 +-0.8470255136489868,-21.814916610717773,5.07022762298584,2.5865425034347098e-05 +-0.8470215201377869,-21.814916610717773,5.070249080657959,2.21853418260146e-05 +-0.8470189571380615,-21.81491470336914,5.070249080657959,1.9493977024501357e-05 +-0.8470167517662048,-21.81491470336914,5.070249080657959,1.8075193515788188e-05 +-0.847014307975769,-21.81491470336914,5.070249080657959,1.8979073662827207e-05 +-0.8470129370689392,-21.81491470336914,5.070249080657959,1.9480921392503903e-05 +-0.8470116257667542,-21.81491470336914,5.070249080657959,1.9820943877632513e-06 +-0.8470110297203064,-21.81491470336914,5.070249080657959,1.5692787223204021e-06 +-0.8470058441162109,-21.81491470336914,5.070249080657959,0.00030770740173152196 +-0.8469786643981934,-21.81491470336914,5.070249080657959,0.0007475266075919846 +-0.846932053565979,-21.81491470336914,5.070249080657959,0.0011451431173506144 +-0.8468661904335022,-21.81491470336914,5.070249080657959,0.0015251237981424462 +-0.8467843532562256,-21.81491470336914,5.070249080657959,0.0018791469214795705 +-0.8466887474060059,-21.81491470336914,5.070249080657959,0.0022143664460933347 +-0.8465874195098877,-21.814910888671875,5.070249080657959,0.0025148375530626567 +-0.8464545011520386,-21.814910888671875,5.070249080657959,0.002855866125279545 +-0.8464386463165283,-21.814910888671875,5.070249080657959,5.038767651018894e-06 +-0.8464387059211731,-21.814910888671875,5.070249080657959,3.182489073385553e-06 +-0.8464386463165283,-21.814910888671875,5.070249080657959,3.0402564209804222e-06 +-0.8464386463165283,-21.814910888671875,5.070249080657959,3.923957831364696e-06 +-0.8464385271072388,-21.814910888671875,5.070249080657959,3.679019841952598e-06 +-0.8464383482933044,-21.814910888671875,5.070249080657959,4.072770420085542e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.191646692658076e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.5691427227359387e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.934524450997817e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.09864739312082e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.778473087473193e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.109301807989647e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.5605594983743357e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.6094411489384755e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.908473194070634e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.559512612218048e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.001220420366691e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.493383463777575e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.9057387408965455e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.0207986427759004e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.039954712266864e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.113634228808273e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.150882666033715e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,2.655495767896004e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.242939859770539e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.413108588568685e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.22477554110131e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.25348913255908e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.410696047444734e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.82294744057197e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.4469232440232418e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.244685968442759e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.001575602074025e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.3640462558292453e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.8924266372930736e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.9536300712655025e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.2144028007952985e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.113231655805403e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.921287327581129e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.0499936301519683e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.975330415172164e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.7893658505058325e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.218500422235638e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.4835023088668418e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.805937744325295e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.976844220104589e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.715828500231085e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.6897123317576514e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.815892425790013e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.075284868133123e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.8735177041781184e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.6499740830276064e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.159561909171469e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.9407547312413144e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.292679225716963e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.7632769627125695e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.087075012320854e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.042723482972154e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.1667642333282e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.4810746255182204e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.734367876428198e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.1450824565578375e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.879240691880065e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.902342256925738e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.0339432864757845e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,2.5457577999768744e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.081502816023641e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.6522595431162337e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.198143412379726e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.096620110270457e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.000446505249325e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.040335034948517e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,2.78234676226156e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.166212587832554e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.101043290955528e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.5666681779894007e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.951747385571232e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.142705486873761e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.0109229092782715e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,9.112409503316012e-07 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.536211085171506e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.961665310132045e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.88186349809536e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.897477786385833e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.369933099217921e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.113172766800676e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,4.023341426462323e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,2.008369707650355e-06 +-0.8464382886886597,-21.814910888671875,5.070249080657959,3.0202667404169327e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.126168204704272e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.810795903512214e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.576017983372131e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.130519663164714e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.1375121675950165e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.123468262645518e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.061124991288238e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.002447917001346e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.2277652670194164e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.242708057487455e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.072545983296674e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.7175102658338864e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.902929005625965e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.9375256828405555e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.008863313729365e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.836738148007741e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,2.3296382079523737e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.560088677353018e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.318367848627831e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.901221399373941e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.967379023244407e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.5060887612072202e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.4563986849612193e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,4.046554944417552e-06 +-0.8464381098747253,-21.814910888671875,5.070249080657959,3.5631250868550636e-06 +4.682607173919678,-14.198596000671387,67.1901626586914,5.526783478462315e-06 +4.682607650756836,-14.198596000671387,67.1901626586914,5.379599212818213e-06 +4.682608127593994,-14.198596000671387,67.1901626586914,5.726837395158105e-06 +4.6826090812683105,-14.198596000671387,67.1901626586914,5.627543112333472e-06 +4.682610034942627,-14.198596000671387,67.1901626586914,5.570833234656931e-06 +4.682610988616943,-14.198596000671387,67.1901626586914,5.744309309043034e-06 +4.682610988616943,-14.198596000671387,67.1901626586914,5.397930232049588e-06 +4.682611465454102,-14.198596000671387,67.1901626586914,5.463730313417086e-06 +4.682610988616943,-14.198596000671387,67.1901626586914,5.676369473466564e-06 +4.682611465454102,-14.198596000671387,67.1901626586914,5.735399476450943e-06 +4.682610988616943,-14.198596000671387,67.1901626586914,5.930650810888697e-06 +4.682611465454102,-14.198596000671387,67.1901626586914,5.61416091076571e-06 +4.682611465454102,-14.198596000671387,67.1901626586914,5.439903810880136e-06 +4.68261194229126,-14.198596000671387,67.1901626586914,5.5867906492448974e-06 +4.682612419128418,-14.198596000671387,67.1901626586914,5.655443070425019e-06 +4.682612895965576,-14.198596000671387,67.1901626586914,5.725836510665879e-06 +4.682612895965576,-14.198596000671387,67.1901626586914,5.213131943003944e-06 +4.682612895965576,-14.198596000671387,67.1901626586914,5.510560069997336e-06 +4.682613372802734,-14.198596000671387,67.1901626586914,5.243907408935436e-06 +4.682613849639893,-14.198596000671387,67.1901626586914,4.813941447440024e-06 +4.682613849639893,-14.198596000671387,67.1901626586914,5.967482495436061e-06 +4.682614326477051,-14.198596000671387,67.1901626586914,5.903855917100212e-06 +4.682614326477051,-14.198596000671387,67.1901626586914,5.244165411249933e-06 +4.682614803314209,-14.198596000671387,67.1901626586914,5.765034900513884e-06 +4.682614326477051,-14.198596000671387,67.1901626586914,5.5806997278973104e-06 +4.682614803314209,-14.198596000671387,67.1901626586914,5.853060065011709e-06 +4.682614803314209,-14.198596000671387,67.1901626586914,5.562958737649197e-06 +4.682615756988525,-14.198596000671387,67.1901626586914,5.8105496462138356e-06 +4.682616233825684,-14.198596000671387,67.1901626586914,5.6812079120675736e-06 +4.682616710662842,-14.198596000671387,67.1901626586914,4.935790434163279e-06 +4.6826171875,-14.198596000671387,67.1901626586914,5.185632951265138e-06 +4.682618141174316,-14.198596000671387,67.1901626586914,5.570702988753784e-06 +4.682617664337158,-14.198596000671387,67.1901626586914,5.702478794962577e-06 +4.6826171875,-14.198596000671387,67.1901626586914,5.524849757493858e-06 +4.6826171875,-14.198596000671387,67.1901626586914,5.376319248893752e-06 +4.6826171875,-14.198596000671387,67.1901626586914,5.0336803306642375e-06 +4.682617664337158,-14.198596000671387,67.1901626586914,4.976875470536887e-06 +4.682617664337158,-14.198596000671387,67.1901626586914,5.707606680401736e-06 +4.6826171875,-14.198596000671387,67.1901626586914,5.624773211709582e-06 +4.682618141174316,-14.198596000671387,67.1901626586914,4.32791918161139e-06 +4.682618618011475,-14.198596000671387,67.1901626586914,5.327056894686993e-06 +4.682619094848633,-14.198596000671387,67.1901626586914,5.736563095250644e-06 +4.682619571685791,-14.198596000671387,67.1901626586914,5.392822190211732e-06 +4.682614803314209,-14.198616981506348,67.1901626586914,0.0033758116829439694 +4.6826276779174805,-14.198603630065918,67.1901626586914,0.0032206975850535145 +4.6826324462890625,-14.198606491088867,67.1901626586914,0.004132230968687076 +4.6825995445251465,-14.19869613647461,67.1901626586914,0.004810414809485927 +4.682379722595215,-14.199237823486328,67.19017028808594,0.01586298906093671 +4.681901931762695,-14.20038890838623,67.1901626586914,0.037954996723668574 +4.681087017059326,-14.202342987060547,67.1901626586914,0.04363367825508737 +4.6804304122924805,-14.203919410705566,67.1901626586914,0.039975493292192035 +4.679778575897217,-14.20548152923584,67.1901626586914,0.03812754075405944 +4.679128170013428,-14.207040786743164,67.1901626586914,0.03845776119271653 +4.678609371185303,-14.208284378051758,67.1901626586914,0.03975542332659805 +4.677774906158447,-14.210283279418945,67.1901626586914,0.046602538176399914 +4.6768598556518555,-14.212474822998047,67.1901626586914,0.050611261243495194 +4.675811290740967,-14.214981079101562,67.1901626586914,0.06385826043456998 +4.674631595611572,-14.21780014038086,67.1901626586914,0.06467634629948461 +4.673230171203613,-14.221144676208496,67.1900405883789,0.09287673000228427 +4.671474456787109,-14.22532844543457,67.18997192382812,0.09758224459958456 +4.669722080230713,-14.229536056518555,67.19204711914062,0.16239857450195225 +4.666325092315674,-14.237560272216797,67.18790435791016,0.23144086878572767 +4.6619672775268555,-14.247908592224121,67.18724060058594,0.24782197374457912 +4.657041072845459,-14.259733200073242,67.19449615478516,0.3382082242751103 +4.650580883026123,-14.275225639343262,67.19998168945312,0.39891843879509276 +4.643274307250977,-14.292634010314941,67.2009506225586,0.40067460976091185 +4.634941577911377,-14.312488555908203,67.20430755615234,0.501687738237964 +4.625919818878174,-14.33396053314209,67.20610809326172,0.5524559329747819 +4.61471700668335,-14.360662460327148,67.2111587524414,0.6348643356537036 +4.6032304763793945,-14.387809753417969,67.20164489746094,0.6568253240573312 +4.590458869934082,-14.418134689331055,67.200927734375,0.6884715605421754 +4.578038692474365,-14.44768238067627,67.2023696899414,0.7324368369450508 +4.56352424621582,-14.482187271118164,67.2033462524414,0.7807467896325413 +4.551033020019531,-14.511874198913574,67.20374298095703,0.7995146197603618 +4.535647869110107,-14.548371315002441,67.1998062133789,0.8123740275339855 +4.525593280792236,-14.57222843170166,67.19763946533203,0.8475790889957904 +4.514873027801514,-14.597725868225098,67.19978332519531,0.8750840298479324 +4.50290584564209,-14.62618350982666,67.20166778564453,0.9089664024460303 +4.486256122589111,-14.665715217590332,67.20046997070312,0.9364183060396734 +4.4703369140625,-14.70350456237793,67.1988296508789,0.925075758828297 +4.4531989097595215,-14.744206428527832,67.19829559326172,0.9016945954987076 +4.43819522857666,-14.779864311218262,67.19570922851562,0.8995112168641175 +4.42094612121582,-14.821369171142578,67.18521118164062,0.902094074110034 +4.404414176940918,-14.862154006958008,67.156982421875,0.937749816531538 +4.386380672454834,-14.908038139343262,67.09960174560547,1.0277060538296876 +4.369845867156982,-14.951430320739746,67.02497100830078,1.0893590228321415 +4.351481914520264,-15.001144409179688,66.91979217529297,1.0585211270968908 +4.335441589355469,-15.045785903930664,66.7933578491211,1.0331475517655984 +4.319265842437744,-15.092244148254395,66.64325714111328,1.1072396110410674 +4.301367282867432,-15.144911766052246,66.45076751708984,1.1487110179727669 +4.284940242767334,-15.192964553833008,66.27654266357422,1.148652648442211 +4.2674241065979,-15.242776870727539,66.10963439941406,1.1080998132871869 +4.250361919403076,-15.289567947387695,65.97068786621094,1.0499494240843754 +4.233899116516113,-15.333017349243164,65.86082458496094,0.9859021661352874 +4.21904993057251,-15.370944023132324,65.77985382080078,0.9251191693685494 +4.203263282775879,-15.410964012145996,65.69461059570312,0.8577378807253533 +4.1889801025390625,-15.44778060913086,65.60405731201172,0.7943188654638351 +4.176461219787598,-15.48087215423584,65.50816345214844,0.7367110286357879 +4.1645355224609375,-15.513340950012207,65.39813232421875,0.6799808570620138 +4.154390335083008,-15.541666030883789,65.29045104980469,0.6307305011797915 +4.144556522369385,-15.568887710571289,65.18877410888672,0.5836532291399443 +4.135404109954834,-15.593484878540039,65.10552215576172,0.5410047312744899 +4.1270060539245605,-15.615306854248047,65.04092407226562,0.5029666659124762 +4.118740558624268,-15.636157989501953,64.98703002929688,0.4662860443519588 +4.1105194091796875,-15.656905174255371,64.9317626953125,0.4295414292944138 +4.103921413421631,-15.674002647399902,64.88025665283203,0.39810901613472993 +4.097259044647217,-15.691548347473145,64.81940460205078,0.36704809850341796 +4.091858863830566,-15.706199645996094,64.76317596435547,0.3418696224714817 +4.086535930633545,-15.720565795898438,64.7090072631836,0.3173408438093228 +4.08174991607666,-15.733154296875,64.6657943725586,0.2956718481749098 +4.076757431030273,-15.74587345123291,64.62725067138672,0.2707898162169716 +4.072743892669678,-15.755806922912598,64.59910583496094,0.1835535912325916 +4.0697150230407715,-15.763405799865723,64.5798568725586,0.15018367270165023 +4.06742000579834,-15.769292831420898,64.56116485595703,0.13237929800803497 +4.065535068511963,-15.774218559265137,64.54296112060547,0.10063569489196435 +4.064141273498535,-15.77801513671875,64.52908325195312,0.08810154265630266 +4.062663555145264,-15.78196907043457,64.5042953491211,0.07441011974507515 +4.061455726623535,-15.785235404968262,64.4896469116211,0.06449526013394177 +4.060296058654785,-15.788287162780762,64.47606658935547,0.06656363941917433 +4.059289932250977,-15.79072093963623,64.457275390625,0.039902351366509416 +4.0583391189575195,-15.793190956115723,64.44991302490234,0.05179142080540155 +4.057461261749268,-15.795401573181152,64.44491577148438,0.039982953424174 +4.056708812713623,-15.797282218933105,64.4413833618164,0.025862131240156242 +4.056038856506348,-15.798985481262207,64.43408966064453,0.05177527444222466 +4.0553483963012695,-15.800782203674316,64.4278564453125,0.04501874928109129 +4.054751873016357,-15.80236530303955,64.42005920410156,0.025968464742824396 +4.054237365722656,-15.80379867553711,64.41844940185547,0.02098184225377647 +4.053737640380859,-15.80514144897461,64.4149398803711,0.029208162926625543 +4.053036689758301,-15.806930541992188,64.40852355957031,0.027124392107675775 +4.052436828613281,-15.808464050292969,64.40799713134766,0.053888170155610045 +4.05147123336792,-15.810847282409668,64.40109252929688,0.04662990658087896 +4.05070161819458,-15.812853813171387,64.3941421508789,0.04705103007571856 +4.050025939941406,-15.814629554748535,64.38777923583984,0.037987969541059645 +4.049388885498047,-15.816354751586914,64.38125610351562,0.03445755796093458 +4.048840522766113,-15.817879676818848,64.37476348876953,0.036492716892766106 +4.048299312591553,-15.819303512573242,64.37007904052734,0.03366672293669229 +4.047603130340576,-15.821045875549316,64.36582946777344,0.05662759028019834 +4.0466837882995605,-15.823351860046387,64.36006164550781,0.06105925666380535 +4.045628547668457,-15.826037406921387,64.35356903076172,0.06703209588789248 +4.044590473175049,-15.828657150268555,64.3419189453125,0.059091087414897665 +4.043587684631348,-15.83130931854248,64.33256530761719,0.05745578099564162 +4.0426154136657715,-15.83394718170166,64.3226318359375,0.08390782313872691 +4.040822505950928,-15.83849048614502,64.29863739013672,0.15183378241101747 +4.03762674331665,-15.846864700317383,64.27116394042969,0.22018965999479412 +4.0331711769104,-15.858302116394043,64.23782348632812,0.27182315793221945 +4.028707504272461,-15.869426727294922,64.21086120605469,0.2587418579188395 +4.023674964904785,-15.881375312805176,64.17574310302734,0.31755800568490683 +4.0168914794921875,-15.897408485412598,64.1370849609375,0.3912611139834018 +4.009617805480957,-15.914704322814941,64.09284210205078,0.4748958025450263 +4.0016679763793945,-15.934353828430176,64.03545379638672,0.5293168469316158 +3.993116617202759,-15.956230163574219,63.95756149291992,0.49080673267688396 +3.9845266342163086,-15.978713035583496,63.869258880615234,0.48897196640954665 +3.9742629528045654,-16.005220413208008,63.751747131347656,0.6261179316213661 +3.962653160095215,-16.034740447998047,63.63777160644531,0.7456650274886456 +3.9479081630706787,-16.070980072021484,63.51051712036133,0.8076409718014691 +3.9330074787139893,-16.106386184692383,63.40686798095703,0.8654439667953273 +3.916149139404297,-16.14515495300293,63.30661392211914,0.9031176068979029 +3.8990700244903564,-16.18426513671875,63.20954513549805,0.921870576058542 +3.8823041915893555,-16.223173141479492,63.098594665527344,0.9575247441402637 +3.8643300533294678,-16.265846252441406,62.957969665527344,0.9391284373293143 +3.848421573638916,-16.30457305908203,62.81148910522461,0.8971957066034536 +3.8330013751983643,-16.342857360839844,62.65152359008789,0.8438799902343194 +3.819672107696533,-16.375652313232422,62.516357421875,0.7930893549624382 +3.8049440383911133,-16.41089630126953,62.38255310058594,0.7349878964246064 +3.792569875717163,-16.43947410583496,62.28662109375,0.6859310597614873 +3.779533624649048,-16.468732833862305,62.20051956176758,0.6342413604934887 +3.7682595252990723,-16.49388313293457,62.12675476074219,0.5894302906535844 +3.7570769786834717,-16.51922607421875,62.043521881103516,0.5440865571284855 +3.7478201389312744,-16.54071044921875,61.963260650634766,0.5056141530698998 +3.7392797470092773,-16.56106185913086,61.87758255004883,0.46919453406853584 +3.7309765815734863,-16.581310272216797,61.78400802612305,0.43324532232121016 +3.723686695098877,-16.59898567199707,61.70315933227539,0.4021656059191171 +3.716407060623169,-16.616195678710938,61.63009262084961,0.3718217409263774 +3.710120677947998,-16.6307315826416,61.58002471923828,0.30945186838730404 +3.704793691635132,-16.642736434936523,61.538169860839844,0.23802081414074433 +3.700770378112793,-16.65159797668457,61.511199951171875,0.19876027243607175 +3.696929931640625,-16.660003662109375,61.48540115356445,0.18131964044299645 +3.6938765048980713,-16.666812896728516,61.46200180053711,0.14897161735089906 +3.691319704055786,-16.67262077331543,61.43939971923828,0.14108058060558545 +3.6889448165893555,-16.678190231323242,61.41575241088867,0.131152054950437 +3.686060667037964,-16.685178756713867,61.386390686035156,0.16516682349050107 +3.6823883056640625,-16.69390106201172,61.34366226196289,0.21460655247046584 +3.6781551837921143,-16.70384407043457,61.30137634277344,0.25938756944852803 +3.673013210296631,-16.715635299682617,61.25396728515625,0.28450668747910624 +3.667090892791748,-16.728723526000977,61.206756591796875,0.31141040062389547 +3.6610934734344482,-16.741697311401367,61.16529083251953,0.3068046541619181 +3.6542909145355225,-16.756372451782227,61.12022399902344,0.3758837035675328 +3.6467556953430176,-16.77284049987793,61.06391143798828,0.399917745621021 +3.6389389038085938,-16.790353775024414,60.99394226074219,0.41034160409380926 +3.6310038566589355,-16.808551788330078,60.914588928222656,0.4541706210236617 +3.622811794281006,-16.827362060546875,60.828887939453125,0.45373750561325255 +3.6139347553253174,-16.847341537475586,60.747344970703125,0.510054700623176 +3.6037750244140625,-16.86959457397461,60.66783905029297,0.5292600818777301 +3.59244441986084,-16.89358901977539,60.589656829833984,0.5353075182392415 +3.58134388923645,-16.91639518737793,60.5260124206543,0.5525244055077427 +3.571192502975464,-16.93717384338379,60.46736145019531,0.5660833522280873 +3.558797597885132,-16.96284294128418,60.38704299926758,0.6000058037172961 +3.54599928855896,-16.98995018005371,60.289188385009766,0.6334445817687319 +3.533682107925415,-17.016674041748047,60.1793327331543,0.6512590042876282 +3.522096872329712,-17.042360305786133,60.062076568603516,0.6553242319088832 +3.509082317352295,-17.07117462158203,59.93061828613281,0.663271817547024 +3.495415210723877,-17.100830078125,59.80369186401367,0.6896253344517377 +3.48012638092041,-17.132925033569336,59.67958068847656,0.7137340054661767 +3.466097116470337,-17.161457061767578,59.583282470703125,0.7274151316084141 +3.4499058723449707,-17.19340705871582,59.49006271362305,0.7406719756767447 +3.4347920417785645,-17.222999572753906,59.40369415283203,0.7452392965985112 +3.417897939682007,-17.2564640045166,59.29629898071289,0.7733448122738348 +3.4018495082855225,-17.288867950439453,59.17770004272461,0.7993894416605096 +3.385693073272705,-17.322216033935547,59.03945541381836,0.8093662941262798 +3.368279457092285,-17.358842849731445,58.871150970458984,0.8292685979418614 +3.351579427719116,-17.393842697143555,58.71033477783203,0.8402465427617061 +3.3355817794799805,-17.426593780517578,58.56982421875,0.8440563091331292 +3.3177478313446045,-17.462127685546875,58.43003845214844,0.8315639851529875 +3.299290895462036,-17.497821807861328,58.30502700805664,0.8556226330239664 +3.2806758880615234,-17.53351593017578,58.1805305480957,0.8741759478048287 +3.2615437507629395,-17.570566177368164,58.0389289855957,0.8824532512042427 +3.2432010173797607,-17.606761932373047,57.884300231933594,0.900533516220796 +3.2249553203582764,-17.64332389831543,57.71414566040039,0.9120398862946218 +3.204883575439453,-17.683353424072266,57.52682876586914,0.9286260357176699 +3.184349298477173,-17.723329544067383,57.35293197631836,0.9441904367596526 +3.1634089946746826,-17.76292610168457,57.196537017822266,0.9427646828640164 +3.1441423892974854,-17.798315048217773,57.06990432739258,0.9452164869437342 +3.1219265460968018,-17.838821411132812,56.926605224609375,0.9607941871864192 +3.0995259284973145,-17.88007354736328,56.76580810546875,0.973720830819473 +3.0781898498535156,-17.92003059387207,56.59156799316406,0.9699021253672053 +3.0569329261779785,-17.96060562133789,56.39447784423828,0.9704588627054828 +3.0369017124176025,-17.999425888061523,56.19005584716797,0.9803468776757076 +3.0144097805023193,-18.042749404907227,55.96147918701172,0.9876691217346073 +2.993488311767578,-18.082080841064453,55.76478958129883,1.0012756093700443 +2.970141649246216,-18.12461280822754,55.57046890258789,1.0133956809629212 +2.9468307495117188,-18.16595458984375,55.40126037597656,1.0097394478675108 +2.923571825027466,-18.20561408996582,55.256378173828125,1.0176245787166183 +2.8990893363952637,-18.247114181518555,55.104984283447266,1.0096469027118886 +2.8763487339019775,-18.286027908325195,54.95068359375,1.0230577041796565 +2.849868059158325,-18.3320255279541,54.747093200683594,1.0220524351608067 +2.8266541957855225,-18.372867584228516,54.546058654785156,1.0328759394917597 +2.803264617919922,-18.41510772705078,54.32173538208008,1.0298047835399946 +2.7783257961273193,-18.4595947265625,54.08426284790039,1.03634380221502 +2.7571609020233154,-18.49644660949707,53.898582458496094,1.0401753058900418 +2.7298550605773926,-18.542587280273438,53.685184478759766,1.0405352845379339 +2.7049527168273926,-18.583288192749023,53.51756286621094,1.0463104756660822 +2.67965030670166,-18.62355613708496,53.3680419921875,1.052219223823921 +2.6530444622039795,-18.665592193603516,53.2091178894043,1.0303949147269627 +2.6285033226013184,-18.704788208007812,53.04827117919922,1.0453210976895402 +2.601288080215454,-18.748838424682617,52.84739303588867,1.0526973016190457 +2.5765979290008545,-18.789451599121094,52.64168167114258,1.0583183327417365 +2.5498673915863037,-18.83402442932129,52.396034240722656,1.0621782688441592 +2.525738477706909,-18.8740177154541,52.174964904785156,1.0475378786331544 +2.5014140605926514,-18.91349983215332,51.9676399230957,1.0216103336749742 +2.475341320037842,-18.95461654663086,51.76768112182617,1.0314939742074258 +2.4486613273620605,-18.99543571472168,51.5880241394043,1.0085692995025795 +2.424281358718872,-19.031810760498047,51.44236373901367,0.9638235102074999 +2.399512529373169,-19.068464279174805,51.293949127197266,0.9063222405199335 +2.3773460388183594,-19.10158920288086,51.152099609375,0.8482998791505415 +2.355006456375122,-19.135143280029297,50.99919891357422,0.7856680089866791 +2.3362534046173096,-19.163501739501953,50.86200714111328,0.7312558485703586 +2.318988084793091,-19.18978500366211,50.7278938293457,0.6802312809151354 +2.302237033843994,-19.2154598236084,50.59027862548828,0.6301182243977737 +2.2863359451293945,-19.2399845123291,50.45285415649414,0.5821861024175414 +2.2731692790985107,-19.260332107543945,50.335960388183594,0.5425589276533366 +2.258960485458374,-19.28205108642578,50.21415710449219,0.5003203326772281 +2.246577501296997,-19.30073356628418,50.114105224609375,0.4634039253087339 +2.2350404262542725,-19.317874908447266,50.02367401123047,0.4290071969558265 +2.225541830062866,-19.332094192504883,49.94558334350586,0.4008561000666091 +2.2114741802215576,-19.353443145751953,49.82090759277344,0.35877270076119616 +2.200244903564453,-19.370647430419922,49.715694427490234,0.3233332493368307 +2.1921017169952393,-19.383081436157227,49.639678955078125,0.3008394890791641 +2.1842610836029053,-19.39502716064453,49.56637954711914,0.27737654517023674 +2.1780686378479004,-19.404460906982422,49.50800704956055,0.2588053440690031 +2.1712260246276855,-19.41489028930664,49.4427375793457,0.23826459406344183 +2.1654202938079834,-19.42373275756836,49.38694381713867,0.22084785949560476 +2.159709930419922,-19.432411193847656,49.33209228515625,0.20374671276348508 +2.1548731327056885,-19.439741134643555,49.285682678222656,0.18927544218505327 +2.150308847427368,-19.4466552734375,49.24171829223633,0.1756103553458897 +2.1462416648864746,-19.452816009521484,49.20236587524414,0.1634245425935868 +2.1421031951904297,-19.45909309387207,49.161922454833984,0.15099622656107978 +2.1385927200317383,-19.46442413330078,49.12722396850586,0.14044678520571724 +2.1351730823516846,-19.46961784362793,49.093170166015625,0.13016881332264751 +2.131948947906494,-19.47450828552246,49.0611572265625,0.12048171677466225 +2.1288363933563232,-19.479217529296875,49.03033447265625,0.11116119634012651 +2.1261415481567383,-19.4832706451416,49.00425338745117,0.1031331145706292 +2.1234188079833984,-19.48731803894043,48.979087829589844,0.09510847740422643 +2.1209986209869385,-19.490848541259766,48.95851135253906,0.08807339083026842 +2.118903875350952,-19.493833541870117,48.94248962402344,0.0820680819427509 +2.116685390472412,-19.4969425201416,48.92705535888672,0.07572850761798063 +2.114781618118286,-19.49962043762207,48.91350173950195,0.07021233744185183 +2.1130263805389404,-19.502134323120117,48.899818420410156,0.06505051972843452 +2.1112751960754395,-19.504695892333984,48.884552001953125,0.05981068384770747 +2.110356092453003,-19.50614356994629,48.8808708190918,0.03129754582225962 +2.109586238861084,-19.5072078704834,48.864444732666016,0.02420803710380141 +2.1088922023773193,-19.508331298828125,48.86091232299805,0.026078829822346803 +2.1083176136016846,-19.509227752685547,48.854713439941406,0.022663530210394283 +2.107726573944092,-19.510080337524414,48.846500396728516,0.022450635268029567 +2.107164144515991,-19.51089096069336,48.84149932861328,0.022906535919855208 +2.106046438217163,-19.512441635131836,48.83255386352539,0.03995852962470768 +2.1049766540527344,-19.51389503479004,48.81949996948242,0.03877497378480028 +2.103761672973633,-19.515567779541016,48.80607986450195,0.0453409079923686 +2.1025564670562744,-19.51735496520996,48.79719924926758,0.044474200516324024 +2.1012485027313232,-19.519378662109375,48.789085388183594,0.0760672969741606 +2.098754405975342,-19.523157119750977,48.76178741455078,0.0868702867301786 +2.095918893814087,-19.527515411376953,48.7303352355957,0.14793450633604804 +2.0925490856170654,-19.532604217529297,48.69669723510742,0.1253631884617443 +2.0891308784484863,-19.537683486938477,48.6650276184082,0.1231874705588501 +2.085188388824463,-19.54332160949707,48.63100051879883,0.1878762678081532 +2.078348398208618,-19.55278205871582,48.577789306640625,0.278219405133716 +2.071685552597046,-19.56202507019043,48.5265007019043,0.25915838079036924 +2.0628697872161865,-19.574478149414062,48.462806701660156,0.358379237188432 +2.0524837970733643,-19.58931541442871,48.37490463256836,0.4103680346894212 +2.041504383087158,-19.605302810668945,48.270904541015625,0.43567136386925337 +2.0292346477508545,-19.62315559387207,48.15557098388672,0.46444689530415684 +2.015751361846924,-19.642391204833984,48.03750991821289,0.4979867536577522 +2.0019619464874268,-19.661584854125977,47.92988204956055,0.5442179635168496 +1.9866377115249634,-19.68242835998535,47.81886291503906,0.5862129429442375 +1.9687479734420776,-19.70665740966797,47.68790817260742,0.6383147706983577 +1.951740026473999,-19.72993278503418,47.555946350097656,0.6961054008667193 +1.9307584762573242,-19.75904655456543,47.37648010253906,0.7411820686948558 +1.91061270236969,-19.787309646606445,47.18605041503906,0.7674950613394714 +1.8879892826080322,-19.818912506103516,46.982147216796875,0.8153834969894258 +1.8653188943862915,-19.849836349487305,46.78899383544922,0.8651723321995248 +1.840140700340271,-19.883258819580078,46.594322204589844,0.9051038830952657 +1.8161715269088745,-19.914335250854492,46.42681121826172,0.9388590188268134 +1.7881654500961304,-19.950361251831055,46.23186111450195,0.9737136882186241 +1.758302092552185,-19.989009857177734,46.009552001953125,1.0261351694470786 +1.7282872200012207,-20.028297424316406,45.76142501831055,1.0490293056168962 +1.700854778289795,-20.064632415771484,45.52085876464844,1.0813843527508584 +1.6679607629776,-20.107845306396484,45.228492736816406,1.124355244810117 +1.6365243196487427,-20.148265838623047,44.97229766845703,1.1591948580845064 +1.6008943319320679,-20.19279670715332,44.706295013427734,1.1736618448540759 +1.5666288137435913,-20.23447036743164,44.47518539428711,1.2099903445492863 +1.5304139852523804,-20.2780818939209,44.230812072753906,1.23240632716764 +1.491538405418396,-20.32510757446289,43.950130462646484,1.2627212144204296 +1.4551465511322021,-20.369518280029297,43.66220474243164,1.2713229150187837 +1.4155988693237305,-20.418140411376953,43.32263946533203,1.304750533549539 +1.3776960372924805,-20.464269638061523,42.99802017211914,1.3087872897867363 +1.34053635597229,-20.508630752563477,42.70293045043945,1.302042551914451 +1.3019174337387085,-20.553224563598633,42.42533493041992,1.32824602650873 +1.2586811780929565,-20.601688385009766,42.1439323425293,1.3642313682213272 +1.2129237651824951,-20.65235137939453,41.850685119628906,1.3942906041863856 +1.1717637777328491,-20.69795036315918,41.5644416809082,1.4070606341903416 +1.1249364614486694,-20.750368118286133,41.21717834472656,1.4269861212383015 +1.0828317403793335,-20.797992706298828,40.873382568359375,1.4455606015648257 +1.0353014469146729,-20.85201072692871,40.4554557800293,1.4582700238504527 +0.9928538799285889,-20.899755477905273,40.08969497680664,1.463241462270869 +0.9434605836868286,-20.953824996948242,39.687339782714844,1.483274999083377 +0.8979081511497498,-21.002126693725586,39.34825134277344,1.499173787485517 +0.8496426939964294,-21.051698684692383,39.023990631103516,1.5079217940394705 +0.8011360764503479,-21.10004997253418,38.72796630859375,1.518522926252648 +0.7474948167800903,-21.152828216552734,38.40099334716797,1.5282099060557446 +0.6981454491615295,-21.20152473449707,38.08223342895508,1.5226284929307956 +0.6509479880332947,-21.248432159423828,37.755069732666016,1.535142834210204 +0.595817506313324,-21.303680419921875,37.334415435791016,1.54824530450937 +0.5494224429130554,-21.350448608398438,36.951656341552734,1.5547052933984167 +0.49449145793914795,-21.405107498168945,36.487144470214844,1.5446640893728452 +0.4435364305973053,-21.45452117919922,36.09141540527344,1.5560028138081006 +0.39312952756881714,-21.501893997192383,35.734886169433594,1.58520542793931 +0.3374538719654083,-21.55262565612793,35.372535705566406,1.5944928145211128 +0.28033357858657837,-21.603933334350586,35.007843017578125,1.5988006264337467 +0.2250019907951355,-21.653539657592773,34.624656677246094,1.6124200151509402 +0.16671693325042725,-21.706071853637695,34.19537353515625,1.624563910654354 +0.11218873411417007,-21.755155563354492,33.77542495727539,1.6357250829265733 +0.06082107871770859,-21.800617218017578,33.392024993896484,1.641095897427896 +-0.0027954562101513147,-21.85527992248535,32.94558334350586,1.646393033152378 +-0.06096222251653671,-21.903532028198242,32.574249267578125,1.657708987759988 +-0.1243404746055603,-21.954721450805664,32.19464874267578,1.668353439440703 +-0.17663924396038055,-21.996654510498047,31.879823684692383,1.6676166891277322 +-0.23903268575668335,-22.046701431274414,31.47024917602539,1.667512078661465 +-0.2994261384010315,-22.095340728759766,31.047924041748047,1.677768030235287 +-0.36199110746383667,-22.145179748535156,30.611188888549805,1.6827603866942458 +-0.42642784118652344,-22.195085525512695,30.18692398071289,1.6972014346352235 +-0.48889654874801636,-22.24186897277832,29.812456130981445,1.7055830174436883 +-0.5554015040397644,-22.2901611328125,29.441198348999023,1.7070316744654492 +-0.6194441318511963,-22.336097717285156,29.082029342651367,1.71444619665243 +-0.6822006106376648,-22.38115119934082,28.70565414428711,1.7209039602079699 +-0.7518933415412903,-22.4313907623291,28.254304885864258,1.7253046874682214 +-0.8178673982620239,-22.478580474853516,27.81656837463379,1.7294520371647064 +-0.8827170133590698,-22.52382469177246,27.40664291381836,1.7367611511389607 +-0.9408872127532959,-22.563156127929688,27.058212280273438,1.7024470189889276 +-1.0300172567367554,-22.621490478515625,26.585519790649414,1.6765474420036337 +-1.0971378087997437,-22.664350509643555,26.23179817199707,1.691629511569607 +-1.1671702861785889,-22.709096908569336,25.84149742126465,1.6888541245811082 +-1.2362563610076904,-22.75347137451172,25.419687271118164,1.7251432477328144 +-1.30087411403656,-22.79481315612793,25.013700485229492,1.7494380638694218 +-1.3742157220840454,-22.840641021728516,24.571401596069336,1.7613758248756757 +-1.445801019668579,-22.883792877197266,24.174091339111328,1.7649533201621648 +-1.5163373947143555,-22.92479705810547,23.818044662475586,1.770471136662613 +-1.5844390392303467,-22.96343421936035,23.48436164855957,1.7690947201048348 +-1.6445612907409668,-22.997365951538086,23.182809829711914,1.770841341521129 +-1.7284941673278809,-23.044864654541016,22.725797653198242,1.768406724183082 +-1.7981915473937988,-23.084501266479492,22.316083908081055,1.7776305074328693 +-1.8649592399597168,-23.122013092041016,21.923004150390625,1.780635046210589 +-1.9452184438705444,-23.16574478149414,21.476734161376953,1.7751794763639752 +-2.011162757873535,-23.200342178344727,21.142148971557617,1.7761834390414846 +-2.0870261192321777,-23.238698959350586,20.792407989501953,1.7877018612784104 +-2.162097692489624,-23.275964736938477,20.447011947631836,1.7938497188974896 +-2.2421698570251465,-23.315731048583984,20.051795959472656,1.7994605429747588 +-2.3093464374542236,-23.34929847717285,19.691434860229492,1.8013408139358549 +-2.39021897315979,-23.38979148864746,19.230222702026367,1.8036561960205821 +-2.464730978012085,-23.426326751708984,18.811927795410156,1.808232065873975 +-2.541147470474243,-23.46247100830078,18.410539627075195,1.805108295334271 +-2.6125683784484863,-23.494916915893555,18.070106506347656,1.801105105172024 +-2.690911293029785,-23.529064178466797,17.73133087158203,1.8104560290276959 +-2.773822069168091,-23.56443214416504,17.374053955078125,1.8199421828281521 +-2.850592613220215,-23.59718894958496,17.019207000732422,1.824409820803049 +-2.930703639984131,-23.63164710998535,16.61478042602539,1.8235212009933592 +-3.005262613296509,-23.663888931274414,16.20880699157715,1.8305103996900391 +-3.081523895263672,-23.696340560913086,15.793923377990723,1.835364780974219 +-3.166400909423828,-23.73107147216797,15.36194133758545,1.8414704019068313 +-3.2462737560272217,-23.762191772460938,14.993398666381836,1.8467119597422268 +-3.325122833251953,-23.79153823852539,14.662275314331055,1.851791406903913 +-3.4114983081817627,-23.8229923248291,14.30016040802002,1.8554664829278373 +-3.484661817550659,-23.84963035583496,13.972260475158691,1.8574405574310318 +-3.571012496948242,-23.881315231323242,13.549500465393066,1.8548691775180484 +-3.6483659744262695,-23.90979766845703,13.144118309020996,1.8571043455348986 +-3.7371432781219482,-23.94167137145996,12.687020301818848,1.8644426265152187 +-3.8167836666107178,-23.968963623046875,12.305837631225586,1.8707134166262607 +-3.8996245861053467,-23.995885848999023,11.945586204528809,1.8745081283457472 +-3.9828789234161377,-24.021554946899414,11.61651611328125,1.877888247287727 +-4.071736812591553,-24.048330307006836,11.263696670532227,1.8799201952516822 +-4.1482157707214355,-24.071401596069336,10.937347412109375,1.8806319292260536 +-4.234231948852539,-24.097612380981445,10.535605430603027,1.8799255244621835 +-4.3172454833984375,-24.123056411743164,10.117742538452148,1.8777408207596527 +-4.402621269226074,-24.14855194091797,9.692252159118652,1.8831463762010405 +-4.478776931762695,-24.170194625854492,9.337440490722656,1.8869263532944207 +-4.567525386810303,-24.19392204284668,8.960482597351074,1.8906696466985395 +-4.6606526374816895,-24.21721649169922,8.603731155395508,1.8942512268094758 +-4.744080543518066,-24.237518310546875,8.282662391662598,1.896311918136227 +-4.827159404754639,-24.257787704467773,7.9379777908325195,1.8964344024960722 +-4.910929203033447,-24.27847671508789,7.557554244995117,1.89167943534177 +-5.000455379486084,-24.30077362060547,7.117336273193359,1.8936826997500444 +-5.090442180633545,-24.32252311706543,6.676799297332764,1.8930957367669023 +-5.175005912780762,-24.341699600219727,6.291635513305664,1.8819484906305655 +-5.261970043182373,-24.359954833984375,5.932326793670654,1.8339941916558544 +-5.341457366943359,-24.37538719177246,5.6360602378845215,1.7537600182313327 +-5.415258884429932,-24.38919448852539,5.363796234130859,1.656975612899185 +-5.493921279907227,-24.403987884521484,5.0508036613464355,1.5402794349293947 +-5.562632083892822,-24.41724967956543,4.7470808029174805,1.4316042588741857 +-5.625671863555908,-24.42972183227539,4.4422807693481445,1.32925736987785 +-5.681885719299316,-24.440614700317383,4.170044422149658,1.2378226431593475 +-5.733986854553223,-24.45012092590332,3.9330391883850098,1.1526614551094976 +-5.7862772941589355,-24.458942413330078,3.716017961502075,1.0669224355104183 +-5.836765766143799,-24.46670150756836,3.5295932292938232,0.9839457494681145 +-5.878331661224365,-24.47268295288086,3.3867299556732178,0.9150462674281861 +-5.919435977935791,-24.4786319732666,3.2382164001464844,0.8464293206482765 +-5.9564738273620605,-24.484220504760742,3.0906097888946533,0.7844118354951816 +-5.9932098388671875,-24.490062713623047,2.927593469619751,0.7227165821652639 +-6.022985935211182,-24.494997024536133,2.7843005657196045,0.6730346264976695 +-6.05427885055542,-24.50006103515625,2.636211395263672,0.6214218311804026 +-6.08164644241333,-24.50419807434082,2.5162694454193115,0.5764520689355161 +-6.105201721191406,-24.50748634338379,2.4225473403930664,0.5377664015123184 +-6.129685401916504,-24.510629653930664,2.3345940113067627,0.49745290034448914 +-6.15299129486084,-24.513534545898438,2.252255916595459,0.45872750769877646 +-6.172908306121826,-24.516117095947266,2.1763646602630615,0.4254624722108241 +-6.192048072814941,-24.51876449584961,2.095454454421997,0.3934005349129951 +-6.207417011260986,-24.521020889282227,2.027981996536255,0.31306550753722967 +-6.221119403839111,-24.52303695678711,1.9676202535629272,0.2640374233577066 +-6.232215404510498,-24.524587631225586,1.9228556156158447,0.24103228510722505 +-6.245127201080322,-24.52620506286621,1.8734259605407715,0.3447511758808256 +-6.2668914794921875,-24.528608322143555,1.803246259689331,0.5846658985832119 +-6.301483631134033,-24.53240394592285,1.6896002292633057,0.8382695584851234 +-6.344670295715332,-24.5373477935791,1.5287607908248901,1.009341205769048 +-6.397219181060791,-24.543731689453125,1.3162156343460083,1.229000470057876 +-6.458347797393799,-24.551513671875,1.0452604293823242,1.4198081814100159 +-6.534339427947998,-24.560985565185547,0.7026229500770569,1.5583621539536885 +-6.607790946960449,-24.56931495666504,0.3897079527378082,1.5732468873113659 +-6.677226543426514,-24.576223373413086,0.12063232809305191,1.5327564734780927 +-6.751265048980713,-24.58258056640625,-0.13897705078125,1.4524569076921405 +-6.815530776977539,-24.587799072265625,-0.36578369140625,1.3651632761760797 +-6.8737664222717285,-24.592695236206055,-0.5889586806297302,1.2780356311828946 +-6.92922306060791,-24.597673416137695,-0.8241271376609802,1.19080589172077 +-6.981160640716553,-24.60259246826172,-1.0636900663375854,1.1073625591906033 +-7.035060405731201,-24.60748291015625,-1.310882568359375,1.0206398817418731 +-7.077815532684326,-24.61089324951172,-1.501953125,0.6572992980974286 +-7.084827899932861,-24.61151123046875,-1.528839111328125,0.0010302438782061251 +-7.08479118347168,-24.611515045166016,-1.5288392305374146,0.0003061020135545053 +-7.084839344024658,-24.611520767211914,-1.5288392305374146,0.0004810461363893223 +-7.084896087646484,-24.61152458190918,-1.528839111328125,0.0003921216588950071 +-7.084954261779785,-24.611528396606445,-1.5288392305374146,0.00028673745042784993 +-7.085002422332764,-24.61154556274414,-1.5288389921188354,0.00021159225978558609 +-7.085037708282471,-24.61155891418457,-1.5288389921188354,0.0001721264418680282 +-7.085068702697754,-24.611572265625,-1.5288389921188354,0.00014193858694965425 +-7.085092067718506,-24.61157989501953,-1.528839111328125,0.00011826234055147073 +-7.085109710693359,-24.61158561706543,-1.528839111328125,9.291112488737998e-05 +-7.085122585296631,-24.611591339111328,-1.5288389921188354,6.878995713504572e-05 +-7.085132122039795,-24.611597061157227,-1.528839111328125,4.8306890760882516e-05 +-7.085137367248535,-24.61159896850586,-1.528839111328125,3.434689707574305e-05 +-7.085139751434326,-24.611600875854492,-1.528839111328125,1.3231296232877298e-05 +-7.085142612457275,-24.611602783203125,-1.528839111328125,1.1654781007874459e-05 +-7.08514404296875,-24.61160659790039,-1.528839111328125,9.73591939011046e-06 +-7.085144996643066,-24.61160659790039,-1.528839111328125,8.116861911742724e-06 +-7.085145950317383,-24.61160659790039,-1.528839111328125,6.462430969019272e-06 +-7.085293292999268,-24.611618041992188,-1.52935791015625,0.007036407024041 +-7.085983753204346,-24.61166763305664,-1.532135009765625,0.013213379630955858 +-7.086576461791992,-24.61170768737793,-1.5345155000686646,0.014437620631545666 +-7.086958408355713,-24.61173439025879,-1.536041259765625,6.950978440502995e-06 +-7.086956024169922,-24.611732482910156,-1.536041259765625,2.1581041447743727e-06 +-7.086956024169922,-24.611732482910156,-1.536041259765625,3.384823452637212e-06 +-7.08695650100708,-24.61173439025879,-1.536041259765625,4.663103400600108e-06 +-7.08695650100708,-24.61173439025879,-1.536041259765625,4.772696405032955e-06 +-7.0869574546813965,-24.61173439025879,-1.536041259765625,4.482659315438443e-06 +-7.0869574546813965,-24.61173439025879,-1.536041259765625,4.106742846492604e-06 +-7.0869574546813965,-24.61173439025879,-1.536041259765625,2.0332327083723044e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,4.317548948671608e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,4.057998921543322e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,4.123965035629055e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.7187746383835297e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.2731546697336695e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.66140030535487e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.5610805491147854e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.975607471616704e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.689128520696735e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,2.8596036326721437e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.334497626166826e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.776128176412796e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,3.8819791133362545e-06 +-7.086957931518555,-24.61173439025879,-1.536041259765625,4.0318376438095e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.375433384160641e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.7731460711933505e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.384139649594022e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.928670118467883e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.981789756706741e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.140125974071037e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.6662547476603026e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.039986950116442e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.24517982830646e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.043449082825764e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.838389903994313e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.7298014061902564e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.8924980036895645e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.416738775014042e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.256921316652425e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.634064957008555e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.499933312345533e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.191226416423942e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.337956609089161e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.397976155057868e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.82008829063734e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.998608720052604e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.931215791557961e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.893129265095091e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.099272434497361e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.283221847117827e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.201954109699715e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.166222532693439e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.5220694727368923e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.906196878097056e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.988729430461715e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.138052168239797e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.148686719526962e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.075010264451841e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.2445362042076995e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.957125200044628e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.3766687564631347e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.08476485064696e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.401626354696082e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.453307987998694e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.169413559176492e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.5478408018257807e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,2.2839775828714896e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.89425381598515e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.215358837054198e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.125958153194569e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.444191453320688e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.065688412442268e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.004243135715876e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.243741048112449e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.286563581501284e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.08299641958709e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.20363142979817e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,3.3904460004026936e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.161943826712468e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.314091787642561e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.5377703909761576e-06 +-4.8475494384765625,-24.538061141967773,5.335170269012451,4.501210157090927e-06 +-4.84737491607666,-24.537931442260742,5.341609954833984,0.0031205072802748058 +-4.847076892852783,-24.537858963012695,5.345667362213135,0.004571052205604519 +-4.846683979034424,-24.5377140045166,5.351377964019775,0.02419668602584408 +-4.845739364624023,-24.53734016418457,5.364868640899658,0.01886948053379242 +-4.843859672546387,-24.536556243896484,5.38709020614624,0.0557249420661946 +-4.839582920074463,-24.53478240966797,5.447758197784424,0.1069714782571468 +-4.832472801208496,-24.531740188598633,5.547866344451904,0.18172572007095952 +-4.822650909423828,-24.527589797973633,5.690010070800781,0.23984023978488941 +-4.809952735900879,-24.52212142944336,5.864106178283691,0.3125062554881517 +-4.795618057250977,-24.515872955322266,6.066020488739014,0.4052242573417077 +-4.782258987426758,-24.50997543334961,6.250126361846924,0.43634452982422794 +-4.763763904571533,-24.501684188842773,6.508621692657471,0.4975333769819383 +-4.739957332611084,-24.49079132080078,6.846253395080566,0.5369027172068965 +-4.718390464782715,-24.480743408203125,7.153125286102295,0.551093913115472 +-4.695491313934326,-24.46990966796875,7.480016231536865,0.555029548555188 +-4.672449111938477,-24.458839416503906,7.810050964355469,0.5526689558594948 +-4.65104866027832,-24.44840431213379,8.117560386657715,0.5472706920350655 +-4.634939193725586,-24.44045066833496,8.349642753601074,0.5419786227570724 +-4.61151647567749,-24.428739547729492,8.688037872314453,0.5331381865385398 +-4.59733772277832,-24.42156219482422,8.893439292907715,0.5273598411682177 +-4.577178478240967,-24.411251068115234,9.186205863952637,0.5187968139884808 +-4.55665397644043,-24.400611877441406,9.485163688659668,0.5098073663205702 +-4.5359015464782715,-24.389719009399414,9.788352012634277,0.5005449339464294 +-4.516043186187744,-24.379159927368164,10.079340934753418,0.49157805658156256 +-4.497550964355469,-24.36920928955078,10.35111141204834,0.4831672774209948 +-4.478206634521484,-24.358673095703125,10.63625431060791,0.47432468181078263 +-4.459751129150391,-24.34850311279297,10.909079551696777,0.4658552226691053 +-4.441710948944092,-24.338451385498047,11.176520347595215,0.45755094496473914 +-4.423769950866699,-24.328344345092773,11.443216323852539,0.4492702295466943 +-4.408433437347412,-24.319618225097656,11.6718111038208,0.44217631838360705 +-4.389266014099121,-24.30859375,11.958328247070312,0.4332899621960241 +-4.372037410736084,-24.298574447631836,12.216680526733398,0.4252849444562549 +-4.355638027191162,-24.288936614990234,12.46325969696045,0.4176488731079297 +-4.339465618133545,-24.279340744018555,12.707122802734375,0.410104063434568 +-4.323627948760986,-24.269845962524414,12.946633338928223,0.4027000031736283 +-4.308775901794434,-24.2608585357666,13.170411109924316,0.3773762561551086 +-4.294741630554199,-24.252174377441406,13.386542320251465,0.3486280595784756 +-4.281933307647705,-24.24418067932129,13.585502624511719,0.345731511427982 +-4.268462657928467,-24.23583984375,13.790518760681152,0.3523219808368928 +-4.256137847900391,-24.22816276550293,13.979520797729492,0.3257979610231816 +-4.242396354675293,-24.219587326049805,14.18993854522705,0.37322492203362756 +-4.2322845458984375,-24.213233947753906,14.344979286193848,0.3919161037852803 +-4.217004776000977,-24.203588485717773,14.578896522521973,0.3960212493486298 +-4.199862480163574,-24.192691802978516,14.842679977416992,0.4793385428751104 +-4.179818153381348,-24.179840087890625,15.15207576751709,0.5050253416119842 +-4.159780025482178,-24.166860580444336,15.459973335266113,0.5918001008618416 +-4.134130001068115,-24.150043487548828,15.854567527770996,0.6941677158313975 +-4.105008602142334,-24.130653381347656,16.305410385131836,0.7829860309298854 +-4.073540687561035,-24.10933494567871,16.794092178344727,0.8496216724702891 +-4.0410919189453125,-24.08694839477539,17.300201416015625,0.9482704277576472 +-4.011279106140137,-24.066015243530273,17.76643180847168,0.9908702922067926 +-3.9650044441223145,-24.032812118530273,18.49321746826172,1.0945133050949063 +-3.9254281520843506,-24.00376319885254,19.117822647094727,1.1659295351964067 +-3.87762188911438,-23.96784210205078,19.87916374206543,1.253387740723418 +-3.8314595222473145,-23.932201385498047,20.617605209350586,1.320427195601519 +-3.7834889888763428,-23.894168853759766,21.391284942626953,1.3797947315232757 +-3.7361810207366943,-23.855541229248047,22.164928436279297,1.4040681675599869 +-3.6990480422973633,-23.824430465698242,22.77889060974121,1.407691767835983 +-3.669435977935791,-23.79910659790039,23.2728214263916,1.404365456123347 +-3.6368696689605713,-23.770727157592773,23.82063865661621,1.3963252878635617 +-3.601956605911255,-23.739675521850586,24.413450241088867,1.3841128032049999 +-3.55788254737854,-23.69950294494629,25.170387268066406,1.3650914827179048 +-3.5119001865386963,-23.656400680541992,25.97091293334961,1.342428160611091 +-3.486140012741089,-23.631715774536133,26.424253463745117,1.32887510758311 +-3.4566895961761475,-23.602994918823242,26.94719123840332,1.3128265484601964 +-3.414307117462158,-23.560697555541992,27.70880126953125,1.2889251012766874 +-3.3730409145355225,-23.518388748168945,28.46101188659668,1.2649488435913543 +-3.332616090774536,-23.475826263427734,29.208602905273438,1.2409229279088676 +-3.29794979095459,-23.43840980529785,29.858600616455078,1.2199441472596821 +-3.270341634750366,-23.40797996520996,30.38250732421875,1.2030047743008878 +-3.2335665225982666,-23.36653709411621,31.089353561401367,1.1801292136849897 +-3.21297550201416,-23.342872619628906,31.49166488647461,1.1608116380480886 +-3.1892569065093994,-23.31521987915039,31.960615158081055,1.1473900130636898 +-3.154810667037964,-23.27424430847168,32.64946365356445,1.1469617156340117 +-3.120418071746826,-23.23237419128418,33.344696044921875,1.1608960850366852 +-3.088843584060669,-23.193078994750977,33.990501403808594,1.1817691204208185 +-3.0541090965270996,-23.148847579956055,34.709991455078125,1.2261425417341274 +-3.0189571380615234,-23.102941513061523,35.44393539428711,1.28147585376406 +-2.9831936359405518,-23.055110931396484,36.20430374145508,1.3411492262023297 +-2.9470207691192627,-23.005407333374023,36.980934143066406,1.4238991470311777 +-2.908925771713257,-22.95156478881836,37.812740325927734,1.5095341402908509 +-2.881671905517578,-22.911945343017578,38.41931915283203,1.5683857745753056 +-2.852468252182007,-22.86847686767578,39.079994201660156,1.6301339382100748 +-2.8124094009399414,-22.80765151977539,39.995361328125,1.7121731631474006 +-2.7828402519226074,-22.76133918762207,40.685604095458984,1.7712069957766217 +-2.752983331680298,-22.713680267333984,41.390743255615234,1.8311541234213466 +-2.7095179557800293,-22.641204833984375,42.4504280090332,1.9148952657994887 +-2.6649584770202637,-22.563722610473633,43.57107162475586,1.9968596590734966 +-2.633824110031128,-22.50762939453125,44.37356185913086,2.0545877619852972 +-2.6019914150238037,-22.448415756225586,45.21323776245117,2.112445695659081 +-2.5550568103790283,-22.357324600219727,46.491249084472656,2.197416962542892 +-2.509166955947876,-22.26337432861328,47.79167938232422,2.2791472038250586 +-2.4679901599884033,-22.17437744140625,49.009422302246094,2.3518941731087293 +-2.423865795135498,-22.073348999023438,50.376583099365234,2.4298594722355484 +-2.379270553588867,-21.964330673217773,51.83530807495117,2.507326851123148 +-2.337891101837158,-21.85563850402832,53.27362823486328,2.5614116065395858 +-2.297539710998535,-21.74085807800293,54.77773666381836,2.573599485591793 +-2.266965389251709,-21.64668846130371,56.002010345458984,2.561687689048797 +-2.2332723140716553,-21.533649444580078,57.4618034362793,2.532987047335472 +-2.2020044326782227,-21.41777801513672,58.94868850708008,2.4943610812259385 +-2.1741549968719482,-21.30256462097168,60.4189338684082,2.4509534537522275 +-2.150092363357544,-21.190265655517578,61.84546661376953,2.406078300241175 +-2.1310155391693115,-21.08942413330078,63.121421813964844,2.3646429840625514 +-2.112812042236328,-20.9786319732666,64.51901245117188,2.3184872780802053 +-2.098621368408203,-20.87718391418457,65.79547119140625,2.275940726105729 +-2.0862998962402344,-20.771060943603516,67.12818145751953,2.2313274488040804 +-2.0772202014923096,-20.673330307006836,68.35344696044922,2.190219859449523 +-2.070361375808716,-20.57660675048828,69.5650405883789,2.1495478732678395 +-2.0653574466705322,-20.473161697387695,70.8600845336914,2.106076684046238 +-2.062814235687256,-20.37400245666504,72.10147094726562,2.0644323548548322 +-2.062396764755249,-20.28720474243164,73.1885757446289,2.0279919123439254 +-2.063904047012329,-20.191394805908203,74.38970184326172,1.987765046215872 +-2.0671496391296387,-20.102535247802734,75.50519561767578,1.9504428612871756 +-2.0720486640930176,-20.015583038330078,76.5985107421875,1.9138940470630241 +-2.078853130340576,-19.92639923095703,77.72201538085938,1.876364772620355 +-2.086820363998413,-19.84333038330078,78.77113342285156,1.841357006561003 +-2.0961742401123047,-19.761821746826172,79.80332946777344,1.806944742294165 +-2.1072280406951904,-19.679046630859375,80.85469055175781,1.771946938398931 +-2.1181182861328125,-19.60718536376953,81.77053833007812,1.7415014281560173 +-2.1324124336242676,-19.52301025390625,82.84709930419922,1.705739383905645 +-2.145800828933716,-19.451868057250977,83.76063537597656,1.6754207656276978 +-2.161036729812622,-19.377727508544922,84.71650695800781,1.6437293715948957 +-2.1770904064178467,-19.305788040161133,85.64805603027344,1.6129038756211438 +-2.1953635215759277,-19.230022430419922,86.63369750976562,1.5803123066987896 +-2.2117528915405273,-19.16661262512207,87.46246337890625,1.552928293333408 +-2.230649709701538,-19.097881317138672,88.36492156982422,1.5231267879490027 +-2.2503128051757812,-19.030603408813477,89.25309753417969,1.4938255354763326 +-2.2693939208984375,-18.96883773803711,90.07270812988281,1.466799021026977 +-2.2888996601104736,-18.90877342224121,90.87361907958984,1.4403998930282618 +-2.310438871383667,-18.845623016357422,91.72030639648438,1.4125081243858124 +-2.33140230178833,-18.786968231201172,92.51113891601562,1.3864707209235803 +-2.3546721935272217,-18.72473907470703,93.3552017211914,1.358698450618464 +-2.3772642612457275,-18.66689682006836,94.14472198486328,1.3327400869676784 +-2.399667501449585,-18.611797332763672,94.9013671875,1.3078743010930431 +-2.42289400100708,-18.55681037902832,95.66127014160156,1.282917766237516 +-2.4444966316223145,-18.507450103759766,96.34742736816406,1.2603903266001468 +-2.469700813293457,-18.451841354370117,97.12540435791016,1.234862808146576 +-2.492887496948242,-18.402427673339844,97.82111358642578,1.2120363427266538 +-2.517158031463623,-18.352336883544922,98.5309066772461,1.1887596481343887 +-2.541818141937256,-18.30303192138672,99.2386245727539,1.1479075174929478 +-2.5653414726257324,-18.257492065429688,99.90403747558594,1.082029781257738 +-2.5854573249816895,-18.221067428588867,100.56718444824219,0.8009935637806247 +-2.5965607166290283,-18.20205307006836,101.0010986328125,0.02672411570930518 +-2.596381425857544,-18.202116012573242,101.00198364257812,4.585116598732261e-05 +-2.5964279174804688,-18.202096939086914,101.00235748291016,0.00014515241560084091 +-2.5965023040771484,-18.202054977416992,101.00255584716797,0.00016523696847055302 +-2.5965781211853027,-18.202007293701172,101.00287628173828,0.00014523457773457405 +-2.5966391563415527,-18.20196533203125,101.00326538085938,0.00011588096842682962 +-2.5966830253601074,-18.201934814453125,101.00365447998047,9.083486113222199e-05 +-2.596714496612549,-18.20191192626953,101.00411224365234,7.164638434815669e-05 +-2.5967400074005127,-18.201894760131836,101.0045394897461,5.570104488287569e-05 +-2.5967628955841064,-18.201879501342773,101.00471496582031,4.263354303447835e-05 +-2.5967812538146973,-18.201868057250977,101.00471496582031,3.2566344758867335e-05 +-2.5967941284179688,-18.201860427856445,101.00472259521484,2.5420999380241476e-05 +-2.5968010425567627,-18.201854705810547,101.00472259521484,1.997774940357499e-05 +-2.5968050956726074,-18.20185089111328,101.00472259521484,1.5788675780456627e-05 +-2.5968081951141357,-18.201847076416016,101.00472259521484,1.3089197633688384e-05 +-2.5968096256256104,-18.20184326171875,101.00472259521484,1.2975229610491362e-05 +-2.596811056137085,-18.20184326171875,101.00472259521484,4.803336883225854e-05 +-2.596811056137085,-18.201841354370117,101.00472259521484,0.00010015825683900331 +-2.596810817718506,-18.201841354370117,101.00472259521484,0.00016397812239764623 +-2.5968081951141357,-18.20184898376465,101.00472259521484,0.0002424237113118679 +-2.5968034267425537,-18.201862335205078,101.00472259521484,0.0003158802579941619 +-2.5967965126037598,-18.20187759399414,101.00472259521484,0.00038529348381010465 +-2.596794366836548,-18.201881408691406,101.00472259521484,5.553415092390778e-06 +-2.596794605255127,-18.201881408691406,101.00472259521484,5.816224105697244e-06 +-2.596795082092285,-18.201879501342773,101.00472259521484,5.682550651241081e-06 +-2.596795082092285,-18.201879501342773,101.00472259521484,5.615760506894106e-06 +-2.596795082092285,-18.201879501342773,101.00472259521484,5.213304005025019e-06 +-2.596795082092285,-18.201879501342773,101.00472259521484,5.5940284199372005e-06 +-2.5967953205108643,-18.201879501342773,101.00472259521484,3.7596410044632678e-06 +-2.5967953205108643,-18.201879501342773,101.00472259521484,5.243846390518963e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.791841384178032e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.8073807195344885e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.31783159655117e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.284830604245278e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.748194749469451e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.156511794354102e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.2646596670885845e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,6.017773276566146e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.533300297986701e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.1973309969322466e-06 +-2.5967955589294434,-18.201879501342773,101.00472259521484,5.5426546251843495e-06 +-2.5967957973480225,-18.201879501342773,101.00472259521484,5.404817323438438e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.456097469272238e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,4.511478864497865e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,3.7283439364015246e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.628114740089708e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.639391046307148e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.677872964327552e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.385711280413698e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.320913464401972e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.5359918565730035e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.684192167807087e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.422018685153872e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.540390517963413e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.417968346297113e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.776585238526216e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.6689406756151775e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,5.603130864570978e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,4.111688781278402e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,4.488410148227468e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,4.9827014163405325e-06 +-2.5967962741851807,-18.201879501342773,101.00472259521484,1.1296502183964957e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,5.0671498990393066e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,5.3288441733387045e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.854621322437129e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,5.083172083111576e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,5.00066789166987e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,5.1766930410043745e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.797691189532892e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,5.0328103987772986e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.735170360783567e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.7226445736717735e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.579486245767869e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.8734931697657425e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.683107778360544e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.639731225469541e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.395119194065304e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.490312119601073e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.4400919342609275e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.3352726836114036e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.401406461460473e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,3.818210642329752e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,3.493900048448177e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.7053661461097624e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.677259435775e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.1858760166908725e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.402195116424136e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,3.7873883400286776e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.418067683009556e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.395533009727135e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.5826918003783765e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.509043657451451e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,3.984856348354438e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.4366672058798095e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.419960226834836e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,3.855669491085617e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.34466329817339e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,3.7109440604579806e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.087503274368476e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.656905502716735e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.274245602028088e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.364138359826524e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,3.7870225685321997e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.048593918403659e-06 +2.189079761505127,-13.853877067565918,56.94373321533203,4.491496256297945e-06 +2.1891114711761475,-13.853882789611816,56.94192886352539,0.002863909156307528 +2.189194917678833,-13.853839874267578,56.94043731689453,0.005584413731475867 +2.189117908477783,-13.853925704956055,56.93981170654297,0.013473001681847738 +2.1886508464813232,-13.85444450378418,56.944358825683594,0.026020863247383216 +2.1877968311309814,-13.855388641357422,56.9551887512207,0.04454302789980634 +2.1852867603302,-13.858107566833496,56.98361587524414,0.12013932038838791 +2.1792819499969482,-13.864506721496582,57.04991912841797,0.24010910158053128 +2.1708617210388184,-13.873363494873047,57.13610076904297,0.29506667436948447 +2.1584243774414062,-13.886462211608887,57.279415130615234,0.5092309692581859 +2.1404597759246826,-13.90553092956543,57.48110580444336,0.6149345698599051 +2.1176512241363525,-13.929794311523438,57.73978042602539,0.7711501312901411 +2.0896193981170654,-13.959731101989746,58.06068801879883,0.9140269731495072 +2.06125807762146,-13.990144729614258,58.39129638671875,1.0340758813895847 +2.025339365005493,-14.028926849365234,58.81960678100586,1.2097238137608868 +1.9877619743347168,-14.069771766662598,59.27252960205078,1.332107045154559 +1.9437257051467896,-14.118122100830078,59.83196258544922,1.3365946777110762 +1.9011762142181396,-14.165472030639648,60.38022232055664,1.4283704733128444 +1.8492153882980347,-14.22442626953125,61.06126022338867,1.6467044170452387 +1.8002736568450928,-14.281147956848145,61.706260681152344,1.7834741096924214 +1.7440223693847656,-14.347881317138672,62.45569610595703,1.8921012243768423 +1.6855101585388184,-14.418865203857422,63.25331115722656,1.9808996621318717 +1.6260180473327637,-14.492429733276367,64.0909652709961,2.0504576675432187 +1.5706278085708618,-14.562274932861328,64.89522552490234,2.105711259202039 +1.5080944299697876,-14.64317512512207,65.82567596435547,2.1635168539570784 +1.446678638458252,-14.725370407104492,66.7559585571289,2.2082435413202917 +1.387412667274475,-14.807356834411621,67.67292785644531,2.217869879527454 +1.3287092447280884,-14.891101837158203,68.60369110107422,2.1732726669552713 +1.2778544425964355,-14.965794563293457,69.4306411743164,2.0910302312735745 +1.2215681076049805,-15.050942420959473,70.37242889404297,1.9640868187212372 +1.1745599508285522,-15.124422073364258,71.17843627929688,1.839708364289974 +1.1321346759796143,-15.192959785461426,71.91974639892578,1.717094748015088 +1.0913127660751343,-15.261235237121582,72.64468383789062,1.59181131258451 +1.0559669733047485,-15.322502136230469,73.27991485595703,1.4782360762810425 +1.0250581502914429,-15.3779296875,73.84066009521484,1.3751059069088372 +0.9971789121627808,-15.429336547851562,74.35317993164062,1.2789983785535375 +0.9699601531028748,-15.48071575164795,74.86195373535156,1.1832688145570374 +0.9468013048171997,-15.525484085083008,75.30073547363281,1.1003128701982356 +0.9242638945579529,-15.570099830627441,75.7320785522461,1.0180986355019455 +0.904904842376709,-15.609346389770508,76.1058578491211,0.9460736641532357 +0.8859079480171204,-15.648683547973633,76.47612762451172,0.8740298713346024 +0.8693163990974426,-15.68370246887207,76.80293273925781,0.8100979321772677 +0.8544169664382935,-15.715670585632324,77.09928894042969,0.751924039064184 +0.8400433659553528,-15.7470121383667,77.3870849609375,0.6725276005240838 +0.8289165496826172,-15.771310806274414,77.60395812988281,0.5699074985137335 +0.8192115426063538,-15.792919158935547,77.80103302001953,0.5050045970133361 +0.8099952340126038,-15.813703536987305,77.98629760742188,0.4567460633177682 +0.8018728494644165,-15.832315444946289,78.1525650024414,0.4427320207485868 +0.7930487394332886,-15.852967262268066,78.3349609375,0.5235488932778611 +0.7825614809989929,-15.878324508666992,78.55513763427734,0.6740217602658564 +0.7695414423942566,-15.91008472442627,78.82259368896484,0.7684002110147801 +0.7540002465248108,-15.948413848876953,79.15374755859375,0.8963323472269824 +0.7371523976325989,-15.990154266357422,79.52354431152344,0.9632961258240501 +0.7200042605400085,-16.032936096191406,79.9018325805664,1.082891371213356 +0.6991947889328003,-16.08553123474121,80.37346649169922,1.2044597772874481 +0.678016185760498,-16.140010833740234,80.86486053466797,1.3164912486731735 +0.6571347117424011,-16.19507598876953,81.3582763671875,1.3924100651769413 +0.6337601542472839,-16.258342742919922,81.9229736328125,1.4853664550589887 +0.6101722121238708,-16.32370376586914,82.51142883300781,1.5677155394990074 +0.5851799249649048,-16.394697189331055,83.15603637695312,1.6385348280908836 +0.5601892471313477,-16.467662811279297,83.826904296875,1.7072020189011718 +0.5347976088523865,-16.54450225830078,84.53282165527344,1.7671543371007887 +0.50916987657547,-16.625225067138672,85.27328491210938,1.8054687415774449 +0.48532459139823914,-16.703439712524414,85.99240112304688,1.800387621676884 +0.46266382932662964,-16.780866622924805,86.70420837402344,1.7490798532313445 +0.44101816415786743,-16.85797119140625,87.4141845703125,1.6603670938117092 +0.4218398332595825,-16.929494857788086,88.0713882446289,1.5604388966578837 +0.40507254004478455,-16.995113372802734,88.6707763671875,1.4601568752594953 +0.38904139399528503,-17.06092071533203,89.26929473876953,1.3546722995856948 +0.3756273090839386,-17.1187744140625,89.79188537597656,1.2599559509091414 +0.36366933584213257,-17.173229217529297,90.2764892578125,1.1699127867318913 +0.35265207290649414,-17.226337432861328,90.7413330078125,1.081515313955513 +0.3439134657382965,-17.270566940307617,91.1270523071289,0.9725018284507818 +0.33545997738838196,-17.3148250579834,91.5220718383789,0.8538767082731359 +0.3284520208835602,-17.35297966003418,91.86164855957031,0.7588464360403332 +0.3226671516895294,-17.38574981689453,92.14458465576172,0.7001757445721519 +0.31776678562164307,-17.415189743041992,92.39942932128906,0.661611183743101 +0.3128455579280853,-17.44595718383789,92.65534210205078,0.6290547301230213 +0.30855998396873474,-17.473743438720703,92.8876953125,0.6067642107964668 +0.3045179843902588,-17.500391006469727,93.10745239257812,0.6009686698686958 +0.30030837655067444,-17.529401779174805,93.35088348388672,0.6001469564992825 +0.29631853103637695,-17.558130264282227,93.58869171142578,0.604970051424642 +0.29243144392967224,-17.587308883666992,93.8299789428711,0.6098027123568118 +0.28898343443870544,-17.614116668701172,94.0555419921875,0.6121445066008498 +0.28547587990760803,-17.641813278198242,94.28347778320312,0.6208352710597628 +0.2818238437175751,-17.671709060668945,94.52962493896484,0.6302198563087004 +0.27834373712539673,-17.70132064819336,94.77264404296875,0.6464121457450551 +0.2749297022819519,-17.73140525817871,95.0190200805664,0.6394568355506253 +0.2720640301704407,-17.757139205932617,95.22673034667969,0.6282005869883089 +0.2688009738922119,-17.78845977783203,95.48974609375,0.6389743432247998 +0.2659030258655548,-17.817798614501953,95.7361068725586,0.6632550332718115 +0.26278921961784363,-17.850032806396484,95.99772644042969,0.6763406090627415 +0.2598857581615448,-17.88138198852539,96.25296783447266,0.6910069495651094 +0.2572280466556549,-17.911405563354492,96.49882507324219,0.676802355345671 +0.2547798156738281,-17.940059661865234,96.7332534790039,0.6523441344368304 +0.25220412015914917,-17.970483779907227,96.9871826171875,0.6323608057936261 +0.24972003698349,-18.001197814941406,97.2443618774414,0.6103758509317393 +0.24775078892707825,-18.027618408203125,97.46243286132812,0.5879904850109061 +0.24592778086662292,-18.05422019958496,97.67735290527344,0.5685876737083763 +0.244394451379776,-18.07770347595215,97.86798858642578,0.5276627497099886 +0.2429446578025818,-18.101444244384766,98.06059265136719,0.4917207743786686 +0.2415933907032013,-18.1251163482666,98.25099182128906,0.5034976990916653 +0.2402815967798233,-18.149137496948242,98.44600677490234,0.48075316448617866 +0.2392144352197647,-18.16987419128418,98.6142349243164,0.46329096035346523 +0.23827779293060303,-18.189844131469727,98.77509307861328,0.4479918444349174 +0.23736163973808289,-18.21078872680664,98.94348907470703,0.4304625215174498 +0.23653003573417664,-18.231143951416016,99.10714721679688,0.43604319868524694 +0.23576323688030243,-18.25166893005371,99.27285766601562,0.4368848561326136 +0.23506198823451996,-18.271198272705078,99.43091583251953,0.42170960965579346 +0.23446065187454224,-18.291019439697266,99.58758544921875,0.403768024533261 +0.23395077884197235,-18.307382583618164,99.71994018554688,0.3992868743251822 +0.23332998156547546,-18.32761001586914,99.88492584228516,0.37452746753427607 +0.2329031378030777,-18.344575881958008,100.01973724365234,0.34592959699273373 +0.23252910375595093,-18.359477996826172,100.13964080810547,0.3139218156712257 +0.23214806616306305,-18.37356185913086,100.25432586669922,0.28766348225800875 +0.23187099397182465,-18.38532257080078,100.34789276123047,0.24049989585645384 +0.231729656457901,-18.39605712890625,100.43515014648438,0.2360324332300591 +0.23165282607078552,-18.406164169311523,100.51150512695312,0.19598234894502267 +0.23169316351413727,-18.414663314819336,100.57139587402344,0.1681019864797315 +0.23184390366077423,-18.421472549438477,100.6156234741211,0.1470154539796925 +0.23205344378948212,-18.427824020385742,100.65702056884766,0.1331934639100293 +0.2322811782360077,-18.434059143066406,100.69005584716797,0.12453193471524575 +0.2325970083475113,-18.43975257873535,100.72347259521484,0.12025065694814661 +0.23290793597698212,-18.44465446472168,100.74989318847656,0.10074347640934807 +0.2331896722316742,-18.448532104492188,100.76702880859375,0.07470118560525947 +0.23350010812282562,-18.452592849731445,100.78430938720703,0.07083687666416698 +0.2337767481803894,-18.45583152770996,100.79939270019531,0.07761238059357663 +0.23410457372665405,-18.459030151367188,100.8227767944336,0.08911746856469759 +0.2346455156803131,-18.464736938476562,100.84112548828125,0.0800954614097433 +0.2350386381149292,-18.468212127685547,100.85140991210938,0.07623029342895662 +0.2355613112449646,-18.472633361816406,100.86489868164062,0.11109079885876047 +0.23627331852912903,-18.47829246520996,100.88023376464844,0.12413731584116748 +0.23703235387802124,-18.483930587768555,100.89347839355469,0.12557408804467057 +0.23789510130882263,-18.489933013916016,100.90531158447266,0.12149454378444857 +0.23860009014606476,-18.49456787109375,100.91327667236328,0.09230022259609329 +0.2391251176595688,-18.497840881347656,100.9179916381836,0.05202236464500235 +0.2394377887248993,-18.499643325805664,100.91974639892578,0.030720315487930156 +0.23963581025600433,-18.50067138671875,100.91986083984375,0.01920108554050445 +0.23978053033351898,-18.50138282775879,100.91986083984375,0.011986267366156782 +0.23987729847431183,-18.501811981201172,100.91986083984375,0.008254194053560149 +0.23995117843151093,-18.502111434936523,100.91986083984375,0.006109032342880476 +0.24001960456371307,-18.502363204956055,100.91986083984375,0.004728177281520088 +0.24007879197597504,-18.502565383911133,100.91986083984375,0.003947463338589139 +0.24011053144931793,-18.502660751342773,100.92021942138672,0.018292562815441667 +0.2402014434337616,-18.502962112426758,100.91911315917969,0.03537186193967045 +0.2405046671628952,-18.50401496887207,100.91519165039062,0.0028299325607354076 +0.2407665252685547,-18.50490951538086,100.91199493408203,0.03397899593070606 +0.24102255702018738,-18.505775451660156,100.90882873535156,0.031631643229256566 +0.24113261699676514,-18.506132125854492,100.90782165527344,0.012413698837228015 +0.24121470749378204,-18.506391525268555,100.90690612792969,0.006189202354105854 +0.24105204641819,-18.505855560302734,100.90972137451172,0.018858287929714192 +0.2406933754682541,-18.50473403930664,100.91602325439453,0.027297866017963697 +0.24044065177440643,-18.503984451293945,100.92012023925781,0.01074253013186811 +0.24044664204120636,-18.504011154174805,100.92012023925781,0.014410458432839807 +0.24024997651576996,-18.50345802307129,100.92501831054688,0.04573609624969775 +0.2398354858160019,-18.5023250579834,100.93363189697266,0.004644894925528339 +0.23936991393566132,-18.501121520996094,100.94371795654297,0.011928192644051518 +0.2384648621082306,-18.498828887939453,100.96420288085938,0.07404067401894886 +0.237238347530365,-18.49574089050293,100.99099731445312,0.0620040242007357 +0.23571833968162537,-18.491872787475586,101.02529907226562,0.11096498543171435 +0.23375312983989716,-18.486780166625977,101.0696029663086,0.12434604166820652 +0.23110723495483398,-18.479948043823242,101.12337493896484,0.16477075047889375 +0.22768205404281616,-18.471281051635742,101.19359588623047,0.20326474616516674 +0.2235380858182907,-18.46068572998047,101.2822036743164,0.2785190647567225 +0.21849052608013153,-18.447933197021484,101.38459014892578,0.31206071690848985 +0.21282054483890533,-18.433740615844727,101.5025405883789,0.3748796144840197 +0.20563946664333344,-18.41559600830078,101.6472396850586,0.4172670685872013 +0.19831448793411255,-18.397188186645508,101.79501342773438,0.46990308731846 +0.1895420402288437,-18.37526512145996,101.96681213378906,0.5384424716145162 +0.1800842434167862,-18.351913452148438,102.14259338378906,0.5889539039257651 +0.1681460589170456,-18.322574615478516,102.37442779541016,0.6935200554846839 +0.15580198168754578,-18.292381286621094,102.61042785644531,0.7430099527104169 +0.14176566898822784,-18.258378982543945,102.87450408935547,0.831918840472541 +0.1259663701057434,-18.220500946044922,103.16747283935547,0.9014554128344849 +0.10989044606685638,-18.18236541748047,103.45903778076172,0.9356732315980355 +0.09205857664346695,-18.14042854309082,103.7765121459961,1.0151842657571728 +0.07378892600536346,-18.097881317138672,104.09430694580078,1.0493311541138504 +0.05270740017294884,-18.04933738708496,104.45366668701172,1.0948987623719217 +0.031187361106276512,-18.000547409057617,104.81439971923828,1.1198408730717098 +0.00967964343726635,-17.952640533447266,105.17005157470703,1.1366406283530381 +-0.01230579987168312,-17.90440559387207,105.525634765625,1.138119992579537 +-0.03347209468483925,-17.858531951904297,105.8611831665039,1.129710739757031 +-0.055827412754297256,-17.810792922973633,106.21051025390625,1.1149574874442763 +-0.07869431376457214,-17.762821197509766,106.56422424316406,1.0966804648554054 +-0.10037104040384293,-17.71807861328125,106.895751953125,1.0779464725054082 +-0.12168591469526291,-17.674707412719727,107.21768188476562,1.0587951897400942 +-0.14385822415351868,-17.63027000427246,107.54914093017578,1.038420959694967 +-0.16542987525463104,-17.58780860900879,107.87022399902344,1.0184105585798093 +-0.18797914683818817,-17.544246673583984,108.2045669555664,0.9977033866620952 +-0.20871397852897644,-17.504777908325195,108.50892639160156,0.9790497433602672 +-0.23007048666477203,-17.464582443237305,108.81816864013672,0.9599664943675448 +-0.25105419754981995,-17.425569534301758,109.1186752319336,0.9412314423244398 +-0.272225022315979,-17.386730194091797,109.41936492919922,0.9225127229019069 +-0.29231756925582886,-17.350324630737305,109.70207977294922,0.9049233942059889 +-0.312357634305954,-17.31446075439453,109.9820327758789,0.8874477158027639 +-0.332573801279068,-17.27880859375,110.2637710571289,0.8698632192186125 +-0.34978678822517395,-17.248903274536133,110.50347900390625,0.8550885508902168 +-0.3709312677383423,-17.212614059448242,110.79612731933594,0.8373469565404716 +-0.3907105028629303,-17.179006576538086,111.06669616699219,0.8209196387944181 +-0.4101148545742035,-17.1463565826416,111.32965850830078,0.8048262585167116 +-0.4291190207004547,-17.114721298217773,111.58550262451172,0.7891672645065932 +-0.4482375979423523,-17.08322525024414,111.84107208251953,0.7735490130466812 +-0.4658708870410919,-17.05445671081543,112.07514953613281,0.7592437182130476 +-0.48419955372810364,-17.024852752685547,112.31703186035156,0.7444044704936403 +-0.5035783648490906,-16.99395179748535,112.5726318359375,0.728734934833392 +-0.5215250849723816,-16.965723037719727,112.80948638916016,0.7144150148726313 +-0.538915753364563,-16.93863296508789,113.03768157958984,0.7008099880969356 +-0.5557948350906372,-16.91253662109375,113.25712585449219,0.6876737109853968 +-0.5732151865959167,-16.885879516601562,113.48173522949219,0.5637708952264302 +-0.5837299823760986,-16.870132446289062,113.61544799804688,0.3007256581367698 +-0.589324414730072,-16.861736297607422,113.68672943115234,0.15861534751558481 +-0.5922040343284607,-16.857349395751953,113.72310638427734,0.08659209378432998 +-0.5938267707824707,-16.854909896850586,113.74333953857422,0.04945201826498663 +-0.5947742462158203,-16.85348892211914,113.7546157836914,0.02929376798611222 +-0.595363974571228,-16.852598190307617,113.76092529296875,0.016541550325447945 +-0.5957053899765015,-16.852079391479492,113.76408386230469,0.009033004821261084 +-0.5958812832832336,-16.851810455322266,113.76513671875,0.00513883310659522 +-0.5961135625839233,-16.851390838623047,113.77085876464844,0.025457784105927098 +-0.5963252186775208,-16.851011276245117,113.77194213867188,0.0035528329147547404 +-0.5963432192802429,-16.851001739501953,113.76773834228516,0.010995540605759893 +-0.5961608290672302,-16.851337432861328,113.76526641845703,0.0066728815869473565 +-0.5959476828575134,-16.8516902923584,113.762939453125,0.011506218379269696 +-0.5957157015800476,-16.85210609436035,113.76080322265625,0.011400204004266163 +-0.5954151153564453,-16.852664947509766,113.75823211669922,0.015245633561210782 +-0.5950542688369751,-16.853374481201172,113.7561264038086,0.014630231641093209 +-0.5946982502937317,-16.854108810424805,113.7547378540039,0.02270285935189324 +-0.594182014465332,-16.855205535888672,113.75360870361328,0.03164563226280409 +-0.5935704708099365,-16.856550216674805,113.75326538085938,0.03399229175359154 +-0.5929532051086426,-16.85795783996582,113.75336456298828,0.0320263591324051 +-0.5923558473587036,-16.85936164855957,113.7542724609375,0.030648505660828784 +-0.5914074778556824,-16.86173439025879,113.7567367553711,0.07899273118328855 +-0.5903796553611755,-16.864337921142578,113.7618179321289,0.04883671783367895 +-0.5893632173538208,-16.867074966430664,113.76863861083984,0.062174906940742895 +-0.5880488753318787,-16.87063980102539,113.77871704101562,0.07536262843661393 +-0.5868416428565979,-16.87409782409668,113.79006958007812,0.10053541027909399 +-0.5854660868644714,-16.878217697143555,113.80692291259766,0.08271978934448243 +-0.5843152403831482,-16.881805419921875,113.82284545898438,0.07194321183630466 +-0.5833255052566528,-16.88503074645996,113.84144592285156,0.08875845066772833 +-0.5821075439453125,-16.889097213745117,113.8563003540039,0.10743159911649844 +-0.5806356072425842,-16.894136428833008,113.88985443115234,0.12250488039731718 +-0.5786349773406982,-16.9012451171875,113.93053436279297,0.1875277894405833 +-0.5761619210243225,-16.910491943359375,113.98770904541016,0.2247987085564283 +-0.5737714171409607,-16.920196533203125,114.05738830566406,0.21398332316301683 +-0.5708259344100952,-16.93305206298828,114.16234588623047,0.21574707269138615 +-0.5670666098594666,-16.94924545288086,114.28689575195312,0.3623874013239148 +-0.559884786605835,-16.97879981994629,114.52090454101562,0.5835233306513945 +-0.553240954875946,-17.005535125732422,114.73005676269531,0.7140994159904105 +-0.5452684164047241,-17.037342071533203,114.98017883300781,0.7368468091062239 +-0.5359510183334351,-17.074125289916992,115.27445983886719,0.8182008332305987 +-0.5259250402450562,-17.11372184753418,115.59956359863281,0.8993310452114088 +-0.5146079063415527,-17.158069610595703,115.9706802368164,1.0108739260193538 +-0.5026611089706421,-17.203866958618164,116.35540771484375,1.0981930769501447 +-0.4882776141166687,-17.257394790649414,116.8050765991211,1.1724352412496541 +-0.47349196672439575,-17.310976028442383,117.25871276855469,1.2056368646592293 +-0.4586406946182251,-17.363523483276367,117.70970153808594,1.194964292295873 +-0.4432111978530884,-17.416715621948242,118.16830444335938,1.1461353772600347 +-0.42860156297683716,-17.465648651123047,118.59030151367188,1.0830345276742364 +-0.41558340191841125,-17.5081844329834,118.95825958251953,1.0199156374610348 +-0.40136563777923584,-17.553607940673828,119.35286712646484,0.9475549150084989 +-0.3878924548625946,-17.595653533935547,119.71882629394531,0.8779069470436666 +-0.3760599195957184,-17.63166046142578,120.03111267089844,0.8169877004962482 +-0.3642628490924835,-17.666728973388672,120.33366394042969,0.7568763397693116 +-0.3527168333530426,-17.70037269592285,120.6237564086914,0.6985994436111082 +-0.3425373136997223,-17.729503631591797,120.87450408935547,0.648006294570408 +-0.33322659134864807,-17.75570297241211,121.09938049316406,0.6023234475398769 +-0.3242609202861786,-17.780616760253906,121.31365966796875,0.5586957729612839 +-0.31526079773902893,-17.805343627929688,121.52680206298828,0.5154275264673862 +-0.30760225653648376,-17.826080322265625,121.70474243164062,0.47917816413076453 +-0.29994267225265503,-17.846508026123047,121.87895202636719,0.44333609976199373 +-0.2933644652366638,-17.863882064819336,122.02701568603516,0.4127180758535801 +-0.28664839267730713,-17.88152503967285,122.17823791503906,0.3816071030125622 +-0.28068047761917114,-17.897098541259766,122.31195831298828,0.3542189564877644 +-0.27485430240631104,-17.91213035583496,122.44031524658203,0.3278265392775743 +-0.2694650888442993,-17.925857543945312,122.55646514892578,0.3036303341455258 +-0.2645798921585083,-17.938215255737305,122.66104888916016,0.2817433369347587 +-0.25996679067611694,-17.949851989746094,122.75995635986328,0.26111551342360023 +-0.2557975947856903,-17.960336685180664,122.84942626953125,0.24257101198593334 +-0.2517679035663605,-17.970415115356445,122.93551635742188,0.2247499750065448 +-0.24804003536701202,-17.97969627380371,123.01467895507812,0.2083060870176267 +-0.24465249478816986,-17.98809051513672,123.08639526367188,0.19345449169354254 +-0.24162232875823975,-17.995548248291016,123.1496810913086,0.1792712727633146 +-0.23860642313957214,-18.00290298461914,123.21168518066406,0.14604358354767547 +-0.2367301881313324,-18.007450103759766,123.25028991699219,0.09283013606391169 +-0.23537902534008026,-18.01071548461914,123.2781982421875,0.05819550229093452 +-0.23454000055789948,-18.01272964477539,123.29508209228516,0.03982728569497296 +-0.2339494526386261,-18.01414680480957,123.30706787109375,0.029582341290416966 +-0.23349221050739288,-18.01523208618164,123.31597137451172,0.023771793364027734 +-0.23307698965072632,-18.016191482543945,123.3235092163086,0.019999986877932065 +-0.23270243406295776,-18.01702880859375,123.32964324951172,0.017592361168824802 +-0.23236499726772308,-18.01776123046875,123.33465576171875,0.01554816006259917 +-0.23208096623420715,-18.01835060119629,123.33826446533203,0.0005515033779604465 +-0.23153917491436005,-18.019407272338867,123.34457397460938,0.040951715578499866 +-0.23130583763122559,-18.01984405517578,123.34648895263672,0.011653967620094916 +-0.23123914003372192,-18.01994514465332,123.34716796875,0.017827870697166952 +-0.23166991770267487,-18.019123077392578,123.34391784667969,0.009068857088639186 +-0.23207873106002808,-18.018369674682617,123.34151458740234,0.046672228986146896 +-0.2328399270772934,-18.017066955566406,123.33602142333984,0.050753817713061644 +-0.23467949032783508,-18.014005661010742,123.32670593261719,0.112250870910505 +-0.23737218976020813,-18.009565353393555,123.32001495361328,0.12057007246761899 +-0.24126070737838745,-18.00334358215332,123.31472778320312,0.1669615782362332 +-0.2460077852010727,-17.995983123779297,123.31068420410156,0.21350154779930547 +-0.2517281770706177,-17.987321853637695,123.31448364257812,0.2332443387891918 +-0.2589775323867798,-17.976593017578125,123.32962036132812,0.29916462328601723 +-0.2674635350704193,-17.964384078979492,123.35525512695312,0.33365999135534324 +-0.2775505781173706,-17.95029067993164,123.39295959472656,0.42127684558452627 +-0.29017317295074463,-17.933130264282227,123.45085144042969,0.48085062326851663 +-0.30378884077072144,-17.91513442993164,123.52356719970703,0.5264466055642842 +-0.3207240700721741,-17.893417358398438,123.62141418457031,0.5942612683835728 +-0.33883532881736755,-17.870908737182617,123.73285675048828,0.6894754058082175 +-0.3606579899787903,-17.84455108642578,123.88290405273438,0.7374731546243377 +-0.38452664017677307,-17.816585540771484,124.06231689453125,0.8396069132817214 +-0.41108226776123047,-17.78638458251953,124.27830505371094,0.9087329979196699 +-0.43985143303871155,-17.754663467407227,124.529296875,0.9666953219536483 +-0.4735313653945923,-17.718748092651367,124.84131622314453,1.0455136928734614 +-0.5105209946632385,-17.68067741394043,125.20293426513672,1.1197802985220053 +-0.5472144484519958,-17.64406967163086,125.5746841430664,1.2010553247261002 +-0.5866000056266785,-17.605392456054688,125.97135925292969,1.257374920186345 +-0.6311222314834595,-17.561832427978516,126.40386199951172,1.3274766609680884 +-0.6775957345962524,-17.51640510559082,126.83417510986328,1.3946343026369807 +-0.7242274284362793,-17.471237182617188,127.25543212890625,1.4574660294091486 +-0.7726039886474609,-17.42511749267578,127.69267272949219,1.5151868481200297 +-0.8294519782066345,-17.37191390991211,128.2052459716797,1.582146644293117 +-0.8819529414176941,-17.323572158813477,128.67770385742188,1.6373560090067922 +-0.9401572346687317,-17.270814895629883,129.190185546875,1.6953633032519608 +-1.0013936758041382,-17.216102600097656,129.72189331054688,1.761432274405576 +-1.0608584880828857,-17.163738250732422,130.2301788330078,1.820129672466499 +-1.1268582344055176,-17.10663414001465,130.78988647460938,1.8777555722639345 +-1.1968642473220825,-17.04731559753418,131.3800811767578,1.9366442729467064 +-1.2671263217926025,-16.9890193939209,131.96807861328125,1.9924527675492791 +-1.3366426229476929,-16.932472229003906,132.54425048828125,2.0445088913286362 +-1.4111156463623047,-16.873119354248047,133.1556854248047,2.097438179199424 +-1.489270806312561,-16.81216812133789,133.7911376953125,2.150204263563312 +-1.5685757398605347,-16.751693725585938,134.429443359375,2.2011744592308764 +-1.6560462713241577,-16.68654441833496,135.1270294189453,2.254720080764775 +-1.7360708713531494,-16.628334045410156,135.7600555419922,2.301488229549725 +-1.8295069932937622,-16.56201171875,136.49195861816406,2.353666342448805 +-1.9189866781234741,-16.5001163482666,137.1858367919922,2.401400865135431 +-2.0146477222442627,-16.435651779174805,137.92054748535156,2.450243491007685 +-2.114715337753296,-16.370046615600586,138.68211364746094,2.4991176540990887 +-2.2107505798339844,-16.308818817138672,139.40676879882812,2.5440599728865183 +-2.3100552558898926,-16.247230529785156,140.1499481201172,2.588688325944324 +-2.413855791091919,-16.1846981048584,140.92022705078125,2.6334831504998553 +-2.5238382816314697,-16.120450973510742,141.72918701171875,2.679037822030307 +-2.6332859992980957,-16.05854034423828,142.5281524658203,2.7223549759748003 +-2.749019145965576,-15.995348930358887,143.37167358398438,2.7658910376714885 +-2.8695085048675537,-15.932099342346191,144.25120544433594,2.8094907431833467 +-2.970249652862549,-15.881068229675293,144.98275756835938,2.8451942886117183 +-3.1014583110809326,-15.816917419433594,145.926513671875,2.8900195216562095 +-3.2186503410339355,-15.76190185546875,146.766357421875,2.928533739222878 +-3.347378969192505,-15.70402717590332,147.68980407714844,2.969595629027028 +-3.472500801086426,-15.650230407714844,148.58465576171875,3.0088663002445895 +-3.596590995788574,-15.599096298217773,149.4651641845703,3.046615648321741 +-3.7289369106292725,-15.547041893005371,150.4016571044922,3.085026121158083 +-3.8608436584472656,-15.497777938842773,151.33663940429688,3.121892352663945 +-4.002601146697998,-15.447668075561523,152.34117126464844,3.1603978323412725 +-4.12624454498291,-15.406343460083008,153.2164306640625,3.1823756450429035 +-4.330793857574463,-15.342928886413574,154.66697692871094,3.1613751448178706 +-4.470893383026123,-15.303062438964844,155.66725158691406,3.1221983554990342 +-4.612610816955566,-15.265666007995605,156.6823272705078,3.072849935072303 +-4.752374649047852,-15.23159408569336,157.68463134765625,3.018460309030053 +-4.891402244567871,-15.200492858886719,158.68467712402344,2.9614209146787216 +-5.027369976043701,-15.1726713180542,159.66168212890625,2.904550615031861 +-5.150953769683838,-15.149516105651855,160.5470428466797,2.852011264502709 +-5.28318977355957,-15.127084732055664,161.49713134765625,2.79487085536041 +-5.414727210998535,-15.10728645324707,162.44932556152344,2.737839930827636 +-5.5371317863464355,-15.091032028198242,163.33790588378906,2.6853438117573702 +-5.651694297790527,-15.077585220336914,164.16685485839844,2.6364900693683695 +-5.776750564575195,-15.06482982635498,165.06927490234375,2.582974011162873 +-5.890501022338867,-15.055034637451172,165.89129638671875,2.5340101514978963 +-6.012244701385498,-15.04658317565918,166.77774047851562,2.4812470964637154 +-6.122711181640625,-15.040788650512695,167.5898895263672,2.433559113059959 +-6.230151653289795,-15.03676700592041,168.38182067871094,2.3877991618540553 +-6.348382472991943,-15.034041404724121,169.2509002685547,2.3376144098437113 +-6.455690860748291,-15.033117294311523,170.0386199951172,2.2438020194743427 +-6.534026145935059,-15.033933639526367,170.6154327392578,1.4320783408782827 +-6.584023952484131,-15.03539752960205,170.98605346679688,0.8299685007088882 +-6.613386154174805,-15.036355972290039,171.20106506347656,0.45295978662589986 +-6.628047466278076,-15.03681468963623,171.30722045898438,0.26530404150499165 +-6.637569427490234,-15.037071228027344,171.3762664794922,0.15315566869996394 +-6.643078327178955,-15.037224769592285,171.41552734375,0.0888700639589975 +-6.6462297439575195,-15.037349700927734,171.43833923339844,0.05127474402027532 +-6.648102283477783,-15.037446022033691,171.4521026611328,0.028819825788068975 +-6.649162292480469,-15.037508964538574,171.45968627929688,0.016065988998598107 +-6.649781227111816,-15.037550926208496,171.46368408203125,0.008276705712417946 +-6.650088310241699,-15.037575721740723,171.46539306640625,0.004237058553865147 +-6.650257587432861,-15.037593841552734,171.46609497070312,0.0017471404547190965 +-6.650299072265625,-15.037599563598633,171.46580505371094,0.008182058212729854 +-6.650764465332031,-15.03760814666748,171.47543334960938,0.03677175222945583 +-6.651347637176514,-15.037614822387695,171.47743225097656,0.012713197506459717 +-6.651697635650635,-15.03764533996582,171.48052978515625,0.006648910280288457 +-6.651766300201416,-15.037676811218262,171.48211669921875,0.003962380627045188 +-6.651284694671631,-15.037694931030273,171.47959899902344,0.01530469050027607 +-6.650415420532227,-15.037630081176758,171.4706573486328,0.024830975358276223 +-6.6489763259887695,-15.03760051727295,171.45620727539062,0.04457526594992505 +-6.6474738121032715,-15.037550926208496,171.44595336914062,0.042851669502263615 +-6.646103382110596,-15.037501335144043,171.43899536132812,0.028714769869276468 +-6.643116474151611,-15.03750228881836,171.41603088378906,0.08646929651555532 +-6.638607501983643,-15.03738021850586,171.38270568847656,0.10079117053489255 +-6.634340763092041,-15.037250518798828,171.35154724121094,0.10591154421540849 +-6.628171443939209,-15.037031173706055,171.3031005859375,0.14861504528632646 +-6.621647357940674,-15.03680419921875,171.24986267089844,0.17502215364737544 +-6.612048625946045,-15.03650951385498,171.177734375,0.19465407352198033 +-6.602231502532959,-15.036163330078125,171.1073455810547,0.2176538996986773 +-6.592142581939697,-15.035888671875,171.02593994140625,0.2798515916324316 +-6.57730770111084,-15.035524368286133,170.91236877441406,0.35556999524643146 +-6.559736251831055,-15.035100936889648,170.77816772460938,0.3802182774797963 +-6.541025161743164,-15.034679412841797,170.63523864746094,0.37712397097264094 +-6.524643421173096,-15.03433895111084,170.5100555419922,0.3627356742538742 +-6.5075578689575195,-15.03402042388916,170.37942504882812,0.3416977896121436 +-6.492031574249268,-15.033761024475098,170.26084899902344,0.31960398331519135 +-6.478028297424316,-15.033552169799805,170.15374755859375,0.29830970938620405 +-6.464881420135498,-15.033379554748535,170.0531463623047,0.27763380764440276 +-6.452401161193848,-15.033236503601074,169.95750427246094,0.2576513125237059 +-6.4409637451171875,-15.033123016357422,169.86990356445312,0.23916962949120496 +-6.430323123931885,-15.03303337097168,169.78826904296875,0.22189691349782958 +-6.420485496520996,-15.03296184539795,169.71275329589844,0.20589737902778038 +-6.411218643188477,-15.032906532287598,169.64158630371094,0.19081222673933426 +-6.402703285217285,-15.032865524291992,169.57611083984375,0.1769482119950898 +-6.394898414611816,-15.032832145690918,169.51597595214844,0.14935611563546564 +-6.38971471786499,-15.032794952392578,169.4733123779297,0.09330711827046444 +-6.386396408081055,-15.032773971557617,169.44644165039062,0.06091779807169447 +-6.38409423828125,-15.032772064208984,169.42840576171875,0.041793572587019066 +-6.382468223571777,-15.03277587890625,169.41552734375,0.03133213548227083 +-6.381124973297119,-15.032790184020996,169.40499877929688,0.02527828746247806 +-6.3800578117370605,-15.032807350158691,169.39739990234375,0.021978504171750016 +-6.379031181335449,-15.0328369140625,169.39044189453125,0.019760562468921796 +-6.378172397613525,-15.032870292663574,169.38497924804688,0.017985058072048903 +-6.377369403839111,-15.03291130065918,169.38023376464844,0.016358845493468197 +-6.3766326904296875,-15.032958984375,169.37615966796875,0.014902184809469874 +-6.37596321105957,-15.03300952911377,169.37283325195312,0.013616037123844594 +-6.375387668609619,-15.033061027526855,169.37008666992188,0.012538218745239376 +-6.374826908111572,-15.033116340637207,169.3677978515625,0.011521721959089314 +-6.374279022216797,-15.033177375793457,169.36575317382812,0.010562093818323041 +-6.374398708343506,-15.033157348632812,169.36581420898438,0.023261392162210397 +-6.374680042266846,-15.033117294311523,169.3660125732422,0.028050691757885816 +-6.375487327575684,-15.032987594604492,169.36705017089844,0.046370241108663335 +-6.377058029174805,-15.03272819519043,169.36795043945312,0.0345452228288875 +-6.380938529968262,-15.032034873962402,169.36814880371094,0.11740235650355736 +-6.388718605041504,-15.030557632446289,169.36419677734375,0.19234841820258317 +-6.4013285636901855,-15.027994155883789,169.35269165039062,0.3174190465009015 +-6.417176246643066,-15.024559020996094,169.3336639404297,0.4123409589946347 +-6.44022798538208,-15.01921272277832,169.29986572265625,0.55381720713848 +-6.469162940979004,-15.012174606323242,169.23524475097656,0.6830912172596552 +-6.504319190979004,-15.00311279296875,169.14077758789062,0.8323233788397684 +-6.545420169830322,-14.99194622039795,169.00599670410156,0.9563607463520057 +-6.59336519241333,-14.978180885314941,168.82276916503906,1.1148656316104455 +-6.640006065368652,-14.96406364440918,168.62295532226562,1.2277669893709484 +-6.703057765960693,-14.943931579589844,168.31900024414062,1.3674802532558696 +-6.763359069824219,-14.92354965209961,167.99896240234375,1.4851788006130393 +-6.834689617156982,-14.898106575012207,167.57858276367188,1.6065874605239543 +-6.912072658538818,-14.868797302246094,167.0835418701172,1.7351602189120718 +-6.986936092376709,-14.838768005371094,166.563720703125,1.8462338035756867 +-7.064830780029297,-14.805740356445312,165.981689453125,1.9521702072430722 +-7.152556419372559,-14.76632308959961,165.27792358398438,2.0630085395552697 +-7.240160942077637,-14.724645614624023,164.5303955078125,2.1680274472311876 +-7.336466312408447,-14.676901817321777,163.69381713867188,2.2798300963940594 +-7.4296464920043945,-14.629575729370117,162.90232849121094,2.375167704444788 +-7.52583122253418,-14.579713821411133,162.10726928710938,2.4431066184866648 +-7.627004623413086,-14.525614738464355,161.27084350585938,2.467860848848635 +-7.73336124420166,-14.46629810333252,160.36962890625,2.4577143584657075 +-7.835005283355713,-14.407144546508789,159.48631286621094,2.429856084469938 +-7.917253017425537,-14.357645988464355,158.76422119140625,2.399947692913706 +-8.019686698913574,-14.293903350830078,157.85519409179688,2.3562468082424752 +-8.111536026000977,-14.23464584350586,157.02674865722656,2.3132916358183775 +-8.199652671813965,-14.175857543945312,156.2208251953125,2.2703633763482367 +-8.284551620483398,-14.11747932434082,155.4376220703125,2.2278972356383444 +-8.37078857421875,-14.05638599395752,154.63377380371094,2.183447296614272 +-8.45015811920166,-13.99832820892334,153.87937927246094,2.1413428017980096 +-8.527239799499512,-13.940116882324219,153.1305389404297,2.099962780705435 +-8.602386474609375,-13.881681442260742,152.38975524902344,2.059701848513102 +-8.70444393157959,-13.799775123596191,151.3744354248047,2.0044923790827656 +-8.794797897338867,-13.724781036376953,150.4638671875,1.9545404597618898 +-8.86210823059082,-13.667221069335938,149.77398681640625,1.9166177713953907 +-8.929350852966309,-13.608080863952637,149.07003784179688,1.8780144443308178 +-8.99592113494873,-13.547810554504395,148.35755920410156,1.8395583530389408 +-9.058309555053711,-13.489877700805664,147.68106079101562,1.8035615657052575 +-9.115459442138672,-13.435619354248047,147.05670166015625,1.7703281396512736 +-9.176005363464355,-13.376853942871094,146.3890380859375,1.7345095734324574 +-9.2304048538208,-13.322819709777832,145.78147888183594,1.7019087742400798 +-9.28736686706543,-13.264960289001465,145.13722229003906,1.6674429566451825 +-9.339435577392578,-13.210882186889648,144.54144287109375,1.6355846807639178 +-9.390949249267578,-13.156229019165039,143.94517517089844,1.6037170779679382 +-9.440951347351074,-13.102048873901367,143.3595733642578,1.5724371509668904 +-9.488937377929688,-13.048967361450195,142.79104614257812,1.5420803228153266 +-9.535715103149414,-12.996163368225098,142.2303009033203,1.5121565734610525 +-9.58109188079834,-12.943904876708984,141.68002319335938,1.4828022278749426 +-9.624679565429688,-12.892715454101562,141.14523315429688,1.454289200468509 +-9.669844627380371,-12.838614463806152,140.5842742919922,1.4244026197167785 +-9.709107398986816,-12.79067611694336,140.09068298339844,1.3981288515596693 +-9.75069522857666,-12.738941192626953,139.56150817871094,1.3699856367273764 +-9.788918495178223,-12.690496444702148,139.06906127929688,1.3438234782282266 +-9.828667640686035,-12.63917350769043,138.55076599121094,1.316304966424859 +-9.864359855651855,-12.592242240905762,138.07952880859375,1.2913118553742504 +-9.900142669677734,-12.544357299804688,137.6015167236328,1.265974761315609 +-9.934386253356934,-12.497725486755371,137.13868713378906,1.2414530755462647 +-9.967728614807129,-12.451533317565918,136.68287658691406,1.2173090703900769 +-10.001261711120605,-12.404268264770508,136.2192840576172,1.192750530892743 +-10.033621788024902,-12.357857704162598,135.7666473388672,1.1687752852763567 +-10.06173324584961,-12.31688117980957,135.36917114257812,1.1477198480744513 +-10.092483520507812,-12.271336555480957,134.92904663085938,1.1244267283560676 +-10.12063217163086,-12.228961944580078,134.52084350585938,1.1028048347504917 +-10.148035049438477,-12.18704605102539,134.1187286376953,1.0810126393327917 +-10.174470901489258,-12.145991325378418,133.72698974609375,1.0594654056227846 +-10.201186180114746,-12.10386848449707,133.3268280029297,1.0374932768934593 +-10.226683616638184,-12.063032150268555,132.9405059814453,1.0163064018060908 +-10.250397682189941,-12.02448558807373,132.57749938964844,0.9966690433127802 +-10.273770332336426,-11.985944747924805,132.21588134765625,0.9776549539508601 +-10.296462059020996,-11.947969436645508,131.8610382080078,0.9589509862822103 +-10.306593894958496,-11.931069374084473,131.7184295654297,0.0038713548300838983 +-10.306777000427246,-11.93081283569336,131.71875,0.0013243033181216156 +-10.306838989257812,-11.930770874023438,131.7192840576172,6.846731533078603e-05 +-10.306814193725586,-11.93082046508789,131.7197723388672,0.0006415596416092836 +-10.306755065917969,-11.930908203125,131.7200469970703,0.0006008488388133934 +-10.306696891784668,-11.931012153625488,131.7203826904297,0.0008007727250675255 +-10.306646347045898,-11.931105613708496,131.7207489013672,0.0004986668889702208 +-10.306610107421875,-11.931183815002441,131.72097778320312,0.0006018441363545335 +-10.306577682495117,-11.93125057220459,131.7213592529297,0.0003146442099788262 +-10.306554794311523,-11.931302070617676,131.72164916992188,0.0003247534802210134 +-10.306537628173828,-11.93134880065918,131.72201538085938,0.00023763106949799926 +-10.306527137756348,-11.931385040283203,131.72251892089844,0.00017385133843423201 +-10.306520462036133,-11.93140983581543,131.72291564941406,0.000158651890311982 +-10.306417465209961,-11.931599617004395,131.72462463378906,0.01533956343505091 +-10.306474685668945,-11.931527137756348,131.72596740722656,0.015941634544188368 +-10.306370735168457,-11.931685447692871,131.72813415527344,0.012977770318510192 +-10.3065185546875,-11.93148136138916,131.72738647460938,0.007739211665755484 +-10.306633949279785,-11.931459426879883,131.72808837890625,0.0034840593758637757 +-10.306746482849121,-11.931391716003418,131.7265625,0.006184215362805468 +-10.306962966918945,-11.931418418884277,131.72291564941406,0.01501366112057376 +-10.307215690612793,-11.931388854980469,131.71868896484375,0.014056562680086312 +-10.307483673095703,-11.931314468383789,131.71646118164062,0.002918015391503366 +-10.307744026184082,-11.931305885314941,131.7114715576172,0.002935321198061235 +-10.308004379272461,-11.931305885314941,131.70733642578125,0.0062870623495071 +-10.308268547058105,-11.931344032287598,131.7039031982422,0.004694336702916575 +-10.30848503112793,-11.931365966796875,131.69923400878906,0.009168147279682959 +-10.30854606628418,-11.931286811828613,131.7002410888672,0.002995154520036838 +-10.308767318725586,-11.931352615356445,131.6953887939453,0.006451989266349643 +-10.30903148651123,-11.931431770324707,131.68936157226562,0.0045248547095268574 +-10.309249877929688,-11.931497573852539,131.68394470214844,0.004954151699956635 +-10.309517860412598,-11.93161392211914,131.6778106689453,0.008327686343955159 +-10.309855461120605,-11.931781768798828,131.66854858398438,0.005933162012443171 +-10.310007095336914,-11.931856155395508,131.66494750976562,0.0019484572683482562 +-10.310012817382812,-11.931929588317871,131.6641082763672,0.0009807245421889568 +-10.309967041015625,-11.93205738067627,131.66371154785156,0.0012853853266536319 +-10.309865951538086,-11.932232856750488,131.66358947753906,0.0012680226005393877 +-10.30975341796875,-11.932400703430176,131.66358947753906,0.0015265590797273962 +-10.309632301330566,-11.932574272155762,131.6637420654297,0.001180568906620568 +-10.309518814086914,-11.932744026184082,131.66453552246094,0.0012876489404704218 +-10.309428215026855,-11.932881355285645,131.66546630859375,0.0009879456534205213 +-10.309353828430176,-11.932995796203613,131.66651916503906,0.0009913245882541835 +-10.309288024902344,-11.933098793029785,131.66763305664062,0.0018763071017733756 +-10.309187889099121,-11.933258056640625,131.66934204101562,0.0036341370637361452 +-10.309062004089355,-11.933456420898438,131.67141723632812,0.0044473164807641375 +-10.308939933776855,-11.933650970458984,131.67327880859375,0.004735089745170544 +-10.308802604675293,-11.933868408203125,131.67538452148438,0.004779665560353965 +-10.308680534362793,-11.934066772460938,131.67742919921875,0.004692986399885075 +-10.308555603027344,-11.934260368347168,131.67926025390625,0.004540168201134197 +-10.30844497680664,-11.934427261352539,131.68081665039062,0.0043716626928199005 +-10.308323860168457,-11.93460464477539,131.68218994140625,0.0041684125742128065 +-10.308212280273438,-11.93476390838623,131.68333435058594,0.003975117711374437 +-10.308106422424316,-11.93491268157959,131.6845703125,0.0037843542221461693 +-10.308000564575195,-11.93505573272705,131.68528747558594,0.0036000975207866803 +-10.307896614074707,-11.93519115447998,131.68528747558594,0.003420634805711838 +-10.307806015014648,-11.935306549072266,131.68528747558594,0.003269571605398764 +-10.307588577270508,-11.935553550720215,131.6875,0.011693776755463004 +-10.307339668273926,-11.935874938964844,131.68968200683594,0.008912249054296589 +-10.307130813598633,-11.936113357543945,131.6906280517578,0.009756954478430495 +-10.306785583496094,-11.936519622802734,131.69190979003906,0.015746622788791857 +-10.306305885314941,-11.9370698928833,131.69271850585938,0.022782242397904863 +-10.30436897277832,-11.939252853393555,131.69337463378906,0.09380775183951938 +-10.300707817077637,-11.943321228027344,131.6887969970703,0.195555033720402 +-10.290090560913086,-11.954744338989258,131.67611694335938,0.3922607969147739 +-10.275766372680664,-11.969828605651855,131.64625549316406,0.4892485299512624 +-10.256534576416016,-11.989602088928223,131.59503173828125,0.6584930634956846 +-10.233657836914062,-12.012629508972168,131.51754760742188,0.8006583673498311 +-10.204266548156738,-12.041640281677246,131.39854431152344,0.9651870748394217 +-10.168758392333984,-12.07603931427002,131.23223876953125,1.1289185069680678 +-10.127063751220703,-12.115729331970215,131.01007080078125,1.2873913999216313 +-10.079493522644043,-12.160283088684082,130.72836303710938,1.43628634912616 +-10.030683517456055,-12.205452919006348,130.40530395507812,1.53008143264988 +-9.975529670715332,-12.255922317504883,130.0080108642578,1.6715186769918153 +-9.912429809570312,-12.313125610351562,129.51353454589844,1.7892729887579912 +-9.857144355773926,-12.362940788269043,129.0479736328125,1.8761255910444512 +-9.771050453186035,-12.440403938293457,128.27627563476562,1.9203413494847026 +-9.699782371520996,-12.505746841430664,127.62797546386719,2.028613598596215 +-9.62459659576416,-12.577067375183105,126.95567321777344,2.163704434374075 +-9.549176216125488,-12.651131629943848,126.29572296142578,2.2661161281585342 +-9.47301197052002,-12.728093147277832,125.6319808959961,2.3542244283768374 +-9.397417068481445,-12.806230545043945,124.96431732177734,2.4336378343480805 +-9.319311141967773,-12.888800621032715,124.26509094238281,2.5105372916934736 +-9.237258911132812,-12.977907180786133,123.526611328125,2.5872514806975446 +-9.153098106384277,-13.072092056274414,122.76837921142578,2.6619782320152936 +-9.073257446289062,-13.16402816772461,122.04434204101562,2.729667100616425 +-8.98822021484375,-13.26473617553711,121.26586151123047,2.799689031285656 +-8.906549453735352,-13.36435604095459,120.51236724853516,2.86550079393052 +-8.81877613067627,-13.474831581115723,119.69843292236328,2.93477651212196 +-8.73502254486084,-13.583670616149902,118.91554260253906,2.9991658345473997 +-8.64726448059082,-13.70114803314209,118.08132934570312,3.0646860101117293 +-8.567582130432129,-13.811089515686035,117.3131103515625,3.1234412807647396 +-8.482924461364746,-13.931703567504883,116.48892211914062,3.1847155736582926 +-8.40298843383789,-14.049528121948242,115.70500946044922,3.241700986580755 +-8.313907623291016,-14.185516357421875,114.82164764404297,3.304016731286041 +-8.232585906982422,-14.313899040222168,113.99826049804688,3.3595535116666224 +-8.148390769958496,-14.451414108276367,113.12989044189453,3.4160620005517375 +-8.071527481079102,-14.581544876098633,112.32563018798828,3.4670166242133416 +-7.988334655761719,-14.727900505065918,111.44438171386719,3.5225616208961212 +-7.913416385650635,-14.864852905273438,110.63928985595703,3.5726787309494594 +-7.831609725952148,-15.020322799682617,109.7431869506836,3.627300707020658 +-7.751461505889893,-15.179008483886719,108.84446716308594,3.680966703206664 +-7.704707622528076,-15.212616920471191,107.98329162597656,0.8870379672777822 +-7.677817344665527,-15.230684280395508,107.4740982055664,0.4599201243079436 +-7.6665191650390625,-15.230841636657715,107.19974517822266,0.18847740015144507 +-7.659086227416992,-15.230988502502441,107.02735137939453,0.16729516304765923 +-7.652078628540039,-15.230962753295898,106.86640167236328,0.1727600448492043 +-7.644247055053711,-15.230804443359375,106.6849136352539,0.18297715611541782 +-7.636495113372803,-15.230552673339844,106.5029525756836,0.19159893004097675 +-7.627895355224609,-15.230230331420898,106.29933166503906,0.201653850621769 +-7.61968994140625,-15.229904174804688,106.10372924804688,0.21084609418465972 +-7.610297679901123,-15.229527473449707,105.87849426269531,0.20925791355038809 +-7.6022820472717285,-15.229217529296875,105.68602752685547,0.20275982442099857 +-7.593967914581299,-15.228901863098145,105.48634338378906,0.1933717393175825 +-7.586068153381348,-15.228615760803223,105.29692840576172,0.18790981080378566 +-7.578564167022705,-15.228358268737793,105.11685180664062,0.18871929503647022 +-7.570851802825928,-15.228108406066895,104.93170928955078,0.19137840629881891 +-7.563260555267334,-15.227867126464844,104.74923706054688,0.173040626419858 +-7.555478572845459,-15.227628707885742,104.56253051757812,0.18100239623667858 +-7.54859733581543,-15.227445602416992,104.39724731445312,0.1540519794882391 +-7.5435991287231445,-15.22716999053955,104.27693939208984,0.10218750190553184 +-7.537829399108887,-15.226869583129883,104.13839721679688,0.15603069302188655 +-7.5316081047058105,-15.226665496826172,103.98905944824219,0.11226836607438583 +-7.526055335998535,-15.22644329071045,103.85389709472656,0.1104956098031365 +-7.521186351776123,-15.226242065429688,103.7367935180664,0.1212122449393329 +-7.515368461608887,-15.226055145263672,103.59764099121094,0.156670258178056 +-7.509790420532227,-15.225957870483398,103.46502685546875,0.12718569870165608 +-7.504609107971191,-15.22587776184082,103.34033203125,0.13244207452601062 +-7.499496936798096,-15.225794792175293,103.21717834472656,0.09234472506227923 +-7.495571136474609,-15.225608825683594,103.12333679199219,0.08676906757366203 +-7.491100311279297,-15.225495338439941,103.01903533935547,0.09426142881883308 +-7.488227367401123,-15.225319862365723,102.94884490966797,0.043782476152059824 +-7.48665714263916,-15.225016593933105,102.90986633300781,0.03404255612654617 +-7.485453128814697,-15.22467041015625,102.88029479980469,0.027298269393201822 +-7.4844536781311035,-15.224306106567383,102.85604858398438,0.022358133189271396 +-7.483663082122803,-15.223963737487793,102.83716583251953,0.01760909867206514 +-7.483018398284912,-15.223644256591797,102.82196044921875,0.014069547385293209 +-7.48249626159668,-15.22335433959961,102.80998229980469,0.011556141199396956 +-7.482075214385986,-15.223101615905762,102.80047607421875,0.009428114933879243 +-7.481730937957764,-15.222888946533203,102.79292297363281,0.00782476002758618 +-7.481428623199463,-15.222692489624023,102.78632354736328,0.006486401006818904 +-7.481201171875,-15.2225341796875,102.78145599365234,0.005002998791524478 +-7.48101806640625,-15.222395896911621,102.77760314941406,0.003980416410409272 +-7.4808669090271,-15.222278594970703,102.77465057373047,0.003287309375594114 +-7.480741500854492,-15.22218132019043,102.77210235595703,0.0027372082425736353 +-7.480634689331055,-15.222100257873535,102.77008819580078,0.0023198732707279354 +-7.4805498123168945,-15.222029685974121,102.7686767578125,0.0016843395249879966 +-7.4804816246032715,-15.221965789794922,102.76753997802734,0.0014166559475076715 +-7.480422019958496,-15.22191333770752,102.7667465209961,0.0011430996025279128 +-7.480375289916992,-15.221871376037598,102.76638793945312,0.0009160387026201202 +-7.480466365814209,-15.221616744995117,102.76871490478516,0.009015480871099652 +-7.4807257652282715,-15.220999717712402,102.77438354492188,0.014725635849824916 +-7.481022834777832,-15.220264434814453,102.78053283691406,0.017449056629684448 +-7.481349468231201,-15.21938419342041,102.78736877441406,0.018887351874855105 +-7.481689929962158,-15.218484878540039,102.79429626464844,0.019489862101888532 +-7.48202657699585,-15.217588424682617,102.80109405517578,0.019644888212591433 +-7.482333660125732,-15.216767311096191,102.80705261230469,0.01957248980374003 +-7.482670783996582,-15.215847969055176,102.81304168701172,0.01935370809776374 +-7.482964515686035,-15.215024948120117,102.81805419921875,0.01908571461364874 +-7.483189105987549,-15.21436595916748,102.82206726074219,0.00013074205684855865 +-7.483184814453125,-15.214360237121582,102.82206726074219,1.1813741975181462e-05 +-7.48318338394165,-15.214353561401367,102.82206726074219,1.3125267683713693e-05 +-7.483182907104492,-15.214347839355469,102.82206726074219,1.157651893963219e-05 +-7.483182430267334,-15.214343070983887,102.82206726074219,1.058362883521651e-05 +-7.483181476593018,-15.214339256286621,102.82206726074219,9.162338229047115e-06 +-7.483181476593018,-15.214335441589355,102.82206726074219,8.192072280489608e-06 +-7.483181476593018,-15.214334487915039,102.82206726074219,7.1938895453583825e-06 +-7.483180999755859,-15.21433162689209,102.82206726074219,6.6935471634226055e-06 +-7.483180999755859,-15.214330673217773,102.82206726074219,7.287365358447025e-06 +-7.483180522918701,-15.214330673217773,102.82206726074219,6.91480113194982e-06 +-7.483180522918701,-15.214329719543457,102.82206726074219,6.817671948149986e-06 +-7.483180522918701,-15.214327812194824,102.82206726074219,6.8066835898440675e-06 +-7.483180522918701,-15.214327812194824,102.82206726074219,6.813230580964674e-06 +-7.483180522918701,-15.214327812194824,102.82206726074219,6.427367836993766e-06 +-7.483180522918701,-15.214327812194824,102.82206726074219,6.147030739353092e-06 +-7.483179569244385,-15.214327812194824,102.82206726074219,6.765529220069432e-06 +-7.483179569244385,-15.214327812194824,102.82206726074219,6.633533009976831e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.590227630338257e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.494947374777326e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.186620239101806e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.082584542367175e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.351209150132855e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.272635089873357e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.29887193777613e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.484197815669006e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,5.6624836824128365e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.039331743027882e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,5.25302021528171e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.2824017477145806e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,5.234588155528512e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,5.553035534308049e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.939980313616582e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.5142914001193425e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.63252941434413e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.592696759691825e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,4.70061383023987e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,6.358405651182416e-06 +-7.483179569244385,-15.214326858520508,102.82206726074219,5.5829020930113005e-06 +-7.483185291290283,-15.214311599731445,102.82249450683594,0.0033104721572389125 +-7.4832000732421875,-15.214137077331543,102.8221435546875,0.006202864034239329 +-7.483244895935059,-15.213311195373535,102.81671142578125,0.025441538107984482 +-7.483407497406006,-15.21065902709961,102.79610443115234,0.09234263159774805 +-7.483780860900879,-15.20390796661377,102.74407196044922,0.2029761778999065 +-7.48429536819458,-15.192047119140625,102.65895080566406,0.32333273596643786 +-7.485074996948242,-15.172590255737305,102.51585388183594,0.4898873237505946 +-7.485970973968506,-15.148823738098145,102.3356704711914,0.6418766944662215 +-7.487246036529541,-15.111678123474121,102.05665588378906,0.8584690532395993 +-7.488463401794434,-15.067235946655273,101.72174835205078,1.0437594520438274 +-7.489502906799316,-15.015339851379395,101.33295440673828,1.2411824620197882 +-7.490237712860107,-14.95310115814209,100.86471557617188,1.431107747345862 +-7.490417957305908,-14.88331413269043,100.33502197265625,1.6226963551122562 +-7.489742755889893,-14.800712585449219,99.69861602783203,1.8212009087133965 +-7.487915515899658,-14.711922645568848,99.0085220336914,2.006960295908191 +-7.484430313110352,-14.611433982849121,98.21881103515625,2.1937813947507467 +-7.479338645935059,-14.511677742004395,97.42031860351562,2.357489678906627 +-7.4706902503967285,-14.389941215515137,96.41873168945312,2.5061450376438223 +-7.4594573974609375,-14.271839141845703,95.41233825683594,2.565676225014406 +-7.445484638214111,-14.156214714050293,94.38896179199219,2.574331649815712 +-7.428586959838867,-14.040884971618652,93.33185577392578,2.556879571163996 +-7.409008026123047,-13.926397323608398,92.25630187988281,2.5265081921523316 +-7.386818885803223,-13.810690879821777,91.16407012939453,2.4889304839284625 +-7.364555358886719,-13.704524040222168,90.16574096679688,2.4500469150959123 +-7.337410926818848,-13.585549354553223,89.0486068725586,2.402689296384063 +-7.309411525726318,-13.472896575927734,87.98460388183594,2.3555036886069427 +-7.281068325042725,-13.367229461669922,86.98151397705078,2.310745172198023 +-7.253353118896484,-13.270116806030273,86.06092834472656,2.2695160952376536 +-7.223506927490234,-13.171120643615723,85.125732421875,2.2269155897147757 +-7.19119119644165,-13.069883346557617,84.16596984863281,2.182182426142157 +-7.160516262054443,-12.979101181030273,83.29719543457031,2.1416210845893557 +-7.127867221832275,-12.887409210205078,82.411865234375,2.1006130042893454 +-7.094002723693848,-12.796857833862305,81.53216552734375,2.060108728118218 +-7.058908939361572,-12.70720386505127,80.65727996826172,2.0199677787156247 +-7.023288249969482,-12.619860649108887,79.80485534667969,1.9799153862981782 +-6.988307952880859,-12.537193298339844,78.9996109008789,1.9460641613217664 +-6.952369213104248,-12.455389976501465,78.1982421875,1.9304481020941473 +-6.914916038513184,-12.374029159545898,77.4453353881836,1.4797510990410687 +-6.904831409454346,-12.372179985046387,77.63365173339844,0.023200886197758137 +-6.904066562652588,-12.371804237365723,77.64869689941406,0.013738961703401697 +-6.90386962890625,-12.37185001373291,77.6589126586914,0.00876515890485285 +-6.903758525848389,-12.371953964233398,77.67072296142578,0.01032853224720153 +-6.9037370681762695,-12.372188568115234,77.68351745605469,0.011548185306426475 +-6.903649806976318,-12.372329711914062,77.6930923461914,0.007333038478481973 +-6.903489112854004,-12.37249755859375,77.70611572265625,0.014958790950203759 +-6.903415203094482,-12.37267017364502,77.71572875976562,0.0094701714179739 +-6.903280258178711,-12.372698783874512,77.7229995727539,0.0026196824240847134 +-6.903242588043213,-12.372777938842773,77.72647094726562,0.001950348295987927 +-6.9032416343688965,-12.372847557067871,77.7291030883789,0.0015581962341751022 +-6.90325403213501,-12.372912406921387,77.73127746582031,0.001137430783607479 +-6.9032793045043945,-12.372974395751953,77.7330551147461,0.0009339309843094416 +-6.90330171585083,-12.373026847839355,77.73455047607422,0.0008805264220860692 +-6.903319358825684,-12.373066902160645,77.73533630371094,0.0009070055587373071 +-6.903329372406006,-12.373096466064453,77.73573303222656,0.0008407864659886763 +-6.903336524963379,-12.373122215270996,77.73580932617188,0.0007452687997368339 +-6.903339862823486,-12.373140335083008,77.73551177978516,0.000633151995372518 +-6.903339862823486,-12.373151779174805,77.73519134521484,0.0007135463965971129 +-6.903334617614746,-12.37315559387207,77.73479461669922,0.0006648075367997907 +-6.903328895568848,-12.373156547546387,77.7343978881836,0.0004995698533423848 +-6.903323650360107,-12.37315559387207,77.73397064208984,0.0005047505793574216 +-6.903420448303223,-12.373541831970215,77.73951721191406,0.022671049116006415 +-6.903700828552246,-12.374147415161133,77.74649810791016,0.038477840497940376 +-6.904118537902832,-12.375018119812012,77.75615692138672,0.0302335323970648 +-6.903891563415527,-12.374587059020996,77.74903106689453,0.035487188271692116 +-6.902975082397461,-12.373108863830566,77.7378158569336,0.011023404329395083 +-6.902444362640381,-12.37306022644043,77.74556732177734,0.006983811104970895 +-6.901777267456055,-12.372978210449219,77.75334930419922,0.011295566231864413 +-6.90101432800293,-12.372891426086426,77.76627349853516,0.008000248422686564 +-6.9002275466918945,-12.372806549072266,77.77947998046875,0.011696528957449662 +-6.89923095703125,-12.37271785736084,77.7960205078125,0.015123925865509624 +-6.898216247558594,-12.372638702392578,77.81109619140625,0.014071056765162893 +-6.897276401519775,-12.372577667236328,77.83270263671875,0.019807937881927303 +-6.896274089813232,-12.372525215148926,77.85527801513672,0.01813027715252175 +-6.895265579223633,-12.372481346130371,77.87418365478516,0.01832494707303031 +-6.894319534301758,-12.372454643249512,77.89484405517578,0.010326302584579986 +-6.893301010131836,-12.372448921203613,77.9189682006836,0.013306599248718335 +-6.892378807067871,-12.372446060180664,77.9415512084961,0.016446475637983664 +-6.891453742980957,-12.372450828552246,77.96089935302734,0.022313424466976234 +-6.890474319458008,-12.372456550598145,77.9832534790039,0.016942412310344795 +-6.891510963439941,-12.375449180603027,78.02865600585938,0.14893414915751185 +-6.896768569946289,-12.38627815246582,78.15730285644531,0.33274819640471853 +-6.905881881713867,-12.404644966125488,78.3836669921875,0.5383200408012003 +-6.918573379516602,-12.430320739746094,78.69095611572266,0.7364981391272607 +-6.935004234313965,-12.463692665100098,79.09086608886719,0.8868560742929478 +-6.955318927764893,-12.505756378173828,79.59042358398438,1.0753744553655458 +-6.9769744873046875,-12.551576614379883,80.13066864013672,1.2402894515732 +-7.003350734710693,-12.609085083007812,80.80087280273438,1.4016478247937314 +-7.027745246887207,-12.66420841217041,81.43344116210938,1.5300166939163031 +-7.059518814086914,-12.739717483520508,82.27174377441406,1.6604540394223455 +-7.089356422424316,-12.815911293029785,83.07501983642578,1.8010159980761873 +-7.116551876068115,-12.890961647033691,83.81822967529297,1.8863941025394577 +-7.144968032836914,-12.976415634155273,84.60513305664062,1.916634720666884 +-7.16995906829834,-13.057805061340332,85.31417083740234,1.8720929214898152 +-7.201527118682861,-13.168022155761719,86.25164794921875,1.76562226739791 +-7.222709655761719,-13.246312141418457,86.91265869140625,1.6598486426753687 +-7.2409515380859375,-13.317543983459473,87.50366973876953,1.5532665001150328 +-7.257981777191162,-13.388569831848145,88.07611083984375,1.441379161382214 +-7.270640850067139,-13.445219039916992,88.51608276367188,1.3499051227207872 +-7.2831268310546875,-13.50527286529541,88.9644775390625,1.2516154750368456 +-7.29392671585083,-13.561237335205078,89.36668395996094,1.1592388201956727 +-7.303330421447754,-13.613509178161621,89.72948455810547,1.072732290377352 +-7.311199188232422,-13.66032600402832,90.04371643066406,0.9952130747012777 +-7.317638397216797,-13.701456069946289,90.30899810791016,0.9273960501098601 +-7.323436737060547,-13.741570472717285,90.55571746826172,0.8612966320442853 +-7.328660488128662,-13.781017303466797,90.7859878540039,0.7964339343717962 +-7.3330817222595215,-13.817713737487793,90.98834991455078,0.7361394960606291 +-7.336684226989746,-13.850367546081543,91.15936279296875,0.6824733747908294 +-7.339822769165039,-13.8812255859375,91.3141098022461,0.6318147957340392 +-7.342350959777832,-13.908374786376953,91.44342803955078,0.5873533170574066 +-7.344659328460693,-13.936083793640137,91.56681060791016,0.5420731730678143 +-7.3463921546936035,-13.959664344787598,91.66422271728516,0.503529546637427 +-7.347899436950684,-13.982693672180176,91.75363159179688,0.46585513962255265 +-7.34901762008667,-14.001522064208984,91.82307434082031,0.43506404547000144 +-7.350144863128662,-14.02284049987793,91.8971939086914,0.4002393935817082 +-7.350889682769775,-14.039084434509277,91.95240020751953,0.32458805579742683 +-7.351458549499512,-14.052669525146484,91.99365997314453,0.28040950809762444 +-7.3518877029418945,-14.06506061553955,92.02735900878906,0.24720515426909098 +-7.352197170257568,-14.075396537780762,92.0518798828125,0.26416443769392733 +-7.352581024169922,-14.092171669006348,92.08821105957031,0.44141118155642756 +-7.353023529052734,-14.118781089782715,92.14432525634766,0.6493362076170558 +-7.353482723236084,-14.15713119506836,92.22367858886719,0.9067725719577445 +-7.353873252868652,-14.209555625915527,92.32955932617188,1.2610782323112306 +-7.354146480560303,-14.273547172546387,92.44974517822266,1.5319084096660855 +-7.354187965393066,-14.351153373718262,92.59004974365234,1.774511700693999 +-7.353828430175781,-14.440407752990723,92.74263763427734,2.001624208668226 +-7.352848529815674,-14.541753768920898,92.90230560302734,2.225216998367497 +-7.350983142852783,-14.654613494873047,93.05957794189453,2.4465999963393448 +-7.348132133483887,-14.776766777038574,93.20807647705078,2.663153634554777 +-7.344559192657471,-14.899139404296875,93.33930969238281,2.861507171849683 +-7.339416980743408,-15.048419952392578,93.48198699951172,3.083598619939822 +-7.3337602615356445,-15.193896293640137,93.60857391357422,3.283227822081812 +-7.332618236541748,-15.22000789642334,93.73778533935547,0.03611307228751791 +-7.331611156463623,-15.24718952178955,93.77594757080078,0.18133258021398582 +-7.332359313964844,-15.248387336730957,93.79004669189453,0.010046603719091328 +-7.33271598815918,-15.249001502990723,93.79961395263672,0.011529965473100912 +-7.33316707611084,-15.24947738647461,93.8096694946289,0.010395813808822325 +-7.333582401275635,-15.249814987182617,93.81977844238281,0.01092503724585385 +-7.334035396575928,-15.25006103515625,93.83074951171875,0.012486285373297995 +-7.334597110748291,-15.250255584716797,93.84467315673828,0.016124115733948872 +-7.335325241088867,-15.25041389465332,93.86202239990234,0.020052448391098723 +-7.336297035217285,-15.250563621520996,93.88558959960938,0.026206170858254007 +-7.337522983551025,-15.250707626342773,93.91548156738281,0.032537867271163506 +-7.339094161987305,-15.250861167907715,93.95388793945312,0.039429930491220976 +-7.340746879577637,-15.251004219055176,93.9941635131836,0.04577532169801927 +-7.342782974243164,-15.251171112060547,94.04438781738281,0.05424216307456665 +-7.345278263092041,-15.251365661621094,94.10498809814453,0.0614633410228151 +-7.348077774047852,-15.251579284667969,94.173583984375,0.06953336318694021 +-7.350846290588379,-15.251788139343262,94.2410659790039,0.07594651154575376 +-7.353996276855469,-15.25202751159668,94.31804656982422,0.08252378471682156 +-7.356173992156982,-15.25207233428955,94.37052917480469,0.038211222984461245 +-7.357644081115723,-15.251912117004395,94.40621185302734,0.03526588351488877 +-7.359080791473389,-15.251648902893066,94.44132232666016,0.03255469763665596 +-7.3603515625,-15.251336097717285,94.47211456298828,0.027755397457921934 +-7.361294269561768,-15.251043319702148,94.49492645263672,0.023402308880865877 +-7.362149715423584,-15.25070858001709,94.51580047607422,0.019282430743027185 +-7.362898826599121,-15.250367164611816,94.5340576171875,0.016136410499483493 +-7.363513469696045,-15.250041007995605,94.54899597167969,0.014870895670273363 +-7.364055156707764,-15.249716758728027,94.56217956542969,0.011528429853534134 +-7.36447286605835,-15.249439239501953,94.57229614257812,0.009795828974500714 +-7.364827632904053,-15.249173164367676,94.58092498779297,0.007824933536174587 +-7.365139484405518,-15.248945236206055,94.58837127685547,0.006794771799173561 +-7.365457534790039,-15.248738288879395,94.59580993652344,0.012225611959963757 +-7.365697860717773,-15.248496055603027,94.59327697753906,0.0038551395780824934 +-7.365794658660889,-15.248236656188965,94.58439636230469,0.009984720476814786 +-7.366006851196289,-15.248024940490723,94.57917022705078,0.011513322583527393 +-7.366257190704346,-15.24791431427002,94.58387756347656,0.010436632741041871 +-7.3665971755981445,-15.247864723205566,94.59160614013672,0.01498704025282284 +-7.367617607116699,-15.247961044311523,94.61663055419922,0.03153252727769432 +-7.36903190612793,-15.248161315917969,94.65106201171875,0.036827296102377845 +-7.370272636413574,-15.248223304748535,94.68090057373047,0.02400659597925368 +-7.371098518371582,-15.248252868652344,94.70092010498047,0.027734648999715512 +-7.37202262878418,-15.248263359069824,94.72380065917969,0.016638190941144448 +-7.372676849365234,-15.24831771850586,94.7392807006836,0.017081488315801332 +-7.373631000518799,-15.248316764831543,94.76261138916016,0.022736285107697866 +-7.37432336807251,-15.248334884643555,94.77967071533203,0.0301935951660584 +-7.375338077545166,-15.248295783996582,94.80387115478516,0.01285395756899972 +-7.376413345336914,-15.248221397399902,94.83038330078125,0.00994286943801935 +-7.377162456512451,-15.248208045959473,94.84849548339844,0.023993841736623406 +-7.378039360046387,-15.248136520385742,94.87012481689453,0.024437851093222582 +-7.379305839538574,-15.248014450073242,94.90097045898438,0.044929526976165444 +-7.380187034606934,-15.248003005981445,94.92265319824219,0.01303349818845435 +-7.3811163902282715,-15.247970581054688,94.94477081298828,0.022061164856104935 +-7.382691383361816,-15.24781322479248,94.98406219482422,0.03438231629008297 +-7.384049415588379,-15.247687339782715,95.01720428466797,0.029746812206287308 +-7.385190486907959,-15.247587203979492,95.04389190673828,0.016297686290379674 +-7.386651039123535,-15.247420310974121,95.08050537109375,0.03976789565931867 +-7.3878326416015625,-15.247344970703125,95.10958099365234,0.025814819802086785 +-7.3891777992248535,-15.247222900390625,95.14253997802734,0.04436091512054583 +-7.3901543617248535,-15.247146606445312,95.16613006591797,0.02093125533385649 +-7.391472816467285,-15.246988296508789,95.1986083984375,0.033080740915910255 +-7.392622947692871,-15.246834754943848,95.22644805908203,0.040745764154454904 +-7.394187927246094,-15.246651649475098,95.26435089111328,0.02369649641656326 +-7.395291805267334,-15.2465238571167,95.29180908203125,0.02720694761217892 +-7.396596908569336,-15.246377944946289,95.3233642578125,0.0561937322216374 +-7.39837121963501,-15.246187210083008,95.36650085449219,0.036153676160261466 +-7.399994850158691,-15.245983123779297,95.40636444091797,0.026377508826338974 +-7.401554584503174,-15.245793342590332,95.44441986083984,0.051066715975424774 +-7.403589248657227,-15.24555778503418,95.49451446533203,0.04408201800933966 +-7.40328311920166,-15.23845386505127,95.41571807861328,0.3602157995015602 +-7.3980631828308105,-15.211549758911133,95.08936309814453,0.7391176793745377 +-7.389339447021484,-15.170668601989746,94.57743835449219,1.0365628247543988 +-7.377101898193359,-15.116985321044922,93.89909362792969,1.2849768511617503 +-7.363027572631836,-15.058676719665527,93.15654754638672,1.4799293249926049 +-7.343966960906982,-14.984432220458984,92.20763397216797,1.6922516609649823 +-7.3251190185546875,-14.915514945983887,91.31580352783203,1.8380888034827552 +-7.289024353027344,-14.793228149414062,89.7439193725586,2.088418577065259 +-7.257267951965332,-14.694161415100098,88.45498657226562,2.278938246761499 +-7.220129013061523,-14.586383819580078,87.04602813720703,2.4644638641311736 +-7.17881441116333,-14.474955558776855,85.58039093017578,2.639665164696284 +-7.1335978507995605,-14.361351013183594,84.0766372680664,2.805866558427729 +-7.0814971923828125,-14.239402770996094,82.45127868652344,2.973687331249955 +-7.025859832763672,-14.118026733398438,80.82048797607422,3.132575979050189 +-6.954493999481201,-13.973428726196289,78.858154296875,3.3134964790822807 +-6.880740642547607,-13.834957122802734,76.9561767578125,3.479876413589763 +-6.800926208496094,-13.695602416992188,75.01663970947266,3.642208635875543 +-6.709961891174316,-13.54806900024414,72.9313735961914,3.8096255401043444 +-6.610737323760986,-13.398735046386719,70.78288269042969,3.9750398447274744 +-6.5068817138671875,-13.253558158874512,68.65233612060547,4.132657328729886 +-6.380282402038574,-13.08974838256836,66.19108581542969,4.307165138739109 +-6.251602649688721,-12.93598747253418,63.81704330444336,4.468290554142808 +-6.111538410186768,-12.781317710876465,61.35564041137695,4.628448414054238 +-5.955211162567139,-12.622349739074707,58.73562240600586,4.792320204998122 +-5.797909259796143,-12.475184440612793,56.213905334472656,4.944074510728223 +-5.613816261291504,-12.317338943481445,53.386356353759766,5.107692904607047 +-5.423086643218994,-12.16835880279541,50.576316833496094,5.263968245345707 +-5.271040439605713,-12.090198516845703,49.06789779663086,1.720012984790501 +-5.215811729431152,-12.127005577087402,49.96601867675781,1.1400889157315206 +-5.161559104919434,-12.113143920898438,49.687320709228516,1.3034280539948302 +-5.1369242668151855,-12.111286163330078,49.861045837402344,0.2670200415571325 +-5.129819393157959,-12.114476203918457,50.04623794555664,0.07806710766424414 +-5.127106666564941,-12.11571979522705,50.11929702758789,0.04691306969310689 +-5.1250739097595215,-12.116629600524902,50.173397064208984,0.03542020050807938 +-5.123356342315674,-12.117379188537598,50.219383239746094,0.0389272740450302 +-5.121577262878418,-12.118139266967773,50.26677703857422,0.03528038665383546 +-5.119978904724121,-12.118817329406738,50.30929183959961,0.026401653168723033 +-5.11850643157959,-12.119434356689453,50.348575592041016,0.028986211369880454 +-5.117131233215332,-12.119991302490234,50.38309097290039,0.03451869904216683 +-5.11574649810791,-12.12057113647461,50.42037582397461,0.029563630852946016 +-5.114346027374268,-12.121158599853516,50.45787811279297,0.02905397088035438 +-5.112879753112793,-12.121763229370117,50.496185302734375,0.02856255251343701 +-5.111401081085205,-12.122360229492188,50.533748626708984,0.03648009095696513 +-5.109816551208496,-12.12298583984375,50.57174301147461,0.03489371267758284 +-5.108132362365723,-12.123687744140625,50.61711120605469,0.029931417536014124 +-5.106684684753418,-12.124289512634277,50.65576934814453,0.03021622186436946 +-5.105344772338867,-12.124849319458008,50.69159698486328,0.026026771211078825 +-5.103906154632568,-12.125425338745117,50.72761154174805,0.030980792269910594 +-5.102194786071777,-12.126133918762207,50.7734489440918,0.029960786729728864 +-5.100756645202637,-12.126726150512695,50.81175994873047,0.02542659691994143 +-5.099474906921387,-12.127254486083984,50.84623718261719,0.028373295660517748 +-5.098278522491455,-12.127717018127441,50.87523651123047,0.019076298693630336 +-5.097807884216309,-12.127899169921875,50.88816452026367,0.0065021264107804864 +-5.0975422859191895,-12.1279878616333,50.89548873901367,0.004006818146471771 +-5.09738302230835,-12.128029823303223,50.9000244140625,0.0026307048470383173 +-5.097285747528076,-12.128044128417969,50.90308380126953,0.0019128644547765608 +-5.0972418785095215,-12.128053665161133,50.90589141845703,0.0018404962063894414 +-5.097619533538818,-12.128321647644043,50.91208267211914,0.013367820282073225 +-5.098273277282715,-12.128758430480957,50.92232894897461,0.01812630397700272 +-5.099103927612305,-12.129303932189941,50.93528366088867,0.019866209641664148 +-5.099853038787842,-12.129793167114258,50.947044372558594,0.01994401989708747 +-5.100674629211426,-12.130331993103027,50.95997619628906,0.019259141313532225 +-5.101402282714844,-12.130807876586914,50.9715690612793,0.018272212485547067 +-5.102105617523193,-12.131268501281738,50.98279571533203,0.017111378897028382 +-5.102734088897705,-12.13167953491211,50.992820739746094,0.01596045732896409 +-5.103307723999023,-12.132055282592773,51.00199508666992,0.01484253919074846 +-5.103846549987793,-12.132411003112793,51.0107421875,0.01374701914790672 +-5.1043500900268555,-12.132739067077637,51.0187873840332,0.012691231005292968 +-5.104811191558838,-12.13304328918457,51.02618408203125,0.011703210062229418 +-5.105219841003418,-12.133317947387695,51.0327262878418,0.01081442648065484 +-5.105647087097168,-12.133611679077148,51.03948974609375,0.009869828681018744 +-5.10600471496582,-12.133868217468262,51.044898986816406,0.009056307577870258 +-5.106322288513184,-12.134102821350098,51.049476623535156,0.00831071417233489 +-5.106564044952393,-12.134292602539062,51.05274200439453,7.811982494441626e-05 +-5.106563568115234,-12.134292602539062,51.05274200439453,4.948676971082128e-06 +-5.106563568115234,-12.134292602539062,51.05274200439453,6.874039052249067e-06 +-5.106564998626709,-12.134292602539062,51.05274200439453,6.723789180070907e-06 +-5.106565952301025,-12.134294509887695,51.05274200439453,5.316159998996267e-06 +-5.106566429138184,-12.134294509887695,51.05274200439453,6.190489443450709e-06 +-5.106566905975342,-12.134294509887695,51.05274200439453,5.50629501745873e-06 +-5.1065673828125,-12.134294509887695,51.05274200439453,5.439116900189507e-06 +-5.1065673828125,-12.134294509887695,51.05274200439453,5.236758719403583e-06 +-5.106567859649658,-12.134294509887695,51.05274200439453,5.1520615967639155e-06 +-5.106567859649658,-12.134294509887695,51.05274200439453,5.1380958569669484e-06 +-5.106567859649658,-12.134294509887695,51.05274200439453,4.467686403494267e-06 +-5.106567859649658,-12.134295463562012,51.05274200439453,4.917427187680284e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,4.922128270143838e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.084189230750306e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,4.960290149105809e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,4.426448540936576e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,4.994343999162911e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,4.729449596045547e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.201177333615392e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,3.925096364320858e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.231175437492014e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.450467759873205e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.052180384156629e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.145228360974644e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.397377257379433e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.38376850102882e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.126805188379853e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,4.5153121047019265e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.2311702982675595e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.246807238023744e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.215287124620634e-06 +-5.106568336486816,-12.134295463562012,51.05274200439453,5.013504902917017e-06 +-5.106583595275879,-12.134329795837402,51.05253982543945,0.006697472930657928 +-5.106604099273682,-12.134445190429688,51.05060958862305,0.005607850500913588 +-5.106681823730469,-12.134547233581543,51.05157470703125,0.0077064695899079425 +-5.107004642486572,-12.13515567779541,51.04599380493164,0.019226029660624873 +-5.107720375061035,-12.136445045471191,51.035343170166016,0.03911062206103405 +-5.111217975616455,-12.142390251159668,50.97901153564453,0.2527532713504244 +-5.119968414306641,-12.157915115356445,50.84473419189453,0.45626396948530296 +-5.132555961608887,-12.180434226989746,50.64763259887695,0.702392880483011 +-5.15139102935791,-12.21403980255127,50.36196517944336,0.9351139920956415 +-5.175022602081299,-12.25534439086914,50.01637268066406,1.210265896452448 +-5.207098484039307,-12.310041427612305,49.568599700927734,1.3960011034943585 +-5.253360271453857,-12.386837005615234,48.955169677734375,1.5342265744485735 +-5.308257102966309,-12.474485397338867,48.26077651977539,1.929440453005513 +-5.36324405670166,-12.560017585754395,47.58029556274414,2.1658053913632753 +-5.421435832977295,-12.648238182067871,46.87759780883789,2.3607962345974007 +-5.484025001525879,-12.740188598632812,46.153480529785156,2.5394204159383524 +-5.553549289703369,-12.83867073059082,45.3951301574707,2.7138096776916574 +-5.629122734069824,-12.941645622253418,44.62071228027344,2.882590479483234 +-5.715615749359131,-13.055093765258789,43.78284454345703,3.055814501141347 +-5.803532600402832,-13.166609764099121,42.961151123046875,3.2151405244867455 +-5.898614406585693,-13.28372859954834,42.08915328979492,3.373252735569326 +-6.00351619720459,-13.408855438232422,41.14971160888672,3.5338161186219956 +-6.118401527404785,-13.541081428527832,40.15366744995117,3.695584483787075 +-6.232546806335449,-13.66759967803955,39.20221710205078,3.8438871611138996 +-6.352377414703369,-13.795563697814941,38.2419319152832,3.988112200571892 +-6.484494686126709,-13.931415557861328,37.220951080322266,4.135483784940646 +-6.615391731262207,-14.061250686645508,36.234535217285156,4.271110208349407 +-6.777779579162598,-14.216508865356445,35.031166076660156,4.427616119578221 +-6.9360527992248535,-14.361977577209473,33.880760192871094,4.558740779457397 +-7.097903728485107,-14.504761695861816,32.73805236816406,4.60926119764304 +-7.2451982498168945,-14.629650115966797,31.729936599731445,4.524314467417515 +-7.405911922454834,-14.760986328125,30.651885986328125,4.32781841676456 +-7.5621490478515625,-14.884285926818848,29.605329513549805,4.07600262834897 +-7.710793972015381,-14.997885704040527,28.59684944152832,3.8037336247313442 +-7.854126453399658,-15.104263305664062,27.600278854370117,3.5242222463110484 +-7.977029800415039,-15.193135261535645,26.720626831054688,3.2801142049099883 +-8.104222297668457,-15.282811164855957,25.786020278930664,3.0263022844420226 +-8.211600303649902,-15.356611251831055,24.980749130249023,2.8122764599862755 +-8.31108283996582,-15.4234037399292,24.22223472595215,2.6146191958316267 +-8.415046691894531,-15.49169635772705,23.414440155029297,2.4082194977453857 +-8.504470825195312,-15.54905891418457,22.70688819885254,2.2324472249951075 +-8.585074424743652,-15.599579811096191,22.065174102783203,2.076357337391424 +-8.662008285522461,-15.646743774414062,21.452957153320312,1.9278389403959517 +-8.734652519226074,-15.690394401550293,20.870737075805664,1.7874051045206818 +-8.806884765625,-15.733011245727539,20.284347534179688,1.6482378643602549 +-8.86950397491455,-15.769354820251465,19.769601821899414,1.5283874464734157 +-8.929598808288574,-15.80362606048584,19.273611068725586,1.4142339395996273 +-8.977510452270508,-15.830497741699219,18.877410888671875,1.323473880114783 +-9.03162670135498,-15.860392570495605,18.42847442626953,1.2214556843588429 +-9.08104133605957,-15.887238502502441,18.018407821655273,1.1287123938191328 +-9.126851081848145,-15.911774635314941,17.636791229248047,1.0428688934670618 +-9.166543006896973,-15.932793617248535,17.30374526977539,0.968706050645731 +-9.205306053161621,-15.95306396484375,16.978214263916016,0.8966800320840477 +-9.241867065429688,-15.971938133239746,16.672908782958984,0.828236834972848 +-9.270678520202637,-15.986678123474121,16.432588577270508,0.5910360718566559 +-9.289073944091797,-15.99610710144043,16.267839431762695,0.3691745179070008 +-9.302009582519531,-16.002641677856445,16.15399169921875,0.22997683268216979 +-9.309999465942383,-16.006628036499023,16.08772850036621,0.1572052904665844 +-9.315217018127441,-16.009201049804688,16.046062469482422,0.11962670541585488 +-9.319785118103027,-16.011478424072266,16.00901222229004,0.0949035006632472 +-9.323644638061523,-16.013439178466797,15.976497650146484,0.07983687407968963 +-9.326642990112305,-16.01497459411621,15.950603485107422,0.07072619756397605 +-9.329524993896484,-16.016443252563477,15.925997734069824,0.06200517785205773 +-9.331902503967285,-16.01763916015625,15.906170845031738,0.05478169282033933 +-9.333870887756348,-16.01862335205078,15.8899564743042,0.048753904852894575 +-9.335844039916992,-16.01961326599121,15.873615264892578,0.0426548911209829 +-9.337578773498535,-16.020484924316406,15.859189987182617,0.03723898178245512 +-9.339044570922852,-16.021221160888672,15.847009658813477,0.03263025346527173 +-9.340237617492676,-16.021820068359375,15.837159156799316,0.028844557336933373 +-9.342044830322266,-16.02269744873047,15.822038650512695,0.06631007333319985 +-9.343603134155273,-16.023454666137695,15.809605598449707,0.02264722698952908 +-9.344732284545898,-16.024009704589844,15.801243782043457,0.0017313480884669752 +-9.344106674194336,-16.023719787597656,15.808209419250488,0.044078690251319046 +-9.342534065246582,-16.02295684814453,15.82210636138916,0.05221163118337305 +-9.340852737426758,-16.02212142944336,15.836703300476074,0.05919948650955824 +-9.33879280090332,-16.021099090576172,15.854741096496582,0.07553694424764917 +-9.335415840148926,-16.01943588256836,15.882287979125977,0.11534798265249467 +-9.32895278930664,-16.0163516998291,15.936904907226562,0.1978015584455077 +-9.31885814666748,-16.011381149291992,16.019641876220703,0.3044990502214403 +-9.303686141967773,-16.00392723083496,16.14996337890625,0.40659890897833867 +-9.282711029052734,-15.993488311767578,16.32512855529785,0.5374109115930548 +-9.256760597229004,-15.98047924041748,16.547616958618164,0.6814662523033397 +-9.227296829223633,-15.965524673461914,16.794931411743164,0.8146835719143893 +-9.189614295959473,-15.946131706237793,17.108051300048828,0.9689749268999637 +-9.145527839660645,-15.923222541809082,17.478954315185547,1.1190637867221636 +-9.094898223876953,-15.896491050720215,17.905519485473633,1.2752747633981707 +-9.038187980651855,-15.866114616394043,18.379220962524414,1.4254430768315458 +-8.977436065673828,-15.8330659866333,18.878599166870117,1.568071113553978 +-8.909228324890137,-15.795308113098145,19.44829750061035,1.7132189199649328 +-8.841382026672363,-15.75689697265625,20.015932083129883,1.8419030451731098 +-8.76103401184082,-15.710397720336914,20.68679428100586,1.9448064923974053 +-8.684865951538086,-15.665325164794922,21.31844139099121,1.9821431935813945 +-8.60341739654541,-15.616094589233398,21.98820686340332,1.9870053061605901 +-8.526481628417969,-15.568573951721191,22.61957359313965,1.9727311154192921 +-8.452165603637695,-15.52138900756836,23.23607635498047,1.9485189695431286 +-8.37370491027832,-15.470237731933594,23.895679473876953,1.9168065848708047 +-8.30047607421875,-15.42125415802002,24.515857696533203,1.8839117706771198 +-8.231048583984375,-15.3739652633667,25.102413177490234,1.8515954275824613 +-8.158949851989746,-15.323919296264648,25.707876205444336,1.8167199690490112 +-8.092860221862793,-15.277070999145508,26.265832901000977,1.7834558700197132 +-8.023892402648926,-15.227030754089355,26.85597801208496,1.7480407888505267 +-7.956942081451416,-15.177313804626465,27.436243057250977,1.7133971700014186 +-7.897308349609375,-15.132182121276855,27.954275131225586,1.682754388010338 +-7.833984375,-15.08355712890625,28.49879264831543,1.6502538662697352 +-7.776197910308838,-15.038715362548828,28.984899520874023,1.6209059596954558 +-7.71854305267334,-14.993766784667969,29.451305389404297,1.5919839477782163 +-7.6558709144592285,-14.944976806640625,29.927776336669922,1.5608281676752263 +-7.601130962371826,-14.90257453918457,30.31414031982422,1.533586801853613 +-7.543200492858887,-14.857998847961426,30.69205093383789,1.504613445794503 +-7.48772668838501,-14.815570831298828,31.02691078186035,1.4767230993575888 +-7.436130046844482,-14.776348114013672,31.315107345581055,1.4507321490257148 +-7.379305362701416,-14.733433723449707,31.60746955871582,1.4220612833004527 +-7.328255653381348,-14.695157051086426,31.84800910949707,1.3962961327976853 +-7.280237197875977,-14.659420013427734,32.05506896972656,1.3720828219313237 +-7.229677200317383,-14.622112274169922,32.2525749206543,1.3496409100851492 +-7.17704963684082,-14.583698272705078,32.433895111083984,1.3269907659191091 +-7.125759124755859,-14.546696662902832,32.58822250366211,1.3205562202025842 +-7.074705600738525,-14.510226249694824,32.7230339050293,1.3234511337215877 +-7.023494720458984,-14.474005699157715,32.84016418457031,1.3490176539916419 +-6.974886417388916,-14.439937591552734,32.93574905395508,1.385196948320654 +-6.917877197265625,-14.400386810302734,33.03099822998047,1.4504253997514427 +-6.8596110343933105,-14.360377311706543,33.11024856567383,1.544955096316492 +-6.785658359527588,-14.310033798217773,33.1850471496582,1.6574519381213795 +-6.714414119720459,-14.261950492858887,33.2404670715332,1.8099248070470548 +-6.635574817657471,-14.209089279174805,33.286136627197266,2.0076618350674176 +-6.559265613555908,-14.158117294311523,33.32109451293945,2.184044846828278 +-6.467562198638916,-14.09701156616211,33.3554573059082,2.3818713316373765 +-6.368500709533691,-14.031134605407715,33.38507080078125,2.5803418002718375 +-6.262806415557861,-13.96099853515625,33.408836364746094,2.776974361592182 +-6.1543498039245605,-13.889223098754883,33.42395782470703,2.9647287145936936 +-6.024959564208984,-13.80393123626709,33.42814254760742,3.1706501408346734 +-5.898962497711182,-13.7213716506958,33.413978576660156,3.346352871757729 +-5.773974895477295,-13.640024185180664,33.381797790527344,3.486033090975709 +-5.625008583068848,-13.543895721435547,33.318607330322266,3.5806189510170863 +-5.486001491546631,-13.455153465270996,33.2331657409668,3.5999038722345267 +-5.346952438354492,-13.36739730834961,33.12262725830078,3.5807309429006997 +-5.204141139984131,-13.27834415435791,32.98549270629883,3.538915992655127 +-5.063786506652832,-13.191923141479492,32.8290901184082,3.485558511098346 +-4.939899921417236,-13.116668701171875,32.67049026489258,3.432623527538314 +-4.803712844848633,-13.03526782989502,32.468467712402344,3.370827842169638 +-4.656421184539795,-12.949079513549805,32.21087646484375,3.3016039771780705 +-4.52078104019165,-12.871600151062012,31.935747146606445,3.2368430823360037 +-4.3910698890686035,-12.79923152923584,31.641632080078125,3.174684920461063 +-4.256831645965576,-12.726075172424316,31.310636520385742,3.1104009261813252 +-4.133373737335205,-12.660332679748535,30.98501205444336,3.0514363116833203 +-4.005553245544434,-12.593828201293945,30.62797737121582,2.9905587287516013 +-3.88191294670105,-12.531075477600098,30.262130737304688,2.9318367888402914 +-3.7632510662078857,-12.472371101379395,29.891422271728516,2.8756819303393155 +-3.641582489013672,-12.413806915283203,29.49014663696289,2.81829029476307 +-3.52321457862854,-12.358488082885742,29.077882766723633,2.762689160790531 +-3.406506061553955,-12.305595397949219,28.65031623840332,2.708117641205408 +-3.291321277618408,-12.25504207611084,28.20764923095703,2.6545089236634816 +-3.17696213722229,-12.20652961730957,27.74751853942871,2.601518352251042 +-3.067476749420166,-12.161662101745605,27.2882080078125,2.551071475194752 +-2.950237989425659,-12.115336418151855,26.777286529541016,2.497371038953393 +-2.8526647090911865,-12.078126907348633,26.338403701782227,2.452977823093521 +-2.738701105117798,-12.036206245422363,25.811283111572266,2.400288245893191 +-2.6309187412261963,-11.998072624206543,25.299543380737305,2.353679408874645 +-2.5335097312927246,-11.964853286743164,24.827390670776367,2.3210663788234576 +-2.4313130378723145,-11.931265830993652,24.322147369384766,2.2982406676760347 +-2.32721209526062,-11.898385047912598,23.797300338745117,2.284870847560759 +-2.223644495010376,-11.867008209228516,23.26517105102539,2.282011406365713 +-2.1244614124298096,-11.838226318359375,22.74589729309082,2.291821900996119 +-2.0196828842163086,-11.80911922454834,22.188983917236328,2.318856112833269 +-1.9129023551940918,-11.780774116516113,21.615022659301758,2.364313740023707 +-1.795641303062439,-11.751134872436523,20.97846794128418,2.434641029935348 +-1.6875256299972534,-11.72517204284668,20.385986328125,2.5171049288802956 +-1.5757355690002441,-11.699702262878418,19.76752471923828,2.61455490291681 +-1.4483633041381836,-11.672399520874023,19.055246353149414,2.731164430756301 +-1.3196053504943848,-11.646699905395508,18.32533836364746,2.851659594583062 +-1.1854952573776245,-11.622017860412598,17.553007125854492,2.978507248992127 +-1.0421679019927979,-11.597996711730957,16.714078903198242,3.1117414331334254 +-0.8964709043502808,-11.576050758361816,15.849124908447266,3.2427273369701948 +-0.7534744739532471,-11.556856155395508,14.992493629455566,3.3666896661264176 +-0.5849506855010986,-11.537076950073242,13.9793119430542,3.5072095536752492 +-0.415676474571228,-11.520185470581055,12.962531089782715,3.6427217149482076 +-0.24748308956623077,-11.506264686584473,11.954205513000488,3.77199022153953 +-0.06343498826026917,-11.494372367858887,10.849200248718262,3.908213952454008 +0.11131804436445236,-11.486367225646973,9.794857025146484,4.033136261849637 +0.30952805280685425,-11.481255531311035,8.589649200439453,4.170140406569951 +0.5142034888267517,-11.480382919311523,7.337441444396973,4.307594262713259 +0.7164829969406128,-11.483782768249512,6.099576950073242,4.438824370086535 +0.9329701066017151,-11.49201488494873,4.776759147644043,4.569574464000101 +1.146533727645874,-11.504791259765625,3.4736149311065674,4.688111109648208 +1.3559377193450928,-11.52184009552002,2.1968913078308105,4.796918706349348 +1.5831295251846313,-11.54541015625,0.812018871307373,4.908922805912073 +1.8254460096359253,-11.576425552368164,-0.665985107421875,5.022992497849175 +2.0506057739257812,-11.610739707946777,-2.042327880859375,5.124928228119311 +2.2758994102478027,-11.65046501159668,-3.4252631664276123,5.223448650223994 +2.5200209617614746,-11.699776649475098,-4.934815883636475,5.328410271930284 +2.7664401531219482,-11.75629711151123,-6.47235631942749,5.435267446007816 +3.031991481781006,-11.824865341186523,-8.142585754394531,5.5510747110908625 +3.2877252101898193,-11.898490905761719,-9.762189865112305,5.663252465982903 +3.546029567718506,-11.980570793151855,-11.409320831298828,5.777077959065331 +3.77182936668396,-12.058835983276367,-12.859699249267578,5.87690410173813 +4.046595573425293,-12.162437438964844,-14.637772560119629,5.998147743007013 +4.322703838348389,-12.276058197021484,-16.438459396362305,6.118817784159436 +4.577555179595947,-12.389554023742676,-18.113258361816406,6.229150365487455 +4.835925102233887,-12.513248443603516,-19.81710433959961,6.337206458996865 +5.118448257446289,-12.658461570739746,-21.673723220825195,6.41253353584124 +5.3616228103637695,-12.791757583618164,-23.25221061706543,6.41036499350441 +5.619380950927734,-12.941412925720215,-24.89115333557129,6.361218938190977 +5.864265441894531,-13.091283798217773,-26.398662567138672,6.286721243182956 +6.115494728088379,-13.252363204956055,-27.876487731933594,6.192180839081494 +6.353204250335693,-13.411155700683594,-29.197751998901367,6.091332063576991 +6.569772720336914,-13.560943603515625,-30.333507537841797,5.992392050066068 +6.808393955230713,-13.731663703918457,-31.523056030273438,5.8768665392436885 +7.028261184692383,-13.894527435302734,-32.58329772949219,5.754242130522403 +7.227210521697998,-14.046798706054688,-33.52510452270508,5.611399201610922 +7.43596887588501,-14.211864471435547,-34.50510787963867,5.466833421691347 +7.623632431030273,-14.365179061889648,-35.386905670166016,5.380481645665912 +7.809717655181885,-14.522014617919922,-36.269161224365234,5.317380376116014 +8.00146198272705,-14.688944816589355,-37.19041061401367,5.25704762211935 +8.1786527633667,-14.848211288452148,-38.05351257324219,5.184332115742504 +8.347957611083984,-15.005000114440918,-38.88693618774414,5.1104621767901035 +8.531847953796387,-15.18056869506836,-39.80173873901367,5.052720145302031 +8.691035270690918,-15.33726692199707,-40.607173919677734,5.014122287114903 +8.850606918334961,-15.484907150268555,-41.55244064331055,1.7269806660710472 +8.879156112670898,-15.460965156555176,-42.30653381347656,0.21647534534475735 +8.880301475524902,-15.460579872131348,-42.33155822753906,0.0037016605571924322 +8.880263328552246,-15.46024227142334,-42.33253479003906,0.01076780688119714 +8.880163192749023,-15.459843635559082,-42.33367156982422,0.01028030877487961 +8.880064010620117,-15.45952320098877,-42.33452224731445,0.008528537740513436 +8.879974365234375,-15.45925235748291,-42.3351936340332,0.006739943876783554 +8.879905700683594,-15.459051132202148,-42.33583068847656,0.005330948339757081 +8.87984848022461,-15.458882331848145,-42.33631896972656,0.004142475452914966 +8.879801750183105,-15.458757400512695,-42.33686828613281,0.0032551647165299474 +8.879765510559082,-15.458662986755371,-42.33738327026367,0.002583747173990122 +8.879734992980957,-15.458598136901855,-42.3378791809082,0.0020135169464368377 +8.87971305847168,-15.4585542678833,-42.33839416503906,0.0016081243027422155 +8.879693984985352,-15.458516120910645,-42.338890075683594,0.0012374736895637624 +8.879679679870605,-15.458489418029785,-42.33927917480469,0.000977804804427347 +8.87969970703125,-15.45850658416748,-42.33979797363281,0.0024621084084111115 +8.879803657531738,-15.458606719970703,-42.34046173095703,0.0043026576104161635 +8.879961013793945,-15.458759307861328,-42.34114456176758,0.005396967723775847 +8.880159378051758,-15.458946228027344,-42.3418083190918,0.006040147414593732 +8.880359649658203,-15.459132194519043,-42.34248733520508,0.006384929236589735 +8.880632400512695,-15.459376335144043,-42.342872619628906,0.006647155650155326 +8.88086986541748,-15.459589958190918,-42.34315872192383,0.0067845614428155 +8.881034851074219,-15.459723472595215,-42.34443664550781,0.00017403755895227586 +8.881037712097168,-15.459717750549316,-42.34443664550781,8.478498668345797e-06 +8.8810396194458,-15.459712982177734,-42.34443664550781,7.2931402512279045e-06 +8.8810396194458,-15.459710121154785,-42.34443664550781,6.762251907649748e-06 +8.881041526794434,-15.459708213806152,-42.34443664550781,6.067296582503088e-06 +8.881041526794434,-15.45970630645752,-42.34443664550781,6.354535782464318e-06 +8.881041526794434,-15.459705352783203,-42.34443664550781,6.384619365410793e-06 +8.881041526794434,-15.459704399108887,-42.34443664550781,5.578463014789925e-06 +8.88104248046875,-15.45970344543457,-42.34443664550781,6.272193435698998e-06 +8.88104248046875,-15.45970344543457,-42.34443664550781,5.532254862281081e-06 +8.88104248046875,-15.459701538085938,-42.34443664550781,5.055024077507211e-06 +8.88104248046875,-15.459701538085938,-42.34443664550781,6.289269654363102e-06 +8.88104248046875,-15.459701538085938,-42.34443664550781,6.229329796124084e-06 +8.88104248046875,-15.459701538085938,-42.34443664550781,6.304063784100948e-06 +8.88104248046875,-15.459701538085938,-42.34443664550781,6.138080090950137e-06 +8.88104248046875,-15.459700584411621,-42.34443664550781,3.946354435481909e-06 +8.88104248046875,-15.459700584411621,-42.34443664550781,6.311293181084584e-06 +8.88104248046875,-15.459700584411621,-42.34443664550781,6.1490593680190075e-06 +8.88104248046875,-15.459700584411621,-42.34443664550781,5.027918288801108e-06 +8.88104248046875,-15.459700584411621,-42.34443664550781,5.0753558282691185e-06 +8.88104248046875,-15.459700584411621,-42.34443664550781,6.378747368298637e-06 +8.88104248046875,-15.45967960357666,-42.34596252441406,0.001031775109196446 +8.88095474243164,-15.459670066833496,-42.33805465698242,0.0045501481014975425 +8.880697250366211,-15.45943832397461,-42.34218215942383,0.008047244176181514 +8.880338668823242,-15.459158897399902,-42.34666442871094,0.012910944602543467 +8.87968635559082,-15.458685874938965,-42.34769821166992,0.018986334663836524 +8.8787841796875,-15.458043098449707,-42.35395431518555,0.02763551458330805 +8.87744140625,-15.457040786743164,-42.369529724121094,0.04709216633558951 +8.871121406555176,-15.45263385772705,-42.41887283325195,0.26162119347501656 +8.858626365661621,-15.444296836853027,-42.51026916503906,0.38574466474992 +8.839959144592285,-15.432022094726562,-42.67582321166992,0.5219018372077345 +8.81707763671875,-15.417366981506348,-42.87565231323242,0.6345841664152734 +8.79049015045166,-15.400593757629395,-43.12412643432617,0.7728672059197881 +8.755260467529297,-15.378551483154297,-43.462432861328125,0.9246776165360807 +8.714097023010254,-15.352514266967773,-43.857261657714844,1.1033238766974027 +8.671334266662598,-15.32492733001709,-44.26307678222656,1.2622706381383888 +8.620025634765625,-15.291274070739746,-44.75282287597656,1.3424407752100234 +8.565196990966797,-15.254752159118652,-45.283409118652344,1.4011071728487827 +8.512725830078125,-15.219307899475098,-45.80256652832031,1.3883763865324614 +8.460359573364258,-15.183420181274414,-46.32752227783203,1.3324494476773936 +8.411727905273438,-15.149517059326172,-46.8184814453125,1.2594077053078505 +8.36609935760498,-15.117156982421875,-47.28229522705078,1.1799954942067912 +8.323753356933594,-15.086628913879395,-47.71562194824219,1.1004728112836193 +8.28382396697998,-15.057400703430176,-48.12702178955078,1.0222516281313305 +8.246176719665527,-15.029419898986816,-48.51701736450195,0.9466728724941004 +8.214823722839355,-15.005745887756348,-48.84172439575195,0.8828155106090032 +8.183428764343262,-14.981687545776367,-49.166893005371094,0.8181640478377256 +8.154093742370605,-14.958818435668945,-49.46855926513672,0.7573089476789773 +8.12702465057373,-14.937360763549805,-49.744808197021484,0.7005843583399566 +8.102571487426758,-14.917696952819824,-49.99289321899414,0.6489634168072929 +8.083380699157715,-14.902100563049316,-50.18741226196289,0.6082102501946998 +8.06057071685791,-14.883398056030273,-50.41907501220703,0.5595179115519572 +8.040700912475586,-14.866979598999023,-50.62178039550781,0.5169713576261346 +8.023798942565918,-14.852933883666992,-50.7951545715332,0.48070783638514 +8.006898880004883,-14.838804244995117,-50.96913146972656,0.44437275305860574 +7.993954181671143,-14.82798957824707,-51.10801696777344,0.2938605196895184 +7.986109256744385,-14.821434020996094,-51.19475173950195,0.1875187024892343 +7.980752944946289,-14.816905975341797,-51.25266647338867,0.12273731866007614 +7.97710657119751,-14.813800811767578,-51.29130172729492,0.08574764615259037 +7.974573612213135,-14.811615943908691,-51.31708908081055,0.06595774024988751 +7.97246789932251,-14.809772491455078,-51.33735656738281,0.0535411286180152 +7.97067928314209,-14.808175086975098,-51.35380554199219,0.04598907537096792 +7.969282150268555,-14.80689811706543,-51.36604309082031,0.040896546300775216 +7.967954635620117,-14.805655479431152,-51.377098083496094,0.03598309559944319 +7.966713905334473,-14.804460525512695,-51.386863708496094,0.031303253557565164 +7.965770721435547,-14.803532600402832,-51.393760681152344,0.027682291900405026 +7.96496057510376,-14.802714347839355,-51.39925003051758,0.024506025141471478 +7.964208126068115,-14.801941871643066,-51.40401077270508,0.02150144510351612 +7.963545799255371,-14.801240921020508,-51.40782165527344,0.01880227668514437 +7.962998390197754,-14.800647735595703,-51.410606384277344,0.016524225220728272 +7.962510585784912,-14.800103187561035,-51.412864685058594,0.014443102705753958 +7.962104797363281,-14.799640655517578,-51.41447830200195,0.01267445564751933 +7.96174955368042,-14.799225807189941,-51.41566848754883,0.011079547986052787 +7.96143102645874,-14.798845291137695,-51.41588592529297,0.00961128425113193 +7.961162090301514,-14.798510551452637,-51.41588592529297,0.008329112210040237 +7.960926532745361,-14.798213958740234,-51.41588592529297,0.0071843059954457035 +7.960739612579346,-14.797978401184082,-51.41588592529297,0.00625164562615712 +7.960575580596924,-14.797773361206055,-51.41588592529297,0.005414137556250572 +7.960556983947754,-14.797751426696777,-51.41588592529297,6.2006525871730385e-06 +7.960556507110596,-14.797751426696777,-51.41588592529297,6.627865813678469e-06 +7.9605560302734375,-14.797749519348145,-51.41588592529297,7.0815496063888115e-06 +7.960555076599121,-14.797749519348145,-51.41588592529297,6.812666391072397e-06 +7.960555076599121,-14.797749519348145,-51.41588592529297,6.199718250299794e-06 +7.960560321807861,-14.797738075256348,-51.41728973388672,0.0022650983844149887 +7.960576057434082,-14.797751426696777,-51.41726303100586,0.000980237626452172 +7.960793495178223,-14.798036575317383,-51.418575286865234,0.01618765022637785 +7.961705207824707,-14.799285888671875,-51.42241668701172,0.045182345786760544 +7.964528560638428,-14.803370475769043,-51.43361282348633,0.14907628444042106 +7.969335556030273,-14.8104887008667,-51.46320724487305,0.24413449030858353 +7.977211952209473,-14.822511672973633,-51.5190315246582,0.38107892477579414 +7.98956298828125,-14.842019081115723,-51.625328063964844,0.5255350453722624 +8.003721237182617,-14.865203857421875,-51.76527404785156,0.6713559865719753 +8.02265453338623,-14.897433280944824,-51.9813117980957,0.8650915492525624 +8.044273376464844,-14.935380935668945,-52.24599075317383,1.071939575467413 +8.070837020874023,-14.982914924621582,-52.584754943847656,1.2733734708822622 +8.102227210998535,-15.040027618408203,-52.98591232299805,1.4980168106544425 +8.138171195983887,-15.106478691101074,-53.452789306640625,1.7251839746617936 +8.17846965789795,-15.182610511779785,-53.98834228515625,1.954850713660667 +8.240580558776855,-15.304139137268066,-54.854820251464844,2.278142829504068 +8.250226020812988,-15.292146682739258,-55.106746673583984,0.09080150185009304 +8.256924629211426,-15.303482055664062,-55.21162033081055,0.4394025196012007 +8.26285457611084,-15.30992317199707,-55.3271598815918,0.02858829598325946 +8.263897895812988,-15.309701919555664,-55.35340881347656,0.008699972725355649 +8.264152526855469,-15.309412956237793,-55.35973358154297,0.004301795734186338 +8.264239311218262,-15.308999061584473,-55.36173629760742,0.0026284526029703562 +8.264214515686035,-15.308558464050293,-55.36088943481445,0.0030797598228071168 +8.264162063598633,-15.308159828186035,-55.35817337036133,0.003607321173206729 +8.264093399047852,-15.307796478271484,-55.35441589355469,0.004119668877047266 +8.264020919799805,-15.307448387145996,-55.35021209716797,0.0045563489296832505 +8.263961791992188,-15.307173728942871,-55.34627151489258,0.004664363257561245 +8.263909339904785,-15.306924819946289,-55.34199905395508,0.004472101584547653 +8.263832092285156,-15.306611061096191,-55.33916091918945,0.016780397072831604 +8.26370906829834,-15.306109428405762,-55.33635711669922,0.056613670729715716 +8.263199806213379,-15.304932594299316,-55.32771301269531,0.04532721852641978 +8.263132095336914,-15.304781913757324,-55.32756042480469,0.022543615170006335 +8.263837814331055,-15.306150436401367,-55.34001159667969,0.06276607362115993 +8.264595031738281,-15.306100845336914,-55.35927200317383,0.019972631359584946 +8.26569938659668,-15.306056022644043,-55.38340377807617,0.019011342625151955 +8.26694107055664,-15.305999755859375,-55.41300582885742,0.027731463133043834 +8.26843547821045,-15.305925369262695,-55.4515495300293,0.035683980164462385 +8.270127296447754,-15.30582332611084,-55.49235916137695,0.03530557126462699 +8.271597862243652,-15.30571460723877,-55.5296516418457,0.031696934532210265 +8.27325439453125,-15.305573463439941,-55.56998825073242,0.03334468744840795 +8.27492618560791,-15.30535888671875,-55.61240768432617,0.033601205291487045 +8.276651382446289,-15.305099487304688,-55.65626525878906,0.03943875806504913 +8.278470039367676,-15.304811477661133,-55.7020149230957,0.03141101944075393 +8.280095100402832,-15.304540634155273,-55.743263244628906,0.0314990200771234 +8.281600952148438,-15.304261207580566,-55.78135681152344,0.031727562560132615 +8.283432960510254,-15.303892135620117,-55.82771682739258,0.034062374889678004 +8.285196304321289,-15.303543090820312,-55.87233352661133,0.03442093417768906 +8.287077903747559,-15.303145408630371,-55.91984558105469,0.03775136656373649 +8.288811683654785,-15.302775382995605,-55.96367263793945,0.03385282053908574 +8.290400505065918,-15.302451133728027,-56.003787994384766,0.02922483427960486 +8.292033195495605,-15.302106857299805,-56.043643951416016,0.030534378241180066 +8.29392147064209,-15.301675796508789,-56.091102600097656,0.034326470080452955 +8.295578956604004,-15.301310539245605,-56.132850646972656,0.033520872782288005 +8.297342300415039,-15.300920486450195,-56.177467346191406,0.038100923012096805 +8.299344062805176,-15.300498962402344,-56.22800827026367,0.03656604153232629 +8.30119514465332,-15.300135612487793,-56.27460479736328,0.036038546113600634 +8.303216934204102,-15.299744606018066,-56.32560348510742,0.036665270784243115 +8.305036544799805,-15.29939079284668,-56.37153244018555,0.036401750028585075 +8.3070068359375,-15.298999786376953,-56.42109298706055,0.03684001426422617 +8.308891296386719,-15.298624992370605,-56.46860122680664,0.03731396507099631 +8.310894012451172,-15.298215866088867,-56.51895523071289,0.036982962535767515 +8.312633514404297,-15.29784870147705,-56.56266403198242,0.031336740328449394 +8.314071655273438,-15.297466278076172,-56.598426818847656,0.019331169602250113 +8.31453800201416,-15.297182083129883,-56.61002731323242,0.006356600513329082 +8.3147554397583,-15.296815872192383,-56.61505889892578,0.0036518696973249433 +8.3148193359375,-15.296466827392578,-56.61625289916992,0.002428643048712032 +8.314812660217285,-15.29609203338623,-56.615604400634766,0.002395871263938025 +8.314767837524414,-15.295769691467285,-56.61417770385742,0.002066963306914879 +8.314706802368164,-15.295480728149414,-56.612247467041016,0.002014007216415519 +8.314655303955078,-15.295254707336426,-56.610015869140625,0.002104995096301355 +8.314600944519043,-15.295050621032715,-56.60761260986328,0.0020886665123209737 +8.314559936523438,-15.294889450073242,-56.60536193847656,0.0020025368007267454 +8.314525604248047,-15.294757843017578,-56.60334396362305,0.0020599467638596834 +8.314496994018555,-15.294650077819824,-56.60154724121094,0.0019018636678289093 +8.314474105834961,-15.294569969177246,-56.60007858276367,0.0014980515619135812 +8.314453125,-15.29450511932373,-56.59867477416992,0.0013926750464404035 +8.314436912536621,-15.294452667236328,-56.59750747680664,0.0011199349462083794 +8.314423561096191,-15.29440975189209,-56.59666061401367,0.0008701275249279218 +8.314414024353027,-15.294381141662598,-56.595733642578125,0.000609711054525629 +8.31440544128418,-15.294356346130371,-56.594886779785156,0.0004924192246385664 +8.314400672912598,-15.294339179992676,-56.594215393066406,0.000393319646451141 +8.314395904541016,-15.294321060180664,-56.593475341796875,0.00032368913949159834 +8.314391136169434,-15.294307708740234,-56.59286880493164,0.00026261935173655797 +8.3143892288208,-15.29429817199707,-56.592594146728516,0.00020853814175453482 +8.31439208984375,-15.29428768157959,-56.59223175048828,7.791640370147659e-05 +8.3143949508667,-15.294285774230957,-56.592079162597656,3.966280867890357e-06 +8.314395904541016,-15.294283866882324,-56.592079162597656,2.2952226466873506e-05 +8.314407348632812,-15.294264793395996,-56.59075927734375,0.00399895376022945 +8.314456939697266,-15.294300079345703,-56.58912658691406,0.0027075790085553833 +8.314314842224121,-15.294008255004883,-56.58710861206055,0.012215247618793678 +8.313676834106445,-15.29282283782959,-56.581825256347656,0.0482344766509615 +8.312673568725586,-15.290982246398926,-56.5747184753418,0.0481551007277165 +8.311147689819336,-15.288371086120605,-56.56815719604492,0.09802811507555037 +8.308465957641602,-15.283844947814941,-56.556983947753906,0.13091301620718132 +8.302794456481934,-15.27467155456543,-56.53595733642578,0.28386043660427585 +8.295208930969238,-15.26252269744873,-56.52503204345703,0.32317893015626403 +8.284324645996094,-15.245636940002441,-56.515777587890625,0.33324966636097475 +8.271599769592285,-15.226593017578125,-56.52579879760742,0.5423857442276778 +8.254570960998535,-15.201845169067383,-56.55405807495117,0.7194101405808925 +8.234867095947266,-15.173912048339844,-56.60240173339844,0.81640032563162 +8.210102081298828,-15.13963794708252,-56.683475494384766,0.9250296893537525 +8.18231201171875,-15.102070808410645,-56.7978630065918,1.0247604437608875 +8.153975486755371,-15.06453800201416,-56.93586349487305,1.1088552655920585 +8.121092796325684,-15.021804809570312,-57.12037658691406,1.2008705253204088 +8.083046913146973,-14.973203659057617,-57.36161804199219,1.2743959894173076 +8.044520378112793,-14.924800872802734,-57.634498596191406,1.321955762921087 +8.005780220031738,-14.876853942871094,-57.936981201171875,1.3543212412333567 +7.964667320251465,-14.826634407043457,-58.28620147705078,1.364295759542677 +7.922181606292725,-14.77538776397705,-58.678382873535156,1.3221840862929317 +7.887290000915527,-14.7337646484375,-59.02451705932617,1.2727314136592838 +7.847064018249512,-14.686148643493652,-59.44904708862305,1.187947022143929 +7.8134942054748535,-14.646580696105957,-59.820953369140625,1.1023381143274 +7.781708240509033,-14.609135627746582,-60.194297790527344,1.0051009548908456 +7.752352237701416,-14.574495315551758,-60.55019760131836,0.9169177218881629 +7.727555274963379,-14.54494857788086,-60.85918045043945,0.8370386923925252 +7.703089237213135,-14.515464782714844,-61.17095184326172,0.7582388858832557 +7.6826491355896,-14.49067211151123,-61.425594329833984,0.6855379382017637 +7.66365385055542,-14.467350959777832,-61.659236907958984,0.6121310801638318 +7.646667957305908,-14.446293830871582,-61.863651275634766,0.5407250599855193 +7.630826950073242,-14.426376342773438,-62.05375289916992,0.4926460306207565 +7.617495059967041,-14.409411430358887,-62.213348388671875,0.45079407375507835 +7.605469703674316,-14.394003868103027,-62.355621337890625,0.40769608233829246 +7.594590663909912,-14.379979133605957,-62.484535217285156,0.3564555966074143 +7.584474086761475,-14.366756439208984,-62.6014518737793,0.3220245507960227 +7.576580047607422,-14.35628890991211,-62.69052505493164,0.28909284075757924 +7.568300724029541,-14.345141410827637,-62.781558990478516,0.27244849240023256 +7.560791969299316,-14.334869384765625,-62.86385726928711,0.2732409897120785 +7.553697109222412,-14.325100898742676,-62.9406623840332,0.23977186181040455 +7.54744291305542,-14.316410064697266,-63.01035690307617,0.22255529782038116 +7.541722297668457,-14.308578491210938,-63.073890686035156,0.20112890791953886 +7.536720275878906,-14.301823616027832,-63.13124465942383,0.16957840874419638 +7.532204627990723,-14.295778274536133,-63.18461608886719,0.1487334191868178 +7.528175354003906,-14.290397644042969,-63.232521057128906,0.12643116545934172 +7.524819850921631,-14.285884857177734,-63.27357864379883,0.11749600178731248 +7.521689414978027,-14.281600952148438,-63.30821228027344,0.12709527024173978 +7.518241882324219,-14.27680778503418,-63.34266662597656,0.10344736672980874 +7.515663146972656,-14.273111343383789,-63.37022399902344,0.10341551951591822 +7.513014793395996,-14.269253730773926,-63.3990478515625,0.08092689276767241 +7.510048866271973,-14.264801025390625,-63.43174362182617,0.09860240392497882 +7.507593154907227,-14.261075973510742,-63.45576095581055,0.09636843835469958 +7.505170822143555,-14.257378578186035,-63.476661682128906,0.08607522177030973 +7.502503871917725,-14.25318717956543,-63.50211715698242,0.10702203128209468 +7.500066757202148,-14.24931526184082,-63.51942443847656,0.09594274929628477 +7.4973626136779785,-14.24489974975586,-63.54264831542969,0.12027454629508556 +7.494195461273193,-14.239651679992676,-63.56916809082031,0.1222703221865613 +7.4907073974609375,-14.233844757080078,-63.596317291259766,0.13974201529794317 +7.487028121948242,-14.227667808532715,-63.61991500854492,0.16725254798005584 +7.482748985290527,-14.220458984375,-63.64387130737305,0.20542628641129126 +7.475885391235352,-14.208762168884277,-63.67707824707031,0.32258523935912864 +7.4676361083984375,-14.194392204284668,-63.71978759765625,0.41891706444081406 +7.456425666809082,-14.174741744995117,-63.778480529785156,0.492039575024785 +7.445367813110352,-14.155323028564453,-63.83372116088867,0.5741762196792957 +7.429005146026611,-14.126479148864746,-63.91366958618164,0.7759415818005344 +7.4092535972595215,-14.091788291931152,-64.01831817626953,0.8971714394685889 +7.386171817779541,-14.051727294921875,-64.1558837890625,1.0316481414490266 +7.358933925628662,-14.00549030303955,-64.34691619873047,1.142708937959994 +7.330115795135498,-13.957878112792969,-64.58076477050781,1.244215561929939 +7.297003746032715,-13.904742240905762,-64.88938903808594,1.3632154595039796 +7.2625861167907715,-13.850970268249512,-65.24940490722656,1.4413596986012465 +7.223870277404785,-13.79190444946289,-65.69721984863281,1.5328790317514822 +7.184670448303223,-13.733306884765625,-66.19297790527344,1.6001238441666026 +7.139892578125,-13.667547225952148,-66.80744934082031,1.6646343778158648 +7.093883514404297,-13.60086727142334,-67.48902130126953,1.724542436829358 +7.046853542327881,-13.533201217651367,-68.23407745361328,1.7695799136922452 +7.002612590789795,-13.469107627868652,-68.964111328125,1.8178498688662805 +6.955708026885986,-13.399898529052734,-69.7603759765625,1.850441288848309 +6.906278610229492,-13.325079917907715,-70.62287139892578,1.895805586301629 +6.854607582092285,-13.244634628295898,-71.55296325683594,1.9448660861649163 +6.808297634124756,-13.170720100402832,-72.41868591308594,1.9837381786083594 +6.762568950653076,-13.096126556396484,-73.30430603027344,2.025267746011926 +6.7088775634765625,-13.006534576416016,-74.39057922363281,2.055945987924393 +6.663527011871338,-12.929094314575195,-75.34855651855469,2.028350588300836 +6.618167400360107,-12.84979248046875,-76.3462905883789,1.9542450435907999 +6.5754828453063965,-12.773136138916016,-77.32376861572266,1.8558495742488852 +6.536940097808838,-12.701923370361328,-78.24137878417969,1.745766506451889 +6.500862121582031,-12.633349418640137,-79.13316345214844,1.6303296505589788 +6.467442989349365,-12.567984580993652,-79.99015808105469,1.5154491580602505 +6.438145160675049,-12.509038925170898,-80.76786041259766,1.4097404630847001 +6.410642623901367,-12.452152252197266,-81.52146911621094,1.3068201648573499 +6.385162830352783,-12.397958755493164,-82.24163055419922,1.208480587431627 +6.364572525024414,-12.35297966003418,-82.83982849121094,1.1270069944366825 +6.343944549560547,-12.306710243225098,-83.45423889160156,1.043422591258301 +6.327068328857422,-12.284533500671387,-83.92875671386719,0.2900677378403006 +6.31995153427124,-12.283863067626953,-84.09492492675781,0.10923773748218743 +6.316857814788818,-12.283452987670898,-84.16979217529297,0.0606041883920248 +6.3155059814453125,-12.28332233428955,-84.19975280761719,0.01814718027167494 +6.314777851104736,-12.283353805541992,-84.21742248535156,0.03440660634695673 +6.313874244689941,-12.283390045166016,-84.23927307128906,0.0145266062632857 +6.31292200088501,-12.283431053161621,-84.26216125488281,0.020694892604584365 +6.312079906463623,-12.283462524414062,-84.28483581542969,0.00696419465416228 +6.311467170715332,-12.283512115478516,-84.29943084716797,0.023567422694012467 +6.309831619262695,-12.28345775604248,-84.33995819091797,0.044443243705804915 +6.308341026306152,-12.28336238861084,-84.37760925292969,0.0333811098756956 +6.307284355163574,-12.28331470489502,-84.40352630615234,0.00900528017797098 +6.306502342224121,-12.283308029174805,-84.42549133300781,0.028320771767524632 +6.304792404174805,-12.283221244812012,-84.46736907958984,0.038483120685046876 +6.303750038146973,-12.283173561096191,-84.49214935302734,0.022030248781753952 +6.302719593048096,-12.283159255981445,-84.5137939453125,0.034059645742400765 +6.301217079162598,-12.28316593170166,-84.55256652832031,0.02510851733236056 +6.300281047821045,-12.283042907714844,-84.57750701904297,0.01512701481988677 +6.298654079437256,-12.282954216003418,-84.61807250976562,0.0444475773114295 +6.297069072723389,-12.282855033874512,-84.65097045898438,0.0230056091867709 +6.296060085296631,-12.28281307220459,-84.67552185058594,0.02336170232328472 +6.294798374176025,-12.28277587890625,-84.70667266845703,0.05283077158764554 +6.292337417602539,-12.282577514648438,-84.76744079589844,0.06854695613761803 +6.289398193359375,-12.282309532165527,-84.83831787109375,0.06974570927186918 +6.28601598739624,-12.281983375549316,-84.92132568359375,0.08230670522740872 +6.283041954040527,-12.281689643859863,-84.99272918701172,0.07409693484938688 +6.284797668457031,-12.290549278259277,-84.8985595703125,0.3068597538083049 +6.292038917541504,-12.311307907104492,-84.63817596435547,0.5410883367318782 +6.302981853485107,-12.341273307800293,-84.30009460449219,0.7612678500422781 +6.317180633544922,-12.37916088104248,-83.86566162109375,0.9399680542623229 +6.332825183868408,-12.419940948486328,-83.40331268310547,1.0834530744163093 +6.352365493774414,-12.46966552734375,-82.83667755126953,1.230871480982886 +6.374788761138916,-12.525407791137695,-82.20269012451172,1.3679278585961252 +6.40096378326416,-12.588793754577637,-81.49113464355469,1.510061823291578 +6.430254936218262,-12.657937049865723,-80.71814727783203,1.6596671972100163 +6.460329055786133,-12.726917266845703,-79.94962310791016,1.7863813415104757 +6.497106075286865,-12.808616638183594,-79.0416259765625,1.9230136911793718 +6.5365824699401855,-12.893237113952637,-78.10220336914062,2.053117570161997 +6.577561378479004,-12.978028297424316,-77.16320037841797,2.1749453780643853 +6.625369548797607,-13.073674201965332,-76.11300659179688,2.304964145279982 +6.672956466674805,-13.166051864624023,-75.11532592773438,2.4249594935284895 +6.729213237762451,-13.27232551574707,-73.9952392578125,2.559694701737831 +6.788430690765381,-13.380899429321289,-72.87496185302734,2.6968323770183242 +6.854831218719482,-13.497844696044922,-71.66581726074219,2.8452956191509835 +6.921253681182861,-13.609415054321289,-70.4915542602539,2.9895504965327926 +6.993381023406982,-13.724688529968262,-69.2481460571289,3.141835647446632 +7.086025714874268,-13.864630699157715,-67.69580841064453,3.3272888068632778 +7.169918060302734,-13.98465347290039,-66.3349838256836,3.4848231546981263 +7.2715630531311035,-14.122735023498535,-64.74272155761719,3.662086845139471 +7.362048625946045,-14.239547729492188,-63.371925354003906,3.808328059466618 +7.493142604827881,-14.399497032165527,-61.45004653930664,4.003201802932485 +7.614463806152344,-14.538552284240723,-59.72896957397461,4.17050341059592 +7.7485480308532715,-14.683436393737793,-57.889312744140625,4.34660571529961 +7.891422748565674,-14.82885456085205,-55.99885177612305,4.526593279397211 +8.045978546142578,-14.976751327514648,-54.025054931640625,4.71195316155525 +8.197333335876465,-15.112924575805664,-52.15378952026367,4.884804246919354 +8.373779296875,-15.261773109436035,-50.04109573364258,5.077391998541175 +8.546022415161133,-15.3651123046875,-48.821651458740234,1.80832944241723 +8.613125801086426,-15.35857105255127,-49.35140609741211,1.3932380671023075 +8.668243408203125,-15.381559371948242,-49.071590423583984,0.5366816486537425 +8.68083381652832,-15.380526542663574,-49.165218353271484,0.12533954014721918 +8.685320854187012,-15.379961013793945,-49.2171630859375,0.09098388052281385 +8.688961029052734,-15.379450798034668,-49.25394058227539,0.07681292417315166 +8.691896438598633,-15.378636360168457,-49.30147171020508,0.06127707043695584 +8.694391250610352,-15.37757396697998,-49.3592529296875,0.0510782223861306 +8.69681453704834,-15.376408576965332,-49.42352294921875,0.055641240945517374 +8.699444770812988,-15.375192642211914,-49.496978759765625,0.05593897076800692 +8.702285766601562,-15.373981475830078,-49.57425308227539,0.05946908143426983 +8.704967498779297,-15.373018264770508,-49.638240814208984,0.05495789156625184 +8.707798957824707,-15.372163772583008,-49.69733428955078,0.05817539873419242 +8.710619926452637,-15.371344566345215,-49.754398345947266,0.05883285760827622 +8.713624000549316,-15.370444297790527,-49.81867599487305,0.05785545818343763 +8.716650009155273,-15.369747161865234,-49.869293212890625,0.05659667598217909 +8.719167709350586,-15.368919372558594,-49.931495666503906,0.055330418444643724 +8.722244262695312,-15.36815357208252,-49.98927307128906,0.06316193021237425 +8.725545883178711,-15.367161750793457,-50.06425094604492,0.059213031044107224 +8.728294372558594,-15.366299629211426,-50.13065719604492,0.05411659995919337 +8.731452941894531,-15.36535930633545,-50.205081939697266,0.05770621575021163 +8.734128952026367,-15.36449146270752,-50.27448272705078,0.05213747668730856 +8.736709594726562,-15.363737106323242,-50.33396911621094,0.04976903906400996 +8.739337921142578,-15.362958908081055,-50.394935607910156,0.054199658191576995 +8.741781234741211,-15.36220645904541,-50.45491027832031,0.04425954954025884 +8.74398422241211,-15.361499786376953,-50.51127624511719,0.04064068413616559 +8.746562957763672,-15.360662460327148,-50.57915496826172,0.051108344240697844 +8.749070167541504,-15.359834671020508,-50.64741134643555,0.05467222926331694 +8.751786231994629,-15.35894775390625,-50.7230110168457,0.051423643684330875 +8.754339218139648,-15.358119010925293,-50.79328918457031,0.05435135076936688 +8.756889343261719,-15.357304573059082,-50.86399459838867,0.05054597484874931 +8.759746551513672,-15.35639476776123,-50.94112777709961,0.048734465856039896 +8.762263298034668,-15.355591773986816,-51.0083122253418,0.050366146807868495 +8.764836311340332,-15.354780197143555,-51.07710647583008,0.04943822346675985 +8.767434120178223,-15.353952407836914,-51.14696502685547,0.053190382367243154 +8.770137786865234,-15.353095054626465,-51.21895217895508,0.05095526119194888 +8.772478103637695,-15.352344512939453,-51.27959060668945,0.04439987011298533 +8.77492618560791,-15.351534843444824,-51.34346008300781,0.03971692646802129 +8.776671409606934,-15.350944519042969,-51.386619567871094,0.03416628257836508 +8.777950286865234,-15.350422859191895,-51.421958923339844,0.03509877647272534 +8.778831481933594,-15.349954605102539,-51.449310302734375,0.01852980169321183 +8.779086112976074,-15.349594116210938,-51.46522903442383,0.0066695794783288185 +8.779095649719238,-15.349305152893066,-51.47499084472656,0.0044621268279592535 +8.778996467590332,-15.349026679992676,-51.483055114746094,0.0030924826755867694 +8.778853416442871,-15.348799705505371,-51.48878860473633,0.0021419322444002627 +8.778705596923828,-15.348615646362305,-51.49315643310547,0.0017141600526449042 +8.778578758239746,-15.34847640991211,-51.496360778808594,0.0012451171091824337 +8.778205871582031,-15.348055839538574,-51.50405502319336,0.02154151324631785 +8.778072357177734,-15.347810745239258,-51.51042938232422,0.02606244005639325 +8.778372764587402,-15.347853660583496,-51.51289367675781,0.016665450086029272 +8.780025482177734,-15.347753524780273,-51.52290344238281,0.039867772345029875 +8.782305717468262,-15.347439765930176,-51.54954528808594,0.044578863615956275 +8.784811019897461,-15.347077369689941,-51.58281326293945,0.03903354197899613 +8.7880859375,-15.34674072265625,-51.61216354370117,0.06916611298945283 +8.791943550109863,-15.346577644348145,-51.62431716918945,0.0832920780668793 +8.796524047851562,-15.34642219543457,-51.63612747192383,0.0917427769734189 +8.801142692565918,-15.346247673034668,-51.65199661254883,0.07058317500247085 +8.804953575134277,-15.345821380615234,-51.69081115722656,0.07834758243253225 +8.808794021606445,-15.345376968383789,-51.73235321044922,0.07160947187085075 +8.812727928161621,-15.344975471496582,-51.769432067871094,0.08013994067239055 +8.816765785217285,-15.344569206237793,-51.80684280395508,0.08159692384376009 +8.820870399475098,-15.344449043273926,-51.81865310668945,0.0967440143057123 +8.8255615234375,-15.344134330749512,-51.84743118286133,0.09472153916251083 +8.829566955566406,-15.34350299835205,-51.90388870239258,0.06934203768973897 +8.834006309509277,-15.343292236328125,-51.92445755004883,0.08785272467667811 +8.83829402923584,-15.343118667602539,-51.94190216064453,0.09565690211224692 +8.841459274291992,-15.342330932617188,-51.98418045043945,0.07808909797186912 +8.828666687011719,-15.331802368164062,-52.16924285888672,0.5283472277370241 +8.800627708435059,-15.310625076293945,-52.571144104003906,0.959609670803546 +8.759243965148926,-15.27924633026123,-53.167091369628906,1.3349071897958584 +8.70207405090332,-15.23510456085205,-53.994232177734375,1.6576987589530214 +8.642326354980469,-15.187719345092773,-54.86568069458008,1.9148846221538662 +8.564303398132324,-15.123713493347168,-56.01438903808594,2.196708762697906 +8.486644744873047,-15.057456016540527,-57.17062759399414,2.444145607568638 +8.39675235748291,-14.977291107177734,-58.52486801147461,2.7046517021089116 +8.298879623413086,-14.885395050048828,-60.01900100708008,2.966355490549135 +8.197973251342773,-14.785296440124512,-61.58478546142578,3.218471647816422 +8.091411590576172,-14.673480033874512,-63.2768440246582,3.4694910157659646 +7.984084129333496,-14.554357528686523,-65.03688049316406,3.709441549083097 +7.8405890464782715,-14.384397506713867,-67.50212097167969,4.015986243748824 +7.7144060134887695,-14.223825454711914,-69.78840637207031,4.276860345099542 +7.5910515785217285,-14.05495548248291,-72.14379119873047,4.5245172279887385 +7.471629619598389,-13.877766609191895,-74.55497741699219,4.703787802491967 +7.357935428619385,-13.694239616394043,-76.99850463867188,4.745246366705889 +7.249687194824219,-13.503156661987305,-79.49649810791016,4.636742835670674 +7.155389785766602,-13.32030963897705,-81.85055541992188,4.436834897326175 +7.069687366485596,-13.136763572692871,-84.18290710449219,4.180586683631167 +6.997596740722656,-12.965055465698242,-86.34117889404297,3.9098589257971956 +6.939878940582275,-12.812061309814453,-88.24703979492188,3.6541548516205147 +6.88933801651001,-12.662534713745117,-90.09471893310547,3.397641282225923 +6.844306945800781,-12.512343406677246,-91.93685913085938,3.1375490383144835 +6.810269832611084,-12.384035110473633,-93.50060272216797,2.915969537781673 +6.780669212341309,-12.257749557495117,-95.03158569335938,2.6992660397236405 +6.769309043884277,-12.257271766662598,-95.25225830078125,0.04725798021020047 +6.76945686340332,-12.262924194335938,-95.19207000732422,0.3885341663084284 +6.774874687194824,-12.291529655456543,-94.84226989746094,0.8287078862270255 +6.783574104309082,-12.33396053314209,-94.32386016845703,1.0723218741136658 +6.7951860427856445,-12.386796951293945,-93.67583465576172,1.206570550024271 +6.8083176612854,-12.442483901977539,-92.98686981201172,1.2680191855127734 +6.822164535522461,-12.497403144836426,-92.29887390136719,1.2902290473284008 +6.838416576385498,-12.557478904724121,-91.5323486328125,1.291313804853721 +6.855138778686523,-12.61489486694336,-90.78192138671875,1.2797338286051598 +6.872189998626709,-12.66983699798584,-90.0504379272461,1.2636383169828296 +6.889936923980713,-12.724356651306152,-89.32014465332031,1.2444587001980472 +6.908450603485107,-12.778801918029785,-88.58727264404297,1.2231936899788225 +6.926865100860596,-12.830772399902344,-87.88452911376953,1.2017001003748882 +6.945217609405518,-12.88062572479248,-87.20355224609375,1.1765358421842227 +6.965264320373535,-12.933025360107422,-86.48291015625,1.1506053830614866 +6.9830451011657715,-12.977958679199219,-85.86284637451172,1.1366779916189003 +7.0034685134887695,-13.027894973754883,-85.17064666748047,1.132553586499456 +7.023608207702637,-13.075522422790527,-84.50753021240234,1.1387839271973514 +7.04457426071167,-13.123770713806152,-83.83751678466797,1.1578614256335193 +7.065287113189697,-13.169971466064453,-83.19206237792969,1.1801869371503413 +7.086932182312012,-13.216876029968262,-82.53487396240234,1.2010517529978804 +7.11258602142334,-13.270651817321777,-81.77439880371094,1.219304803754682 +7.137228012084961,-13.320735931396484,-81.06439208984375,1.2418426313862283 +7.1622748374938965,-13.37006950378418,-80.35955047607422,1.2594103458537653 +7.1896491050720215,-13.422380447387695,-79.60820007324219,1.2760871499898225 +7.218907356262207,-13.4765625,-78.82574462890625,1.2936573396482418 +7.246778964996338,-13.52657699584961,-78.0973892211914,1.3077924806882653 +7.2770256996154785,-13.579240798950195,-77.32510375976562,1.3185214436422048 +7.307929992675781,-13.631387710571289,-76.54934692382812,1.3224174326103721 +7.340184211730957,-13.684209823608398,-75.75933837890625,1.3293167675943658 +7.373500823974609,-13.737045288085938,-74.96713256835938,1.334546847696143 +7.40664529800415,-13.788126945495605,-74.19059753417969,1.3429553342166922 +7.43863582611084,-13.836065292358398,-73.45787048339844,1.3651467980201324 +7.473520278930664,-13.886955261230469,-72.67732238769531,1.421094650392488 +7.51578950881958,-13.947019577026367,-71.74864959716797,1.5652299345962601 +7.561765193939209,-14.010493278503418,-70.76194763183594,1.7792412044099273 +7.612653732299805,-14.078688621520996,-69.69854736328125,2.02693355160627 +7.669384479522705,-14.152233123779297,-68.54359436035156,2.2820817234025976 +7.744129657745361,-14.245348930358887,-67.06733703613281,2.5714016195449414 +7.819250106811523,-14.3348388671875,-65.6305923461914,2.821809240421164 +7.910159587860107,-14.438091278076172,-63.94783401489258,3.0911102038708704 +8.01246166229248,-14.548229217529297,-62.1192626953125,3.3629362354005834 +8.120977401733398,-14.658661842346191,-60.24626922607422,3.6234128451195327 +8.244904518127441,-14.777454376220703,-58.18118667602539,3.8924866498625836 +8.383585929870605,-14.901866912841797,-55.953346252441406,4.1648456151294235 +8.54256534576416,-15.034600257873535,-53.492713928222656,4.447766234786783 +8.711901664733887,-15.165230751037598,-50.96852111816406,4.720899391783967 +8.892430305480957,-15.293546676635742,-48.37037658691406,4.986703790059849 +9.085280418395996,-15.419135093688965,-45.68714904785156,5.2468998075496565 +9.211050987243652,-15.44084358215332,-44.82017135620117,2.4029635377085685 +9.303853988647461,-15.45463752746582,-43.93483352661133,1.6492248462356105 +9.369050025939941,-15.467194557189941,-43.17496871948242,1.1507750876711742 +9.41187858581543,-15.476283073425293,-42.65327072143555,0.8821495250485057 +9.444283485412598,-15.483665466308594,-42.2535514831543,0.7498431368568981 +9.476213455200195,-15.491443634033203,-41.851070404052734,0.6914226547536629 +9.506264686584473,-15.499054908752441,-41.47031021118164,0.6752146086130026 +9.53505802154541,-15.506609916687012,-41.09808349609375,0.6629935776862694 +9.564462661743164,-15.514328002929688,-40.720947265625,0.6545607710066816 +9.5936279296875,-15.522189140319824,-40.33721160888672,0.6920175359211614 +9.62491512298584,-15.530598640441895,-39.9289436340332,0.7362833396467687 +9.658482551574707,-15.53974723815918,-39.48517608642578,0.7937248539669638 +9.694518089294434,-15.549724578857422,-39.0030517578125,0.8602213228464823 +9.734407424926758,-15.5608491897583,-38.469268798828125,0.9493897695443343 +9.77448844909668,-15.572122573852539,-37.9345703125,1.0431708412872607 +9.827373504638672,-15.587294578552246,-37.22452926635742,1.1928994150150645 +9.884403228759766,-15.604037284851074,-36.45573806762695,1.3755301966864646 +9.9466552734375,-15.62261962890625,-35.61939239501953,1.5905491231235003 +10.015165328979492,-15.643315315246582,-34.708229064941406,1.8448202008426622 +10.104851722717285,-15.67042064666748,-33.53358840942383,2.1784053319114203 +10.215073585510254,-15.702311515808105,-32.1114616394043,2.52399798509511 +10.333674430847168,-15.734345436096191,-30.601905822753906,2.8393351809284297 +10.470829963684082,-15.767601013183594,-28.877351760864258,3.158496714302002 +10.613164901733398,-15.798276901245117,-27.109027862548828,3.453916377403703 +10.775449752807617,-15.828585624694824,-25.116676330566406,3.7589110107435797 +10.955244064331055,-15.856009483337402,-22.934368133544922,4.066596904299704 +11.15460205078125,-15.879931449890137,-20.54153060913086,4.379614633100229 +11.36473560333252,-15.897278785705566,-18.047924041748047,4.684056451692394 +11.584723472595215,-15.90687084197998,-15.46226978302002,4.98042571804294 +11.83720588684082,-15.907218933105469,-12.518757820129395,5.297421652556267 +12.067880630493164,-15.89759635925293,-9.846051216125488,5.544681775696469 +12.332598686218262,-15.874553680419922,-6.79010534286499,5.725227078008339 +12.58804988861084,-15.839533805847168,-3.8394479751586914,5.784484567226401 +12.84317684173584,-15.791487693786621,-0.874298095703125,5.770166343642678 +13.104068756103516,-15.72803020477295,2.19511342048645,5.708623540316818 +13.348127365112305,-15.654827117919922,5.113857746124268,5.6289515978399995 +13.599723815917969,-15.564767837524414,8.199968338012695,5.521805608991856 +13.814451217651367,-15.475374221801758,10.896897315979004,5.427736768474093 +14.048746109008789,-15.36284351348877,13.913631439208984,5.313924235731421 +14.251680374145508,-15.251850128173828,16.602672576904297,5.212237726274056 +14.444973945617676,-15.1332368850708,19.238964080810547,5.10617665630519 +14.644437789916992,-14.996296882629395,22.05331802368164,4.961625890570692 +14.8228178024292,-14.860016822814941,24.671146392822266,4.820067444437741 +14.987664222717285,-14.721056938171387,27.189664840698242,4.693050133058104 +15.147748947143555,-14.573702812194824,29.70049476623535,4.5638794012909525 +15.300918579101562,-14.42128849029541,32.12397766113281,4.438245549628215 +15.423205375671387,-14.29179573059082,34.04786682128906,4.335246280478505 +15.568094253540039,-14.129435539245605,36.29829406738281,4.207876510784821 +15.689501762390137,-13.985658645629883,38.16202926635742,4.096245000199256 +15.809576034545898,-13.835838317871094,39.99940490722656,3.9826740593826226 +15.906207084655762,-13.708955764770508,41.488529205322266,3.88601591841945 +16.057397842407227,-13.49750804901123,43.86048126220703,3.725669442916507 +16.15398406982422,-13.353388786315918,45.411903381347656,3.6172154412063353 +16.23817253112793,-13.221144676208496,46.794158935546875,3.519193603284713 +16.320730209350586,-13.084992408752441,48.17544937133789,3.419246606182236 +16.39838409423828,-12.950634002685547,49.49983596801758,3.3228328537503367 +16.472686767578125,-12.815532684326172,50.80094528198242,3.227407312847229 +16.540931701660156,-12.6847505569458,52.04158401489258,3.137283264424277 +16.60113525390625,-12.5631103515625,53.18345642089844,3.058219437794097 +16.662567138671875,-12.43200397491455,54.40324783325195,2.97929435182951 +16.711973190307617,-12.320743560791016,55.430171966552734,2.915337991228338 +16.765899658203125,-12.192423820495605,56.60578155517578,2.8436324706860288 +16.794282913208008,-12.17212963104248,57.37474060058594,0.3259280059428641 +16.795692443847656,-12.173720359802246,57.431095123291016,0.0012598413282004874 +16.79578399658203,-12.173698425292969,57.43042755126953,0.0008505248360483953 +16.795930862426758,-12.173711776733398,57.429443359375,0.000959825283971043 +16.79585838317871,-12.174129486083984,57.42215347290039,0.0252718508680376 +16.795312881469727,-12.175752639770508,57.40339279174805,0.04484373009127996 +16.79457664489746,-12.177857398986816,57.38084030151367,0.052309725926550046 +16.793752670288086,-12.180173873901367,57.356727600097656,0.05402092717858754 +16.792905807495117,-12.182551383972168,57.332298278808594,0.05280028175539906 +16.792095184326172,-12.184831619262695,57.30891799926758,0.050232931530108015 +16.791372299194336,-12.186848640441895,57.288265228271484,0.04735415007051158 +16.790639877319336,-12.188897132873535,57.26738357543945,0.044109368095154054 +16.78997802734375,-12.190735816955566,57.24876403808594,0.04103427125533574 +16.78937530517578,-12.192401885986328,57.231990814208984,0.03817372552994257 +16.78877067565918,-12.194061279296875,57.215431213378906,0.035285815817294765 +16.788211822509766,-12.195556640625,57.200870513916016,0.032665826878890254 +16.78767967224121,-12.196956634521484,57.18749237060547,0.030202494896557363 +16.78721809387207,-12.198139190673828,57.1766471862793,0.028107911577150667 +16.78687858581543,-12.199142456054688,57.17308044433594,0.03286667381758394 +16.786359786987305,-12.200380325317383,57.163700103759766,0.02476971180417952 +16.785737991333008,-12.201786994934082,57.153682708740234,0.033918771087687094 +16.785085678100586,-12.203211784362793,57.143672943115234,0.03162544538748359 +16.784475326538086,-12.204486846923828,57.135623931884766,0.0338184836926924 +16.783483505249023,-12.20645809173584,57.12474822998047,0.051681445685132804 +16.781156539916992,-12.210949897766113,57.10861587524414,0.20058981684549232 +16.774818420410156,-12.222643852233887,57.05711364746094,0.3572590352062503 +16.764692306518555,-12.241003036499023,56.989341735839844,0.5318341704220869 +16.74893569946289,-12.26888656616211,56.902549743652344,0.7579708039475688 +16.728281021118164,-12.30461311340332,56.80794143676758,0.9692698243621931 +16.701784133911133,-12.349209785461426,56.712059020996094,1.2142815321770097 +16.668848037719727,-12.403146743774414,56.62358474731445,1.452081823470073 +16.630043029785156,-12.465572357177734,56.54001235961914,1.6251366656452306 +16.588279724121094,-12.531928062438965,56.464603424072266,1.7672393053181727 +16.542409896850586,-12.603763580322266,56.4022331237793,1.8986513379248773 +16.491497039794922,-12.682087898254395,56.362457275390625,2.025822187348691 +16.439546585083008,-12.760529518127441,56.35430908203125,2.1413737953011096 +16.383197784423828,-12.84404182434082,56.38192367553711,2.2547009467021395 +16.3176326751709,-12.939775466918945,56.44908142089844,2.373912631714143 +16.251888275146484,-13.03498363494873,56.53865432739258,2.483214876567202 +16.188501358032227,-13.12667465209961,56.63320541381836,2.581090400261267 +16.11668586730957,-13.23095703125,56.73828125,2.6849575947751485 +16.047719955444336,-13.331762313842773,56.83168411254883,2.777111500568897 +15.970154762268066,-13.44582462310791,56.930625915527344,2.869125322575289 +15.894973754882812,-13.55681324005127,57.0269775390625,2.9229325986829435 +15.81848430633545,-13.669577598571777,57.14015579223633,2.8842352556051405 +15.749469757080078,-13.770475387573242,57.27330780029297,2.7755790951259227 +15.67214298248291,-13.88195514678955,57.473838806152344,2.6088798079489224 +15.605937004089355,-13.975869178771973,57.696353912353516,2.445806956402496 +15.54234790802002,-14.064655303955078,57.95939636230469,2.2796171658046536 +15.48145866394043,-14.148290634155273,58.261680603027344,2.115931706703945 +15.425150871276855,-14.224235534667969,58.59306716918945,1.9627958068263736 +15.374350547790527,-14.291474342346191,58.939979553222656,1.8242962904600002 +15.323796272277832,-14.357012748718262,59.33663558959961,1.687037197786131 +15.277729988098145,-14.41543960571289,59.746665954589844,1.5628149615705202 +15.23559284210205,-14.467748641967773,60.16520690917969,1.4501152643669457 +15.192293167114258,-14.520413398742676,60.63895034790039,1.335701607777326 +15.154205322265625,-14.566102027893066,61.087318420410156,1.2364681251834384 +15.11755657196045,-14.609782218933105,61.542266845703125,1.141489698020759 +15.08466911315918,-14.648842811584473,61.96953201293945,1.0565546212486931 +15.056265830993652,-14.682591438293457,62.35064697265625,0.9835913139258451 +15.028535842895508,-14.715804100036621,62.729034423828125,0.9125245268779811 +15.003226280212402,-14.746504783630371,63.0773811340332,0.8470612312374056 +14.978696823120117,-14.776634216308594,63.417442321777344,0.7831364645855967 +14.956400871276855,-14.80443000793457,63.72744369506836,0.7246102447106415 +14.936746597290039,-14.829310417175293,64.00032043457031,0.6724981351684811 +14.918715476989746,-14.852466583251953,64.25018310546875,0.6242184206780096 +14.901060104370117,-14.875447273254395,64.49462890625,0.5764843370384798 +14.885371208190918,-14.896109580993652,64.71210479736328,0.5337183081229081 +14.870891571044922,-14.915353775024414,64.91322326660156,0.4939507914934426 +14.858454704284668,-14.932002067565918,65.08686828613281,0.4595936555428422 +14.845940589904785,-14.948833465576172,65.26283264160156,0.42489009309840897 +14.834895133972168,-14.963749885559082,65.41934204101562,0.39423569298267047 +14.824044227600098,-14.978482246398926,65.5738754272461,0.36399891548846625 +14.814797401428223,-14.991072654724121,65.70651245117188,0.3381142886474495 +14.805495262145996,-15.003748893737793,65.8414535522461,0.3120591065690827 +14.797249794006348,-15.01500129699707,65.96231842041016,0.2889559937330977 +14.789767265319824,-15.025221824645996,66.07279968261719,0.2680066462662445 +14.782716751098633,-15.03488826751709,66.1773452758789,0.24822953357649244 +14.775945663452148,-15.044206619262695,66.27812957763672,0.2291700760195306 +14.769893646240234,-15.0525541305542,66.36834716796875,0.21208755686560932 +14.764456748962402,-15.060084342956543,66.44962310791016,0.19671381046874775 +14.759743690490723,-15.066670417785645,66.52396392822266,0.17979298413612757 +14.7551908493042,-15.072938919067383,66.5859375,0.13351969692879512 +14.752056121826172,-15.077287673950195,66.6373519897461,0.10555042069104467 +14.749485969543457,-15.080781936645508,66.67330932617188,0.083754903176033 +14.747249603271484,-15.083807945251465,66.70344543457031,0.0907404134465512 +14.744583129882812,-15.087590217590332,66.73921203613281,0.11352756095292328 +14.741791725158691,-15.091445922851562,66.780517578125,0.08494030872554557 +14.739108085632324,-15.095149040222168,66.82152557373047,0.10768442778300666 +14.736287117004395,-15.099146842956543,66.86795806884766,0.09775281082652972 +14.731959342956543,-15.105392456054688,66.94242858886719,0.2025478660921071 +14.726473808288574,-15.113176345825195,67.02386474609375,0.2175546408970213 +14.720097541809082,-15.122049331665039,67.1235580444336,0.22462250217930804 +14.71380615234375,-15.13084602355957,67.21702575683594,0.24504545996272528 +14.706271171569824,-15.141547203063965,67.335205078125,0.28223173706949395 +14.699284553527832,-15.15157413482666,67.44063568115234,0.3194589990874788 +14.689451217651367,-15.165749549865723,67.58460998535156,0.3454768548106699 +14.6802396774292,-15.17911434173584,67.73091125488281,0.38271536639503045 +14.67026424407959,-15.193565368652344,67.88831329345703,0.37508522721533266 +14.660453796386719,-15.207820892333984,68.0423583984375,0.3780052793655679 +14.650736808776855,-15.222052574157715,68.19396209716797,0.3806182715067777 +14.63633918762207,-15.24331283569336,68.41096496582031,0.4123489818994039 +14.62118148803711,-15.266066551208496,68.65477752685547,0.4710357604101715 +14.609376907348633,-15.2839994430542,68.83971405029297,0.472829783561149 +14.597107887268066,-15.302827835083008,69.03095245361328,0.46982730569596964 +14.58385181427002,-15.323534965515137,69.2379379272461,0.5644996246713372 +14.569084167480469,-15.346837043762207,69.46937561035156,0.6097958177343438 +14.555163383483887,-15.36893367767334,69.68858337402344,0.6101302606653689 +14.540677070617676,-15.392037391662598,69.9188003540039,0.5893344878879597 +14.526373863220215,-15.414948463439941,70.14871978759766,0.5575278371508382 +14.512873649597168,-15.436676979064941,70.3683853149414,0.521727207410298 +14.50095272064209,-15.455964088439941,70.56405639648438,0.4874162956218164 +14.48978042602539,-15.474180221557617,70.74818420410156,0.45385340188004925 +14.479782104492188,-15.490705490112305,70.91209411621094,0.4230547624149873 +14.469575881958008,-15.507943153381348,71.07677459716797,0.3908089394862641 +14.461079597473145,-15.522632598876953,71.21097564697266,0.3631845949627475 +14.453052520751953,-15.536699295043945,71.33683776855469,0.336417873906394 +14.445269584655762,-15.550341606140137,71.46044158935547,0.31027350606349935 +14.438715934753418,-15.561784744262695,71.56621551513672,0.2883644210092054 +14.43203353881836,-15.573465347290039,71.67488098144531,0.266183692992069 +14.426501274108887,-15.58322811126709,71.76421356201172,0.24774370169053428 +14.421056747436523,-15.592937469482422,71.85167694091797,0.22938534473527883 +14.416231155395508,-15.601591110229492,71.92909240722656,0.21298025260431533 +14.411741256713867,-15.609685897827148,72.0011215209961,0.19769958795246884 +14.407554626464844,-15.617307662963867,72.06784057617188,0.18338395819987247 +14.403444290161133,-15.624869346618652,72.13269805908203,0.16917191747153265 +14.399909019470215,-15.631404876708984,72.188232421875,0.15685462851408613 +14.396565437316895,-15.637608528137207,72.2408447265625,0.14517865467481694 +14.393446922302246,-15.643424034118652,72.28972625732422,0.1342615031069951 +14.390823364257812,-15.648343086242676,72.33056640625,0.1250415829622805 +14.388139724731445,-15.653421401977539,72.3722152709961,0.1155385682878115 +14.385712623596191,-15.658042907714844,72.40959167480469,0.10688811072846321 +14.383461952209473,-15.662368774414062,72.44371795654297,0.09882788346463296 +14.381427764892578,-15.666330337524414,72.47406768798828,0.09146039613449296 +14.379582405090332,-15.669974327087402,72.50110626220703,0.08470502863674718 +14.377978324890137,-15.673187255859375,72.52409362792969,0.07876302993042696 +14.37645149230957,-15.676300048828125,72.54537200927734,0.07302954298142665 +14.375027656555176,-15.679265022277832,72.56444549560547,0.06758201039945816 +14.37370777130127,-15.682072639465332,72.58145141601562,0.06243935567097018 +14.372539520263672,-15.684610366821289,72.59583282470703,0.05780524300490235 +14.371509552001953,-15.686896324157715,72.60781860351562,0.05364170048468824 +14.370505332946777,-15.689187049865723,72.61882781982422,0.04948443338863432 +14.36966323852539,-15.691157341003418,72.62741088867188,0.045910353539744396 +14.369476318359375,-15.691604614257812,72.62993621826172,0.0002668434587895797 +14.369476318359375,-15.691609382629395,72.62993621826172,5.576466616643291e-06 +14.369473457336426,-15.691612243652344,72.62993621826172,1.6406813882538335e-05 +14.36946964263916,-15.691615104675293,72.62993621826172,1.2766523688889618e-05 +14.369467735290527,-15.691617965698242,72.62993621826172,1.068320909918665e-05 +14.369464874267578,-15.691619873046875,72.62993621826172,9.119324739105178e-06 +14.369463920593262,-15.691621780395508,72.62993621826172,8.170089447195115e-06 +14.369462966918945,-15.691622734069824,72.62993621826172,5.65669129946727e-06 +14.369461059570312,-15.691624641418457,72.62993621826172,7.403391892678853e-06 +14.369460105895996,-15.691625595092773,72.62993621826172,3.7484459328145998e-06 +14.369460105895996,-15.691625595092773,72.62993621826172,5.690727298379992e-06 +14.369460105895996,-15.691625595092773,72.62993621826172,4.186840768998538e-06 +14.36945915222168,-15.69162654876709,72.62993621826172,6.225481199028474e-06 +14.36940860748291,-15.69168758392334,72.62615203857422,0.0036717568199727242 +14.369332313537598,-15.6918306350708,72.62571716308594,0.0033235829554635896 +14.369285583496094,-15.691991806030273,72.62836456298828,0.0044209325569770095 +14.369230270385742,-15.692183494567871,72.63069152832031,0.005275322804308767 +14.36906623840332,-15.69247055053711,72.6250228881836,0.00912892073516969 +14.368897438049316,-15.693029403686523,72.63372802734375,0.015790342623012387 +14.36854076385498,-15.69384479522705,72.6314926147461,0.03971616049280041 +14.367948532104492,-15.69547176361084,72.64295959472656,0.03625914988741832 +14.367258071899414,-15.697196960449219,72.64734649658203,0.036248481459084665 +14.366544723510742,-15.698946952819824,72.65272521972656,0.07352850433168895 +14.364421844482422,-15.70421314239502,72.67185974121094,0.14368710107962562 +14.36135482788086,-15.711798667907715,72.69937896728516,0.17077604941220578 +14.358420372009277,-15.719053268432617,72.72584533691406,0.17562508036604596 +14.355292320251465,-15.726784706115723,72.75404357910156,0.17149688143366243 +14.352360725402832,-15.734047889709473,72.78047180175781,0.1632579194940919 +14.349653244018555,-15.740761756896973,72.80492401123047,0.15362647638111018 +14.346942901611328,-15.747481346130371,72.8293685913086,0.1428905270666979 +14.34467601776123,-15.7531156539917,72.84988403320312,0.1334085604677794 +14.34239387512207,-15.758790016174316,72.87054443359375,0.12360301294187587 +14.340484619140625,-15.763541221618652,72.88787841796875,0.11526488200758513 +14.338510513305664,-15.768463134765625,72.90577697753906,0.1065586350526958 +14.336662292480469,-15.773073196411133,72.92230987548828,0.09836684991295334 +14.335097312927246,-15.776975631713867,72.93663787841797,0.07390583724906667 +14.334152221679688,-15.779333114624023,72.9456787109375,0.044805152731753575 +14.333565711975098,-15.780805587768555,72.95111083984375,0.027736533193823777 +14.333200454711914,-15.781725883483887,72.95420837402344,0.018008990191301297 +14.332944869995117,-15.782379150390625,72.95625305175781,0.011982680239541481 +14.332778930664062,-15.78281307220459,72.95683288574219,0.008637422947466939 +14.332659721374512,-15.783138275146484,72.95683288574219,0.0066155253857027455 +14.332560539245605,-15.783400535583496,72.95683288574219,0.005300151615799549 +14.332480430603027,-15.7836275100708,72.95683288574219,0.004333771056604306 +14.332477569580078,-15.783635139465332,72.95683288574219,1.5206141764114628e-05 +14.332476615905762,-15.783637046813965,72.95683288574219,1.0698295001859136e-05 +14.332475662231445,-15.783638954162598,72.95683288574219,5.806294313156639e-06 +14.332473754882812,-15.783639907836914,72.95683288574219,6.0644182562330764e-06 +14.332473754882812,-15.78364086151123,72.95683288574219,7.33919752794071e-06 +14.332472801208496,-15.783641815185547,72.95683288574219,6.983776274233495e-06 +14.332472801208496,-15.783641815185547,72.95683288574219,6.631670184012082e-06 +14.332475662231445,-15.783628463745117,72.95639038085938,0.010498892957905449 +14.33248519897461,-15.78365421295166,72.95857238769531,0.008058632311886006 +14.332507133483887,-15.783639907836914,72.95841979980469,0.00739633654761322 +14.332650184631348,-15.783236503601074,72.95402526855469,0.021605651866700794 +14.33299732208252,-15.782320022583008,72.950927734375,0.041314881770934925 +14.33377456665039,-15.780336380004883,72.94892883300781,0.06017674344889937 +14.335774421691895,-15.774946212768555,72.9249267578125,0.16002452539245263 +14.33903694152832,-15.766305923461914,72.89691162109375,0.26070136985056913 +14.344156265258789,-15.752772331237793,72.85369110107422,0.35298334777302237 +14.350822448730469,-15.73521900177002,72.7991714477539,0.47583559722900903 +14.359684944152832,-15.71207332611084,72.7311019897461,0.595856537082603 +14.371171951293945,-15.68221664428711,72.6449203491211,0.7187639665243876 +14.384242057800293,-15.648365020751953,72.54569244384766,0.8352553332864119 +14.399272918701172,-15.609634399414062,72.43333435058594,0.9594959429070486 +14.416547775268555,-15.565394401550293,72.30561065673828,1.0801416173109841 +14.437830924987793,-15.51125717163086,72.14948272705078,1.2053754727282693 +14.45978832244873,-15.455841064453125,71.99056243896484,1.3242696162173406 +14.483271598815918,-15.39702320098877,71.82189178466797,1.4389803540865485 +14.509477615356445,-15.332027435302734,71.64139556884766,1.552441746011509 +14.537410736083984,-15.263246536254883,71.44414520263672,1.6620284311376776 +14.574795722961426,-15.172211647033691,71.18602752685547,1.7765755182129808 +14.613587379455566,-15.078866958618164,70.92366790771484,1.8985129190353431 +14.648917198181152,-14.994709014892578,70.68487548828125,2.0109351992178714 +14.687994003295898,-14.902618408203125,70.42426300048828,2.1175760430480097 +14.728649139404297,-14.807950019836426,70.15655517578125,2.2136714047913166 +14.76777458190918,-14.717924118041992,69.90206146240234,2.2954688411355653 +14.815455436706543,-14.60959529876709,69.59552764892578,2.385401924942214 +14.861953735351562,-14.505385398864746,69.30057525634766,2.4658645615776944 +14.910676002502441,-14.397652626037598,68.99539184570312,2.544418769202398 +14.958934783935547,-14.292365074157715,68.69696044921875,2.6174180390502473 +15.009865760803223,-14.182745933532715,68.38591766357422,2.686474610848762 +15.064651489257812,-14.066478729248047,68.05565643310547,2.7462101366237524 +15.119644165039062,-13.951457023620605,67.72850036621094,2.7918057175787396 +15.180070877075195,-13.82695198059082,67.37359619140625,2.8082795349296097 +15.234455108642578,-13.71656322479248,67.05809783935547,2.7938621606049905 +15.291205406188965,-13.603008270263672,66.73262786865234,2.7628009216538287 +15.350163459777832,-13.486753463745117,66.3982162475586,2.721075237003295 +15.409262657165527,-13.371919631958008,66.06676483154297,2.67412140264118 +15.469709396362305,-13.25617790222168,65.73149871826172,2.6234322627595597 +15.523653984069824,-13.154297828674316,65.43523406982422,2.577136215919701 +15.577277183532715,-13.05431079864502,65.14334869384766,2.5307483000040345 +15.636629104614258,-12.945070266723633,64.82320404052734,2.4793853653626523 +15.691420555114746,-12.845535278320312,64.53032684326172,2.43215773244286 +15.740241050720215,-12.757888793945312,64.27149200439453,2.390325931359091 +15.799660682678223,-12.652480125427246,63.958980560302734,2.339783730144461 +15.852992057800293,-12.559069633483887,63.68009567260742,2.2947623510700765 +15.902629852294922,-12.473196983337402,63.42007827758789,2.253170279689373 +15.956798553466797,-12.380755424499512,63.134090423583984,2.2081629979824937 +16.010908126831055,-12.289862632751465,62.84310531616211,2.1635909398610345 +16.062864303588867,-12.204166412353516,62.55439376831055,2.1211582328866867 +16.095314025878906,-12.161252975463867,62.469364166259766,0.45114428158892017 +16.088592529296875,-12.17375373840332,62.52985763549805,0.25063889038228876 +16.083728790283203,-12.18136978149414,62.56673049926758,0.14462129091645218 +16.080793380737305,-12.18588638305664,62.59053039550781,0.08639902913161158 +16.078956604003906,-12.188663482666016,62.60628890991211,0.05421719589553989 +16.07773780822754,-12.190474510192871,62.61747741699219,0.03610600162463654 +16.07682991027832,-12.191807746887207,62.62654113769531,0.02529598701527004 +16.076223373413086,-12.19268798828125,62.632755279541016,0.019698937777684944 +16.075702667236328,-12.193429946899414,62.638145446777344,0.01604226783400715 +16.07525634765625,-12.194061279296875,62.643062591552734,0.01357143991358591 +16.074892044067383,-12.194571495056152,62.647098541259766,0.011546754538463752 +16.0745792388916,-12.19500732421875,62.65061569213867,0.009743363787914787 +16.074325561523438,-12.195356369018555,62.653533935546875,0.008232432648766275 +16.074100494384766,-12.195658683776855,62.65623092651367,0.006841102785132862 +16.07391357421875,-12.195910453796387,62.658565521240234,0.005609916985363306 +16.07376480102539,-12.196110725402832,62.66054916381836,0.004544955095001869 +16.073644638061523,-12.196267127990723,62.662296295166016,0.0036259164046942394 +16.073551177978516,-12.196389198303223,62.66386795043945,0.0028249420281317387 +16.07347869873047,-12.196484565734863,62.66489028930664,0.0021143126982974664 +16.07342529296875,-12.196553230285645,62.665138244628906,0.0014657725770515903 +16.07339096069336,-12.196599960327148,62.665138244628906,0.0009043239063293289 +16.07337188720703,-12.196626663208008,62.665138244628906,0.0004209152067094042 +16.0733642578125,-12.196635246276855,62.665138244628906,1.4223589946454331e-05 +16.0733642578125,-12.196635246276855,62.665138244628906,6.733949271441611e-06 +16.0733642578125,-12.196637153625488,62.665138244628906,6.609908722024038e-06 +16.073362350463867,-12.196638107299805,62.665138244628906,5.912100667838524e-06 +16.073362350463867,-12.196638107299805,62.665138244628906,5.8156083504670225e-06 +16.073362350463867,-12.196638107299805,62.665138244628906,4.884492954077335e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,4.599522379845279e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,3.460363891313188e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.034892610554261e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.0544899356617505e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.5092891547073235e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.392304173610219e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,4.69274786885839e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.117026500352396e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.31805408322137e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.246702871406503e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.335919695838279e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,4.841218473022327e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.439903206962049e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.523346066831604e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.583358915203611e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.575778259781631e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,3.9783686748473256e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.276316216949494e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.5076559479434085e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.687533544146015e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,3.27886914305161e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,4.9952127157862775e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.648757725489327e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.213813974093151e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.4396199937133106e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.778457656270444e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.456269326691276e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.86539296993623e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.766836038077738e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.505325029317561e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,4.426411954663426e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.114814964943516e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.355033363156177e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.585604743899978e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.53439363134565e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.070766367431326e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.3049845127359265e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,3.331072271849993e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.602327184833889e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.501336657598269e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.387087131551724e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.466711738697529e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,3.6858514746310663e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.6962972402284e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.410315181028564e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.5733710800814405e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.44855776117746e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.679167011754301e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,4.4786210029352e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.507407298507624e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.637056551595957e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.6457752655956155e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.340602013930219e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.1890919595794656e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.11814326989273e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.149393316794058e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.726109233602938e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,6.356601650568272e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.045831635686803e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.915292907343331e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.624329906506754e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.399909542503287e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.1753620231523995e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.459886905405485e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.257428568173117e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.450315735545264e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.207042948188985e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.232367077293988e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.56313033980199e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.173601490788341e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.762175976099029e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,5.422880322548329e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,5.283375778898415e-06 +16.073362350463867,-12.196639060974121,62.665138244628906,3.571398571317813e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.97191538798337e-06 +16.073362350463867,-12.196640014648438,62.665138244628906,4.674833475837525e-06 +16.07335662841797,-12.196700096130371,62.665069580078125,0.011614588647197409 +16.07333755493164,-12.196659088134766,62.6646728515625,0.009288321086729836 +16.073320388793945,-12.19684886932373,62.66313552856445,0.006564835252751703 +16.07330322265625,-12.197003364562988,62.661441802978516,0.01793992235023866 +16.073253631591797,-12.19736099243164,62.657447814941406,0.024862666451845383 +16.07314109802246,-12.197940826416016,62.649845123291016,0.007174756101872718 +16.072961807250977,-12.198915481567383,62.63699722290039,0.03475044345365534 +16.072734832763672,-12.200369834899902,62.61860275268555,0.0421632218439615 +16.07243537902832,-12.20230770111084,62.59392547607422,0.062455877782010276 +16.071773529052734,-12.205915451049805,62.546348571777344,0.09505950821254257 +16.070955276489258,-12.210472106933594,62.490257263183594,0.10422448053289739 +16.06964874267578,-12.217704772949219,62.396644592285156,0.2384106181103062 +16.06754493713379,-12.229724884033203,62.240394592285156,0.27580605439263445 +16.06548500061035,-12.242096900939941,62.07610321044922,0.29251999024684416 +16.062536239624023,-12.258270263671875,61.86324691772461,0.3872652275121727 +16.059484481811523,-12.275287628173828,61.63718032836914,0.388808105731092 +16.056072235107422,-12.293940544128418,61.38816452026367,0.43848120134767105 +16.05205726623535,-12.31449031829834,61.117088317871094,0.5266391026161193 +16.046875,-12.340760231018066,60.773948669433594,0.6041087889726624 +16.041120529174805,-12.369708061218262,60.39268112182617,0.6458677677528641 +16.03501319885254,-12.399332046508789,60.00396728515625,0.7140813878269213 +16.02800941467285,-12.431988716125488,59.575462341308594,0.7857625818415599 +16.019390106201172,-12.4707612991333,59.064632415771484,0.8501934355400002 +16.01087188720703,-12.507669448852539,58.57705307006836,0.889112189354012 +16.000213623046875,-12.551911354064941,57.992149353027344,0.9504789360963151 +15.989681243896484,-12.593697547912598,57.44004440307617,0.9966424413305058 +15.97803020477295,-12.63817024230957,56.850791931152344,1.037306696516286 +15.965715408325195,-12.683281898498535,56.252098083496094,1.0703562241576163 +15.95184326171875,-12.731757164001465,55.609886169433594,1.121309973237378 +15.936223983764648,-12.784269332885742,54.90818405151367,1.1561724811125043 +15.921700477600098,-12.831125259399414,54.28656768798828,1.1756083004991607 +15.903517723083496,-12.887269973754883,53.529945373535156,1.2312789166785945 +15.885608673095703,-12.940155982971191,52.8177490234375,1.2732303333452342 +15.866137504577637,-12.995345115661621,52.07006072998047,1.3048809677728594 +15.845126152038574,-13.052517890930176,51.29182815551758,1.3336795324231399 +15.823504447937012,-13.109009742736816,50.521671295166016,1.3638409265156985 +15.800198554992676,-13.167497634887695,49.723060607910156,1.382239278368383 +15.777270317077637,-13.222844123840332,48.96434783935547,1.3961677023496715 +15.750481605529785,-13.284998893737793,48.10445785522461,1.4260532274305773 +15.724093437194824,-13.34383487701416,47.28449630737305,1.4467556625655154 +15.696361541748047,-13.403426170349121,46.450748443603516,1.4455418108622737 +15.668928146362305,-13.46020221710205,45.652740478515625,1.468201995786901 +15.637160301208496,-13.523538589477539,44.75274658203125,1.4937639435653185 +15.605255126953125,-13.584728240966797,43.87738037109375,1.5171606082027647 +15.572111129760742,-13.645978927612305,42.99457931518555,1.5363894883472922 +15.538521766662598,-13.705863952636719,42.12374496459961,1.5557313075087489 +15.504584312438965,-13.764304161071777,41.267093658447266,1.5663415515374313 +15.465399742126465,-13.829411506652832,40.304534912109375,1.5787367464327622 +15.425590515136719,-13.893095016479492,39.3502311706543,1.59764095841647 +15.38830852508545,-13.950651168823242,38.480926513671875,1.6114461551945543 +15.346786499023438,-14.012615203857422,37.53343200683594,1.6266769643614205 +15.304953575134277,-14.072877883911133,36.60198974609375,1.641357886403709 +15.258692741394043,-14.13717269897461,35.5971794128418,1.6565703396843035 +15.214252471923828,-14.19676685333252,34.65347671508789,1.6684028587825044 +15.168228149414062,-14.256417274475098,33.7001838684082,1.671285872507126 +15.124439239501953,-14.311366081237793,32.809974670410156,1.6644238851679114 +15.07143783569336,-14.375640869140625,31.754680633544922,1.6726225272980908 +15.021894454956055,-14.433538436889648,30.788137435913086,1.693949754319882 +14.971962928771973,-14.489909172058105,29.834333419799805,1.7081209365034384 +14.916793823242188,-14.550090789794922,28.798521041870117,1.7224655534301696 +14.86363410949707,-14.606037139892578,27.820770263671875,1.7385983838684373 +14.807501792907715,-14.663119316101074,26.803857803344727,1.7418690399712662 +14.751370429992676,-14.71827220916748,25.80687713623047,1.7510360338842224 +14.692097663879395,-14.774434089660645,24.772863388061523,1.7669603688188253 +14.633171081542969,-14.828292846679688,23.76060676574707,1.7812163257081481 +14.57336711883545,-14.881044387817383,22.750680923461914,1.792967828876623 +14.510884284973145,-14.934229850769043,21.71013832092285,1.7951213551194571 +14.449124336242676,-14.984941482543945,20.69765853881836,1.803804933377173 +14.38410758972168,-15.036396026611328,19.647491455078125,1.7979867261751084 +14.319494247436523,-15.085674285888672,18.617225646972656,1.7852676397195455 +14.254107475280762,-15.133723258972168,17.588396072387695,1.767978493465154 +14.18482494354248,-15.182735443115234,16.51112174987793,1.726003772351269 +14.123111724853516,-15.22481632232666,15.560707092285156,1.6535906385310046 +14.06531810760498,-15.262944221496582,14.677058219909668,1.566042368488287 +14.006121635437012,-15.3007173538208,13.778496742248535,1.4654711987735316 +13.951774597167969,-15.334272384643555,12.959395408630371,1.3677244459612508 +13.90214729309082,-15.363985061645508,12.216322898864746,1.2759971662248373 +13.852431297302246,-15.392878532409668,11.476578712463379,1.1829448202340442 +13.808283805847168,-15.417819023132324,10.823431015014648,1.0999507369953159 +13.763275146484375,-15.442570686340332,10.161012649536133,1.0153413507394504 +13.724884986877441,-15.463146209716797,9.598809242248535,0.9433358277994747 +13.690105438232422,-15.48137092590332,9.091471672058105,0.8782789148133832 +13.656328201293945,-15.498692512512207,8.600682258605957,0.8153391336951099 +13.622812271118164,-15.515525817871094,8.115309715270996,0.7530919059257536 +13.592974662780762,-15.530210494995117,7.684637546539307,0.6978470877555089 +13.565774917602539,-15.543360710144043,7.293145179748535,0.6477148053634305 +13.54002571105957,-15.555596351623535,6.923506736755371,0.6003980128328475 +13.514448165893555,-15.567550659179688,6.557165622711182,0.5535155353159319 +13.493654251098633,-15.577128410339355,6.259964942932129,0.515509299931823 +13.472879409790039,-15.586566925048828,5.96358585357666,0.4776263686174335 +13.453975677490234,-15.59504508972168,5.694344520568848,0.44322645084135964 +13.437020301818848,-15.602560997009277,5.453201770782471,0.412419813700421 +13.414650917053223,-15.612343788146973,5.135560512542725,0.371773446310855 +13.399723052978516,-15.618791580200195,4.923918724060059,0.3447315598629293 +13.38510799407959,-15.625040054321289,4.717004776000977,0.3183298815202698 +13.372467041015625,-15.63039779663086,4.53819465637207,0.2955088373205002 +13.360654830932617,-15.63536262512207,4.371253967285156,0.2741979484251577 +13.349407196044922,-15.640054702758789,4.212480545043945,0.2539277732716978 +13.33879280090332,-15.644450187683105,4.0627875328063965,0.23479882190214682 +13.330119132995605,-15.64802074432373,3.9405622482299805,0.21917675929621006 +13.320595741271973,-15.651917457580566,3.806450605392456,0.2020285185367304 +13.312501907348633,-15.655200004577637,3.692883253097534,0.18750011605983513 +13.30470085144043,-15.658342361450195,3.583601474761963,0.17345222700420593 +13.297799110412598,-15.661108016967773,3.4869840145111084,0.16102448990363247 +13.291606903076172,-15.663579940795898,3.4003984928131104,0.14992344506145094 +13.285244941711426,-15.666061401367188,3.313288927078247,0.13873483695510874 +13.279284477233887,-15.668305397033691,3.2346231937408447,0.12830114580627694 +13.273974418640137,-15.670220375061035,3.1677355766296387,0.11902372828925321 +13.269472122192383,-15.671778678894043,3.113497018814087,0.1111655166677111 +13.264755249023438,-15.673344612121582,3.059279203414917,0.10294685095573355 +13.260163307189941,-15.67480182647705,3.009110689163208,0.09496437172900946 +13.256230354309082,-15.675992012023926,2.968414783477783,0.08814374148490765 +13.25231647491455,-15.677115440368652,2.9303085803985596,0.08141588078899334 +13.248854637145996,-15.67805004119873,2.8988654613494873,0.07546786081600486 +13.245452880859375,-15.678911209106445,2.8703930377960205,0.06965907628208581 +13.242546081542969,-15.679594039916992,2.8481709957122803,0.06470684578960034 +13.239607810974121,-15.680229187011719,2.82792329788208,0.05970659861219775 +13.236991882324219,-15.680747032165527,2.8118791580200195,0.055263844813025854 +13.235788345336914,-15.680965423583984,2.8040590286254883,0.0004974124004357783 +13.23577880859375,-15.680964469909668,2.804002046585083,0.0001841752906826257 +13.235774993896484,-15.680967330932617,2.804002046585083,7.144581285612829e-05 +13.235771179199219,-15.680971145629883,2.804002046585083,5.386200626478071e-06 +13.235767364501953,-15.680974960327148,2.804002046585083,1.9167094332432502e-05 +13.235763549804688,-15.680978775024414,2.804002046585083,1.1743701598923717e-05 +13.235761642456055,-15.68097972869873,2.804002046585083,1.0108113887002185e-05 +13.235758781433105,-15.68098258972168,2.804002046585083,7.40006744904893e-06 +13.235757827758789,-15.680983543395996,2.804002046585083,7.193740171947084e-06 +13.235756874084473,-15.680984497070312,2.804002046585083,5.038482118410792e-06 +13.23575496673584,-15.680984497070312,2.804002046585083,5.106105931610429e-06 +13.23575496673584,-15.680986404418945,2.804002046585083,5.158226498954455e-06 +13.235754013061523,-15.680986404418945,2.804002046585083,5.009970640700192e-06 +13.235754013061523,-15.680986404418945,2.804002046585083,4.670317913001119e-06 +13.235754013061523,-15.680987358093262,2.804002046585083,4.64829705761757e-06 +13.235754013061523,-15.680987358093262,2.804002046585083,4.548417973292761e-06 +13.235753059387207,-15.680987358093262,2.804002046585083,4.219471567885289e-06 +13.235753059387207,-15.680987358093262,2.804002046585083,4.13067601396277e-06 +13.235753059387207,-15.680987358093262,2.804002046585083,4.133755518881188e-06 +13.235753059387207,-15.680987358093262,2.804002046585083,4.36064772371793e-06 +13.235753059387207,-15.680987358093262,2.804002046585083,4.131492521427359e-06 +13.235753059387207,-15.680987358093262,2.804002046585083,4.061991363600108e-06 +13.235753059387207,-15.680987358093262,2.804002046585083,1.83824365103047e-06 +13.235762596130371,-15.680991172790527,2.8046815395355225,0.002912879596906295 +13.235957145690918,-15.680975914001465,2.8043301105499268,0.007746998709511191 +13.236441612243652,-15.680919647216797,2.8017306327819824,0.009090861258642207 +13.236844062805176,-15.680891990661621,2.8024141788482666,0.00417944425706978 +13.23709487915039,-15.680870056152344,2.802922010421753,0.00465150678979215 +13.236948013305664,-15.680874824523926,2.802922010421753,0.0030452883975208133 +13.23668384552002,-15.680889129638672,2.802582263946533,0.007444773988572787 +13.236377716064453,-15.680909156799316,2.802300214767456,0.007411740882352228 +13.2352294921875,-15.680984497070312,2.8014190196990967,0.024226836825261312 +13.234137535095215,-15.681053161621094,2.800570249557495,0.025495192987571975 +13.232841491699219,-15.681135177612305,2.7996573448181152,0.03395933041037455 +13.231416702270508,-15.681224822998047,2.798738956451416,0.03504560026735247 +13.229157447814941,-15.681365966796875,2.7974464893341064,0.0586417546102824 +13.226065635681152,-15.681562423706055,2.795741558074951,0.0667860977743709 +13.220852851867676,-15.681879997253418,2.7913591861724854,0.1662750571919896 +13.210623741149902,-15.682500839233398,2.7807693481445312,0.23070704121258592 +13.197182655334473,-15.68334674835205,2.7701799869537354,0.3021787431889986 +13.183966636657715,-15.68419075012207,2.760730266571045,0.30863749832819526 +13.167142868041992,-15.685256958007812,2.7493326663970947,0.3885816876150634 +13.146063804626465,-15.686591148376465,2.7346324920654297,0.5188417557452768 +13.121761322021484,-15.688111305236816,2.717723846435547,0.5522366766126572 +13.09701156616211,-15.689654350280762,2.7009472846984863,0.5814059119557484 +13.06762409210205,-15.691478729248047,2.6809990406036377,0.5964451120253 +13.03919792175293,-15.69323444366455,2.6617987155914307,0.654276507304762 +13.00636100769043,-15.695247650146484,2.639732837677002,0.7338622902473361 +12.970778465270996,-15.69741439819336,2.615875244140625,0.8103469229158463 +12.930378913879395,-15.69985580444336,2.588876485824585,0.8645404779233236 +12.888070106506348,-15.70239543914795,2.560593605041504,0.891467447037451 +12.844902992248535,-15.704957962036133,2.5320041179656982,0.9583579963693567 +12.799468994140625,-15.707629203796387,2.502140998840332,0.991815849718077 +12.75631332397461,-15.710150718688965,2.4736573696136475,0.9983190328576119 +12.70576286315918,-15.713065147399902,2.440755844116211,1.0568761632887556 +12.657005310058594,-15.715838432312012,2.4092085361480713,1.103929434916156 +12.603730201721191,-15.718836784362793,2.375046491622925,1.131127905548039 +12.548541069030762,-15.72189998626709,2.3399498462677,1.182163671278071 +12.491286277770996,-15.7250394821167,2.303758144378662,1.2186773590224833 +12.436158180236816,-15.728020668029785,2.26926589012146,1.2439528771808357 +12.375275611877441,-15.731268882751465,2.231457471847534,1.2786002291675918 +12.317291259765625,-15.734318733215332,2.1956496238708496,1.3103549558074614 +12.254939079284668,-15.737545013427734,2.1580166816711426,1.3099294051349921 +12.195096969604492,-15.74056339263916,2.1234383583068848,1.3337817417396316 +12.128812789916992,-15.743828773498535,2.086580276489258,1.3868022505921498 +12.065505027770996,-15.746892929077148,2.0519113540649414,1.4272763121731253 +11.994378089904785,-15.750269889831543,2.0138893127441406,1.4709937723315376 +11.925163269042969,-15.75348949432373,1.9776960611343384,1.5035021773400292 +11.849668502807617,-15.756942749023438,1.9386556148529053,1.5412775613614174 +11.776567459106445,-15.760231971740723,1.9010018110275269,1.586483218189877 +11.702679634094238,-15.763498306274414,1.8633736371994019,1.591045166327185 +11.625751495361328,-15.766838073730469,1.8247212171554565,1.6322199798118264 +11.549763679504395,-15.77006721496582,1.7874053716659546,1.6694262433286506 +11.47504997253418,-15.77318286895752,1.7510194778442383,1.7071605039512507 +11.394731521606445,-15.776477813720703,1.7119346857070923,1.7411989618951258 +11.310209274291992,-15.779886245727539,1.6708528995513916,1.7738229035527346 +11.23133659362793,-15.783012390136719,1.6325371265411377,1.8032828846525892 +11.140312194824219,-15.786553382873535,1.5883057117462158,1.8358917098624001 +11.05974006652832,-15.789629936218262,1.5492993593215942,1.8639243261351557 +10.971295356750488,-15.792943000793457,1.506402850151062,1.8936351264115103 +10.880960464477539,-15.796260833740234,1.462607502937317,1.9234191593424985 +10.789678573608398,-15.799541473388672,1.418375849723816,1.9531008129124048 +10.699381828308105,-15.802719116210938,1.3746470212936401,1.9818360189146311 +10.60749626159668,-15.805880546569824,1.3301740884780884,2.0105276989067584 +10.504196166992188,-15.80935001373291,1.2802056074142456,2.042402292037932 +10.417302131652832,-15.812200546264648,1.2381949424743652,2.0696263657899996 +10.284649848937988,-15.816428184509277,1.1739647388458252,2.097768100680266 +10.181794166564941,-15.81960391998291,1.1242384910583496,2.138380292526692 +10.08394718170166,-15.822550773620605,1.076609492301941,2.1735202927640187 +9.982295036315918,-15.825532913208008,1.0268617868423462,2.20655246582094 +9.876663208007812,-15.828544616699219,0.9749924540519714,2.2396374600291384 +9.772294998168945,-15.831427574157715,0.9237580895423889,2.271271353120216 +9.667041778564453,-15.834242820739746,0.8721196055412292,2.3025900433469975 +9.556004524230957,-15.83710765838623,0.8176798820495605,2.3352864080954023 +9.45502758026123,-15.839619636535645,0.7682029008865356,2.3646052450850044 +9.335298538208008,-15.842488288879395,0.7095679640769958,2.3950476695806713 +9.229386329650879,-15.84493350982666,0.6571967005729675,2.4076420213133947 +9.11229419708252,-15.847626686096191,0.5945696830749512,2.391525197742895 +8.995615005493164,-15.850372314453125,0.523956835269928,2.3439981206771416 +8.89885139465332,-15.852643966674805,0.46147632598876953,2.2984426048621236 +8.789321899414062,-15.855104446411133,0.39033979177474976,2.266256283916027 +8.678877830505371,-15.857409477233887,0.32046088576316833,2.257369733638593 +8.572530746459961,-15.859481811523438,0.2557937800884247,2.2608728566393994 +8.460688591003418,-15.8613920211792,0.19033993780612946,2.274840656695852 +8.356741905212402,-15.862981796264648,0.13175302743911743,2.291835073293143 +8.252737998962402,-15.864501953125,0.07481562346220016,2.3000728885960444 +8.142855644226074,-15.865968704223633,0.015066070482134819,2.298334400899251 +8.027626991271973,-15.86737060546875,-0.047515869140625,2.3003166264035606 +7.924993515014648,-15.868501663208008,-0.10302734375,2.3129069471448624 +7.812838554382324,-15.869616508483887,-0.1633911281824112,2.332478143227794 +7.707979679107666,-15.870536804199219,-0.219024658203125,2.3522887850840943 +7.595803737640381,-15.871426582336426,-0.277008056640625,2.373107519053667 +7.483389854431152,-15.872088432312012,-0.334259033203125,2.3948134823340803 +7.371676921844482,-15.872602462768555,-0.3908080756664276,2.4165051393030454 +7.255465984344482,-15.8731050491333,-0.449554443359375,2.4376045970924225 +7.139825820922852,-15.87348461151123,-0.5080260634422302,2.457021811486769 +7.024396896362305,-15.873733520507812,-0.5663452744483948,2.4754172096309075 +6.904626846313477,-15.873867988586426,-0.6270446181297302,2.493588567565045 +6.790567874908447,-15.873885154724121,-0.685272216796875,2.510062868969739 +6.663830280303955,-15.873793601989746,-0.7510071396827698,2.527454373721044 +6.5458550453186035,-15.87362289428711,-0.814300537109375,2.542809122598913 +6.433313846588135,-15.873414039611816,-0.8778381943702698,2.5567500048346927 +6.31605339050293,-15.87316608428955,-0.9486083388328552,2.570572462101283 +6.19893741607666,-15.87292766571045,-1.0259703397750854,2.5836962342543024 +6.071568012237549,-15.872735023498535,-1.1207886934280396,2.597224444988004 +5.947455883026123,-15.872697830200195,-1.228485107421875,2.6092782329998916 +5.830316543579102,-15.8728666305542,-1.3481138944625854,2.606867821958401 +5.716017723083496,-15.873296737670898,-1.485870361328125,2.5622549042992464 +5.594943523406982,-15.874159812927246,-1.658843755722046,2.465882753205982 +5.477477073669434,-15.875253677368164,-1.856567144393921,2.3262292641793034 +5.374995708465576,-15.876514434814453,-2.057067632675171,2.182842086216225 +5.278562068939209,-15.878124237060547,-2.272766351699829,2.037677207938086 +5.180367946624756,-15.880046844482422,-2.520935535430908,1.8837235418663905 +5.0946784019470215,-15.881941795349121,-2.761475086212158,1.74634095256079 +5.020932674407959,-15.883697509765625,-2.985840320587158,1.6267814229402853 +4.945479869842529,-15.885543823242188,-3.230102777481079,1.5036616678902985 +4.878505706787109,-15.887173652648926,-3.4577646255493164,1.3940400129451462 +4.819100379943848,-15.888561248779297,-3.666656732559204,1.29668630688731 +4.759559631347656,-15.889840126037598,-3.8804638385772705,1.1990515030553812 +4.704929828643799,-15.890900611877441,-4.078187942504883,1.1097674994988735 +4.6543707847595215,-15.891630172729492,-4.260744094848633,1.027281172956593 +4.607577323913574,-15.892118453979492,-4.427919387817383,0.9505701272438105 +4.566047191619873,-15.89238166809082,-4.573488712310791,0.8825215161177301 +4.527531147003174,-15.892409324645996,-4.703371524810791,0.8195413288721891 +4.491095066070557,-15.892159461975098,-4.818026065826416,0.7600658717931558 +4.455532073974609,-15.891533851623535,-4.917879581451416,0.7016331476956013 +4.42526912689209,-15.89068603515625,-4.989748477935791,0.6521838179285867 +4.395143508911133,-15.889404296875,-5.045625686645508,0.6030860135017397 +4.369514465332031,-15.88793659210205,-5.078676700592041,0.5612730981559022 +4.343354225158691,-15.88604736328125,-5.097079277038574,0.4898527354244062 +4.325790882110596,-15.884488105773926,-5.097628116607666,0.2882046572679554 +4.315518379211426,-15.883544921875,-5.096958160400391,0.19010604689800412 +4.308674335479736,-15.882821083068848,-5.092440605163574,0.1543691076688901 +4.302209854125977,-15.882038116455078,-5.084261894226074,0.12198233956675218 +4.29675817489624,-15.88127613067627,-5.073488712310791,0.1011626965215596 +4.292511940002441,-15.88059139251709,-5.061373233795166,0.08029978091611766 +4.288654804229736,-15.879914283752441,-5.048311233520508,0.09663618475195952 +4.285068988800049,-15.87923526763916,-5.031191349029541,0.07034960336190203 +4.282241344451904,-15.878621101379395,-5.016695976257324,0.0607547849750883 +4.279757022857666,-15.878036499023438,-5.002841472625732,0.05325533042454919 +4.276998996734619,-15.877363204956055,-4.983736991882324,0.05246964079228098 +4.274694442749023,-15.876771926879883,-4.968844413757324,0.05210675397859983 +4.272110462188721,-15.876105308532715,-4.954256534576416,0.07529273808789745 +4.269058704376221,-15.87527084350586,-4.931155681610107,0.06697974450972219 +4.266546249389648,-15.874553680419922,-4.910768508911133,0.06462055758035472 +4.262589454650879,-15.87343978881836,-4.883485317230225,0.0844456682736014 +4.257739543914795,-15.87207317352295,-4.850832939147949,0.12169974387591034 +4.251957416534424,-15.870433807373047,-4.805788516998291,0.1408537556898767 +4.245316028594971,-15.86857795715332,-4.752321243286133,0.14934147604572307 +4.23883581161499,-15.866731643676758,-4.697664737701416,0.1511367239258645 +4.232461929321289,-15.864879608154297,-4.645143508911133,0.13287913838229043 +4.2268829345703125,-15.863277435302734,-4.598696708679199,0.13101823746571045 +4.217259883880615,-15.860575675964355,-4.517946243286133,0.24019152109051245 +4.205565929412842,-15.857248306274414,-4.41781759262085,0.2835242641835887 +4.191766738891602,-15.853429794311523,-4.299775123596191,0.33825773418251004 +4.174821376800537,-15.848702430725098,-4.159303665161133,0.429912258851206 +4.1531453132629395,-15.84267807006836,-3.9771130084991455,0.5004633869047711 +4.127618789672852,-15.835763931274414,-3.7567763328552246,0.6260470279143948 +4.098161220550537,-15.82774543762207,-3.5048224925994873,0.7069941039776628 +4.066486835479736,-15.819158554077148,-3.230011224746704,0.7923642984366531 +4.026369571685791,-15.808494567871094,-2.8834235668182373,0.8803607174603544 +3.9856457710266113,-15.797871589660645,-2.526824712753296,0.9764400502013493 +3.943437337875366,-15.78705883026123,-2.15478515625,1.047018144031653 +3.8936824798583984,-15.774636268615723,-1.7163084745407104,1.1379433740093285 +3.8398938179016113,-15.7615327835083,-1.2383116483688354,1.2096985054633171 +3.782273769378662,-15.747903823852539,-0.7233580946922302,1.2834919872754518 +3.7232940196990967,-15.73448657989502,-0.1971740573644638,1.3597987165939207 +3.655987501144409,-15.719806671142578,0.4043208360671997,1.4376909317883602 +3.590792655944824,-15.706277847290039,0.9836129546165466,1.4972229045944008 +3.5234718322753906,-15.693013191223145,1.5806090831756592,1.545224854159094 +3.452080011367798,-15.679719924926758,2.213701009750366,1.5907691666366826 +3.378185987472534,-15.666827201843262,2.867403745651245,1.6395530543851218 +3.303905487060547,-15.654738426208496,3.5225887298583984,1.6792531138701263 +3.2293691635131836,-15.643464088439941,4.17879581451416,1.7057025701961288 +3.151075601577759,-15.632513999938965,4.866770267486572,1.722738509589072 +3.062871217727661,-15.621326446533203,5.640682697296143,1.7642148192599372 +2.9839749336242676,-15.61235523223877,6.332156658172607,1.7926313283841746 +2.8972442150115967,-15.603582382202148,7.092445373535156,1.821589042807389 +2.818882942199707,-15.596651077270508,7.778557300567627,1.8464485064433254 +2.7084176540374756,-15.58850383758545,8.73027229309082,1.7679453930160576 +2.595679759979248,-15.582045555114746,9.709863662719727,1.8121916898603112 +2.510097026824951,-15.57874870300293,10.44446849822998,1.8899596818109456 +2.4188191890716553,-15.576704025268555,11.214792251586914,1.932631311626672 +2.330662250518799,-15.576000213623047,11.954400062561035,1.9571576981512624 +2.2523210048675537,-15.57629108428955,12.612156867980957,1.9724291885728513 +2.1469907760620117,-15.578022956848145,13.501903533935547,1.991633069197299 +2.0519604682922363,-15.58099365234375,14.303309440612793,2.011886645982795 +1.9586907625198364,-15.585189819335938,15.090819358825684,2.027335927480643 +1.8645728826522827,-15.590665817260742,15.887727737426758,2.0406921320872873 +1.7703734636306763,-15.59743595123291,16.686710357666016,2.0504505682666987 +1.6741708517074585,-15.605701446533203,17.503705978393555,2.0541372085302885 +1.5822782516479492,-15.614849090576172,18.286949157714844,2.0572612754317707 +1.485947847366333,-15.625645637512207,19.116050720214844,2.0657136570974695 +1.3990739583969116,-15.636260986328125,19.87948226928711,2.0751006947695765 +1.306161880493164,-15.648468971252441,20.71492576599121,2.086543766566459 +1.2041149139404297,-15.66308879852295,21.647829055786133,2.0999764381245463 +1.1054022312164307,-15.67873764038086,22.55525016784668,2.1130990932689353 +1.0100390911102295,-15.695368766784668,23.434125900268555,2.1234545943557546 +0.914609432220459,-15.713509559631348,24.315990447998047,2.1290714033893345 +0.8162124156951904,-15.733809471130371,25.228130340576172,2.1326497709140155 +0.7249283194541931,-15.754107475280762,26.07761573791504,2.135155472150374 +0.6244856119155884,-15.778076171875,27.015872955322266,2.137548489547828 +0.5277352929115295,-15.802813529968262,27.9233341217041,2.139636040115852 +0.42853844165802,-15.829882621765137,28.857967376708984,2.141166385929187 +0.3330579400062561,-15.857583045959473,29.761751174926758,2.141758931276588 +0.24319228529930115,-15.885157585144043,30.616348266601562,2.141932399534398 +0.1469232738018036,-15.916335105895996,31.536514282226562,2.1411236451063136 +0.052969302982091904,-15.948420524597168,32.439388275146484,2.139831511523168 +-0.0432196781039238,-15.982996940612793,33.369056701660156,2.1383640234441685 +-0.1363486498594284,-16.018165588378906,34.274436950683594,2.1369355913481995 +-0.23147791624069214,-16.05584144592285,35.204803466796875,2.1355139011390154 +-0.3253120481967926,-16.094776153564453,36.12841796875,2.1341647857629282 +-0.4060876667499542,-16.12972068786621,36.92835998535156,2.133048465836123 +-0.5041351318359375,-16.17395782470703,37.90589141845703,2.1317497476150815 +-0.5921111702919006,-16.215396881103516,38.78926467895508,2.130717349856721 +-0.6764912009239197,-16.25676918029785,39.64053726196289,2.1299794615813474 +-0.7700022459030151,-16.30459976196289,40.586971282958984,2.1291418145759913 +-0.8529235124588013,-16.348758697509766,41.43037414550781,2.1194364472817693 +-0.9368671178817749,-16.395017623901367,42.292747497558594,2.0734997960786523 +-1.0181176662445068,-16.4412784576416,43.136539459228516,1.9967496604136343 +-1.0942120552062988,-16.486019134521484,43.93414306640625,1.8922175418240503 +-1.1606940031051636,-16.526277542114258,44.63707733154297,1.784654566492935 +-1.232064962387085,-16.570831298828125,45.39695358276367,1.6586804815033893 +-1.2955994606018066,-16.611759185791016,46.07637405395508,1.5403099686051978 +-1.3514257669448853,-16.648786544799805,46.6734619140625,1.4331050309697486 +-1.4057583808898926,-16.685869216918945,47.25262451171875,1.3264730426609517 +-1.4522935152053833,-16.718494415283203,47.746543884277344,1.233802948807644 +-1.495595932006836,-16.74970054626465,48.20059585571289,1.1468492065872966 +-1.5380185842514038,-16.781190872192383,48.63711929321289,1.060366220760469 +-1.575098991394043,-16.80937957763672,49.014984130859375,0.9836195397057392 +-1.61198091506958,-16.83791160583496,49.39080810546875,0.9065475610535991 +-1.6435221433639526,-16.862640380859375,49.71391296386719,0.8402962792078011 +-1.672926425933838,-16.88595962524414,50.016780853271484,0.778324480464643 +-1.6977852582931519,-16.905895233154297,50.273494720458984,0.7258215747139313 +-1.7231900691986084,-16.926525115966797,50.53517150878906,0.6719950816422694 +-1.7469358444213867,-16.9460391998291,50.7794075012207,0.6213013573479641 +-1.7686986923217773,-16.964092254638672,51.0036735534668,0.5747231336773931 +-1.7884658575057983,-16.980670928955078,51.20671844482422,0.5322701683512395 +-1.805864930152893,-16.995410919189453,51.384883880615234,0.4947137305558167 +-1.8230990171432495,-17.010147094726562,51.56067657470703,0.45734958195919645 +-1.8387764692306519,-17.0236759185791,51.719993591308594,0.4232292611520255 +-1.8530704975128174,-17.036096572875977,51.86507034301758,0.3919702893370055 +-1.865567684173584,-17.04701042175293,51.992279052734375,0.36456958232500747 +-1.877798080444336,-17.057741165161133,52.11701583862305,0.3376931247228971 +-1.8893920183181763,-17.067956924438477,52.23572540283203,0.3121748327249013 +-1.8998892307281494,-17.077241897583008,52.34327697753906,0.2890129399188033 +-1.9093941450119019,-17.08568000793457,52.44091033935547,0.26801622141423137 +-1.9176523685455322,-17.093032836914062,52.525909423828125,0.24973693907212446 +-1.9257978200912476,-17.100305557250977,52.6098747253418,0.2316705568088154 +-1.93352472782135,-17.10722541809082,52.689720153808594,0.21449721309918576 +-1.9408531188964844,-17.11380958557129,52.76551818847656,0.19819353462259276 +-1.9471988677978516,-17.119524002075195,52.831214904785156,0.18404419625487523 +-1.9535397291183472,-17.12525177001953,52.89691925048828,0.16989021224161985 +-1.958025336265564,-17.12932014465332,52.9437141418457,0.10365480025395166 +-1.9607475996017456,-17.131803512573242,52.972076416015625,0.06482815933246244 +-1.9625438451766968,-17.133451461791992,52.99057388305664,0.04194402518977553 +-1.9637178182601929,-17.134521484375,53.00271987915039,0.02928353556831718 +-1.9646110534667969,-17.135332107543945,53.01202392578125,0.021699264694245532 +-1.9652389287948608,-17.13589859008789,53.018646240234375,0.017571518883035573 +-1.9658116102218628,-17.136411666870117,53.024662017822266,0.014681321366263482 +-1.966286301612854,-17.136838912963867,53.029727935791016,0.012584117130880727 +-1.96668541431427,-17.1372013092041,53.0340576171875,0.010756960821585629 +-1.9670088291168213,-17.137493133544922,53.03760528564453,0.009216262717804017 +-1.9673058986663818,-17.137760162353516,53.04093933105469,0.007732066212623043 +-1.9675570726394653,-17.137983322143555,53.0436897277832,0.006401326009225086 +-1.9677488803863525,-17.138158798217773,53.04584503173828,0.0053129894488103775 +-1.967918038368225,-17.138315200805664,53.047786712646484,0.004269949247301356 +-1.9680335521697998,-17.138418197631836,53.04914474487305,0.00348552417773616 +-1.9681463241577148,-17.138521194458008,53.05055618286133,0.002613289873845445 +-1.9682241678237915,-17.138593673706055,53.050785064697266,0.0019006298945465796 +-1.968276023864746,-17.138639450073242,53.05101013183594,0.0013053770871427686 +-1.9683034420013428,-17.138662338256836,53.05101013183594,7.449998964490356e-06 +-1.9683042764663696,-17.138662338256836,53.05101013183594,1.1144031465348617e-05 +-1.9683047533035278,-17.13866424560547,53.05101013183594,7.6169119604145736e-06 +-1.968304991722107,-17.13866424560547,53.05101013183594,4.9379536233858066e-06 +-1.9683047533035278,-17.13866424560547,53.05101013183594,4.824616809338465e-06 +-1.9683043956756592,-17.13866424560547,53.05101013183594,4.773786270362256e-06 +-1.9683042764663696,-17.13866424560547,53.05101013183594,4.137102289640936e-06 +-1.968279480934143,-17.13863182067871,53.050254821777344,0.011704688405320351 +-1.9680402278900146,-17.13837242126465,53.04588317871094,0.013461073493037025 +-1.9671529531478882,-17.13754653930664,53.03795623779297,0.05120262370569916 +-1.9654511213302612,-17.13597297668457,53.02079391479492,0.06876546526240683 +-1.96340012550354,-17.134105682373047,53.002586364746094,0.05995676276641919 +-1.9599498510360718,-17.130970001220703,52.970802307128906,0.12860545274085375 +-1.9544391632080078,-17.125961303710938,52.91206741333008,0.19052912931367894 +-1.9472863674163818,-17.11949348449707,52.839561462402344,0.22102312453583722 +-1.9378653764724731,-17.1109619140625,52.74434280395508,0.28678107906399375 +-1.9265788793563843,-17.10076141357422,52.62809753417969,0.3816415857353676 +-1.9123998880386353,-17.088050842285156,52.481014251708984,0.45482284458839684 +-1.8956587314605713,-17.073209762573242,52.30520248413086,0.4873465980032662 +-1.8786089420318604,-17.058324813842773,52.12275695800781,0.5537142426222937 +-1.8579257726669312,-17.04047966003418,51.903350830078125,0.5854811462932197 +-1.8290653228759766,-17.015775680541992,51.60022735595703,0.5989671172603753 +-1.8067798614501953,-16.99692726135254,51.36612319946289,0.5976902504262102 +-1.7859216928482056,-16.979494094848633,51.14608383178711,0.5920578140130905 +-1.7646982669830322,-16.9619140625,50.92259979248047,0.5840565547903416 +-1.7448490858078003,-16.94557762145996,50.714927673339844,0.5753547667667112 +-1.7234641313552856,-16.928096771240234,50.492271423339844,0.5651333146475964 +-1.7042126655578613,-16.912485122680664,50.29182815551758,0.5568967386043343 +-1.686453938484192,-16.89817237854004,50.10450744628906,0.5140188552889627 +-1.6650680303573608,-16.8810977935791,49.8842658996582,0.5370863763068963 +-1.6457680463790894,-16.86572265625,49.68546676635742,0.6025829210522273 +-1.6229227781295776,-16.847482681274414,49.44792556762695,0.6912779131768803 +-1.5940560102462769,-16.824588775634766,49.152191162109375,0.8020532229583897 +-1.562751293182373,-16.80008316040039,48.835594177246094,0.9334580906296822 +-1.529806137084961,-16.77467155456543,48.500343322753906,1.0302389069293043 +-1.488130807876587,-16.74310302734375,48.07607650756836,1.1226663510303287 +-1.4420926570892334,-16.70881462097168,47.609474182128906,1.2470946632150057 +-1.394567847251892,-16.67403221130371,47.134979248046875,1.3506587523816764 +-1.3421087265014648,-16.63633155822754,46.61664962768555,1.4590291777267226 +-1.28468918800354,-16.595870971679688,46.048004150390625,1.5694320285831027 +-1.2213456630706787,-16.55220603942871,45.42512512207031,1.688261615067511 +-1.1542809009552002,-16.506975173950195,44.771724700927734,1.798213791348603 +-1.081837773323059,-16.459157943725586,44.07509994506836,1.8752885621883633 +-1.0118950605392456,-16.413951873779297,43.416343688964844,1.9018336806334033 +-0.9354369044303894,-16.365467071533203,42.71412658691406,1.9021749064507645 +-0.8638066053390503,-16.320789337158203,42.07566452026367,1.8877123759784598 +-0.7850404381752014,-16.2723331451416,41.397769927978516,1.8627488027130894 +-0.7164601683616638,-16.230621337890625,40.8293342590332,1.8365626865999356 +-0.6393921971321106,-16.184207916259766,40.2149772644043,1.8044137477193432 +-0.5690663456916809,-16.142139434814453,39.67982482910156,1.773880061413322 +-0.49645522236824036,-16.09876251220703,39.158443450927734,1.741757071846597 +-0.42955514788627625,-16.058738708496094,38.7078742980957,1.7115253610043832 +-0.35952460765838623,-16.0167293548584,38.26646423339844,1.6794101014642866 +-0.2956503629684448,-15.978302001953125,37.88948440551758,1.6498054392044985 +-0.23088239133358002,-15.939231872558594,37.53097915649414,1.6194586379781444 +-0.16798913478851318,-15.901267051696777,37.2016716003418,1.589656055227092 +-0.10714130848646164,-15.864615440368652,36.89643096923828,1.5606332091221518 +-0.04257788509130478,-15.825841903686523,36.58562469482422,1.5298442479677956 +0.01670399121940136,-15.79029655456543,36.313297271728516,1.501631807643484 +0.07794898003339767,-15.753582000732422,36.04588317871094,1.4721360545745843 +0.13724860548973083,-15.718009948730469,35.801578521728516,1.4297270810635048 +0.18785013258457184,-15.687544822692871,35.60454559326172,1.4107213627857764 +0.24449767172336578,-15.653213500976562,35.39536666870117,1.3855933341453859 +0.300571084022522,-15.619072914123535,35.204952239990234,1.3557932786670837 +0.3555499315261841,-15.585524559020996,35.03581619262695,1.3280748335516748 +0.4094303548336029,-15.55251693725586,34.87936019897461,1.310048603919089 +0.46151381731033325,-15.520491600036621,34.741390228271484,1.295335954889279 +0.5130450129508972,-15.48869514465332,34.61893844604492,1.282098040259186 +0.5623671412467957,-15.458086967468262,34.507930755615234,1.270534374276289 +0.611799955368042,-15.427287101745605,34.4105224609375,1.2596182124803181 +0.6600585579872131,-15.397074699401855,34.31938934326172,1.254210465604264 +0.7091273069381714,-15.366313934326172,34.234127044677734,1.2512108849685613 +0.76291424036026,-15.332590103149414,34.14934539794922,1.2496867506768494 +0.8102812767028809,-15.302736282348633,34.076332092285156,1.2587938478834697 +0.8607761859893799,-15.270583152770996,34.00909423828125,1.289159197431961 +0.9130858182907104,-15.236865997314453,33.965232849121094,1.3198213177546627 +0.9820202589035034,-15.191747665405273,33.934814453125,1.3684867480142575 +1.0353410243988037,-15.156344413757324,33.92815017700195,1.4137049450998074 +1.0872925519943237,-15.12142276763916,33.935794830322266,1.4558205745370731 +1.1472941637039185,-15.08057689666748,33.958797454833984,1.4986062006849143 +1.199302315711975,-15.044779777526855,33.994476318359375,1.52096899755581 +1.2602858543395996,-15.002372741699219,34.038475036621094,1.5287812191023513 +1.3218308687210083,-14.959147453308105,34.10493087768555,1.5211719179160794 +1.3805726766586304,-14.917437553405762,34.178279876708984,1.520123781736117 +1.4409027099609375,-14.874212265014648,34.264122009277344,1.491166921852714 +1.4933483600616455,-14.836320877075195,34.341251373291016,1.4743966073299009 +1.5462052822113037,-14.797882080078125,34.42717361450195,1.4524248149756127 +1.604273796081543,-14.755289077758789,34.530975341796875,1.4274150268800716 +1.6564421653747559,-14.716645240783691,34.63220977783203,1.4087395850802702 +1.70709228515625,-14.678787231445312,34.73699951171875,1.3723866721013713 +1.7578176259994507,-14.640573501586914,34.845008850097656,1.3626811644602437 +1.8097866773605347,-14.601202011108398,34.95661163330078,1.341011174059626 +1.8596177101135254,-14.56329345703125,35.063880920410156,1.3179352857852085 +1.9091203212738037,-14.52548885345459,35.170345306396484,1.2937247303617276 +1.957177996635437,-14.488651275634766,35.27376937866211,1.269496250323116 +2.005554676055908,-14.451425552368164,35.37812423706055,1.2446769909837765 +2.048381805419922,-14.418338775634766,35.47111892700195,1.2224737912947459 +2.0929176807403564,-14.383748054504395,35.57022476196289,1.1991714582475093 +2.137751340866089,-14.34862995147705,35.676082611083984,1.1754856637622992 +2.178213119506836,-14.316591262817383,35.77955627441406,1.1539611618731673 +2.2210168838500977,-14.282307624816895,35.897769927978516,1.131058172008766 +2.2630982398986816,-14.24817943572998,36.0234489440918,1.1084076733738673 +2.302612781524658,-14.215751647949219,36.14958190917969,1.0870662274213154 +2.341087818145752,-14.183853149414062,36.27834701538086,1.0662585884071143 +2.3779430389404297,-14.153047561645508,36.40549087524414,1.0463014970588742 +2.4139914512634277,-14.122700691223145,36.53251266479492,1.0267439462599661 +2.449371576309204,-14.09269905090332,36.6602783203125,1.0074627011275654 +2.4878830909729004,-14.059741020202637,36.80436325073242,0.9863517065272589 +2.5210838317871094,-14.03104019165039,36.93391036987305,0.9680564141627314 +2.5571537017822266,-13.999540328979492,37.080360412597656,0.9481068665355288 +2.5902867317199707,-13.970306396484375,37.220149993896484,0.929701304584319 +2.6225860118865967,-13.941548347473145,37.36048126220703,0.9117656989700247 +2.652238607406616,-13.914953231811523,37.49172592163086,0.8952340188317982 +2.6823458671569824,-13.88769245147705,37.62971115112305,0.8782563347292575 +2.7132790088653564,-13.859346389770508,37.77819061279297,0.8607510125813255 +2.743236541748047,-13.831618309020996,37.926414489746094,0.8438123240388595 +2.7714014053344727,-13.80534839630127,38.0681266784668,0.8279033810906213 +2.79667592048645,-13.781655311584473,38.195838928222656,0.8136299339457443 +2.8261590003967285,-13.75387954711914,38.34514236450195,0.7969459216229926 +2.8528127670288086,-13.728638648986816,38.48046112060547,0.7818317502986515 +2.879155397415161,-13.703577995300293,38.6145133972168,0.7668678212520954 +2.904317855834961,-13.67952823638916,38.7428092956543,0.7525514116534564 +2.928915023803711,-13.655920028686523,38.86830139160156,0.7385319956590948 +2.9530739784240723,-13.63262939453125,38.991878509521484,0.724737029181384 +2.9789602756500244,-13.60755729675293,39.12460708618164,0.7099287210993028 +3.000460147857666,-13.586636543273926,39.23533630371094,0.697595037211673 +3.02364444732666,-13.563966751098633,39.355716705322266,0.6842384257232281 +3.0466580390930176,-13.541314125061035,39.47722244262695,0.6709188068939951 +3.068272590637207,-13.519888877868652,39.59352493286133,0.6583627400145378 +3.0906364917755127,-13.49757194519043,39.71580505371094,0.6453598203405148 +3.107536554336548,-13.480618476867676,39.809261322021484,0.6355289435889712 +3.1296145915985107,-13.458366394042969,39.932193756103516,0.6226696637494012 +3.150850772857666,-13.436851501464844,40.051292419433594,0.6102722131435421 +3.1713016033172607,-13.416041374206543,40.166561126708984,0.598326479628984 +3.191096067428589,-13.395809173583984,40.27854919433594,0.5867482872692504 +3.2096807956695557,-13.376740455627441,40.384063720703125,0.5758657844912496 +3.229065179824829,-13.356772422790527,40.49439239501953,0.5644989121893416 +3.2460005283355713,-13.339263916015625,40.59104537963867,0.554554680174957 +3.2640883922576904,-13.320496559143066,40.69442367553711,0.5439210610022371 +3.281827211380005,-13.30202865600586,40.79607391357422,0.5334784024698187 +3.2980775833129883,-13.28504753112793,40.88943099975586,0.5239004489404177 +3.316039562225342,-13.266214370727539,40.99296188354492,0.5133013121331432 +3.331878185272217,-13.249540328979492,41.08441162109375,0.43878921382032937 +3.3413569927215576,-13.23946762084961,41.139610290527344,0.24342385889505153 +3.3469009399414062,-13.233585357666016,41.17258071899414,0.1284603368902285 +3.349914789199829,-13.230368614196777,41.191261291503906,0.06804523335363076 +3.351491689682007,-13.228677749633789,41.201133728027344,0.03904366215359674 +3.352437973022461,-13.227659225463867,41.20712661743164,0.02287663242861576 +3.3529934883117676,-13.227057456970215,41.21062469482422,0.013459366011458982 +3.353346824645996,-13.226675987243652,41.21287155151367,0.007660082775698938 +3.3535354137420654,-13.226469039916992,41.21412658691406,0.00468599389247026 +3.353660821914673,-13.226329803466797,41.2150993347168,0.0028785786366728053 +3.3537378311157227,-13.226245880126953,41.215736389160156,0.001919853654558582 +3.353797197341919,-13.226180076599121,41.2161979675293,0.0013178899838487208 +3.353837251663208,-13.226136207580566,41.21631622314453,0.0010208049294899324 +3.353870153427124,-13.226099967956543,41.21631622314453,0.0008639025774209971 +3.3538994789123535,-13.226066589355469,41.21631622314453,0.0007859765710966286 +3.35392689704895,-13.226036071777344,41.21631622314453,0.0007491770994819964 +3.3539514541625977,-13.226006507873535,41.21631622314453,0.0007388327399359799 +3.353976249694824,-13.225979804992676,41.21631622314453,0.0007403251693696251 +3.354132890701294,-13.225839614868164,41.21847915649414,0.01380799811578937 +3.354224681854248,-13.22575855255127,41.21826171875,0.011056725985175861 +3.3542556762695312,-13.225730895996094,41.219268798828125,0.015518302290235455 +3.354271411895752,-13.225712776184082,41.21872329711914,0.010394236105149158 +3.3543002605438232,-13.225691795349121,41.219383239746094,0.00899816398360508 +3.3544228076934814,-13.225616455078125,41.22260284423828,0.002311773690832048 +3.3542702198028564,-13.225748062133789,41.22342300415039,0.002777547230015755 +3.3540902137756348,-13.22590446472168,41.22410202026367,0.009892298911517317 +3.3537309169769287,-13.226198196411133,41.22524642944336,0.012748422529861067 +3.3526577949523926,-13.227034568786621,41.228904724121094,0.04300147508549767 +3.3512678146362305,-13.228095054626465,41.23377227783203,0.037635193296739665 +3.349282741546631,-13.229496002197266,41.24367904663086,0.05766427275331097 +3.347280263900757,-13.2308931350708,41.25542449951172,0.050553056097063134 +3.3447322845458984,-13.232688903808594,41.27201843261719,0.06439795104791105 +3.3425254821777344,-13.234176635742188,41.2856330871582,0.08836448573301818 +3.3392083644866943,-13.236364364624023,41.30815505981445,0.08749274527672037 +3.3353686332702637,-13.238850593566895,41.33820724487305,0.0939464749344278 +3.3310649394989014,-13.24165153503418,41.36980056762695,0.11859746339655912 +3.32594633102417,-13.244959831237793,41.40922927856445,0.13801550069924656 +3.317734718322754,-13.250118255615234,41.474853515625,0.2649781320183132 +3.306643486022949,-13.256986618041992,41.563011169433594,0.2893091409911444 +3.2937145233154297,-13.264982223510742,41.66628646850586,0.3525227020499099 +3.2783079147338867,-13.274479866027832,41.80007553100586,0.4404329526464109 +3.2624053955078125,-13.28415584564209,41.94480895996094,0.4385720964804643 +3.2437736988067627,-13.295413970947266,42.11241912841797,0.4318445172909014 +3.224677562713623,-13.307079315185547,42.28678894042969,0.543272926998012 +3.200623035430908,-13.321895599365234,42.50589370727539,0.6657563117315944 +3.173755645751953,-13.338560104370117,42.74811935424805,0.726157185961939 +3.14374041557312,-13.357318878173828,43.0208740234375,0.8033996494907146 +3.1093709468841553,-13.37901782989502,43.33436584472656,0.8574387084223494 +3.074768543243408,-13.401098251342773,43.65132522583008,0.9023968181976452 +3.0374815464019775,-13.425166130065918,43.9937629699707,0.9689644446095801 +2.9984359741210938,-13.450701713562012,44.353939056396484,1.017870087934511 +2.9583306312561035,-13.47727108001709,44.7253532409668,1.0431721313453444 +2.9206864833831787,-13.50252628326416,45.07691192626953,1.0354956378418294 +2.8791582584381104,-13.53080940246582,45.467369079589844,1.0326613524485118 +2.8408620357513428,-13.55724048614502,45.82904052734375,0.993964893352331 +2.8076422214508057,-13.580439567565918,46.14412307739258,0.9454511135520299 +2.769362688064575,-13.60750961303711,46.50840377807617,0.8796954553455186 +2.738981008529663,-13.629256248474121,46.79841613769531,0.8229878294845189 +2.709615468978882,-13.650506019592285,47.079559326171875,0.7658549283597639 +2.681534767150879,-13.67105484008789,47.34878158569336,0.7098712569122445 +2.6538197994232178,-13.691548347473145,47.61500549316406,0.6537062264469752 +2.6319665908813477,-13.707855224609375,47.82558059692383,0.6090106753815173 +2.6102349758148193,-13.724202156066895,48.03547286987305,0.5642915221284598 +2.589980125427246,-13.739554405212402,48.2317008972168,0.5224110242214892 +2.570868968963623,-13.754143714904785,48.417236328125,0.4827852237160003 +2.553914785385132,-13.767195701599121,48.58161163330078,0.4475194321916727 +2.539275646209717,-13.778538703918457,48.72359085083008,0.4169515187312005 +2.5241549015045166,-13.790328025817871,48.87202072143555,0.37721087502368345 +2.512251853942871,-13.799548149108887,48.98038864135742,0.30366024918549106 +2.5024430751800537,-13.807188034057617,49.0739860534668,0.24916606424093196 +2.49363112449646,-13.814131736755371,49.16486358642578,0.2161963112046253 +2.485325574874878,-13.820657730102539,49.24287414550781,0.2200315186688657 +2.477266550064087,-13.827011108398438,49.32185745239258,0.22560518217093992 +2.469388723373413,-13.833209991455078,49.39990234375,0.21441783957524302 +2.4610509872436523,-13.83986759185791,49.484413146972656,0.2464974625989224 +2.4490349292755127,-13.849628448486328,49.605628967285156,0.36298923014906637 +2.434518814086914,-13.861425399780273,49.74988555908203,0.42908228404432075 +2.417473793029785,-13.875327110290527,49.91676330566406,0.5138319966747097 +2.3982768058776855,-13.891070365905762,50.106300354003906,0.5593772989361203 +2.377372980117798,-13.908273696899414,50.312686920166016,0.6103735023078539 +2.354564666748047,-13.927199363708496,50.537872314453125,0.6700167840581817 +2.3298704624176025,-13.947834968566895,50.78373336791992,0.7115726051601607 +2.306699514389038,-13.96732234954834,51.017234802246094,0.7464862764259353 +2.277466297149658,-13.992172241210938,51.311492919921875,0.791093512437129 +2.247831106185913,-14.017637252807617,51.610843658447266,0.8485806801996066 +2.217451333999634,-14.044026374816895,51.91943359375,0.8935117408886546 +2.1849472522735596,-14.07248592376709,52.2529296875,0.9270217971657845 +2.150883197784424,-14.102697372436523,52.602779388427734,0.9957965607991766 +2.117940664291382,-14.132256507873535,52.942840576171875,1.0531490365780092 +2.0827980041503906,-14.164121627807617,53.30815887451172,1.0673172336712708 +2.045628786087036,-14.19832706451416,53.69403839111328,1.1251236234326971 +2.006452798843384,-14.234891891479492,54.104652404785156,1.180913190586041 +1.9665195941925049,-14.272706031799316,54.52530288696289,1.225962952663933 +1.9227131605148315,-14.314817428588867,54.98995590209961,1.2702583693378022 +1.8795751333236694,-14.35694694519043,55.45072555541992,1.2851937002674731 +1.836718201637268,-14.399454116821289,55.91327667236328,1.2844416072810787 +1.7966588735580444,-14.439742088317871,56.35131072998047,1.2516234073905745 +1.7539888620376587,-14.483372688293457,56.820438385009766,1.2174697534339294 +1.7152093648910522,-14.523698806762695,57.251075744628906,1.2004805124751559 +1.6796996593475342,-14.561220169067383,57.65037155151367,1.1679362349500262 +1.6414304971694946,-14.602282524108887,58.07977294921875,1.1278273909355028 +1.6059409379959106,-14.641010284423828,58.479488372802734,1.076287953065864 +1.5654436349868774,-14.68610954284668,58.932762145996094,1.0462021287253844 +1.5334588289260864,-14.72227954864502,59.292091369628906,0.9933857690990822 +1.5028324127197266,-14.757329940795898,59.638694763183594,0.9303849297938976 +1.475422978401184,-14.789053916931152,59.95121765136719,0.8679470279103872 +1.4513328075408936,-14.817225456237793,60.22766876220703,0.8101113822229228 +1.4284549951553345,-14.844239234924316,60.49181365966797,0.7535163049571137 +1.4050397872924805,-14.872176170349121,60.763423919677734,0.6944514826252599 +1.3860955238342285,-14.895028114318848,60.983375549316406,0.6460324235846067 +1.3673462867736816,-14.91787338256836,61.20137405395508,0.597566377264589 +1.3508243560791016,-14.93817138671875,61.39409637451172,0.5545074472053774 +1.3354538679122925,-14.957180976867676,61.57418441772461,0.5142377786526887 +1.3206088542938232,-14.975655555725098,61.74903106689453,0.47516204110833393 +1.3081449270248413,-14.991242408752441,61.89673614501953,0.44221039587482663 +1.2952033281326294,-15.007442474365234,62.052215576171875,0.4077878991669307 +1.2834957838058472,-15.022001266479492,62.196834564208984,0.3765905318934109 +1.273160696029663,-15.034733772277832,62.32851791381836,0.34926938774464267 +1.2641584873199463,-15.04578971862793,62.44499969482422,0.3257723186705975 +1.2550286054611206,-15.057065963745117,62.5629997253418,0.3019329458745277 +1.246325135231018,-15.067902565002441,62.67494583129883,0.2790669982143329 +1.238640308380127,-15.077545166015625,62.77342987060547,0.2587319496803458 +1.2311896085739136,-15.086953163146973,62.8686637878418,0.23892415079661905 +1.2248209714889526,-15.095043182373047,62.94985580444336,0.22189247832801154 +1.2189044952392578,-15.102579116821289,63.02547836303711,0.20600482405155587 +1.21314537525177,-15.109930992126465,63.09934616088867,0.19052640319985126 +1.207870364189148,-15.11671257019043,63.16960906982422,0.16300560489965663 +1.2037341594696045,-15.121994018554688,63.22518539428711,0.13292781554296929 +1.2008293867111206,-15.125682830810547,63.264896392822266,0.11001817105440709 +1.1982285976409912,-15.128995895385742,63.29570007324219,0.07799107975210152 +1.1961934566497803,-15.131633758544922,63.32288360595703,0.05657350859112126 +1.1942272186279297,-15.134187698364258,63.34782791137695,0.07410560612291965 +1.1918599605560303,-15.137247085571289,63.37783432006836,0.08519238343821785 +1.189839482307434,-15.139901161193848,63.40324783325195,0.0703099798433707 +1.1877986192703247,-15.14255428314209,63.428890228271484,0.0658165375356141 +1.1859886646270752,-15.144936561584473,63.449832916259766,0.08929545170424309 +1.183126449584961,-15.148666381835938,63.48579788208008,0.11532240076624907 +1.1797608137130737,-15.153206825256348,63.53261184692383,0.12632329864952066 +1.1766082048416138,-15.157353401184082,63.573970794677734,0.12174069303346083 +1.1714338064193726,-15.164177894592285,63.64741516113281,0.20974058001153126 +1.165223479270935,-15.172344207763672,63.724937438964844,0.2465254287539808 +1.1568398475646973,-15.183582305908203,63.83464431762695,0.36399618556135827 +1.1461304426193237,-15.197894096374512,63.97917938232422,0.43879505611286773 +1.1311893463134766,-15.218019485473633,64.1755142211914,0.5616673499001223 +1.1147273778915405,-15.240042686462402,64.39350128173828,0.6645318701428301 +1.095450758934021,-15.265849113464355,64.65145111083984,0.705464835888868 +1.0748780965805054,-15.293614387512207,64.93046569824219,0.7892297534290305 +1.0521212816238403,-15.324522018432617,65.24246215820312,0.8674920948727646 +1.0290017127990723,-15.356138229370117,65.56285858154297,0.923986725556647 +1.0039516687393188,-15.390657424926758,65.91343688964844,0.9014484787828944 +0.9773156642913818,-15.427895545959473,66.28913879394531,1.0174885965170493 +0.9489635229110718,-15.468096733093262,66.69338989257812,1.104261598056169 +0.9165849089622498,-15.51469612121582,67.15946197509766,1.2117757906159201 +0.886683464050293,-15.55837345123291,67.59835052490234,1.2691796559194832 +0.8511515855789185,-15.61096477508545,68.13137817382812,1.2964347134170173 +0.8189303874969482,-15.659307479858398,68.62567901611328,1.310740756829156 +0.785765528678894,-15.709710121154785,69.15232849121094,1.2947035027270548 +0.7530934810638428,-15.760076522827148,69.6788330078125,1.313576229450204 +0.7187995910644531,-15.814064979553223,70.23379516601562,1.3239465111677184 +0.68791264295578,-15.86387825012207,70.74414825439453,1.305863615653737 +0.6570331454277039,-15.91471004486084,71.25682830810547,1.2821042609616182 +0.6283726692199707,-15.962824821472168,71.73754119873047,1.2296551377021823 +0.5990816950798035,-16.013032913208008,72.23472595214844,1.1563746847741634 +0.5737494826316833,-16.057472229003906,72.66812896728516,1.0830931304092402 +0.549551784992218,-16.101057052612305,73.0829086303711,1.0070575516994795 +0.528714120388031,-16.13959312438965,73.43988037109375,0.937991112160591 +0.509145975112915,-16.17677879333496,73.77356719970703,0.8706059499544754 +0.49231767654418945,-16.20969581604004,74.05758666992188,0.8109220394400063 +0.4760066866874695,-16.242645263671875,74.32823944091797,0.7512831425428759 +0.4614116847515106,-16.273122787475586,74.56552124023438,0.6963385657812714 +0.4501265287399292,-16.297412872314453,74.74508666992188,0.6526628149154705 +0.4366892874240875,-16.32720375061035,74.95399475097656,0.5993069561205299 +0.4261322617530823,-16.35127830505371,75.11447143554688,0.5563090322448767 +0.4163094162940979,-16.374187469482422,75.26128387451172,0.5155059189229763 +0.40700095891952515,-16.396366119384766,75.39794158935547,0.4761471419045882 +0.3992185890674591,-16.415313720703125,75.509765625,0.4426469625301412 +0.3922216594219208,-16.43267822265625,75.60826110839844,0.41203062710138333 +0.38546809554100037,-16.449783325195312,75.70099639892578,0.38196483243254553 +0.3787481486797333,-16.467172622680664,75.7908706665039,0.35146595559713323 +0.37327060103416443,-16.481597900390625,75.86241912841797,0.32617581053461003 +0.36789241433143616,-16.495906829833984,75.93211364746094,0.30105250867869754 +0.3633174002170563,-16.508119583129883,75.99170684814453,0.27961011623722537 +0.3590231239795685,-16.5196533203125,76.04740905761719,0.25941870685959134 +0.3551117181777954,-16.530263900756836,76.0974349975586,0.24087967972848198 +0.3513754904270172,-16.540555953979492,76.1440200805664,0.22296897092246812 +0.34795936942100525,-16.550127029418945,76.1831283569336,0.1873024856558797 +0.3455686569213867,-16.55689239501953,76.2105941772461,0.14943719891273766 +0.3434511423110962,-16.56296730041504,76.23410034179688,0.1234131279242497 +0.34180524945259094,-16.567861557006836,76.25072479248047,0.0972505503439073 +0.34060776233673096,-16.571575164794922,76.26126098632812,0.07647665473554581 +0.3396204710006714,-16.574710845947266,76.2698745727539,0.07165102888890483 +0.33865371346473694,-16.577932357788086,76.27662658691406,0.08170466894566852 +0.3375701904296875,-16.581571578979492,76.28449249267578,0.0779239054186717 +0.3363996744155884,-16.58562660217285,76.29151916503906,0.09291808986873427 +0.3347673714160919,-16.59127426147461,76.29476165771484,0.1716696585992129 +0.33249416947364807,-16.599349975585938,76.30674743652344,0.1844468848155028 +0.33022570610046387,-16.60751724243164,76.31742858886719,0.18442045197673937 +0.3280808627605438,-16.61530876159668,76.32643127441406,0.18742684550685826 +0.3257831931114197,-16.62375259399414,76.33570861816406,0.18189700441028545 +0.3237428665161133,-16.63132095336914,76.34356689453125,0.1813988652207949 +0.3207986056804657,-16.642454147338867,76.35457611083984,0.23988963974923033 +0.31817522644996643,-16.652605056762695,76.36392974853516,0.2368326304134518 +0.3153449594974518,-16.66362190246582,76.36982727050781,0.23558447197506124 +0.3125297725200653,-16.674720764160156,76.37364196777344,0.30101371355201156 +0.3083488345146179,-16.69146156311035,76.37779235839844,0.4150216524175485 +0.30359163880348206,-16.710662841796875,76.38034057617188,0.40628465913783746 +0.2988990843296051,-16.72978401184082,76.38121032714844,0.488842554030091 +0.2935006320476532,-16.75166130065918,76.3738021850586,0.5436610982933252 +0.2868233323097229,-16.7789249420166,76.37252044677734,0.6103864171627862 +0.2794358432292938,-16.809234619140625,76.3779525756836,0.6969927710839156 +0.27114391326904297,-16.84305191040039,76.37530517578125,0.7702222086901144 +0.26241040229797363,-16.878795623779297,76.37934112548828,0.8702485314121875 +0.25226229429244995,-16.92012596130371,76.37665557861328,0.9726134829749425 +0.24092607200145721,-16.966394424438477,76.37761688232422,1.0557946245824124 +0.22592411935329437,-17.02794075012207,76.39087677001953,1.0481381113600852 +0.21430861949920654,-17.075389862060547,76.39131927490234,1.0747345489161617 +0.20032694935798645,-17.132492065429688,76.3902816772461,1.2779460828130844 +0.18521124124526978,-17.194196701049805,76.38997650146484,1.3512098141016082 +0.16899782419204712,-17.260299682617188,76.39089965820312,1.4000168379026745 +0.15372750163078308,-17.32245635986328,76.39470672607422,1.3978755901892914 +0.13755333423614502,-17.388275146484375,76.40127563476562,1.4179730862488584 +0.12222765386104584,-17.450693130493164,76.40904998779297,1.4215054938071858 +0.10731983929872513,-17.51136589050293,76.41094207763672,1.4208374403529707 +0.09063496440649033,-17.579580307006836,76.4178237915039,1.45534938263138 +0.07375073432922363,-17.64878273010254,76.41852569580078,1.4177126328915215 +0.06238958612084389,-17.695341110229492,76.41197967529297,0.7901767509007744 +0.056125085800886154,-17.72113037109375,76.41133117675781,0.4135662616952256 +0.052968740463256836,-17.73413848876953,76.4110336303711,0.20169623400115078 +0.05147808417677879,-17.740327835083008,76.41046142578125,0.11442818148342515 +0.05026284232735634,-17.74568748474121,76.40666198730469,0.13365932224802812 +0.04881312698125839,-17.752294540405273,76.40008544921875,0.13875393408771186 +0.047529637813568115,-17.758352279663086,76.39205932617188,0.13602678410390495 +0.046339213848114014,-17.76416778564453,76.3821792602539,0.11011357961776148 +0.04530658945441246,-17.769176483154297,76.36656188964844,0.08042634912219428 +0.04474083334207535,-17.772216796875,76.35858917236328,0.06788663532215962 +0.04424101114273071,-17.775001525878906,76.35118103027344,0.0584581293452558 +0.04368909075856209,-17.778121948242188,76.34281158447266,0.0690300224286471 +0.04315933957695961,-17.78131675720215,76.3326416015625,0.07102815355655659 +0.04233662039041519,-17.786306381225586,76.31562805175781,0.10971151621387323 +0.04120926186442375,-17.793119430541992,76.2869873046875,0.21459210207113527 +0.03928632289171219,-17.805463790893555,76.23809051513672,0.29284078209415676 +0.036927707493305206,-17.82144546508789,76.1715087890625,0.34178576855008574 +0.03419405221939087,-17.840784072875977,76.08476257324219,0.4706449291169406 +0.03114152140915394,-17.863094329833984,75.98333740234375,0.5533840812465043 +0.027499059215188026,-17.890165328979492,75.85948944091797,0.6699399745456012 +0.02293277159333229,-17.92442512512207,75.68389129638672,0.7576549068625982 +0.017826296389102936,-17.963632583618164,75.48223114013672,0.9188593580622116 +0.011584652587771416,-18.01152229309082,75.22738647460938,1.1419989087469986 +0.003787359455600381,-18.0711612701416,74.90117645263672,1.357033937060934 +-0.004679945297539234,-18.13425636291504,74.55156707763672,1.5889653353188256 +-0.016610532999038696,-18.2198486328125,74.06993103027344,1.8116121371244884 +-0.02912261337041855,-18.30547523498535,73.58143615722656,1.9782737150709644 +-0.0447080172598362,-18.40742301940918,72.99017333984375,2.14116573461004 +-0.05943424254655838,-18.499958038330078,72.44029998779297,2.2712886081683905 +-0.07842005044221878,-18.614564895629883,71.73947143554688,2.417366740272111 +-0.0981583371758461,-18.728750228881836,71.0172348022461,2.5503434673435823 +-0.11894774436950684,-18.844223022460938,70.25932312011719,2.6745142143608334 +-0.14331330358982086,-18.974042892456055,69.3736801147461,2.8043282362881774 +-0.1687699258327484,-19.10340118408203,68.45674133300781,2.9249709736161558 +-0.19602592289447784,-19.23528289794922,67.48619079589844,3.039704989976176 +-0.22051356732845306,-19.3481388092041,66.6287841796875,3.124528826049651 +-0.2576453983783722,-19.509815216064453,65.36091613769531,3.1733233921114867 +-0.2916256785392761,-19.649003982543945,64.2331314086914,3.1039688505019853 +-0.3287980854511261,-19.792858123779297,63.03031921386719,2.9554217665578753 +-0.3595634400844574,-19.905818939208984,62.05466842651367,2.804264818592604 +-0.4053572118282318,-20.065074920654297,60.62176513671875,2.5610098662378378 +-0.44089633226394653,-20.182355880737305,59.518470764160156,2.3689265104219497 +-0.47262436151504517,-20.28273582458496,58.5409049987793,2.199250734801794 +-0.5025274157524109,-20.37384033203125,57.62580490112305,2.042408105889035 +-0.53258216381073,-20.462284088134766,56.710227966308594,1.888166532414052 +-0.5592915415763855,-20.538480758666992,55.89845275878906,1.7542644386944117 +-0.5871509313583374,-20.615625381469727,55.05532455444336,1.6181803474690888 +-0.6116422414779663,-20.68136215209961,54.32283020019531,1.501924312063918 +-0.6340997815132141,-20.739965438842773,53.6590690612793,1.3976551696431483 +-0.6580795645713806,-20.80097770690918,52.95559310913086,1.2886058211731757 +-0.6793553829193115,-20.85390853881836,52.333953857421875,1.193721890543845 +-0.6999558806419373,-20.90410804748535,51.73444747924805,1.1036307406791863 +-0.7187685370445251,-20.948944091796875,51.19256591796875,1.023184299980967 +-0.736662745475769,-20.990577697753906,50.686649322509766,0.9483932132256243 +-0.7526164054870605,-21.026865005493164,50.243751525878906,0.8828880952191663 +-0.7687544822692871,-21.06285858154297,49.80159378051758,0.8174374473489944 +-0.7838395237922668,-21.096080780029297,49.38774108886719,0.7564697335741685 +-0.7982439398765564,-21.127695083618164,48.985069274902344,0.6982377179390231 +-0.8108275532722473,-21.155399322509766,48.622310638427734,0.6470331948911582 +-0.8220371603965759,-21.180294036865234,48.28630447387695,0.6010804669930417 +-0.8328688740730286,-21.20464324951172,47.94719696044922,0.556198128703916 +-0.8426526188850403,-21.226715087890625,47.63363265991211,0.516548171559452 +-0.8525879979133606,-21.248844146728516,47.31814193725586,0.47668600330152017 +-0.8612194657325745,-21.26781463623047,47.046871185302734,0.4423191778846118 +-0.8688204884529114,-21.284330368041992,46.81021499633789,0.4122742346517612 +-0.8767920732498169,-21.30146026611328,46.564212799072266,0.38100031828170755 +-0.8832564949989319,-21.315338134765625,46.3657112121582,0.30466709670825914 +-0.8886006474494934,-21.32680892944336,46.19762420654297,0.24760894789911736 +-0.8933626413345337,-21.33709144592285,46.04951858520508,0.2198161470886571 +-0.8974801301956177,-21.34581184387207,45.928436279296875,0.19902415087476072 +-0.9013237357139587,-21.353778839111328,45.81151580810547,0.24286017998252668 +-0.9063604474067688,-21.364152908325195,45.66116714477539,0.2470797650418701 +-0.9135552644729614,-21.378419876098633,45.45669174194336,0.3532167015699229 +-0.9207704663276672,-21.392805099487305,45.248558044433594,0.3895901378570164 +-0.9301385283470154,-21.41096305847168,44.99038314819336,0.48166275681252324 +-0.9408046007156372,-21.43169593811035,44.68351364135742,0.5357082409151186 +-0.9530882835388184,-21.455217361450195,44.335784912109375,0.6176764012578875 +-0.9675862193107605,-21.482521057128906,43.93330764770508,0.7006491818208522 +-0.9837608337402344,-21.512521743774414,43.488914489746094,0.7728157042740349 +-1.000793695449829,-21.543561935424805,43.02635955810547,0.8211608232193784 +-1.0198131799697876,-21.577619552612305,42.52070236206055,0.888242138872731 +-1.0409142971038818,-21.614593505859375,41.970760345458984,0.9488251162628223 +-1.0644806623458862,-21.654918670654297,41.36528015136719,1.007172412109665 +-1.088051676750183,-21.694360733032227,40.772972106933594,1.0549498118110237 +-1.1130484342575073,-21.735239028930664,40.15635299682617,1.1037434146112366 +-1.1403069496154785,-21.778759002685547,39.49517822265625,1.1350418809343756 +-1.169441819190979,-21.824127197265625,38.79542541503906,1.1462270065006341 +-1.1979784965515137,-21.867488861083984,38.1284294128418,1.1611567560666507 +-1.2285983562469482,-21.912851333618164,37.42570495605469,1.1693564533115788 +-1.2573076486587524,-21.95427131652832,36.77377700805664,1.1586540020424319 +-1.2877880334854126,-21.997230529785156,36.08937072753906,1.1385332566752644 +-1.3180620670318604,-22.03884506225586,35.42129135131836,1.126548626419036 +-1.3479382991790771,-22.078956604003906,34.7774772644043,1.1309717532058312 +-1.3808743953704834,-22.122053146362305,34.07660675048828,1.1386133698820062 +-1.4120864868164062,-22.161964416503906,33.429473876953125,1.1347477668885364 +-1.4446699619293213,-22.202655792236328,32.75825881958008,1.1413760903842405 +-1.4798904657363892,-22.245487213134766,32.04182052612305,1.1546577356751018 +-1.5147602558135986,-22.28685188293457,31.347442626953125,1.1739518032777916 +-1.5484853982925415,-22.325904846191406,30.685197830200195,1.1838547101946548 +-1.5811134576797485,-22.362855911254883,30.045576095581055,1.1639974134121531 +-1.6192220449447632,-22.405054092407227,29.309688568115234,1.1735005585818765 +-1.6522129774093628,-22.44068717956543,28.68924903869629,1.1964558562502803 +-1.6920368671417236,-22.482711791992188,27.953523635864258,1.208171315640972 +-1.7330766916275024,-22.52483367919922,27.193315505981445,1.2197474918203797 +-1.7712208032608032,-22.56299591064453,26.499752044677734,1.2338316982266748 +-1.8137820959091187,-22.604476928710938,25.73885726928711,1.2707074202079511 +-1.854604721069336,-22.64323616027832,25.015256881713867,1.2931572319991511 +-1.900606393814087,-22.685827255249023,24.213132858276367,1.3044189708365213 +-1.9434782266616821,-22.724403381347656,23.471370697021484,1.3344124109680948 +-1.9892170429229736,-22.764469146728516,22.693561553955078,1.3578790479608933 +-2.0401995182037354,-22.807886123657227,21.837787628173828,1.3831406354885223 +-2.0840797424316406,-22.84419822692871,21.10882568359375,1.4014337501779623 +-2.1383726596832275,-22.887897491455078,20.224008560180664,1.4179547651315814 +-2.1882224082946777,-22.926822662353516,19.419485092163086,1.4393993245923347 +-2.2393898963928223,-22.965404510498047,18.61327362060547,1.4582564852726823 +-2.29636812210083,-23.006404876708984,17.754304885864258,1.4730747751216868 +-2.3523895740509033,-23.04464340209961,16.95367431640625,1.4837389380051733 +-2.4079411029815674,-23.08058738708496,16.201913833618164,1.499843858629774 +-2.468994140625,-23.11794662475586,15.422417640686035,1.5269826684803376 +-2.5290939807891846,-23.152687072753906,14.698007583618164,1.5448205904658998 +-2.593364715576172,-23.187768936157227,13.968306541442871,1.5746374583638787 +-2.658198833465576,-23.22111701965332,13.276021957397461,1.5978740067546044 +-2.72263503074646,-23.252391815185547,12.628503799438477,1.6084262925887653 +-2.7908358573913574,-23.283615112304688,11.983290672302246,1.569275882327416 +-2.860111713409424,-23.313390731811523,11.371623039245605,1.5145567769703439 +-2.920438528060913,-23.3377685546875,10.875772476196289,1.4407799737256715 +-2.983548164367676,-23.36178970336914,10.39284896850586,1.3492186344980566 +-3.0398571491241455,-23.381948471069336,9.993921279907227,1.2606830886540559 +-3.093731641769409,-23.40011978149414,9.640918731689453,1.1726877483863165 +-3.1436617374420166,-23.415985107421875,9.340031623840332,1.089721010969629 +-3.1935298442840576,-23.430877685546875,9.066691398620605,1.0061791030406306 +-3.236877918243408,-23.443044662475586,8.85229206085205,0.9333727729245019 +-3.275702714920044,-23.45330810546875,8.679718017578125,0.8681626729193339 +-3.3163392543792725,-23.463397979736328,8.52053451538086,0.8000379136076591 +-3.3499608039855957,-23.471227645874023,8.406277656555176,0.7438131065759397 +-3.3808979988098145,-23.477996826171875,8.316296577453613,0.6921640539898088 +-3.413290023803711,-23.484622955322266,8.238492965698242,0.6382015954561678 +-3.441124439239502,-23.48992347717285,8.186249732971191,0.5918900418235405 +-3.466364622116089,-23.494449615478516,8.154179573059082,0.49267385585719486 +-3.486988067626953,-23.497875213623047,8.129590034484863,0.4208281589296306 +-3.504215955734253,-23.500545501708984,8.12436580657959,0.3589285860679693 +-3.5210468769073486,-23.50274658203125,8.125892639160156,0.3161685633569219 +-3.5352537631988525,-23.504648208618164,8.136499404907227,0.2814152766487051 +-3.5474016666412354,-23.506067276000977,8.152088165283203,0.24006116185752321 +-3.5582051277160645,-23.507152557373047,8.171874046325684,0.23029831494962072 +-3.569497585296631,-23.50814437866211,8.19871997833252,0.26055759822219476 +-3.5802037715911865,-23.50895881652832,8.228471755981445,0.24366927163241275 +-3.5927670001983643,-23.509794235229492,8.271300315856934,0.274141409257398 +-3.606471538543701,-23.510515213012695,8.319132804870605,0.3004776396614278 +-3.6206791400909424,-23.511125564575195,8.381093978881836,0.3332954989477173 +-3.6353344917297363,-23.511608123779297,8.45054817199707,0.3240952657652366 +-3.650933027267456,-23.511964797973633,8.529608726501465,0.37285396431217027 +-3.670130491256714,-23.51228141784668,8.641392707824707,0.4130821976954477 +-3.6896862983703613,-23.512367248535156,8.76185131072998,0.4285386438036969 +-3.709536075592041,-23.512218475341797,8.893060684204102,0.4177536773758097 +-3.7308027744293213,-23.511886596679688,9.044992446899414,0.4757162246530176 +-3.7523772716522217,-23.511348724365234,9.207058906555176,0.4909142902021171 +-3.777522563934326,-23.510589599609375,9.412150382995605,0.545778986069012 +-3.803894281387329,-23.50979995727539,9.62360668182373,0.5834419850415464 +-3.8334836959838867,-23.509172439575195,9.86621379852295,0.6476952680785977 +-3.863929033279419,-23.508686065673828,10.105749130249023,0.6864293233025855 +-3.896854877471924,-23.50834083557129,10.368233680725098,0.7194115438429348 +-3.931992292404175,-23.508066177368164,10.642394065856934,0.7768668528065558 +-3.9690685272216797,-23.507953643798828,10.93939208984375,0.8222157025652223 +-4.007900714874268,-23.508024215698242,11.249765396118164,0.8434742170233654 +-4.047034740447998,-23.508329391479492,11.561837196350098,0.8812098850571739 +-4.087830543518066,-23.5087890625,11.883143424987793,0.9210442141070783 +-4.134451866149902,-23.509559631347656,12.259308815002441,0.9787548775501148 +-4.18076229095459,-23.510576248168945,12.632177352905273,1.0231749922366125 +-4.22968053817749,-23.51198959350586,13.027359008789062,1.0557942385583607 +-4.283610820770264,-23.513959884643555,13.45985221862793,1.0992076913379354 +-4.32815408706665,-23.515783309936523,13.811936378479004,1.1247407163072596 +-4.384450912475586,-23.518436431884766,14.270650863647461,1.1452352417997356 +-4.450170993804932,-23.521940231323242,14.80700397491455,1.1363253887667966 +-4.50476598739624,-23.52547836303711,15.264019012451172,1.1390278523676507 +-4.559080600738525,-23.529306411743164,15.698171615600586,1.1473952258622533 +-4.614192485809326,-23.533716201782227,16.14751434326172,1.1888468558241698 +-4.669641494750977,-23.538681030273438,16.59807014465332,1.2309916472715232 +-4.729861259460449,-23.544382095336914,17.088031768798828,1.276358763619057 +-4.7874436378479,-23.550323486328125,17.560388565063477,1.3053730907400778 +-4.849797248840332,-23.55715560913086,18.07881736755371,1.3140204469613677 +-4.911150932312012,-23.564409255981445,18.589143753051758,1.3330253384465696 +-4.971399307250977,-23.572065353393555,19.08492088317871,1.3596122867414018 +-5.0312581062316895,-23.580142974853516,19.575197219848633,1.397322051197571 +-5.101576328277588,-23.590221405029297,20.160032272338867,1.4310626306498868 +-5.162452220916748,-23.59947967529297,20.669118881225586,1.4505397315455513 +-5.226855278015137,-23.609914779663086,21.210453033447266,1.458709586394938 +-5.29428768157959,-23.621511459350586,21.777822494506836,1.4470607770409734 +-5.362864971160889,-23.633913040161133,22.362754821777344,1.4382807444381847 +-5.425840377807617,-23.645816802978516,22.90186882019043,1.4655341392891126 +-5.496123313903809,-23.659774780273438,23.506074905395508,1.491600308204638 +-5.56326150894165,-23.673871994018555,24.0828857421875,1.5185791074531636 +-5.635905742645264,-23.68996810913086,24.70513343811035,1.5308559259190664 +-5.70110559463501,-23.705080032348633,25.264623641967773,1.4993072951960595 +-5.768462181091309,-23.721385955810547,25.845043182373047,1.4666648407584084 +-5.8361406326293945,-23.73847198486328,26.42812728881836,1.393979844371948 +-5.890625476837158,-23.75273895263672,26.899227142333984,1.3199197395148343 +-5.951551914215088,-23.76925277709961,27.428091049194336,1.2275851089501966 +-6.003811359405518,-23.78389549255371,27.88359260559082,1.143506942790204 +-6.0524773597717285,-23.79795265197754,28.30878257751465,1.0628602185521152 +-6.0971832275390625,-23.811275482177734,28.697994232177734,0.9875590637979551 +-6.1358561515808105,-23.823083877563477,29.03411102294922,0.42936803544893765 +-6.1379923820495605,-23.823863983154297,29.058307647705078,0.0004522693504219105 +-6.137988567352295,-23.823848724365234,29.05823516845703,0.0005603912489958629 +-6.138063907623291,-23.82384490966797,29.058242797851562,0.0006151585218835692 +-6.1381378173828125,-23.823848724365234,29.05815315246582,0.0005304875540227459 +-6.138206481933594,-23.823863983154297,29.05817413330078,0.0004167421323611619 +-6.138252258300781,-23.823863983154297,29.058181762695312,0.00033672911491058 +-6.138294696807861,-23.823854446411133,29.058177947998047,0.0002565272515423243 +-6.13832426071167,-23.823848724365234,29.058116912841797,0.00020001557956385963 +-6.138345241546631,-23.823843002319336,29.058116912841797,0.00016172003510132667 +-6.1383585929870605,-23.82383918762207,29.058116912841797,0.00013371576587793577 +-6.13837194442749,-23.823835372924805,29.058082580566406,0.00010660196619844867 +-6.138383865356445,-23.82383155822754,29.058082580566406,8.699507198032299e-05 +-6.138391971588135,-23.823829650878906,29.058082580566406,7.044788607351716e-05 +-6.138396263122559,-23.823827743530273,29.058082580566406,1.4349312653595651e-05 +-6.138399124145508,-23.823827743530273,29.058082580566406,1.044679768344458e-05 +-6.138400077819824,-23.82382583618164,29.058082580566406,9.973863683777123e-06 +-6.138401508331299,-23.82382583618164,29.058082580566406,8.379506996730349e-06 +-6.138402462005615,-23.82382583618164,29.058082580566406,7.522518764058643e-06 +-6.138403415679932,-23.823822021484375,29.058082580566406,6.6802574093241885e-06 +-6.13840389251709,-23.823822021484375,29.058082580566406,6.027967913404253e-06 +-6.138404369354248,-23.823822021484375,29.058082580566406,5.070740657395907e-06 +-6.138405799865723,-23.823822021484375,29.058082580566406,5.326293436662079e-06 +-6.138406276702881,-23.823822021484375,29.058082580566406,4.8796623429055215e-06 +-6.138406276702881,-23.823822021484375,29.058082580566406,4.845287029146549e-06 +-6.138406276702881,-23.823822021484375,29.058082580566406,4.388005831560004e-06 +-6.138406276702881,-23.823822021484375,29.058082580566406,3.333970373672405e-06 +-6.138406276702881,-23.823822021484375,29.058082580566406,4.366123428262346e-06 +-6.138406276702881,-23.823822021484375,29.058082580566406,4.327697738575407e-06 +-6.138406276702881,-23.823820114135742,29.058082580566406,4.3854803092414715e-06 +-6.138406276702881,-23.823820114135742,29.058082580566406,4.153999515564308e-06 +-6.138406276702881,-23.823820114135742,29.058082580566406,3.5599001357640065e-06 +-6.138406276702881,-23.823820114135742,29.058082580566406,3.82836191436023e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.331946375680028e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.155934484684725e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.337895385384066e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,2.3837857719768608e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.859937024934876e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,2.4003433182093534e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.10954505312517e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.85936046273807e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,1.94568984399937e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.419335627644997e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.5785555314493224e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.924644905550054e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.990517618900275e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.875758965255109e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.6463761076961317e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.012059689550674e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.316212870804755e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.1553518405426e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.222221323181963e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.651330386084452e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.230097611112634e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.182297202373889e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.220388373765261e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.222348489781391e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.668649374905527e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.5851161632434157e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.297548683830626e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.229883869059357e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.2123354077272435e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.9472570599134705e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.5997489002297432e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.303139119670168e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.951399086289253e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,2.1984814228762115e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,2.25952663850545e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.564778130004922e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.755594562580258e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.6508928086691e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.896899226375047e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.302177573419269e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,3.6848500689661395e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.282990300763901e-06 +-6.138406753540039,-23.823820114135742,29.058082580566406,4.275591059247353e-06 +-6.26848030090332,-23.89092254638672,29.215843200683594,2.123579749596426 +-6.191652297973633,-23.845949172973633,29.294485092163086,2.317093414725689 +-6.10037088394165,-23.79216957092285,29.394676208496094,2.5264997165814895 +-5.991113662719727,-23.727296829223633,29.52309799194336,2.755268651448918 +-5.878059387207031,-23.65963363647461,29.663881301879883,2.9726291596292245 +-5.773307800292969,-23.596439361572266,29.801254272460938,3.159983374966046 +-5.627208232879639,-23.50737762451172,30.006912231445312,3.4026391194827426 +-5.4838762283325195,-23.41887664794922,30.226966857910156,3.6243078092125556 +-5.324041843414307,-23.31879425048828,30.493213653564453,3.8559075918942463 +-5.169105052947998,-23.22035026550293,30.770492553710938,4.067362689718846 +-4.994061470031738,-23.10736083984375,31.103450775146484,4.293341268054251 +-4.814267635345459,-22.989349365234375,31.464460372924805,4.513338871023422 +-4.648684978485107,-22.87911033630371,31.812847137451172,4.706024655918941 +-4.466715335845947,-22.756107330322266,32.21375274658203,4.908119776072714 +-4.261043548583984,-22.614044189453125,32.688941955566406,5.127497410636009 +-4.05989408493042,-22.47234535217285,33.17110824584961,5.333447487712379 +-3.8480656147003174,-22.320329666137695,33.68968200683594,5.542077334270012 +-3.640947103500366,-22.169017791748047,34.200748443603516,5.738713576024767 +-3.4284920692443848,-22.011024475097656,34.72758102416992,5.933537092431249 +-3.1974172592163086,-21.8359317779541,35.30341720581055,6.138357182546243 +-2.9724111557006836,-21.662099838256836,35.86698913574219,6.331402036364975 +-2.7317214012145996,-21.472457885742188,36.4730224609375,6.531678700548569 +-2.4775941371917725,-21.268033981323242,37.11444854736328,6.736924171695178 +-2.2349491119384766,-21.068668365478516,37.732765197753906,6.926736902262635 +-1.9977071285247803,-20.868480682373047,38.39021682739258,7.105266597898601 +-1.7470887899398804,-20.649274826049805,39.2032585144043,7.287163235899546 +-1.4667179584503174,-20.392635345458984,40.28409957885742,7.486979457320535 +-1.2156026363372803,-20.15201759338379,41.37173843383789,7.665954548529551 +-0.9602720141410828,-19.896730422973633,42.55279541015625,7.846907301246481 +-0.7148830890655518,-19.641952514648438,43.699974060058594,8.017258397329034 +-0.44702011346817017,-19.354700088500977,44.89393615722656,8.190364276929717 +-0.19414407014846802,-19.075510025024414,45.9389533996582,8.320361628406939 +0.08443418145179749,-18.759336471557617,46.99979782104492,8.378965725613229 +0.33159494400024414,-18.470170974731445,47.91025924682617,8.347716871737308 +0.560762345790863,-18.193113327026367,48.7780647277832,8.2717743249093 +0.8192785382270813,-17.868886947631836,49.82154846191406,8.149581591301295 +1.0530259609222412,-17.563085556030273,50.836753845214844,8.01672411380091 +1.2727985382080078,-17.265214920043945,51.80385971069336,7.8807259639413685 +1.4754348993301392,-16.98274040222168,52.65043640136719,7.748065144527707 +1.691009521484375,-16.6746768951416,53.48271560668945,7.599675741721607 +1.8791444301605225,-16.398591995239258,54.185577392578125,7.463814069001893 +2.0698540210723877,-16.110736846923828,54.91092300415039,7.3210058802651 +2.2628564834594727,-15.810369491577148,55.67143249511719,7.172114024230852 +2.431027889251709,-15.540499687194824,56.35772705078125,7.033392633820587 +2.599149465560913,-15.26276683807373,57.06357955932617,6.876258541988058 +2.7725775241851807,-14.967421531677246,57.81037521362305,6.727449009700314 +2.925496816635132,-14.698980331420898,58.48518371582031,6.6003751068365 +3.0614750385284424,-14.453571319580078,59.09870147705078,6.472530045035514 +3.2104427814483643,-14.177332878112793,59.77726745605469,6.317862388442162 +3.3474011421203613,-13.918052673339844,60.36171340942383,6.160254782233011 +3.474794626235962,-13.673587799072266,60.846839904785156,6.017529066211618 +3.5930166244506836,-13.443126678466797,61.27705764770508,5.893966214243839 +3.7201309204101562,-13.190125465393066,61.75192642211914,5.767066697559715 +3.832148551940918,-12.96183967590332,62.194496154785156,5.654617763334178 +3.946338415145874,-12.723416328430176,62.67206573486328,5.535355166658909 +4.049285411834717,-12.503310203552246,63.12005615234375,5.423013415346366 +4.162156105041504,-12.256232261657715,63.6245002746582,5.293204346132862 +4.181422233581543,-12.264142990112305,63.87055587768555,0.1367343501719721 +4.182095050811768,-12.26380729675293,63.87035369873047,0.0008711123590003284 +4.182106971740723,-12.26404857635498,63.87132263183594,0.008328997752391666 +4.182024002075195,-12.26445484161377,63.87227249145508,0.008054364704766503 +4.181933879852295,-12.264813423156738,63.873104095458984,0.006671284179265336 +4.181850433349609,-12.265119552612305,63.87379455566406,0.005272111354762429 +4.181785583496094,-12.265350341796875,63.874271392822266,0.004171867648647384 +4.1817307472229,-12.26554012298584,63.87479782104492,0.0032300233687860436 +4.181690216064453,-12.265689849853516,63.87528991699219,0.0025094943069433446 +4.181660175323486,-12.265801429748535,63.87577438354492,0.001926807023360375 +4.18165922164917,-12.265828132629395,63.87639617919922,0.005604540440816851 +4.181825160980225,-12.265443801879883,63.877647399902344,0.014296912182028406 +4.18212366104126,-12.264741897583008,63.879913330078125,0.019326942139429988 +4.182464599609375,-12.263930320739746,63.88249588012695,0.021850755076694005 +4.182896137237549,-12.262898445129395,63.88583755493164,0.02332660484250505 +4.183322906494141,-12.261872291564941,63.889259338378906,0.023949935823507625 +4.183732986450195,-12.260881423950195,63.89263916015625,0.024165813512091 +4.1841630935668945,-12.259841918945312,63.89617156982422,0.024179896588929987 +4.184584140777588,-12.258825302124023,63.899681091308594,0.0240795031709708 +4.1849822998046875,-12.257864952087402,63.902992248535156,0.023928727301982755 +4.1854248046875,-12.256794929504395,63.90670394897461,0.023724964129667313 +4.185833930969238,-12.255802154541016,63.910247802734375,0.023515636991411144 +4.1859540939331055,-12.25551700592041,63.911434173583984,1.9495169634121632e-05 +4.185955047607422,-12.255523681640625,63.911434173583984,8.393720566435645e-06 +4.18595552444458,-12.255524635314941,63.911434173583984,6.03170616888895e-06 +4.1859564781188965,-12.255525588989258,63.911434173583984,5.537294122347856e-06 +4.185956954956055,-12.255525588989258,63.911434173583984,5.451045402468103e-06 +4.185957431793213,-12.255525588989258,63.911434173583984,5.485415211985292e-06 +4.185957431793213,-12.255525588989258,63.911434173583984,5.22605674376036e-06 +4.185957431793213,-12.255525588989258,63.911434173583984,5.071623046766557e-06 +4.185957431793213,-12.255525588989258,63.911434173583984,5.694851645041008e-06 +4.185957908630371,-12.255525588989258,63.911434173583984,5.666772671880169e-06 +4.185957908630371,-12.255525588989258,63.911434173583984,5.685322590932108e-06 +4.185958385467529,-12.255525588989258,63.911434173583984,5.8349470193913794e-06 +4.185958385467529,-12.255525588989258,63.911434173583984,5.067318868564824e-06 +4.185958385467529,-12.255525588989258,63.911434173583984,5.642974058254205e-06 +4.185958385467529,-12.255525588989258,63.911434173583984,5.837958683002606e-06 +4.185958385467529,-12.255525588989258,63.911434173583984,5.420545889397192e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.258484100441881e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.343400079013922e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.2830889476017704e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,6.168933827406442e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.854899261581145e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,4.3306800858390975e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.923394225388735e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.919787829333144e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.702265692923525e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.539688110272092e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.585605176617378e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,4.404177824782188e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.695373606329754e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.81447872705704e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.603160106446037e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.699774677289739e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.1473550372983355e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.4462177203772875e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.624697926788093e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.6397131694530985e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.581624076708179e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,4.732794348682317e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.5627873419929564e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.556220049978112e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.314880633833937e-06 +4.1859588623046875,-12.255525588989258,63.911434173583984,5.6459236804312625e-06 +4.185954570770264,-12.255532264709473,63.91132736206055,0.0012751538486734883 +4.185949325561523,-12.255558013916016,63.91178512573242,0.004003570653764408 +4.185868263244629,-12.25573444366455,63.91211700439453,0.0005743786792522306 +4.1856231689453125,-12.25629997253418,63.91156005859375,0.014329449498686867 +4.185187816619873,-12.257245063781738,63.91099166870117,0.04305643044854772 +4.183938980102539,-12.259950637817383,63.90873718261719,0.06906418592803651 +4.182479381561279,-12.26305103302002,63.90568542480469,0.12520874921055006 +4.1789960861206055,-12.270248413085938,63.902645111083984,0.16876053488266235 +4.172818183898926,-12.282576560974121,63.90412902832031,0.3527583047416275 +4.164397716522217,-12.299041748046875,63.91325378417969,0.4779067642793249 +4.153478622436523,-12.320448875427246,63.93001937866211,0.589095153713091 +4.1390061378479,-12.34926700592041,63.93986892700195,0.7227236844135377 +4.122481346130371,-12.383078575134277,63.9364013671875,0.84455160853336 +4.104008674621582,-12.421806335449219,63.910064697265625,0.9590908753902037 +4.082850456237793,-12.46630573272705,63.88386917114258,1.1143133510960745 +4.059955596923828,-12.513646125793457,63.87081527709961,1.2339446116775863 +4.03285551071167,-12.568285942077637,63.8812255859375,1.352402684799333 +4.000980854034424,-12.63107967376709,63.920989990234375,1.4905375983251468 +3.9692201614379883,-12.693695068359375,63.95966339111328,1.5987235416965497 +3.934638500213623,-12.763111114501953,63.98048400878906,1.6880745620780615 +3.8960697650909424,-12.842647552490234,63.96134567260742,1.7805617358105652 +3.8626890182495117,-12.913169860839844,63.913047790527344,1.8379999073470028 +3.8256313800811768,-12.991435050964355,63.860477447509766,1.7934329283561126 +3.7978732585906982,-13.048506736755371,63.847469329833984,1.0071243289544944 +3.782461404800415,-13.07982063293457,63.84776306152344,0.5717121975319306 +3.7709407806396484,-13.102405548095703,63.8638916015625,0.5585309761079102 +3.7588114738464355,-13.125508308410645,63.892818450927734,0.5305232535969168 +3.7477424144744873,-13.146617889404297,63.91850662231445,0.4985857157777177 +3.737088918685913,-13.167349815368652,63.93573760986328,0.4641896750665105 +3.7296276092529297,-13.182435989379883,63.93743896484375,0.27402135289675755 +3.7254207134246826,-13.19100284576416,63.937740325927734,0.1675965926183376 +3.722574472427368,-13.196805953979492,63.937931060791016,0.10153182932889562 +3.7208714485168457,-13.20028018951416,63.93842315673828,0.06714275373977899 +3.7196757793426514,-13.202640533447266,63.94034194946289,0.052570287618276194 +3.718613862991333,-13.204679489135742,63.9432373046875,0.04329378438402837 +3.717754364013672,-13.206342697143555,63.94540786743164,0.037594590364376054 +3.717419147491455,-13.207006454467773,63.94631576538086,0.008148384983482228 +3.717235565185547,-13.207392692565918,63.946754455566406,0.006909535915317874 +3.717003107070923,-13.207892417907715,63.94706726074219,0.01614897479362832 +3.7167046070098877,-13.20855712890625,63.946739196777344,0.01662434182322566 +3.7164065837860107,-13.20920467376709,63.9465217590332,0.017112636383098956 +3.716060161590576,-13.209945678710938,63.94639205932617,0.020832712607509216 +3.715569019317627,-13.21096420288086,63.94651412963867,0.027559966050837884 +3.7146565914154053,-13.212788581848145,63.947689056396484,0.05330302046646551 +3.7133233547210693,-13.215396881103516,63.950347900390625,0.061650842837308324 +3.711851119995117,-13.218262672424316,63.9535026550293,0.07169795479623171 +3.710322380065918,-13.22127914428711,63.95565414428711,0.06549920876102676 +3.7089669704437256,-13.22403335571289,63.95588684082031,0.06448245184151497 +3.706598997116089,-13.228939056396484,63.95090866088867,0.15184167863868717 +3.7032859325408936,-13.236040115356445,63.946876525878906,0.2111859273103284 +3.698228597640991,-13.246809959411621,63.933109283447266,0.2669921894632674 +3.6926894187927246,-13.258434295654297,63.925540924072266,0.2878371130770165 +3.6855974197387695,-13.27297592163086,63.925662994384766,0.3505775799223497 +3.677820920944214,-13.288455963134766,63.933441162109375,0.37308980390250057 +3.669581174850464,-13.304447174072266,63.95067596435547,0.4427054021289534 +3.659050464630127,-13.324812889099121,63.969730377197266,0.509382314731098 +3.6474571228027344,-13.34762954711914,63.984588623046875,0.5608836552317737 +3.634873867034912,-13.373064041137695,63.98810577392578,0.6204591293436456 +3.62202787399292,-13.39981460571289,63.976924896240234,0.6730016550960232 +3.609412670135498,-13.426786422729492,63.95283889770508,0.7256965457456128 +3.593722105026245,-13.460515975952148,63.92024612426758,0.8087801630326263 +3.5764284133911133,-13.497057914733887,63.8960075378418,0.887251837304494 +3.5562222003936768,-13.5386323928833,63.88860321044922,0.9612505842753105 +3.537153482437134,-13.57677936553955,63.90205764770508,1.020211321574228 +3.514110565185547,-13.621756553649902,63.9388313293457,1.070060888393397 +3.49086332321167,-13.66709041595459,63.97571563720703,1.1165098172131296 +3.4686193466186523,-13.711213111877441,63.99724197387695,1.1755870005152047 +3.441962718963623,-13.76546859741211,63.9974365234375,1.2240817196153542 +3.419189691543579,-13.81314468383789,63.97284698486328,1.2583826029305003 +3.394472360610962,-13.866207122802734,63.92130661010742,1.2974069834598843 +3.366931915283203,-13.925440788269043,63.86215591430664,1.3191023500059367 +3.341704845428467,-13.978676795959473,63.826168060302734,1.367750972521927 +3.3124325275421143,-14.038857460021973,63.813236236572266,1.3981994765277461 +3.283221960067749,-14.097142219543457,63.83257293701172,1.4407710440734125 +3.251371383666992,-14.159086227416992,63.88388442993164,1.4864286045427113 +3.2191250324249268,-14.221662521362305,63.937835693359375,1.5249476917354614 +3.1858434677124023,-14.287416458129883,63.97201919555664,1.5386404584571844 +3.1543991565704346,-14.351133346557617,63.97529220581055,1.5588298129412135 +3.1234333515167236,-14.415725708007812,63.94426727294922,1.5929989816300723 +3.092188596725464,-14.48255443572998,63.88139724731445,1.617886245610916 +3.0589404106140137,-14.553794860839844,63.812129974365234,1.6458303092672248 +3.026658058166504,-14.621695518493652,63.767154693603516,1.6672533272679397 +2.9898033142089844,-14.697113037109375,63.75307083129883,1.6902101886925556 +2.9560952186584473,-14.764097213745117,63.77672576904297,1.710319725506301 +2.917546510696411,-14.838851928710938,63.8389892578125,1.730252453171214 +2.880537748336792,-14.910520553588867,63.90060806274414,1.7456260065661782 +2.8419411182403564,-14.986673355102539,63.93964385986328,1.760596966688708 +2.8072361946105957,-15.056939125061035,63.94230651855469,1.7795236908086856 +2.7689080238342285,-15.136828422546387,63.9023323059082,1.796053987770402 +2.7360613346099854,-15.207037925720215,63.83448028564453,1.8059961242328244 +2.6984355449676514,-15.287492752075195,63.75585174560547,1.8239028198610208 +2.6614935398101807,-15.364888191223145,63.70634460449219,1.8380559338981688 +2.623554229736328,-15.442252159118652,63.69307327270508,1.8517526116365086 +2.582190990447998,-15.524102210998535,63.724609375,1.8648668832124566 +2.5406646728515625,-15.604252815246582,63.79498291015625,1.876142510382674 +2.501753568649292,-15.67951774597168,63.85979080200195,1.887081189070473 +2.4599852561950684,-15.761758804321289,63.90121078491211,1.8984281529999973 +2.4221839904785156,-15.838126182556152,63.90400314331055,1.908528546154348 +2.3832037448883057,-15.919112205505371,63.864601135253906,1.9184725438189807 +2.3472049236297607,-15.995888710021973,63.79046630859375,1.9275949395661638 +2.307878017425537,-16.08013343811035,63.70269775390625,1.936460976085264 +2.2668683528900146,-16.166248321533203,63.64002990722656,1.9456712210857126 +2.2294535636901855,-16.24275779724121,63.61825180053711,1.9524206429475208 +2.1881253719329834,-16.324974060058594,63.63671875,1.9626424210247082 +2.1448721885681152,-16.408824920654297,63.697113037109375,1.9729911889657035 +2.102454423904419,-16.49087905883789,63.75917053222656,1.9827604283289284 +2.0621862411499023,-16.570152282714844,63.79342269897461,1.9926167038593263 +2.020089864730835,-16.655141830444336,63.79049301147461,2.002981753520347 +1.9801136255264282,-16.738176345825195,63.74353790283203,2.0133429537982694 +1.9429802894592285,-16.8172664642334,63.6610221862793,2.0231906465041605 +1.9041595458984375,-16.900333404541016,63.56602478027344,2.033559316528295 +1.8605101108551025,-16.992082595825195,63.48579788208008,2.0440759398128447 +1.81842041015625,-17.07816505432129,63.45035171508789,2.0540436139021496 +1.7772600650787354,-17.159997940063477,63.45801544189453,2.062770298681622 +1.7330520153045654,-17.245725631713867,63.50663757324219,2.0730354282888634 +1.6909253597259521,-17.327119827270508,63.557613372802734,2.0835766827465494 +1.6297677755355835,-17.447612762451172,63.589759826660156,2.03167193004501 +1.5757538080215454,-17.557798385620117,63.549034118652344,2.065784493144491 +1.5328946113586426,-17.647838592529297,63.46211242675781,2.1089177698162858 +1.4896634817123413,-17.738739013671875,63.37193298339844,2.1334660660953664 +1.4461324214935303,-17.82854652404785,63.310672760009766,2.1506873870219434 +1.3973562717437744,-17.926441192626953,63.29038619995117,2.1660645256243707 +1.3531678915023804,-18.01264190673828,63.318206787109375,2.1780571902831674 +1.3064112663269043,-18.101776123046875,63.38792037963867,2.1897511033547623 +1.2563321590423584,-18.197208404541016,63.46339416503906,2.201824614395916 +1.2075672149658203,-18.29192543029785,63.50493621826172,2.2130985640884937 +1.162207007408142,-18.382492065429688,63.50099563598633,2.2245232231939025 +1.1179641485214233,-18.47307014465332,63.450008392333984,2.2351741683798036 +1.076606273651123,-18.559818267822266,63.35992431640625,2.244618818960805 +1.0287572145462036,-18.660634994506836,63.2435302734375,2.2549163921999478 +0.9828631281852722,-18.755828857421875,63.160709381103516,2.2649653843889213 +0.932489275932312,-18.857439041137695,63.11815643310547,2.2752705061291527 +0.8830653429031372,-18.954147338867188,63.13033676147461,2.284185668869708 +0.8397255539894104,-19.03693389892578,63.17919921875,2.2820470632742356 +0.7893658876419067,-19.13270378112793,63.242740631103516,2.19521690061633 +0.7520750761032104,-19.205055236816406,63.2570686340332,1.2434828649938003 +0.7326874136924744,-19.243196487426758,63.2576789855957,0.7056709787416183 +0.7217487692832947,-19.26479721069336,63.2586669921875,0.3966066047275115 +0.7154704928398132,-19.277164459228516,63.26449966430664,0.26944212152254043 +0.7098062634468079,-19.287843704223633,63.27461624145508,0.2591208372111438 +0.7040207982063293,-19.298507690429688,63.289485931396484,0.24412000396575087 +0.698740541934967,-19.308271408081055,63.302310943603516,0.2284031509182072 +0.6938833594322205,-19.317428588867188,63.31099319458008,0.2127856306708797 +0.6902796030044556,-19.324472427368164,63.312774658203125,0.13872222490791777 +0.6881031394004822,-19.32878303527832,63.313194274902344,0.0834979038314653 +0.6864526867866516,-19.33214569091797,63.31172561645508,0.06885933353409332 +0.6851226687431335,-19.33486557006836,63.310638427734375,0.05832145437250894 +0.6841503977775574,-19.336795806884766,63.31117248535156,0.033832843832478005 +0.6836130619049072,-19.337862014770508,63.31166458129883,0.021571180783992405 +0.6831583380699158,-19.338735580444336,63.31288528442383,0.01805464019455562 +0.6827837824821472,-19.33943748474121,63.31412887573242,0.015844221456803653 +0.6824617385864258,-19.34004020690918,63.315303802490234,0.014255103241337384 +0.6821681261062622,-19.340604782104492,63.316070556640625,0.012950099738553681 +0.6819708347320557,-19.340999603271484,63.31608200073242,0.007524261490074384 +0.6818548440933228,-19.341238021850586,63.31610870361328,0.004037589639341668 +0.6817951798439026,-19.34136199951172,63.31610870361328,0.0019975374840894267 +0.6817660331726074,-19.341421127319336,63.31610870361328,0.0007005735759015569 +0.6817516088485718,-19.341449737548828,63.31610870361328,0.0005622179138427558 +0.6817393898963928,-19.341474533081055,63.31610870361328,0.00044171169685697307 +0.6817305088043213,-19.341487884521484,63.31610870361328,0.0003326769146815973 +0.6817243695259094,-19.341503143310547,63.31610870361328,0.00014748942861189342 +0.6817276477813721,-19.34149742126465,63.31610870361328,0.0003878227183034654 +0.6817395687103271,-19.341474533081055,63.31610870361328,0.000755987801595611 +0.6817565560340881,-19.34144401550293,63.31610870361328,0.0010352564990501669 +0.6818389892578125,-19.34129524230957,63.3171272277832,0.004048054351487246 +0.6819791793823242,-19.34103775024414,63.31724166870117,0.002891307673635241 +0.6820237040519714,-19.34097671508789,63.31794738769531,0.016389050402527656 +0.6816862225532532,-19.341655731201172,63.320438385009766,0.01964108029975349 +0.6811903715133667,-19.342632293701172,63.321163177490234,0.02436623668898437 +0.6801217794418335,-19.344738006591797,63.32168197631836,0.05427389817160537 +0.6788709163665771,-19.347278594970703,63.321067810058594,0.07639612499192543 +0.6773952841758728,-19.350337982177734,63.317569732666016,0.07296667623260193 +0.6736596822738647,-19.35794448852539,63.30171203613281,0.22575948042145313 +0.6679412722587585,-19.3696231842041,63.29670333862305,0.2843617763870217 +0.6603114008903503,-19.384769439697266,63.296382904052734,0.4373130775036533 +0.6507391333580017,-19.403316497802734,63.30526351928711,0.4921307571905256 +0.6377449035644531,-19.42780303955078,63.324989318847656,0.6027458405628899 +0.6233803629875183,-19.454845428466797,63.349483489990234,0.7292883778712463 +0.6070970296859741,-19.486053466796875,63.367515563964844,0.8071620355308929 +0.588871955871582,-19.521846771240234,63.372467041015625,0.8984322302436372 +0.5699953436851501,-19.559961318969727,63.35775375366211,0.9982089786027432 +0.5484949946403503,-19.60452651977539,63.31877517700195,1.065243851324895 +0.5258188843727112,-19.651691436767578,63.275177001953125,1.1784627303326338 +0.4987480342388153,-19.70697593688965,63.24249267578125,1.2853833221875126 +0.47111091017723083,-19.761953353881836,63.236305236816406,1.3742413023179996 +0.441914439201355,-19.818464279174805,63.25933837890625,1.4561309651148555 +0.40852129459381104,-19.881622314453125,63.31450271606445,1.502176348479527 +0.37491574883461,-19.94507598876953,63.371639251708984,1.541235607795396 +0.3423236906528473,-20.007740020751953,63.406105041503906,1.4904428938408125 +0.31802552938461304,-20.055561065673828,63.410728454589844,0.79500085906142 +0.30468857288360596,-20.082313537597656,63.405189514160156,0.6068922493943267 +0.29563799500465393,-20.10026741027832,63.398433685302734,0.3419064553339526 +0.2905001640319824,-20.110443115234375,63.396541595458984,0.18381171196369947 +0.28765177726745605,-20.116104125976562,63.39668655395508,0.0885719714346538 +0.28616201877593994,-20.119022369384766,63.39773178100586,0.07258000672662343 +0.2845175564289093,-20.122188568115234,63.4000244140625,0.07490445605910231 +0.282941997051239,-20.12520408630371,63.402591705322266,0.07326006249857467 +0.28136780858039856,-20.12820053100586,63.4052848815918,0.06981642414023063 +0.2798393964767456,-20.13108253479004,63.40857696533203,0.06557358092488652 +0.2784515917301178,-20.133670806884766,63.4121208190918,0.061312265236655804 +0.27704763412475586,-20.136259078979492,63.41643142700195,0.0567898268649644 +0.2758793234825134,-20.138383865356445,63.420555114746094,0.05294526985879875 +0.27464258670806885,-20.14060401916504,63.4256591796875,0.04884043022715405 +0.2735699713230133,-20.142494201660156,63.43063735961914,0.045279356006086 +0.2725856602191925,-20.144203186035156,63.43577575683594,0.042020273319698334 +0.2718925178050995,-20.145294189453125,63.43434143066406,0.03336835223123475 +0.271474689245224,-20.14599609375,63.43714904785156,0.0037952622138000803 +0.2711493968963623,-20.146556854248047,63.439517974853516,0.01978643555347199 +0.2705549895763397,-20.147563934326172,63.44319152832031,0.029190029570378802 +0.26982662081718445,-20.148801803588867,63.44755554199219,0.03263107733077115 +0.2690076231956482,-20.150217056274414,63.452030181884766,0.03305848374195991 +0.26830610632896423,-20.15145492553711,63.45545196533203,0.0320819540060224 +0.2675558924674988,-20.15281867980957,63.45831298828125,0.030288878961082632 +0.26690810918807983,-20.15403175354004,63.46024703979492,0.0283534060658838 +0.26633575558662415,-20.155139923095703,63.46088409423828,0.022385074915414485 +0.2659771144390106,-20.15586280822754,63.46088409423828,0.012492469982450696 +0.2657676339149475,-20.156293869018555,63.46088409423828,0.009469958010623112 +0.26548922061920166,-20.15686798095703,63.46119689941406,0.011223329911507372 +0.26512429118156433,-20.157617568969727,63.46119689941406,0.02013832675769191 +0.26476675271987915,-20.158340454101562,63.461666107177734,0.014479200515285614 +0.2643266022205353,-20.159194946289062,63.4627799987793,0.02561486808016654 +0.2637687027454376,-20.160282135009766,63.46364212036133,0.025504542155070826 +0.26224491000175476,-20.16323471069336,63.464637756347656,0.0963943723802293 +0.25997310876846313,-20.16783332824707,63.4694938659668,0.14611095564977986 +0.2570253610610962,-20.17388916015625,63.46629333496094,0.15767995775055926 +0.25296667218208313,-20.18253517150879,63.46498107910156,0.26551534033455637 +0.2464391142129898,-20.196319580078125,63.452659606933594,0.34070233601944294 +0.23819705843925476,-20.21342658996582,63.436607360839844,0.4575247079429122 +0.22531254589557648,-20.23945426940918,63.430904388427734,0.47137326815477393 +0.21027730405330658,-20.268558502197266,63.44662094116211,0.6009131444435232 +0.19457562267780304,-20.298145294189453,63.4831428527832,0.7785060780343649 +0.17609746754169464,-20.333038330078125,63.51924514770508,0.90286027890568 +0.15680603682994843,-20.370140075683594,63.54399871826172,1.0141208210272086 +0.13367539644241333,-20.41572380065918,63.55324172973633,1.1434532101428072 +0.10675133764743805,-20.470388412475586,63.53366470336914,1.281177330519274 +0.081532321870327,-20.52290916442871,63.49006271362305,1.3688228969824963 +0.05152028799057007,-20.585487365722656,63.43729782104492,1.4443628755293083 +0.021291742101311684,-20.64727783203125,63.40751647949219,1.3873669534640276 +0.0008315931190736592,-20.68820571899414,63.4049072265625,0.7655472112873092 +-0.014043310657143593,-20.717174530029297,63.41686248779297,0.6417898844014605 +-0.02694690227508545,-20.741344451904297,63.445255279541016,0.6352171988790539 +-0.0410391129553318,-20.767126083374023,63.487998962402344,0.6087005055562713 +-0.05455377325415611,-20.791833877563477,63.529239654541016,0.5736264170343321 +-0.06752270460128784,-20.81599235534668,63.56071090698242,0.534487060134668 +-0.0783965215086937,-20.836837768554688,63.576332092285156,0.4670707041012182 +-0.08585216104984283,-20.851686477661133,63.57743453979492,0.2753186688084778 +-0.09035048633813858,-20.86068344116211,63.577693939208984,0.16561955949757326 +-0.09303388744592667,-20.86605453491211,63.577857971191406,0.10623783774585073 +-0.09456326067447662,-20.86911392211914,63.578250885009766,0.0008381509856395711 +-0.09456390142440796,-20.869117736816406,63.57851791381836,0.0001050921913616365 +-0.0945735052227974,-20.869142532348633,63.578914642333984,9.956502448980682e-05 +-0.09458299726247787,-20.86916732788086,63.57926940917969,9.74847226357026e-05 +-0.09459057450294495,-20.869186401367188,63.57948303222656,9.175968864280343e-05 +-0.09459614753723145,-20.869203567504883,63.57952117919922,8.918999531925954e-05 +-0.09459897875785828,-20.86921501159668,63.57972717285156,8.72823261931945e-05 +-0.09460049122571945,-20.86922836303711,63.579830169677734,8.262970474909899e-05 +-0.09460092335939407,-20.86923599243164,63.5799446105957,7.868831447422134e-05 +-0.09460077434778214,-20.869239807128906,63.5799446105957,7.584288373906943e-05 +-0.09460009634494781,-20.869243621826172,63.5799446105957,7.627929093136539e-05 +-0.09460031986236572,-20.869247436523438,63.5799446105957,1.023480916247853e-05 +-0.09460119903087616,-20.86924934387207,63.5799446105957,8.979880456589079e-06 +-0.09460167586803436,-20.86924934387207,63.5799446105957,7.26245653750833e-06 +-0.0946020558476448,-20.869253158569336,63.5799446105957,6.969328180991159e-06 +-0.09460217505693436,-20.869253158569336,63.5799446105957,6.965732122321511e-06 +-0.09460224956274033,-20.86925506591797,63.5799446105957,6.620396123366277e-06 +-0.09460227936506271,-20.86925506591797,63.5799446105957,6.663118133666057e-06 +-0.09460222721099854,-20.86925506591797,63.5799446105957,6.225577495978449e-06 +-0.09460204094648361,-20.86925506591797,63.5799446105957,4.485697562692246e-05 +-0.09460105746984482,-20.86925506591797,63.5799446105957,0.00013863065177048325 +-0.09459938853979111,-20.86925506591797,63.5799446105957,0.00021196332253757048 +-0.09459875524044037,-20.8692569732666,63.5799446105957,6.042106027126957e-06 +-0.094598688185215,-20.8692569732666,63.5799446105957,4.126164750768801e-06 +-0.09459858387708664,-20.8692569732666,63.5799446105957,5.507196097572126e-06 +-0.09459846466779709,-20.8692569732666,63.5799446105957,5.7523066510836585e-06 +-0.09459836781024933,-20.8692569732666,63.5799446105957,6.307042239845491e-06 +-0.09459817409515381,-20.8692569732666,63.5799446105957,5.948960070779589e-06 +-0.09459802508354187,-20.8692569732666,63.5799446105957,6.069918155025601e-06 +-0.09459786117076874,-20.8692569732666,63.5799446105957,4.048095531794353e-06 +-0.09459765255451202,-20.8692569732666,63.5799446105957,4.802759176742336e-06 +-0.09459755569696426,-20.8692569732666,63.5799446105957,5.8941791158850274e-06 +-0.09459734708070755,-20.8692569732666,63.5799446105957,6.307447651092511e-06 +-0.09459713846445084,-20.8692569732666,63.5799446105957,6.3197531868908595e-06 +-0.0945969820022583,-20.8692569732666,63.5799446105957,5.71452014225357e-06 +-0.09459680318832397,-20.8692569732666,63.5799446105957,4.31833540237071e-06 +-0.09459663927555084,-20.8692569732666,63.5799446105957,5.789847671729818e-06 +-0.0945965051651001,-20.8692569732666,63.5799446105957,5.950461108089341e-06 +-0.09459632635116577,-20.8692569732666,63.5799446105957,5.920586587133453e-06 +-0.09459622949361801,-20.8692569732666,63.5799446105957,5.235541053913579e-06 +-0.09459615498781204,-20.8692569732666,63.5799446105957,6.00053708150588e-06 +-0.09459606558084488,-20.8692569732666,63.5799446105957,5.195985624207711e-06 +-0.0945960134267807,-20.8692569732666,63.5799446105957,5.972390872113914e-06 +-0.09459585696458817,-20.8692569732666,63.5799446105957,5.847543730914525e-06 +-0.09459567815065384,-20.8692569732666,63.5799446105957,5.7609246732478615e-06 +-0.09459549933671951,-20.8692569732666,63.5799446105957,6.020106529895454e-06 +-0.09459540247917175,-20.8692569732666,63.5799446105957,5.6984211613033305e-06 +-0.09459526091814041,-20.8692569732666,63.5799446105957,5.8052116628359284e-06 +-0.09459517896175385,-20.8692569732666,63.5799446105957,5.713263715520705e-06 +-0.09459508955478668,-20.8692569732666,63.5799446105957,5.476315207915015e-06 +-0.09459498524665833,-20.8692569732666,63.5799446105957,5.870169813745109e-06 +-0.09459493309259415,-20.8692569732666,63.5799446105957,5.345551103164102e-06 +-0.09459491819143295,-20.8692569732666,63.5799446105957,5.861885278049635e-06 +-0.09459476172924042,-20.8692569732666,63.5799446105957,5.581364398188465e-06 +-0.09459465742111206,-20.8692569732666,63.5799446105957,5.416115640730852e-06 +-0.09459449350833893,-20.8692569732666,63.5799446105957,5.115254992634551e-06 +-0.09459439665079117,-20.8692569732666,63.5799446105957,5.6612825064584974e-06 +-0.09459428489208221,-20.8692569732666,63.5799446105957,5.797005728191011e-06 +-0.09459404647350311,-20.8692569732666,63.5799446105957,5.990657402897754e-06 +-0.09459390491247177,-20.8692569732666,63.5799446105957,5.998762106039066e-06 +-0.09459377825260162,-20.8692569732666,63.5799446105957,5.317298561655114e-06 +-0.0945935919880867,-20.8692569732666,63.5799446105957,5.1912019522460155e-06 +-0.09459343552589417,-20.8692569732666,63.5799446105957,6.064400615326857e-06 +-0.09459327161312103,-20.8692569732666,63.5799446105957,6.275083493385359e-06 +-0.0945931002497673,-20.8692569732666,63.5799446105957,4.665307674737167e-06 +-0.09459290653467178,-20.8692569732666,63.5799446105957,3.824568944664758e-06 +-0.09459268301725388,-20.8692569732666,63.5799446105957,5.8350271032755015e-06 +-0.09459247440099716,-20.8692569732666,63.5799446105957,6.199512805739571e-06 +-0.09459222853183746,-20.8692569732666,63.5799446105957,6.008543989823248e-06 +-0.09459203481674194,-20.8692569732666,63.5799446105957,5.269913167019785e-06 +-0.09459184110164642,-20.8692569732666,63.5799446105957,6.294446052518625e-06 +-0.0945916697382927,-20.8692569732666,63.5799446105957,5.728591370123189e-06 +-0.094591423869133,-20.8692569732666,63.5799446105957,5.9971748431561694e-06 +-0.09459128230810165,-20.8692569732666,63.5799446105957,5.9857183189821126e-06 +-0.09459112584590912,-20.8692569732666,63.5799446105957,6.050509022256262e-06 +3.804107666015625,-12.09050464630127,67.50428771972656,0.0011726270596512764 +3.8040449619293213,-12.090641975402832,67.50479888916016,0.0010215451059124873 +3.803992509841919,-12.0907564163208,67.50543975830078,0.000868298141519491 +3.80395245552063,-12.090850830078125,67.5060806274414,0.0006908966317144311 +3.8039281368255615,-12.09090805053711,67.50646209716797,0.0005178489901743943 +3.803903818130493,-12.090965270996094,67.50698852539062,0.00046520233917631037 +3.803882598876953,-12.09101676940918,67.50745391845703,0.0003602421951477894 +3.803868055343628,-12.091052055358887,67.50790405273438,0.000296487918854752 +3.8038604259490967,-12.091073036193848,67.50821685791016,0.00018510672928589758 +3.8038549423217773,-12.09108829498291,67.50835418701172,0.0001569272705009786 +3.8038485050201416,-12.091108322143555,67.50879669189453,0.00017898209678266565 +3.8038439750671387,-12.0911226272583,67.50906372070312,0.00011221282989938011 +3.803839683532715,-12.091134071350098,67.50906372070312,0.0001368467485650953 +3.8038384914398193,-12.09113883972168,67.50906372070312,9.766436808697287e-05 +3.803837776184082,-12.091143608093262,67.50906372070312,8.70238252032731e-05 +3.803835868835449,-12.091148376464844,67.50906372070312,8.587108420024433e-05 +3.8038346767425537,-12.091154098510742,67.50906372070312,9.181732272043915e-05 +3.8038341999053955,-12.091157913208008,67.50906372070312,7.472743251921309e-05 +3.803832530975342,-12.091160774230957,67.50906372070312,3.23035400447102e-05 +3.8038313388824463,-12.091160774230957,67.50906372070312,0.0001792413954621268 +3.8038036823272705,-12.091239929199219,67.50906372070312,0.005164572669982453 +3.803720235824585,-12.091456413269043,67.50906372070312,0.00657116729598366 +3.8035740852355957,-12.091822624206543,67.50906372070312,0.014075101046426427 +3.8033504486083984,-12.092373847961426,67.50906372070312,0.015839214660987408 +3.8028552532196045,-12.093576431274414,67.50907897949219,0.03648990325724349 +3.8020613193511963,-12.095490455627441,67.50907897949219,0.04628099231264185 +3.80112886428833,-12.097735404968262,67.50907897949219,0.06297379016183775 +3.7997186183929443,-12.101117134094238,67.50860595703125,0.08723961125779164 +3.7977895736694336,-12.105722427368164,67.50818634033203,0.19347552990440997 +3.7935709953308105,-12.115779876708984,67.50527954101562,0.28310847405880185 +3.7900946140289307,-12.12414264678955,67.50724792480469,0.2958759000521456 +3.7863688468933105,-12.133058547973633,67.5071792602539,0.3153064506662899 +3.778925657272339,-12.15084171295166,67.50727844238281,0.4498864784788059 +3.773280143737793,-12.164350509643555,67.50764465332031,0.5331776171013242 +3.7624363899230957,-12.190247535705566,67.50609588623047,0.637809864836743 +3.7508435249328613,-12.217926979064941,67.50420379638672,0.7235573441526308 +3.7365620136260986,-12.25205135345459,67.50313568115234,0.8387879147712127 +3.7200136184692383,-12.291597366333008,67.50205993652344,0.9299488417483258 +3.7026805877685547,-12.333020210266113,67.50157928466797,1.045443598681639 +3.682868242263794,-12.380329132080078,67.49872589111328,1.1496909230723973 +3.6603474617004395,-12.434139251708984,67.4983139038086,1.2708509107643045 +3.6450092792510986,-12.470791816711426,67.4984359741211,1.3343422019298836 +3.6206657886505127,-12.528984069824219,67.4999008178711,1.417091916615758 +3.5945892333984375,-12.591287612915039,67.49937438964844,1.4856080475080076 +3.5752742290496826,-12.63743782043457,67.49934387207031,1.5149980424957248 +3.5476040840148926,-12.703522682189941,67.49726104736328,1.5256426256273292 +3.5217156410217285,-12.765373229980469,67.49722290039062,1.5182947080290876 +3.4963457584381104,-12.826020240783691,67.4996109008789,1.1672404864722934 +3.481046676635742,-12.862594604492188,67.5014419555664,0.6443447886872599 +3.472839832305908,-12.882205963134766,67.5018539428711,0.3470674544216877 +3.469348907470703,-12.890547752380371,67.50222778320312,0.21117187617580888 +3.4674437046051025,-12.895103454589844,67.50248718261719,0.1299150864435733 +3.4663166999816895,-12.89780044555664,67.50263214111328,0.07466885512246002 +3.4656591415405273,-12.899373054504395,67.50303649902344,0.032994018767006826 +3.465423822402954,-12.899943351745605,67.50342559814453,0.0015057411388751584 +3.4656567573547363,-12.899394989013672,67.50381469726562,0.02151892317161684 +3.466125726699829,-12.89828872680664,67.50418853759766,0.025452555765690502 +3.4663710594177246,-12.897711753845215,67.50444793701172,0.02133335392994084 +3.4665536880493164,-12.89728832244873,67.50469970703125,0.016142756454312613 +3.466660737991333,-12.897043228149414,67.5047607421875,0.005441296313944936 +3.466686964035034,-12.896991729736328,67.50482177734375,0.0018054115331963725 +3.4664299488067627,-12.897623062133789,67.50515747070312,0.027497399744357488 +3.4659111499786377,-12.89887523651123,67.50544738769531,0.03548344510611254 +3.4651896953582764,-12.900617599487305,67.50562286376953,0.04397402853760509 +3.4636683464050293,-12.904271125793457,67.50593566894531,0.1239259452042423 +3.4607176780700684,-12.911308288574219,67.50426483154297,0.19453872971154504 +3.455540895462036,-12.923772811889648,67.50813293457031,0.31196187606239667 +3.4485344886779785,-12.940570831298828,67.5127944946289,0.4767343299194162 +3.4396612644195557,-12.961844444274902,67.51508331298828,0.524131470494053 +3.4296648502349854,-12.985753059387207,67.51508331298828,0.5977174807043615 +3.4171416759490967,-13.01569652557373,67.51507568359375,0.7094561052362804 +3.4084300994873047,-13.03652286529541,67.51507568359375,0.7869282197614852 +3.393012285232544,-13.073382377624512,67.51506042480469,0.8907774561228115 +3.375718355178833,-13.114726066589355,67.5150375366211,0.9953936304623469 +3.3568644523620605,-13.159794807434082,67.5150375366211,1.1013683822598705 +3.343984365463257,-13.190583229064941,67.5150375366211,1.1743844949995272 +3.3220531940460205,-13.24300479888916,67.51502990722656,1.270662055150763 +3.2973525524139404,-13.302043914794922,67.51502990722656,1.350412867909212 +3.2710931301116943,-13.364809036254883,67.51500701904297,1.4292307019612236 +3.247236490249634,-13.421828269958496,67.51476287841797,1.4842067677653599 +3.226876974105835,-13.47048568725586,67.51468658447266,1.5486196969510428 +3.208535671234131,-13.514318466186523,67.51468658447266,1.5973447162516647 +3.1804070472717285,-13.58154296875,67.51468658447266,1.6599092338974344 +3.146954298019409,-13.66148567199707,67.51455688476562,1.7216050373832221 +3.12774658203125,-13.707386016845703,67.51441955566406,1.7535985399213367 +3.0952889919281006,-13.784947395324707,67.51422882080078,1.8038658716415832 +3.0634658336639404,-13.860987663269043,67.51417541503906,1.8495113157081884 +3.0275399684906006,-13.94666862487793,67.51695251464844,1.897335994707538 +2.992741346359253,-14.02855110168457,67.53951263427734,1.9399024895405355 +2.959127187728882,-14.105978965759277,67.59089660644531,1.9776389972945068 +2.9196462631225586,-14.194683074951172,67.69221496582031,2.0181982174952937 +2.882219076156616,-14.276750564575195,67.8272705078125,2.0533807969079714 +2.836855411529541,-14.37382698059082,68.0409164428711,2.0923834542625888 +2.796200752258301,-14.458963394165039,68.2756576538086,2.124361645313265 +2.751291036605835,-14.551300048828125,68.57981872558594,2.157023992841532 +2.7055652141571045,-14.64380931854248,68.93561553955078,2.187651952290545 +2.658423900604248,-14.737894058227539,69.34933471679688,2.2168514823438863 +2.6138904094696045,-14.825812339782715,69.7829360961914,2.2424340461187806 +2.564384937286377,-14.922747611999512,70.31230926513672,2.2689545847531023 +2.515367269515991,-15.018136978149414,70.88516235351562,2.2934214133303774 +2.4676172733306885,-15.110783576965332,71.48945617675781,2.3157093310338346 +2.417435646057129,-15.208046913146973,72.17415618896484,2.337599659400771 +2.369176149368286,-15.301725387573242,72.88136291503906,2.357365422717899 +2.316619396209717,-15.404141426086426,73.70721435546875,2.3775247632057614 +2.264016628265381,-15.50731086730957,74.59400939941406,2.396515594618239 +2.215038776397705,-15.604273796081543,75.47528076171875,2.4131884050613936 +2.1640684604644775,-15.706332206726074,76.45298767089844,2.4294644069384685 +2.118180274963379,-15.79959774017334,77.38951110839844,2.443154514390653 +2.0672800540924072,-15.904842376708984,78.48672485351562,2.4597634336699246 +2.0202107429504395,-16.006181716918945,79.5440673828125,2.4777467210744466 +1.972877025604248,-16.114124298095703,80.64067840576172,2.4966762663010176 +1.926811933517456,-16.226530075073242,81.74931335449219,2.5132841288432943 +1.8850370645523071,-16.334199905395508,82.8056869506836,2.52642770157898 +1.8471819162368774,-16.436262130737305,83.81607055664062,2.5380402268646405 +1.805844783782959,-16.553468704223633,84.98247528076172,2.5518396895361106 +1.7690998315811157,-16.664600372314453,86.07853698730469,2.5652037818716895 +1.731989860534668,-16.785810470581055,87.25133514404297,2.5793533962384005 +1.6987632513046265,-16.903955459594727,88.37215423583984,2.5917257387153994 +1.669561743736267,-17.01621437072754,89.42987823486328,2.6019641698613336 +1.642629861831665,-17.12763786315918,90.48076629638672,2.611513543432285 +1.6166809797286987,-17.24403190612793,91.57814025878906,2.6214880156156433 +1.5922836065292358,-17.36461067199707,92.7087631225586,2.631554284658707 +1.5691393613815308,-17.492460250854492,93.90009307861328,2.641541005221711 +1.5500521659851074,-17.61138916015625,95.00456237792969,2.6501494018866127 +1.5322474241256714,-17.73826026916504,96.1800308227539,2.6589584992617668 +1.518424391746521,-17.85289764404297,97.23942565917969,2.666543125425474 +1.5060148239135742,-17.97551155090332,98.37006378173828,2.6742718490756996 +1.495537519454956,-18.10547637939453,99.5662612915039,2.682056547505076 +1.488025188446045,-18.23059844970703,100.71519470214844,2.689399823485975 +1.483046054840088,-18.35945701599121,101.89030456542969,2.697046145924054 +1.480969786643982,-18.483816146850586,103.01422119140625,2.7039269320764228 +1.4813143014907837,-18.598819732666016,104.05032348632812,2.709428900814889 +1.484157681465149,-18.728759765625,105.223876953125,2.7152096988003014 +1.4893842935562134,-18.854509353637695,106.36283111572266,2.7207649289709317 +1.4967669248580933,-18.974489212036133,107.449951171875,2.7257091113782907 +1.5071542263031006,-19.10274314880371,108.61134338378906,2.7314966036582997 +1.5199944972991943,-19.22880744934082,109.74824523925781,2.737656235143565 +1.5357519388198853,-19.355945587158203,110.88842010498047,2.7429172009001266 +1.5543098449707031,-19.483434677124023,112.03246307373047,2.7468530051656486 +1.5743298530578613,-19.604782104492188,113.12773895263672,2.7506665135712303 +1.5983774662017822,-19.734769821166992,114.30653381347656,2.7550661713764164 +1.623377799987793,-19.85614776611328,115.408935546875,2.759312128390278 +1.652763843536377,-19.98489761352539,116.57544708251953,2.763921807788341 +1.6826364994049072,-20.104076385498047,117.65238189697266,2.767723053081619 +1.7133523225784302,-20.217464447021484,118.68080139160156,2.7706517851457035 +1.7531641721725464,-20.353946685791016,119.92972564697266,2.7739749684202586 +1.7912909984588623,-20.47541046142578,121.0488510131836,2.7774005520404526 +1.8297165632247925,-20.589698791503906,122.10163116455078,2.780943139949858 +1.8727130889892578,-20.709274291992188,123.2005386352539,2.7843552977434527 +1.9214385747909546,-20.836402893066406,124.37387084960938,2.787022688969063 +1.9461218118667603,-20.906076431274414,125.21869659423828,0.13685318838437915 +1.9481353759765625,-20.917274475097656,125.39012145996094,0.07873463608672546 +1.9460868835449219,-20.91912841796875,125.46331787109375,0.05902592071822837 +1.944417953491211,-20.92048454284668,125.51851654052734,0.05108932770758062 +1.9429984092712402,-20.921552658081055,125.56398010253906,0.04370234427739156 +1.9416698217391968,-20.922452926635742,125.60408782958984,0.02389833569923645 +1.9410213232040405,-20.92287826538086,125.62140655517578,0.012419248326772086 +1.940490961074829,-20.92302131652832,125.63200378417969,0.006905780704679991 +1.93983793258667,-20.923158645629883,125.64405822753906,0.026311830482506127 +1.939103364944458,-20.923229217529297,125.65775299072266,0.011022149389726793 +1.9388526678085327,-20.923105239868164,125.65969848632812,0.006383942053938946 +1.9386937618255615,-20.923004150390625,125.65962982177734,0.005835790852093436 +1.9386732578277588,-20.922832489013672,125.65435791015625,0.005314186956015144 +1.9383593797683716,-20.922765731811523,125.65697479248047,0.006954294292832154 +1.937745451927185,-20.922794342041016,125.67039489746094,0.007608445365520451 +1.937369704246521,-20.92278289794922,125.67861938476562,0.007781437807353007 +1.9370044469833374,-20.922780990600586,125.68421936035156,0.00552245888461437 +1.9364854097366333,-20.922868728637695,125.696044921875,0.011435148220124447 +1.935930609703064,-20.923004150390625,125.71036529541016,0.008908599257337519 +1.9356504678726196,-20.923051834106445,125.71702575683594,0.003610591978922425 +1.9352357387542725,-20.92316436767578,125.72489929199219,0.0066272258992931465 +1.934795618057251,-20.923307418823242,125.73686218261719,0.011633808490354598 +1.9343547821044922,-20.923437118530273,125.74988555908203,0.013676621443671577 +1.9338120222091675,-20.923648834228516,125.76637268066406,0.01866234311609512 +1.933366298675537,-20.923725128173828,125.77550506591797,0.006416227472948836 +1.9330819845199585,-20.92371940612793,125.77974700927734,0.003701109882417208 +1.9328722953796387,-20.923673629760742,125.78177642822266,0.003057770298492828 +1.9326800107955933,-20.923583984375,125.78295135498047,0.0019089873477697787 +1.9325323104858398,-20.923498153686523,125.78353118896484,0.0016982731542745978 +1.932371735572815,-20.92339324951172,125.7837905883789,0.0010329987361513775 +1.9322373867034912,-20.92330551147461,125.78398132324219,0.0045871275296047054 +1.9321234226226807,-20.923200607299805,125.78404998779297,0.0009240897165186856 +1.9320261478424072,-20.92314338684082,125.7840347290039,0.0018560705886029455 +1.9318828582763672,-20.923004150390625,125.78372192382812,0.0013190296523151064 +1.9318037033081055,-20.92290687561035,125.78339385986328,0.0008716475514108826 +1.9317398071289062,-20.922832489013672,125.78288269042969,0.0006463139838016465 +1.9316864013671875,-20.922771453857422,125.78243255615234,0.0005681246554277077 +1.931639552116394,-20.922712326049805,125.78199768066406,0.00046679330389408515 +1.9316033124923706,-20.92266845703125,125.78158569335938,0.00035414413629788376 +1.9315792322158813,-20.92262077331543,125.78123474121094,0.00032822801963367204 +1.9315694570541382,-20.922588348388672,125.78168487548828,0.00037470476598351426 +1.9315568208694458,-20.922550201416016,125.78182220458984,0.00021572464148971165 +1.9315505027770996,-20.92251968383789,125.7821044921875,0.0001975622907984845 +1.931545376777649,-20.922494888305664,125.78215026855469,0.0003618747253979956 +1.9315365552902222,-20.922475814819336,125.7820816040039,0.00014201286934543064 +1.9315276145935059,-20.922460556030273,125.78202819824219,0.00022556791595336416 +1.9315149784088135,-20.92245101928711,125.7819595336914,7.314389806588431e-05 +1.9314979314804077,-20.92244529724121,125.78170013427734,4.39014273866101e-05 +1.9314937591552734,-20.92244529724121,125.78170013427734,4.103626788891303e-05 +1.9314836263656616,-20.92244529724121,125.78170013427734,2.077149870505732e-05 +1.9314607381820679,-20.92244529724121,125.7816390991211,7.098503739862834e-05 +1.9314467906951904,-20.922449111938477,125.78163146972656,1.9033416601110125e-05 +1.931436538696289,-20.922449111938477,125.78163146972656,3.6816324583204655e-05 +1.931429147720337,-20.92245101928711,125.78157043457031,1.0295884661413426e-05 +1.9314254522323608,-20.92245101928711,125.78157043457031,3.9108734386728945e-05 +1.9314162731170654,-20.92245101928711,125.78153228759766,2.2366170698905127e-05 +1.9314091205596924,-20.922452926635742,125.78150939941406,8.879213121736827e-06 +1.9314038753509521,-20.922454833984375,125.78150939941406,5.359076542227108e-06 +1.931397557258606,-20.922454833984375,125.78150939941406,3.642635021094989e-05 +1.9313929080963135,-20.922454833984375,125.78150939941406,2.8217148232854317e-05 +1.9313840866088867,-20.92245864868164,125.781494140625,1.8749255726895422e-05 +1.9313801527023315,-20.92245864868164,125.78150939941406,1.7113479462391394e-05 +1.931377649307251,-20.922460556030273,125.78150939941406,1.3322314374023233e-05 +1.9313764572143555,-20.922460556030273,125.78150939941406,5.967138038702097e-06 +1.931374430656433,-20.922460556030273,125.78150939941406,5.38525519568919e-06 +1.9313725233078003,-20.922462463378906,125.78150939941406,2.342760834290147e-05 +1.9313710927963257,-20.922462463378906,125.78150939941406,1.2538722944998563e-05 +1.9313708543777466,-20.922462463378906,125.78150939941406,4.952590404725444e-06 +1.931369423866272,-20.922462463378906,125.78150939941406,2.2654779422056536e-05 +1.9313678741455078,-20.922466278076172,125.78150939941406,1.1520331393304e-05 +1.9313663244247437,-20.922466278076172,125.78150939941406,2.81322674652557e-05 +1.9313651323318481,-20.922466278076172,125.78150939941406,2.8563418526508644e-05 +1.931363821029663,-20.922466278076172,125.78150939941406,8.0591873682588e-06 +1.931362271308899,-20.922466278076172,125.78150939941406,3.9945163799095066e-06 +1.9313608407974243,-20.922466278076172,125.78150939941406,3.39755430205333e-05 +1.9313594102859497,-20.922466278076172,125.78144073486328,2.6577028034022457e-05 +1.931357502937317,-20.922468185424805,125.78144073486328,1.4494476309602312e-05 +1.9313572645187378,-20.922468185424805,125.78144073486328,1.2894562260555669e-05 +1.931355357170105,-20.922468185424805,125.78144073486328,2.0719351873910722e-05 +1.9313552379608154,-20.922468185424805,125.78144073486328,9.78696052183011e-06 +1.9313547611236572,-20.922468185424805,125.78144073486328,4.083729475319393e-06 +1.9313547611236572,-20.922468185424805,125.78144073486328,9.700138583037692e-06 +1.9313547611236572,-20.922468185424805,125.78144073486328,1.500934156719216e-05 +1.9313536882400513,-20.922468185424805,125.78144073486328,2.2941631388869223e-05 +1.931353211402893,-20.922466278076172,125.78144073486328,1.144745920494208e-05 +1.931353211402893,-20.922466278076172,125.78144073486328,3.6998238012949126e-05 +1.9313514232635498,-20.922466278076172,125.78144073486328,1.3202092677828179e-05 +1.9313507080078125,-20.922468185424805,125.78144073486328,2.5106107812293256e-05 +1.9313507080078125,-20.922466278076172,125.78144073486328,1.2618133135254591e-05 +1.9313501119613647,-20.922466278076172,125.78144073486328,1.2028215585292332e-05 +1.9312565326690674,-20.92232894897461,125.77928924560547,0.004545230348979482 +1.930860996246338,-20.921661376953125,125.77557373046875,0.04234949518147312 +1.9303228855133057,-20.92074203491211,125.7718505859375,0.0054627517437776515 +1.9297471046447754,-20.919776916503906,125.76813507080078,0.04792112999186251 +1.9287241697311401,-20.918136596679688,125.76290130615234,0.06512921042216747 +1.927825927734375,-20.916723251342773,125.7593994140625,0.017998025994624765 +1.9270968437194824,-20.91559600830078,125.75798034667969,0.024702093209993177 +1.9258763790130615,-20.913787841796875,125.75574493408203,0.03404052424130316 +1.9242169857025146,-20.91141128540039,125.75483703613281,0.08592126557464856 +1.9222259521484375,-20.908607482910156,125.75706481933594,0.07402470436492153 +1.9189162254333496,-20.90414810180664,125.75809478759766,0.1193857058793975 +1.9144290685653687,-20.89820098876953,125.7703857421875,0.1822011808487134 +1.9092730283737183,-20.891578674316406,125.78680419921875,0.19285527452579673 +1.9025996923446655,-20.883224487304688,125.81273651123047,0.2556700823416891 +1.8942712545394897,-20.87311553955078,125.84833526611328,0.26435702348637596 +1.8851232528686523,-20.86224365234375,125.89776611328125,0.33094328283202656 +1.8737953901290894,-20.84908676147461,125.96961212158203,0.4241816222108051 +1.8586856126785278,-20.832088470458984,126.06968688964844,0.5031975353487887 +1.842514157295227,-20.814422607421875,126.18661499023438,0.5452888266480067 +1.8238897323608398,-20.794618606567383,126.3314208984375,0.6000456917722585 +1.8033338785171509,-20.773420333862305,126.49878692626953,0.6967747698841349 +1.7793998718261719,-20.749475479125977,126.7045669555664,0.752964481321092 +1.751238465309143,-20.722152709960938,126.96337127685547,0.8229446353353168 +1.7228292226791382,-20.69538688659668,127.23875427246094,0.8961749103317805 +1.6897186040878296,-20.66478729248047,127.56522369384766,0.9697219116689041 +1.655669927597046,-20.63351058959961,127.89289093017578,1.0256347796135783 +1.620658278465271,-20.601327896118164,128.22256469726562,1.087839437104706 +1.5796318054199219,-20.563722610473633,128.60037231445312,1.1793569939743758 +1.540302038192749,-20.528057098388672,128.96084594726562,1.2363830744009967 +1.497362494468689,-20.489723205566406,129.35577392578125,1.284125590249274 +1.4492145776748657,-20.447368621826172,129.7942657470703,1.3574354821371006 +1.403335690498352,-20.407461166381836,130.2072296142578,1.4208592496319654 +1.3497140407562256,-20.361469268798828,130.67681884765625,1.4866991019671154 +1.2926981449127197,-20.313344955444336,131.17323303222656,1.5510562530906502 +1.2388291358947754,-20.268535614013672,131.63650512695312,1.6070714451341153 +1.1794365644454956,-20.219818115234375,132.13882446289062,1.664618235492469 +1.1182270050048828,-20.170379638671875,132.6574249267578,1.7167645337287523 +1.0526059865951538,-20.118438720703125,133.2073516845703,1.77944376929406 +0.9888590574264526,-20.068950653076172,133.73805236816406,1.834333231010732 +0.9192079901695251,-20.01588249206543,134.31167602539062,1.8895812683301891 +0.8506484627723694,-19.964534759521484,134.86724853515625,1.9419392074335764 +0.7773054242134094,-19.91053009033203,135.45216369628906,1.9944293266724142 +0.7002883553504944,-19.85490608215332,136.06005859375,2.045416869199318 +0.6190502047538757,-19.79761505126953,136.6967010498047,2.098066850651069 +0.5353936553001404,-19.74004364013672,137.34800720214844,2.149532335165848 +0.45470476150512695,-19.685771942138672,137.97071838378906,2.196818701346502 +0.3683570325374603,-19.629064559936523,138.63150024414062,2.244862615491618 +0.2823984622955322,-19.57392692565918,139.28431701660156,2.2907982018453747 +0.1916394829750061,-19.517168045043945,139.96829223632812,2.3372832348936803 +0.09516523778438568,-19.458444595336914,140.68959045410156,2.3845794114448635 +-0.00011975169036304578,-19.402034759521484,141.3971405029297,2.429139432035108 +-0.09469129145145416,-19.347702026367188,142.09893798828125,2.4711783219464185 +-0.19632524251937866,-19.291202545166016,142.85487365722656,2.514597091113901 +-0.30158811807632446,-19.23457908630371,143.63406372070312,2.5584350996910254 +-0.40707868337631226,-19.17955207824707,144.4057159423828,2.600899488904197 +-0.506578266620636,-19.129194259643555,145.12620544433594,2.6392471750767874 +-0.6593042612075806,-19.055017471313477,146.2257537841797,2.69419161771184 +-0.7807249426841736,-18.998748779296875,147.10079956054688,2.736582944444462 +-0.89678555727005,-18.947202682495117,147.9391632080078,2.7751798283173645 +-1.023310899734497,-18.89328384399414,148.8459930419922,2.7996862315186846 +-1.1449140310287476,-18.843626022338867,149.70916748046875,2.788985791671228 +-1.2605094909667969,-18.798532485961914,150.53033447265625,2.7597262522019124 +-1.3838666677474976,-18.75279426574707,151.41184997558594,2.7176202599089865 +-1.498981237411499,-18.712236404418945,152.23536682128906,2.6730880243784925 +-1.6170599460601807,-18.67271614074707,153.08038330078125,2.6241440894866623 +-1.7386521100997925,-18.63421630859375,153.95230102539062,2.570486287872554 +-1.853090524673462,-18.59994888305664,154.7713623046875,2.4982678321531964 +-1.9558368921279907,-18.570720672607422,155.50254821777344,2.4016477719617217 +-2.0700058937072754,-18.540002822875977,156.31361389160156,2.297421431036775 +-2.1718978881835938,-18.51427459716797,157.0423126220703,2.1983181474671545 +-2.2333977222442627,-18.4963436126709,157.56556701660156,0.4347378195576442 +-2.2319235801696777,-18.495216369628906,157.59051513671875,0.0021178551542137872 +-2.231947898864746,-18.495166778564453,157.59071350097656,0.0015302819614880627 +-2.2318599224090576,-18.495101928710938,157.59071350097656,0.0018248641543378804 +-2.231764078140259,-18.49505043029785,157.5906982421875,0.0015169722198825997 +-2.2316644191741943,-18.495004653930664,157.59071350097656,0.0011759634355002814 +-2.231590747833252,-18.49497413635254,157.59071350097656,0.0009225883582197594 +-2.231534719467163,-18.49495506286621,157.5907745361328,0.0007419215648926277 +-2.2314870357513428,-18.49493408203125,157.59078979492188,0.0005630794985510705 +-2.2314512729644775,-18.494922637939453,157.59078979492188,0.0004294675108579798 +-2.2314250469207764,-18.49490737915039,157.59078979492188,0.00014703122518486248 +-2.2314016819000244,-18.49488639831543,157.59078979492188,6.862135540178675e-05 +-2.231384038925171,-18.494869232177734,157.59078979492188,5.05638917927012e-05 +-2.231372594833374,-18.494855880737305,157.59078979492188,3.937914312207224e-05 +-2.23136305809021,-18.49484634399414,157.5907745361328,7.477075599465238e-05 +-2.231350898742676,-18.494840621948242,157.5907745361328,0.0002133608933500085 +-2.231327772140503,-18.494834899902344,157.59078979492188,0.0004779707046863243 +-2.231294870376587,-18.49483299255371,157.5907745361328,0.000758862163823139 +-2.2312533855438232,-18.494842529296875,157.5907745361328,0.0010247985983688102 +-2.2311971187591553,-18.494855880737305,157.5907745361328,0.001289329539851441 +-2.231132984161377,-18.494871139526367,157.5907745361328,0.0015154986342321738 +-2.2310521602630615,-18.49488639831543,157.5907745361328,0.00173626833114157 +-2.231008291244507,-18.494892120361328,157.5907745361328,3.0122083750308707e-06 +-2.231008291244507,-18.494890213012695,157.5907745361328,3.60493642949911e-06 +-2.2310078144073486,-18.494890213012695,157.5907745361328,3.7005215567941733e-06 +-2.2310075759887695,-18.494890213012695,157.5907745361328,2.479506175680501e-06 +-2.2310070991516113,-18.494888305664062,157.5907745361328,2.728143593483241e-06 +-2.2310068607330322,-18.494888305664062,157.5907745361328,4.254777062665247e-06 +-2.231006622314453,-18.494888305664062,157.5907745361328,3.989468274913136e-06 +-2.231006383895874,-18.494888305664062,157.5907745361328,4.220537350686765e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.493346295660607e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.305640717312689e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,3.619996465866957e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.362082846544139e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.36308707978422e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.5809400882801995e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.401825411713115e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.206979140946899e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.577500580768785e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.294554935738144e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.647898434823767e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,2.392264212686348e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.2979776895155305e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.570963356826447e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.64778718687501e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.567598778415361e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.554639379813861e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.090240149911153e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.077484285290537e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.263240774646533e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,4.669964875539581e-06 +-2.231006383895874,-18.49488639831543,157.5907745361328,3.6471298681584215e-06 +-2.230980396270752,-18.494869232177734,157.58876037597656,0.004334314793779177 +-2.231001615524292,-18.494874954223633,157.590576171875,0.005354941249157282 +-2.2309744358062744,-18.494873046875,157.59059143066406,0.005454628439039972 +-2.230795383453369,-18.494943618774414,157.59136962890625,0.02076622613342527 +-2.230088949203491,-18.49509048461914,157.58543395996094,0.01048880740865019 +-2.229133129119873,-18.49529266357422,157.58053588867188,0.032739635303181275 +-2.2276670932769775,-18.495609283447266,157.57012939453125,0.04522141088852977 +-2.2250421047210693,-18.496206283569336,157.54832458496094,0.05174847407167711 +-2.2221744060516357,-18.496809005737305,157.5268096923828,0.05367628014856545 +-2.2167105674743652,-18.49806785583496,157.4786834716797,0.16031268703279075 +-2.2089407444000244,-18.49979019165039,157.4176788330078,0.1780938192177834 +-2.199777364730835,-18.501798629760742,157.34510803222656,0.2607677907836233 +-2.18406343460083,-18.505287170410156,157.2264404296875,0.3697358066613344 +-2.167004346847534,-18.50909423828125,157.0937957763672,0.45010390985358595 +-2.1418821811676025,-18.514904022216797,156.9015655517578,0.5691400655096621 +-2.1162149906158447,-18.520957946777344,156.69784545898438,0.6183299292550772 +-2.0855934619903564,-18.528270721435547,156.47158813476562,0.7430516731332769 +-2.050494432449341,-18.536745071411133,156.20712280273438,0.823364257162366 +-2.007983446121216,-18.547285079956055,155.88731384277344,0.9285829884908706 +-1.9647026062011719,-18.55835723876953,155.56378173828125,1.017410984005996 +-1.91969633102417,-18.570180892944336,155.22804260253906,1.0889983011308306 +-1.8675696849822998,-18.584165573120117,154.8347625732422,1.1381116115172782 +-1.8145525455474854,-18.598867416381836,154.43807983398438,1.2562446018725688 +-1.7537096738815308,-18.616352081298828,153.9891815185547,1.3599187947896074 +-1.691111445426941,-18.634931564331055,153.52871704101562,1.4321934406965442 +-1.625940203666687,-18.65479278564453,153.0476531982422,1.493735885739423 +-1.5599862337112427,-18.675466537475586,152.5583038330078,1.5489461951531107 +-1.4917298555374146,-18.69757843017578,152.05477905273438,1.5910914691265041 +-1.4172145128250122,-18.72262954711914,151.50965881347656,1.6095446039281889 +-1.347527027130127,-18.746809005737305,150.99851989746094,1.5759607030851561 +-1.283437728881836,-18.769582748413086,150.5244598388672,1.5091532236834098 +-1.2172491550445557,-18.793655395507812,150.03111267089844,1.4189963464305915 +-1.1615760326385498,-18.814407348632812,149.61512756347656,1.3333818014480256 +-1.103782296180725,-18.836456298828125,149.1819305419922,1.2385903017021103 +-1.0503244400024414,-18.857288360595703,148.77899169921875,1.1477132846411227 +-1.0053046941757202,-18.87516975402832,148.438232421875,1.0696874053784753 +-0.9587288498878479,-18.893999099731445,148.08441162109375,0.9880165835846153 +-0.9168372750282288,-18.91122055053711,147.7646942138672,0.9140219847153663 +-0.8810491561889648,-18.92613983154297,147.4903106689453,0.8504403312990102 +-0.846594512462616,-18.940637588500977,147.22323608398438,0.788949080002605 +-0.8124434947967529,-18.95511245727539,146.95498657226562,0.7279892713203407 +-0.7833658456802368,-18.96757698059082,146.72564697265625,0.6761440048043197 +-0.7553845643997192,-18.97972297668457,146.50534057617188,0.6261699424827536 +-0.7312923073768616,-18.99028968811035,146.3153533935547,0.5829901652402951 +-0.7080283164978027,-19.00054168701172,146.12997436523438,0.5411232562059085 +-0.6805421113967896,-19.012725830078125,145.9029083251953,0.4668093396561187 +-0.6568922400474548,-19.02313232421875,145.71994018554688,0.38370799790940224 +-0.6423896551132202,-19.029600143432617,145.60348510742188,0.33731184049824314 +-0.6279792785644531,-19.03606414794922,145.4893798828125,0.3203146129806527 +-0.6155763268470764,-19.04176139831543,145.38400268554688,0.3130041977691415 +-0.6009305715560913,-19.048452377319336,145.26052856445312,0.33286125380069165 +-0.5875257253646851,-19.0545654296875,145.14955139160156,0.36125152276058875 +-0.5703212022781372,-19.062503814697266,145.0098876953125,0.40969340122248427 +-0.551518440246582,-19.07122802734375,144.8555145263672,0.4370896824894099 +-0.5326667428016663,-19.080053329467773,144.70095825195312,0.5098764976708077 +-0.5104770660400391,-19.09050941467285,144.51588439941406,0.531930462535942 +-0.48437488079071045,-19.10299301147461,144.3037872314453,0.6182410790305785 +-0.4576937258243561,-19.115907669067383,144.08921813964844,0.6723722102067059 +-0.42839884757995605,-19.13031005859375,143.84275817871094,0.7087541831924172 +-0.3983682096004486,-19.145158767700195,143.5971221923828,0.7604809990166826 +-0.3653387129306793,-19.161720275878906,143.3299102783203,0.8218230851691273 +-0.3288755416870117,-19.1802921295166,143.0376739501953,0.8676271879000075 +-0.2917601764202118,-19.19951820373535,142.73434448242188,0.9168591463146009 +-0.25364944338798523,-19.21947479248047,142.42384338378906,0.9742002704517598 +-0.21185119450092316,-19.24163818359375,142.08425903320312,1.0237069903506377 +-0.1688128560781479,-19.264833450317383,141.74111938476562,1.086302190350935 +-0.12494496256113052,-19.28896713256836,141.39053344726562,1.1360359813641343 +-0.07794956862926483,-19.315229415893555,141.015380859375,1.1769216369205064 +-0.03133239224553108,-19.341678619384766,140.63584899902344,1.2182991692112453 +0.01682511903345585,-19.36936378479004,140.24746704101562,1.2606038615623114 +0.07024811953306198,-19.40066146850586,139.8199462890625,1.2868936700675435 +0.12138713896274567,-19.43129539489746,139.4112091064453,1.3291871194402503 +0.17562103271484375,-19.464385986328125,138.9743194580078,1.3558675631866874 +0.22743424773216248,-19.496471405029297,138.5550537109375,1.3974761207212878 +0.2870781123638153,-19.53397560119629,138.07379150390625,1.4318486796848782 +0.34090831875801086,-19.568511962890625,137.6298370361328,1.4472125397411604 +0.3997608423233032,-19.607030868530273,137.15150451660156,1.4722154015368452 +0.45694950222969055,-19.645309448242188,136.6933135986328,1.5067929979402699 +0.5130634307861328,-19.68353271484375,136.23934936523438,1.5331626371972702 +0.5751857161521912,-19.726577758789062,135.73114013671875,1.5475663217538338 +0.6358952522277832,-19.769372940063477,135.22938537597656,1.5532905404506558 +0.6922305226325989,-19.809871673583984,134.75770568847656,1.5805562123261314 +0.7559146881103516,-19.8565731048584,134.2257843017578,1.6145395271233638 +0.8158752918243408,-19.901439666748047,133.7220001220703,1.6201095686723679 +0.8733554482460022,-19.945358276367188,133.24380493164062,1.6365120979615175 +0.9367818832397461,-19.994789123535156,132.71621704101562,1.666262392662885 +0.9971982836723328,-20.04269027709961,132.20831298828125,1.6817565253180757 +1.0605435371398926,-20.093839645385742,131.67076110839844,1.7033151255608134 +1.1203433275222778,-20.143062591552734,131.161376953125,1.715867956036556 +1.1809847354888916,-20.193920135498047,130.6412811279297,1.726005771155807 +1.2414242029190063,-20.24566078186035,130.1220245361328,1.7403383048237702 +1.3052457571029663,-20.301538467407227,129.5747833251953,1.7570709536380407 +1.3647211790084839,-20.354673385620117,129.06195068359375,1.7707983843230926 +1.420564889907837,-20.405376434326172,128.57562255859375,1.7703268887964838 +1.4810844659805298,-20.461246490478516,128.0424346923828,1.7874958655270807 +1.5454813241958618,-20.521907806396484,127.47088623046875,1.8051247860863675 +1.6062064170837402,-20.58026885986328,126.92717742919922,1.8213830900521712 +1.6692070960998535,-20.642009735107422,126.35783386230469,1.82921259056985 +1.7283729314804077,-20.701269149780273,125.82308959960938,1.843574641504346 +1.785806655883789,-20.760089874267578,125.30464935302734,1.857008542366667 +1.8448994159698486,-20.821794509887695,124.7671127319336,1.8694617575696753 +1.9078245162963867,-20.888710021972656,124.18650817871094,1.8853762290024756 +1.9308513402938843,-20.89156150817871,123.6718521118164,0.3145527298324881 +1.939583420753479,-20.889347076416016,123.45033264160156,0.17312777872422985 +1.9453535079956055,-20.887985229492188,123.3106689453125,0.13757463628733177 +1.9494216442108154,-20.88693618774414,123.21185302734375,0.0810964090510537 +1.9536559581756592,-20.885589599609375,123.1083984375,0.10886373632161642 +1.9576183557510376,-20.88425064086914,123.0096206665039,0.09197739250600526 +1.9610742330551147,-20.88298988342285,122.92134857177734,0.09088788467903765 +1.964394450187683,-20.881731033325195,122.83553314208984,0.07815612308028813 +1.9674180746078491,-20.88050079345703,122.75720977783203,0.07354316631570187 +1.9702672958374023,-20.87936019897461,122.68364715576172,0.07486237853153915 +1.9730182886123657,-20.878238677978516,122.6128158569336,0.06658904529159469 +1.9757570028305054,-20.877174377441406,122.54415893554688,0.05238001831101092 +1.978279948234558,-20.876169204711914,122.48241424560547,0.06929504801203708 +1.9812003374099731,-20.87506103515625,122.40997314453125,0.07293033651579539 +1.9836596250534058,-20.874122619628906,122.34892272949219,0.06790231441782345 +1.9860233068466187,-20.873241424560547,122.28854370117188,0.06725517948044238 +1.9885146617889404,-20.872323989868164,122.22371673583984,0.05876008418453514 +1.9912692308425903,-20.871347427368164,122.15409851074219,0.06325112512109923 +1.993631362915039,-20.870513916015625,122.09459686279297,0.06585005984678467 +1.996181607246399,-20.869609832763672,122.0297622680664,0.06499399252569676 +1.9986302852630615,-20.868852615356445,121.97181701660156,0.042642958089222 +2.0009214878082275,-20.868009567260742,121.91436004638672,0.06243261817829401 +2.002976655960083,-20.867279052734375,121.86351776123047,0.04754989537513548 +2.004290819168091,-20.866777420043945,121.82899475097656,0.027401114294374935 +2.0051896572113037,-20.86636734008789,121.80488586425781,0.02130336101475033 +2.0059399604797363,-20.865983963012695,121.78462982177734,0.01737036899872102 +2.006495714187622,-20.86564826965332,121.76959228515625,0.013845165737802503 +2.0069103240966797,-20.86536979675293,121.7581558227539,0.011586908031609621 +2.007293224334717,-20.86508560180664,121.74763488769531,0.009185322380059776 +2.007551431655884,-20.86486053466797,121.74021911621094,0.007291233922008366 +2.0077672004699707,-20.864652633666992,121.73410034179688,0.005793120553460985 +2.007938861846924,-20.864471435546875,121.72914123535156,0.0046708047255474535 +2.008066415786743,-20.864336013793945,121.7254638671875,0.00407879213305266 +2.0081822872161865,-20.864200592041016,121.7222671508789,0.0031280481623046216 +2.0082695484161377,-20.86408805847168,121.7200698852539,0.0024565478093558127 +2.0083394050598145,-20.863994598388672,121.71830749511719,0.002013838907113047 +2.0084002017974854,-20.863935470581055,121.7168197631836,0.0024545679332549277 +2.008469581604004,-20.863859176635742,121.7151107788086,0.0017574801997494234 +2.0085182189941406,-20.863780975341797,121.71395111083984,0.001022512602775447 +2.0085458755493164,-20.863727569580078,121.7135238647461,0.0008282927966729683 +2.0085675716400146,-20.863691329956055,121.71308898925781,0.0007440711150156864 +2.008589506149292,-20.863658905029297,121.71286010742188,0.0006510943757035574 +2.0086047649383545,-20.863632202148438,121.71281433105469,0.0005002212806291432 +2.008622169494629,-20.863611221313477,121.71267700195312,0.00042903365205208593 +2.0086185932159424,-20.86359977722168,121.71295166015625,0.00020858909514795545 +2.0086066722869873,-20.86359405517578,121.7132797241211,0.00021918974068179121 +2.0085954666137695,-20.86359405517578,121.71333312988281,0.00023460661674877485 +2.00858473777771,-20.86358642578125,121.71341705322266,0.00018079082123489626 +2.008575201034546,-20.863582611083984,121.71341705322266,3.6666525658162226e-05 +2.0085690021514893,-20.863582611083984,121.71341705322266,4.396966333344364e-05 +2.0085668563842773,-20.863582611083984,121.71341705322266,6.3370348399165e-06 +2.0085654258728027,-20.86358642578125,121.71343231201172,4.114912195114408e-05 +2.0085644721984863,-20.86358642578125,121.71343231201172,6.748680481044707e-05 +2.008563995361328,-20.86358642578125,121.71343231201172,4.638081655682391e-06 +2.008563995361328,-20.86358642578125,121.71343231201172,8.692757648620871e-06 +2.008563756942749,-20.86358642578125,121.71343231201172,5.095204471405218e-05 +2.008563280105591,-20.86358642578125,121.71343231201172,2.2481439099816803e-06 +2.008563756942749,-20.86358642578125,121.71343231201172,4.801146399517866e-05 +2.0085620880126953,-20.863588333129883,121.71343231201172,4.197868811764113e-05 +2.0085623264312744,-20.863588333129883,121.71343231201172,4.2651544878697075e-05 +2.008561611175537,-20.863590240478516,121.71341705322266,5.632558781930324e-05 +2.008561134338379,-20.863588333129883,121.71341705322266,1.0212961152208121e-05 +2.008561372756958,-20.863588333129883,121.71341705322266,3.860289200237522e-05 +2.0085623264312744,-20.863588333129883,121.71341705322266,2.582100715970392e-06 +2.0085625648498535,-20.86358642578125,121.71341705322266,4.1359337106620554e-05 +2.008561611175537,-20.86358642578125,121.71341705322266,4.23610211965491e-05 +2.008561134338379,-20.86358642578125,121.71341705322266,3.1574743363319784e-06 +2.0085604190826416,-20.863588333129883,121.71345520019531,5.187414953404666e-05 +2.0085606575012207,-20.863588333129883,121.71345520019531,2.719231665296365e-06 +2.0085625648498535,-20.86358642578125,121.71347045898438,5.157521539548889e-05 +2.008561849594116,-20.86358642578125,121.71347045898438,3.856714547098421e-05 +2.008561849594116,-20.86358642578125,121.71347045898438,5.1318398894656474e-05 +2.008561134338379,-20.86358642578125,121.71347045898438,5.587053885677376e-05 +2.0085599422454834,-20.863588333129883,121.71347045898438,2.2462773410847607e-06 +2.0085599422454834,-20.863588333129883,121.71347045898438,3.540427083379941e-05 +2.008559465408325,-20.863590240478516,121.7135238647461,5.0781017035976356e-05 +2.008559465408325,-20.863590240478516,121.7135238647461,5.207310877880414e-05 +2.008559465408325,-20.863590240478516,121.7135238647461,5.4758610454777514e-05 +2.0085601806640625,-20.863590240478516,121.7135238647461,2.7231613736382148e-06 +2.008561849594116,-20.863588333129883,121.7135238647461,5.529718662707254e-05 +2.008561134338379,-20.863588333129883,121.7135238647461,6.186934077348061e-06 +2.0085608959198,-20.863588333129883,121.7135238647461,4.4485965857202504e-05 +2.0085608959198,-20.863588333129883,121.7135238647461,4.100901994789007e-06 +2.0085601806640625,-20.863588333129883,121.7135238647461,5.658662175908951e-06 +2.0085601806640625,-20.863588333129883,121.7135238647461,4.2483870673376434e-05 +2.0085604190826416,-20.863588333129883,121.7135238647461,4.570371321387932e-06 +2.0085642337799072,-20.86358642578125,121.71360778808594,3.2992603747908797e-06 +2.008570432662964,-20.863582611083984,121.71366119384766,6.814686487900055e-05 +2.0085694789886475,-20.86357879638672,121.71366119384766,4.4538824097114635e-06 +2.0085740089416504,-20.863576889038086,121.71366119384766,7.613989263560577e-05 +2.0085737705230713,-20.86357307434082,121.71366119384766,3.449957610814983e-05 +2.008573532104492,-20.86357307434082,121.71366119384766,7.980826232206243e-06 +2.0085737705230713,-20.86357307434082,121.71366119384766,2.7919370701439125e-06 +2.008573055267334,-20.863576889038086,121.71366119384766,3.462353013395023e-06 +2.0085742473602295,-20.863576889038086,121.71366119384766,1.3010002021368007e-06 +2.0085761547088623,-20.863576889038086,121.71366119384766,3.754683753422395e-05 +2.0085761547088623,-20.863576889038086,121.71366119384766,3.714368944317808e-06 +2.0085763931274414,-20.86357879638672,121.71370697021484,7.9597805253002e-06 +2.0085763931274414,-20.863576889038086,121.71370697021484,4.914435598601336e-05 +2.008575916290283,-20.863576889038086,121.71370697021484,1.542893686190826e-06 +2.0085766315460205,-20.863576889038086,121.71370697021484,7.158314556589448e-06 +2.0085763931274414,-20.863576889038086,121.71370697021484,3.9140311558061795e-05 +2.0085763931274414,-20.863576889038086,121.71370697021484,4.765959589691354e-06 +2.0085763931274414,-20.863576889038086,121.71370697021484,1.0933227042774956e-06 +2.0085766315460205,-20.863576889038086,121.71370697021484,9.794658038260735e-06 +2.0085768699645996,-20.863576889038086,121.71370697021484,1.412508908886312e-06 +2.0085763931274414,-20.863576889038086,121.71370697021484,2.841929630545846e-06 +2.0085768699645996,-20.86357879638672,121.71370697021484,2.986084417378855e-05 +2.0085787773132324,-20.86357307434082,121.7137451171875,5.339447630967226e-05 +2.008577346801758,-20.86357307434082,121.7137451171875,2.7801405278558682e-05 +2.008578062057495,-20.86357307434082,121.7137451171875,3.708562064610071e-05 +2.0085771083831787,-20.86357307434082,121.7137451171875,1.6994017573569497e-06 +2.008577346801758,-20.863576889038086,121.71372985839844,6.1624793383767205e-06 +2.0085806846618652,-20.86357307434082,121.71372985839844,6.949570725406758e-05 +2.008579730987549,-20.86357307434082,121.71372985839844,5.048369213074449e-06 +2.008580446243286,-20.86357307434082,121.71372985839844,4.314308824030464e-05 +2.0085794925689697,-20.863576889038086,121.71372985839844,3.875693938970752e-05 +2.0085790157318115,-20.863576889038086,121.71372985839844,4.0573314843692444e-05 +2.0085790157318115,-20.863576889038086,121.71372985839844,4.326074492420273e-05 +2.008580207824707,-20.86357879638672,121.71372985839844,4.023249192715415e-06 +2.008584499359131,-20.86357307434082,121.7137451171875,1.3596123328438917e-05 +2.00858473777771,-20.863571166992188,121.7137451171875,4.218599418931297e-05 diff --git a/PythonAPI/data/path_logs/log3.txt b/PythonAPI/data/path_logs/log3.txt new file mode 100644 index 0000000..031d3c1 --- /dev/null +++ b/PythonAPI/data/path_logs/log3.txt @@ -0,0 +1,57 @@ +-0.5744883418083191,-27.28974723815918,-62.007869720458984,5.113949732033437e-06 +-0.5744833946228027,-27.28974723815918,-62.007869720458984,4.94074616885288e-06 +-0.5744791030883789,-27.28974723815918,-62.007869720458984,4.782081812505532e-06 +-0.5744743347167969,-27.28974723815918,-62.007869720458984,5.552208489990626e-06 +-0.574469268321991,-27.28974723815918,-62.007869720458984,5.157902042135696e-06 +-0.5744658708572388,-27.28974723815918,-62.007869720458984,4.807927334644345e-06 +-0.5744608640670776,-27.28974723815918,-62.007869720458984,5.44575246758677e-06 +-0.5744561553001404,-27.28974723815918,-62.007869720458984,4.876364470822699e-06 +-0.5744504332542419,-27.28974723815918,-62.007869720458984,5.826092823930177e-06 +-0.5744457840919495,-27.28974723815918,-62.007869720458984,5.005465196639243e-06 +-0.5744415521621704,-27.28974723815918,-62.007869720458984,4.922704822414039e-06 +-0.5744365453720093,-27.28974723815918,-62.007869720458984,5.191376789711948e-06 +-0.5743823051452637,-27.28982925415039,-62.00765609741211,0.0011796795200044526 +-0.5731377005577087,-27.29170799255371,-62.00765609741211,0.002382127927932274 +-0.5791295766830444,-27.28063201904297,-62.02069091796875,0.030062352779786482 +-0.5996732115745544,-27.245065689086914,-62.091060638427734,0.0512595672052047 +-0.6311220526695251,-27.192182540893555,-62.225711822509766,0.10336322964835429 +-0.8359410762786865,-26.85402488708496,-63.405242919921875,0.4581259118205594 +-1.100361943244934,-26.43408966064453,-65.8071517944336,0.45941639872748924 +-1.349555492401123,-26.068912506103516,-69.53517150878906,0.37793501109961636 +-1.572477102279663,-25.752973556518555,-74.16047668457031,0.321795744051519 +-1.7501184940338135,-25.4694766998291,-78.53511047363281,0.36269048573558177 +-1.906842589378357,-25.171310424804688,-82.933349609375,0.28747038034718997 +-2.0271785259246826,-24.894887924194336,-86.8951416015625,0.34289506853529556 +-2.13987135887146,-24.574848175048828,-91.33609771728516,0.28611608834507557 +-2.224073648452759,-24.261215209960938,-95.56959533691406,0.4014397546324367 +-2.29756498336792,-23.842487335205078,-101.06585693359375,0.4516783216593707 +-2.330349922180176,-23.45967674255371,-106.09175109863281,0.23986358813437567 +-2.31766676902771,-23.295124053955078,-107.59609985351562,0.1572746465172942 +-2.2343149185180664,-23.05118179321289,-107.35232543945312,0.3181380831764387 +-2.0576400756835938,-22.73606300354004,-103.96961212158203,0.3894596896793634 +-1.8592193126678467,-22.392160415649414,-98.77252960205078,0.4198336739964111 +-1.6650066375732422,-21.966203689575195,-92.6154556274414,0.4618919313679109 +-1.5217111110687256,-21.533580780029297,-86.65357208251953,0.43490185686583216 +-1.4274327754974365,-21.105058670043945,-80.93293762207031,0.3936652011016317 +-1.3788496255874634,-20.68831443786621,-75.46005249023438,0.37352675650954065 +-1.3706411123275757,-20.231924057006836,-69.53128051757812,0.4891911569494131 +-1.409234881401062,-19.759105682373047,-63.29548263549805,0.4403283208930505 +-1.4952174425125122,-19.315542221069336,-57.37358093261719,0.37267446715031044 +-1.6247518062591553,-18.8856201171875,-51.4610481262207,0.4429809023611669 +-1.7959202527999878,-18.47950553894043,-45.70296096801758,0.4309503819898341 +-2.0207901000976562,-18.065027236938477,-39.49836349487305,0.43296693487014365 +-2.280994176864624,-17.690397262573242,-33.51591491699219,0.4452953456993487 +-2.5857646465301514,-17.335012435913086,-27.340103149414062,0.43072678862322616 +-2.927900552749634,-17.016265869140625,-21.21901512145996,0.4106140251822105 +-3.318718194961548,-16.72498893737793,-14.83299446105957,0.43218673284889314 +-3.734856367111206,-16.480085372924805,-8.492319107055664,0.4031429710195781 +-4.141321182250977,-16.297863006591797,-2.665832996368408,0.3754424106711442 +-4.5604658126831055,-16.15803337097168,3.119793176651001,0.45074780154428346 +-5.039942741394043,-16.054412841796875,9.519532203674316,0.417370561822425 +-5.473152160644531,-16.00836753845215,15.185162544250488,0.3820372732933026 +-5.9425048828125,-16.00515365600586,21.34079933166504,0.45801024399842294 +-6.227499485015869,-15.999040603637695,24.697072982788086,0.10001195092907776 +-6.349680423736572,-15.96968936920166,25.751026153564453,0.1387641120162097 +-6.408232688903809,-15.954096794128418,26.293777465820312,0.003581540333824478 +-6.408669471740723,-15.952470779418945,26.27781867980957,0.000416729334878987 +-6.408573627471924,-15.952436447143555,26.275236129760742,1.149729859361044e-06 diff --git a/PythonAPI/data/paths/driving_path_left2right.txt b/PythonAPI/data/paths/driving_path_left2right.txt new file mode 100644 index 0000000..8d8060a --- /dev/null +++ b/PythonAPI/data/paths/driving_path_left2right.txt @@ -0,0 +1,122 @@ +-2.376371583333333, -13.749357381666668 +-2.3756074359366393, -13.813926828333335 +-2.3731159473691457, -13.945901363608813 +-2.369276809848485, -14.146782290275482 +-2.3655190954820937, -14.373598865936641 +-2.3627404541597796, -14.635228240909091 +-2.3616332343801654, -14.955879360564737 +-2.364393537782369, -15.359148520826446 +-2.3708479727410467, -15.801469889159778 +-2.3825112493388425, -16.300373365592286 +-2.397777951597796, -16.80843430100551 +-2.4162517283333336, -17.308433501666666 +-2.4337892111570247, -17.772247362920112 +-2.448110591859504, -18.23796838717631 +-2.4555393862396695, -18.711517582093663 +-2.455495908953168, -19.182840640440773 +-2.447396729476584, -19.671597803471077 +-2.4319331137741047, -20.188277654903583 +-2.408568514862259, -20.724087896019284 +-2.375411939008264, -21.240948858498623 +-2.3322898495454543, -21.7282670776584 +-2.268663500564738, -22.211421948002755 +-2.192037356969697, -22.700906030454544 +-2.1008599183746557, -23.162751075826446 +-1.9975222897658405, -23.603867306060607 +-1.8799308476033056, -24.060758011280992 +-1.7551922902066115, -24.472925382382922 +-1.6296007119008262, -24.857475611143247 +-1.5014403696143248, -25.253865353567495 +-1.4012006525619833, -25.577241929104684 +-1.318978540509642, -25.83184848198347 +-1.2370667314325063, -26.060869991749314 +-1.1551136535123965, -26.259964996666664 +-1.055994903939394, -26.479132043030305 +-0.9496435808264464, -26.68689674586777 +-0.8342154241184571, -26.89403548939394 +-0.7377378132644629, -27.05826769070248 +-0.6674016941184574, -27.16930356341598 +-0.6053283948484848, -27.255913677327825 +-0.566469992644628, -27.297582133636364 +-0.5701310139807163, -27.278332515550968 +-0.6013187876584022, -27.21817986869146 +-0.6362082767493114, -27.14992707001377 +-0.6779293786225898, -27.06890777517906 +-0.7309688718181819, -26.96752412409091 +-0.7885729158402203, -26.8575722930303 +-0.845604674752066, -26.750129203774108 +-0.9015996355785125, -26.64475472177686 +-0.9497715554958677, -26.558600495123965 +-0.9905645421900825, -26.489164419022035 +-1.0301700886639118, -26.421732369669424 +-1.066749826680441, -26.35975317026171 +-1.1015793094352617, -26.30150535892562 +-1.1386485279201102, -26.23903582508264 +-1.1793905751377411, -26.16881826413223 +-1.2344422766666667, -26.072166963636363 +-1.2913316121900826, -25.973048378595042 +-1.3543968752617077, -25.86324440643251 +-1.4301442995316804, -25.733525043154273 +-1.516132050922865, -25.587937231019282 +-1.6102962817493112, -25.43253089673554 +-1.7151192728925622, -25.266453740289254 +-1.8134100320936646, -25.116396120289256 +-1.9038350276584026, -24.978689133677687 +-1.9843575322865012, -24.853368567589527 +-2.0551639455371906, -24.740186242066116 +-2.115471887878788, -24.64016402939394 +-2.1646146533333335, -24.555408845853993 +-2.204614573856749, -24.48286533652892 +-2.245612590096419, -24.409259034146004 +-2.2883555729063363, -24.334205110220385 +-2.3420856975344355, -24.24731715556474 +-2.4078780027961435, -24.150240057024792 +-2.4941665089807166, -24.02598494198347 +-2.5894818384297515, -23.892140142809918 +-2.6831726203168045, -23.763223807382918 +-2.7738167478374653, -23.644810346611568 +-2.85517562469697, -23.542480816363636 +-2.917401288746557, -23.466352349242428 +-2.9731754809641875, -23.4007191627135 +-3.0221463862396694, -23.346189685330575 +-3.0666661716253443, -23.299893824683195 +-3.108645773856749, -23.2581166681405 +-3.1685473622314047, -23.195733311955923 +-3.2242987275757575, -23.139737880068868 +-3.2773786924517903, -23.083547423181816 +-3.3369068067493117, -23.020983305922865 +-3.4050259592011023, -22.947571911349865 +-3.4983252898484856, -22.85001280848485 +-3.6039228086088158, -22.745508186914602 +-3.703774030812672, -22.65269936198347 +-3.801029995633609, -22.567905521983466 +-3.9034134737465567, -22.485065710964182 +-4.00183154322314, -22.409964919297522 +-4.0984117541597795, -22.342007986143255 +-4.195843093264464, -22.2781446338843 +-4.295869338140496, -22.214661083071622 +-4.40291087506887, -22.14504111750689 +-4.525513163856749, -22.07192453464187 +-4.659861971060607, -21.99886599439394 +-4.780306413953168, -21.93630155911846 +-4.883295368677685, -21.88880634513774 +-4.974673940013774, -21.851750118360883 +-5.062507065137741, -21.82217171093664 +-5.156814773980717, -21.789412832741046 +-5.2620597196831955, -21.748264798512395 +-5.370727080977961, -21.700286704889805 +-5.499110410110192, -21.648127213663912 +-5.631855718402204, -21.5981380949449 +-5.783319551887051, -21.55197037231405 +-5.969592889242424, -21.505520704848482 +-6.141692552190082, -21.461904025826446 +-6.273884234820937, -21.422010614146007 +-6.392044962768594, -21.39500466670799 +-6.522984504765841, -21.367669197809917 +-6.667634710606062, -21.338779059159776 +-6.801137372823692, -21.30754500907713 +-7.006202151515152, -21.277375165716254 +-7.209050932258954, -21.25851920475207 +-7.377529198911847, -21.25872856902204 +-7.558026800564739, -21.268538719201104 +-7.7486732, -21.271947543333333 diff --git a/PythonAPI/data/paths/driving_path_right2left.txt b/PythonAPI/data/paths/driving_path_right2left.txt new file mode 100644 index 0000000..ef5f431 --- /dev/null +++ b/PythonAPI/data/paths/driving_path_right2left.txt @@ -0,0 +1,142 @@ +-2.284308814,-31.734065629999996 +-2.2855382103687942,-31.61415707790071 +-2.2928445443971635,-31.390397837262412 +-2.320643309446809,-31.033096629617024 +-2.3600132680567376,-30.600974323304968 +-2.393995245588653,-30.12895142468085 +-2.4198266132765958,-29.65668028208511 +-2.4437094081843975,-29.21265234815603 +-2.466718848751773,-28.719696714028366 +-2.4858282840425536,-28.25063261476596 +-2.5072193571773047,-27.741882952042555 +-2.531492053219858,-27.14321331316312 +-2.5488645941702126,-26.48827530085107 +-2.542198833546099,-25.76417492795744 +-2.4863190055602837,-25.129483443617023 +-2.394669990255319,-24.441520048085106 +-2.2735989587517733,-23.85269974748936 +-2.135711156624114,-23.38523275977305 +-1.9922983560425536,-22.94952367489362 +-1.8355270280425533,-22.541206927432622 +-1.6638384989929083,-22.143856238099293 +-1.4685902529787238,-21.742724997659575 +-1.2785593976028369,-21.347942388666667 +-1.089187299985816,-20.95014106815603 +-0.886941995957447,-20.571647771659578 +-0.6913022040992906,-20.218830642723404 +-0.4712967538156031,-19.859991971985814 +-0.3111158399148938,-19.590391532680847 +-0.21002050717730486,-19.387216854382977 +-0.12546262258156043,-19.22744936851064 +-0.04736635038297869,-19.085258531702127 +0.00963143687943262,-18.973319135446808 +0.018967377106383056,-18.896448524950355 +0.016118662000000138,-18.836253649234045 +0.0047615362411349785,-18.792290097929076 +0.013079292907801543,-18.749433342340428 +0.06351224008510625,-18.672630650851065 +0.11571184014184413,-18.603924937914893 +0.19276729641855345,-18.52513962351773 +0.26148047221089377,-18.47276835506383 +0.30903101883687983,-18.460897204978725 +0.3441169975177306,-18.471459084085105 +0.37300747782978727,-18.482014149914892 +0.3993364845957446,-18.476809483758863 +0.3975385849645389,-18.47801424106383 +0.38258697051063817,-18.48376540280851 +0.409550333177305,-18.459612079588652 +0.3861407833333331,-18.469425836666666 +0.34829373255319135,-18.49020844306383 +0.2958265879007091,-18.53172275632624 +0.22645086560283664,-18.594818816695035 +0.16507745544680857,-18.650783708978725 +0.11338770036879442,-18.699208256411346 +0.05165739475177307,-18.7685268598156 +-0.019532585148936254,-18.851013410170214 +-0.09073136346099316,-18.938652128397162 +-0.17762566270922017,-19.031053856950358 +-0.2626810538723402,-19.11261711961702 +-0.333257054850383,-19.182634941957446 +-0.3911042057304965,-19.2408842478156 +-0.43309882927659593,-19.283204521914893 +-0.46219449211347524,-19.313981640340426 +-0.49436223290780124,-19.34593334771631 +-0.5260722620425531,-19.376103452425532 +-0.5815808722411345,-19.428860101078016 +-0.6687594078960283,-19.521009466638297 +-0.748747112090298,-19.613608333829788 +-0.8221305535319144,-19.696291573304965 +-0.884925281617021,-19.76444410131915 +-0.9318508677446807,-19.812027269234044 +-0.9867036934609932,-19.862254614964538 +-1.0627988135177302,-19.92469398295035 +-1.1727121121276591,-20.01112009387234 +-1.28695281951773,-20.098509846737592 +-1.3987304874326238,-20.180773464212766 +-1.5156471304680852,-20.266594305531918 +-1.631195473758865,-20.34698909470922 +-1.736226186851064,-20.414491385957444 +-1.8314667061702128,-20.473511343234044 +-1.9370228813758872,-20.53860959306383 +-2.0544295403262405,-20.615131888964537 +-2.1828809883829785,-20.698569308978723 +-2.2901963269645385,-20.769517987446807 +-2.3480016434326236,-20.81496123161702 +-2.3951834979999997,-20.85398156255319 +-2.437363451943262,-20.887048321205675 +-2.496082599432624,-20.928457742907803 +-2.563591520723404,-20.97266732919149 +-2.6650243273758867,-21.03236440089362 +-2.7868531921276603,-21.09818101470922 +-2.9174380563829794,-21.165799858893617 +-3.0038895756879427,-21.215523535418438 +-3.0809111122836876,-21.261898698595743 +-3.1528756839148935,-21.30539448387234 +-3.2292216706666665,-21.350172678666667 +-3.304141049148936,-21.389171492851066 +-3.3796636901276593,-21.42413398242553 +-3.4674150956737586,-21.45949667448227 +-3.534534872893617,-21.480036545730492 +-3.5884537451063827,-21.48708344408511 +-3.398906698765959,-21.481640101829786 +-3.4515617218581567,-21.492908244170213 +-3.555326405404254,-21.513277331404254 +-3.6617575932907798,-21.53124049266667 +-3.7662833954042547,-21.545864413815604 +-3.8637471107659573,-21.560647030085104 +-3.9636393773333323,-21.576389957702126 +-4.061071121730497,-21.58913527539007 +-4.161587850425532,-21.598229778127664 +-3.9704106792765863,-21.581369071914896 +-3.3739543687517726,-21.53464447292199 +-3.4136319405531914,-21.535667412851062 +-3.4667456031347514,-21.53905586876596 +-3.5494319138156016,-21.549921994695033 +-3.6607873459999993,-21.565086226255318 +-3.7926316006099285,-21.580389467078014 +-3.9287362661276597,-21.595493019163122 +-4.04077230974468,-21.60097062097872 +-4.145167795588653,-21.606159455943263 +-4.225810036865248,-21.6074154510922 +-4.311653188127661,-21.607935351531914 +-4.403104414297873,-21.606726324921986 +-4.5090219314042566,-21.60406828724823 +-4.6349604082978715,-21.60139893970213 +-4.767843190737588,-21.601072550198584 +-4.909858272198581,-21.600607482609927 +-5.041170917914893,-21.594244035957445 +-5.168056243886523,-21.58287128878014 +-5.283588547390071,-21.570500989773052 +-5.377747571446809,-21.5595963073617 +-5.455950027829788,-21.55249187673759 +-5.489976668269504,-21.548663229517732 +-5.5647439664255325,-21.544136308085108 +-5.717571521007093,-21.536141024269504 +-5.9264550796170195,-21.52550635329078 +-6.159447802127658,-21.51381284740426 +-6.399474417007092,-21.500973649503543 +-6.624504590312055,-21.48844143797163 +-6.8553737242127655,-21.477772125148938 +-7.082913656893616,-21.46998007673759 +-7.270498690255319,-21.464705316141842 +-7.449310874,-21.459648512 diff --git a/PythonAPI/data/paths/hitachi.txt b/PythonAPI/data/paths/hitachi.txt new file mode 100644 index 0000000..9d35fbe --- /dev/null +++ b/PythonAPI/data/paths/hitachi.txt @@ -0,0 +1,498 @@ +1.04,-18.33 +1.03,-18.33 +1.03,-18.34 +1.02,-18.34 +1.02,-18.35 +1.01,-18.35 +1.01,-18.36 +1.00,-18.37 +1.00,-18.37 +0.99,-18.38 +0.99,-18.38 +0.98,-18.39 +0.98,-18.40 +0.97,-18.40 +0.97,-18.41 +0.96,-18.41 +0.96,-18.42 +0.95,-18.42 +0.95,-18.43 +0.94,-18.44 +0.94,-18.44 +0.93,-18.45 +0.93,-18.45 +0.92,-18.46 +0.92,-18.47 +0.91,-18.47 +0.91,-18.48 +0.90,-18.48 +0.90,-18.49 +0.89,-18.49 +0.89,-18.50 +0.88,-18.51 +0.88,-18.51 +0.87,-18.52 +0.87,-18.52 +0.86,-18.53 +0.86,-18.54 +0.85,-18.54 +0.85,-18.55 +0.84,-18.55 +0.84,-18.56 +0.83,-18.56 +0.83,-18.57 +0.83,-18.58 +0.82,-18.58 +0.82,-18.59 +0.81,-18.59 +0.81,-18.60 +0.80,-18.61 +0.80,-18.61 +0.79,-18.62 +0.79,-18.62 +0.78,-18.63 +0.78,-18.63 +0.77,-18.64 +0.77,-18.65 +0.76,-18.65 +0.76,-18.66 +0.75,-18.66 +0.75,-18.67 +0.74,-18.68 +0.74,-18.68 +0.73,-18.69 +0.73,-18.69 +0.72,-18.70 +0.72,-18.70 +0.71,-18.71 +0.71,-18.72 +0.70,-18.72 +0.70,-18.73 +0.69,-18.73 +0.69,-18.74 +0.68,-18.74 +0.68,-18.75 +0.67,-18.76 +0.67,-18.76 +0.66,-18.77 +0.66,-18.77 +0.65,-18.78 +0.65,-18.79 +0.64,-18.79 +0.64,-18.80 +0.63,-18.80 +0.63,-18.81 +0.62,-18.81 +0.62,-18.82 +0.62,-18.83 +0.61,-18.83 +0.61,-18.84 +0.60,-18.84 +0.60,-18.85 +0.59,-18.86 +0.59,-18.86 +0.58,-18.87 +0.58,-18.87 +0.57,-18.88 +0.57,-18.88 +0.56,-18.89 +0.56,-18.90 +0.55,-18.90 +0.55,-18.91 +0.54,-18.91 +0.54,-18.91 +0.54,-18.92 +0.53,-18.92 +0.53,-18.93 +0.53,-18.93 +0.52,-18.93 +0.52,-18.94 +0.52,-18.94 +0.51,-18.95 +0.51,-18.95 +0.51,-18.95 +0.50,-18.96 +0.50,-18.96 +0.50,-18.97 +0.49,-18.97 +0.49,-18.97 +0.49,-18.98 +0.48,-18.98 +0.48,-18.99 +0.48,-18.99 +0.47,-18.99 +0.47,-19.00 +0.47,-19.00 +0.46,-19.01 +0.46,-19.01 +0.46,-19.01 +0.45,-19.02 +0.45,-19.02 +0.45,-19.03 +0.44,-19.03 +0.44,-19.03 +0.44,-19.04 +0.43,-19.04 +0.43,-19.04 +0.43,-19.05 +0.42,-19.05 +0.42,-19.06 +0.42,-19.06 +0.41,-19.06 +0.41,-19.07 +0.41,-19.07 +0.40,-19.08 +0.40,-19.08 +0.40,-19.08 +0.39,-19.09 +0.39,-19.09 +0.39,-19.10 +0.38,-19.10 +0.38,-19.10 +0.38,-19.11 +0.37,-19.11 +0.37,-19.12 +0.37,-19.12 +0.36,-19.12 +0.36,-19.13 +0.36,-19.13 +0.35,-19.14 +0.35,-19.14 +0.35,-19.14 +0.34,-19.15 +0.34,-19.15 +0.34,-19.16 +0.33,-19.16 +0.33,-19.16 +0.33,-19.17 +0.32,-19.17 +0.32,-19.17 +0.32,-19.18 +0.31,-19.18 +0.31,-19.19 +0.31,-19.19 +0.30,-19.19 +0.30,-19.20 +0.30,-19.20 +0.29,-19.21 +0.29,-19.21 +0.29,-19.21 +0.28,-19.22 +0.28,-19.22 +0.27,-19.23 +0.27,-19.23 +0.27,-19.23 +0.26,-19.24 +0.26,-19.24 +0.26,-19.24 +0.25,-19.25 +0.25,-19.25 +0.25,-19.26 +0.24,-19.26 +0.24,-19.26 +0.24,-19.27 +0.23,-19.27 +0.23,-19.28 +0.23,-19.28 +0.22,-19.28 +0.22,-19.29 +0.22,-19.29 +0.21,-19.29 +0.18,-19.33 +0.15,-19.36 +0.12,-19.40 +0.09,-19.43 +0.06,-19.46 +0.02,-19.49 +-0.01,-19.53 +-0.04,-19.56 +-0.07,-19.59 +-0.11,-19.62 +-0.14,-19.65 +-0.17,-19.68 +-0.21,-19.71 +-0.24,-19.74 +-0.27,-19.77 +-0.31,-19.80 +-0.34,-19.83 +-0.38,-19.86 +-0.41,-19.89 +-0.45,-19.92 +-0.48,-19.95 +-0.52,-19.98 +-0.56,-20.01 +-0.59,-20.03 +-0.63,-20.06 +-0.67,-20.09 +-0.70,-20.11 +-0.74,-20.14 +-0.78,-20.17 +-0.81,-20.19 +-0.85,-20.22 +-0.89,-20.24 +-0.93,-20.27 +-0.97,-20.29 +-1.00,-20.32 +-1.04,-20.34 +-1.08,-20.37 +-1.12,-20.39 +-1.16,-20.41 +-1.20,-20.44 +-1.24,-20.46 +-1.28,-20.48 +-1.32,-20.50 +-1.36,-20.52 +-1.40,-20.55 +-1.44,-20.57 +-1.48,-20.59 +-1.52,-20.61 +-1.56,-20.63 +-1.60,-20.65 +-1.65,-20.67 +-1.69,-20.69 +-1.73,-20.71 +-1.77,-20.72 +-1.81,-20.74 +-1.85,-20.76 +-1.90,-20.78 +-1.94,-20.79 +-1.98,-20.81 +-2.02,-20.83 +-2.07,-20.84 +-2.11,-20.86 +-2.15,-20.88 +-2.19,-20.89 +-2.24,-20.91 +-2.28,-20.92 +-2.32,-20.93 +-2.37,-20.95 +-2.41,-20.96 +-2.45,-20.97 +-2.50,-20.99 +-2.54,-21.00 +-2.59,-21.01 +-2.63,-21.02 +-2.67,-21.03 +-2.72,-21.05 +-2.76,-21.06 +-2.81,-21.07 +-2.85,-21.08 +-2.90,-21.09 +-2.94,-21.10 +-2.99,-21.10 +-3.03,-21.11 +-3.08,-21.12 +-3.12,-21.13 +-3.17,-21.14 +-3.21,-21.14 +-3.26,-21.15 +-3.30,-21.16 +-3.35,-21.16 +-3.39,-21.17 +-3.44,-21.17 +-3.48,-21.18 +-3.53,-21.18 +-3.57,-21.19 +-3.62,-21.19 +-3.66,-21.20 +-3.71,-21.20 +-3.75,-21.20 +-3.80,-21.20 +-3.81,-21.20 +-3.81,-21.20 +-3.82,-21.20 +-3.82,-21.20 +-3.83,-21.21 +-3.83,-21.21 +-3.84,-21.21 +-3.84,-21.21 +-3.85,-21.21 +-3.85,-21.21 +-3.86,-21.21 +-3.86,-21.21 +-3.87,-21.21 +-3.87,-21.21 +-3.88,-21.21 +-3.88,-21.21 +-3.89,-21.21 +-3.89,-21.21 +-3.90,-21.21 +-3.90,-21.21 +-3.91,-21.21 +-3.91,-21.21 +-3.92,-21.21 +-3.92,-21.21 +-3.93,-21.21 +-3.93,-21.21 +-3.94,-21.21 +-3.95,-21.21 +-3.95,-21.21 +-3.96,-21.21 +-3.96,-21.21 +-3.97,-21.21 +-3.97,-21.21 +-3.98,-21.21 +-3.98,-21.21 +-3.99,-21.21 +-3.99,-21.21 +-4.00,-21.21 +-4.00,-21.21 +-4.01,-21.21 +-4.01,-21.21 +-4.02,-21.21 +-4.02,-21.21 +-4.03,-21.21 +-4.03,-21.21 +-4.04,-21.21 +-4.04,-21.21 +-4.05,-21.21 +-4.05,-21.21 +-4.06,-21.21 +-4.06,-21.21 +-4.07,-21.21 +-4.07,-21.21 +-4.08,-21.21 +-4.09,-21.21 +-4.09,-21.21 +-4.10,-21.21 +-4.10,-21.21 +-4.11,-21.21 +-4.11,-21.21 +-4.12,-21.21 +-4.12,-21.21 +-4.13,-21.21 +-4.13,-21.21 +-4.14,-21.21 +-4.14,-21.21 +-4.15,-21.21 +-4.15,-21.21 +-4.16,-21.21 +-4.16,-21.21 +-4.17,-21.21 +-4.17,-21.21 +-4.18,-21.21 +-4.18,-21.21 +-4.19,-21.21 +-4.19,-21.21 +-4.20,-21.21 +-4.20,-21.21 +-4.21,-21.21 +-4.21,-21.21 +-4.22,-21.21 +-4.23,-21.21 +-4.23,-21.21 +-4.24,-21.21 +-4.24,-21.21 +-4.25,-21.21 +-4.25,-21.21 +-4.26,-21.21 +-4.26,-21.21 +-4.27,-21.21 +-4.27,-21.21 +-4.28,-21.21 +-4.28,-21.21 +-4.29,-21.21 +-4.29,-21.21 +-4.30,-21.21 +-4.30,-21.21 +-4.31,-21.21 +-4.31,-21.21 +-4.32,-21.21 +-4.35,-21.21 +-4.39,-21.21 +-4.42,-21.21 +-4.45,-21.21 +-4.49,-21.21 +-4.52,-21.21 +-4.55,-21.21 +-4.59,-21.21 +-4.62,-21.21 +-4.66,-21.21 +-4.69,-21.21 +-4.72,-21.21 +-4.76,-21.21 +-4.79,-21.21 +-4.82,-21.21 +-4.86,-21.21 +-4.89,-21.21 +-4.92,-21.21 +-4.96,-21.21 +-4.99,-21.21 +-5.03,-21.21 +-5.06,-21.21 +-5.09,-21.21 +-5.13,-21.21 +-5.16,-21.21 +-5.19,-21.21 +-5.23,-21.21 +-5.26,-21.21 +-5.29,-21.21 +-5.33,-21.21 +-5.36,-21.21 +-5.40,-21.21 +-5.43,-21.21 +-5.46,-21.21 +-5.50,-21.21 +-5.53,-21.21 +-5.56,-21.21 +-5.60,-21.21 +-5.63,-21.21 +-5.67,-21.21 +-5.70,-21.21 +-5.73,-21.21 +-5.77,-21.21 +-5.80,-21.21 +-5.83,-21.21 +-5.87,-21.21 +-5.90,-21.21 +-5.93,-21.21 +-5.97,-21.21 +-6.00,-21.21 +-6.04,-21.21 +-6.07,-21.21 +-6.10,-21.21 +-6.14,-21.21 +-6.17,-21.21 +-6.20,-21.21 +-6.24,-21.21 +-6.27,-21.21 +-6.30,-21.21 +-6.34,-21.21 +-6.37,-21.21 +-6.41,-21.21 +-6.44,-21.21 +-6.47,-21.21 +-6.51,-21.21 +-6.54,-21.21 +-6.57,-21.21 +-6.61,-21.21 +-6.64,-21.21 +-6.68,-21.21 +-6.71,-21.21 +-6.74,-21.21 +-6.78,-21.21 +-6.81,-21.21 +-6.84,-21.21 +-6.88,-21.21 +-6.91,-21.21 +-6.94,-21.21 +-6.98,-21.21 +-7.01,-21.21 +-7.05,-21.21 +-7.08,-21.21 +-7.11,-21.21 +-7.15,-21.21 +-7.18,-21.21 +-7.21,-21.21 +-7.25,-21.21 +-7.28,-21.21 +-7.31,-21.21 +-7.35,-21.21 +-7.38,-21.21 +-7.42,-21.21 +-7.45,-21.21 +-7.48,-21.21 +-7.52,-21.21 +-7.55,-21.21 +-7.58,-21.21 +-7.62,-21.21 \ No newline at end of file diff --git a/PythonAPI/data/paths/manual.txt b/PythonAPI/data/paths/manual.txt new file mode 100644 index 0000000..ef5f431 --- /dev/null +++ b/PythonAPI/data/paths/manual.txt @@ -0,0 +1,142 @@ +-2.284308814,-31.734065629999996 +-2.2855382103687942,-31.61415707790071 +-2.2928445443971635,-31.390397837262412 +-2.320643309446809,-31.033096629617024 +-2.3600132680567376,-30.600974323304968 +-2.393995245588653,-30.12895142468085 +-2.4198266132765958,-29.65668028208511 +-2.4437094081843975,-29.21265234815603 +-2.466718848751773,-28.719696714028366 +-2.4858282840425536,-28.25063261476596 +-2.5072193571773047,-27.741882952042555 +-2.531492053219858,-27.14321331316312 +-2.5488645941702126,-26.48827530085107 +-2.542198833546099,-25.76417492795744 +-2.4863190055602837,-25.129483443617023 +-2.394669990255319,-24.441520048085106 +-2.2735989587517733,-23.85269974748936 +-2.135711156624114,-23.38523275977305 +-1.9922983560425536,-22.94952367489362 +-1.8355270280425533,-22.541206927432622 +-1.6638384989929083,-22.143856238099293 +-1.4685902529787238,-21.742724997659575 +-1.2785593976028369,-21.347942388666667 +-1.089187299985816,-20.95014106815603 +-0.886941995957447,-20.571647771659578 +-0.6913022040992906,-20.218830642723404 +-0.4712967538156031,-19.859991971985814 +-0.3111158399148938,-19.590391532680847 +-0.21002050717730486,-19.387216854382977 +-0.12546262258156043,-19.22744936851064 +-0.04736635038297869,-19.085258531702127 +0.00963143687943262,-18.973319135446808 +0.018967377106383056,-18.896448524950355 +0.016118662000000138,-18.836253649234045 +0.0047615362411349785,-18.792290097929076 +0.013079292907801543,-18.749433342340428 +0.06351224008510625,-18.672630650851065 +0.11571184014184413,-18.603924937914893 +0.19276729641855345,-18.52513962351773 +0.26148047221089377,-18.47276835506383 +0.30903101883687983,-18.460897204978725 +0.3441169975177306,-18.471459084085105 +0.37300747782978727,-18.482014149914892 +0.3993364845957446,-18.476809483758863 +0.3975385849645389,-18.47801424106383 +0.38258697051063817,-18.48376540280851 +0.409550333177305,-18.459612079588652 +0.3861407833333331,-18.469425836666666 +0.34829373255319135,-18.49020844306383 +0.2958265879007091,-18.53172275632624 +0.22645086560283664,-18.594818816695035 +0.16507745544680857,-18.650783708978725 +0.11338770036879442,-18.699208256411346 +0.05165739475177307,-18.7685268598156 +-0.019532585148936254,-18.851013410170214 +-0.09073136346099316,-18.938652128397162 +-0.17762566270922017,-19.031053856950358 +-0.2626810538723402,-19.11261711961702 +-0.333257054850383,-19.182634941957446 +-0.3911042057304965,-19.2408842478156 +-0.43309882927659593,-19.283204521914893 +-0.46219449211347524,-19.313981640340426 +-0.49436223290780124,-19.34593334771631 +-0.5260722620425531,-19.376103452425532 +-0.5815808722411345,-19.428860101078016 +-0.6687594078960283,-19.521009466638297 +-0.748747112090298,-19.613608333829788 +-0.8221305535319144,-19.696291573304965 +-0.884925281617021,-19.76444410131915 +-0.9318508677446807,-19.812027269234044 +-0.9867036934609932,-19.862254614964538 +-1.0627988135177302,-19.92469398295035 +-1.1727121121276591,-20.01112009387234 +-1.28695281951773,-20.098509846737592 +-1.3987304874326238,-20.180773464212766 +-1.5156471304680852,-20.266594305531918 +-1.631195473758865,-20.34698909470922 +-1.736226186851064,-20.414491385957444 +-1.8314667061702128,-20.473511343234044 +-1.9370228813758872,-20.53860959306383 +-2.0544295403262405,-20.615131888964537 +-2.1828809883829785,-20.698569308978723 +-2.2901963269645385,-20.769517987446807 +-2.3480016434326236,-20.81496123161702 +-2.3951834979999997,-20.85398156255319 +-2.437363451943262,-20.887048321205675 +-2.496082599432624,-20.928457742907803 +-2.563591520723404,-20.97266732919149 +-2.6650243273758867,-21.03236440089362 +-2.7868531921276603,-21.09818101470922 +-2.9174380563829794,-21.165799858893617 +-3.0038895756879427,-21.215523535418438 +-3.0809111122836876,-21.261898698595743 +-3.1528756839148935,-21.30539448387234 +-3.2292216706666665,-21.350172678666667 +-3.304141049148936,-21.389171492851066 +-3.3796636901276593,-21.42413398242553 +-3.4674150956737586,-21.45949667448227 +-3.534534872893617,-21.480036545730492 +-3.5884537451063827,-21.48708344408511 +-3.398906698765959,-21.481640101829786 +-3.4515617218581567,-21.492908244170213 +-3.555326405404254,-21.513277331404254 +-3.6617575932907798,-21.53124049266667 +-3.7662833954042547,-21.545864413815604 +-3.8637471107659573,-21.560647030085104 +-3.9636393773333323,-21.576389957702126 +-4.061071121730497,-21.58913527539007 +-4.161587850425532,-21.598229778127664 +-3.9704106792765863,-21.581369071914896 +-3.3739543687517726,-21.53464447292199 +-3.4136319405531914,-21.535667412851062 +-3.4667456031347514,-21.53905586876596 +-3.5494319138156016,-21.549921994695033 +-3.6607873459999993,-21.565086226255318 +-3.7926316006099285,-21.580389467078014 +-3.9287362661276597,-21.595493019163122 +-4.04077230974468,-21.60097062097872 +-4.145167795588653,-21.606159455943263 +-4.225810036865248,-21.6074154510922 +-4.311653188127661,-21.607935351531914 +-4.403104414297873,-21.606726324921986 +-4.5090219314042566,-21.60406828724823 +-4.6349604082978715,-21.60139893970213 +-4.767843190737588,-21.601072550198584 +-4.909858272198581,-21.600607482609927 +-5.041170917914893,-21.594244035957445 +-5.168056243886523,-21.58287128878014 +-5.283588547390071,-21.570500989773052 +-5.377747571446809,-21.5595963073617 +-5.455950027829788,-21.55249187673759 +-5.489976668269504,-21.548663229517732 +-5.5647439664255325,-21.544136308085108 +-5.717571521007093,-21.536141024269504 +-5.9264550796170195,-21.52550635329078 +-6.159447802127658,-21.51381284740426 +-6.399474417007092,-21.500973649503543 +-6.624504590312055,-21.48844143797163 +-6.8553737242127655,-21.477772125148938 +-7.082913656893616,-21.46998007673759 +-7.270498690255319,-21.464705316141842 +-7.449310874,-21.459648512 diff --git a/PythonAPI/data/transform_log_data.py b/PythonAPI/data/transform_log_data.py new file mode 100644 index 0000000..ab697e4 --- /dev/null +++ b/PythonAPI/data/transform_log_data.py @@ -0,0 +1,162 @@ +# transform data/log to xlsx +from pathlib import Path +from pprint import pprint + +import matplotlib.pyplot as plt +import numpy as np +import pandas as pd + +"""Frame log template +{'AngularVelocity': array([-4.37428025e-06, 6.01823886e-05, -7.62434183e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13139057, -13.58492756, 0.16977863]), + 'Rotation': array([ 2.82769813e-03, -8.76779175e+01, 6.53911904e-02]), + 'Velocity': array([5.51639096e-06, 9.15236285e-07, 5.89568799e-06]), + 'brake_input': 0.0, + 'camera_location': array([-2.73157787, 17.28938675, -1.66063035]), + 'camera_rotation': array([-14.0348835 , -0.6602667 , -0.08262103]), + 'current_gear_input': False, + 'focus_actor_dist': 687.36474609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -199.36732483, -2041.00537109, 17.01990509]), + 'frame': 17268, + 'frame_number': 17268, + 'framesequence': 66642, + 'gaze_dir': array([0.99712372, 0.02189636, 0.05830383]), + 'gaze_origin': array([-3.93994713, -0.01803055, -0.53388059]), + 'gaze_valid': True, + 'gaze_vergence': 0.7961492538452148, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99966431, 0.02079773, 0.01531982]), + 'left_gaze_origin': array([-3.71361256, 2.82757282, -0.55886388]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4825439453125, + 'left_pupil_posn': array([ 0.31178343, -0.64217329]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99458313, 0.022995 , 0.10128784]), + 'right_gaze_origin': array([-4.16628122, -2.86363387, -0.50889742]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1923370361328125, + 'right_pupil_posn': array([-0.23540282, -0.80398464]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.725004479289, + 'timestamp_carla': 564726, + 'timestamp_device': 3718156, + 'timestamp_stream': 564.725004479289, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36903366e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +""" + +# necessary data +tab = { + 'timestamp_carla': [], + 'timestamp_device': [], + 'frame_number': [], + 'brake_input': [], + 'steering_input': [], + 'throttle_input': [], + 'LocationX': [], + 'LocationY': [], + 'LocationZ': [], + 'RotationRoll': [], + 'RotationPitch': [], + 'RotationYaw': [], + 'AngularVelocityX': [], + 'AngularVelocityY': [], + 'AngularVelocityZ': [], + 'VelocityX': [], + 'VelocityY': [], + 'VelocityZ': [], + 'transformX': [], + 'transformY': [], + 'transformZ': [], + 'transformRoll': [], + 'transformPitch': [], + 'transformYaw': [], + 'FL_Wheel_Angle': [], + 'FR_Wheel_Angle': [], + 'BL_Wheel_Angle': [], + 'BR_Wheel_Angle': [], +} + +# txt +__path__ = Path(__file__).resolve().parent +log_path = f'{__path__}/trials/trial_v_equal_vx.txt' + +with open(log_path) as rf: + lines = rf.readlines() + + for line in lines: + if 'brake_input' in line and 'handbrake_input' not in line: + tab['brake_input'].append(float(line.split(': ')[1].split(',')[0])) + if 'steering_input' in line: + tab['steering_input'].append(float(line.split(': ')[1].split(',')[0])) + if 'throttle_input' in line: + tab['throttle_input'].append(float(line.split(': ')[1].split(',')[0])) + if 'timestamp_carla' in line: + tab['timestamp_carla'].append(float(line.split(': ')[1].split(',')[0])) + if 'timestamp_device' in line: + tab['timestamp_device'].append(float(line.split(': ')[1].split(',')[0])) + if 'frame_number' in line: + tab['frame_number'].append(int(line.split(': ')[1].split(',')[0])) + if 'transform' in line: + # print(line.split('[')[2]) + transform_data = line.split('[')[2].split(']')[0].split(',') + tab['transformX'].append(float(transform_data[0])) + tab['transformY'].append(float(transform_data[1])) + tab['transformZ'].append(float(transform_data[2])) + + if '}' in line: + rpy_data = line.split('[')[1].split(']')[0].split(',') + tab['transformPitch'].append(float(rpy_data[0])) + tab['transformYaw'].append(float(rpy_data[1])) + tab['transformRoll'].append(float(rpy_data[2])) + + if 'Location' in line: + location_data = line.split('[')[1].split(']')[0].split(',') + tab['LocationX'].append(float(location_data[0])) + tab['LocationY'].append(float(location_data[1])) + tab['LocationZ'].append(float(location_data[2])) + + if 'Rotation' in line: + rpy_data = line.split('[')[1].split(']')[0].split(',') + tab['RotationPitch'].append(float(rpy_data[0])) + tab['RotationYaw'].append(float(rpy_data[1])) + tab['RotationRoll'].append(float(rpy_data[2])) + + if 'Velocity' in line and 'AngularVelocity' not in line: + v_data = line.split('[')[1].split(']')[0].split(',') + tab['VelocityX'].append(float(v_data[0])) + tab['VelocityY'].append(float(v_data[1])) + tab['VelocityZ'].append(float(v_data[2])) + + if 'AngularVelocity' in line: + av_data = line.split('[')[1].split(']')[0].split(',') + tab['AngularVelocityX'].append(float(av_data[0])) + tab['AngularVelocityY'].append(float(av_data[1])) + tab['AngularVelocityZ'].append(float(av_data[2])) + + if 'FL_Wheel_Angle' in line: + tab['FL_Wheel_Angle'].append(float(line.split(': ')[1].split(',')[0])) + if 'FR_Wheel_Angle' in line: + tab['FR_Wheel_Angle'].append(float(line.split(': ')[1].split(',')[0])) + if 'BL_Wheel_Angle' in line: + tab['BL_Wheel_Angle'].append(float(line.split(': ')[1].split(',')[0])) + if 'BR_Wheel_Angle' in line: + tab['BR_Wheel_Angle'].append(float(line.split(': ')[1].split(',')[0])) + +df = pd.DataFrame().from_dict(tab) +df.to_excel(log_path.replace('.txt', '.xlsx'), index=False) +print(df.head()) + + + diff --git a/PythonAPI/data/trials/log_03121548.txt b/PythonAPI/data/trials/log_03121548.txt new file mode 100644 index 0000000..eada331 Binary files /dev/null and b/PythonAPI/data/trials/log_03121548.txt differ diff --git a/PythonAPI/data/trials/log_03121550.txt b/PythonAPI/data/trials/log_03121550.txt new file mode 100644 index 0000000..d99bc6d Binary files /dev/null and b/PythonAPI/data/trials/log_03121550.txt differ diff --git a/PythonAPI/data/trials/log_03121552.txt b/PythonAPI/data/trials/log_03121552.txt new file mode 100644 index 0000000..2678995 Binary files /dev/null and b/PythonAPI/data/trials/log_03121552.txt differ diff --git a/PythonAPI/data/trials/trial1.txt b/PythonAPI/data/trials/trial1.txt new file mode 100644 index 0000000..77f71c7 --- /dev/null +++ b/PythonAPI/data/trials/trial1.txt @@ -0,0 +1,7708 @@ +{'AngularVelocity': array([-4.37428025e-06, 6.01823886e-05, -7.62434183e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13139057, -13.58492756, 0.16977863]), + 'Rotation': array([ 2.82769813e-03, -8.76779175e+01, 6.53911904e-02]), + 'Velocity': array([5.51639096e-06, 9.15236285e-07, 5.89568799e-06]), + 'brake_input': 0.0, + 'camera_location': array([-2.73157787, 17.28938675, -1.66063035]), + 'camera_rotation': array([-14.0348835 , -0.6602667 , -0.08262103]), + 'current_gear_input': False, + 'focus_actor_dist': 687.36474609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -199.36732483, -2041.00537109, 17.01990509]), + 'frame': 17268, + 'frame_number': 17268, + 'framesequence': 66642, + 'gaze_dir': array([0.99712372, 0.02189636, 0.05830383]), + 'gaze_origin': array([-3.93994713, -0.01803055, -0.53388059]), + 'gaze_valid': True, + 'gaze_vergence': 0.7961492538452148, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99966431, 0.02079773, 0.01531982]), + 'left_gaze_origin': array([-3.71361256, 2.82757282, -0.55886388]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4825439453125, + 'left_pupil_posn': array([ 0.31178343, -0.64217329]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99458313, 0.022995 , 0.10128784]), + 'right_gaze_origin': array([-4.16628122, -2.86363387, -0.50889742]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1923370361328125, + 'right_pupil_posn': array([-0.23540282, -0.80398464]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.725004479289, + 'timestamp_carla': 564726, + 'timestamp_device': 3718156, + 'timestamp_stream': 564.725004479289, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36903366e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 3.67426837e-05, -5.04455966e-05, -7.81011113e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13139057, -13.58492756, 0.16975829]), + 'Rotation': array([ 2.82769813e-03, -8.76779175e+01, 6.53911904e-02]), + 'Velocity': array([5.67369170e-06, 9.72945713e-07, 3.52968753e-04]), + 'brake_input': 0.0, + 'camera_location': array([-2.62917328, 17.27171707, -1.54976976]), + 'camera_rotation': array([-13.80090904, -0.99494165, 0.14572088]), + 'current_gear_input': False, + 'focus_actor_dist': 624.629638671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -214.15158081, -1978.12524414, 17.0125351 ]), + 'frame': 17269, + 'frame_number': 17269, + 'framesequence': 66646, + 'gaze_dir': array([0.99188232, 0.03288269, 0.12213135]), + 'gaze_origin': array([-3.74846411, -0.02136917, -0.64352727]), + 'gaze_valid': True, + 'gaze_vergence': 170.91488647460938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99118042, 0.02363586, 0.13031006]), + 'left_gaze_origin': array([-3.60833454, 2.81956959, -0.61534888]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5418853759765625, + 'left_pupil_posn': array([ 0.32368803, -0.65445054]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99258423, 0.04212952, 0.11395264]), + 'right_gaze_origin': array([-3.88859439, -2.86230779, -0.67170566]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5035552978515625, + 'right_pupil_posn': array([-0.23559356, -0.81230378]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.7594169788063, + 'timestamp_carla': 564760, + 'timestamp_device': 3718190, + 'timestamp_stream': 564.7594169788063, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35694091e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 2.85969854e-05, -4.54128458e-05, -7.66396170e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13139057, -13.58492756, 0.1697792 ]), + 'Rotation': array([ 2.82769813e-03, -8.76779175e+01, 6.53911904e-02]), + 'Velocity': array([5.50988125e-06, 9.08870675e-07, 6.92393078e-05]), + 'brake_input': 0.0, + 'camera_location': array([-2.56033134, 17.27591705, -1.4261111 ]), + 'camera_rotation': array([-13.51089859, -1.1720829 , 0.14489418]), + 'current_gear_input': False, + 'focus_actor_dist': 980.4007568359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -190.4994812 , -2337.37060547, 16.98117065]), + 'frame': 17270, + 'frame_number': 17270, + 'framesequence': 66650, + 'gaze_dir': array([0.99812317, 0.02439117, 0.02096558]), + 'gaze_origin': array([-3.88842487, -0.02092285, -0.58520359]), + 'gaze_valid': True, + 'gaze_vergence': 20.023096084594727, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99958801, 0.00595093, -0.02755737]), + 'left_gaze_origin': array([-3.79115939, 2.82542276, -0.54965061]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.418121337890625, + 'left_pupil_posn': array([ 0.32418239, -0.66954255]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99665833, 0.04283142, 0.06948853]), + 'right_gaze_origin': array([-3.98569036, -2.86726856, -0.62075657]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.208038330078125, + 'right_pupil_posn': array([-0.24239302, -0.8718164 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.7920676767826, + 'timestamp_carla': 564793, + 'timestamp_device': 3718223, + 'timestamp_stream': 564.7920676767826, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36350254e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 4.97830933e-06, -5.30278658e-06, -7.60270314e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13139057, -13.58492756, 0.16978545]), + 'Rotation': array([ 2.82769813e-03, -8.76779175e+01, 6.53911904e-02]), + 'Velocity': array([6.04763136e-06, 1.08297911e-06, 4.96494118e-04]), + 'brake_input': 0.0, + 'camera_location': array([-2.55738449, 17.2910862 , -1.32169318]), + 'camera_rotation': array([-13.17014122, -1.19186044, 0.14205095]), + 'current_gear_input': False, + 'focus_actor_dist': 544.0137939453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -221.57749939, -1896.30456543, 16.99121094]), + 'frame': 17271, + 'frame_number': 17271, + 'framesequence': 66654, + 'gaze_dir': array([ 0.9934845 , 0.06594849, -0.00669098]), + 'gaze_origin': array([-3.96854496, -0.02790527, -0.57369161]), + 'gaze_valid': True, + 'gaze_vergence': 10.104310035705566, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99085999, 0.09666443, -0.09396362]), + 'left_gaze_origin': array([-3.80943942, 2.82067728, -0.57205969]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.472991943359375, + 'left_pupil_posn': array([ 0.32669246, -0.68981838]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99610901, 0.03523254, 0.08058167]), + 'right_gaze_origin': array([-4.12765074, -2.87648797, -0.57532352]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.264190673828125, + 'right_pupil_posn': array([-0.20043486, -0.91154361]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.8301255777478, + 'timestamp_carla': 564831, + 'timestamp_device': 3718256, + 'timestamp_stream': 564.8301255777478, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.32112131e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-5.21282309e-05, -4.90457096e-05, -7.62164518e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13139057, -13.58492756, 0.16977313]), + 'Rotation': array([ 2.82769813e-03, -8.76779175e+01, 6.53911904e-02]), + 'Velocity': array([5.38592212e-06, 9.52926882e-07, 3.59281803e-05]), + 'brake_input': 0.0, + 'camera_location': array([-2.6368494 , 17.31697083, -1.37587428]), + 'camera_rotation': array([-13.08643723, -1.12461984, 0.1016358 ]), + 'current_gear_input': False, + 'focus_actor_dist': 495.98681640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -203.22096252, -1845.60986328, 16.95529938]), + 'frame': 17272, + 'frame_number': 17272, + 'framesequence': 66658, + 'gaze_dir': array([0.99557495, 0.0574646 , 0.04418945]), + 'gaze_origin': array([-3.94420171, -0.02446976, -0.58111423]), + 'gaze_valid': True, + 'gaze_vergence': 23.093008041381836, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99620056, 0.08666992, -0.00787354]), + 'left_gaze_origin': array([-3.818506 , 2.82141876, -0.56681216]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.567474365234375, + 'left_pupil_posn': array([ 0.32323527, -0.68170178]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99494934, 0.02825928, 0.09625244]), + 'right_gaze_origin': array([-4.06989765, -2.87035823, -0.59541625]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.191986083984375, + 'right_pupil_posn': array([-0.20669502, -0.8651309 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.8589079789817, + 'timestamp_carla': 564860, + 'timestamp_device': 3718290, + 'timestamp_stream': 564.8589079789817, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.30178053e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 2.73747937e-05, -5.40616275e-05, -7.64246943e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13139057, -13.58492756, 0.16977958]), + 'Rotation': array([ 2.82769813e-03, -8.76779175e+01, 6.53911904e-02]), + 'Velocity': array([5.66517929e-06, 9.63192406e-07, 2.10137790e-04]), + 'brake_input': 0.0, + 'camera_location': array([-2.81383991, 17.36949158, -1.55222785]), + 'camera_rotation': array([-13.42056942, -1.0017246 , 0.02559197]), + 'current_gear_input': False, + 'focus_actor_dist': 634.3823852539062, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -195.95120239, -1986.92004395, 16.99758911]), + 'frame': 17273, + 'frame_number': 17273, + 'framesequence': 66662, + 'gaze_dir': array([0.99568939, 0.03610992, 0.07801056]), + 'gaze_origin': array([-3.82640481, -0.01804352, -0.60652548]), + 'gaze_valid': True, + 'gaze_vergence': 12.963841438293457, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99855042, 0.03063965, 0.04402161]), + 'left_gaze_origin': array([-3.66860223, 2.82741714, -0.59574437]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6068115234375, + 'left_pupil_posn': array([ 0.31891191, -0.65631223]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99282837, 0.0415802 , 0.11199951]), + 'right_gaze_origin': array([-3.98420739, -2.86350417, -0.61730653]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.377197265625, + 'right_pupil_posn': array([-0.23338103, -0.83417332]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.8917423784733, + 'timestamp_carla': 564893, + 'timestamp_device': 3718323, + 'timestamp_stream': 564.8917423784733, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.33424364e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.06857497, -0.00293383, -0.00125993]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.029457364231348038, + 'FR_Wheel_Angle': 0.029461853206157684, + 'Location': array([ -2.13136506, -13.5853014 , 0.16976421]), + 'Rotation': array([ 3.40143405e-03, -8.76776962e+01, 6.53604791e-02]), + 'Velocity': array([ 0.00199646, -0.04412762, 0.0010604 ]), + 'brake_input': 0.0, + 'camera_location': array([-3.02068233, 17.41468239, -1.63268673]), + 'camera_rotation': array([-13.58127689, -0.83495647, 0.16649593]), + 'current_gear_input': False, + 'focus_actor_dist': 745.134521484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -201.58612061, -2099.91333008, 17.03590393]), + 'frame': 17274, + 'frame_number': 17274, + 'framesequence': 66666, + 'gaze_dir': array([0.99233246, 0.05619049, 0.10101318]), + 'gaze_origin': array([-3.73174858, -0.01513443, -0.65104067]), + 'gaze_valid': True, + 'gaze_vergence': 52.80470657348633, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9928894 , 0.09173584, 0.07580566]), + 'left_gaze_origin': array([-3.60392475, 2.82944655, -0.61934662]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6325531005859375, + 'left_pupil_posn': array([ 0.30772984, -0.65139353]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99177551, 0.02064514, 0.1262207 ]), + 'right_gaze_origin': array([-3.85957217, -2.85971546, -0.68273473]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2904510498046875, + 'right_pupil_posn': array([-0.21189088, -0.83784246]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.9253552779555, + 'timestamp_carla': 564926, + 'timestamp_device': 3718356, + 'timestamp_stream': 564.9253552779555, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.34870150e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.07192738, -0.00291642, -0.00068662]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.029455672949552536, + 'FR_Wheel_Angle': 0.029464401304721832, + 'Location': array([ -2.13126588, -13.58650589, 0.16977787]), + 'Rotation': array([ 3.40143405e-03, -8.76776962e+01, 6.53604791e-02]), + 'Velocity': array([ 2.14092317e-03, -4.74714600e-02, 7.43579876e-05]), + 'brake_input': 0.0, + 'camera_location': array([-3.20144463, 17.44878197, -1.52448452]), + 'camera_rotation': array([-13.32471466, -0.65121186, 0.42689574]), + 'current_gear_input': False, + 'focus_actor_dist': 855.7811889648438, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -175.11114502, -2210.01660156, 16.9868927 ]), + 'frame': 17275, + 'frame_number': 17275, + 'framesequence': 66670, + 'gaze_dir': array([0.99345398, 0.05350494, 0.09674072]), + 'gaze_origin': array([-3.78489232, -0.01255722, -0.62571186]), + 'gaze_valid': True, + 'gaze_vergence': 59.18240737915039, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99478149, 0.07055664, 0.07366943]), + 'left_gaze_origin': array([-3.59844518, 2.83323836, -0.62838596]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4839630126953125, + 'left_pupil_posn': array([ 0.31110442, -0.65945876]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99212646, 0.03645325, 0.11981201]), + 'right_gaze_origin': array([-3.9713397 , -2.8583529 , -0.62303776]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.414306640625, + 'right_pupil_posn': array([-0.22054935, -0.82047176]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.9606760777533, + 'timestamp_carla': 564962, + 'timestamp_device': 3718390, + 'timestamp_stream': 564.9606760777533, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.34400949e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.0555821 , 0.00233454, -0.00091878]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.029407601803541183, + 'FR_Wheel_Angle': 0.02938513271510601, + 'Location': array([ -2.13095188, -13.59316349, 0.16973183]), + 'Rotation': array([ 5.94909443e-03, -8.76777267e+01, 6.53627217e-02]), + 'Velocity': array([ 0.00213058, -0.04722204, -0.00020532]), + 'brake_input': 0.0, + 'camera_location': array([-3.34326172, 17.47300339, -1.32996118]), + 'camera_rotation': array([-12.67479515, -0.43290982, 0.60435969]), + 'current_gear_input': False, + 'focus_actor_dist': 855.8081665039062, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -174.34353638, -2209.734375 , 16.98619843]), + 'frame': 17276, + 'frame_number': 17276, + 'framesequence': 66674, + 'gaze_dir': array([ 0.99517822, 0.06839752, -0.00411224]), + 'gaze_origin': array([-3.83817077, -0.00725861, -0.61133653]), + 'gaze_valid': True, + 'gaze_vergence': 19.92960548400879, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99252319, 0.10339355, -0.06471252]), + 'left_gaze_origin': array([-3.72472095, 2.84021616, -0.58874053]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.561279296875, + 'left_pupil_posn': array([ 0.30885458, -0.6891644 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99783325, 0.03340149, 0.05648804]), + 'right_gaze_origin': array([-3.95162058, -2.85473347, -0.63393253]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2439727783203125, + 'right_pupil_posn': array([-0.21463275, -0.89270842]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 564.9933391772211, + 'timestamp_carla': 564994, + 'timestamp_device': 3718423, + 'timestamp_stream': 564.9933391772211, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36174746e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.00140994, 0.00294606, -0.2642312 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.029207667335867882, + 'FR_Wheel_Angle': 0.029184935614466667, + 'Location': array([ -2.127527 , -13.67262077, 0.16971573]), + 'Rotation': array([ 1.76355466e-02, -8.76929855e+01, 6.54008016e-02]), + 'Velocity': array([ 1.91728175e-02, -4.73173738e-01, 4.51469416e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.48574543, 17.46878242, -1.15962505]), + 'camera_rotation': array([-11.98306084, -0.27485788, 0.51935017]), + 'current_gear_input': False, + 'focus_actor_dist': 518.5626220703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -193.29707336, -1867.3182373 , 16.95309448]), + 'frame': 17277, + 'frame_number': 17277, + 'framesequence': 66678, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.61993980407715, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.71484685, 2.85785079, -0.62440646]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7103118896484375, + 'left_pupil_posn': array([ 0.27925801, -0.7149179 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9985199 , -0.00947571, 0.05348206]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 3.26458740234375, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.0243648774922, + 'timestamp_carla': 565025, + 'timestamp_device': 3718456, + 'timestamp_stream': 565.0243648774922, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.38230874e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.02553066, 0.00150048, -0.03963054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.16323140263557434, + 'FR_Wheel_Angle': -0.31907469034194946, + 'Location': array([ -2.12137818, -13.82388115, 0.16974518]), + 'Rotation': array([ 1.79429054e-02, -8.77006226e+01, 6.55452013e-02]), + 'Velocity': array([ 3.02473679e-02, -7.76598752e-01, 1.89638129e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.63436508, 17.44901848, -1.08114898]), + 'camera_rotation': array([-11.55858517, -0.19769721, 0.30068019]), + 'current_gear_input': False, + 'focus_actor_dist': 558.14501953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -225.79452515, -1913.95214844, 17.00153351]), + 'frame': 17278, + 'frame_number': 17278, + 'framesequence': 66682, + 'gaze_dir': array([ 0.99576569, -0.05471802, 0.00949097]), + 'gaze_origin': array([-3.91988754, 0.03633881, -0.59713137]), + 'gaze_valid': True, + 'gaze_vergence': 6.27476692199707, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99697876, -0.04524231, -0.06304932]), + 'left_gaze_origin': array([-3.54614258, 2.8792727 , -0.68383336]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6096649169921875, + 'left_pupil_posn': array([ 0.23874855, -0.70365202]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99455261, -0.06419373, 0.08203125]), + 'right_gaze_origin': array([-4.29363298, -2.80659485, -0.51042938]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3011474609375, + 'right_pupil_posn': array([-0.31719404, -0.89467072]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.0586798787117, + 'timestamp_carla': 565060, + 'timestamp_device': 3718490, + 'timestamp_stream': 565.0586798787117, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.37017826e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.00371032, 0.00490944, 0.01967687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.0710036754608154, + 'FR_Wheel_Angle': -2.266948699951172, + 'Location': array([ -2.11631441, -13.9774828 , 0.16983306]), + 'Rotation': array([ 1.02111325e-02, -8.77491760e+01, 6.70143589e-02]), + 'Velocity': array([ 1.86521728e-02, -7.94663668e-01, 2.26268763e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.79678249, 17.42357254, -1.04718864]), + 'camera_rotation': array([-11.33096218, -0.20564853, 0.10718247]), + 'current_gear_input': False, + 'focus_actor_dist': 609.8935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -256.68634033, -1962.83630371, 17.04919434]), + 'frame': 17279, + 'frame_number': 17279, + 'framesequence': 66686, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 35.12932586669922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.74714065, 2.8923769 , -0.60127717]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6046600341796875, + 'left_pupil_posn': array([ 0.23633504, -0.70778477]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99755859, -0.05282593, 0.04548645]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.0923333764076, + 'timestamp_carla': 565093, + 'timestamp_device': 3718523, + 'timestamp_stream': 565.0923333764076, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36781317e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.0177003 , 0.00810962, -0.5302676 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.8952629566192627, + 'FR_Wheel_Angle': -4.001589775085449, + 'Location': array([ -2.11288714, -14.15145588, 0.16992034]), + 'Rotation': array([ 3.41509446e-03, -8.79444580e+01, 6.74588680e-02]), + 'Velocity': array([ 2.13216338e-03, -7.32265055e-01, 2.57778156e-05]), + 'brake_input': 0.0, + 'camera_location': array([-3.94806099, 17.37747192, -1.00199151]), + 'camera_rotation': array([-11.13628769, -0.29239866, 0.05953209]), + 'current_gear_input': False, + 'focus_actor_dist': 590.3428344726562, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -223.97988892, -1946.45043945, 17.01113892]), + 'frame': 17280, + 'frame_number': 17280, + 'framesequence': 66690, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 25.199647903442383, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.6754899 , 2.88863087, -0.63208622]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.76190185546875, + 'left_pupil_posn': array([ 0.24405146, -0.70566714]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99725342, -0.03736877, 0.06385803]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.1259132772684, + 'timestamp_carla': 565127, + 'timestamp_device': 3718556, + 'timestamp_stream': 565.1259132772684, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36655402e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.00184223, -0.00353731, -1.24088061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.8228302001953125, + 'FR_Wheel_Angle': -5.845873832702637, + 'Location': array([ -2.11315703, -14.32408047, 0.16996124]), + 'Rotation': array([ 6.48867944e-03, -8.82185287e+01, 6.84678555e-02]), + 'Velocity': array([-1.71379652e-02, -7.66955376e-01, 2.08139420e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.08421612, 17.3246727 , -0.90782195]), + 'camera_rotation': array([-10.86655045, -0.45393994, 0.1264537 ]), + 'current_gear_input': False, + 'focus_actor_dist': 600.7481079101562, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -224.53231812, -1956.9263916 , 17.01535034]), + 'frame': 17281, + 'frame_number': 17281, + 'framesequence': 66694, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.16402816772461, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66384602, 2.88412642, -0.65421599]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.594085693359375, + 'left_pupil_posn': array([ 0.24435365, -0.7118082 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99531555, -0.04563904, 0.08517456]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.1589356772602, + 'timestamp_carla': 565160, + 'timestamp_device': 3718589, + 'timestamp_stream': 565.1589356772602, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36960596e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.04055192, -0.01723194, -0.55182481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.604852676391602, + 'FR_Wheel_Angle': -8.31897258758545, + 'Location': array([ -2.11850953, -14.52019501, 0.17005172]), + 'Rotation': array([ 1.91928307e-03, -8.86619873e+01, 6.78597167e-02]), + 'Velocity': array([-3.74222100e-02, -6.51350021e-01, -2.87818893e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.21336174, 17.26084328, -0.79175371]), + 'camera_rotation': array([-10.52161884, -0.63966668, 0.1747824 ]), + 'current_gear_input': False, + 'focus_actor_dist': 615.953857421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -225.74719238, -1972.31359863, 17.02194214]), + 'frame': 17282, + 'frame_number': 17282, + 'framesequence': 66698, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 50.36361312866211, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7113893 , 2.89026046, -0.62861639]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.54388427734375, + 'left_pupil_posn': array([ 0.2421298 , -0.72798431]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99861145, -0.04328918, 0.02958679]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.1927082762122, + 'timestamp_carla': 565194, + 'timestamp_device': 3718623, + 'timestamp_stream': 565.1927082762122, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36537170e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.03394546, 0.00376369, -1.47602189]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.841328620910645, + 'FR_Wheel_Angle': -10.998923301696777, + 'Location': array([ -2.12700272, -14.66349697, 0.17010364]), + 'Rotation': array([ 3.49022658e-03, -8.91410446e+01, 6.83114827e-02]), + 'Velocity': array([-5.93942329e-02, -6.20298088e-01, 7.30991378e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.32989216, 17.18574142, -0.66892403]), + 'camera_rotation': array([-10.16676998, -0.87473196, 0.19536839]), + 'current_gear_input': False, + 'focus_actor_dist': 636.5177612304688, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -227.16239929, -1993.1451416 , 17.03063202]), + 'frame': 17283, + 'frame_number': 17283, + 'framesequence': 66702, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.226676877588, + 'timestamp_carla': 565228, + 'timestamp_device': 3718656, + 'timestamp_stream': 565.226676877588, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36121335e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.04038841, 0.00879775, -2.47431278]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.689659118652344, + 'FR_Wheel_Angle': -12.09890079498291, + 'Location': array([ -2.14108348, -14.82032394, 0.17012794]), + 'Rotation': array([ 1.10512450e-02, -8.97912521e+01, 6.98340610e-02]), + 'Velocity': array([-9.27107409e-02, -7.44124234e-01, 2.58626940e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.43137741, 17.11711121, -0.55324405]), + 'camera_rotation': array([-9.78804302, -1.06890011, 0.13450858]), + 'current_gear_input': False, + 'focus_actor_dist': 659.1487426757812, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -229.22796631, -2016.07788086, 17.04071808]), + 'frame': 17284, + 'frame_number': 17284, + 'framesequence': 66706, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.2589978761971, + 'timestamp_carla': 565260, + 'timestamp_device': 3718689, + 'timestamp_stream': 565.2589978761971, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.37067419e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 1.61318516e-03, -1.47278411e-02, -4.08076620e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.290387153625488, + 'FR_Wheel_Angle': -11.655545234680176, + 'Location': array([ -2.15900946, -14.99119091, 0.17014907]), + 'Rotation': array([ 1.91040374e-02, -9.05365829e+01, 7.12924600e-02]), + 'Velocity': array([-1.29603028e-01, -9.57108498e-01, 5.68304036e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.5306921 , 17.03577805, -0.4657923 ]), + 'camera_rotation': array([-9.41208172, -1.31283712, 0.07665711]), + 'current_gear_input': False, + 'focus_actor_dist': 685.0296020507812, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -230.92462158, -2042.28393555, 17.05157471]), + 'frame': 17285, + 'frame_number': 17285, + 'framesequence': 66710, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 14.651019096374512, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.99507141, 0.04046631, 0.09039307]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 4.110687255859375, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.22642231, -2.87155008, -0.53997803]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.521514892578125, + 'right_pupil_posn': array([-0.22193831, -0.81790709]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.2912083789706, + 'timestamp_carla': 565292, + 'timestamp_device': 3718723, + 'timestamp_stream': 565.2912083789706, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.37654851e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.0224263 , -0.02805879, -4.99520016]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.077030181884766, + 'FR_Wheel_Angle': -9.763204574584961, + 'Location': array([ -2.19546008, -15.31152534, 0.17025588]), + 'Rotation': array([ 2.84887180e-02, -9.18044434e+01, 7.14355558e-02]), + 'Velocity': array([-1.90743163e-01, -1.39506090e+00, 7.94644351e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.61145401, 16.9419384 , -0.35455194]), + 'camera_rotation': array([-8.92915344, -1.59070659, 0.10348228]), + 'current_gear_input': False, + 'focus_actor_dist': 712.6315307617188, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -233.39047241, -2070.22021484, 17.06378937]), + 'frame': 17286, + 'frame_number': 17286, + 'framesequence': 66714, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 7.505129337310791, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.82089734, 2.81789422, -0.59595495]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4798126220703125, + 'left_pupil_posn': array([ 0.33249187, -0.70699894]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99462891, 0.04136658, 0.09477234]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 2.866729736328125, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.3250007778406, + 'timestamp_carla': 565326, + 'timestamp_device': 3718756, + 'timestamp_stream': 565.3250007778406, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36785135e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.02611049, -0.03894009, -4.59738064]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.887454986572266, + 'FR_Wheel_Angle': -6.631408214569092, + 'Location': array([ -2.23844528, -15.68361568, 0.17040989]), + 'Rotation': array([ 3.11320014e-02, -9.29588318e+01, 6.75759614e-02]), + 'Velocity': array([-2.26691902e-01, -1.76617599e+00, 9.95316426e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.71390438, 16.86471367, -0.27684569]), + 'camera_rotation': array([-8.40915108, -1.88830745, 0.14689602]), + 'current_gear_input': False, + 'focus_actor_dist': 751.5673828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -236.39328003, -2109.61328125, 17.06943512]), + 'frame': 17287, + 'frame_number': 17287, + 'framesequence': 66718, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 4.0768842697143555, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.81020236, 2.81246948, -0.60136414]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5804443359375, + 'left_pupil_posn': array([ 0.33379841, -0.70334291]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99327087, 0.03404236, 0.11058044]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.3593295775354, + 'timestamp_carla': 565360, + 'timestamp_device': 3718789, + 'timestamp_stream': 565.3593295775354, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35839051e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.05814233, -0.06576204, -0.87431914]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0257853269577026, + 'FR_Wheel_Angle': 0.11830908805131912, + 'Location': array([ -2.28195047, -16.14164734, 0.1706229 ]), + 'Rotation': array([ 2.98342649e-02, -9.36342621e+01, 5.36124259e-02]), + 'Velocity': array([-1.60970911e-01, -2.08152676e+00, 1.12467282e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.82232189, 16.78497505, -0.21774244]), + 'camera_rotation': array([-8.00795269, -2.08448958, 0.08687049]), + 'current_gear_input': False, + 'focus_actor_dist': 798.2998657226562, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -239.97317505, -2156.81005859, 17.06362915]), + 'frame': 17288, + 'frame_number': 17288, + 'framesequence': 66722, + 'gaze_dir': array([0.99369049, 0.09366608, 0.03946686]), + 'gaze_origin': array([-3.85557628, -0.04374924, -0.64461291]), + 'gaze_valid': True, + 'gaze_vergence': 36.291526794433594, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99247742, 0.12240601, 0.00184631]), + 'left_gaze_origin': array([-3.70811343, 2.81203485, -0.63371736]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5318603515625, + 'left_pupil_posn': array([ 0.34449208, -0.71510684]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99490356, 0.06492615, 0.0770874 ]), + 'right_gaze_origin': array([-4.00303984, -2.89953303, -0.65550846]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0836944580078125, + 'right_pupil_posn': array([-0.17083985, -0.89731336]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.3931791782379, + 'timestamp_carla': 565394, + 'timestamp_device': 3718823, + 'timestamp_stream': 565.3931791782379, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35686500e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.10302629, 0.04162798, 1.19880784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.7203364372253418, + 'FR_Wheel_Angle': 1.7660771608352661, + 'Location': array([ -2.30896974, -16.63715744, 0.17089145]), + 'Rotation': array([ 1.65427178e-02, -9.34484558e+01, 5.20785004e-02]), + 'Velocity': array([-8.97490680e-02, -2.07026267e+00, 8.50963581e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.89797878, 16.72064972, -0.1374135 ]), + 'camera_rotation': array([-7.52637625, -2.23536134, 0.05399448]), + 'current_gear_input': False, + 'focus_actor_dist': 1172.372802734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -131.27719116, -2523.98120117, 16.90502167]), + 'frame': 17289, + 'frame_number': 17289, + 'framesequence': 66726, + 'gaze_dir': array([0.99281311, 0.09851074, 0.02233887]), + 'gaze_origin': array([-3.87180042, -0.04434967, -0.64511877]), + 'gaze_valid': True, + 'gaze_vergence': 26.302629470825195, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99014282, 0.13699341, -0.02882385]), + 'left_gaze_origin': array([-3.74282217, 2.81008458, -0.61989444]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6430816650390625, + 'left_pupil_posn': array([ 0.34513259, -0.71578395]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9954834 , 0.06002808, 0.07350159]), + 'right_gaze_origin': array([-4.00077868, -2.89878392, -0.67034304]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([-0.16618776, -0.92403591]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.4241350777447, + 'timestamp_carla': 565425, + 'timestamp_device': 3718856, + 'timestamp_stream': 565.4241350777447, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.37586212e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.02264101, 0.00213239, 1.90996492]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.910217523574829, + 'FR_Wheel_Angle': 3.2048094272613525, + 'Location': array([ -2.32801104, -17.10666656, 0.17113197]), + 'Rotation': array([ 7.55418884e-03, -9.31050949e+01, 5.56588322e-02]), + 'Velocity': array([-5.06769232e-02, -1.96189821e+00, 7.97958346e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.9564724 , 16.65179825, -0.04633313]), + 'camera_rotation': array([-7.00885963e+00, -2.31911492e+00, -7.45163125e-04]), + 'current_gear_input': False, + 'focus_actor_dist': 1079.4385986328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -137.95925903, -2430.64648438, 16.91784668]), + 'frame': 17290, + 'frame_number': 17290, + 'framesequence': 66730, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.9297513961792, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.75245547, 2.80800176, -0.62097019]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.656280517578125, + 'left_pupil_posn': array([ 0.33928907, -0.72530758]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99742126, 0.03895569, 0.06002808]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 3.1878814697265625, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.4593315757811, + 'timestamp_carla': 565460, + 'timestamp_device': 3718889, + 'timestamp_stream': 565.4593315757811, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35552949e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.01580189, 0.00367148, 2.71225905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.670226573944092, + 'FR_Wheel_Angle': 5.078044414520264, + 'Location': array([ -2.33602738, -17.48666191, 0.17128815]), + 'Rotation': array([ 3.46973585e-03, -9.26307983e+01, 5.53797409e-02]), + 'Velocity': array([-3.53551167e-03, -1.81402373e+00, 7.10134511e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.00376701, 16.59401321, 0.04237894]), + 'camera_rotation': array([-6.57072353, -2.33043456, -0.06724306]), + 'current_gear_input': False, + 'focus_actor_dist': 959.0076293945312, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -246.12518311, -2318.72290039, 17.04084778]), + 'frame': 17291, + 'frame_number': 17291, + 'framesequence': 66734, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 29.982580184936523, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.77289271, 2.80924082, -0.6084305 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.609832763671875, + 'left_pupil_posn': array([ 0.35345769, -0.73334444]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99667358, 0.07383728, 0.03424072]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.4917371794581, + 'timestamp_carla': 565493, + 'timestamp_device': 3718923, + 'timestamp_stream': 565.4917371794581, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36556216e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.03123498, 0.0341495 , 2.78254604]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.093907833099365, + 'FR_Wheel_Angle': 5.363872528076172, + 'Location': array([ -2.33617592, -17.88544083, 0.17144573]), + 'Rotation': array([ 9.56226431e-04, -9.19581070e+01, 5.82902730e-02]), + 'Velocity': array([ 2.65120808e-02, -1.62139678e+00, 5.54408995e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.03438568, 16.54079056, 0.08879801]), + 'camera_rotation': array([-6.31424332, -2.35116506, -0.20961204]), + 'current_gear_input': False, + 'focus_actor_dist': 1023.5419921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -246.38265991, -2383.65551758, 17.03153229]), + 'frame': 17292, + 'frame_number': 17292, + 'framesequence': 66738, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 28.193437576293945, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73506474, 2.80566883, -0.62332463]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5517578125, + 'left_pupil_posn': array([ 0.34133327, -0.73019457]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99835205, 0.03997803, 0.0410614 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.5253920778632, + 'timestamp_carla': 565526, + 'timestamp_device': 3718956, + 'timestamp_stream': 565.5253920778632, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36228158e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.07045665, -0.01699831, 2.86854649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.099582672119141, + 'FR_Wheel_Angle': 5.360123157501221, + 'Location': array([ -2.33091235, -18.28679276, 0.17149121]), + 'Rotation': array([ 6.61845272e-03, -9.12556229e+01, 6.01710230e-02]), + 'Velocity': array([ 4.80810069e-02, -1.60717607e+00, 5.45625691e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.0558691 , 16.50816917, 0.07580712]), + 'camera_rotation': array([-6.24236917, -2.34756804, -0.36372533]), + 'current_gear_input': False, + 'focus_actor_dist': 1065.4290771484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -246.82603455, -2425.77392578, 17.02926636]), + 'frame': 17293, + 'frame_number': 17293, + 'framesequence': 66742, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 24.25797462463379, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69826961, 2.80374169, -0.63515782]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.498565673828125, + 'left_pupil_posn': array([ 0.34813213, -0.72621763]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99719238, 0.05604553, 0.04954529]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.5585844777524, + 'timestamp_carla': 565560, + 'timestamp_device': 3718989, + 'timestamp_stream': 565.5585844777524, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36380755e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-4.59446646e-02, 8.74187448e-04, 3.31713915e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.0492472648620605, + 'FR_Wheel_Angle': 5.261317253112793, + 'Location': array([ -2.32098317, -18.68747139, 0.17159039]), + 'Rotation': array([ 2.12282259e-02, -9.05579834e+01, 5.83653115e-02]), + 'Velocity': array([ 7.73100108e-02, -1.93887997e+00, 1.23590941e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.07320595, 16.47840118, 0.0397022 ]), + 'camera_rotation': array([-6.25996351, -2.3518281 , -0.47399104]), + 'current_gear_input': False, + 'focus_actor_dist': 1077.5428466796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -246.79827881, -2437.94189453, 17.02845764]), + 'frame': 17294, + 'frame_number': 17294, + 'framesequence': 66746, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.860031127929688, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.71143961, 2.80120087, -0.62723392]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6154022216796875, + 'left_pupil_posn': array([ 0.34818721, -0.7182759 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99682617, 0.05195618, 0.06019592]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 3.2316741943359375, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.5914596766233, + 'timestamp_carla': 565592, + 'timestamp_device': 3719023, + 'timestamp_stream': 565.5914596766233, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36693539e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-1.65962987e-02, -1.12563884e-03, 3.58168817e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.505404949188232, + 'FR_Wheel_Angle': 4.705150127410889, + 'Location': array([ -2.30378127, -19.17861748, 0.17169806]), + 'Rotation': array([ 2.76622642e-02, -8.97610168e+01, 5.80688119e-02]), + 'Velocity': array([ 1.13024391e-01, -2.34400177e+00, 1.39583112e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.07929039e+00, 1.64730396e+01, 3.27362679e-03]), + 'camera_rotation': array([-6.41557598, -2.3345716 , -0.51077425]), + 'current_gear_input': False, + 'focus_actor_dist': 1074.1947021484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -246.90666199, -2434.56152344, 17.02876282]), + 'frame': 17295, + 'frame_number': 17295, + 'framesequence': 66750, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 12.803874969482422, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66630268, 2.79856873, -0.63834387]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6435394287109375, + 'left_pupil_posn': array([ 0.34751546, -0.70778942]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99588013, 0.04954529, 0.07580566]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.6252119764686, + 'timestamp_carla': 565626, + 'timestamp_device': 3719056, + 'timestamp_stream': 565.6252119764686, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36209112e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.03002145, 0.01517036, 3.68839407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.714651107788086, + 'FR_Wheel_Angle': 3.45927357673645, + 'Location': array([ -2.28099084, -19.68276787, 0.17175582]), + 'Rotation': array([ 2.52170563e-02, -8.90086975e+01, 5.83545864e-02]), + 'Velocity': array([ 1.52787924e-01, -2.69504976e+00, 1.19709963e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.07742977e+00, 1.64767609e+01, -6.35051774e-03]), + 'camera_rotation': array([-6.4761734 , -2.3010478 , -0.43088371]), + 'current_gear_input': False, + 'focus_actor_dist': 1047.878173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -246.58467102, -2408.08203125, 17.03017426]), + 'frame': 17296, + 'frame_number': 17296, + 'framesequence': 66754, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 13.064607620239258, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66069818, 2.79756784, -0.63937992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.514862060546875, + 'left_pupil_posn': array([ 0.35293543, -0.70449162]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99462891, 0.06202698, 0.08273315]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.6584003791213, + 'timestamp_carla': 565659, + 'timestamp_device': 3719089, + 'timestamp_stream': 565.6584003791213, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36354072e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.0985836 , 0.02838944, 1.08413053]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.0111892223358154, + 'FR_Wheel_Angle': 0.909572184085846, + 'Location': array([ -2.24772978, -20.43697166, 0.1718282 ]), + 'Rotation': array([ 1.07233962e-02, -8.83667908e+01, 6.86769783e-02]), + 'Velocity': array([ 1.17614865e-01, -2.98471642e+00, -5.64041140e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.0744915 , 16.49486351, 0.03157285]), + 'camera_rotation': array([-6.36022377, -2.21905279, -0.37891024]), + 'current_gear_input': False, + 'focus_actor_dist': 1038.0130615234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -245.9758606 , -2398.15722656, 17.03017426]), + 'frame': 17297, + 'frame_number': 17297, + 'framesequence': 66758, + 'gaze_dir': array([9.90653992e-01, 9.98077393e-02, 5.95092773e-04]), + 'gaze_origin': array([-4.26023483, -0.05873261, -0.46307683]), + 'gaze_valid': True, + 'gaze_vergence': 14.020527839660645, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98684692, 0.13807678, -0.08396912]), + 'left_gaze_origin': array([-3.67584872, 2.79947662, -0.63295293]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.51556396484375, + 'left_pupil_posn': array([ 0.3513025 , -0.70177257]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99446106, 0.0615387 , 0.0851593 ]), + 'right_gaze_origin': array([-4.84462166, -2.91694188, -0.2932007 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.86700439453125, + 'right_pupil_posn': array([-0.14324796, -0.87568223]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.6924630776048, + 'timestamp_carla': 565694, + 'timestamp_device': 3719123, + 'timestamp_stream': 565.6924630776048, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35778049e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.09717759, -0.01424467, 0.0013002 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.22594357, -21.08645248, 0.17194961]), + 'Rotation': array([-1.17479246e-02, -8.82680359e+01, 7.02070668e-02]), + 'Velocity': array([ 8.66713896e-02, -2.86928391e+00, 7.14635826e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.06826496, 16.53084755, 0.06034593]), + 'camera_rotation': array([-6.20021296, -2.12932849, -0.26456988]), + 'current_gear_input': False, + 'focus_actor_dist': 1074.7916259765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -136.75567627, -2425.23535156, 16.91699219]), + 'frame': 17298, + 'frame_number': 17298, + 'framesequence': 66762, + 'gaze_dir': array([ 0.99034882, 0.08887482, -0.01508331]), + 'gaze_origin': array([-4.07802773, -0.0542511 , -0.533593 ]), + 'gaze_valid': True, + 'gaze_vergence': 6.4044952392578125, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98683167, 0.11065674, -0.1178894 ]), + 'left_gaze_origin': array([-3.66812015, 2.80016184, -0.63541722]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.49041748046875, + 'left_pupil_posn': array([ 0.35252643, -0.70003653]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99386597, 0.0670929 , 0.08772278]), + 'right_gaze_origin': array([-4.48793507, -2.90866399, -0.43176883]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([-0.16578871, -0.9063803 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.7259355783463, + 'timestamp_carla': 565727, + 'timestamp_device': 3719156, + 'timestamp_stream': 565.7259355783463, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35915373e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 5.47021404e-02, -8.54813587e-03, 3.14425165e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.2092247 , -21.6404705 , 0.17203316]), + 'Rotation': array([-2.68289819e-02, -8.82680969e+01, 6.69920444e-02]), + 'Velocity': array([ 7.98545033e-02, -2.64943528e+00, -1.21116638e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.05137157, 16.57086563, 0.06991226]), + 'camera_rotation': array([-6.10196781, -2.02515221, -0.19379117]), + 'current_gear_input': False, + 'focus_actor_dist': 957.4161987304688, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -157.55056763, -2308.74121094, 16.95223999]), + 'frame': 17299, + 'frame_number': 17299, + 'framesequence': 66766, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 10.490403175354004, + 'handbrake_input': False, + 'left_eye_openness': 0.10000000149011612, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66082931, 2.80042887, -0.63825536]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4038543701171875, + 'left_pupil_posn': array([ 0.34582341, -0.70112228]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99497986, 0.05067444, 0.08618164]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 2.993896484375, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.7583197765052, + 'timestamp_carla': 565759, + 'timestamp_device': 3719189, + 'timestamp_stream': 565.7583197765052, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36781317e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 2.51171347e-02, -4.96699649e-04, 1.65719390e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.060091972351074, + 'FR_Wheel_Angle': 2.4015538692474365, + 'Location': array([ -2.1860764 , -22.25260925, 0.172089 ]), + 'Rotation': array([-3.61316986e-02, -8.80796127e+01, 5.85207790e-02]), + 'Velocity': array([ 1.27494812e-01, -2.38946533e+00, -3.03058623e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.05663681, 16.62176895, 0.07998039]), + 'camera_rotation': array([-5.99713135, -1.89493537, -0.13625821]), + 'current_gear_input': False, + 'focus_actor_dist': 1102.2120361328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -240.57933044, -2462.74267578, 17.02050781]), + 'frame': 17300, + 'frame_number': 17300, + 'framesequence': 66770, + 'gaze_dir': array([ 0.98471832, 0.14024353, -0.00214386]), + 'gaze_origin': array([-3.85264683, -0.06299515, -0.63285834]), + 'gaze_valid': True, + 'gaze_vergence': 13.38967227935791, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97746277, 0.18977356, -0.09234619]), + 'left_gaze_origin': array([-3.57121158, 2.78858662, -0.67787325]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.195587158203125, + 'left_pupil_posn': array([ 0.36906922, -0.70852947]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99197388, 0.0907135 , 0.08805847]), + 'right_gaze_origin': array([-4.13408184, -2.91457677, -0.58784336]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([-0.13073778, -0.92319119]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 565.7925388775766, + 'timestamp_carla': 565794, + 'timestamp_device': 3719223, + 'timestamp_stream': 565.7925388775766, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35903918e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.00764534, -0.00713438, 2.81835413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.864858388900757, + 'FR_Wheel_Angle': 4.312748432159424, + 'Location': array([ -2.15422273, -22.77643967, 0.17203864]), + 'Rotation': array([-3.58243398e-02, -8.75557480e+01, 5.68414368e-02]), + 'Velocity': array([ 1.74039364e-01, -2.16430449e+00, 3.93438313e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.07295418, 16.68036079, 0.07486007]), + 'camera_rotation': array([-5.97605324, -1.74344206, -0.08257115]), + 'current_gear_input': False, + 'focus_actor_dist': 1110.9993896484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -81.49757385, -2455.35449219, 16.85864258]), + 'frame': 17301, + 'frame_number': 17301, + 'framesequence': 66774, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 565.8244911767542, + 'timestamp_carla': 565826, + 'timestamp_device': 3719256, + 'timestamp_stream': 565.8244911767542, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.37055964e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.00515272, -0.00642915, 4.02814627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.320216655731201, + 'FR_Wheel_Angle': 7.129753112792969, + 'Location': array([ -2.11820292, -23.1891613 , 0.17191391]), + 'Rotation': array([-3.44856232e-02, -8.68667603e+01, 5.43730259e-02]), + 'Velocity': array([ 2.26179183e-01, -1.98275590e+00, -5.81016531e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.07291031, 16.74473 , 0.0586524 ]), + 'camera_rotation': array([-6.03751802, -1.54588604, -0.03224026]), + 'current_gear_input': False, + 'focus_actor_dist': 1125.4254150390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -234.84667969, -2486.01635742, 17.01316833]), + 'frame': 17302, + 'frame_number': 17302, + 'framesequence': 66778, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 7.169505596160889, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.94604492, 0.32180786, 0.03778076]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.19085407, -3.05875874, -0.65774846]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.888397216796875, + 'right_pupil_posn': array([ 0.03861022, -0.91821623]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 565.8585707768798, + 'timestamp_carla': 565860, + 'timestamp_device': 3719289, + 'timestamp_stream': 565.8585707768798, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36155701e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-2.26369896e-03, 1.91369373e-02, 5.36942720e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.117719650268555, + 'FR_Wheel_Angle': 10.44515323638916, + 'Location': array([ -2.05600095, -23.68159103, 0.17172305]), + 'Rotation': array([-3.33927944e-02, -8.55900116e+01, 5.29354922e-02]), + 'Velocity': array([ 2.94163913e-01, -1.75947785e+00, -6.70986134e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.07806683, 16.83146858, 0.058065 ]), + 'camera_rotation': array([-6.04627419, -1.22897971, 0.06923801]), + 'current_gear_input': False, + 'focus_actor_dist': 1113.8446044921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -231.08128357, -2474.32617188, 17.01006317]), + 'frame': 17303, + 'frame_number': 17303, + 'framesequence': 66782, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 565.8907843790948, + 'timestamp_carla': 565892, + 'timestamp_device': 3719323, + 'timestamp_stream': 565.8907843790948, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36998734e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([0.01782903, 0.05240552, 6.11739922]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.242307662963867, + 'FR_Wheel_Angle': 12.843448638916016, + 'Location': array([ -1.97692442, -24.12950325, 0.17168021]), + 'Rotation': array([-3.43626812e-02, -8.39656219e+01, 5.45583926e-02]), + 'Velocity': array([ 3.38992953e-01, -1.51652741e+00, -5.51242789e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.06615257, 16.93541908, 0.064607 ]), + 'camera_rotation': array([-6.04449177, -0.75803679, 0.14898606]), + 'current_gear_input': False, + 'focus_actor_dist': 1112.2137451171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -224.90020752, -2472.578125 , 17.00388336]), + 'frame': 17304, + 'frame_number': 17304, + 'framesequence': 66786, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 3.1490936279296875, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 565.9251637756824, + 'timestamp_carla': 565926, + 'timestamp_device': 3719356, + 'timestamp_stream': 565.9251637756824, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35861962e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-0.04936843, 0.01206111, 6.5586462 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.147156715393066, + 'FR_Wheel_Angle': 13.857867240905762, + 'Location': array([ -1.90277839, -24.46622086, 0.17151809]), + 'Rotation': array([-2.86526419e-02, -8.25092926e+01, 5.50393201e-02]), + 'Velocity': array([ 3.90929610e-01, -1.49553263e+00, -4.72712505e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.08036232, 17.06708527, 0.04775967]), + 'camera_rotation': array([-6.08942747, -0.17095011, 0.20950577]), + 'current_gear_input': False, + 'focus_actor_dist': 1112.5977783203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -215.69688416, -2472.76074219, 16.99446106]), + 'frame': 17305, + 'frame_number': 17305, + 'framesequence': 66790, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 565.9589979760349, + 'timestamp_carla': 565960, + 'timestamp_device': 3719389, + 'timestamp_stream': 565.9589979760349, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35659771e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([-1.83653738e-02, 7.63493031e-03, 7.80562782e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.09865665435791, + 'FR_Wheel_Angle': 15.15073299407959, + 'Location': array([ -1.81288874, -24.81705475, 0.17132591]), + 'Rotation': array([-2.08730567e-02, -8.08727264e+01, 5.11622876e-02]), + 'Velocity': array([ 4.91387695e-01, -1.62097883e+00, -6.79087650e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.09219074, 17.21233559, 0.02337462]), + 'camera_rotation': array([-6.15953255, 0.5280537 , 0.37937447]), + 'current_gear_input': False, + 'focus_actor_dist': 1104.2276611328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -204.55078125, -2463.96435547, 16.9836731 ]), + 'frame': 17306, + 'frame_number': 17306, + 'framesequence': 66794, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 565.9921810775995, + 'timestamp_carla': 565993, + 'timestamp_device': 3719423, + 'timestamp_stream': 565.9921810775995, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36052696e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([4.51323390e-03, 2.06529032e-02, 9.14702511e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.292994499206543, + 'FR_Wheel_Angle': 16.731657028198242, + 'Location': array([ -1.71744812, -25.13864517, 0.17116661]), + 'Rotation': array([-1.93499252e-02, -7.92222748e+01, 4.73482311e-02]), + 'Velocity': array([ 6.00235403e-01, -1.72817957e+00, -1.00166316e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.12535095e+00, 1.73738880e+01, -1.27095273e-02]), + 'camera_rotation': array([-6.2506609 , 1.33460271, 0.51598006]), + 'current_gear_input': False, + 'focus_actor_dist': 1091.4378662109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -191.66287231, -2450.51806641, 16.97138214]), + 'frame': 17307, + 'frame_number': 17307, + 'framesequence': 66798, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 566.0247340761125, + 'timestamp_carla': 566026, + 'timestamp_device': 3719456, + 'timestamp_stream': 566.0247340761125, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.36739361e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([9.89262201e-03, 2.57894713e-02, 1.09815598e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.342109680175781, + 'FR_Wheel_Angle': 18.095369338989258, + 'Location': array([ -1.54883921, -25.61958885, 0.17094772]), + 'Rotation': array([-2.18156222e-02, -7.64783096e+01, 4.29940894e-02]), + 'Velocity': array([ 7.71610498e-01, -1.84468973e+00, -1.03376387e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.14474106, 17.53748703, -0.03040517]), + 'camera_rotation': array([-6.35837984, 2.13515663, 0.60064423]), + 'current_gear_input': False, + 'focus_actor_dist': 1075.2188720703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -177.29263306, -2433.33447266, 16.95783234]), + 'frame': 17308, + 'frame_number': 17308, + 'framesequence': 66802, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 566.0590364784002, + 'timestamp_carla': 566060, + 'timestamp_device': 3719489, + 'timestamp_stream': 566.0590364784002, + 'transform': [array([2.11354113e+00, 1.51294756e+01, 5.35816187e-03]), + array([-0.06390325, -7.67797327, 0.01413985])]} +{'AngularVelocity': array([ 0.02694601, 0.04727291, 12.16945171]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.045711517333984, + 'FR_Wheel_Angle': 19.023611068725586, + 'Location': array([ -1.36473417, -26.06232071, 0.17075732]), + 'Rotation': array([-2.61869431e-02, -7.37147064e+01, 4.05031480e-02]), + 'Velocity': array([ 9.20756459e-01, -1.89186442e+00, -1.04210852e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.1656971 , 17.68351555, -0.03954534]), + 'camera_rotation': array([-6.37440348, 2.85667014, 0.63839883]), + 'current_gear_input': False, + 'focus_actor_dist': 1056.884521484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -163.66670227, -2413.86425781, 16.94517517]), + 'frame': 17309, + 'frame_number': 17309, + 'framesequence': 66807, + 'gaze_dir': array([0.97953033, 0.20044708, 0.01009369]), + 'gaze_origin': array([-3.92385507, -0.1438141 , -0.61126256]), + 'gaze_valid': True, + 'gaze_vergence': 14.02612018585205, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97912598, 0.20170593, 0.02444458]), + 'left_gaze_origin': array([-3.70304132, 2.68074489, -0.64972693]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3409576416015625, + 'left_pupil_posn': array([ 0.48708379, -0.75163794]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97993469, 0.19918823, -0.0042572 ]), + 'right_gaze_origin': array([-4.14466906, -2.9683733 , -0.57279819]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.892547607421875, + 'right_pupil_posn': array([-0.07986808, -0.85079753]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0238040741533041, + 'timestamp': 566.0971092768013, + 'timestamp_carla': 566098, + 'timestamp_device': 3719531, + 'timestamp_stream': 566.0971092768013, + 'transform': [array([2.11342072e+00, 1.51293659e+01, 5.13223652e-03]), + array([-0.06381445, -7.67772627, 0.01450593])]} +{'AngularVelocity': array([ 0.03928243, 0.04471685, 12.17311382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.519912719726562, + 'FR_Wheel_Angle': 19.5704345703125, + 'Location': array([ -1.15499365, -26.49473763, 0.17057678]), + 'Rotation': array([-3.71084139e-02, -7.08217850e+01, 4.30515073e-02]), + 'Velocity': array([ 9.89177883e-01, -1.75363207e+00, -6.95524213e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.17935371, 17.81783295, -0.04516269]), + 'camera_rotation': array([-6.39324808, 3.45942402, 0.61043513]), + 'current_gear_input': False, + 'focus_actor_dist': 1157.4188232421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 87.34150696, -2464.99804688, 16.68572235]), + 'frame': 17310, + 'frame_number': 17310, + 'framesequence': 66810, + 'gaze_dir': array([ 0.98199463, 0.18513489, -0.0125351 ]), + 'gaze_origin': array([-3.91270709, -0.12733383, -0.59540558]), + 'gaze_valid': True, + 'gaze_vergence': 48.146976470947266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98632812, 0.16403198, 0.01525879]), + 'left_gaze_origin': array([-3.69528246, 2.70881963, -0.61943364]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.014984130859375, + 'left_pupil_posn': array([ 0.49175715, -0.76522183]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97766113, 0.20623779, -0.04032898]), + 'right_gaze_origin': array([-4.13013172, -2.96348739, -0.57137758]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.86395263671875, + 'right_pupil_posn': array([-0.0993222 , -0.84817708]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.03967345505952835, + 'timestamp': 566.1274841763079, + 'timestamp_carla': 566129, + 'timestamp_device': 3719556, + 'timestamp_stream': 566.1274841763079, + 'transform': [array([2.11345649e+00, 1.51291151e+01, 5.07192593e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([ 0.01311235, 0.02211695, 11.15713978]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.597156524658203, + 'FR_Wheel_Angle': 19.66878890991211, + 'Location': array([ -0.94098419, -26.88305664, 0.17038761]), + 'Rotation': array([-4.50450964e-02, -6.81132584e+01, 4.82633896e-02]), + 'Velocity': array([ 9.77947533e-01, -1.55084693e+00, -1.09272473e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.1906662 , 17.92171288, -0.0251155 ]), + 'camera_rotation': array([-6.45303965, 3.92981529, 0.6905486 ]), + 'current_gear_input': False, + 'focus_actor_dist': 943.3067016601562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 20.81697083, -2260.04931641, 16.77850342]), + 'frame': 17311, + 'frame_number': 17311, + 'framesequence': 66814, + 'gaze_dir': array([0.98323059, 0.17573547, 0.02436829]), + 'gaze_origin': array([-3.93338799, -0.11671448, -0.58319247]), + 'gaze_valid': True, + 'gaze_vergence': 6.064131259918213, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98506165, 0.17127991, -0.01731873]), + 'left_gaze_origin': array([-3.72512984, 2.72564411, -0.62146914]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1417999267578125, + 'left_pupil_posn': array([ 0.46259737, -0.72300327]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98139954, 0.18019104, 0.0660553 ]), + 'right_gaze_origin': array([-4.14164591, -2.95907307, -0.5449158 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9824371337890625, + 'right_pupil_posn': array([-0.09990329, -0.84383237]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.05555810034275055, + 'timestamp': 566.1609749794006, + 'timestamp_carla': 566162, + 'timestamp_device': 3719589, + 'timestamp_stream': 566.1609749794006, + 'transform': [array([2.11347032e+00, 1.51289558e+01, 5.07520651e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([4.21058340e-03, 1.13094328e-02, 1.02939663e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.646923065185547, + 'FR_Wheel_Angle': 19.729583740234375, + 'Location': array([ -0.75885105, -27.18198586, 0.17017254]), + 'Rotation': array([-4.76952083e-02, -6.59667130e+01, 5.05590886e-02]), + 'Velocity': array([ 9.53904092e-01, -1.39109087e+00, -1.17157935e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.19952774e+00, 1.80103970e+01, -8.50378163e-03]), + 'camera_rotation': array([-6.42271328, 4.25435114, 0.69754285]), + 'current_gear_input': False, + 'focus_actor_dist': 1321.5819091796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 127.07441711, -2625.28125 , 16.63480377]), + 'frame': 17312, + 'frame_number': 17312, + 'framesequence': 66818, + 'gaze_dir': array([0.97431183, 0.21770477, 0.01974487]), + 'gaze_origin': array([-3.92147684, -0.11490785, -0.59023136]), + 'gaze_valid': True, + 'gaze_vergence': 41.33085250854492, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98464966, 0.17416382, -0.01048279]), + 'left_gaze_origin': array([-3.71728992, 2.72976995, -0.62436068]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.00848388671875, + 'left_pupil_posn': array([ 0.4949559 , -0.73384166]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.963974 , 0.26124573, 0.04997253]), + 'right_gaze_origin': array([-4.12566423, -2.95958567, -0.55610204]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.159576416015625, + 'right_pupil_posn': array([-0.09846067, -0.84548736]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0793621763586998, + 'timestamp': 566.191897276789, + 'timestamp_carla': 566193, + 'timestamp_device': 3719623, + 'timestamp_stream': 566.191897276789, + 'transform': [array([2.11348486e+00, 1.51287622e+01, 5.09416591e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([1.74873136e-03, 6.11937232e-03, 9.35020924e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.687061309814453, + 'FR_Wheel_Angle': 19.784101486206055, + 'Location': array([ -0.55272162, -27.49202728, 0.16995411]), + 'Rotation': array([-4.91022281e-02, -6.36772270e+01, 5.19812703e-02]), + 'Velocity': array([ 9.16642129e-01, -1.22602141e+00, -7.99956324e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.19960308e+00, 1.80688515e+01, -1.48000140e-02]), + 'camera_rotation': array([-6.37962866, 4.41705132, 0.7133221 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1268.9254150390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 170.91668701, -2555.68725586, 16.59459686]), + 'frame': 17313, + 'frame_number': 17313, + 'framesequence': 66822, + 'gaze_dir': array([0.97939301, 0.19338989, 0.03704834]), + 'gaze_origin': array([-3.86771631, -0.11091156, -0.61957479]), + 'gaze_valid': True, + 'gaze_vergence': 30.308027267456055, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9851532 , 0.1716156 , -0.00164795]), + 'left_gaze_origin': array([-3.72005773, 2.73235321, -0.62572479]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15087890625, + 'left_pupil_posn': array([ 0.47199249, -0.7225877 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97363281, 0.21516418, 0.07574463]), + 'right_gaze_origin': array([-4.01537514, -2.95417643, -0.61342472]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.89837646484375, + 'right_pupil_posn': array([-0.10513663, -0.85794461]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.09919890016317368, + 'timestamp': 566.2261241786182, + 'timestamp_carla': 566227, + 'timestamp_device': 3719656, + 'timestamp_stream': 566.2261241786182, + 'transform': [array([2.11349702e+00, 1.51286488e+01, 5.08172996e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([8.74209276e-04, 3.87170329e-03, 8.32638454e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.723417282104492, + 'FR_Wheel_Angle': 19.829036712646484, + 'Location': array([ -0.35229063, -27.76930428, 0.16970077]), + 'Rotation': array([-4.99560013e-02, -6.15676575e+01, 5.27431220e-02]), + 'Velocity': array([ 0.87242538, -1.07974088, -0.0013916 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.20513153, 18.09521675, -0.02526766]), + 'camera_rotation': array([-6.37165785, 4.45982313, 0.69831479]), + 'current_gear_input': False, + 'focus_actor_dist': 1172.27392578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST14', + 'focus_actor_pt': array([ 115.14620972, -2474.83935547, 46.2154007 ]), + 'frame': 17314, + 'frame_number': 17314, + 'framesequence': 66826, + 'gaze_dir': array([0.97853851, 0.19728088, 0.04220581]), + 'gaze_origin': array([-3.69924355, -0.100869 , -0.67522967]), + 'gaze_valid': True, + 'gaze_vergence': 51.32985305786133, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98596191, 0.16624451, 0.01528931]), + 'left_gaze_origin': array([-3.72036481, 2.73819137, -0.62818152]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0886383056640625, + 'left_pupil_posn': array([ 0.47348905, -0.72840703]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97111511, 0.22831726, 0.06912231]), + 'right_gaze_origin': array([-3.67812204, -2.93992925, -0.72227788]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.104949951171875, + 'right_pupil_posn': array([-0.12146819, -0.84241712]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.11506828665733337, + 'timestamp': 566.2590554766357, + 'timestamp_carla': 566260, + 'timestamp_device': 3719689, + 'timestamp_stream': 566.2590554766357, + 'transform': [array([2.11351037e+00, 1.51285009e+01, 5.08417096e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([-0.11014796, -0.19607471, -0.0005416 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.96860408782959, + 'FR_Wheel_Angle': 18.229385375976562, + 'Location': array([ -0.26848292, -27.87970734, 0.16994186]), + 'Rotation': array([ -0.10189959, -60.6252327 , 0.08616638]), + 'Velocity': array([-9.46484579e-05, 1.06370950e-04, -1.20644443e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.20347786, 18.09382248, -0.0267342 ]), + 'camera_rotation': array([-6.35387182, 4.30869436, 0.70677811]), + 'current_gear_input': False, + 'focus_actor_dist': 1138.0025634765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST14', + 'focus_actor_pt': array([ 109.85733032, -2441.26025391, 54.79950714]), + 'frame': 17315, + 'frame_number': 17315, + 'framesequence': 66830, + 'gaze_dir': array([ 0.9977417 , -0.00832367, 0.01854706]), + 'gaze_origin': array([-3.83931923, 0.04251404, -0.61787951]), + 'gaze_valid': True, + 'gaze_vergence': 21.621614456176758, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9990387 , 0.02252197, -0.03744507]), + 'left_gaze_origin': array([-3.66949487, 2.89362955, -0.62522894]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1696319580078125, + 'left_pupil_posn': array([ 0.23809052, -0.69054139]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.10000000149011612, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9964447 , -0.03916931, 0.07453918]), + 'right_gaze_origin': array([-4.00914335, -2.80860162, -0.61053008]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1315155029296875, + 'right_pupil_posn': array([-0.28311235, -0.87509084]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.1269855797290802, + 'timestamp': 566.2924540787935, + 'timestamp_carla': 566294, + 'timestamp_device': 3719723, + 'timestamp_stream': 566.2924540787935, + 'transform': [array([2.11352372e+00, 1.51283464e+01, 5.08180587e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([-0.06802525, -0.09164054, -0.00022917]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.254834175109863, + 'FR_Wheel_Angle': 13.057455062866211, + 'Location': array([ -0.26822552, -27.87990189, 0.16968627]), + 'Rotation': array([-5.93884923e-02, -6.06251526e+01, 6.60671592e-02]), + 'Velocity': array([-4.23481106e-05, 6.06499198e-05, 1.43656696e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.18025303e+00, 1.80307579e+01, 9.48236790e-04]), + 'camera_rotation': array([-6.25072241, 3.78647351, 0.64139777]), + 'current_gear_input': False, + 'focus_actor_dist': 1269.6290283203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -109.39645386, -2619.73925781, 16.8764801 ]), + 'frame': 17316, + 'frame_number': 17316, + 'framesequence': 66834, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 12.585880279541016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72029591, 3.02824426, -0.61076665]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1207275390625, + 'left_pupil_posn': array([ 0.0728426 , -0.70841646]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.97763062, -0.20758057, 0.03366089]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.14682230353355408, + 'timestamp': 566.3254442773759, + 'timestamp_carla': 566327, + 'timestamp_device': 3719756, + 'timestamp_stream': 566.3254442773759, + 'transform': [array([2.11353874e+00, 1.51281548e+01, 5.08302683e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([-1.57722048e-02, -2.34375261e-02, -4.34120957e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.817742824554443, + 'FR_Wheel_Angle': 7.704761981964111, + 'Location': array([ -0.26814631, -27.87996292, 0.16960511]), + 'Rotation': array([-4.63564917e-02, -6.06251602e+01, 6.00027367e-02]), + 'Velocity': array([-6.63061610e-06, 1.61975204e-05, -3.91996407e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.14185715, 17.83872032, 0.04050658]), + 'camera_rotation': array([-6.09239864, 2.53200364, 0.57910085]), + 'current_gear_input': False, + 'focus_actor_dist': 1075.3818359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -131.03869629, -2429.63525391, 16.91086578]), + 'frame': 17317, + 'frame_number': 17317, + 'framesequence': 66838, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 6.882084846496582, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.74907255, 3.12148762, -0.62964326]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2296600341796875, + 'left_pupil_posn': array([-0.04975873, -0.75299895]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.93995667, -0.3412323 , -0.00378418]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.16269169747829437, + 'timestamp': 566.358127579093, + 'timestamp_carla': 566359, + 'timestamp_device': 3719789, + 'timestamp_stream': 566.358127579093, + 'transform': [array([2.11355591e+00, 1.51279097e+01, 5.08558284e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([-0.00347667, -0.00590692, 0.00023424]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.5176570415496826, + 'FR_Wheel_Angle': 3.0108749866485596, + 'Location': array([ -0.26812312, -27.87997818, 0.1696043 ]), + 'Rotation': array([-4.32419255e-02, -6.06251526e+01, 5.83163537e-02]), + 'Velocity': array([ 0.00010607, -0.00016511, -0.00018558]), + 'brake_input': 0.0, + 'camera_location': array([-5.08234215, 17.4926796 , 0.07247221]), + 'camera_rotation': array([-5.95201778, 0.41037652, 0.70707297]), + 'current_gear_input': False, + 'focus_actor_dist': 1103.6649169921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -152.11813354, -2460.27685547, 16.93040466]), + 'frame': 17318, + 'frame_number': 17318, + 'framesequence': 66842, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 5.2784624099731445, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.77654743, 3.16641259, -0.65969241]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1852264404296875, + 'left_pupil_posn': array([-0.11428857, -0.79736185]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9108429 , -0.41242981, -0.01559448]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.17856107652187347, + 'timestamp': 566.3915551789105, + 'timestamp_carla': 566393, + 'timestamp_device': 3719823, + 'timestamp_stream': 566.3915551789105, + 'transform': [array([2.11357522e+00, 1.51276112e+01, 5.08104311e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([-7.18723750e-05, -1.29034661e-03, -6.56313705e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.26805374, -27.88009453, 0.16957736]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([ 4.47018056e-06, 1.44341141e-06, -9.45613720e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.02071762, 17.01179504, 0.09607466]), + 'camera_rotation': array([-5.81324196, -2.51346183, 0.85222369]), + 'current_gear_input': False, + 'focus_actor_dist': 1130.002197265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -191.74356079, -2489.51220703, 16.96894073]), + 'frame': 17319, + 'frame_number': 17319, + 'framesequence': 66846, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 5.732112884521484, + 'handbrake_input': False, + 'left_eye_openness': 0.5611274242401123, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.76495838, 3.13545847, -0.66305089]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1605072021484375, + 'left_pupil_posn': array([-0.07975966, -0.79388046]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.92164612, -0.38783264, -0.0112915 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.1904631108045578, + 'timestamp': 566.4260449782014, + 'timestamp_carla': 566427, + 'timestamp_device': 3719856, + 'timestamp_stream': 566.4260449782014, + 'transform': [array([2.11359811e+00, 1.51272326e+01, 5.06994221e-03]), + array([-0.0637803 , -7.67776489, 0.01469954])]} +{'AngularVelocity': array([-2.50253681e-04, -5.08024474e-04, -1.47909668e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.26805162, -27.88009644, 0.16957672]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([ 4.17851834e-06, 1.52605776e-06, -2.96522921e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.98546505, 16.4802475 , 0.09854848]), + 'camera_rotation': array([-5.73184681, -5.66484404, 0.96356684]), + 'current_gear_input': False, + 'focus_actor_dist': 1157.2303466796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -249.64395142, -2518.26342773, 17.02615356]), + 'frame': 17320, + 'frame_number': 17320, + 'framesequence': 66850, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 7.154902458190918, + 'handbrake_input': False, + 'left_eye_openness': 0.9056243896484375, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.74693012, 3.09698796, -0.66036993]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.299407958984375, + 'left_pupil_posn': array([-0.02411956, -0.78745854]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9460144 , -0.32315063, -0.02484131]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.20236514508724213, + 'timestamp': 566.4591091759503, + 'timestamp_carla': 566460, + 'timestamp_device': 3719889, + 'timestamp_stream': 566.4591091759503, + 'transform': [array([2.11364198e+00, 1.51266851e+01, 4.98189917e-03]), + array([-0.06374615, -7.67778778, 0.01488162])]} +{'AngularVelocity': array([-5.65226765e-05, -1.34934890e-04, -1.44679489e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.26805013, -27.88009644, 0.16958359]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([4.71700923e-06, 1.27495878e-06, 7.61310293e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.98609352, 15.91960144, 0.11126194]), + 'camera_rotation': array([-5.63636732, -8.82730389, 0.85041231]), + 'current_gear_input': False, + 'focus_actor_dist': 1173.720703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -314.42245483, -2532.95092773, 17.09131622]), + 'frame': 17321, + 'frame_number': 17321, + 'framesequence': 66854, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 9.288769721984863, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73081374, 3.04985356, -0.65101779]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.10662841796875, + 'left_pupil_posn': array([ 0.03920436, -0.77669454]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.96644592, -0.25448608, -0.0348053 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2063324898481369, + 'timestamp': 566.4922760762274, + 'timestamp_carla': 566493, + 'timestamp_device': 3719923, + 'timestamp_stream': 566.4922760762274, + 'transform': [array([2.11367893e+00, 1.51258850e+01, 4.82940674e-03]), + array([-0.06369151, -7.67778778, 0.01518447])]} +{'AngularVelocity': array([-6.41629667e-05, 3.84543600e-05, -1.50262704e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.26804894, -27.88009644, 0.16957515]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([ 4.30803721e-06, 1.27510600e-06, -3.20640713e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.00075722, 15.35913658, 0.12897637]), + 'camera_rotation': array([ -5.54648876, -11.82012653, 0.6327607 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1193.8173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -381.48171997, -2547.55883789, 17.15882111]), + 'frame': 17322, + 'frame_number': 17322, + 'framesequence': 66859, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 12.45683479309082, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.6945467 , 2.99521804, -0.66327977]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.300689697265625, + 'left_pupil_posn': array([ 0.10458446, -0.77478635]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98052979, -0.19371033, -0.03190613]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.21031509339809418, + 'timestamp': 566.5273936763406, + 'timestamp_carla': 566529, + 'timestamp_device': 3719964, + 'timestamp_stream': 566.5273936763406, + 'transform': [array([2.11375904e+00, 1.51240931e+01, 4.30698367e-03]), + array([-0.06352076, -7.67778873, 0.01617969])]} +{'AngularVelocity': array([-2.83988502e-05, 6.68275825e-05, -1.47424789e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.26804799, -27.88009644, 0.16958335]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([ 4.60201863e-06, 1.26214138e-06, -1.36393661e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.04242706, 14.86171341, 0.14351493]), + 'camera_rotation': array([ -5.49670362, -14.34993172, 0.5256961 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1213.446533203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -446.73858643, -2558.45898438, 17.22470093]), + 'frame': 17323, + 'frame_number': 17323, + 'framesequence': 66863, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 14.273505210876465, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.64977765, 2.9597261 , -0.68498385]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2313232421875, + 'left_pupil_posn': array([ 0.14344501, -0.78289318]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98588562, -0.16285706, -0.03860474]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.23015183210372925, + 'timestamp': 566.5628735758364, + 'timestamp_carla': 566564, + 'timestamp_device': 3719998, + 'timestamp_stream': 566.5628735758364, + 'transform': [array([2.11388445e+00, 1.51212444e+01, 3.77124781e-03]), + array([-0.06333634, -7.67778969, 0.01720888])]} +{'AngularVelocity': array([ 6.64349500e-05, -5.01719151e-05, -1.44332762e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': -1.4794656038284302, + 'Location': array([ -0.26804692, -27.88009644, 0.16958843]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([4.87563193e-06, 1.17306013e-06, 1.68416940e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.07314682, 14.42344856, 0.15838425]), + 'camera_rotation': array([ -5.38697672, -16.52649879, 0.3334088 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1224.821044921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -501.99481201, -2559.83154297, 17.28099823]), + 'frame': 17324, + 'frame_number': 17324, + 'framesequence': 66867, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 20.335128784179688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73987436, 2.92522907, -0.66291809]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21746826171875, + 'left_pupil_posn': array([ 0.18704391, -0.78537512]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99237061, -0.12113953, -0.02278137]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.24998855590820312, + 'timestamp': 566.5967880785465, + 'timestamp_carla': 566598, + 'timestamp_device': 3720031, + 'timestamp_stream': 566.5967880785465, + 'transform': [array([2.11405778e+00, 1.51163597e+01, 2.44215014e-03]), + array([-0.06287872, -7.67772913, 0.01982539])]} +{'AngularVelocity': array([-3.08749331e-05, 6.86261992e-05, -1.44487531e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.5671865940093994, + 'FR_Wheel_Angle': -3.902549982070923, + 'Location': array([ -0.26804602, -27.88009644, 0.16958465]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([ 4.86318959e-06, 1.18430398e-06, -4.79726305e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.11383629, 14.03110123, 0.16057356]), + 'camera_rotation': array([ -5.31328583, -18.26327896, 0.20108686]), + 'current_gear_input': False, + 'focus_actor_dist': 1245.229248046875, + 'focus_actor_name': 'Plane36', + 'focus_actor_pt': array([ -552.5647583 , -2569.5065918 , 17.79415131]), + 'frame': 17325, + 'frame_number': 17325, + 'framesequence': 66871, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 26.14790153503418, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73964095, 2.9025681 , -0.66357118]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.25048828125, + 'left_pupil_posn': array([ 0.21509123, -0.78543186]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99533081, -0.09454346, -0.01921082]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.269825279712677, + 'timestamp': 566.6281724758446, + 'timestamp_carla': 566629, + 'timestamp_device': 3720064, + 'timestamp_stream': 566.6281724758446, + 'transform': [array([2.11424541e+00, 1.51112461e+01, 1.94995874e-03]), + array([-0.0626943 , -7.67767763, 0.02083375])]} +{'AngularVelocity': array([ 2.17993929e-05, -2.50488029e-05, -1.39679578e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.008759021759033, + 'FR_Wheel_Angle': -6.9989471435546875, + 'Location': array([ -0.26804492, -27.88009644, 0.16959381]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([5.18660045e-06, 1.08464315e-06, 1.89559141e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.10019732, 13.73144817, 0.1486623 ]), + 'camera_rotation': array([ -5.34070206, -19.36451149, 0.12677684]), + 'current_gear_input': False, + 'focus_actor_dist': 1056.797119140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -537.71148682, -2379.93066406, 36.84033966]), + 'frame': 17326, + 'frame_number': 17326, + 'framesequence': 66875, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 24.772430419921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.74340963, 2.89126301, -0.6504761 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2084197998046875, + 'left_pupil_posn': array([ 0.22938573, -0.78334522]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99607849, -0.08036804, -0.03666687]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.28172731399536133, + 'timestamp': 566.6611212790012, + 'timestamp_carla': 566662, + 'timestamp_device': 3720097, + 'timestamp_stream': 566.6611212790012, + 'transform': [array([2.11590934e+00, 1.51032629e+01, 6.44550310e-04]), + array([-0.06222985, -7.68030834, 0.02339485])]} +{'AngularVelocity': array([-2.15635027e-05, 7.00043302e-06, -1.35470964e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.473509788513184, + 'FR_Wheel_Angle': -9.884750366210938, + 'Location': array([ -0.26804385, -27.88009644, 0.16958103]), + 'Rotation': array([-4.26955111e-02, -6.06251106e+01, 5.80089539e-02]), + 'Velocity': array([5.25501537e-06, 9.79781589e-07, 2.28155754e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.08800316, 13.49897003, 0.11973897]), + 'camera_rotation': array([ -5.37885571, -20.11244202, -0.07951557]), + 'current_gear_input': False, + 'focus_actor_dist': 1017.4494018554688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -545.8807373 , -2337.22460938, 40.00722504]), + 'frame': 17327, + 'frame_number': 17327, + 'framesequence': 66879, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 21.959331512451172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.75285673, 2.87587595, -0.64937139]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1566925048828125, + 'left_pupil_posn': array([ 0.24499714, -0.7905798 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9962616 , -0.07243347, -0.04685974]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.29761195182800293, + 'timestamp': 566.6953427791595, + 'timestamp_carla': 566696, + 'timestamp_device': 3720131, + 'timestamp_stream': 566.6953427791595, + 'transform': [array([ 2.11848640e+00, 1.50935783e+01, -9.08088696e-05]), + array([-0.061902 , -7.68462086, 0.02482148])]} +{'AngularVelocity': array([ 0.05617667, -0.01539086, -0.38814694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.791537284851074, + 'FR_Wheel_Angle': -11.565630912780762, + 'Location': array([ -0.26696 , -27.88235474, 0.16958022]), + 'Rotation': array([-4.25725654e-02, -6.06345100e+01, 5.79022914e-02]), + 'Velocity': array([-0.00253938, 0.01251219, -0.00015279]), + 'brake_input': 0.0, + 'camera_location': array([-5.0720911 , 13.30688667, 0.09323101]), + 'camera_rotation': array([ -5.45485497, -20.57261658, -0.23707233]), + 'current_gear_input': False, + 'focus_actor_dist': 1009.6993408203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -556.36352539, -2326.64257812, 40.08187103]), + 'frame': 17328, + 'frame_number': 17328, + 'framesequence': 66883, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 34.3939094543457, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73393703, 2.87106037, -0.65395057]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2639007568359375, + 'left_pupil_posn': array([ 0.25240958, -0.77961171]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99780273, -0.06124878, -0.02522278]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.3015792965888977, + 'timestamp': 566.7279118783772, + 'timestamp_carla': 566729, + 'timestamp_device': 3720164, + 'timestamp_stream': 566.7279118783772, + 'transform': [array([ 2.11649585e+00, 1.50834322e+01, -6.77967037e-04]), + array([-0.06171758, -7.67981291, 0.02598887])]} +{'AngularVelocity': array([ 0.06000694, -0.0189589 , -0.3153401 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.762922286987305, + 'FR_Wheel_Angle': -12.169291496276855, + 'Location': array([ -0.26648349, -27.88323593, 0.16958126]), + 'Rotation': array([-4.32760753e-02, -6.06395226e+01, 5.76396175e-02]), + 'Velocity': array([-0.0075243 , 0.02580697, -0.00019643]), + 'brake_input': 0.0, + 'camera_location': array([-5.03136635, 13.22682476, 0.05907433]), + 'camera_rotation': array([ -5.59154081, -20.44830894, -0.45842153]), + 'current_gear_input': False, + 'focus_actor_dist': 1010.0345458984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -564.32922363, -2325.27392578, 38.72045898]), + 'frame': 17329, + 'frame_number': 17329, + 'framesequence': 66886, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 51.20045852661133, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72958231, 2.87297988, -0.65759283]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2884979248046875, + 'left_pupil_posn': array([ 0.25500596, -0.7744633 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.998703 , -0.04994202, -0.00947571]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.3015792965888977, + 'timestamp': 566.7605139762163, + 'timestamp_carla': 566762, + 'timestamp_device': 3720189, + 'timestamp_stream': 566.7605139762163, + 'transform': [array([ 2.11897874e+00, 1.50708790e+01, -1.40468590e-03]), + array([-0.06144438, -7.68366861, 0.0274236 ])]} +{'AngularVelocity': array([0.11561694, 0.00881396, 0.94317353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.757440567016602, + 'FR_Wheel_Angle': -12.157041549682617, + 'Location': array([ -0.26907143, -27.87748718, 0.16960171]), + 'Rotation': array([-4.56529818e-02, -6.06000290e+01, 5.69893084e-02]), + 'Velocity': array([-0.04653604, 0.10782213, 0.00049887]), + 'brake_input': 0.0, + 'camera_location': array([-4.98625851, 13.2039175 , 0.04559237]), + 'camera_rotation': array([ -5.74248791, -20.04978561, -0.6471951 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1008.4636840820312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -561.65625 , -2325.37255859, 36.45778656]), + 'frame': 17330, + 'frame_number': 17330, + 'framesequence': 66891, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 26.734865188598633, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7358799 , 2.87705398, -0.64483953]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2215118408203125, + 'left_pupil_posn': array([ 0.24643314, -0.77754605]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99719238, -0.06420898, -0.03823853]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.3015792965888977, + 'timestamp': 566.7953366786242, + 'timestamp_carla': 566797, + 'timestamp_device': 3720231, + 'timestamp_stream': 566.7953366786242, + 'transform': [array([ 2.12115526e+00, 1.50560331e+01, -1.69546122e-03]), + array([-0.06142389, -7.68677568, 0.02796881])]} +{'AngularVelocity': array([-0.04002127, -0.03503772, 2.66037774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.80121898651123, + 'FR_Wheel_Angle': -12.301025390625, + 'Location': array([ -0.30382836, -27.79841805, 0.16974963]), + 'Rotation': array([-6.25986829e-02, -6.02253609e+01, 4.99635190e-02]), + 'Velocity': array([-0.2060288 , 0.51726151, 0.00056213]), + 'brake_input': 0.0, + 'camera_location': array([-4.93695545, 13.21716499, 0.0250894 ]), + 'camera_rotation': array([ -5.88070393, -19.50761032, -0.74188459]), + 'current_gear_input': False, + 'focus_actor_dist': 1007.1852416992188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -554.58044434, -2327.31005859, 33.94450378]), + 'frame': 17331, + 'frame_number': 17331, + 'framesequence': 66895, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 38.29545593261719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.62463546, 2.88893294, -0.70086366]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3756103515625, + 'left_pupil_posn': array([ 0.23187172, -0.76907873]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99726868, -0.07267761, 0.01300049]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.24602121114730835, + 'timestamp': 566.8272476792336, + 'timestamp_carla': 566828, + 'timestamp_device': 3720264, + 'timestamp_stream': 566.8272476792336, + 'transform': [array([ 2.12495589e+00, 1.50406160e+01, -2.06535333e-03]), + array([-0.06134875, -7.69306374, 0.02872441])]} +{'AngularVelocity': array([-0.02500251, -0.00867832, 4.26124477]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.891220092773438, + 'FR_Wheel_Angle': -13.129499435424805, + 'Location': array([ -0.36421034, -27.66183853, 0.16976635]), + 'Rotation': array([-5.61236627e-02, -5.95321846e+01, 5.24758920e-02]), + 'Velocity': array([-2.75893271e-01, 6.71934366e-01, 4.67481615e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.87784433e+00, 1.32888336e+01, -5.91295958e-03]), + 'camera_rotation': array([ -5.98551321, -18.80636024, -0.83140767]), + 'current_gear_input': False, + 'focus_actor_dist': 1012.5951538085938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -547.03112793, -2336.55419922, 30.95481873]), + 'frame': 17332, + 'frame_number': 17332, + 'framesequence': 66899, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 25.77179527282715, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.71591043, 2.90290689, -0.64674687]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2328033447265625, + 'left_pupil_posn': array([ 0.21860349, -0.76931393]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99606323, -0.08218384, -0.03295898]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.21428243815898895, + 'timestamp': 566.8621066771448, + 'timestamp_carla': 566863, + 'timestamp_device': 3720297, + 'timestamp_stream': 566.8621066771448, + 'transform': [array([ 2.12883520e+00, 1.50213289e+01, -2.85671232e-03]), + array([-0.0610414 , -7.69917488, 0.0302536 ])]} +{'AngularVelocity': array([-4.59735058e-02, 8.29702010e-04, 6.02030277e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.720503807067871, + 'FR_Wheel_Angle': -13.786131858825684, + 'Location': array([ -0.45331839, -27.46479416, 0.16987099]), + 'Rotation': array([-5.92928678e-02, -5.84849243e+01, 5.18502854e-02]), + 'Velocity': array([-4.02855098e-01, 9.48448539e-01, 3.90386587e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.83404493e+00, 1.33646135e+01, 3.70018277e-03]), + 'camera_rotation': array([ -5.85547972, -18.16801262, -0.84778857]), + 'current_gear_input': False, + 'focus_actor_dist': 1125.786376953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -567.13299561, -2449.40112305, 17.354599 ]), + 'frame': 17333, + 'frame_number': 17333, + 'framesequence': 66903, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 43.86054992675781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66995263, 2.9045732 , -0.66729736]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.320892333984375, + 'left_pupil_posn': array([ 0.22490084, -0.76249087]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99813843, -0.06039429, -0.00817871]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.20236514508724213, + 'timestamp': 566.8957321792841, + 'timestamp_carla': 566897, + 'timestamp_device': 3720331, + 'timestamp_stream': 566.8957321792841, + 'transform': [array([ 2.12830806e+00, 1.50020332e+01, -3.12852859e-03]), + array([-0.06098676, -7.69656992, 0.03079778])]} +{'AngularVelocity': array([0.03416128, 0.01193139, 6.04859591]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.569835662841797, + 'FR_Wheel_Angle': -14.390835762023926, + 'Location': array([ -0.55801475, -27.24036598, 0.16998188]), + 'Rotation': array([-5.78312092e-02, -5.72485466e+01, 5.25010601e-02]), + 'Velocity': array([-4.85913426e-01, 1.10316658e+00, 9.64512816e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.78682184, 13.44818878, 0.04274351]), + 'camera_rotation': array([ -5.61315823, -17.69570351, -0.8206991 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1151.17236328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -562.08569336, -2479.30957031, 17.34753418]), + 'frame': 17334, + 'frame_number': 17334, + 'framesequence': 66906, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 21.70328712463379, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.75786901, 2.91526794, -0.64155734]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2455291748046875, + 'left_pupil_posn': array([ 0.19885063, -0.77431643]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99354553, -0.11026001, -0.02636719]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.19839780032634735, + 'timestamp': 566.9271410778165, + 'timestamp_carla': 566928, + 'timestamp_device': 3720356, + 'timestamp_stream': 566.9271410778165, + 'transform': [array([ 2.12980580e+00, 1.49826021e+01, -3.15814954e-03]), + array([-0.06100725, -7.69797611, 0.03089727])]} +{'AngularVelocity': array([-0.07572737, -0.01343018, 4.94404221]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.947521209716797, + 'FR_Wheel_Angle': -14.645296096801758, + 'Location': array([ -0.67003304, -27.01091194, 0.1699968 ]), + 'Rotation': array([-4.20261510e-02, -5.59066315e+01, 6.16236255e-02]), + 'Velocity': array([-3.94791663e-01, 8.53168309e-01, 3.90653615e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.74337101, 13.55207157, 0.08813515]), + 'camera_rotation': array([ -5.34682894, -17.18764687, -0.70804763]), + 'current_gear_input': False, + 'focus_actor_dist': 1201.454345703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -566.19262695, -2532.57617188, 17.34828186]), + 'frame': 17335, + 'frame_number': 17335, + 'framesequence': 66910, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 19.45366096496582, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73286605, 2.92196226, -0.64672244]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.201629638671875, + 'left_pupil_posn': array([ 0.19384563, -0.77741849]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9931488 , -0.10926819, -0.04138184]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00021973327966406941, + 'throttle_input': 0.17856107652187347, + 'timestamp': 566.9602844789624, + 'timestamp_carla': 566962, + 'timestamp_device': 3720389, + 'timestamp_stream': 566.9602844789624, + 'transform': [array([ 2.13125110e+00, 1.49609776e+01, -3.04418546e-03]), + array([-0.06103457, -7.69911003, 0.03068089])]} +{'AngularVelocity': array([ 1.15787331e-03, -5.30751329e-03, 3.44109178e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.092376708984375, + 'FR_Wheel_Angle': -14.726213455200195, + 'Location': array([ -0.75231487, -26.84982681, 0.17003925]), + 'Rotation': array([-3.50661911e-02, -5.49414253e+01, 6.36829138e-02]), + 'Velocity': array([-2.81072527e-01, 5.83000779e-01, 3.76033771e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.70547485, 13.67126656, 0.13302323]), + 'camera_rotation': array([ -5.07412004, -16.70681763, -0.66116911]), + 'current_gear_input': False, + 'focus_actor_dist': 1122.0042724609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -535.60345459, -2461.36889648, 30.2975235 ]), + 'frame': 17336, + 'frame_number': 17336, + 'framesequence': 66914, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 19.908658981323242, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.6993134 , 2.92508388, -0.66179812]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3429718017578125, + 'left_pupil_posn': array([ 0.18919468, -0.77758753]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99281311, -0.11462402, -0.03405762]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17062638700008392, + 'timestamp': 566.9941482767463, + 'timestamp_carla': 566995, + 'timestamp_device': 3720422, + 'timestamp_stream': 566.9941482767463, + 'transform': [array([ 2.13228464e+00, 1.49377327e+01, -2.88314815e-03]), + array([-0.06107555, -7.69929457, 0.03036366])]} +{'AngularVelocity': array([ 1.87063105e-02, -1.46814913e-03, 2.33859420e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.92508316040039, + 'FR_Wheel_Angle': -14.598155975341797, + 'Location': array([ -0.81015015, -26.74051857, 0.17012329]), + 'Rotation': array([-3.71767171e-02, -5.42809982e+01, 6.15053177e-02]), + 'Velocity': array([-1.98149785e-01, 3.97273928e-01, 2.50081997e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.67521477, 13.78359127, 0.17199287]), + 'camera_rotation': array([ -4.91222382, -16.28649712, -0.54575646]), + 'current_gear_input': False, + 'focus_actor_dist': 1330.409912109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -578.1270752 , -2667.45727539, 17.35173798]), + 'frame': 17337, + 'frame_number': 17337, + 'framesequence': 66919, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 21.079145431518555, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65337849, 2.93180871, -0.67101902]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3218536376953125, + 'left_pupil_posn': array([ 0.19189525, -0.77561021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9947052 , -0.09269714, -0.04405212]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0008056886726990342, + 'throttle_input': 0.16665904223918915, + 'timestamp': 567.0276934765279, + 'timestamp_carla': 567029, + 'timestamp_device': 3720464, + 'timestamp_stream': 567.0276934765279, + 'transform': [array([ 2.13341331e+00, 1.49136524e+01, -2.62336736e-03]), + array([-0.06119849, -7.69962835, 0.02986455])]} +{'AngularVelocity': array([1.68778542e-02, 3.44442145e-04, 1.59611964e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.97589874267578, + 'FR_Wheel_Angle': -14.634588241577148, + 'Location': array([ -0.85088491, -26.66546822, 0.17018627]), + 'Rotation': array([-4.05918136e-02, -5.38273048e+01, 5.87758832e-02]), + 'Velocity': array([-1.37577116e-01, 2.70561755e-01, 2.54483224e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.66344357, 13.89910889, 0.17957872]), + 'camera_rotation': array([ -4.78340673, -15.76268101, -0.39114419]), + 'current_gear_input': False, + 'focus_actor_dist': 1374.7596435546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -579.25750732, -2715.38330078, 17.34983826]), + 'frame': 17338, + 'frame_number': 17338, + 'framesequence': 66923, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.48632049560547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66904187, 2.93882442, -0.66758275]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.46453857421875, + 'left_pupil_posn': array([ 0.17807591, -0.7775867 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99234009, -0.11579895, -0.04292297]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0023621327709406614, + 'throttle_input': 0.1269855797290802, + 'timestamp': 567.061221178621, + 'timestamp_carla': 567062, + 'timestamp_device': 3720497, + 'timestamp_stream': 567.061221178621, + 'transform': [array([ 2.13493013e+00, 1.48887939e+01, -2.20249174e-03]), + array([-0.06143072, -7.70069456, 0.02905217])]} +{'AngularVelocity': array([0.03302927, 0.02370379, 1.565611 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.034257888793945, + 'FR_Wheel_Angle': -14.69310188293457, + 'Location': array([ -0.88096648, -26.61160088, 0.17022026]), + 'Rotation': array([-4.25725654e-02, -5.34751053e+01, 5.74512258e-02]), + 'Velocity': array([-8.75101462e-02, 1.58284426e-01, -6.34098033e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.6302433 , 14.02638149, 0.19480318]), + 'camera_rotation': array([ -4.60739279, -15.19843674, -0.39926213]), + 'current_gear_input': False, + 'focus_actor_dist': 1411.8270263671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -575.54846191, -2756.94189453, 17.34577179]), + 'frame': 17339, + 'frame_number': 17339, + 'framesequence': 66926, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 12.30068588256836, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.57863164, 2.94216776, -0.70173955]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2133636474609375, + 'left_pupil_posn': array([ 0.16266346, -0.79101872]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98646545, -0.14710999, -0.07223511]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.004632710013538599, + 'throttle_input': 0.09919890016317368, + 'timestamp': 567.0939012765884, + 'timestamp_carla': 567095, + 'timestamp_device': 3720522, + 'timestamp_stream': 567.0939012765884, + 'transform': [array([ 2.13691735e+00, 1.48639946e+01, -1.63532258e-03]), + array([-0.0617654 , -7.7027669 , 0.02796552])]} +{'AngularVelocity': array([0.03532136, 0.02563627, 1.20323467]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.476106643676758, + 'FR_Wheel_Angle': -15.042234420776367, + 'Location': array([ -0.89530158, -26.58659554, 0.1702425 ]), + 'Rotation': array([-4.51953597e-02, -5.33019142e+01, 5.55549823e-02]), + 'Velocity': array([-0.0554648 , 0.0975768 , -0.00025715]), + 'brake_input': 0.0, + 'camera_location': array([-4.60823059, 14.15520096, 0.19874649]), + 'camera_rotation': array([ -4.56714249, -14.73521709, -0.48834831]), + 'current_gear_input': False, + 'focus_actor_dist': 1465.857421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -573.9588623 , -2815.44433594, 17.34378815]), + 'frame': 17340, + 'frame_number': 17340, + 'framesequence': 66931, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.437000274658203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.58239603, 2.94339299, -0.69923252]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3802337646484375, + 'left_pupil_posn': array([ 0.1696291 , -0.77383864]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99147034, -0.12559509, -0.03462219]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.008020265027880669, + 'throttle_input': 0.08332952111959457, + 'timestamp': 567.1280722767115, + 'timestamp_carla': 567129, + 'timestamp_device': 3720564, + 'timestamp_stream': 567.1280722767115, + 'transform': [array([ 2.13978529e+00, 1.48377218e+01, -9.30232985e-04]), + array([-0.06221619, -7.70659018, 0.02658291])]} +{'AngularVelocity': array([-0.03074941, 0.04203967, 0.08722018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.68483543395996, + 'FR_Wheel_Angle': -15.16001033782959, + 'Location': array([ -0.90504408, -26.56929207, 0.17027237]), + 'Rotation': array([-4.76610586e-02, -5.31803665e+01, 5.41288666e-02]), + 'Velocity': array([-0.03783691, 0.06153503, 0.00030564]), + 'brake_input': 0.0, + 'camera_location': array([-4.58325863, 14.29245758, 0.22509427]), + 'camera_rotation': array([ -4.49795914, -14.22418404, -0.52619267]), + 'current_gear_input': False, + 'focus_actor_dist': 1478.5377197265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -565.00238037, -2832.92724609, 17.33448029]), + 'frame': 17341, + 'frame_number': 17341, + 'framesequence': 66934, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 133.13888549804688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.71089506, 2.83901691, -0.64899755]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5101165771484375, + 'left_pupil_posn': array([ 0.29732609, -0.76435506]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99992371, -0.0087738 , -0.00823975]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.012817774899303913, + 'throttle_input': 0.07142747938632965, + 'timestamp': 567.1609184779227, + 'timestamp_carla': 567162, + 'timestamp_device': 3720589, + 'timestamp_stream': 567.1609184779227, + 'transform': [array([ 2.14608407e+00, 1.48115206e+01, -3.58142832e-04]), + array([-0.06272846, -7.71735764, 0.02548548])]} +{'AngularVelocity': array([0.28009209, 0.01567755, 3.1713891 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.76774787902832, + 'FR_Wheel_Angle': -15.290748596191406, + 'Location': array([ -0.91859692, -26.54537773, 0.17035267]), + 'Rotation': array([-6.01807944e-02, -5.30143623e+01, 4.64991145e-02]), + 'Velocity': array([-1.89291641e-01, 3.64939123e-01, 1.81102751e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.58003426, 14.42163467, 0.22482839]), + 'camera_rotation': array([ -4.57442999, -13.56535244, -0.27623767]), + 'current_gear_input': False, + 'focus_actor_dist': 1495.2176513671875, + 'focus_actor_name': 'Plane35', + 'focus_actor_pt': array([ -555.48120117, -2854.70458984, 17.79415894]), + 'frame': 17342, + 'frame_number': 17342, + 'framesequence': 66938, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.494357109069824, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7037127 , 2.76575327, -0.65009773]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.47613525390625, + 'left_pupil_posn': array([ 0.43479824, -0.75626802]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98210144, 0.18527222, 0.03363037]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.01748710684478283, + 'throttle_input': 0.05555810034275055, + 'timestamp': 567.1933571770787, + 'timestamp_carla': 567195, + 'timestamp_device': 3720622, + 'timestamp_stream': 567.1933571770787, + 'transform': [array([2.15116787e+00, 1.47856951e+01, 2.73284910e-04]), + array([-0.06327487, -7.72590065, 0.0242725 ])]} +{'AngularVelocity': array([-0.09752934, -0.01379348, 5.23823404]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.123945236206055, + 'FR_Wheel_Angle': -15.500656127929688, + 'Location': array([ -0.99779457, -26.40636253, 0.1705011 ]), + 'Rotation': array([-6.90941885e-02, -5.20782013e+01, 4.34464924e-02]), + 'Velocity': array([-3.49524945e-01, 6.57953143e-01, 1.96857451e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.58854198, 14.57180023, 0.21378607]), + 'camera_rotation': array([ -4.70137596, -12.87970448, -0.2308607 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1475.74462890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -534.91992188, -2841.43798828, 17.30351257]), + 'frame': 17343, + 'frame_number': 17343, + 'framesequence': 66942, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 29.82444190979004, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.76305103, 2.78522062, -0.61526644]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5199432373046875, + 'left_pupil_posn': array([ 0.38492513, -0.76632571]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99482727, 0.09791565, -0.02690125]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.021900083869695663, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.2274982780218, + 'timestamp_carla': 567229, + 'timestamp_device': 3720656, + 'timestamp_stream': 567.2274982780218, + 'transform': [array([2.15565515e+00, 1.47587414e+01, 9.91973910e-04]), + array([-0.06384178, -7.73337555, 0.0228603 ])]} +{'AngularVelocity': array([4.65715528e-02, 2.20672786e-03, 6.42117834e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.10590934753418, + 'FR_Wheel_Angle': -15.447967529296875, + 'Location': array([ -1.09620059, -26.23943329, 0.17057155]), + 'Rotation': array([-6.50029033e-02, -5.09707184e+01, 4.60283235e-02]), + 'Velocity': array([-4.76701587e-01, 8.52418363e-01, 3.99932847e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.60526943, 14.72430992, 0.23954694]), + 'camera_rotation': array([ -4.53217173, -12.14505386, -0.28354028]), + 'current_gear_input': False, + 'focus_actor_dist': 1435.33984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -510.16348267, -2807.39697266, 17.27826691]), + 'frame': 17344, + 'frame_number': 17344, + 'framesequence': 66947, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 41.74840545654297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69038248, 2.79336548, -0.64293218]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.544464111328125, + 'left_pupil_posn': array([ 0.36452854, -0.7585547 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99743652, 0.07072449, -0.01004028]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0262215044349432, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.2609618790448, + 'timestamp_carla': 567262, + 'timestamp_device': 3720697, + 'timestamp_stream': 567.2609618790448, + 'transform': [array([2.16431785e+00, 1.47315941e+01, 1.59526826e-03]), + array([-0.06422427, -7.74924517, 0.02169298])]} +{'AngularVelocity': array([0.07094717, 0.01602976, 6.68779469]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.035268783569336, + 'FR_Wheel_Angle': -15.399606704711914, + 'Location': array([ -1.22948241, -26.02438164, 0.17071655]), + 'Rotation': array([-6.33295104e-02, -4.95516357e+01, 4.79749851e-02]), + 'Velocity': array([-6.09539449e-01, 1.02723551e+00, 8.18400353e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.61222744, 14.83312416, 0.26496696]), + 'camera_rotation': array([ -4.32801723, -11.48599339, -0.12918873]), + 'current_gear_input': False, + 'focus_actor_dist': 1482.1859130859375, + 'focus_actor_name': 'Plane35', + 'focus_actor_pt': array([ -500.14239502, -2859.58105469, 17.79416656]), + 'frame': 17345, + 'frame_number': 17345, + 'framesequence': 66950, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 28.593294143676758, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.75017118, 2.8049531 , -0.61509252]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.46356201171875, + 'left_pupil_posn': array([ 0.36473262, -0.7712369 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99478149, 0.0880127 , -0.05131531]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.02999359369277954, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.2938115783036, + 'timestamp_carla': 567295, + 'timestamp_device': 3720722, + 'timestamp_stream': 567.2938115783036, + 'transform': [array([2.17891002e+00, 1.47038603e+01, 1.97509769e-03]), + array([-0.06453846, -7.77695131, 0.02097152])]} +{'AngularVelocity': array([-0.10757857, -0.0224257 , 5.77347279]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.112564086914062, + 'FR_Wheel_Angle': -14.47415828704834, + 'Location': array([ -1.38415408, -25.78971672, 0.17082199]), + 'Rotation': array([ -0.05361698, -47.98984528, 0.05557719]), + 'Velocity': array([-5.81967533e-01, 9.10262227e-01, 6.36959041e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.64064312, 14.9350872 , 0.28749239]), + 'camera_rotation': array([ -4.16572523, -10.8930769 , -0.18570215]), + 'current_gear_input': False, + 'focus_actor_dist': 1559.12939453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -495.98782349, -2941.04296875, 17.26289368]), + 'frame': 17346, + 'frame_number': 17346, + 'framesequence': 66954, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 40.076995849609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.6140871 , 2.81065226, -0.67142791]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5017852783203125, + 'left_pupil_posn': array([ 0.34804332, -0.76778018]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99725342, 0.06739807, -0.03051758]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.033564258366823196, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.325632378459, + 'timestamp_carla': 567327, + 'timestamp_device': 3720756, + 'timestamp_stream': 567.325632378459, + 'transform': [array([2.19252658e+00, 1.46773462e+01, 2.52702716e-03]), + array([-0.06485264, -7.80291462, 0.01992363])]} +{'AngularVelocity': array([-0.00550095, -0.01635966, 3.45317602]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.64742660522461, + 'FR_Wheel_Angle': -12.57083797454834, + 'Location': array([ -1.50629115, -25.61854362, 0.17087384]), + 'Rotation': array([-4.15958501e-02, -4.69431610e+01, 6.07337132e-02]), + 'Velocity': array([-4.29124713e-01, 6.12858474e-01, 5.81436150e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.69164658, 15.02501678, 0.31185725]), + 'camera_rotation': array([ -4.07609272, -10.46523952, -0.28317967]), + 'current_gear_input': False, + 'focus_actor_dist': 1619.9910888671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -489.87011719, -3006.27734375, 17.25621033]), + 'frame': 17347, + 'frame_number': 17347, + 'framesequence': 66958, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 31.805877685546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.61541319, 2.81630278, -0.67172092]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5381317138671875, + 'left_pupil_posn': array([ 0.3505218 , -0.77401423]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99560547, 0.08354187, -0.04217529]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03740959241986275, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.3597508780658, + 'timestamp_carla': 567361, + 'timestamp_device': 3720789, + 'timestamp_stream': 567.3597508780658, + 'transform': [array([2.20602083e+00, 1.46494627e+01, 3.18614952e-03]), + array([-0.06511902, -7.82873583, 0.01862657])]} +{'AngularVelocity': array([ 0.02256197, -0.00621603, 1.85780621]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.214094161987305, + 'FR_Wheel_Angle': -9.681073188781738, + 'Location': array([ -1.59412301, -25.50440216, 0.17097659]), + 'Rotation': array([-4.22378890e-02, -4.63518944e+01, 5.80047518e-02]), + 'Velocity': array([-3.11680257e-01, 4.07102108e-01, 2.79188156e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.72549343, 15.08852482, 0.33416307]), + 'camera_rotation': array([ -4.01725769, -10.1995163 , -0.36549231]), + 'current_gear_input': False, + 'focus_actor_dist': 1655.5931396484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -483.65026855, -3045.65625 , 17.24957275]), + 'frame': 17348, + 'frame_number': 17348, + 'framesequence': 66962, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 129.36398315429688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.68885064, 2.84186888, -0.64438176]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5453948974609375, + 'left_pupil_posn': array([ 0.30520868, -0.7545743 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9997406 , 0.01974487, -0.01004028]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04127323627471924, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.392144177109, + 'timestamp_carla': 567393, + 'timestamp_device': 3720822, + 'timestamp_stream': 567.392144177109, + 'transform': [array([2.21941376e+00, 1.46232233e+01, 3.74584179e-03]), + array([-0.06535125, -7.85452414, 0.01755778])]} +{'AngularVelocity': array([ 0.02460349, -0.00533246, 1.07722437]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.344381332397461, + 'FR_Wheel_Angle': -8.577627182006836, + 'Location': array([ -1.65663493, -25.42826843, 0.17106602]), + 'Rotation': array([-4.54070941e-02, -4.60421219e+01, 5.33493347e-02]), + 'Velocity': array([-2.19943762e-01, 2.73862094e-01, 2.07414618e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.74917221, 15.14441586, 0.34375021]), + 'camera_rotation': array([ -3.89423203, -10.05325127, -0.5589211 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1679.617431640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -480.05438232, -3073.02734375, 17.24569702]), + 'frame': 17349, + 'frame_number': 17349, + 'framesequence': 66966, + 'gaze_dir': array([ 0.9842453 , -0.17438507, -0.01235199]), + 'gaze_origin': array([-3.87107468, 0.13945161, -0.63893664]), + 'gaze_valid': True, + 'gaze_vergence': 105.60271453857422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98860168, -0.1493988 , -0.01846313]), + 'left_gaze_origin': array([-3.65565968, 2.97660375, -0.65104985]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3993377685546875, + 'left_pupil_posn': array([ 0.11534929, -0.73990178]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97988892, -0.19937134, -0.00624084]), + 'right_gaze_origin': array([-4.08649015, -2.69770074, -0.62682343]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([-0.45392257, -0.92113459]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04460585117340088, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.4262312762439, + 'timestamp_carla': 567427, + 'timestamp_device': 3720856, + 'timestamp_stream': 567.4262312762439, + 'transform': [array([2.23417759e+00, 1.45959101e+01, 4.26599476e-03]), + array([-0.06554249, -7.88314104, 0.01653737])]} +{'AngularVelocity': array([ 0.03306837, -0.01854258, 0.70776755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.526594161987305, + 'FR_Wheel_Angle': -8.73111343383789, + 'Location': array([ -1.69596434, -25.38094521, 0.17111309]), + 'Rotation': array([ -0.04596034, -45.85506058, 0.05056688]), + 'Velocity': array([-0.11134411, 0.14452635, 0.00041337]), + 'brake_input': 0.0, + 'camera_location': array([-4.78385544, 15.15526199, 0.37891552]), + 'camera_rotation': array([ -3.76150107, -10.04721546, -0.46376997]), + 'current_gear_input': False, + 'focus_actor_dist': 979.5397338867188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -546.60852051, -2341.14257812, 55.25287628]), + 'frame': 17350, + 'frame_number': 17350, + 'framesequence': 66970, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 12.284432411193848, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66333508, 2.99716496, -0.65661472]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.331146240234375, + 'left_pupil_posn': array([ 0.0978446 , -0.75086606]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9783783 , -0.20655823, -0.0093689 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04830469936132431, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.4589576758444, + 'timestamp_carla': 567460, + 'timestamp_device': 3720889, + 'timestamp_stream': 567.4589576758444, + 'transform': [array([2.24912977e+00, 1.45698738e+01, 4.66844533e-03]), + array([-0.06569958, -7.91229296, 0.01577412])]} +{'AngularVelocity': array([ 0.03875384, -0.01351512, 0.51292807]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.53780746459961, + 'FR_Wheel_Angle': -8.738797187805176, + 'Location': array([ -1.71705472, -25.35554123, 0.17115825]), + 'Rotation': array([ -0.05027019, -45.75428009, 0.04870619]), + 'Velocity': array([-7.17157051e-02, 9.46330875e-02, 2.49195091e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.82936573, 15.12457657, 0.41030198]), + 'camera_rotation': array([ -3.59834838, -10.36428928, -0.28944662]), + 'current_gear_input': False, + 'focus_actor_dist': 1793.6663818359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -492.84405518, -3191.49462891, 17.25812531]), + 'frame': 17351, + 'frame_number': 17351, + 'framesequence': 66974, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 13.064095497131348, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66238284, 2.99636841, -0.65664679]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3827056884765625, + 'left_pupil_posn': array([ 0.10238576, -0.74991167]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98060608, -0.19572449, -0.00976562]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05227820947766304, + 'throttle_input': 0.043656062334775925, + 'timestamp': 567.4932301789522, + 'timestamp_carla': 567494, + 'timestamp_device': 3720922, + 'timestamp_stream': 567.4932301789522, + 'transform': [array([2.26556993e+00, 1.45428839e+01, 5.02332672e-03]), + array([-0.06584302, -7.94451857, 0.01507737])]} +{'AngularVelocity': array([0.06191775, 0.03759509, 0.46618018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.51917552947998, + 'FR_Wheel_Angle': -8.718881607055664, + 'Location': array([ -1.73260462, -25.3369236 , 0.17120606]), + 'Rotation': array([ -0.0559051 , -45.67964172, 0.0469684 ]), + 'Velocity': array([-0.11893966, 0.14494547, 0.00055063]), + 'brake_input': 0.0, + 'camera_location': array([-4.88321114, 15.05323982, 0.41643697]), + 'camera_rotation': array([ -3.58856082, -10.8562746 , -0.30234614]), + 'current_gear_input': False, + 'focus_actor_dist': 1875.2113037109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -515.31549072, -3273.15136719, 17.28074646]), + 'frame': 17352, + 'frame_number': 17352, + 'framesequence': 66978, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 13.103528022766113, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.66271853, 2.99521971, -0.65805209]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5133819580078125, + 'left_pupil_posn': array([ 0.10294199, -0.74923003]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98045349, -0.19665527, -0.0045166 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05634327605366707, + 'throttle_input': 0.03967345505952835, + 'timestamp': 567.5255195759237, + 'timestamp_carla': 567527, + 'timestamp_device': 3720956, + 'timestamp_stream': 567.5255195759237, + 'transform': [array([2.28189349e+00, 1.45175848e+01, 5.26409131e-03]), + array([-0.0659523 , -7.97667885, 0.01463929])]} +{'AngularVelocity': array([-0.02399198, -0.01500239, 0.70666832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.520200729370117, + 'FR_Wheel_Angle': -8.72414779663086, + 'Location': array([ -1.77040601, -25.29211807, 0.17124958]), + 'Rotation': array([ -0.05746921, -45.50114822, 0.04645336]), + 'Velocity': array([-1.40848920e-01, 1.72883481e-01, 6.47449488e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.91763306, 14.9791851 , 0.43730283]), + 'camera_rotation': array([ -3.50457668, -11.41842556, -0.3694934 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1880.085205078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -533.0435791 , -3277.81835938, 17.2989502 ]), + 'frame': 17353, + 'frame_number': 17353, + 'framesequence': 66983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 13.108918190002441, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.67616153, 2.99272156, -0.68013614]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4792022705078125, + 'left_pupil_posn': array([ 0.1042937 , -0.75223696]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.97932434, -0.19793701, 0.04167175]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06018860638141632, + 'throttle_input': 0.035706110298633575, + 'timestamp': 567.560913875699, + 'timestamp_carla': 567562, + 'timestamp_device': 3720997, + 'timestamp_stream': 567.560913875699, + 'transform': [array([2.30055428e+00, 1.44901867e+01, 5.50201396e-03]), + array([-0.06603426, -8.01360893, 0.01415334])]} +{'AngularVelocity': array([ 0.02789901, -0.0210026 , 0.54756331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.538559913635254, + 'FR_Wheel_Angle': -8.739697456359863, + 'Location': array([ -1.79783273, -25.25963593, 0.1712154 ]), + 'Rotation': array([ -0.05227827, -45.37205124, 0.04749468]), + 'Velocity': array([-0.07551375, 0.09856153, 0.00031523]), + 'brake_input': 0.0, + 'camera_location': array([-4.9445715 , 14.8827486 , 0.44717073]), + 'camera_rotation': array([ -3.33838463, -12.05742836, -0.40004286]), + 'current_gear_input': False, + 'focus_actor_dist': 1925.3358154296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -559.7208252 , -3321.7019043 , 17.32608795]), + 'frame': 17354, + 'frame_number': 17354, + 'framesequence': 66986, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 11.805468559265137, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65214229, 2.98380446, -0.66518712]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4470672607421875, + 'left_pupil_posn': array([ 0.10881591, -0.76334596]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.97833252, -0.20503235, -0.0282135 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06419873982667923, + 'throttle_input': 0.0, + 'timestamp': 567.592275775969, + 'timestamp_carla': 567593, + 'timestamp_device': 3721022, + 'timestamp_stream': 567.592275775969, + 'transform': [array([2.31837916e+00, 1.44647884e+01, 5.00946026e-03]), + array([-0.06625966, -8.04912281, 0.01516484])]} +{'AngularVelocity': array([ 0.03091681, -0.0120832 , 0.34176862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.546823501586914, + 'FR_Wheel_Angle': -8.740535736083984, + 'Location': array([ -1.81178188, -25.24311256, 0.17131664]), + 'Rotation': array([ -0.052852 , -45.30574417, 0.04729564]), + 'Velocity': array([-0.03939198, 0.05322859, 0.00020653]), + 'brake_input': 0.0, + 'camera_location': array([-4.99182796, 14.75978279, 0.45794174]), + 'camera_rotation': array([ -3.31659627, -12.75851727, -0.35441869]), + 'current_gear_input': False, + 'focus_actor_dist': 2013.7701416015625, + 'focus_actor_name': 'Plane33', + 'focus_actor_pt': array([ -597.64776611, -3407.53100586, 17.79415894]), + 'frame': 17355, + 'frame_number': 17355, + 'framesequence': 66990, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 17.886802673339844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.5605576 , 2.97193313, -0.7076813 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2819366455078125, + 'left_pupil_posn': array([ 0.13920116, -0.76245105]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98913574, -0.14659119, -0.01055908]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06778771430253983, + 'throttle_input': 0.0, + 'timestamp': 567.626646976918, + 'timestamp_carla': 567628, + 'timestamp_device': 3721056, + 'timestamp_stream': 567.626646976918, + 'transform': [array([2.33787131e+00, 1.44360142e+01, 4.24345024e-03]), + array([-0.06633479, -8.08819389, 0.01665584])]} +{'AngularVelocity': array([-0.00341813, -0.00586917, 0.43983755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.53493881225586, + 'FR_Wheel_Angle': -8.743577003479004, + 'Location': array([ -1.82765377, -25.2245121 , 0.17130896]), + 'Rotation': array([ -0.05734627, -45.23103714, 0.04608465]), + 'Velocity': array([-8.36675614e-02, 1.02323920e-01, 8.63361347e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.02777863, 14.59886456, 0.45007759]), + 'camera_rotation': array([ -3.36121106, -13.57427692, -0.46444163]), + 'current_gear_input': False, + 'focus_actor_dist': 1806.703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -584.42193604, -3202.03808594, 30.54934692]), + 'frame': 17356, + 'frame_number': 17356, + 'framesequence': 66994, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.667415618896484, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.55397201, 2.96343398, -0.71146703]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.53533935546875, + 'left_pupil_posn': array([ 0.14577758, -0.77667928]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98829651, -0.14743042, -0.03900146]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07207251340150833, + 'throttle_input': 0.0, + 'timestamp': 567.6598606780171, + 'timestamp_carla': 567661, + 'timestamp_device': 3721089, + 'timestamp_stream': 567.6598606780171, + 'transform': [array([2.35826778e+00, 1.44074888e+01, 3.72484210e-03]), + array([-0.06634162, -8.12920952, 0.01769058])]} +{'AngularVelocity': array([ 0.02743569, -0.00898352, -0.16642293]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.645359992980957, + 'FR_Wheel_Angle': -9.837526321411133, + 'Location': array([ -1.84625387, -25.20258331, 0.17132865]), + 'Rotation': array([ -0.05425902, -45.14240646, 0.04669615]), + 'Velocity': array([-0.05217977, 0.06798074, 0.00019023]), + 'brake_input': 0.0, + 'camera_location': array([-5.06092072, 14.42004108, 0.45738977]), + 'camera_rotation': array([ -3.37776732, -14.43019962, -0.63723516]), + 'current_gear_input': False, + 'focus_actor_dist': 1808.0172119140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -611.23974609, -3200.51904297, 29.13631439]), + 'frame': 17357, + 'frame_number': 17357, + 'framesequence': 66998, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.623640060424805, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.604599 , 2.95452595, -0.68995821]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.320098876953125, + 'left_pupil_posn': array([ 0.16602004, -0.77630508]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99253845, -0.11349487, -0.04426575]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07580798119306564, + 'throttle_input': 0.0, + 'timestamp': 567.6932340785861, + 'timestamp_carla': 567694, + 'timestamp_device': 3721122, + 'timestamp_stream': 567.6932340785861, + 'transform': [array([2.37976336e+00, 1.43784714e+01, 3.47351073e-03]), + array([-0.06632113, -8.17257595, 0.01819946])]} +{'AngularVelocity': array([ 0.05617719, 0.00424143, -0.24140385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.939080238342285, + 'FR_Wheel_Angle': -10.879837036132812, + 'Location': array([ -1.85184205, -25.19573212, 0.17131877]), + 'Rotation': array([ -0.05382872, -45.11411285, 0.04672385]), + 'Velocity': array([-0.02988146, 0.04163644, 0.00030866]), + 'brake_input': 0.0, + 'camera_location': array([-5.09423637, 14.23069763, 0.44453266]), + 'camera_rotation': array([ -3.46596575, -15.29707909, -0.76551807]), + 'current_gear_input': False, + 'focus_actor_dist': 2000.0, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -680.74725342, -3384.10644531, 17.45012665]), + 'frame': 17358, + 'frame_number': 17358, + 'framesequence': 67002, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 22.870393753051758, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.61582327, 2.94750381, -0.68889773]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.324981689453125, + 'left_pupil_posn': array([ 0.18028188, -0.77666581]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99513245, -0.09060669, -0.03869629]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07985474169254303, + 'throttle_input': 0.0, + 'timestamp': 567.7269377782941, + 'timestamp_carla': 567728, + 'timestamp_device': 3721156, + 'timestamp_stream': 567.7269377782941, + 'transform': [array([2.40250921e+00, 1.43489799e+01, 3.43915937e-03]), + array([-0.06630065, -8.21859837, 0.01827947])]} +{'AngularVelocity': array([ 0.06028776, 0.00111374, -0.28504983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.055452346801758, + 'FR_Wheel_Angle': -11.66428279876709, + 'Location': array([ -1.85437071, -25.19249153, 0.17133395]), + 'Rotation': array([ -0.05477811, -45.10129547, 0.04651134]), + 'Velocity': array([-2.07905620e-02, 3.08965314e-02, 6.35528559e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.12086964, 14.0205307 , 0.44072026]), + 'camera_rotation': array([ -3.50054693, -16.22015572, -0.89909673]), + 'current_gear_input': False, + 'focus_actor_dist': 1949.1383056640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -699.99938965, -3329.92114258, 17.47023773]), + 'frame': 17359, + 'frame_number': 17359, + 'framesequence': 67006, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 22.00950050354004, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72396851, 2.94071364, -0.65526432]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.264434814453125, + 'left_pupil_posn': array([ 0.1851083, -0.7811383]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99468994, -0.09487915, -0.039505 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.08434095978736877, + 'throttle_input': 0.0, + 'timestamp': 567.7603819780052, + 'timestamp_carla': 567761, + 'timestamp_device': 3721189, + 'timestamp_stream': 567.7603819780052, + 'transform': [array([2.42619467e+00, 1.43196421e+01, 3.56056215e-03]), + array([-0.06632113, -8.26666355, 0.01806083])]} +{'AngularVelocity': array([ 0.05603753, 0.00093806, -0.25478983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.133720397949219, + 'FR_Wheel_Angle': -11.697796821594238, + 'Location': array([ -1.85611355, -25.19016838, 0.17134838]), + 'Rotation': array([ -0.05569336, -45.09272003, 0.04623282]), + 'Velocity': array([-0.01884338, 0.02830003, 0.00066919]), + 'brake_input': 0.0, + 'camera_location': array([-5.14653301, 13.78708267, 0.41527334]), + 'camera_rotation': array([ -3.57043338, -17.23443985, -0.9999879 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1929.8785400390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -727.36987305, -3305.83886719, 17.49851227]), + 'frame': 17360, + 'frame_number': 17360, + 'framesequence': 67010, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.096317291259766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69149184, 2.92924047, -0.65210575]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3679046630859375, + 'left_pupil_posn': array([ 0.20512557, -0.78193569]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99559021, -0.06584167, -0.06672668]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.08972442150115967, + 'throttle_input': 0.0, + 'timestamp': 567.7943349778652, + 'timestamp_carla': 567795, + 'timestamp_device': 3721222, + 'timestamp_stream': 567.7943349778652, + 'transform': [array([2.45138216e+00, 1.42898483e+01, 3.76464846e-03]), + array([-0.06639627, -8.31793404, 0.01767237])]} +{'AngularVelocity': array([-0.0478672 , 0.02944754, 0.85840899]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.959720611572266, + 'FR_Wheel_Angle': -12.460981369018555, + 'Location': array([ -1.87211454, -25.17048073, 0.17141834]), + 'Rotation': array([-6.65601864e-02, -4.49690781e+01, 4.19711918e-02]), + 'Velocity': array([-0.15186317, 0.19025318, 0.00076828]), + 'brake_input': 0.0, + 'camera_location': array([-5.17870903, 13.55616951, 0.3863267 ]), + 'camera_rotation': array([ -3.75947928, -18.24431419, -1.22240484]), + 'current_gear_input': False, + 'focus_actor_dist': 1891.562255859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -751.89111328, -3262.12792969, 17.52399445]), + 'frame': 17361, + 'frame_number': 17361, + 'framesequence': 67014, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 23.723989486694336, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.58898783, 2.92346358, -0.69059145]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4149017333984375, + 'left_pupil_posn': array([ 0.19915211, -0.77008092]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99543762, -0.08821106, -0.03623962]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09463179856538773, + 'throttle_input': 0.0, + 'timestamp': 567.8269455768168, + 'timestamp_carla': 567828, + 'timestamp_device': 3721256, + 'timestamp_stream': 567.8269455768168, + 'transform': [array([2.47668862e+00, 1.42612705e+01, 4.00917046e-03]), + array([-0.06646457, -8.36956215, 0.01722654])]} +{'AngularVelocity': array([-0.00991288, -0.04263537, 2.46914196]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.943974494934082, + 'FR_Wheel_Angle': -13.143152236938477, + 'Location': array([ -1.92825449, -25.10062981, 0.1714938 ]), + 'Rotation': array([-6.80218488e-02, -4.45318298e+01, 4.04918119e-02]), + 'Velocity': array([-2.78192103e-01, 3.75264376e-01, -6.30092618e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.21585226, 13.3065033 , 0.36995167]), + 'camera_rotation': array([ -3.92563057, -19.30171394, -1.45113564]), + 'current_gear_input': False, + 'focus_actor_dist': 1026.9005126953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -539.6605835 , -2427.5925293 , 67.57942963]), + 'frame': 17362, + 'frame_number': 17362, + 'framesequence': 67019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 14.222968101501465, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69896102, 2.96148229, -0.68386847]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3673553466796875, + 'left_pupil_posn': array([ 0.15763485, -0.81035614]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98976135, -0.12658691, -0.06591797]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09979553520679474, + 'throttle_input': 0.0, + 'timestamp': 567.8639382794499, + 'timestamp_carla': 567865, + 'timestamp_device': 3721297, + 'timestamp_stream': 567.8639382794499, + 'transform': [array([2.50583863e+00, 1.42290821e+01, 4.25653439e-03]), + array([-0.06651238, -8.42922783, 0.01670058])]} +{'AngularVelocity': array([-0.01763003, -0.04460498, 3.01586914]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.303360939025879, + 'FR_Wheel_Angle': -13.413076400756836, + 'Location': array([ -2.00406241, -25.00692749, 0.17153603]), + 'Rotation': array([-6.31382689e-02, -4.39601555e+01, 4.24427576e-02]), + 'Velocity': array([-3.23147357e-01, 4.29758400e-01, -1.52568813e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.25599909, 13.05051994, 0.36722577]), + 'camera_rotation': array([ -3.97019076, -20.39057159, -1.66593742]), + 'current_gear_input': False, + 'focus_actor_dist': 968.6156005859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -541.21313477, -2368.54345703, 68.56932068]), + 'frame': 17363, + 'frame_number': 17363, + 'framesequence': 67023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 13.983689308166504, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65233469, 2.94444752, -0.69056553]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.539459228515625, + 'left_pupil_posn': array([ 0.16369414, -0.79987729]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98788452, -0.1439209 , -0.05789185]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10627766698598862, + 'throttle_input': 0.0, + 'timestamp': 567.8956022784114, + 'timestamp_carla': 567897, + 'timestamp_device': 3721331, + 'timestamp_stream': 567.8956022784114, + 'transform': [array([2.53272319e+00, 1.42014656e+01, 4.49705124e-03]), + array([-0.066608 , -8.48433971, 0.01629458])]} +{'AngularVelocity': array([0.06459431, 0.01374668, 2.58218503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.479986190795898, + 'FR_Wheel_Angle': -13.499319076538086, + 'Location': array([ -2.07567739, -24.91961098, 0.17159282]), + 'Rotation': array([ -0.05865766, -43.40948868, 0.04455823]), + 'Velocity': array([-0.32781962, 0.41869029, 0.00043029]), + 'brake_input': 0.0, + 'camera_location': array([-5.2884264 , 12.79295349, 0.33920869]), + 'camera_rotation': array([ -4.09133768, -21.43259239, -1.90348566]), + 'current_gear_input': False, + 'focus_actor_dist': 936.0501708984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -549.44586182, -2334.34838867, 70.06343079]), + 'frame': 17364, + 'frame_number': 17364, + 'framesequence': 67023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 17.218257904052734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.71267724, 2.94417596, -0.67644811]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5041961669921875, + 'left_pupil_posn': array([ 0.17149615, -0.79992533]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99108887, -0.12561035, -0.04399109]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1123020127415657, + 'throttle_input': 0.0, + 'timestamp': 567.9281109757721, + 'timestamp_carla': 567929, + 'timestamp_device': 3721331, + 'timestamp_stream': 567.9281109757721, + 'transform': [array([2.56109858e+00, 1.41732540e+01, 4.70388401e-03]), + array([-0.06671046, -8.5426712 , 0.01592438])]} +{'AngularVelocity': array([-0.03005645, -0.01551372, 2.1608119 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.52100658416748, + 'FR_Wheel_Angle': -13.5652437210083, + 'Location': array([ -2.15083718, -24.8302002 , 0.17166625]), + 'Rotation': array([ -0.05548162, -42.84242249, 0.04606236]), + 'Velocity': array([-2.75761247e-01, 3.44609529e-01, 8.54301397e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.34038448, 12.54839325, 0.30120394]), + 'camera_rotation': array([ -4.30091524, -22.33862495, -2.06314397]), + 'current_gear_input': False, + 'focus_actor_dist': 930.8611450195312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -564.83911133, -2325.67675781, 68.44469452]), + 'frame': 17365, + 'frame_number': 17365, + 'framesequence': 67024, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 17.218257904052734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.71267724, 2.94417596, -0.67644811]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5041961669921875, + 'left_pupil_posn': array([ 0.17149615, -0.79992533]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99108887, -0.12561035, -0.04399109]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11850947886705399, + 'throttle_input': 0.035706110298633575, + 'timestamp': 567.9615684784949, + 'timestamp_carla': 567963, + 'timestamp_device': 3721339, + 'timestamp_stream': 567.9615684784949, + 'transform': [array([2.58845019e+00, 1.41453829e+01, 5.24618151e-03]), + array([-0.066608 , -8.59915447, 0.0148799 ])]} +{'AngularVelocity': array([ 0.00212977, -0.00166438, 1.45428848]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.029495239257812, + 'FR_Wheel_Angle': -14.036371231079102, + 'Location': array([ -2.21250415, -24.75792694, 0.17171989]), + 'Rotation': array([ -0.05197091, -42.37318802, 0.04679129]), + 'Velocity': array([-0.1810289 , 0.22448751, 0.00066061]), + 'brake_input': 0.0, + 'camera_location': array([-5.38965464, 12.342659 , 0.27225658]), + 'camera_rotation': array([ -4.44524384, -23.05444527, -2.27655697]), + 'current_gear_input': False, + 'focus_actor_dist': 930.9374389648438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -579.76159668, -2322.33203125, 65.01797485]), + 'frame': 17366, + 'frame_number': 17366, + 'framesequence': 67035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 20.702165603637695, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69245005, 2.91651177, -0.68327183]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5218658447265625, + 'left_pupil_posn': array([ 0.2024039 , -0.79902315]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99409485, -0.10075378, -0.04016113]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12440565973520279, + 'throttle_input': 0.0634927898645401, + 'timestamp': 567.9963642768562, + 'timestamp_carla': 567997, + 'timestamp_device': 3721431, + 'timestamp_stream': 567.9963642768562, + 'transform': [array([2.61894155e+00, 1.41170702e+01, 5.86141553e-03]), + array([-0.06649189, -8.66204834, 0.0136739 ])]} +{'AngularVelocity': array([0.00735305, 0.00261108, 1.04854095]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.87994384765625, + 'FR_Wheel_Angle': -14.598955154418945, + 'Location': array([ -2.24853086, -24.7157383 , 0.1717591 ]), + 'Rotation': array([ -0.05303642, -42.08498001, 0.04586918]), + 'Velocity': array([-0.1231057 , 0.15356632, 0.00031934]), + 'brake_input': 0.0, + 'camera_location': array([-5.43332577, 12.15551949, 0.27492437]), + 'camera_rotation': array([ -4.38905191, -23.55642891, -2.5654676 ]), + 'current_gear_input': False, + 'focus_actor_dist': 932.7395629882812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -592.32519531, -2321.54174805, 62.50839996]), + 'frame': 17367, + 'frame_number': 17367, + 'framesequence': 67039, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 17.99051856994629, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73402882, 2.90888381, -0.65083319]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4751739501953125, + 'left_pupil_posn': array([ 0.21632004, -0.79161024]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99504089, -0.08067322, -0.05805969]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1306680589914322, + 'throttle_input': 0.10316624492406845, + 'timestamp': 568.0295391790569, + 'timestamp_carla': 568031, + 'timestamp_device': 3721464, + 'timestamp_stream': 568.0295391790569, + 'transform': [array([2.64826465e+00, 1.40907660e+01, 6.32726634e-03]), + array([-0.06641676, -8.7226553 , 0.01279273])]} +{'AngularVelocity': array([0.0063423, 0.0029845, 0.7128436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.988513946533203, + 'FR_Wheel_Angle': -14.499420166015625, + 'Location': array([ -2.27310467, -24.68699646, 0.17179066]), + 'Rotation': array([ -0.05462785, -41.88304901, 0.04510668]), + 'Velocity': array([-0.08440457, 0.10451313, 0.00012137]), + 'brake_input': 0.0, + 'camera_location': array([-5.47328424, 12.00211525, 0.26939526]), + 'camera_rotation': array([ -4.37649822, -23.99742699, -2.8090229 ]), + 'current_gear_input': False, + 'focus_actor_dist': 933.9590454101562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -601.60699463, -2321.54174805, 63.32013702]), + 'frame': 17368, + 'frame_number': 17368, + 'framesequence': 67043, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.087528228759766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.82267308, 2.90891743, -0.61614841]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.444549560546875, + 'left_pupil_posn': array([ 0.22098744, -0.78922033]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99569702, -0.07154846, -0.05874634]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13773614168167114, + 'throttle_input': 0.13492026925086975, + 'timestamp': 568.0631083771586, + 'timestamp_carla': 568064, + 'timestamp_device': 3721497, + 'timestamp_stream': 568.0631083771586, + 'transform': [array([2.67900229e+00, 1.40645113e+01, 6.58821082e-03]), + array([-0.06641676, -8.78625584, 0.01229987])]} +{'AngularVelocity': array([0.00567037, 0.00116426, 0.42705598]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.823546409606934, + 'FR_Wheel_Angle': -12.846141815185547, + 'Location': array([ -2.29013443, -24.66756821, 0.17181426]), + 'Rotation': array([ -0.05587777, -41.75444412, 0.0445962 ]), + 'Velocity': array([-5.91147467e-02, 6.99973553e-02, -7.20335447e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.52001524, 11.87725639, 0.25334513]), + 'camera_rotation': array([ -4.44203377, -24.27552414, -3.01619172]), + 'current_gear_input': False, + 'focus_actor_dist': 935.0997924804688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -609.84460449, -2321.54150391, 63.42733765]), + 'frame': 17369, + 'frame_number': 17369, + 'framesequence': 67047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.676654815673828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.75453973, 2.90361643, -0.64398658]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4727020263671875, + 'left_pupil_posn': array([ 0.21718669, -0.79585993]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99372864, -0.09036255, -0.06568909]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14372387528419495, + 'throttle_input': 0.1428549587726593, + 'timestamp': 568.0965267792344, + 'timestamp_carla': 568098, + 'timestamp_device': 3721531, + 'timestamp_stream': 568.0965267792344, + 'transform': [array([2.71026373e+00, 1.40386724e+01, 6.66271197e-03]), + array([-0.06643724, -8.8510685 , 0.01217259])]} +{'AngularVelocity': array([0.00416489, 0.00056008, 0.27397335]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.87997055053711, + 'FR_Wheel_Angle': -12.165802001953125, + 'Location': array([ -2.30170417, -24.65471649, 0.1718393 ]), + 'Rotation': array([ -0.05679302, -41.67680359, 0.0439124 ]), + 'Velocity': array([-0.04094618, 0.04750864, 0.00020455]), + 'brake_input': 0.0, + 'camera_location': array([-5.56195593, 11.78293514, 0.24084751]), + 'camera_rotation': array([ -4.57343292, -24.36395073, -3.1459825 ]), + 'current_gear_input': False, + 'focus_actor_dist': 935.3502807617188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -615.27209473, -2321.54150391, 62.32348633]), + 'frame': 17370, + 'frame_number': 17370, + 'framesequence': 67051, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 17.893070220947266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72253275, 2.90009618, -0.65546113]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4960784912109375, + 'left_pupil_posn': array([ 0.22401309, -0.79283845]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99520874, -0.07846069, -0.05827332]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15126805007457733, + 'throttle_input': 0.14682230353355408, + 'timestamp': 568.1288310773671, + 'timestamp_carla': 568130, + 'timestamp_device': 3721564, + 'timestamp_stream': 568.1288310773671, + 'transform': [array([2.74065661e+00, 1.40138836e+01, 6.58105826e-03]), + array([-0.06645773, -8.9142704 , 0.01236313])]} +{'AngularVelocity': array([ 0.04135447, -0.02803389, 0.31676134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.68783187866211, + 'FR_Wheel_Angle': -11.047203063964844, + 'Location': array([ -2.30811286, -24.64765549, 0.17180805]), + 'Rotation': array([ -0.05627393, -41.63414001, 0.04371151]), + 'Velocity': array([-0.01185059, 0.02160845, -0.00048135]), + 'brake_input': 0.0, + 'camera_location': array([-5.60671139, 11.71145058, 0.22785269]), + 'camera_rotation': array([ -4.75125694, -24.45129585, -3.39807177]), + 'current_gear_input': False, + 'focus_actor_dist': 934.4534301757812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -617.36486816, -2321.54174805, 60.24476624]), + 'frame': 17371, + 'frame_number': 17371, + 'framesequence': 67055, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 22.100744247436523, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.68115568, 2.8972764 , -0.6728791 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5459136962890625, + 'left_pupil_posn': array([ 0.22221017, -0.78798366]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99534607, -0.08670044, -0.04199219]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1577868014574051, + 'throttle_input': 0.14682230353355408, + 'timestamp': 568.161998976022, + 'timestamp_carla': 568163, + 'timestamp_device': 3721597, + 'timestamp_stream': 568.161998976022, + 'transform': [array([2.77460599e+00, 1.39878893e+01, 6.23273849e-03]), + array([-0.06648505, -8.98480511, 0.01305515])]} +{'AngularVelocity': array([ 0.0382025 , -0.01522945, 0.22648098]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.847967147827148, + 'FR_Wheel_Angle': -8.524967193603516, + 'Location': array([ -2.31036544, -24.64517212, 0.17183349]), + 'Rotation': array([ -0.05767411, -41.62342834, 0.0431185 ]), + 'Velocity': array([-0.00811881, 0.01462263, -0.0003624 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.67237806, 11.6644001 , 0.23619625]), + 'camera_rotation': array([ -4.82203817, -24.46743774, -3.67789912]), + 'current_gear_input': False, + 'focus_actor_dist': 933.71630859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -619.42871094, -2321.54174805, 57.40795898]), + 'frame': 17372, + 'frame_number': 17372, + 'framesequence': 67059, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 21.224225997924805, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72228098, 2.89947677, -0.65711367]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6375885009765625, + 'left_pupil_posn': array([ 0.21853781, -0.78748322]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99472046, -0.09364319, -0.04193115]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1644703596830368, + 'throttle_input': 0.14682230353355408, + 'timestamp': 568.1952713765204, + 'timestamp_carla': 568196, + 'timestamp_device': 3721630, + 'timestamp_stream': 568.1952713765204, + 'transform': [array([2.80959773e+00, 1.39614534e+01, 5.76168066e-03]), + array([-0.06653287, -9.05767822, 0.0139857 ])]} +{'AngularVelocity': array([ 0.02140833, -0.00445222, 0.12926783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.912201404571533, + 'FR_Wheel_Angle': -4.03460168838501, + 'Location': array([ -2.31211162, -24.64336586, 0.17186114]), + 'Rotation': array([ -0.05850057, -41.61686707, 0.04290486]), + 'Velocity': array([-0.01137338, 0.01430684, 0.00030266]), + 'brake_input': 0.0, + 'camera_location': array([-5.71209669, 11.63576508, 0.21874827]), + 'camera_rotation': array([ -4.67705393, -24.38273239, -3.8293376 ]), + 'current_gear_input': False, + 'focus_actor_dist': 932.3611450195312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -620.33081055, -2321.54174805, 56.39134979]), + 'frame': 17373, + 'frame_number': 17373, + 'framesequence': 67063, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 20.65286636352539, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65914488, 2.89983845, -0.68606263]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.51873779296875, + 'left_pupil_posn': array([ 0.21897876, -0.79433346]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99488831, -0.0899353 , -0.04562378]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17104405164718628, + 'throttle_input': 0.15078964829444885, + 'timestamp': 568.2293583787978, + 'timestamp_carla': 568230, + 'timestamp_device': 3721664, + 'timestamp_stream': 568.2293583787978, + 'transform': [array([2.84972072e+00, 1.39331551e+01, 5.08878706e-03]), + array([-0.06666947, -9.14111042, 0.01529942])]} +{'AngularVelocity': array([0.00867546, 0.00679575, 0.01531353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5419961810112, + 'FR_Wheel_Angle': -0.5404015183448792, + 'Location': array([ -2.31569171, -24.6400013 , 0.17187473]), + 'Rotation': array([ -0.05910845, -41.61219788, 0.0428905 ]), + 'Velocity': array([-2.18982995e-02, 2.01098751e-02, 7.48062084e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.77768517, 11.63953495, 0.2173392 ]), + 'camera_rotation': array([ -4.63627052, -24.28247452, -4.06096983]), + 'current_gear_input': False, + 'focus_actor_dist': 929.9718017578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -619.4586792 , -2321.54174805, 58.93262482]), + 'frame': 17374, + 'frame_number': 17374, + 'framesequence': 67067, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 21.48136329650879, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72344851, 2.903795 , -0.65847933]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.51153564453125, + 'left_pupil_posn': array([ 0.22130561, -0.79093838]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99581909, -0.07791138, -0.04750061]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17756280303001404, + 'throttle_input': 0.15475699305534363, + 'timestamp': 568.2633873783052, + 'timestamp_carla': 568264, + 'timestamp_device': 3721697, + 'timestamp_stream': 568.2633873783052, + 'transform': [array([2.88978744e+00, 1.39044914e+01, 4.48635081e-03]), + array([-0.06684706, -9.22479439, 0.01648305])]} +{'AngularVelocity': array([0.01064824, 0.00046839, 0.05826592]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.2647361755371094, + 'FR_Wheel_Angle': -2.5669052600860596, + 'Location': array([ -2.32058311, -24.63555145, 0.17187923]), + 'Rotation': array([ -0.05953876, -41.6101799 , 0.04271076]), + 'Velocity': array([-0.03186268, 0.03044432, -0.00027949]), + 'brake_input': 0.0, + 'camera_location': array([-5.80985165, 11.62794876, 0.24129389]), + 'camera_rotation': array([ -4.55041504, -24.22084045, -4.26981735]), + 'current_gear_input': False, + 'focus_actor_dist': 927.6281127929688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -618.46051025, -2321.54174805, 59.7985611 ]), + 'frame': 17375, + 'frame_number': 17375, + 'framesequence': 67071, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 19.696758270263672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.73371625, 2.90668344, -0.66372836]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.50738525390625, + 'left_pupil_posn': array([ 0.22177875, -0.8015393 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9959259 , -0.07255554, -0.05337524]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18281808495521545, + 'throttle_input': 0.15475699305534363, + 'timestamp': 568.2958928793669, + 'timestamp_carla': 568297, + 'timestamp_device': 3721730, + 'timestamp_stream': 568.2958928793669, + 'transform': [array([2.92800045e+00, 1.38766193e+01, 3.89539707e-03]), + array([-0.0669017 , -9.30488014, 0.01767075])]} +{'AngularVelocity': array([-0.03862809, -0.04284842, 0.82799178]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.0914130210876465, + 'FR_Wheel_Angle': -5.140374183654785, + 'Location': array([ -2.38244677, -24.57731438, 0.17204399]), + 'Rotation': array([-7.72357732e-02, -4.15072746e+01, 3.97227220e-02]), + 'Velocity': array([-0.38035032, 0.3698445 , 0.00090497]), + 'brake_input': 0.0, + 'camera_location': array([-5.84463835, 11.6203537 , 0.28389239]), + 'camera_rotation': array([ -4.37438774, -24.18088531, -4.40555525]), + 'current_gear_input': False, + 'focus_actor_dist': 925.4328002929688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -618.14904785, -2321.54174805, 61.39924622]), + 'frame': 17376, + 'frame_number': 17376, + 'framesequence': 67075, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 13.34652328491211, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.70267677, 2.90741134, -0.67905581]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.298126220703125, + 'left_pupil_posn': array([ 0.22308791, -0.81252348]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99516296, -0.06716919, -0.07148743]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18750573694705963, + 'throttle_input': 0.15475699305534363, + 'timestamp': 568.3286993764341, + 'timestamp_carla': 568330, + 'timestamp_device': 3721764, + 'timestamp_stream': 568.3286993764341, + 'transform': [array([2.96930957e+00, 1.38474665e+01, 3.35968006e-03]), + array([-0.06679925, -9.39138985, 0.01874101])]} +{'AngularVelocity': array([-0.03973281, -0.03086664, 0.93737364]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.376829147338867, + 'FR_Wheel_Angle': -7.208749294281006, + 'Location': array([ -2.46242976, -24.49959373, 0.17202331]), + 'Rotation': array([-5.92313968e-02, -4.12858086e+01, 4.12226692e-02]), + 'Velocity': array([-0.27848411, 0.28264657, 0.00038871]), + 'brake_input': 0.0, + 'camera_location': array([-5.88241816, 11.61295891, 0.31759861]), + 'camera_rotation': array([ -4.26091766, -24.11637688, -4.545856 ]), + 'current_gear_input': False, + 'focus_actor_dist': 923.3128662109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -618.17529297, -2321.54174805, 64.45642853]), + 'frame': 17377, + 'frame_number': 17377, + 'framesequence': 67079, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.462697982788086, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.67029119, 2.90602899, -0.69689637]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4501190185546875, + 'left_pupil_posn': array([ 0.22148824, -0.81200552]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99571228, -0.07339478, -0.0562439 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19135107100009918, + 'throttle_input': 0.1587243527173996, + 'timestamp': 568.361964777112, + 'timestamp_carla': 568363, + 'timestamp_device': 3721797, + 'timestamp_stream': 568.361964777112, + 'transform': [array([3.01344657e+00, 1.38169622e+01, 2.87164678e-03]), + array([-0.06681291, -9.48391914, 0.01970804])]} +{'AngularVelocity': array([-6.57235133e-03, -8.26009258e-04, 8.44134092e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.07875919342041, + 'FR_Wheel_Angle': -9.553537368774414, + 'Location': array([ -2.51706958, -24.44475365, 0.17205253]), + 'Rotation': array([ -0.0540746 , -41.06806183, 0.04220046]), + 'Velocity': array([-1.85851321e-01, 1.96878746e-01, -9.31644390e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.89478064, 11.62020302, 0.328715 ]), + 'camera_rotation': array([ -4.17086172, -24.11107445, -4.71736813]), + 'current_gear_input': False, + 'focus_actor_dist': 921.085205078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -617.86743164, -2321.54174805, 66.49365997]), + 'frame': 17378, + 'frame_number': 17378, + 'framesequence': 67083, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.88428497314453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.67029119, 2.90618753, -0.6975159 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4503326416015625, + 'left_pupil_posn': array([ 0.22148824, -0.81200552]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99580383, -0.07307434, -0.05505371]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19497667253017426, + 'throttle_input': 0.1745937317609787, + 'timestamp': 568.395876377821, + 'timestamp_carla': 568397, + 'timestamp_device': 3721830, + 'timestamp_stream': 568.395876377821, + 'transform': [array([3.05986619e+00, 1.37849464e+01, 2.32305517e-03]), + array([-0.06686072, -9.58139896, 0.02078572])]} +{'AngularVelocity': array([ 0.00609976, 0.01766922, -0.14875244]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.82752799987793, + 'FR_Wheel_Angle': -11.67943286895752, + 'Location': array([ -2.54740214, -24.4130764 , 0.1720842 ]), + 'Rotation': array([ -0.05303642, -40.91559219, 0.04276754]), + 'Velocity': array([-1.17686242e-01, 1.29627943e-01, -8.29982746e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.89145279, 11.62870216, 0.32175598]), + 'camera_rotation': array([ -4.15794563, -24.05995941, -4.8085556 ]), + 'current_gear_input': False, + 'focus_actor_dist': 919.24072265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -618.65734863, -2321.54174805, 68.09708405]), + 'frame': 17379, + 'frame_number': 17379, + 'framesequence': 67087, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.878318786621094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.67029119, 2.90602899, -0.6975159 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.474273681640625, + 'left_pupil_posn': array([ 0.22025788, -0.81200552]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99554443, -0.0766449 , -0.05480957]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1975768357515335, + 'throttle_input': 0.1904631108045578, + 'timestamp': 568.4287322759628, + 'timestamp_carla': 568430, + 'timestamp_device': 3721864, + 'timestamp_stream': 568.4287322759628, + 'transform': [array([3.10861635e+00, 1.37524223e+01, 1.82365417e-03]), + array([-0.06684706, -9.68367481, 0.02178852])]} +{'AngularVelocity': array([0.01295988, 0.01032357, 0.45581126]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.798624992370605, + 'FR_Wheel_Angle': -13.188472747802734, + 'Location': array([ -2.56802273, -24.39068222, 0.1721223 ]), + 'Rotation': array([ -0.05664276, -40.79242325, 0.0422564 ]), + 'Velocity': array([-0.08710206, 0.09930754, 0.00011134]), + 'brake_input': 0.0, + 'camera_location': array([-5.88287544, 11.66689205, 0.3246662 ]), + 'camera_rotation': array([ -4.1919055 , -23.95335007, -4.67518377]), + 'current_gear_input': False, + 'focus_actor_dist': 917.0787963867188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -618.69763184, -2321.54150391, 68.46817017]), + 'frame': 17380, + 'frame_number': 17380, + 'framesequence': 67091, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 17.14487075805664, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.74035645, 2.88008571, -0.6518082 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5416259765625, + 'left_pupil_posn': array([ 0.24487925, -0.79748034]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99595642, -0.06684875, -0.05984497]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19818110764026642, + 'throttle_input': 0.23015183210372925, + 'timestamp': 568.4622701779008, + 'timestamp_carla': 568463, + 'timestamp_device': 3721897, + 'timestamp_stream': 568.4622701779008, + 'transform': [array([3.15982962e+00, 1.37179852e+01, 1.20597833e-03]), + array([-0.06685389, -9.79133224, 0.02300997])]} +{'AngularVelocity': array([6.16194739e-05, 9.88904387e-04, 4.60270613e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.675518035888672, + 'FR_Wheel_Angle': -14.62295913696289, + 'Location': array([ -2.58781958, -24.36899376, 0.17216495]), + 'Rotation': array([ -0.05758532, -40.6477623 , 0.04220736]), + 'Velocity': array([-0.05870433, 0.06931107, 0.00031823]), + 'brake_input': 0.0, + 'camera_location': array([-5.85860491, 11.69752502, 0.33275515]), + 'camera_rotation': array([ -4.20773077, -23.74226379, -4.43267155]), + 'current_gear_input': False, + 'focus_actor_dist': 914.6154174804688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -617.82800293, -2321.54174805, 68.1224823 ]), + 'frame': 17381, + 'frame_number': 17381, + 'framesequence': 67095, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.09687140583992004, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7561388 , 2.88362455, -0.64617157]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5348968505859375, + 'left_pupil_posn': array([ 0.26089907, -0.80611646]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99684143, -0.02111816, -0.07650757]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19818110764026642, + 'throttle_input': 0.2856946587562561, + 'timestamp': 568.4964571781456, + 'timestamp_carla': 568498, + 'timestamp_device': 3721930, + 'timestamp_stream': 568.4964571781456, + 'transform': [array([3.21484375e+00, 1.36812639e+01, 6.41059887e-04]), + array([-0.06675144, -9.90703011, 0.02412299])]} +{'AngularVelocity': array([ 0.02151585, 0.02282557, -0.3919999 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.309585571289062, + 'FR_Wheel_Angle': -15.713387489318848, + 'Location': array([ -2.59671783, -24.35876465, 0.17216823]), + 'Rotation': array([ -0.05725064, -40.58257294, 0.04249415]), + 'Velocity': array([-0.04179084, 0.04783987, 0.00031848]), + 'brake_input': 0.0, + 'camera_location': array([-5.84393215, 11.72503281, 0.34944424]), + 'camera_rotation': array([ -4.12956619, -23.58819199, -4.37570858]), + 'current_gear_input': False, + 'focus_actor_dist': 911.2847900390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -615.20782471, -2321.54174805, 68.13635254]), + 'frame': 17382, + 'frame_number': 17382, + 'framesequence': 67098, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 5.057682037353516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.76426888, 2.88523126, -0.64308321]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4760284423828125, + 'left_pupil_posn': array([ 0.25404155, -0.80611646]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99627686, -0.03535461, -0.07847595]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19818110764026642, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.5280594788492, + 'timestamp_carla': 568529, + 'timestamp_device': 3721955, + 'timestamp_stream': 568.5280594788492, + 'transform': [array([3.26569843e+00, 1.36462593e+01, 1.87892903e-04]), + array([ -0.06656019, -10.01430321, 0.02505972])]} +{'AngularVelocity': array([ 0.02959611, 0.0250834 , -0.36173084]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.96396255493164, + 'FR_Wheel_Angle': -16.132362365722656, + 'Location': array([ -2.60379362, -24.35047722, 0.17218933]), + 'Rotation': array([ -0.05913578, -40.52447128, 0.04181318]), + 'Velocity': array([-0.04083014, 0.04557731, 0.00021287]), + 'brake_input': 0.0, + 'camera_location': array([-5.84391117, 11.75758553, 0.34386885]), + 'camera_rotation': array([ -4.15968752, -23.35599518, -4.30055046]), + 'current_gear_input': False, + 'focus_actor_dist': 908.1608276367188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -613.68707275, -2321.54174805, 69.62981415]), + 'frame': 17383, + 'frame_number': 17383, + 'framesequence': 67103, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 6.995779037475586, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.78708649, 2.89447784, -0.63962406]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4021759033203125, + 'left_pupil_posn': array([ 0.2414937 , -0.81328928]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99493408, -0.05029297, -0.08692932]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19807124137878418, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.5615136772394, + 'timestamp_carla': 568563, + 'timestamp_device': 3721997, + 'timestamp_stream': 568.5615136772394, + 'transform': [array([ 3.32216358e+00, 1.36073580e+01, -4.38880903e-04]), + array([ -0.06650555, -10.13353252, 0.02629814])]} +{'AngularVelocity': array([ 0.05064751, -0.03562552, 1.97842824]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.28899574279785, + 'FR_Wheel_Angle': -16.421239852905273, + 'Location': array([ -2.62708735, -24.32422829, 0.17227241]), + 'Rotation': array([-7.00640753e-02, -4.03456955e+01, 3.56809348e-02]), + 'Velocity': array([-1.85120106e-01, 2.32149422e-01, 1.69105522e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.80836868, 11.77473259, 0.34056002]), + 'camera_rotation': array([ -4.18525982, -23.02281952, -4.25890064]), + 'current_gear_input': False, + 'focus_actor_dist': 904.6948852539062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -610.72412109, -2321.54174805, 69.40913391]), + 'frame': 17384, + 'frame_number': 17384, + 'framesequence': 67106, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 25.435745239257812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7500658 , 2.89969349, -0.65648043]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6658172607421875, + 'left_pupil_posn': array([ 0.23117983, -0.79624867]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99713135, -0.0632019 , -0.04135132]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19770501554012299, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.5935444757342, + 'timestamp_carla': 568595, + 'timestamp_device': 3722022, + 'timestamp_stream': 568.5935444757342, + 'transform': [array([ 3.38058138e+00, 1.35676775e+01, -1.22697826e-03]), + array([ -0.06662166, -10.25685978, 0.02787327])]} +{'AngularVelocity': array([-2.51079332e-02, 2.31775595e-03, 3.30754614e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.97874641418457, + 'FR_Wheel_Angle': -16.8499755859375, + 'Location': array([ -2.7002306 , -24.24127579, 0.17236686]), + 'Rotation': array([-7.25707561e-02, -3.96719780e+01, 3.36419567e-02]), + 'Velocity': array([-0.34687522, 0.4187077 , 0.00056619]), + 'brake_input': 0.0, + 'camera_location': array([-5.79981279, 11.77502632, 0.33226439]), + 'camera_rotation': array([ -4.20130396, -22.75957298, -4.3604393 ]), + 'current_gear_input': False, + 'focus_actor_dist': 900.31494140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -606.18157959, -2321.54150391, 69.33323669]), + 'frame': 17385, + 'frame_number': 17385, + 'framesequence': 67111, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 21.0891170501709, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.80619359, 2.89996362, -0.62501985]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6191253662109375, + 'left_pupil_posn': array([ 0.2328403 , -0.78996861]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99691772, -0.05960083, -0.05072021]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19710074365139008, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.6290853768587, + 'timestamp_carla': 568630, + 'timestamp_device': 3722064, + 'timestamp_stream': 568.6290853768587, + 'transform': [array([ 3.44686270e+00, 1.35215683e+01, -2.05713278e-03]), + array([ -0.06670363, -10.39718246, 0.02947543])]} +{'AngularVelocity': array([-0.07128017, 0.01182175, 1.81740391]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.068464279174805, + 'FR_Wheel_Angle': -16.89863395690918, + 'Location': array([ -2.75967646, -24.17436981, 0.17235015]), + 'Rotation': array([ -0.05865766, -39.10932922, 0.04193649]), + 'Velocity': array([-0.24013065, 0.2815775 , 0.00060045]), + 'brake_input': 0.0, + 'camera_location': array([-5.78441048, 11.77329159, 0.30119327]), + 'camera_rotation': array([ -4.30545044, -22.59249878, -4.43781328]), + 'current_gear_input': False, + 'focus_actor_dist': 896.4464111328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -602.95300293, -2321.54199219, 69.37610626]), + 'frame': 17386, + 'frame_number': 17386, + 'framesequence': 67115, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 30.791765213012695, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72574615, 2.90055847, -0.66663671]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.71466064453125, + 'left_pupil_posn': array([ 0.22450686, -0.78851533]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99681091, -0.07667542, -0.02174377]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19556261599063873, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.6623274758458, + 'timestamp_carla': 568663, + 'timestamp_device': 3722097, + 'timestamp_stream': 568.6623274758458, + 'transform': [array([ 3.51268244e+00, 1.34757252e+01, -2.91870115e-03]), + array([ -0.06689487, -10.5366745 , 0.03119368])]} +{'AngularVelocity': array([-0.00733716, -0.01258846, 1.42767239]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.15009880065918, + 'FR_Wheel_Angle': -17.009435653686523, + 'Location': array([ -2.81178498, -24.11675453, 0.17240535]), + 'Rotation': array([ -0.05856204, -38.60391998, 0.0417631 ]), + 'Velocity': array([-0.20275719, 0.24023747, 0.00030395]), + 'brake_input': 0.0, + 'camera_location': array([-5.76180315, 11.77372074, 0.26399252]), + 'camera_rotation': array([ -4.51873684, -22.33160019, -4.45948124]), + 'current_gear_input': False, + 'focus_actor_dist': 892.9388427734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -601.52209473, -2321.54174805, 68.00111389]), + 'frame': 17387, + 'frame_number': 17387, + 'framesequence': 67119, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 34.10096740722656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72878122, 2.90433049, -0.66364139]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.604644775390625, + 'left_pupil_posn': array([ 0.22486782, -0.78604138]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99746704, -0.06744385, -0.02197266]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19353008270263672, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.6942747756839, + 'timestamp_carla': 568695, + 'timestamp_device': 3722130, + 'timestamp_stream': 568.6942747756839, + 'transform': [array([ 3.57805204e+00, 1.34293194e+01, -3.76802427e-03]), + array([ -0.06705879, -10.67555809, 0.0329023 ])]} +{'AngularVelocity': array([ 0.01001593, -0.00343813, 1.93033385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.098554611206055, + 'FR_Wheel_Angle': -17.696535110473633, + 'Location': array([ -2.87474656, -24.04893494, 0.17250232]), + 'Rotation': array([ -0.06350709, -37.99344635, 0.03803384]), + 'Velocity': array([-0.27251846, 0.31821674, 0.00032937]), + 'brake_input': 0.0, + 'camera_location': array([-5.72821999, 11.77331734, 0.26115945]), + 'camera_rotation': array([ -4.54474592, -22.17074013, -4.5983448 ]), + 'current_gear_input': False, + 'focus_actor_dist': 888.9764404296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -598.5178833 , -2321.54174805, 64.9827652 ]), + 'frame': 17388, + 'frame_number': 17388, + 'framesequence': 67122, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 26.865896224975586, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.70041847, 2.90635991, -0.66440129]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.69952392578125, + 'left_pupil_posn': array([ 0.21470714, -0.77897656]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99581909, -0.08805847, -0.02401733]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1911313235759735, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.7269911766052, + 'timestamp_carla': 568728, + 'timestamp_device': 3722155, + 'timestamp_stream': 568.7269911766052, + 'transform': [array([ 3.64813471e+00, 1.33791742e+01, -4.56779450e-03]), + array([ -0.06709977, -10.82464886, 0.03449693])]} +{'AngularVelocity': array([ 0.04396597, -0.01291626, 2.24059653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.371381759643555, + 'FR_Wheel_Angle': -17.82399559020996, + 'Location': array([ -2.94077468, -23.97797585, 0.17254467]), + 'Rotation': array([ -0.06100725, -37.34675217, 0.03926925]), + 'Velocity': array([-2.58726805e-01, 3.01925749e-01, 2.07166668e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.71291876, 11.75844097, 0.28309917]), + 'camera_rotation': array([ -4.53401613, -22.10425186, -4.57489157]), + 'current_gear_input': False, + 'focus_actor_dist': 885.3851318359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -597.17852783, -2321.54174805, 64.88549805]), + 'frame': 17389, + 'frame_number': 17389, + 'framesequence': 67127, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 29.427143096923828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.74924946, 2.91528487, -0.64474642]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5602874755859375, + 'left_pupil_posn': array([ 0.20554745, -0.76404727]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99562073, -0.09335327, 0.00271606]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18761558830738068, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.7646186761558, + 'timestamp_carla': 568766, + 'timestamp_device': 3722197, + 'timestamp_stream': 568.7646186761558, + 'transform': [array([ 3.72999859e+00, 1.33190107e+01, -5.21633122e-03]), + array([ -0.06692219, -10.99929714, 0.03572121])]} +{'AngularVelocity': array([ 0.07734326, -0.0253899 , 3.46579981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.848928451538086, + 'FR_Wheel_Angle': -18.217552185058594, + 'Location': array([ -3.0162549 , -23.89842033, 0.17266017]), + 'Rotation': array([-6.47638515e-02, -3.65977325e+01, 3.61953266e-02]), + 'Velocity': array([-0.30416971, 0.3547917 , 0.0005793 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.67548513, 11.74140739, 0.28397185]), + 'camera_rotation': array([ -4.58821344, -22.00952339, -4.32714033]), + 'current_gear_input': False, + 'focus_actor_dist': 882.180419921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -597.53338623, -2321.54174805, 65.34738159]), + 'frame': 17390, + 'frame_number': 17390, + 'framesequence': 67131, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 25.812524795532227, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.721596 , 2.92469645, -0.64790499]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.532806396484375, + 'left_pupil_posn': array([ 0.19814563, -0.76928651]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99536133, -0.09303284, -0.02410889]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1828363984823227, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.7977456785738, + 'timestamp_carla': 568799, + 'timestamp_device': 3722230, + 'timestamp_stream': 568.7977456785738, + 'transform': [array([ 3.80471373e+00, 1.32633095e+01, -5.79298008e-03]), + array([ -0.06676509, -11.15894413, 0.03691476])]} +{'AngularVelocity': array([-0.0069734 , -0.00737417, 3.30656028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.447063446044922, + 'FR_Wheel_Angle': -18.67074966430664, + 'Location': array([ -3.08421063, -23.82803154, 0.17273857]), + 'Rotation': array([-6.64372444e-02, -3.59160728e+01, 3.54690291e-02]), + 'Velocity': array([-3.43195796e-01, 3.81567955e-01, 1.83954238e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.65005684, 11.75546741, 0.26741594]), + 'camera_rotation': array([ -4.7083497 , -21.83502007, -4.24979925]), + 'current_gear_input': False, + 'focus_actor_dist': 878.2455444335938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -597.61871338, -2321.54199219, 64.84138489]), + 'frame': 17391, + 'frame_number': 17391, + 'framesequence': 67135, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 23.2769832611084, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.77310514, 2.92469192, -0.62624055]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5890350341796875, + 'left_pupil_posn': array([ 0.195557 , -0.76818585]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.9944458 , -0.10144043, -0.02767944]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17758110165596008, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.8293560780585, + 'timestamp_carla': 568830, + 'timestamp_device': 3722264, + 'timestamp_stream': 568.8293560780585, + 'transform': [array([ 3.87708974e+00, 1.32078829e+01, -6.34935359e-03]), + array([ -0.06655336, -11.31400776, 0.03807647])]} +{'AngularVelocity': array([0.10352578, 0.0714118 , 4.40807056]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.921937942504883, + 'FR_Wheel_Angle': -18.90599250793457, + 'Location': array([ -3.17300725, -23.73807335, 0.17285819]), + 'Rotation': array([-7.09246770e-02, -3.50282974e+01, 3.15991528e-02]), + 'Velocity': array([-4.81004745e-01, 5.12660027e-01, 3.92312999e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.63836241, 11.7711134 , 0.24958497]), + 'camera_rotation': array([ -4.70286512, -21.7424202 , -4.39641476]), + 'current_gear_input': False, + 'focus_actor_dist': 874.1206665039062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -596.19476318, -2321.54150391, 63.3420639 ]), + 'frame': 17392, + 'frame_number': 17392, + 'framesequence': 67139, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 23.22112464904785, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7644639 , 2.92469192, -0.62949073]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.580078125, + 'left_pupil_posn': array([ 0.19460285, -0.76734126]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99429321, -0.10348511, -0.02563477]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17272867262363434, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.8615458756685, + 'timestamp_carla': 568863, + 'timestamp_device': 3722297, + 'timestamp_stream': 568.8615458756685, + 'transform': [array([ 3.95128036e+00, 1.31493025e+01, -6.83656661e-03]), + array([ -0.06623917, -11.47343445, 0.03908275])]} +{'AngularVelocity': array([0.13095482, 0.05587913, 5.48703098]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.81033706665039, + 'FR_Wheel_Angle': -18.818723678588867, + 'Location': array([ -3.2930975 , -23.61963654, 0.17300484]), + 'Rotation': array([-7.35474750e-02, -3.38314323e+01, 3.06690820e-02]), + 'Velocity': array([-6.08006477e-01, 6.28789842e-01, 4.24556725e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.6295743 , 11.80239677, 0.22271839]), + 'camera_rotation': array([ -4.81401253, -21.66558838, -4.47874641]), + 'current_gear_input': False, + 'focus_actor_dist': 870.3525390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -596.04724121, -2321.54174805, 63.73178864]), + 'frame': 17393, + 'frame_number': 17393, + 'framesequence': 67143, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 24.623971939086914, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.76960158, 2.92487049, -0.62655795]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.578338623046875, + 'left_pupil_posn': array([ 0.19690645, -0.76620722]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99493408, -0.097229 , -0.02528381]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1675100028514862, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.895192977041, + 'timestamp_carla': 568896, + 'timestamp_device': 3722330, + 'timestamp_stream': 568.895192977041, + 'transform': [array([ 4.02936125e+00, 1.30858774e+01, -7.19621638e-03]), + array([ -0.06580887, -11.64169407, 0.03981741])]} +{'AngularVelocity': array([-0.05851073, 0.01707048, 7.03255272]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.764724731445312, + 'FR_Wheel_Angle': -18.787322998046875, + 'Location': array([ -3.46225262, -23.46182632, 0.17320949]), + 'Rotation': array([-7.57194757e-02, -3.21938591e+01, 3.04399412e-02]), + 'Velocity': array([-0.75407743, 0.73581505, 0.00077746]), + 'brake_input': 0.0, + 'camera_location': array([-5.63184738, 11.84087086, 0.1995144 ]), + 'camera_rotation': array([ -4.92912197, -21.47841454, -4.52690792]), + 'current_gear_input': False, + 'focus_actor_dist': 866.5933837890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -596.13336182, -2321.54174805, 62.34877777]), + 'frame': 17394, + 'frame_number': 17394, + 'framesequence': 67147, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.037748336791992, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.62013578, 2.92156696, -0.67924351]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.871002197265625, + 'left_pupil_posn': array([ 0.16895068, -0.7555325 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98506165, -0.17210388, 0.00256348]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1624378263950348, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.9274685792625, + 'timestamp_carla': 568929, + 'timestamp_device': 3722364, + 'timestamp_stream': 568.9274685792625, + 'transform': [array([ 4.10471535e+00, 1.30228996e+01, -7.49658560e-03]), + array([ -0.06539906, -11.80454826, 0.04046064])]} +{'AngularVelocity': array([-0.54924875, 0.19147171, 7.32929373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.79391860961914, + 'FR_Wheel_Angle': -18.892118453979492, + 'Location': array([ -3.65503645, -23.28477478, 0.171693 ]), + 'Rotation': array([ -0.05434781, -30.47150421, 0.13978727]), + 'Velocity': array([-0.80568898, 0.77772766, -0.01284614]), + 'brake_input': 0.0, + 'camera_location': array([-5.61457968, 11.91904354, 0.20767006]), + 'camera_rotation': array([ -4.91561842, -21.25860214, -4.82926941]), + 'current_gear_input': False, + 'focus_actor_dist': 861.8016967773438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -594.43817139, -2321.54174805, 61.00600433]), + 'frame': 17395, + 'frame_number': 17395, + 'framesequence': 67150, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 23.3735294342041, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.56059122, 2.92001343, -0.708664 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.588958740234375, + 'left_pupil_posn': array([ 0.19267452, -0.76714206]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99369812, -0.11140442, -0.01164246]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15809810161590576, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.9594199769199, + 'timestamp_carla': 568960, + 'timestamp_device': 3722389, + 'timestamp_stream': 568.9594199769199, + 'transform': [array([ 4.17976236e+00, 1.29584570e+01, -7.75562273e-03]), + array([ -0.06505072, -11.96722889, 0.04102237])]} +{'AngularVelocity': array([-0.13185769, 0.01718437, 9.49700832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.746110916137695, + 'FR_Wheel_Angle': -19.56037712097168, + 'Location': array([ -3.87238646, -23.09450722, 0.17022187]), + 'Rotation': array([ -0.049594 , -28.45296478, 0.15987484]), + 'Velocity': array([-0.90347677, 0.84587818, -0.00416049]), + 'brake_input': 0.0, + 'camera_location': array([-5.58779478, 11.98841286, 0.25067362]), + 'camera_rotation': array([ -4.796978 , -20.95967674, -4.79066563]), + 'current_gear_input': False, + 'focus_actor_dist': 856.5882568359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -592.08203125, -2321.54174805, 61.66539764]), + 'frame': 17396, + 'frame_number': 17396, + 'framesequence': 67154, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 19.066530227661133, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.64995456, 2.93204069, -0.67223972]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5936126708984375, + 'left_pupil_posn': array([ 0.17730808, -0.76711452]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99127197, -0.12982178, -0.02282715]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15320901572704315, + 'throttle_input': 0.30951398611068726, + 'timestamp': 568.9924220778048, + 'timestamp_carla': 568993, + 'timestamp_device': 3722422, + 'timestamp_stream': 568.9924220778048, + 'transform': [array([ 4.25744629e+00, 1.28898506e+01, -7.94498436e-03]), + array([ -0.0646614 , -12.13615227, 0.04143172])]} +{'AngularVelocity': array([ 0.31856433, -0.04175775, 12.12559223]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.387222290039062, + 'FR_Wheel_Angle': -20.879838943481445, + 'Location': array([ -4.11599398, -22.89842224, 0.17169067]), + 'Rotation': array([ -0.07851985, -26.09046555, 0.13854097]), + 'Velocity': array([-1.12206292, 0.93196654, 0.01065076]), + 'brake_input': 0.0, + 'camera_location': array([-5.57624388, 12.06161976, 0.272955 ]), + 'camera_rotation': array([ -4.66837931, -20.65530968, -4.60663462]), + 'current_gear_input': False, + 'focus_actor_dist': 850.6026611328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -588.42980957, -2321.54174805, 63.97614288]), + 'frame': 17397, + 'frame_number': 17397, + 'framesequence': 67158, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 18.146873474121094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.60334039, 2.93331027, -0.69600987]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5367584228515625, + 'left_pupil_posn': array([ 0.17817867, -0.77979803]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99143982, -0.12519836, -0.03671265]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1479354351758957, + 'throttle_input': 0.31348133087158203, + 'timestamp': 569.0275069773197, + 'timestamp_carla': 569029, + 'timestamp_device': 3722455, + 'timestamp_stream': 569.0275069773197, + 'transform': [array([ 4.33970213e+00, 1.28148851e+01, -8.02146923e-03]), + array([ -0.06418329, -12.31561852, 0.04159735])]} +{'AngularVelocity': array([ 6.42549098e-02, -5.76489186e-03, 1.43684597e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.33327865600586, + 'FR_Wheel_Angle': -22.77647590637207, + 'Location': array([ -4.4014287 , -22.68902588, 0.1743671 ]), + 'Rotation': array([ -0.10213865, -23.12314606, 0.09550322]), + 'Velocity': array([-1.22827065, 0.96851963, 0.00741395]), + 'brake_input': 0.0, + 'camera_location': array([-5.5581255 , 12.12153149, 0.26702994]), + 'camera_rotation': array([ -4.60828733, -20.42503548, -4.62564087]), + 'current_gear_input': False, + 'focus_actor_dist': 843.56787109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -584.4442749 , -2320.8684082 , 66.46902466]), + 'frame': 17398, + 'frame_number': 17398, + 'framesequence': 67162, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 22.649879455566406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69956088, 2.94068146, -0.66595769]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6053314208984375, + 'left_pupil_posn': array([ 0.17872834, -0.77579927]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99356079, -0.11154175, -0.01913452]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14110538363456726, + 'throttle_input': 0.3174487054347992, + 'timestamp': 569.0599231794477, + 'timestamp_carla': 569061, + 'timestamp_device': 3722489, + 'timestamp_stream': 569.0599231794477, + 'transform': [array([ 4.41472483e+00, 1.27438087e+01, -8.11136235e-03]), + array([ -0.06365053, -12.47999096, 0.04184448])]} +{'AngularVelocity': array([-0.03262899, -0.03036952, 12.31272316]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.18927764892578, + 'FR_Wheel_Angle': -23.874666213989258, + 'Location': array([ -4.68089819, -22.49709129, 0.17421195]), + 'Rotation': array([ -0.05828883, -20.05004501, 0.03100409]), + 'Velocity': array([-1.09596407, 0.8060661 , 0.00110173]), + 'brake_input': 0.0, + 'camera_location': array([-5.52774715, 12.16736126, 0.24954583]), + 'camera_rotation': array([ -4.64155722, -20.21839714, -4.57075357]), + 'current_gear_input': False, + 'focus_actor_dist': 838.4136352539062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -582.38952637, -2321.84326172, 67.75232697]), + 'frame': 17399, + 'frame_number': 17399, + 'framesequence': 67166, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 77.63478088378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69347548, 2.84316111, -0.65828705]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6068878173828125, + 'left_pupil_posn': array([ 0.30260122, -0.77454555]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99967957, 0.01153564, -0.02218628]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13456831872463226, + 'throttle_input': 0.3174487054347992, + 'timestamp': 569.0930504761636, + 'timestamp_carla': 569094, + 'timestamp_device': 3722522, + 'timestamp_stream': 569.0930504761636, + 'transform': [array([ 4.49005127e+00, 1.26694345e+01, -8.20091274e-03]), + array([ -0.06301532, -12.64573383, 0.04207741])]} +{'AngularVelocity': array([ 0.02525236, 0.02118703, 10.8515873 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.809627532958984, + 'FR_Wheel_Angle': -24.930572509765625, + 'Location': array([ -4.95457983, -22.32466698, 0.17471348]), + 'Rotation': array([ -0.06021494, -16.98225212, 0.03026102]), + 'Velocity': array([-0.93877971, 0.63589329, 0.00191741]), + 'brake_input': 0.0, + 'camera_location': array([-5.49995613, 12.21126366, 0.22847933]), + 'camera_rotation': array([ -4.77786732, -19.86368942, -4.43759394]), + 'current_gear_input': False, + 'focus_actor_dist': 833.5546264648438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -580.51379395, -2322.71655273, 67.64007568]), + 'frame': 17400, + 'frame_number': 17400, + 'framesequence': 67170, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 37.07244873046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.84726596, 2.78951287, -0.60626221]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.636688232421875, + 'left_pupil_posn': array([ 0.37568951, -0.7691009 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99700928, 0.07679749, 0.00743103]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12620015442371368, + 'throttle_input': 0.3174487054347992, + 'timestamp': 569.1263741776347, + 'timestamp_carla': 569127, + 'timestamp_device': 3722555, + 'timestamp_stream': 569.1263741776347, + 'transform': [array([ 4.56350946e+00, 1.25931377e+01, -8.25891457e-03]), + array([ -0.06216838, -12.8081398 , 0.04224866])]} +{'AngularVelocity': array([ 0.07242223, 0.04017545, 11.42772198]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.99827194213867, + 'FR_Wheel_Angle': -26.338239669799805, + 'Location': array([ -5.14132309, -22.21557999, 0.17500854]), + 'Rotation': array([ -0.06673777, -14.80876637, 0.0218793 ]), + 'Velocity': array([-0.94485164, 0.60880888, 0.00134352]), + 'brake_input': 0.0, + 'camera_location': array([-5.46813154, 12.24680138, 0.22448957]), + 'camera_rotation': array([ -4.8372488 , -19.46226692, -4.40520239]), + 'current_gear_input': False, + 'focus_actor_dist': 827.626220703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -576.27209473, -2323.58789062, 66.12995911]), + 'frame': 17401, + 'frame_number': 17401, + 'framesequence': 67174, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 34.82023239135742, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.69376087, 2.79208851, -0.66140902]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.78948974609375, + 'left_pupil_posn': array([ 0.37161958, -0.77010834]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99659729, 0.08190918, 0.00756836]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11645863950252533, + 'throttle_input': 0.3174487054347992, + 'timestamp': 569.1586248762906, + 'timestamp_carla': 569160, + 'timestamp_device': 3722589, + 'timestamp_stream': 569.1586248762906, + 'transform': [array([ 4.63129568e+00, 1.25181170e+01, -8.29418190e-03]), + array([ -0.06113702, -12.9589386 , 0.04239355])]} +{'AngularVelocity': array([ 0.05175718, 0.04070421, 14.60628033]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.994384765625, + 'FR_Wheel_Angle': -27.476125717163086, + 'Location': array([ -5.38651896, -22.08213043, 0.17534824]), + 'Rotation': array([-7.86154717e-02, -1.18225584e+01, 7.95564707e-03]), + 'Velocity': array([-1.16096294, 0.69649869, 0.00143041]), + 'brake_input': 0.0, + 'camera_location': array([-5.42496395, 12.29011154, 0.24875112]), + 'camera_rotation': array([ -4.78826284, -18.92858505, -4.42546368]), + 'current_gear_input': False, + 'focus_actor_dist': 821.1265258789062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -571.24719238, -2324.47875977, 65.81000519]), + 'frame': 17402, + 'frame_number': 17402, + 'framesequence': 67178, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 36.139183044433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.68197346, 2.80278182, -0.64846504]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7161712646484375, + 'left_pupil_posn': array([ 0.35990787, -0.77272081]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99662781, 0.07475281, -0.03379822]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1047029048204422, + 'throttle_input': 0.3174487054347992, + 'timestamp': 569.1932717785239, + 'timestamp_carla': 569194, + 'timestamp_device': 3722622, + 'timestamp_stream': 569.1932717785239, + 'transform': [array([ 4.69895458e+00, 1.24367714e+01, -8.22658557e-03]), + array([ -0.05973683, -13.11057091, 0.04230636])]} +{'AngularVelocity': array([5.56350872e-03, 2.58221142e-02, 1.91784248e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.10593795776367, + 'FR_Wheel_Angle': -28.109437942504883, + 'Location': array([ -5.70150614, -21.92919159, 0.17573436]), + 'Rotation': array([-8.74947160e-02, -7.89347076e+00, -1.22070174e-04]), + 'Velocity': array([-1.52521694, 0.80624986, 0.00162816]), + 'brake_input': 0.0, + 'camera_location': array([-5.39853191, 12.33848381, 0.25095004]), + 'camera_rotation': array([ -4.81850004, -18.24288177, -4.34438467]), + 'current_gear_input': False, + 'focus_actor_dist': 814.095947265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -564.2064209 , -2325.73535156, 67.10945892]), + 'frame': 17403, + 'frame_number': 17403, + 'framesequence': 67182, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 62.319976806640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.71376491, 2.80536819, -0.64246368]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6779937744140625, + 'left_pupil_posn': array([ 0.34140611, -0.77262211]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99909973, 0.03213501, -0.02734375]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09239783883094788, + 'throttle_input': 0.3174487054347992, + 'timestamp': 569.2266650758684, + 'timestamp_carla': 569228, + 'timestamp_device': 3722655, + 'timestamp_stream': 569.2266650758684, + 'transform': [array([ 4.75824690e+00, 1.23578711e+01, -8.12093727e-03]), + array([ -0.05822736, -13.24473381, 0.04217705])]} +{'AngularVelocity': array([-1.84539836e-02, 2.96741948e-02, 2.48718071e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.13863754272461, + 'FR_Wheel_Angle': -28.011157989501953, + 'Location': array([ -6.11684418, -21.76242065, 0.17622776]), + 'Rotation': array([-9.48166773e-02, -2.76348877e+00, -2.53295898e-03]), + 'Velocity': array([-2.0487597 , 0.87368667, 0.00229052]), + 'brake_input': 0.0, + 'camera_location': array([-5.35614491, 12.39717388, 0.23982969]), + 'camera_rotation': array([ -4.7679019 , -17.58369064, -4.51907635]), + 'current_gear_input': False, + 'focus_actor_dist': 807.322021484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -555.36804199, -2328.43676758, 67.2337265 ]), + 'frame': 17404, + 'frame_number': 17404, + 'framesequence': 67186, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 45.444190979003906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72099328, 2.81265116, -0.63069004]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.64398193359375, + 'left_pupil_posn': array([ 0.3419615 , -0.76802564]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99815369, 0.04875183, -0.03581238]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07714468985795975, + 'throttle_input': 0.28172731399536133, + 'timestamp': 569.2586948759854, + 'timestamp_carla': 569260, + 'timestamp_device': 3722689, + 'timestamp_stream': 569.2586948759854, + 'transform': [array([ 4.80775356e+00, 1.22822227e+01, -7.98814744e-03]), + array([ -0.05636272, -13.35827923, 0.04201462])]} +{'AngularVelocity': array([-1.29584417e-01, 1.10392803e-02, 2.87642002e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.45785903930664, + 'FR_Wheel_Angle': -25.136926651000977, + 'Location': array([ -6.66513252, -21.60594749, 0.17680775]), + 'Rotation': array([-0.10147612, 3.60335565, 0.01263949]), + 'Velocity': array([-2.65915775e+00, 7.46715605e-01, 2.61732098e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.30137539, 12.47054672, 0.24776196]), + 'camera_rotation': array([ -4.69790649, -16.99803162, -5.00591946]), + 'current_gear_input': False, + 'focus_actor_dist': 805.0536499023438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -548.33056641, -2335.24462891, 68.10848236]), + 'frame': 17405, + 'frame_number': 17405, + 'framesequence': 67190, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 86.79975891113281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7275362 , 2.8155992 , -0.62772369]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.63818359375, + 'left_pupil_posn': array([ 0.32930148, -0.75854695]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99951172, 0.02442932, -0.01873779]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06320994347333908, + 'throttle_input': 0.269825279712677, + 'timestamp': 569.2930168770254, + 'timestamp_carla': 569294, + 'timestamp_device': 3722722, + 'timestamp_stream': 569.2930168770254, + 'transform': [array([ 4.85208035e+00, 1.22016525e+01, -7.71306967e-03]), + array([ -0.05425219, -13.46183395, 0.04153958])]} +{'AngularVelocity': array([-0.16351698, -0.10655888, 24.69971275]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.758085250854492, + 'FR_Wheel_Angle': -19.084463119506836, + 'Location': array([ -7.34524965, -21.52114296, 0.17744194]), + 'Rotation': array([-0.09633981, 10.06018639, 0.05236207]), + 'Velocity': array([-3.03423476, 0.27049521, 0.00367408]), + 'brake_input': 0.0, + 'camera_location': array([-5.25580788, 12.53590012, 0.23290807]), + 'camera_rotation': array([ -4.71545315, -16.49392509, -5.20133495]), + 'current_gear_input': False, + 'focus_actor_dist': 807.2830810546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -543.51348877, -2345.88183594, 68.90577698]), + 'frame': 17406, + 'frame_number': 17406, + 'framesequence': 67194, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 65.64435577392578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72014332, 2.81880188, -0.6292755 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.73419189453125, + 'left_pupil_posn': array([ 0.32991576, -0.76102126]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99916077, 0.03208923, -0.02522278]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.047242652624845505, + 'throttle_input': 0.2380865216255188, + 'timestamp': 569.3253663778305, + 'timestamp_carla': 569326, + 'timestamp_device': 3722755, + 'timestamp_stream': 569.3253663778305, + 'transform': [array([ 4.88456154e+00, 1.21265793e+01, -7.35216122e-03]), + array([ -0.05211434, -13.54004288, 0.04093222])]} +{'AngularVelocity': array([ 0.05581775, -0.18543464, 10.94592476]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.412542343139648, + 'FR_Wheel_Angle': -10.952496528625488, + 'Location': array([ -8.0133934 , -21.55316544, 0.1779314 ]), + 'Rotation': array([-0.05770143, 14.37417126, 0.0852396 ]), + 'Velocity': array([-2.37067127e+00, -2.46522427e-01, 2.09080684e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.19956589, 12.62421417, 0.2390072 ]), + 'camera_rotation': array([ -4.66800356, -16.07242584, -5.5093503 ]), + 'current_gear_input': False, + 'focus_actor_dist': 816.4677124023438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -541.95458984, -2363.16210938, 67.88137054]), + 'frame': 17407, + 'frame_number': 17407, + 'framesequence': 67198, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 51.999427795410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.67197275, 2.82420039, -0.65098882]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.80908203125, + 'left_pupil_posn': array([ 0.32029665, -0.74391937]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99946594, 0.02401733, 0.02209473]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.032135993242263794, + 'throttle_input': 0.1904631108045578, + 'timestamp': 569.3594922758639, + 'timestamp_carla': 569361, + 'timestamp_device': 3722789, + 'timestamp_stream': 569.3594922758639, + 'transform': [array([ 4.90830088e+00, 1.20488024e+01, -6.80129975e-03]), + array([ -0.04986038, -13.60040474, 0.03992544])]} +{'AngularVelocity': array([0.31821659, 0.00417309, 2.3228054 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.235925197601318, + 'FR_Wheel_Angle': -3.1944682598114014, + 'Location': array([ -8.46510983, -21.64024925, 0.17831832]), + 'Rotation': array([-0.03893891, 15.67604828, 0.05953774]), + 'Velocity': array([-1.60327375e+00, -3.75489980e-01, 4.84647753e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.17750072, 12.7000742 , 0.23505542]), + 'camera_rotation': array([ -4.79036665, -15.62929916, -5.52408886]), + 'current_gear_input': False, + 'focus_actor_dist': 824.8114013671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -540.69287109, -2379.2409668 , 67.87451172]), + 'frame': 17408, + 'frame_number': 17408, + 'framesequence': 67202, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 42.8209342956543, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.67206287, 2.82362819, -0.65083623]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.8116302490234375, + 'left_pupil_posn': array([ 0.3191849 , -0.74273837]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99949646, 0.0202179 , 0.02441406]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.015234840102493763, + 'throttle_input': 0.16269169747829437, + 'timestamp': 569.3917417787015, + 'timestamp_carla': 569393, + 'timestamp_device': 3722822, + 'timestamp_stream': 569.3917417787015, + 'transform': [array([ 4.91980457e+00, 1.19771461e+01, -6.11801120e-03]), + array([ -0.04762008, -13.63436222, 0.03869076])]} +{'AngularVelocity': array([ 0.13017581, 0.09881711, -0.00017177]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4047311842441559, + 'FR_Wheel_Angle': 0.3499242067337036, + 'Location': array([ -8.65504646, -21.6906414 , 0.17816322]), + 'Rotation': array([9.68520809e-03, 1.57932701e+01, 1.67838875e-02]), + 'Velocity': array([ 3.63416621e-04, -1.09617773e-03, 8.85563204e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.12620258, 12.7818737 , 0.23664494]), + 'camera_rotation': array([ -4.64107227, -15.40254211, -5.67398739]), + 'current_gear_input': False, + 'focus_actor_dist': 834.7635498046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -539.25769043, -2397.30566406, 65.26947784]), + 'frame': 17409, + 'frame_number': 17409, + 'framesequence': 67206, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.218387603759766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65733194, 2.82573724, -0.65466774]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7451171875, + 'left_pupil_posn': array([ 0.31395352, -0.73851931]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99943542, 0.01254272, 0.03111267]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0017578662373125553, + 'throttle_input': 0.12300297617912292, + 'timestamp': 569.425376676023, + 'timestamp_carla': 569426, + 'timestamp_device': 3722855, + 'timestamp_stream': 569.425376676023, + 'transform': [array([ 4.91938877e+00, 1.19049549e+01, -5.20429621e-03]), + array([ -0.04524317, -13.6433897 , 0.03698147])]} +{'AngularVelocity': array([ 5.56753192e-04, 1.90900609e-01, -4.23768979e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.03076259419322014, + 'FR_Wheel_Angle': 0.011535977013409138, + 'Location': array([ -8.65534115, -21.69073486, 0.17843506]), + 'Rotation': array([-3.82353961e-02, 1.57934504e+01, -1.92260731e-03]), + 'Velocity': array([ 0.0002386 , -0.00036161, -0.00032758]), + 'brake_input': 0.0, + 'camera_location': array([-5.06443024, 12.90497112, 0.24593958]), + 'camera_rotation': array([ -4.55762768, -15.1778574 , -6.09888983]), + 'current_gear_input': False, + 'focus_actor_dist': 842.1941528320312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -539.52856445, -2412.16625977, 66.82239532]), + 'frame': 17410, + 'frame_number': 17410, + 'framesequence': 67210, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 140.02720642089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65859079, 2.83123946, -0.64606631]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.8555450439453125, + 'left_pupil_posn': array([ 0.3002789 , -0.73892319]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99984741, -0.0115509 , 0.01239014]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.014465774409472942, + 'throttle_input': 0.0952315554022789, + 'timestamp': 569.458991676569, + 'timestamp_carla': 569460, + 'timestamp_device': 3722889, + 'timestamp_stream': 569.458991676569, + 'transform': [array([ 4.90837526e+00, 1.18351641e+01, -4.16004192e-03]), + array([ -0.04348781, -13.62979221, 0.03501421])]} +{'AngularVelocity': array([ 8.84783745e-04, 4.96176034e-02, -1.77422226e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.01409761980175972, + 'FR_Wheel_Angle': 0.014099543914198875, + 'Location': array([ -8.6554842 , -21.6907711 , 0.17858584]), + 'Rotation': array([-6.11301884e-02, 1.57937202e+01, -8.57543852e-03]), + 'Velocity': array([3.49760521e-05, 8.62468096e-06, 2.66824412e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.02782822, 13.00190735, 0.21675356]), + 'camera_rotation': array([ -4.61726904, -14.91572189, -5.76315737]), + 'current_gear_input': False, + 'focus_actor_dist': 850.5348510742188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -539.6237793 , -2428.32495117, 67.36852264]), + 'frame': 17411, + 'frame_number': 17411, + 'framesequence': 67214, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 65.610107421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.6649828 , 2.83114195, -0.65236211]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.852447509765625, + 'left_pupil_posn': array([ 0.3013612 , -0.74136126]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99967957, -0.00946045, 0.02302551]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.020801417529582977, + 'throttle_input': 0.0634927898645401, + 'timestamp': 569.4913316778839, + 'timestamp_carla': 569492, + 'timestamp_device': 3722922, + 'timestamp_stream': 569.4913316778839, + 'transform': [array([ 4.89144754e+00, 1.17695055e+01, -3.14336759e-03]), + array([ -0.04292774, -13.60308075, 0.03310546])]} +{'AngularVelocity': array([ 0.00443013, -0.00162203, -0.00082976]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -8.65475082, -21.69055176, 0.17859352]), + 'Rotation': array([-6.62255138e-02, 1.57939272e+01, -1.04675265e-02]), + 'Velocity': array([ 0.02048603, 0.00576419, -0.00044628]), + 'brake_input': 0.0, + 'camera_location': array([-4.9793129 , 13.08549309, 0.19792156]), + 'camera_rotation': array([ -4.55645323, -14.86430454, -5.46472359]), + 'current_gear_input': False, + 'focus_actor_dist': 863.426025390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -540.1651001 , -2448.95068359, 65.39537048]), + 'frame': 17412, + 'frame_number': 17412, + 'framesequence': 67218, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 9.642362594604492, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.64550638, 2.82906199, -0.65764165]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7536468505859375, + 'left_pupil_posn': array([ 0.30704844, -0.7349242 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99937439, 0.00312805, 0.03503418]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.023346660658717155, + 'throttle_input': 0.051590751856565475, + 'timestamp': 569.525881677866, + 'timestamp_carla': 569527, + 'timestamp_device': 3722955, + 'timestamp_stream': 569.525881677866, + 'transform': [array([ 4.87008238e+00, 1.17003450e+01, -2.04586028e-03]), + array([ -0.04362442, -13.56734753, 0.03098947])]} +{'AngularVelocity': array([-8.73139012e-04, 6.69756811e-03, -4.41664588e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -8.64750957, -21.68850136, 0.17861041]), + 'Rotation': array([-6.73524886e-02, 1.57941198e+01, -1.09558096e-02]), + 'Velocity': array([ 0.03532597, 0.00998527, -0.00017818]), + 'brake_input': 0.0, + 'camera_location': array([-4.91722775, 13.20635223, 0.19513486]), + 'camera_rotation': array([ -4.66006708, -14.8113699 , -5.34046173]), + 'current_gear_input': False, + 'focus_actor_dist': 867.9105224609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -540.79180908, -2460.60644531, 65.91085815]), + 'frame': 17413, + 'frame_number': 17413, + 'framesequence': 67222, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 26.95861053466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7998569 , 2.84121251, -0.57368779]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7734222412109375, + 'left_pupil_posn': array([ 0.2883929 , -0.73893213]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99893188, -0.02876282, -0.03590393]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.025763727724552155, + 'throttle_input': 0.051590751856565475, + 'timestamp': 569.5574688762426, + 'timestamp_carla': 569559, + 'timestamp_device': 3722989, + 'timestamp_stream': 569.5574688762426, + 'transform': [array([ 4.84873343e+00, 1.16378098e+01, -1.07381819e-03]), + array([ -0.0448197 , -13.53066254, 0.02916022])]} +{'AngularVelocity': array([ 0.00019623, -0.00011629, 0.00085743]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.019215485081076622, + 'FR_Wheel_Angle': 0.011531336233019829, + 'Location': array([ -8.63964367, -21.68627167, 0.17861263]), + 'Rotation': array([-6.86638877e-02, 1.57943096e+01, -1.10778799e-02]), + 'Velocity': array([0.03075305, 0.00867222, 0.00026466]), + 'brake_input': 0.0, + 'camera_location': array([-4.93316746, 13.32538128, 0.21501233]), + 'camera_rotation': array([ -4.70823336, -14.63917732, -4.92900562]), + 'current_gear_input': False, + 'focus_actor_dist': 872.7918701171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -541.28076172, -2472.98730469, 63.92131042]), + 'frame': 17414, + 'frame_number': 17414, + 'framesequence': 67226, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 4.694645404815674, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.80453205, 2.84334898, -0.57373965]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7132110595703125, + 'left_pupil_posn': array([ 0.29572904, -0.74219227]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99919128, -0.00640869, -0.03959656]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.025983460247516632, + 'throttle_input': 0.043656062334775925, + 'timestamp': 569.5920353792608, + 'timestamp_carla': 569593, + 'timestamp_device': 3723022, + 'timestamp_stream': 569.5920353792608, + 'transform': [array([ 4.82473755e+00, 1.15699749e+01, -3.72886643e-05]), + array([ -0.04658189, -13.48896694, 0.02714838])]} +{'AngularVelocity': array([ 0.0007261 , -0.00803251, -0.00923753]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.3831336498260498, + 'FR_Wheel_Angle': -0.4427412152290344, + 'Location': array([ -8.6333189 , -21.68450356, 0.1786103 ]), + 'Rotation': array([-6.88483045e-02, 1.57943401e+01, -1.10778790e-02]), + 'Velocity': array([ 2.49170493e-02, 6.76038768e-03, -1.52492521e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.9047823 , 13.44800568, 0.30740094]), + 'camera_rotation': array([ -4.51581335, -14.60674286, -4.55689955]), + 'current_gear_input': False, + 'focus_actor_dist': 1433.4654541015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -712.74865723, -3011.58789062, 17.4852829 ]), + 'frame': 17415, + 'frame_number': 17415, + 'framesequence': 67230, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 57.520362854003906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.63847542, 2.83613586, -0.66372383]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.86981201171875, + 'left_pupil_posn': array([ 0.29005396, -0.73948741]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99919128, -0.02671814, 0.029953 ]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.025983460247516632, + 'throttle_input': 0.03967345505952835, + 'timestamp': 569.6254713758826, + 'timestamp_carla': 569627, + 'timestamp_device': 3723055, + 'timestamp_stream': 569.6254713758826, + 'transform': [array([4.80156708e+00, 1.15048876e+01, 9.11064155e-04]), + array([ -0.04841921, -13.44853687, 0.02533477])]} +{'AngularVelocity': array([ 0.00165984, -0.01346064, -0.01426831]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5765191912651062, + 'FR_Wheel_Angle': -0.5731847882270813, + 'Location': array([ -8.62909317, -21.68333626, 0.17860161]), + 'Rotation': array([-6.84794709e-02, 1.57939730e+01, -1.10778809e-02]), + 'Velocity': array([0.03094355, 0.00830514, 0.00013309]), + 'brake_input': 0.0, + 'camera_location': array([-4.90327263, 13.56978226, 0.37275878]), + 'camera_rotation': array([ -4.28704309, -14.36500072, -3.99025893]), + 'current_gear_input': False, + 'focus_actor_dist': 1495.225341796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -730.46350098, -3078.42041016, 17.50306702]), + 'frame': 17416, + 'frame_number': 17416, + 'framesequence': 67234, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 132.007080078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65228271, 2.84360671, -0.65976411]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.671234130859375, + 'left_pupil_posn': array([ 0.28709137, -0.75106156]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99975586, -0.02146912, 0.00357056]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0262215044349432, + 'throttle_input': 0.03967345505952835, + 'timestamp': 569.6581899784505, + 'timestamp_carla': 569659, + 'timestamp_device': 3723089, + 'timestamp_stream': 569.6581899784505, + 'transform': [array([4.77899647e+00, 1.14417248e+01, 1.76034926e-03]), + array([ -0.0500926 , -13.40901852, 0.02372348])]} +{'AngularVelocity': array([ 0.01181012, -0.00750933, 0.91735959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8489872813224792, + 'FR_Wheel_Angle': -1.0135141611099243, + 'Location': array([ -8.59122849, -21.6728344 , 0.17848431]), + 'Rotation': array([-5.59392460e-02, 1.57822084e+01, -1.08337384e-02]), + 'Velocity': array([ 3.21866065e-01, 9.04502347e-02, -1.62792203e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.9179306 , 13.6826725 , 0.39964369]), + 'camera_rotation': array([ -4.04099941, -13.83668613, -3.48682094]), + 'current_gear_input': False, + 'focus_actor_dist': 1575.4461669921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -748.29821777, -3164.32714844, 17.52086639]), + 'frame': 17417, + 'frame_number': 17417, + 'framesequence': 67238, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 56.352012634277344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.6756258 , 2.85174274, -0.66357881]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.666290283203125, + 'left_pupil_posn': array([ 0.27068615, -0.75684881]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99873352, -0.0489502 , 0.01144409]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.027320170775055885, + 'throttle_input': 0.0317387655377388, + 'timestamp': 569.691146876663, + 'timestamp_carla': 569692, + 'timestamp_device': 3723122, + 'timestamp_stream': 569.691146876663, + 'transform': [array([4.75594997e+00, 1.13788013e+01, 2.54823687e-03]), + array([ -0.05151328, -13.36836243, 0.02222613])]} +{'AngularVelocity': array([-0.00897725, -0.025789 , -0.32092038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.188178539276123, + 'FR_Wheel_Angle': -2.393277168273926, + 'Location': array([ -8.4554739 , -21.63615417, 0.17827873]), + 'Rotation': array([-4.43415865e-02, 1.57136402e+01, -8.54492094e-03]), + 'Velocity': array([ 0.83805335, 0.21894796, -0.00114098]), + 'brake_input': 0.0, + 'camera_location': array([-4.94266891, 13.78919792, 0.39502266]), + 'camera_rotation': array([ -3.92392302, -13.24061775, -3.58837366]), + 'current_gear_input': False, + 'focus_actor_dist': 1671.35888671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -762.1607666 , -3267.68286133, 17.53451538]), + 'frame': 17418, + 'frame_number': 17418, + 'framesequence': 67242, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 79.15096282958984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.7153964 , 2.86388278, -0.63292086]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7751617431640625, + 'left_pupil_posn': array([ 0.26813674, -0.75056911]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99943542, -0.03271484, -0.00614929]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.029554126784205437, + 'throttle_input': 0.027771420776844025, + 'timestamp': 569.7252271771431, + 'timestamp_carla': 569726, + 'timestamp_device': 3723155, + 'timestamp_stream': 569.7252271771431, + 'transform': [array([4.73113298e+00, 1.13147173e+01, 3.32912430e-03]), + array([ -0.05261977, -13.32405663, 0.02072829])]} +{'AngularVelocity': array([ 0.23692693, -0.12357426, -1.93558717]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.67879056930542, + 'FR_Wheel_Angle': -3.7122955322265625, + 'Location': array([ -8.15190697, -21.55894089, 0.17801701]), + 'Rotation': array([-3.90276983e-02, 1.53972378e+01, 3.17819254e-03]), + 'Velocity': array([ 1.58465028, 0.37734741, -0.00261794]), + 'brake_input': 0.0, + 'camera_location': array([-4.97416592, 13.91242409, 0.38111916]), + 'camera_rotation': array([ -3.95372319, -12.6307106 , -4.05912781]), + 'current_gear_input': False, + 'focus_actor_dist': 1720.691162109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -758.76879883, -3327.27099609, 17.53064728]), + 'frame': 17419, + 'frame_number': 17419, + 'framesequence': 67246, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 31.32736587524414, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.61044478, 2.86739969, -0.66711891]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5583038330078125, + 'left_pupil_posn': array([ 0.24351871, -0.74743712]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99642944, -0.08396912, -0.00721741]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.03268532454967499, + 'throttle_input': 0.0158693827688694, + 'timestamp': 569.7586807757616, + 'timestamp_carla': 569760, + 'timestamp_device': 3723188, + 'timestamp_stream': 569.7586807757616, + 'transform': [array([4.70519543e+00, 1.12530050e+01, 4.04863339e-03]), + array([ -0.05332328, -13.27699661, 0.01936899])]} +{'AngularVelocity': array([-0.01404633, 0.04948221, -4.24500751]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.946337699890137, + 'FR_Wheel_Angle': -6.1339430809021, + 'Location': array([ -7.74357367, -21.46310234, 0.177513 ]), + 'Rotation': array([-3.24092470e-02, 1.47934065e+01, 2.68584816e-04]), + 'Velocity': array([ 2.22845030e+00, 4.74037051e-01, -1.63093559e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.99405289, 14.00417137, 0.3915427 ]), + 'camera_rotation': array([ -3.91221595, -11.9329834 , -4.36416197]), + 'current_gear_input': False, + 'focus_actor_dist': 1706.9755859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -736.3494873 , -3326.50976562, 17.50763702]), + 'frame': 17420, + 'frame_number': 17420, + 'framesequence': 67250, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 20.364850997924805, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.72694254, 2.88351893, -0.60717475]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7298431396484375, + 'left_pupil_posn': array([ 0.24029088, -0.75027895]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.99649048, -0.06507874, -0.05249023]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.036896880716085434, + 'throttle_input': 0.0, + 'timestamp': 569.7906355783343, + 'timestamp_carla': 569792, + 'timestamp_device': 3723222, + 'timestamp_stream': 569.7906355783343, + 'transform': [array([4.67798519e+00, 1.11951094e+01, 4.48781950e-03]), + array([ -0.05345306, -13.22666168, 0.01857976])]} +{'AngularVelocity': array([-0.02312273, 0.11970964, -7.60732508]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.395970344543457, + 'FR_Wheel_Angle': -10.08825397491455, + 'Location': array([ -7.18059778, -21.35422134, 0.17805004]), + 'Rotation': array([-8.70166067e-03, 1.33887596e+01, -6.54601976e-02]), + 'Velocity': array([ 2.44856930e+00, 3.57542783e-01, -1.40523433e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.00686836, 14.07462311, 0.45819104]), + 'camera_rotation': array([ -3.71550655, -11.37536144, -4.4082284 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1724.7647705078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -719.8894043 , -3356.42871094, 17.49051666]), + 'frame': 17421, + 'frame_number': 17421, + 'framesequence': 67254, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 26.29959487915039, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([-3.65143156, 2.75657511, -0.6824677 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.623931884765625, + 'left_pupil_posn': array([ 0.41053653, -0.77724564]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.99417114, 0.10691833, 0.01350403]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04076052084565163, + 'throttle_input': 0.0, + 'timestamp': 569.8245527781546, + 'timestamp_carla': 569826, + 'timestamp_device': 3723255, + 'timestamp_stream': 569.8245527781546, + 'transform': [array([4.64646912e+00, 1.11348886e+01, 4.88962140e-03]), + array([ -0.05345306, -13.16743088, 0.01783005])]} +{'AngularVelocity': array([ 0.05681625, 0.0486773 , -9.61653519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.819999694824219, + 'FR_Wheel_Angle': -12.22301959991455, + 'Location': array([ -6.62950468, -21.28390121, 0.17767361]), + 'Rotation': array([-0.0280106 , 11.26252842, -0.06979369]), + 'Velocity': array([ 2.26107049e+00, 1.58770606e-01, -1.83553691e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.99880886, 14.14410782, 0.5229947 ]), + 'camera_rotation': array([ -3.42888451, -10.8632946 , -4.43338013]), + 'current_gear_input': False, + 'focus_actor_dist': 1816.8248291015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -725.67749023, -3456.83520508, 17.49586487]), + 'frame': 17422, + 'frame_number': 17422, + 'framesequence': 67258, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04434949904680252, + 'throttle_input': 0.0, + 'timestamp': 569.8575292788446, + 'timestamp_carla': 569859, + 'timestamp_device': 3723288, + 'timestamp_stream': 569.8575292788446, + 'transform': [array([4.61373663e+00, 1.10775070e+01, 5.28785679e-03]), + array([ -0.05350087, -13.10517311, 0.01710452])]} +{'AngularVelocity': array([ 6.97512105e-02, 2.33225967e-03, -9.07671642e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.64188003540039, + 'FR_Wheel_Angle': -11.711507797241211, + 'Location': array([ -6.13225222, -21.24703979, 0.17731911]), + 'Rotation': array([-0.02984793, 9.07412434, -0.08761595]), + 'Velocity': array([ 2.05889654e+00, 6.01898357e-02, -1.18232728e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.98493004, 14.26270771, 0.55919045]), + 'camera_rotation': array([ -3.21276379, -10.09348106, -4.28171587]), + 'current_gear_input': False, + 'focus_actor_dist': 1538.1961669921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -641.00732422, -3198.81445312, 43.16898346]), + 'frame': 17423, + 'frame_number': 17423, + 'framesequence': 67262, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 4.358347415924072, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.88981628, 0.45533752, 0.02938843]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.16701984, -3.11748219, -0.63725591]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([ 0.13900197, -0.90771723]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04744407907128334, + 'throttle_input': 0.0, + 'timestamp': 569.890792477876, + 'timestamp_carla': 569892, + 'timestamp_device': 3723322, + 'timestamp_stream': 569.890792477876, + 'transform': [array([4.57899904e+00, 1.10208101e+01, 5.68716042e-03]), + array([ -0.05365796, -13.03843021, 0.0163693 ])]} +{'AngularVelocity': array([-0.14425838, 0.18940082, -5.28792953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.763748645782471, + 'FR_Wheel_Angle': -5.119089126586914, + 'Location': array([ -5.68654346, -21.22285843, 0.1757904 ]), + 'Rotation': array([-8.37927535e-02, 7.39036417e+00, 2.57838098e-03]), + 'Velocity': array([ 1.76443112, 0.09209798, -0.0092649 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.99462032, 14.46226311, 0.56533885]), + 'camera_rotation': array([-3.18144727, -8.84834862, -4.10239601]), + 'current_gear_input': False, + 'focus_actor_dist': 1528.00341796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -617.17053223, -3201.03540039, 49.53044128]), + 'frame': 17424, + 'frame_number': 17424, + 'framesequence': 67266, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.051161229610443115, + 'throttle_input': 0.0, + 'timestamp': 569.9241886772215, + 'timestamp_carla': 569925, + 'timestamp_device': 3723355, + 'timestamp_stream': 569.9241886772215, + 'transform': [array([4.54223967e+00, 1.09651337e+01, 6.08947733e-03]), + array([ -0.05380823, -12.96719933, 0.0156259 ])]} +{'AngularVelocity': array([-0.0162503 , 0.01766287, -0.44176322]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.40126049518585205, + 'FR_Wheel_Angle': 0.49294114112854004, + 'Location': array([ -5.25691414, -21.1809597 , 0.17513935]), + 'Rotation': array([-0.08633359, 6.87310648, -0.00973511]), + 'Velocity': array([ 1.44536042e+00, 1.77499697e-01, -8.66746879e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.00869942, 14.70726204, 0.56742448]), + 'camera_rotation': array([-3.13771367, -7.33746433, -3.97792411]), + 'current_gear_input': False, + 'focus_actor_dist': 1511.0020751953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -579.57104492, -3198.57617188, 51.26105499]), + 'frame': 17425, + 'frame_number': 17425, + 'framesequence': 67271, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05546434223651886, + 'throttle_input': 0.0, + 'timestamp': 569.9604896791279, + 'timestamp_carla': 569962, + 'timestamp_device': 3723397, + 'timestamp_stream': 569.9604896791279, + 'transform': [array([4.49993086e+00, 1.09061317e+01, 6.49202336e-03]), + array([ -0.05391068, -12.88447094, 0.01484007])]} +{'AngularVelocity': array([ 1.03425728e-02, -2.53691256e-01, -9.87397243e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4809783101081848, + 'FR_Wheel_Angle': 0.4832284450531006, + 'Location': array([ -5.134758 , -21.1652832 , 0.17538871]), + 'Rotation': array([-1.32505655e-01, 6.81923628e+00, -5.79833053e-04]), + 'Velocity': array([-1.70890140e-04, -2.14563261e-05, 4.69109102e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.0441494 , 14.93225479, 0.58142388]), + 'camera_rotation': array([-3.08509374, -5.91373444, -3.86512232]), + 'current_gear_input': False, + 'focus_actor_dist': 2152.0302734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -653.15002441, -3842.86914062, 17.4189682 ]), + 'frame': 17426, + 'frame_number': 17426, + 'framesequence': 67274, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06015198677778244, + 'throttle_input': 0.0, + 'timestamp': 569.9909890778363, + 'timestamp_carla': 569992, + 'timestamp_device': 3723422, + 'timestamp_stream': 569.9909890778363, + 'transform': [array([4.46230936e+00, 1.08578138e+01, 6.86010346e-03]), + array([ -0.05389702, -12.81030846, 0.01421899])]} +{'AngularVelocity': array([ 7.54899299e-03, -1.06195748e-01, -1.86517209e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4809790551662445, + 'FR_Wheel_Angle': 0.48322951793670654, + 'Location': array([ -5.13446093, -21.16526031, 0.17513283]), + 'Rotation': array([-8.68799984e-02, 6.81931543e+00, 1.85179035e-03]), + 'Velocity': array([-7.10894528e-05, -9.13333952e-06, -1.09772780e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.07617378, 15.13339138, 0.57883346]), + 'camera_rotation': array([-3.10290694, -4.58802843, -3.69296813]), + 'current_gear_input': False, + 'focus_actor_dist': 2188.572265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -602.95849609, -3895.32641602, 17.36705017]), + 'frame': 17427, + 'frame_number': 17427, + 'framesequence': 67278, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06416212022304535, + 'throttle_input': 0.0, + 'timestamp': 570.0255898758769, + 'timestamp_carla': 570027, + 'timestamp_device': 3723455, + 'timestamp_stream': 570.0255898758769, + 'transform': [array([4.41745758e+00, 1.08043804e+01, 7.20222434e-03]), + array([ -0.05389702, -12.72127914, 0.01357424])]} +{'AngularVelocity': array([ 2.10337690e-03, -3.14697959e-02, -1.50992119e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4822494387626648, + 'FR_Wheel_Angle': 0.48451170325279236, + 'Location': array([ -5.13438082, -21.16525269, 0.17507893]), + 'Rotation': array([-7.46744573e-02, 6.81939030e+00, 2.47584586e-03]), + 'Velocity': array([-1.83813045e-05, -2.62724006e-06, 8.51666788e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.13064766, 15.36019897, 0.56664217]), + 'camera_rotation': array([-3.19879603, -3.10920596, -3.7096467 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2175.73095703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -548.34448242, -3895.83349609, 17.31090546]), + 'frame': 17428, + 'frame_number': 17428, + 'framesequence': 67283, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06835535913705826, + 'throttle_input': 0.0, + 'timestamp': 570.0590403787792, + 'timestamp_carla': 570060, + 'timestamp_device': 3723497, + 'timestamp_stream': 570.0590403787792, + 'transform': [array([4.37218285e+00, 1.07540283e+01, 7.50337588e-03]), + array([ -0.05393117, -12.63086605, 0.01303366])]} +{'AngularVelocity': array([-4.31980588e-05, -2.77554453e-03, -1.46273451e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -5.1333847 , -21.16514206, 0.17499305]), + 'Rotation': array([-7.02826455e-02, 6.81948090e+00, 2.71351729e-03]), + 'Velocity': array([ 0.0058762 , 0.00069937, -0.00013542]), + 'brake_input': 0.0, + 'camera_location': array([-5.18066311, 15.62531948, 0.55026788]), + 'camera_rotation': array([-3.3182013 , -1.58887815, -3.92369366]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.034423828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -482.46972656, -3843.63427734, 17.2435379 ]), + 'frame': 17429, + 'frame_number': 17429, + 'framesequence': 67287, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07220069319009781, + 'throttle_input': 0.0, + 'timestamp': 570.0923444777727, + 'timestamp_carla': 570093, + 'timestamp_device': 3723530, + 'timestamp_stream': 570.0923444777727, + 'transform': [array([4.32539892e+00, 1.07051125e+01, 7.75985699e-03]), + array([ -0.05402679, -12.53696156, 0.01257822])]} +{'AngularVelocity': array([ 0.00156722, -0.00099054, 0.00894032]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.4244701862335205, + 'FR_Wheel_Angle': 2.994168281555176, + 'Location': array([ -5.1322093 , -21.16498947, 0.17503643]), + 'Rotation': array([-6.99206442e-02, 6.81993246e+00, 2.72199488e-03]), + 'Velocity': array([ 0.00286409, 0.00060638, -0.00038328]), + 'brake_input': 0.0, + 'camera_location': array([-5.2258215 , 15.91288376, 0.54698455]), + 'camera_rotation': array([-3.37081432, -0.02842887, -3.9844377 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2033.697509765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -417.64352417, -3778.68481445, 17.17728424]), + 'frame': 17430, + 'frame_number': 17430, + 'framesequence': 67290, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07492905110120773, + 'throttle_input': 0.0, + 'timestamp': 570.125489179045, + 'timestamp_carla': 570127, + 'timestamp_device': 3723555, + 'timestamp_stream': 570.125489179045, + 'transform': [array([4.27775240e+00, 1.06574841e+01, 7.96335191e-03]), + array([-5.42590208e-02, -1.24409246e+01, 1.22235743e-02])]} +{'AngularVelocity': array([-0.02250407, 0.00579944, -0.10110496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.453436374664307, + 'FR_Wheel_Angle': 6.24206018447876, + 'Location': array([ -5.13100004, -21.16481972, 0.17498146]), + 'Rotation': array([-6.94630221e-02, 6.82076883e+00, 2.78060720e-03]), + 'Velocity': array([ 0.00339142, -0.00175895, 0.00059785]), + 'brake_input': 0.0, + 'camera_location': array([-5.24787712, 16.1934433 , 0.54781741]), + 'camera_rotation': array([-3.370507 , 1.48659766, -3.84266376]), + 'current_gear_input': False, + 'focus_actor_dist': 2001.805419921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -357.44793701, -3756.25146484, 17.11554718]), + 'frame': 17431, + 'frame_number': 17431, + 'framesequence': 67294, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07659535109996796, + 'throttle_input': 0.0, + 'timestamp': 570.1574772782624, + 'timestamp_carla': 570159, + 'timestamp_device': 3723588, + 'timestamp_stream': 570.1574772782624, + 'transform': [array([4.23132133e+00, 1.06123352e+01, 8.11857171e-03]), + array([-5.46415113e-02, -1.23470592e+01, 1.19723985e-02])]} diff --git a/PythonAPI/data/trials/trial10.txt b/PythonAPI/data/trials/trial10.txt new file mode 100644 index 0000000..fa8c863 --- /dev/null +++ b/PythonAPI/data/trials/trial10.txt @@ -0,0 +1,11798 @@ +{'AngularVelocity': array([-1.95728662e-05, 6.30715886e-06, 9.37957793e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.41052723, -31.86808777, 0.17172442]), + 'Rotation': array([-1.93772465e-02, 8.40792542e+01, -6.19201697e-02]), + 'Velocity': array([ 5.33104867e-06, -2.77142021e-07, -1.64105877e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.43063354, 13.82787704, 2.05153179]), + 'camera_rotation': array([-8.54923153, 2.76674247, 0.66940075]), + 'current_gear_input': False, + 'focus_actor_dist': 2095.839111328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -449.45285034, -1104.72363281, 16.9728775 ]), + 'frame': 15009, + 'frame_number': 15009, + 'framesequence': 57615, + 'gaze_dir': array([0.97136688, 0.22098541, 0.08638763]), + 'gaze_origin': array([-3.0761919 , -0.20557177, 0.09487992]), + 'gaze_valid': True, + 'gaze_vergence': 253.64772033691406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96864319, 0.23147583, 0.09011841]), + 'left_gaze_origin': array([-3.0165329 , 2.98408985, 0.10196534]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1434173583984375, + 'left_pupil_posn': array([ 0.24499142, -0.02203894]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9642746448516846, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97409058, 0.210495 , 0.08265686]), + 'right_gaze_origin': array([-3.13585067, -3.39523339, 0.0877945 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0443572998046875, + 'right_pupil_posn': array([ 0.22211885, -0.09352076]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0032593768555670977, + 'throttle_input': 0.0, + 'timestamp': 490.8339335657656, + 'timestamp_carla': 490834, + 'timestamp_device': 4229047, + 'timestamp_stream': 490.8339335657656, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.82898271e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([-1.99995848e-05, 6.53738152e-06, 9.51606944e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.2894950807094574, + 'Location': array([ -2.41052723, -31.86808777, 0.17171444]), + 'Rotation': array([-1.93772465e-02, 8.40792542e+01, -6.19201697e-02]), + 'Velocity': array([ 5.02643161e-06, -2.71773814e-07, -3.76915064e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.44353962, 13.84822464, 2.0321877 ]), + 'camera_rotation': array([-8.55492115, 2.80959105, 0.73421961]), + 'current_gear_input': False, + 'focus_actor_dist': 1943.0457763671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -536.68151855, -1271.7833252 , 17.1037674 ]), + 'frame': 15010, + 'frame_number': 15010, + 'framesequence': 57619, + 'gaze_dir': array([0.97259521, 0.21630096, 0.08464813]), + 'gaze_origin': array([-3.07511544, -0.20570222, 0.09601441]), + 'gaze_valid': True, + 'gaze_vergence': 335.658203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9707489 , 0.22515869, 0.08323669]), + 'left_gaze_origin': array([-3.01565099, 2.98575759, 0.10285493]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.144012451171875, + 'left_pupil_posn': array([ 0.24277008, -0.02011287]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9777392148971558, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97444153, 0.20744324, 0.08605957]), + 'right_gaze_origin': array([-3.13457966, -3.39716196, 0.08917389]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0199432373046875, + 'right_pupil_posn': array([ 0.22114277, -0.09450924]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0032593768555670977, + 'throttle_input': 0.0, + 'timestamp': 490.86735696718097, + 'timestamp_carla': 490868, + 'timestamp_device': 4229081, + 'timestamp_stream': 490.86735696718097, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.83039460e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([ 0.07104685, -0.00501272, 0.0138941 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.8209789395332336, + 'FR_Wheel_Angle': 1.0031731128692627, + 'Location': array([ -2.41038775, -31.86709404, 0.17173481]), + 'Rotation': array([-1.90084148e-02, 8.40790634e+01, -6.19201586e-02]), + 'Velocity': array([0.00477152, 0.04672106, 0.00012088]), + 'brake_input': 0.0, + 'camera_location': array([-6.45479488, 13.86683846, 2.02477837]), + 'camera_rotation': array([-8.6125946 , 2.8848567 , 0.77624947]), + 'current_gear_input': False, + 'focus_actor_dist': 1875.9996337890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -518.06890869, -1336.77416992, 17.10147095]), + 'frame': 15011, + 'frame_number': 15011, + 'framesequence': 57623, + 'gaze_dir': array([0.97283936, 0.21508789, 0.08464813]), + 'gaze_origin': array([-3.0750246 , -0.20509416, 0.09728318]), + 'gaze_valid': True, + 'gaze_vergence': 273.42266845703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9704895 , 0.22612 , 0.08364868]), + 'left_gaze_origin': array([-3.01547408, 2.98706675, 0.10429841]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1370697021484375, + 'left_pupil_posn': array([ 0.24070704, -0.01916301]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9827861189842224, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97518921, 0.20405579, 0.08564758]), + 'right_gaze_origin': array([-3.13457513, -3.39725494, 0.09026795]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.036376953125, + 'right_pupil_posn': array([ 0.22151601, -0.09374237]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0032593768555670977, + 'throttle_input': 0.0, + 'timestamp': 490.89974876865745, + 'timestamp_carla': 490900, + 'timestamp_device': 4229114, + 'timestamp_stream': 490.89974876865745, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.83859582e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([ 0.06714968, 0.001849 , -0.23263068]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.9050817489624023, + 'FR_Wheel_Angle': 3.4467601776123047, + 'Location': array([ -2.40771365, -31.83405495, 0.17164943]), + 'Rotation': array([-7.39026442e-03, 8.40798569e+01, -6.31713793e-02]), + 'Velocity': array([2.40633655e-02, 3.30529690e-01, 2.05011369e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.46154976, 13.88698769, 2.02673817]), + 'camera_rotation': array([-8.58902359, 2.97318006, 0.81594592]), + 'current_gear_input': False, + 'focus_actor_dist': 1842.39013671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -512.81994629, -1370.04821777, 17.10471344]), + 'frame': 15012, + 'frame_number': 15012, + 'framesequence': 57627, + 'gaze_dir': array([0.97281647, 0.21529388, 0.08447266]), + 'gaze_origin': array([-3.07481337, -0.20472184, 0.0977684 ]), + 'gaze_valid': True, + 'gaze_vergence': 287.3189392089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97050476, 0.22584534, 0.084198 ]), + 'left_gaze_origin': array([-3.01504993, 2.98794127, 0.10473786]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.14947509765625, + 'left_pupil_posn': array([ 0.24033248, -0.01911783]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9708263874053955, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97512817, 0.20474243, 0.08474731]), + 'right_gaze_origin': array([-3.13457656, -3.39738464, 0.09079896]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0385284423828125, + 'right_pupil_posn': array([ 0.22151601, -0.09318781]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0032593768555670977, + 'throttle_input': 0.0, + 'timestamp': 490.93260706588626, + 'timestamp_carla': 490933, + 'timestamp_device': 4229147, + 'timestamp_stream': 490.93260706588626, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.83989315e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([0.05859201, 0.02708151, 1.53782701]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.773976802825928, + 'FR_Wheel_Angle': 6.48214054107666, + 'Location': array([ -2.39900255, -31.69768906, 0.17158195]), + 'Rotation': array([ 4.07762267e-03, 8.42781143e+01, -6.71386644e-02]), + 'Velocity': array([ 3.60930078e-02, 8.49665642e-01, -2.03647607e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.47248936, 13.90017033, 2.03097749]), + 'camera_rotation': array([-8.57539082, 3.02461672, 0.87430346]), + 'current_gear_input': False, + 'focus_actor_dist': 1844.7161865234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -516.49816895, -1368.30432129, 17.10805511]), + 'frame': 15013, + 'frame_number': 15013, + 'framesequence': 57631, + 'gaze_dir': array([0.97271729, 0.21577454, 0.08449554]), + 'gaze_origin': array([-3.07473612, -0.20438996, 0.09769669]), + 'gaze_valid': True, + 'gaze_vergence': 307.1990661621094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97050476, 0.2256012 , 0.08494568]), + 'left_gaze_origin': array([-3.01481795, 2.98871779, 0.10450441]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1453094482421875, + 'left_pupil_posn': array([ 0.24021637, -0.01950562]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9802278876304626, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97492981, 0.20594788, 0.08404541]), + 'right_gaze_origin': array([-3.13465452, -3.39749765, 0.09088898]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.03717041015625, + 'right_pupil_posn': array([ 0.22151601, -0.0928874 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0032593768555670977, + 'throttle_input': 0.0, + 'timestamp': 490.96726436540484, + 'timestamp_carla': 490968, + 'timestamp_device': 4229181, + 'timestamp_stream': 490.96726436540484, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.82657990e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([-0.00659746, 0.01603385, 4.18221331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.091135025024414, + 'FR_Wheel_Angle': 9.141563415527344, + 'Location': array([ -2.38851166, -31.42404556, 0.17152305]), + 'Rotation': array([ 1.34691326e-02, 8.49946060e+01, -7.44323656e-02]), + 'Velocity': array([9.96900350e-03, 1.47904718e+00, 1.52301785e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.48087788, 13.90766144, 2.04476047]), + 'camera_rotation': array([-8.56627274, 3.08568811, 0.97602737]), + 'current_gear_input': False, + 'focus_actor_dist': 1846.0517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -519.41021729, -1367.44799805, 17.11073303]), + 'frame': 15014, + 'frame_number': 15014, + 'framesequence': 57635, + 'gaze_dir': array([0.97307587, 0.2144165 , 0.0838623 ]), + 'gaze_origin': array([-3.07457066, -0.20380938, 0.0976822 ]), + 'gaze_valid': True, + 'gaze_vergence': 312.2646789550781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97088623, 0.22402954, 0.0847168 ]), + 'left_gaze_origin': array([-3.01439214, 2.99016595, 0.10450441]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1385650634765625, + 'left_pupil_posn': array([ 0.23882914, -0.01974094]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9752655 , 0.20480347, 0.08300781]), + 'right_gaze_origin': array([-3.13474917, -3.39778471, 0.09085999]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.02398681640625, + 'right_pupil_posn': array([ 0.22115588, -0.09296548]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0032776880543679, + 'throttle_input': 0.0, + 'timestamp': 490.9996684677899, + 'timestamp_carla': 491000, + 'timestamp_device': 4229214, + 'timestamp_stream': 490.9996684677899, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.83607846e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([-3.34150493e-02, 3.91905429e-03, 7.61579370e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.772391319274902, + 'FR_Wheel_Angle': 10.984567642211914, + 'Location': array([ -2.38746834, -30.9953289 , 0.17151146]), + 'Rotation': array([ 1.68159250e-02, 8.63638840e+01, -8.20007324e-02]), + 'Velocity': array([-7.29428530e-02, 2.12135005e+00, -6.70433001e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.49590111, 13.92470169, 2.0485363 ]), + 'camera_rotation': array([-8.53489494, 3.12830329, 0.90607524]), + 'current_gear_input': False, + 'focus_actor_dist': 1821.3878173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -514.94372559, -1391.76721191, 17.11241913]), + 'frame': 15015, + 'frame_number': 15015, + 'framesequence': 57639, + 'gaze_dir': array([0.97338867, 0.21257019, 0.08498383]), + 'gaze_origin': array([-3.07452488, -0.20293275, 0.09609833]), + 'gaze_valid': True, + 'gaze_vergence': 348.4913635253906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97154236, 0.2212677 , 0.0843811 ]), + 'left_gaze_origin': array([-3.01418781, 2.99191904, 0.10139924]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1337890625, + 'left_pupil_posn': array([ 0.23733366, -0.02085984]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9728735685348511, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97523499, 0.20387268, 0.08558655]), + 'right_gaze_origin': array([-3.13486195, -3.39778471, 0.09079742]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0431976318359375, + 'right_pupil_posn': array([ 0.22016633, -0.09308672]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0034241769462823868, + 'throttle_input': 0.0, + 'timestamp': 491.03499756753445, + 'timestamp_carla': 491035, + 'timestamp_device': 4229247, + 'timestamp_stream': 491.03499756753445, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.81898869e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([ 0.01395254, -0.022617 , 8.21872425]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.842103958129883, + 'FR_Wheel_Angle': 9.02597427368164, + 'Location': array([ -2.40557313, -30.42960167, 0.17155594]), + 'Rotation': array([ 1.63719617e-02, 8.83170013e+01, -8.19091722e-02]), + 'Velocity': array([-1.63564488e-01, 2.69895887e+00, 3.33499884e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.49910069, 13.93425941, 2.04527497]), + 'camera_rotation': array([-8.54029751, 3.1626966 , 0.91574228]), + 'current_gear_input': False, + 'focus_actor_dist': 1875.327880859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -521.70117188, -1338.09912109, 17.10554504]), + 'frame': 15016, + 'frame_number': 15016, + 'framesequence': 57643, + 'gaze_dir': array([0.97360229, 0.21211243, 0.08364105]), + 'gaze_origin': array([-3.07411051, -0.20222473, 0.09595261]), + 'gaze_valid': True, + 'gaze_vergence': 321.506591796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97160339, 0.22154236, 0.08302307]), + 'left_gaze_origin': array([-3.01335931, 2.99257064, 0.10108643]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.104888916015625, + 'left_pupil_posn': array([ 0.23647237, -0.02132034]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.976303219795227, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9756012 , 0.2026825 , 0.08425903]), + 'right_gaze_origin': array([-3.13486195, -3.39701986, 0.09081879]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0426788330078125, + 'right_pupil_posn': array([ 0.21974123, -0.0935241 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00377208786085248, + 'throttle_input': 0.0, + 'timestamp': 491.067050665617, + 'timestamp_carla': 491067, + 'timestamp_device': 4229281, + 'timestamp_stream': 491.067050665617, + 'transform': [array([ 4.16224509e-01, -1.88662186e+01, 8.83440021e-03]), + array([-0.06192249, -5.92078352, 0.01937868])]} +{'AngularVelocity': array([-0.07950372, -0.06624329, 4.42860746]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.446921348571777, + 'FR_Wheel_Angle': 3.960927724838257, + 'Location': array([ -2.43188739, -29.76749611, 0.17166263]), + 'Rotation': array([ 4.55573574e-03, 8.98697357e+01, -6.40563890e-02]), + 'Velocity': array([-1.27324373e-01, 2.91589379e+00, 8.02898358e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.50628471, 13.94438171, 2.03557229]), + 'camera_rotation': array([-8.53908825, 3.16319346, 0.93295521]), + 'current_gear_input': False, + 'focus_actor_dist': 1832.6787109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -514.85388184, -1380.28601074, 17.10940552]), + 'frame': 15017, + 'frame_number': 15017, + 'framesequence': 57647, + 'gaze_dir': array([0.9737854 , 0.21169281, 0.08261108]), + 'gaze_origin': array([-3.07349634, -0.20192337, 0.0960495 ]), + 'gaze_valid': True, + 'gaze_vergence': 349.8011779785156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97193909, 0.22036743, 0.0821228 ]), + 'left_gaze_origin': array([-3.01213098, 2.99283314, 0.10108643]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1075286865234375, + 'left_pupil_posn': array([ 0.23639524, -0.02148592]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9622461795806885, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97563171, 0.20301819, 0.08309937]), + 'right_gaze_origin': array([-3.13486195, -3.39667988, 0.09101258]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.042083740234375, + 'right_pupil_posn': array([ 0.219069 , -0.09370148]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004138309974223375, + 'throttle_input': 0.0238040741533041, + 'timestamp': 491.1006707660854, + 'timestamp_carla': 491101, + 'timestamp_device': 4229314, + 'timestamp_stream': 491.1006707660854, + 'transform': [array([ 4.16288137e-01, -1.88660526e+01, 8.91475659e-03]), + array([-0.06192249, -5.92096376, 0.01901246])]} +{'AngularVelocity': array([-0.06443192, 0.02025955, 0.00102526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.44484997, -29.10588837, 0.17179489]), + 'Rotation': array([-1.44595094e-02, 9.03224640e+01, -4.81567346e-02]), + 'Velocity': array([-1.52917597e-02, 2.74486804e+00, -1.02920530e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.51508999, 13.96507454, 2.03188062]), + 'camera_rotation': array([-8.56803513, 3.12691045, 0.8885572 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1802.6370849609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -509.13980103, -1409.85717773, 17.11118317]), + 'frame': 15018, + 'frame_number': 15018, + 'framesequence': 57652, + 'gaze_dir': array([0.97401428, 0.21081543, 0.0821991 ]), + 'gaze_origin': array([-3.07274938, -0.20192415, 0.09631272]), + 'gaze_valid': True, + 'gaze_vergence': 343.00103759765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97213745, 0.21966553, 0.08172607]), + 'left_gaze_origin': array([-3.01073766, 2.99283147, 0.10115204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.107269287109375, + 'left_pupil_posn': array([ 0.23600674, -0.02132034]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9830532073974609, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97589111, 0.20196533, 0.08267212]), + 'right_gaze_origin': array([-3.13476133, -3.39667988, 0.09147339]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.042938232421875, + 'right_pupil_posn': array([ 0.2188201 , -0.09350073]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004632710013538599, + 'throttle_input': 0.09919890016317368, + 'timestamp': 491.1372277662158, + 'timestamp_carla': 491138, + 'timestamp_device': 4229356, + 'timestamp_stream': 491.1372277662158, + 'transform': [array([ 4.16303396e-01, -1.88659782e+01, 8.88835918e-03]), + array([-0.06192249, -5.92096376, 0.01901246])]} +{'AngularVelocity': array([-0.01509769, 0.02519012, -0.02607007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 1.3509732484817505, + 'Location': array([ -2.44804358, -28.49396706, 0.17185695]), + 'Rotation': array([-2.27991696e-02, 9.03225632e+01, -5.74340709e-02]), + 'Velocity': array([-1.27103049e-02, 2.49463916e+00, -1.23929975e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.51698685, 13.98333549, 2.03622413]), + 'camera_rotation': array([-8.58572483, 3.14121747, 0.94456732]), + 'current_gear_input': False, + 'focus_actor_dist': 1782.407470703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -502.99133301, -1429.36914062, 17.1099472 ]), + 'frame': 15019, + 'frame_number': 15019, + 'framesequence': 57655, + 'gaze_dir': array([0.97392273, 0.21107483, 0.08242035]), + 'gaze_origin': array([-3.07211995, -0.20221177, 0.09667283]), + 'gaze_valid': True, + 'gaze_vergence': 314.7502746582031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97184753, 0.22073364, 0.0821991 ]), + 'left_gaze_origin': array([-3.00947905, 2.99249887, 0.10174867]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1211395263671875, + 'left_pupil_posn': array([ 0.23600674, -0.02070963]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9758414030075073, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97599792, 0.20141602, 0.0826416 ]), + 'right_gaze_origin': array([-3.13476133, -3.39692235, 0.09159699]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0538177490234375, + 'right_pupil_posn': array([ 0.21936238, -0.09329772]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005328531842678785, + 'throttle_input': 0.1428549587726593, + 'timestamp': 491.16860956698656, + 'timestamp_carla': 491169, + 'timestamp_device': 4229381, + 'timestamp_stream': 491.16860956698656, + 'transform': [array([ 4.16328728e-01, -1.88657970e+01, 8.91372655e-03]), + array([-0.06192249, -5.92096376, 0.01901246])]} +{'AngularVelocity': array([0.0042307 , 0.02983121, 3.77550435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.052444934844971, + 'FR_Wheel_Angle': 6.080061435699463, + 'Location': array([ -2.46513557, -27.94032478, 0.17190552]), + 'Rotation': array([-2.35300008e-02, 9.08675842e+01, -7.57751390e-02]), + 'Velocity': array([-1.43465936e-01, 2.25425935e+00, 5.02014154e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.52837563, 14.00557137, 2.04188776]), + 'camera_rotation': array([-8.58265781, 3.21377254, 1.08970416]), + 'current_gear_input': False, + 'focus_actor_dist': 1775.064453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -502.85412598, -1436.79675293, 17.11164093]), + 'frame': 15020, + 'frame_number': 15020, + 'framesequence': 57659, + 'gaze_dir': array([0.97386932, 0.21076965, 0.08384705]), + 'gaze_origin': array([-3.07184696, -0.20224382, 0.09675675]), + 'gaze_valid': True, + 'gaze_vergence': 292.4546203613281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97163391, 0.22116089, 0.08366394]), + 'left_gaze_origin': array([-3.00887322, 2.99243474, 0.10174867]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.12188720703125, + 'left_pupil_posn': array([ 0.23568726, -0.02010107]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9636358618736267, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97610474, 0.20037842, 0.08403015]), + 'right_gaze_origin': array([-3.1348207 , -3.39692235, 0.09176484]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.055328369140625, + 'right_pupil_posn': array([ 0.21952832, -0.09266591]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0061525315977633, + 'throttle_input': 0.17062638700008392, + 'timestamp': 491.2005223669112, + 'timestamp_carla': 491201, + 'timestamp_device': 4229414, + 'timestamp_stream': 491.2005223669112, + 'transform': [array([ 4.16353285e-01, -1.88656235e+01, 8.92547611e-03]), + array([-0.06192249, -5.92096376, 0.01901246])]} +{'AngularVelocity': array([ 0.01166497, -0.01857834, 5.64725685]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.154867172241211, + 'FR_Wheel_Angle': 8.90114688873291, + 'Location': array([ -2.49839354, -27.51165962, 0.17195782]), + 'Rotation': array([-2.19044164e-02, 9.18752365e+01, -7.92541429e-02]), + 'Velocity': array([-2.33985528e-01, 2.06122041e+00, 1.41992568e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.52074432, 14.03848648, 2.04296875]), + 'camera_rotation': array([-8.51515579, 3.31108117, 1.12897861]), + 'current_gear_input': False, + 'focus_actor_dist': 1800.4503173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -509.15045166, -1412.04418945, 17.11174774]), + 'frame': 15021, + 'frame_number': 15021, + 'framesequence': 57663, + 'gaze_dir': array([0.97429657, 0.20877075, 0.08353424]), + 'gaze_origin': array([-3.07178521, -0.20212936, 0.09689561]), + 'gaze_valid': True, + 'gaze_vergence': 234.75123596191406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97163391, 0.22166443, 0.08236694]), + 'left_gaze_origin': array([-3.00854826, 2.99243474, 0.10174867]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1255645751953125, + 'left_pupil_posn': array([ 0.23411334, -0.01974893]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9692206382751465, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97695923, 0.19587708, 0.08470154]), + 'right_gaze_origin': array([-3.13502216, -3.39669371, 0.09204254]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.079803466796875, + 'right_pupil_posn': array([ 0.21952832, -0.09302783]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007507553789764643, + 'throttle_input': 0.18649576604366302, + 'timestamp': 491.2342567667365, + 'timestamp_carla': 491235, + 'timestamp_device': 4229447, + 'timestamp_stream': 491.2342567667365, + 'transform': [array([ 4.16376472e-01, -1.88654652e+01, 8.91891494e-03]), + array([-0.06192249, -5.92096376, 0.01901246])]} +{'AngularVelocity': array([-0.00479913, -0.04354312, 3.83628392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.208034992218018, + 'FR_Wheel_Angle': 7.410739421844482, + 'Location': array([ -2.55553269, -26.99456215, 0.17203739]), + 'Rotation': array([-1.96504537e-02, 9.33059464e+01, -6.75048679e-02]), + 'Velocity': array([-2.38724068e-01, 1.80595362e+00, 3.52048868e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.51753235, 14.06194115, 2.04576731]), + 'camera_rotation': array([-8.48893452, 3.38736629, 1.21512818]), + 'current_gear_input': False, + 'focus_actor_dist': 1818.7755126953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -511.68676758, -1393.81506348, 17.10962677]), + 'frame': 15022, + 'frame_number': 15022, + 'framesequence': 57667, + 'gaze_dir': array([0.9764328 , 0.19418335, 0.09282684]), + 'gaze_origin': array([-3.06063628, -0.18868944, 0.09948884]), + 'gaze_valid': True, + 'gaze_vergence': 198.11878967285156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97387695, 0.20881653, 0.08905029]), + 'left_gaze_origin': array([-2.9930954 , 3.00452137, 0.10213166]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1168670654296875, + 'left_pupil_posn': array([ 0.22004735, -0.0124234 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9418441653251648, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97898865, 0.17955017, 0.09660339]), + 'right_gaze_origin': array([-3.12817693, -3.38190007, 0.09684601]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.158538818359375, + 'right_pupil_posn': array([ 0.20462418, -0.08595812]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.009302042424678802, + 'throttle_input': 0.20236514508724213, + 'timestamp': 491.26670636609197, + 'timestamp_carla': 491267, + 'timestamp_device': 4229481, + 'timestamp_stream': 491.26670636609197, + 'transform': [array([ 4.16406542e-01, -1.88652344e+01, 8.92387331e-03]), + array([-0.06192249, -5.92096376, 0.01901246])]} +{'AngularVelocity': array([ 0.02350775, -0.00985559, 2.0170188 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.895369052886963, + 'FR_Wheel_Angle': 4.8538618087768555, + 'Location': array([ -2.60136127, -26.59722328, 0.1720943 ]), + 'Rotation': array([-1.68159250e-02, 9.41508331e+01, -6.00280762e-02]), + 'Velocity': array([-2.00480014e-01, 1.63105345e+00, 4.84323478e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.51556683, 14.08091164, 2.02253866]), + 'camera_rotation': array([-8.54619884, 3.39763117, 1.26241839]), + 'current_gear_input': False, + 'focus_actor_dist': 2119.170654296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -533.75976562, -1092.49389648, 17.05503845]), + 'frame': 15023, + 'frame_number': 15023, + 'framesequence': 57671, + 'gaze_dir': array([0.97497559, 0.19523621, 0.10467529]), + 'gaze_origin': array([-3.06474257, -0.18847962, 0.10895997]), + 'gaze_valid': True, + 'gaze_vergence': 160.2261505126953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97232056, 0.21203613, 0.09803772]), + 'left_gaze_origin': array([-3.0000062 , 3.00215459, 0.11113892]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.14434814453125, + 'left_pupil_posn': array([ 0.22143972, -0.00260496]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97763062, 0.17843628, 0.11131287]), + 'right_gaze_origin': array([-3.12947845, -3.37911391, 0.10678101]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1460723876953125, + 'right_pupil_posn': array([ 0.20400941, -0.07637274]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011828974820673466, + 'throttle_input': 0.23015183210372925, + 'timestamp': 491.3003652654588, + 'timestamp_carla': 491301, + 'timestamp_device': 4229514, + 'timestamp_stream': 491.3003652654588, + 'transform': [array([ 4.16410506e-01, -1.88649426e+01, 8.93148407e-03]), + array([-0.06192249, -5.9208312 , 0.01895143])]} +{'AngularVelocity': array([0.05771915, 0.01183185, 1.08624458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.2549118995666504, + 'FR_Wheel_Angle': 3.196106433868408, + 'Location': array([ -2.64265823, -26.22113228, 0.17210174]), + 'Rotation': array([-8.14841501e-03, 9.46708145e+01, -5.93872033e-02]), + 'Velocity': array([-1.88130379e-01, 1.64416611e+00, 4.84461780e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.52661514, 14.09791756, 2.00012374]), + 'camera_rotation': array([-8.68739891, 3.41905189, 1.27302814]), + 'current_gear_input': False, + 'focus_actor_dist': 2991.449462890625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-671.62664795, -230.88427734, 0. ]), + 'frame': 15024, + 'frame_number': 15024, + 'framesequence': 57675, + 'gaze_dir': array([0.97465515, 0.19632721, 0.10598755]), + 'gaze_origin': array([-3.06151986, -0.18762361, 0.10989762]), + 'gaze_valid': True, + 'gaze_vergence': 194.16842651367188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97192383, 0.21157837, 0.10287476]), + 'left_gaze_origin': array([-2.99316716, 3.00494862, 0.11233521]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.121002197265625, + 'left_pupil_posn': array([ 0.22043312, -0.00116038]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97738647, 0.18107605, 0.10910034]), + 'right_gaze_origin': array([-3.12987232, -3.38019586, 0.10746003]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1428985595703125, + 'right_pupil_posn': array([ 0.20461428, -0.0743897 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.014337596483528614, + 'throttle_input': 0.2658579349517822, + 'timestamp': 491.33323296532035, + 'timestamp_carla': 491334, + 'timestamp_device': 4229547, + 'timestamp_stream': 491.33323296532035, + 'transform': [array([ 4.16409433e-01, -1.88644981e+01, 8.96789506e-03]), + array([-0.06192249, -5.92061234, 0.01879884])]} +{'AngularVelocity': array([0.07675495, 0.01204625, 0.77291387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9741730690002441, + 'FR_Wheel_Angle': 1.7803772687911987, + 'Location': array([ -2.6806314 , -25.86313248, 0.17207386]), + 'Rotation': array([ 6.20181160e-03, 9.49995422e+01, -6.03332445e-02]), + 'Velocity': array([-2.12208480e-01, 1.94614601e+00, 6.91127789e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.54072285, 14.11151886, 1.9835813 ]), + 'camera_rotation': array([-8.79899025, 3.53397226, 1.26985383]), + 'current_gear_input': False, + 'focus_actor_dist': 2919.370849609375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.64943115e+02, -3.02848389e+02, 1.67846680e-04]), + 'frame': 15025, + 'frame_number': 15025, + 'framesequence': 57679, + 'gaze_dir': array([0.97455597, 0.19620514, 0.10722351]), + 'gaze_origin': array([-3.0602715 , -0.1856842 , 0.11087724]), + 'gaze_valid': True, + 'gaze_vergence': 193.68142700195312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97232056, 0.21022034, 0.10185242]), + 'left_gaze_origin': array([-2.99091649, 3.00831628, 0.11310884]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1316986083984375, + 'left_pupil_posn': array([0.21842921, 0.00068021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97679138, 0.18218994, 0.1125946 ]), + 'right_gaze_origin': array([-3.12962651, -3.37968469, 0.10864563]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1414947509765625, + 'right_pupil_posn': array([ 0.20377123, -0.07385135]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.017194129526615143, + 'throttle_input': 0.29364460706710815, + 'timestamp': 491.36659866571426, + 'timestamp_carla': 491367, + 'timestamp_device': 4229581, + 'timestamp_stream': 491.36659866571426, + 'transform': [array([ 4.16343987e-01, -1.88636150e+01, 9.08115413e-03]), + array([-0.06194981, -5.91992712, 0.01828004])]} +{'AngularVelocity': array([ 0.0281611, -0.0316646, -0.7708503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.30098336935043335, + 'FR_Wheel_Angle': -0.7290727496147156, + 'Location': array([ -2.73962355, -25.26441765, 0.17209324]), + 'Rotation': array([ 1.97870564e-02, 9.52157822e+01, -5.61523363e-02]), + 'Velocity': array([-2.27152079e-01, 2.53434467e+00, 2.46877666e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.55460167, 14.13124084, 1.97716808]), + 'camera_rotation': array([-8.73390579, 3.62020278, 1.27872431]), + 'current_gear_input': False, + 'focus_actor_dist': 2879.148193359375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.64099243e+02, -3.43452393e+02, 1.98364258e-04]), + 'frame': 15026, + 'frame_number': 15026, + 'framesequence': 57683, + 'gaze_dir': array([0.97418976, 0.19770813, 0.1078186 ]), + 'gaze_origin': array([-3.05973673, -0.18456727, 0.11024094]), + 'gaze_valid': True, + 'gaze_vergence': 192.86703491210938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97224426, 0.21080017, 0.10142517]), + 'left_gaze_origin': array([-2.98988342, 3.00986052, 0.11183625]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.099884033203125, + 'left_pupil_posn': array([0.21828032, 0.00068021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97613525, 0.18461609, 0.11421204]), + 'right_gaze_origin': array([-3.12959003, -3.3789947 , 0.10864563]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1404876708984375, + 'right_pupil_posn': array([ 0.20350552, -0.07400548]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.020801417529582977, + 'throttle_input': 0.3174487054347992, + 'timestamp': 491.39912896603346, + 'timestamp_carla': 491399, + 'timestamp_device': 4229614, + 'timestamp_stream': 491.39912896603346, + 'transform': [array([ 4.16541725e-01, -1.88613319e+01, 9.42697469e-03]), + array([-0.06200445, -5.91984797, 0.01675417])]} +{'AngularVelocity': array([ 0.0099789 , -0.03424251, -3.52787018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.2053213119506836, + 'FR_Wheel_Angle': -3.5394580364227295, + 'Location': array([ -2.78926015, -24.60704041, 0.17218971]), + 'Rotation': array([ 2.45067179e-02, 9.48318024e+01, -4.68444861e-02]), + 'Velocity': array([-1.72367916e-01, 3.08611393e+00, 3.05395108e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.56617832, 14.14419746, 1.97138977]), + 'camera_rotation': array([-8.69570446, 3.58138299, 1.30957294]), + 'current_gear_input': False, + 'focus_actor_dist': 2218.446044921875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-566.66241455, -995.97094727, 35.14013672]), + 'frame': 15027, + 'frame_number': 15027, + 'framesequence': 57687, + 'gaze_dir': array([0.97451019, 0.19596863, 0.10831451]), + 'gaze_origin': array([-3.05935526, -0.18326722, 0.11004868]), + 'gaze_valid': True, + 'gaze_vergence': 214.7599639892578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97291565, 0.20727539, 0.10221863]), + 'left_gaze_origin': array([-2.98919559, 3.01060653, 0.11158296]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1311492919921875, + 'left_pupil_posn': array([0.21777213, 0.00068021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97610474, 0.18466187, 0.1144104 ]), + 'right_gaze_origin': array([-3.12951517, -3.377141 , 0.10851441]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1408233642578125, + 'right_pupil_posn': array([ 0.20098996, -0.07373548]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.025012971833348274, + 'throttle_input': 0.3333180844783783, + 'timestamp': 491.4330544658005, + 'timestamp_carla': 491433, + 'timestamp_device': 4229647, + 'timestamp_stream': 491.4330544658005, + 'transform': [array([ 4.17336255e-01, -1.88569393e+01, 1.00353425e-02]), + array([-0.06231181, -5.92175436, 0.01397707])]} +{'AngularVelocity': array([-1.75748416e-03, -7.57468268e-02, -7.85855150e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.848311901092529, + 'FR_Wheel_Angle': -7.141597270965576, + 'Location': array([ -2.81976151, -23.82591438, 0.17231235]), + 'Rotation': array([ 2.47389432e-02, 9.35872574e+01, -3.21655273e-02]), + 'Velocity': array([-9.67249181e-03, 3.61442900e+00, 2.59103777e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.56667423, 14.14990807, 1.95270538]), + 'camera_rotation': array([-8.6755352 , 3.56693578, 1.46939766]), + 'current_gear_input': False, + 'focus_actor_dist': 3056.108642578125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.94066223e+02, -1.68557373e+02, -1.52587891e-05]), + 'frame': 15028, + 'frame_number': 15028, + 'framesequence': 57691, + 'gaze_dir': array([0.97449493, 0.19566345, 0.10900116]), + 'gaze_origin': array([-3.0590508 , -0.18281557, 0.10968399]), + 'gaze_valid': True, + 'gaze_vergence': 214.67701721191406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9727478 , 0.20751953, 0.10333252]), + 'left_gaze_origin': array([-2.98887491, 3.01093602, 0.11150666]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1543426513671875, + 'left_pupil_posn': array([0.21721017, 0.00068021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97624207, 0.18380737, 0.1146698 ]), + 'right_gaze_origin': array([-3.12922668, -3.37656736, 0.10786133]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.13812255859375, + 'right_pupil_posn': array([ 0.20067716, -0.07373548]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03017670288681984, + 'throttle_input': 0.33728542923927307, + 'timestamp': 491.467353168875, + 'timestamp_carla': 491468, + 'timestamp_device': 4229681, + 'timestamp_stream': 491.467353168875, + 'transform': [array([ 4.17544991e-01, -1.88506088e+01, 1.05459020e-02]), + array([-0.06244159, -5.92031097, 0.01165773])]} +{'AngularVelocity': array([ -0.06148287, -0.1122885 , -16.02159119]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.996500015258789, + 'FR_Wheel_Angle': -12.294364929199219, + 'Location': array([ -2.79441571, -22.93127632, 0.17243522]), + 'Rotation': array([ 1.82570945e-02, 9.07836533e+01, -2.83813546e-03]), + 'Velocity': array([ 3.85301620e-01, 3.98350048e+00, -3.81469718e-08]), + 'brake_input': 0.0, + 'camera_location': array([-6.57256317, 14.13769722, 1.93676364]), + 'camera_rotation': array([-8.75643826, 3.54158759, 1.8005048 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3092.53125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-698.93426514, -131.97607422, 0. ]), + 'frame': 15029, + 'frame_number': 15029, + 'framesequence': 57695, + 'gaze_dir': array([0.97422791, 0.19534302, 0.11169434]), + 'gaze_origin': array([-3.05615711, -0.18268357, 0.10877915]), + 'gaze_valid': True, + 'gaze_vergence': 191.9564666748047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97241211, 0.20820618, 0.10502625]), + 'left_gaze_origin': array([-2.98401189, 3.01065993, 0.11037751]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1897430419921875, + 'left_pupil_posn': array([0.21686733, 0.00199431]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9760437 , 0.18247986, 0.11836243]), + 'right_gaze_origin': array([-3.1283021 , -3.37602711, 0.10718079]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.133514404296875, + 'right_pupil_posn': array([ 0.20054018, -0.07344282]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03631092607975006, + 'throttle_input': 0.3452201187610626, + 'timestamp': 491.5019541680813, + 'timestamp_carla': 491502, + 'timestamp_device': 4229714, + 'timestamp_stream': 491.5019541680813, + 'transform': [array([ 4.18743134e-01, -1.88424072e+01, 1.09836198e-02]), + array([-0.06277627, -5.92281199, 0.00964357])]} +{'AngularVelocity': array([-1.67655855e-01, -1.33862058e-02, -2.12478065e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.061878204345703, + 'FR_Wheel_Angle': -15.764388084411621, + 'Location': array([ -2.69684911, -22.14573288, 0.17249042]), + 'Rotation': array([-4.02981136e-03, 8.69836121e+01, 1.49159683e-02]), + 'Velocity': array([ 7.93185115e-01, 3.88060212e+00, -1.48705475e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.59012508, 14.14762974, 1.91738188]), + 'camera_rotation': array([-8.88296127, 3.52407408, 1.69995177]), + 'current_gear_input': False, + 'focus_actor_dist': 3108.554443359375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.01270691e+02, -1.15498291e+02, -1.52587891e-05]), + 'frame': 15030, + 'frame_number': 15030, + 'framesequence': 57699, + 'gaze_dir': array([0.97425079, 0.19493866, 0.11236572]), + 'gaze_origin': array([-3.05588174, -0.18248826, 0.10877915]), + 'gaze_valid': True, + 'gaze_vergence': 203.62469482421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97264099, 0.20675659, 0.10585022]), + 'left_gaze_origin': array([-2.98399663, 3.01100922, 0.11037751]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.178009033203125, + 'left_pupil_posn': array([0.21686733, 0.00218385]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9758606 , 0.18312073, 0.11888123]), + 'right_gaze_origin': array([-3.12776637, -3.37598586, 0.10718079]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.12298583984375, + 'right_pupil_posn': array([ 0.19999158, -0.07301271]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04292123392224312, + 'throttle_input': 0.3650568425655365, + 'timestamp': 491.5349438674748, + 'timestamp_carla': 491535, + 'timestamp_device': 4229747, + 'timestamp_stream': 491.5349438674748, + 'transform': [array([ 4.18901205e-01, -1.88321228e+01, 1.14900013e-02]), + array([-0.06317241, -5.92015409, 0.00738526])]} +{'AngularVelocity': array([ -0.09810726, 0.06597753, -21.80834961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.919137954711914, + 'FR_Wheel_Angle': -17.098432540893555, + 'Location': array([ -2.49961782, -21.29060936, 0.172328 ]), + 'Rotation': array([-3.76275107e-02, 8.18810425e+01, 6.81360532e-03]), + 'Velocity': array([ 1.11242759e+00, 3.44730425e+00, -1.64183136e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.59051704, 14.1658802 , 1.92464948]), + 'camera_rotation': array([-8.76845264, 3.60091019, 1.71587992]), + 'current_gear_input': False, + 'focus_actor_dist': 3031.610107421875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.86274475e+02, -1.90295898e+02, -1.52587891e-05]), + 'frame': 15031, + 'frame_number': 15031, + 'framesequence': 57703, + 'gaze_dir': array([0.97427368, 0.19488525, 0.11235046]), + 'gaze_origin': array([-3.05337691, -0.18128969, 0.10633698]), + 'gaze_valid': True, + 'gaze_vergence': 207.60891723632812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97296143, 0.20547485, 0.1053772 ]), + 'left_gaze_origin': array([-2.97905278, 3.01326156, 0.10549317]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0831298828125, + 'left_pupil_posn': array([2.15747833e-01, 9.28640366e-05]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97558594, 0.18429565, 0.11932373]), + 'right_gaze_origin': array([-3.12770081, -3.3758409 , 0.10718079]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1204833984375, + 'right_pupil_posn': array([ 0.19943225, -0.07313275]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.049586474895477295, + 'throttle_input': 0.3809414803981781, + 'timestamp': 491.5675128661096, + 'timestamp_carla': 491568, + 'timestamp_device': 4229780, + 'timestamp_stream': 491.5675128661096, + 'transform': [array([ 4.16132033e-01, -1.88196011e+01, 1.18703740e-02]), + array([-6.33568317e-02, -5.90372896e+00, 5.70679363e-03])]} +{'AngularVelocity': array([-6.44917712e-02, 3.47079011e-03, -2.33663826e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.793733596801758, + 'FR_Wheel_Angle': -20.09212303161621, + 'Location': array([ -2.20336771, -20.45713615, 0.17200957]), + 'Rotation': array([-5.84390946e-02, 7.60326233e+01, 4.77156788e-03]), + 'Velocity': array([ 1.40853012e+00, 2.91055560e+00, -1.65768620e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.57139683, 14.17461491, 1.93383789]), + 'camera_rotation': array([-8.79569817, 3.68007374, 1.80096114]), + 'current_gear_input': False, + 'focus_actor_dist': 3166.994873046875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.11716736e+02, -5.61223145e+01, -3.81469727e-04]), + 'frame': 15032, + 'frame_number': 15032, + 'framesequence': 57707, + 'gaze_dir': array([0.97441101, 0.19507599, 0.11079407]), + 'gaze_origin': array([-3.0535965 , -0.18100968, 0.10629044]), + 'gaze_valid': True, + 'gaze_vergence': 194.55764770507812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97323608, 0.20536804, 0.10296631]), + 'left_gaze_origin': array([-2.97963738, 3.0138216 , 0.10540009]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.142425537109375, + 'left_pupil_posn': array([ 0.21551931, -0.00037038]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97558594, 0.18478394, 0.11862183]), + 'right_gaze_origin': array([-3.12755585, -3.3758409 , 0.10718079]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1220550537109375, + 'right_pupil_posn': array([ 0.19937313, -0.07392502]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.056563008576631546, + 'throttle_input': 0.3928435146808624, + 'timestamp': 491.6002677679062, + 'timestamp_carla': 491601, + 'timestamp_device': 4229814, + 'timestamp_stream': 491.6002677679062, + 'transform': [array([ 4.14192796e-01, -1.88044376e+01, 1.23911472e-02]), + array([-6.40330166e-02, -5.89064693e+00, 3.32642719e-03])]} +{'AngularVelocity': array([-3.43136005e-02, 1.50497612e-02, -2.59411373e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.635143280029297, + 'FR_Wheel_Angle': -23.730167388916016, + 'Location': array([ -1.86712921, -19.81764412, 0.17165329]), + 'Rotation': array([-7.18399286e-02, 7.00696335e+01, 1.00802118e-02]), + 'Velocity': array([ 1.65755928e+00, 2.38292885e+00, -1.61859510e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.56630802, 14.19225311, 1.91624045]), + 'camera_rotation': array([-8.86702633, 3.71252227, 1.80288363]), + 'current_gear_input': False, + 'focus_actor_dist': 3007.604736328125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.92249023e+02, -2.13411865e+02, 1.52587891e-05]), + 'frame': 15033, + 'frame_number': 15033, + 'framesequence': 57711, + 'gaze_dir': array([0.97424316, 0.19452667, 0.11335754]), + 'gaze_origin': array([-3.05239034, -0.17934266, 0.10514145]), + 'gaze_valid': True, + 'gaze_vergence': 225.64501953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97303772, 0.20428467, 0.10694885]), + 'left_gaze_origin': array([-2.97829461, 3.01546335, 0.10538788]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1451568603515625, + 'left_pupil_posn': array([0.21438468, 0.00022525]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97544861, 0.18476868, 0.11976624]), + 'right_gaze_origin': array([-3.1264863 , -3.37414885, 0.10489503]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1555023193359375, + 'right_pupil_posn': array([ 0.19780028, -0.07396138]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06337474286556244, + 'throttle_input': 0.40474554896354675, + 'timestamp': 491.6346247680485, + 'timestamp_carla': 491635, + 'timestamp_device': 4229847, + 'timestamp_stream': 491.6346247680485, + 'transform': [array([ 4.09373760e-01, -1.87852249e+01, 1.28986547e-02]), + array([-6.46682307e-02, -5.86384630e+00, 9.46051616e-04])]} +{'AngularVelocity': array([-7.55140977e-03, 2.75365487e-02, -2.62270927e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.18019485473633, + 'FR_Wheel_Angle': -25.821495056152344, + 'Location': array([ -1.49689329, -19.30619431, 0.17118305]), + 'Rotation': array([-7.77275488e-02, 6.39570007e+01, 9.16659832e-03]), + 'Velocity': array([ 1.78542984, 1.91931176, -0.0023225 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.53344536, 14.20599842, 1.89657938]), + 'camera_rotation': array([-8.87510681, 3.6355648 , 1.98326802]), + 'current_gear_input': False, + 'focus_actor_dist': 3102.364990234375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-708.31872559, -118.47558594, 0. ]), + 'frame': 15034, + 'frame_number': 15034, + 'framesequence': 57716, + 'gaze_dir': array([0.97395325, 0.19587708, 0.11345673]), + 'gaze_origin': array([-3.05173731, -0.17845231, 0.10495682]), + 'gaze_valid': True, + 'gaze_vergence': 216.29067993164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97250366, 0.20674133, 0.10714722]), + 'left_gaze_origin': array([-2.97783375, 3.01590753, 0.10528107]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1537322998046875, + 'left_pupil_posn': array([0.2141583 , 0.00022525]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97540283, 0.18501282, 0.11976624]), + 'right_gaze_origin': array([-3.12564111, -3.37281179, 0.10463258]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1564178466796875, + 'right_pupil_posn': array([ 0.19772506, -0.07396865]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07051607221364975, + 'throttle_input': 0.4166475832462311, + 'timestamp': 491.6699142679572, + 'timestamp_carla': 491670, + 'timestamp_device': 4229889, + 'timestamp_stream': 491.6699142679572, + 'transform': [array([ 4.08130944e-01, -1.87641659e+01, 1.31674763e-02]), + array([-6.52146414e-02, -5.85294724e+00, -3.75655829e-04])]} +{'AngularVelocity': array([ 2.02538949e-02, 3.79791260e-02, -2.47728462e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.52484130859375, + 'FR_Wheel_Angle': -26.481409072875977, + 'Location': array([ -1.10544765, -18.8893528 , 0.17064422]), + 'Rotation': array([-7.98653960e-02, 5.79735222e+01, 1.35450973e-03]), + 'Velocity': array([ 1.81439376, 1.53373635, -0.00252369]), + 'brake_input': 0.0, + 'camera_location': array([-6.48322392, 14.21333218, 1.86355007]), + 'camera_rotation': array([-8.91867638, 3.5058713 , 2.14558268]), + 'current_gear_input': False, + 'focus_actor_dist': 2210.93994140625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-566.81536865, -995.97070312, 37.87620544]), + 'frame': 15035, + 'frame_number': 15035, + 'framesequence': 57719, + 'gaze_dir': array([0.97377014, 0.19579315, 0.11500549]), + 'gaze_origin': array([-3.05072498, -0.17845231, 0.10453644]), + 'gaze_valid': True, + 'gaze_vergence': 187.05308532714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9724884 , 0.20684814, 0.10697937]), + 'left_gaze_origin': array([-2.97667861, 3.01590753, 0.10456391]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.163604736328125, + 'left_pupil_posn': array([0.21405363, 0.0010457 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97505188, 0.18473816, 0.12303162]), + 'right_gaze_origin': array([-3.12477136, -3.37281179, 0.10450898]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1383514404296875, + 'right_pupil_posn': array([ 0.19774389, -0.07392502]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07743766903877258, + 'throttle_input': 0.4325169622898102, + 'timestamp': 491.7006528675556, + 'timestamp_carla': 491701, + 'timestamp_device': 4229914, + 'timestamp_stream': 491.7006528675556, + 'transform': [array([ 4.02396828e-01, -1.87422981e+01, 1.35000320e-02]), + array([-6.59454763e-02, -5.82222795e+00, -1.83048705e-03])]} +{'AngularVelocity': array([ 2.18173135e-02, 2.87816711e-02, -2.22401676e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.00453567504883, + 'FR_Wheel_Angle': -25.936092376708984, + 'Location': array([ -0.71329969, -18.55157089, 0.17011783]), + 'Rotation': array([-8.02956969e-02, 5.24892159e+01, -7.17162713e-03]), + 'Velocity': array([ 1.77315533, 1.23488593, -0.00209252]), + 'brake_input': 0.0, + 'camera_location': array([-6.44022274, 14.22646523, 1.84157431]), + 'camera_rotation': array([-9.01653862, 3.38161206, 2.27823925]), + 'current_gear_input': False, + 'focus_actor_dist': 3077.648193359375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.01285278e+02, -1.38491943e+02, -1.52587891e-05]), + 'frame': 15036, + 'frame_number': 15036, + 'framesequence': 57723, + 'gaze_dir': array([0.97322845, 0.19709778, 0.11711884]), + 'gaze_origin': array([-3.04982471, -0.17856522, 0.10441209]), + 'gaze_valid': True, + 'gaze_vergence': 165.4918975830078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97175598, 0.2097168 , 0.10809326]), + 'left_gaze_origin': array([-2.97517729, 3.0157671 , 0.10434265]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1653594970703125, + 'left_pupil_posn': array([0.21405363, 0.00221461]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97470093, 0.18447876, 0.12614441]), + 'right_gaze_origin': array([-3.12447214, -3.37289762, 0.1044815 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1396942138671875, + 'right_pupil_posn': array([ 0.19882298, -0.07354689]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08296762406826019, + 'throttle_input': 0.4444190263748169, + 'timestamp': 491.73354236781597, + 'timestamp_carla': 491734, + 'timestamp_device': 4229947, + 'timestamp_stream': 491.73354236781597, + 'transform': [array([ 3.93981934e-01, -1.87160645e+01, 1.37589164e-02]), + array([-6.64987192e-02, -5.77883863e+00, -3.04625556e-03])]} +{'AngularVelocity': array([ 0.01966843, 0.02029719, -19.05005836]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.936372756958008, + 'FR_Wheel_Angle': -23.8867130279541, + 'Location': array([ -0.38348356, -18.30721283, 0.16969162]), + 'Rotation': array([-7.99268708e-02, 4.83527184e+01, -1.53808584e-02]), + 'Velocity': array([ 1.69400156, 1.05719507, -0.00186337]), + 'brake_input': 0.0, + 'camera_location': array([-6.39757633, 14.23927116, 1.81416798]), + 'camera_rotation': array([-9.16744518, 3.23719239, 2.43456769]), + 'current_gear_input': False, + 'focus_actor_dist': 3078.41943359375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-701.43823242, -135.65625 , 0. ]), + 'frame': 15037, + 'frame_number': 15037, + 'framesequence': 57727, + 'gaze_dir': array([0.97316742, 0.19670868, 0.11825562]), + 'gaze_origin': array([-3.04953694, -0.17989121, 0.10453949]), + 'gaze_valid': True, + 'gaze_vergence': 166.0303955078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97166443, 0.20947266, 0.10932922]), + 'left_gaze_origin': array([-2.97467971, 3.01450658, 0.10438386]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.16583251953125, + 'left_pupil_posn': array([0.2147212 , 0.00268763]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97467041, 0.1839447 , 0.12718201]), + 'right_gaze_origin': array([-3.12439442, -3.37428904, 0.10469514]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.147735595703125, + 'right_pupil_posn': array([ 0.19969833, -0.07296801]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08862575143575668, + 'throttle_input': 0.45235371589660645, + 'timestamp': 491.7673735655844, + 'timestamp_carla': 491768, + 'timestamp_device': 4229980, + 'timestamp_stream': 491.7673735655844, + 'transform': [array([ 3.82597804e-01, -1.86860237e+01, 1.39663983e-02]), + array([-6.71339259e-02, -5.72188807e+00, -4.07761568e-03])]} +{'AngularVelocity': array([ -0.10974277, -0.2604157 , -14.77266312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.917634963989258, + 'FR_Wheel_Angle': -21.187807083129883, + 'Location': array([ 0.03484449, -18.02913475, 0.1691938 ]), + 'Rotation': array([-7.74816647e-02, 4.38304024e+01, -1.67541523e-02]), + 'Velocity': array([1.56067777e+00, 8.91592681e-01, 6.17027283e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.35600662, 14.26860428, 1.79322779]), + 'camera_rotation': array([-9.2901907 , 3.14861941, 2.62921214]), + 'current_gear_input': False, + 'focus_actor_dist': 2948.17236328125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.75260010e+02, -2.61043457e+02, -3.05175781e-05]), + 'frame': 15038, + 'frame_number': 15038, + 'framesequence': 57731, + 'gaze_dir': array([0.9728241 , 0.19755554, 0.11974335]), + 'gaze_origin': array([-3.04917836, -0.18212815, 0.10668412]), + 'gaze_valid': True, + 'gaze_vergence': 182.72689819335938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97106934, 0.21066284, 0.11242676]), + 'left_gaze_origin': array([-2.97407389, 3.01257181, 0.10633088]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1746063232421875, + 'left_pupil_posn': array([0.2161876, 0.0040108]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97457886, 0.18444824, 0.12705994]), + 'right_gaze_origin': array([-3.12428308, -3.37682819, 0.10703736]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1738433837890625, + 'right_pupil_posn': array([ 0.20185649, -0.07040024]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09410077333450317, + 'throttle_input': 0.4563210606575012, + 'timestamp': 491.80160826817155, + 'timestamp_carla': 491802, + 'timestamp_device': 4230014, + 'timestamp_stream': 491.80160826817155, + 'transform': [array([ 3.66635263e-01, -1.86517277e+01, 1.42411226e-02]), + array([-6.78989068e-02, -5.64420700e+00, -5.42316632e-03])]} +{'AngularVelocity': array([-1.04643833e-02, -2.74309516e-02, -1.12024689e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.303213119506836, + 'FR_Wheel_Angle': -17.981412887573242, + 'Location': array([ 0.37904587, -17.8158493 , 0.16895756]), + 'Rotation': array([-6.95518106e-02, 4.07638664e+01, -5.52368211e-03]), + 'Velocity': array([ 1.43133414e+00, 7.93126285e-01, -1.33588794e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.30419159, 14.30406284, 1.77899528]), + 'camera_rotation': array([-9.32636356, 3.11691117, 2.83912778]), + 'current_gear_input': False, + 'focus_actor_dist': 2869.330078125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.64840515e+02, -3.36528809e+02, 2.74658203e-04]), + 'frame': 15039, + 'frame_number': 15039, + 'framesequence': 57735, + 'gaze_dir': array([0.97252655, 0.19908905, 0.11972046]), + 'gaze_origin': array([-3.04920197, -0.18236771, 0.10857086]), + 'gaze_valid': True, + 'gaze_vergence': 215.0548553466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97018433, 0.21258545, 0.11625671]), + 'left_gaze_origin': array([-2.97407389, 3.01257181, 0.10921326]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1823272705078125, + 'left_pupil_posn': array([0.21655917, 0.00460321]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97486877, 0.18559265, 0.1231842 ]), + 'right_gaze_origin': array([-3.12433028, -3.37730718, 0.10792847]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1959991455078125, + 'right_pupil_posn': array([ 0.20289218, -0.06857586]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09975890070199966, + 'throttle_input': 0.4563210606575012, + 'timestamp': 491.83339066803455, + 'timestamp_carla': 491834, + 'timestamp_device': 4230047, + 'timestamp_stream': 491.83339066803455, + 'transform': [array([ 3.51778090e-01, -1.86170158e+01, 1.45520782e-02]), + array([-0.06878683, -5.57211208, -0.00685068])]} +{'AngularVelocity': array([-0.01638359, -0.03130514, -8.26460648]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.72191047668457, + 'FR_Wheel_Angle': -14.70515251159668, + 'Location': array([ 0.68420953, -17.63222504, 0.16868602]), + 'Rotation': array([-6.60684183e-02, 3.85554085e+01, 1.49989122e-04]), + 'Velocity': array([ 1.30595613e+00, 7.25661397e-01, -7.71179155e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.25001144, 14.34390831, 1.75952888]), + 'camera_rotation': array([-9.34479809, 3.06057715, 3.06237674]), + 'current_gear_input': False, + 'focus_actor_dist': 2477.322509765625, + 'focus_actor_name': 'Road_Curb_Town05_210', + 'focus_actor_pt': array([-609.2532959 , -721.23535156, 15.23997498]), + 'frame': 15040, + 'frame_number': 15040, + 'framesequence': 57739, + 'gaze_dir': array([0.97210693, 0.20031738, 0.12094879]), + 'gaze_origin': array([-3.0497582 , -0.18233186, 0.10890046]), + 'gaze_valid': True, + 'gaze_vergence': 196.68235778808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9697113 , 0.21466064, 0.1164093 ]), + 'left_gaze_origin': array([-2.97447228, 3.01264358, 0.10945588]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.208251953125, + 'left_pupil_posn': array([0.2166481 , 0.00543809]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97450256, 0.18597412, 0.12548828]), + 'right_gaze_origin': array([-3.12504435, -3.37730718, 0.10834504]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1963958740234375, + 'right_pupil_posn': array([ 0.20364833, -0.06842327]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10519730299711227, + 'throttle_input': 0.4563210606575012, + 'timestamp': 491.8669936656952, + 'timestamp_carla': 491867, + 'timestamp_device': 4230080, + 'timestamp_stream': 491.8669936656952, + 'transform': [array([ 3.31248164e-01, -1.85761280e+01, 1.48751251e-02]), + array([-0.0697977 , -5.47436666, -0.00842845])]} +{'AngularVelocity': array([-0.00878866, -0.00821663, -6.00202417]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.075196266174316, + 'FR_Wheel_Angle': -11.106467247009277, + 'Location': array([ 0.92760414, -17.48588371, 0.16803718]), + 'Rotation': array([-7.98653960e-02, 3.71616287e+01, -2.86254808e-02]), + 'Velocity': array([ 1.19865453, 0.68342149, -0.00168388]), + 'brake_input': 0.0, + 'camera_location': array([-6.21827602, 14.36113548, 1.7273494 ]), + 'camera_rotation': array([-9.54234791, 3.0162077 , 3.4861033 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2196.042236328125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-568.10797119, -995.97412109, 29.29808044]), + 'frame': 15041, + 'frame_number': 15041, + 'framesequence': 57743, + 'gaze_dir': array([0.97071075, 0.20430756, 0.12561035]), + 'gaze_origin': array([-3.05058455, -0.17918703, 0.11500015]), + 'gaze_valid': True, + 'gaze_vergence': 215.92515563964844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96867371, 0.21690369, 0.12083435]), + 'left_gaze_origin': array([-2.97604251, 3.01459527, 0.11571656]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2624053955078125, + 'left_pupil_posn': array([0.21731853, 0.01075912]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9727478 , 0.19171143, 0.13038635]), + 'right_gaze_origin': array([-3.1251266 , -3.37296915, 0.11428376]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1779022216796875, + 'right_pupil_posn': array([ 0.20154512, -0.06287086]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11107517033815384, + 'throttle_input': 0.4563210606575012, + 'timestamp': 491.901209667325, + 'timestamp_carla': 491901, + 'timestamp_device': 4230114, + 'timestamp_stream': 491.901209667325, + 'transform': [array([ 3.08693379e-01, -1.85311852e+01, 1.51087474e-02]), + array([-0.07082906, -5.36801004, -0.00962374])]} +{'AngularVelocity': array([-0.00805947, -0.01017987, -3.69100022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.306065559387207, + 'FR_Wheel_Angle': -7.142947673797607, + 'Location': array([ 1.18786633, -17.32567406, 0.16773131]), + 'Rotation': array([-7.87315890e-02, 3.60717468e+01, -2.79846136e-02]), + 'Velocity': array([ 1.07569885, 0.64858723, -0.00119205]), + 'brake_input': 0.0, + 'camera_location': array([-6.18897438, 14.36058712, 1.69749069]), + 'camera_rotation': array([-9.59599876, 2.94891524, 3.81937504]), + 'current_gear_input': False, + 'focus_actor_dist': 2195.2333984375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-581.07348633, -995.33251953, 28.75074005]), + 'frame': 15042, + 'frame_number': 15042, + 'framesequence': 57747, + 'gaze_dir': array([0.97051239, 0.20536804, 0.1253891 ]), + 'gaze_origin': array([-3.05070424, -0.1793419 , 0.11552583]), + 'gaze_valid': True, + 'gaze_vergence': 219.62680053710938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96813965, 0.21859741, 0.12208557]), + 'left_gaze_origin': array([-2.97633982, 3.01437545, 0.11575776]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2551727294921875, + 'left_pupil_posn': array([0.21759796, 0.01012146]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97288513, 0.19213867, 0.12869263]), + 'right_gaze_origin': array([-3.1250689 , -3.37305927, 0.11529389]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.231170654296875, + 'right_pupil_posn': array([ 0.2021817 , -0.06189001]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11680655181407928, + 'throttle_input': 0.4603036642074585, + 'timestamp': 491.9338154681027, + 'timestamp_carla': 491934, + 'timestamp_device': 4230147, + 'timestamp_stream': 491.9338154681027, + 'transform': [array([ 2.86047041e-01, -1.84848499e+01, 1.54077904e-02]), + array([-0.07202434, -5.26217413, -0.01105808])]} +{'AngularVelocity': array([-0.00577812, -0.00659627, -1.65871644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.5498580932617188, + 'FR_Wheel_Angle': -2.8234522342681885, + 'Location': array([ 1.42219329, -17.17448997, 0.16745739]), + 'Rotation': array([-7.80349076e-02, 3.54918404e+01, -2.79235896e-02]), + 'Velocity': array([ 0.95705193, 0.62389636, -0.00109021]), + 'brake_input': 0.0, + 'camera_location': array([-6.11871624, 14.37158775, 1.70310295]), + 'camera_rotation': array([-9.48914719, 2.86197567, 4.04464102]), + 'current_gear_input': False, + 'focus_actor_dist': 2357.718017578125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-614.11120605, -832.58837891, 15.18941498]), + 'frame': 15043, + 'frame_number': 15043, + 'framesequence': 57751, + 'gaze_dir': array([0.9707489 , 0.20415497, 0.12541199]), + 'gaze_origin': array([-3.05052447, -0.17955628, 0.1145874 ]), + 'gaze_valid': True, + 'gaze_vergence': 209.02423095703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96801758, 0.21850586, 0.12319946]), + 'left_gaze_origin': array([-2.97590494, 3.01418614, 0.11481324]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2369384765625, + 'left_pupil_posn': array([0.21693468, 0.00933373]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97348022, 0.18980408, 0.12762451]), + 'right_gaze_origin': array([-3.12514353, -3.37329888, 0.11436158]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2314300537109375, + 'right_pupil_posn': array([ 0.20232224, -0.06215632]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12257454544305801, + 'throttle_input': 0.4603036642074585, + 'timestamp': 491.96785166859627, + 'timestamp_carla': 491968, + 'timestamp_device': 4230180, + 'timestamp_stream': 491.96785166859627, + 'transform': [array([ 2.59281158e-01, -1.84326210e+01, 1.56564415e-02]), + array([-0.07321279, -5.13851547, -0.01232849])]} +{'AngularVelocity': array([-0.00785194, -0.01150231, -0.91683203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.35639721155166626, + 'FR_Wheel_Angle': 0.29835063219070435, + 'Location': array([ 1.62576044, -17.0347538 , 0.16722237]), + 'Rotation': array([-8.03844929e-02, 3.53366280e+01, -2.72216816e-02]), + 'Velocity': array([ 7.95383990e-01, 5.62287211e-01, -7.06858642e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.0751152 , 14.387146 , 1.69981337]), + 'camera_rotation': array([-9.48558903, 2.77912188, 4.16147232]), + 'current_gear_input': False, + 'focus_actor_dist': 2187.64892578125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-583.74316406, -995.33959961, 26.3114624 ]), + 'frame': 15044, + 'frame_number': 15044, + 'framesequence': 57755, + 'gaze_dir': array([0.97067261, 0.20391846, 0.12635803]), + 'gaze_origin': array([-3.05045629, -0.17959595, 0.11425782]), + 'gaze_valid': True, + 'gaze_vergence': 208.59986877441406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96800232, 0.21820068, 0.12379456]), + 'left_gaze_origin': array([-2.97574329, 3.01405048, 0.11457063]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.242034912109375, + 'left_pupil_posn': array([0.21697283, 0.0096184 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9733429 , 0.18963623, 0.12892151]), + 'right_gaze_origin': array([-3.12516952, -3.37324214, 0.11394501]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.231781005859375, + 'right_pupil_posn': array([ 0.20218349, -0.0622375 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12880033254623413, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.0005912669003, + 'timestamp_carla': 492001, + 'timestamp_device': 4230214, + 'timestamp_stream': 492.0005912669003, + 'transform': [array([ 2.30145559e-01, -1.83785877e+01, 1.58879180e-02]), + array([-0.07442857, -5.00537872, -0.01346913])]} +{'AngularVelocity': array([ 0.03400166, -0.06695543, -0.65152073]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03503585606813431, + 'FR_Wheel_Angle': 0.035008762031793594, + 'Location': array([ 1.83368361, -16.88717461, 0.16686767]), + 'Rotation': array([-6.34524524e-02, 3.53474388e+01, -2.20642071e-02]), + 'Velocity': array([ 1.03295600e+00, 7.33180225e-01, -9.74545430e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.04975224, 14.37626266, 1.68279028]), + 'camera_rotation': array([-9.62181664, 2.73842335, 4.43194246]), + 'current_gear_input': False, + 'focus_actor_dist': 2183.03759765625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-584.49389648, -995.34155273, 27.88715363]), + 'frame': 15045, + 'frame_number': 15045, + 'framesequence': 57759, + 'gaze_dir': array([0.97370911, 0.18286133, 0.13527679]), + 'gaze_origin': array([-3.045331 , -0.1636406 , 0.11852494]), + 'gaze_valid': True, + 'gaze_vergence': 260.05572509765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9712677 , 0.1938324 , 0.13804626]), + 'left_gaze_origin': array([-2.96721053, 3.03083515, 0.11692506]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3817901611328125, + 'left_pupil_posn': array([0.19931698, 0.01400185]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97615051, 0.17189026, 0.13250732]), + 'right_gaze_origin': array([-3.12345147, -3.35811639, 0.12012482]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.279266357421875, + 'right_pupil_posn': array([ 0.18321157, -0.05263555]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13444013893604279, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.0345772653818, + 'timestamp_carla': 492035, + 'timestamp_device': 4230247, + 'timestamp_stream': 492.0345772653818, + 'transform': [array([ 1.96177065e-01, -1.83186474e+01, 1.60515402e-02]), + array([-0.07563068, -4.85176849, -0.01435706])]} +{'AngularVelocity': array([-0.01607516, 0.01560947, -0.11758392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.11474085, -16.68790627, 0.16646557]), + 'Rotation': array([-5.34667186e-02, 3.53548431e+01, -2.02636681e-02]), + 'Velocity': array([ 1.34562838, 0.95399374, -0.00161897]), + 'brake_input': 0.0, + 'camera_location': array([-6.03068066, 14.36543083, 1.67881083]), + 'camera_rotation': array([-9.68269444, 2.68712449, 4.70003414]), + 'current_gear_input': False, + 'focus_actor_dist': 3160.357666015625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-694.70214844, -18.38452148, 0. ]), + 'frame': 15046, + 'frame_number': 15046, + 'framesequence': 57765, + 'gaze_dir': array([0.97298431, 0.18802643, 0.13332367]), + 'gaze_origin': array([-3.04601073, -0.1629242 , 0.12033997]), + 'gaze_valid': True, + 'gaze_vergence': 249.29869079589844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97038269, 0.1993103 , 0.13642883]), + 'left_gaze_origin': array([-2.9686923 , 3.03098774, 0.1189789 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.394500732421875, + 'left_pupil_posn': array([0.20086002, 0.01417023]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97558594, 0.17674255, 0.13021851]), + 'right_gaze_origin': array([-3.1233294 , -3.35683608, 0.12170105]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.314849853515625, + 'right_pupil_posn': array([ 0.18429124, -0.05206299]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13927426934242249, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.0780067667365, + 'timestamp_carla': 492078, + 'timestamp_device': 4230297, + 'timestamp_stream': 492.0780067667365, + 'transform': [array([ 1.47454366e-01, -1.82363758e+01, 1.62606146e-02]), + array([-0.07709234, -4.63370085, -0.0154977 ])]} +{'AngularVelocity': array([-0.05588781, 0.07709935, -0.87971723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07106160372495651, + 'FR_Wheel_Angle': 0.07741235196590424, + 'Location': array([ 2.42703772, -16.46645355, 0.16617531]), + 'Rotation': array([-7.09519982e-02, 3.53566093e+01, -1.99584961e-02]), + 'Velocity': array([ 1.23735142, 0.87844336, -0.00157722]), + 'brake_input': 0.0, + 'camera_location': array([-5.99342346, 14.34118652, 1.68304181]), + 'camera_rotation': array([-9.61288929, 2.55234027, 4.80909729]), + 'current_gear_input': False, + 'focus_actor_dist': 2884.953857421875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.73465332e+02, -2.88792480e+02, 1.22070312e-04]), + 'frame': 15047, + 'frame_number': 15047, + 'framesequence': 57767, + 'gaze_dir': array([0.97304535, 0.1869278 , 0.13452148]), + 'gaze_origin': array([-3.04576874, -0.162986 , 0.12005615]), + 'gaze_valid': True, + 'gaze_vergence': 278.8315734863281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97079468, 0.19769287, 0.13583374]), + 'left_gaze_origin': array([-2.96824503, 3.03086424, 0.11866608]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.402252197265625, + 'left_pupil_posn': array([0.20075262, 0.01504982]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97529602, 0.17616272, 0.13320923]), + 'right_gaze_origin': array([-3.12329268, -3.35683608, 0.12144624]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.309234619140625, + 'right_pupil_posn': array([ 0.18372583, -0.05237746]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14537186920642853, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.1002683676779, + 'timestamp_carla': 492100, + 'timestamp_device': 4230314, + 'timestamp_stream': 492.1002683676779, + 'transform': [array([ 1.20128937e-01, -1.81919460e+01, 1.63305085e-02]), + array([-0.07782317, -4.5124259 , -0.01578458])]} +{'AngularVelocity': array([-1.16930164e-01, 1.52924880e-01, 6.35122560e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10627797245979309, + 'FR_Wheel_Angle': 0.1294592022895813, + 'Location': array([ 2.61360335, -16.33334732, 0.16634995]), + 'Rotation': array([-1.38243020e-01, 3.53018036e+01, -1.95007306e-02]), + 'Velocity': array([8.45994946e-05, 1.05847648e-04, 1.50123058e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.95665264, 14.30686188, 1.67605853]), + 'camera_rotation': array([-9.56054974, 2.41630983, 5.01790905]), + 'current_gear_input': False, + 'focus_actor_dist': 3019.013427734375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.96941528e+02, -1.49262451e+02, 6.10351562e-05]), + 'frame': 15048, + 'frame_number': 15048, + 'framesequence': 57771, + 'gaze_dir': array([0.97296143, 0.18736267, 0.13447571]), + 'gaze_origin': array([-3.04563689, -0.16325226, 0.12014771]), + 'gaze_valid': True, + 'gaze_vergence': 260.2414245605469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97050476, 0.19866943, 0.13650513]), + 'left_gaze_origin': array([-2.96782708, 3.0306735 , 0.1185669 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3696136474609375, + 'left_pupil_posn': array([0.20085371, 0.01485717]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97541809, 0.17605591, 0.13244629]), + 'right_gaze_origin': array([-3.1234467 , -3.35717797, 0.12172852]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.309234619140625, + 'right_pupil_posn': array([ 0.18430936, -0.05201435]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1484481394290924, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.134281065315, + 'timestamp_carla': 492135, + 'timestamp_device': 4230347, + 'timestamp_stream': 492.134281065315, + 'transform': [array([ 7.48721287e-02, -1.81207104e+01, 1.63963698e-02]), + array([-0.07897747, -4.31308174, -0.01624219])]} +{'AngularVelocity': array([ 8.52288902e-02, -1.19465873e-01, -4.30165819e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.22254835069179535, + 'FR_Wheel_Angle': 0.24610093235969543, + 'Location': array([ 2.61382937, -16.33320045, 0.16607387]), + 'Rotation': array([-9.63124931e-02, 3.53018837e+01, -1.95007268e-02]), + 'Velocity': array([-6.25803004e-05, -8.25699681e-05, 6.55928452e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.91844273, 14.26068497, 1.67051363]), + 'camera_rotation': array([-9.50506115, 2.2169106 , 5.15764141]), + 'current_gear_input': False, + 'focus_actor_dist': 3026.95068359375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.00026917e+02, -1.37719238e+02, -1.52587891e-05]), + 'frame': 15049, + 'frame_number': 15049, + 'framesequence': 57775, + 'gaze_dir': array([0.97279358, 0.18942261, 0.13253021]), + 'gaze_origin': array([-3.04564285, -0.16616975, 0.11986008]), + 'gaze_valid': True, + 'gaze_vergence': 216.8282470703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97009277, 0.2035675 , 0.13215637]), + 'left_gaze_origin': array([-2.96738768, 3.03000665, 0.11812898]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3585968017578125, + 'left_pupil_posn': array([0.20104146, 0.0148229 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97549438, 0.17527771, 0.13290405]), + 'right_gaze_origin': array([-3.12389851, -3.36234617, 0.1215912 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3147125244140625, + 'right_pupil_posn': array([ 0.18954265, -0.05379832]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15280619263648987, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.16802076622844, + 'timestamp_carla': 492168, + 'timestamp_device': 4230380, + 'timestamp_stream': 492.16802076622844, + 'transform': [array([ 2.61306763e-02, -1.80464821e+01, 1.64370444e-02]), + array([-0.08004981, -4.10015059, -0.01654956])]} +{'AngularVelocity': array([ 1.85068697e-02, -2.59388164e-02, -2.07358353e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.272298663854599, + 'FR_Wheel_Angle': 0.2730185091495514, + 'Location': array([ 2.61393547, -16.33312416, 0.16597492]), + 'Rotation': array([-7.69352466e-02, 3.53020325e+01, -1.95007287e-02]), + 'Velocity': array([-1.57230952e-05, -1.29309665e-05, -4.41496435e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.87912178, 14.22815514, 1.67426562]), + 'camera_rotation': array([-9.54845333, 1.94183719, 5.12509108]), + 'current_gear_input': False, + 'focus_actor_dist': 2923.826171875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.89617310e+02, -2.34247070e+02, -1.52587891e-05]), + 'frame': 15050, + 'frame_number': 15050, + 'framesequence': 57779, + 'gaze_dir': array([0.97301483, 0.18954468, 0.13075256]), + 'gaze_origin': array([-3.04449701, -0.17086183, 0.11644363]), + 'gaze_valid': True, + 'gaze_vergence': 207.36964416503906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97129822, 0.20222473, 0.12518311]), + 'left_gaze_origin': array([-2.9658556 , 3.02398396, 0.11368257]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5027313232421875, + 'left_pupil_posn': array([0.2056098, 0.0131076]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97473145, 0.17686462, 0.13632202]), + 'right_gaze_origin': array([-3.12313867, -3.3657074 , 0.11920471]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.284027099609375, + 'right_pupil_posn': array([ 0.19127274, -0.05767238]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15676139295101166, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.20025316625834, + 'timestamp_carla': 492201, + 'timestamp_device': 4230414, + 'timestamp_stream': 492.20025316625834, + 'transform': [array([-2.41743457e-02, -1.79722137e+01, 1.64915938e-02]), + array([-0.08111532, -3.88207316, -0.01686374])]} +{'AngularVelocity': array([ 5.46189211e-03, -7.61383027e-03, -1.31842926e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2722987234592438, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.61395645, -16.3331089 , 0.16595364]), + 'Rotation': array([-7.33630583e-02, 3.53021011e+01, -1.95007306e-02]), + 'Velocity': array([-2.42021861e-06, -3.62580408e-06, 3.78557997e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.86033916, 14.20982647, 1.67502964]), + 'camera_rotation': array([-9.59984398, 1.74316132, 4.97634983]), + 'current_gear_input': False, + 'focus_actor_dist': 2779.753173828125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-662.65081787, -369.31225586, 0. ]), + 'frame': 15051, + 'frame_number': 15051, + 'framesequence': 57783, + 'gaze_dir': array([0.97274017, 0.18835449, 0.13463593]), + 'gaze_origin': array([-3.04449773, -0.17306748, 0.11530914]), + 'gaze_valid': True, + 'gaze_vergence': 250.1025848388672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97070312, 0.20036316, 0.13252258]), + 'left_gaze_origin': array([-2.9648118 , 3.0218935 , 0.11256867]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3968048095703125, + 'left_pupil_posn': array([0.20684719, 0.01276517]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97477722, 0.17634583, 0.13674927]), + 'right_gaze_origin': array([-3.12418389, -3.36802816, 0.11804963]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.28277587890625, + 'right_pupil_posn': array([ 0.19232023, -0.05603206]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16013062000274658, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.23406736552715, + 'timestamp_carla': 492234, + 'timestamp_device': 4230447, + 'timestamp_stream': 492.23406736552715, + 'transform': [array([-8.13160688e-02, -1.78910084e+01, 1.64545346e-02]), + array([-0.08200324, -3.63609457, -0.01681593])]} +{'AngularVelocity': array([-0.000317 , 0.00041227, -0.00023032]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.61411929, -16.33299065, 0.16593552]), + 'Rotation': array([-7.23248720e-02, 3.53021584e+01, -1.95007324e-02]), + 'Velocity': array([5.34124665e-05, 3.49251168e-05, 2.27503217e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.87242699, 14.21537209, 1.66326523]), + 'camera_rotation': array([-9.71817017, 1.64751387, 4.74775076]), + 'current_gear_input': False, + 'focus_actor_dist': 3000.02783203125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.96232971e+02, -1.44689697e+02, -1.52587891e-05]), + 'frame': 15052, + 'frame_number': 15052, + 'framesequence': 57788, + 'gaze_dir': array([0.97225189, 0.19137573, 0.1333847 ]), + 'gaze_origin': array([-3.04434919, -0.17406847, 0.11861344]), + 'gaze_valid': True, + 'gaze_vergence': 176.68118286132812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9697876 , 0.20742798, 0.12834167]), + 'left_gaze_origin': array([-2.96495986, 3.02086043, 0.11686707]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4083251953125, + 'left_pupil_posn': array([0.20714223, 0.01599473]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97471619, 0.17532349, 0.13842773]), + 'right_gaze_origin': array([-3.12373829, -3.3689971 , 0.12035981]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3933868408203125, + 'right_pupil_posn': array([ 0.19545007, -0.05591273]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16337169706821442, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.27075446769595, + 'timestamp_carla': 492271, + 'timestamp_device': 4230489, + 'timestamp_stream': 492.27075446769595, + 'transform': [array([-1.47659600e-01, -1.77999001e+01, 1.62409581e-02]), + array([-0.0826726 , -3.35256767, -0.01605094])]} +{'AngularVelocity': array([ 2.71562312e-04, -4.90936625e-04, -1.02773456e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.61411977, -16.33299065, 0.16595039]), + 'Rotation': array([-7.23248720e-02, 3.53021584e+01, -1.95007324e-02]), + 'Velocity': array([ 2.53221947e-06, -7.03497776e-08, -5.64052107e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.90468216, 14.25135612, 1.6672194 ]), + 'camera_rotation': array([-9.73305988, 1.65308666, 4.39110041]), + 'current_gear_input': False, + 'focus_actor_dist': 2835.86767578125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.83989319e+02, -3.02011230e+02, 1.83105469e-04]), + 'frame': 15053, + 'frame_number': 15053, + 'framesequence': 57792, + 'gaze_dir': array([0.97159576, 0.19426727, 0.13399506]), + 'gaze_origin': array([-3.04615426, -0.17752229, 0.12282105]), + 'gaze_valid': True, + 'gaze_vergence': 163.35665893554688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9697876 , 0.20898438, 0.12580872]), + 'left_gaze_origin': array([-2.9684999 , 3.01611042, 0.12148286]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4846954345703125, + 'left_pupil_posn': array([0.21187747, 0.01962686]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97340393, 0.17955017, 0.1421814 ]), + 'right_gaze_origin': array([-3.12380838, -3.37115479, 0.12415925]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.36004638671875, + 'right_pupil_posn': array([ 0.19740009, -0.05448258]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16505631804466248, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.3083350658417, + 'timestamp_carla': 492309, + 'timestamp_device': 4230522, + 'timestamp_stream': 492.3083350658417, + 'transform': [array([-2.19813988e-01, -1.77033272e+01, 1.60369296e-02]), + array([-0.08321902, -3.04644918, -0.01528597])]} +{'AngularVelocity': array([-0.00299022, 0.00286282, -0.00123181]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26972147822380066, + 'FR_Wheel_Angle': 0.2537664473056793, + 'Location': array([ 2.61273336, -16.33399582, 0.16597156]), + 'Rotation': array([-7.28439614e-02, 3.53026123e+01, -1.94702130e-02]), + 'Velocity': array([-1.25288963e-02, -9.13175661e-03, 6.46257395e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.93242168, 14.30650234, 1.72418225]), + 'camera_rotation': array([-9.54251862, 1.62648296, 3.94507861]), + 'current_gear_input': False, + 'focus_actor_dist': 2925.202392578125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.20163696e+02, -2.09387695e+02, -1.52587891e-05]), + 'frame': 15054, + 'frame_number': 15054, + 'framesequence': 57797, + 'gaze_dir': array([0.9717865 , 0.19730377, 0.1279068 ]), + 'gaze_origin': array([-3.04527068, -0.17765045, 0.1136322 ]), + 'gaze_valid': True, + 'gaze_vergence': 163.97817993164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96936035, 0.21359253, 0.12121582]), + 'left_gaze_origin': array([-2.9669466 , 3.01541615, 0.11364899]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.386505126953125, + 'left_pupil_posn': array([0.21286166, 0.01231986]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97421265, 0.18101501, 0.13459778]), + 'right_gaze_origin': array([-3.12359476, -3.37071705, 0.11361543]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3876953125, + 'right_pupil_posn': array([ 0.19863617, -0.06329036]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16458022594451904, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.34321146830916, + 'timestamp_carla': 492343, + 'timestamp_device': 4230564, + 'timestamp_stream': 492.34321146830916, + 'transform': [array([-2.89555192e-01, -1.76106377e+01, 1.60071757e-02]), + array([-0.08370396, -2.75275254, -0.01512887])]} +{'AngularVelocity': array([-0.00352418, 0.00853736, 0.01289043]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5421182513237, + 'FR_Wheel_Angle': -0.8061864376068115, + 'Location': array([ 2.61052394, -16.33558846, 0.16596657]), + 'Rotation': array([-7.26049095e-02, 3.53027725e+01, -1.94702130e-02]), + 'Velocity': array([-0.01359405, -0.00936478, 0.00027562]), + 'brake_input': 0.0, + 'camera_location': array([-5.93049526, 14.40558529, 1.83389962]), + 'camera_rotation': array([-9.09992218, 1.55788958, 3.40741444]), + 'current_gear_input': False, + 'focus_actor_dist': 2839.29345703125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.23853943e+02, -2.88798096e+02, -3.05175781e-04]), + 'frame': 15055, + 'frame_number': 15055, + 'framesequence': 57800, + 'gaze_dir': array([0.97376251, 0.19606018, 0.11450958]), + 'gaze_origin': array([-3.04459238, -0.17736588, 0.10995484]), + 'gaze_valid': True, + 'gaze_vergence': 202.50527954101562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97146606, 0.21000671, 0.11012268]), + 'left_gaze_origin': array([-2.96554875, 3.01647067, 0.10986328]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.423187255859375, + 'left_pupil_posn': array([0.21233189, 0.00447893]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97605896, 0.18211365, 0.11889648]), + 'right_gaze_origin': array([-3.12363601, -3.37120223, 0.11004639]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.358734130859375, + 'right_pupil_posn': array([ 0.19762719, -0.06935215]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16214485466480255, + 'throttle_input': 0.4603036642074585, + 'timestamp': 492.3729378655553, + 'timestamp_carla': 492373, + 'timestamp_device': 4230589, + 'timestamp_stream': 492.3729378655553, + 'transform': [array([-3.50009292e-01, -1.75294971e+01, 1.59791559e-02]), + array([-0.08385423, -2.49990392, -0.01512887])]} +{'AngularVelocity': array([-0.00495524, -0.00898915, -0.02746494]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.952991485595703, + 'FR_Wheel_Angle': -3.296377658843994, + 'Location': array([ 2.6072464 , -16.33786774, 0.16594902]), + 'Rotation': array([-7.28712827e-02, 3.53048897e+01, -1.95922852e-02]), + 'Velocity': array([-0.01649578, -0.01232998, 0.00065615]), + 'brake_input': 0.0, + 'camera_location': array([-5.91452885, 14.51049614, 1.91320181]), + 'camera_rotation': array([-8.62447262, 1.54691887, 3.16952395]), + 'current_gear_input': False, + 'focus_actor_dist': 2112.181396484375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-593.82073975, -995.36816406, 26.58279419]), + 'frame': 15056, + 'frame_number': 15056, + 'framesequence': 57804, + 'gaze_dir': array([0.97434235, 0.19272614, 0.11515808]), + 'gaze_origin': array([-3.04119349, -0.17581558, 0.10509491]), + 'gaze_valid': True, + 'gaze_vergence': 202.2680206298828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97203064, 0.20687866, 0.11103821]), + 'left_gaze_origin': array([-2.95966053, 3.0191865 , 0.10433197]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4889068603515625, + 'left_pupil_posn': array([0.20921993, 0.00207764]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97665405, 0.17857361, 0.11927795]), + 'right_gaze_origin': array([-3.12272668, -3.37081766, 0.10585785]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4278106689453125, + 'right_pupil_posn': array([ 0.19616723, -0.07181835]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15822626650333405, + 'throttle_input': 0.4285496175289154, + 'timestamp': 492.4038351662457, + 'timestamp_carla': 492404, + 'timestamp_device': 4230622, + 'timestamp_stream': 492.4038351662457, + 'transform': [array([-4.14079875e-01, -1.74428501e+01, 1.61353201e-02]), + array([-0.08370396, -2.2332027 , -0.01556601])]} +{'AngularVelocity': array([-0.07048386, 0.21742298, 0.98531759]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.823915481567383, + 'FR_Wheel_Angle': -6.929935932159424, + 'Location': array([ 2.58597398, -16.35164833, 0.16608097]), + 'Rotation': array([-8.59989077e-02, 3.53710823e+01, -2.29186974e-02]), + 'Velocity': array([-0.35289928, -0.21580751, 0.00076861]), + 'brake_input': 0.0, + 'camera_location': array([-5.88442707, 14.61670494, 1.96153843]), + 'camera_rotation': array([-8.35583401, 1.4788053 , 3.00393176]), + 'current_gear_input': False, + 'focus_actor_dist': 3222.73828125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-7.97777832e+02, 1.03687744e+02, -1.52587891e-05]), + 'frame': 15057, + 'frame_number': 15057, + 'framesequence': 57807, + 'gaze_dir': array([0.97564697, 0.19106293, 0.10612488]), + 'gaze_origin': array([-3.03782892, -0.17382127, 0.09627457]), + 'gaze_valid': True, + 'gaze_vergence': 169.56170654296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97267151, 0.20843506, 0.10221863]), + 'left_gaze_origin': array([-2.95422077, 3.02188587, 0.0968628 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4806671142578125, + 'left_pupil_posn': array([ 0.20561039, -0.00494933]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97862244, 0.1736908 , 0.11003113]), + 'right_gaze_origin': array([-3.12143707, -3.36952853, 0.09568635]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.400146484375, + 'right_pupil_posn': array([ 0.19570971, -0.08146274]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15243995189666748, + 'throttle_input': 0.40871289372444153, + 'timestamp': 492.43452786654234, + 'timestamp_carla': 492435, + 'timestamp_device': 4230647, + 'timestamp_stream': 492.43452786654234, + 'transform': [array([-4.77528840e-01, -1.73545532e+01, 1.63144879e-02]), + array([-0.08315755, -1.97063649, -0.01613974])]} +{'AngularVelocity': array([ 0.05155702, -0.04259289, 2.79108834]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.93159294128418, + 'FR_Wheel_Angle': -10.310519218444824, + 'Location': array([ 2.4711535 , -16.4220562 , 0.16626576]), + 'Rotation': array([-9.49669480e-02, 3.57542000e+01, -2.74658184e-02]), + 'Velocity': array([-0.68078351, -0.39016381, 0.00084891]), + 'brake_input': 0.0, + 'camera_location': array([-5.844244 , 14.67207623, 1.98160422]), + 'camera_rotation': array([-8.11063766, 1.47527337, 2.97259521]), + 'current_gear_input': False, + 'focus_actor_dist': 2096.615234375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-594.64898682, -995.32714844, 39.64251709]), + 'frame': 15058, + 'frame_number': 15058, + 'framesequence': 57811, + 'gaze_dir': array([0.97573853, 0.19275665, 0.10321808]), + 'gaze_origin': array([-3.03609252, -0.17032625, 0.09384918]), + 'gaze_valid': True, + 'gaze_vergence': 306.0500793457031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97395325, 0.20259094, 0.10168457]), + 'left_gaze_origin': array([-2.95278788, 3.02652907, 0.09243927]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5049285888671875, + 'left_pupil_posn': array([ 0.20559788, -0.00956225]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9775238 , 0.18292236, 0.10475159]), + 'right_gaze_origin': array([-3.11939716, -3.36718154, 0.0952591 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3929595947265625, + 'right_pupil_posn': array([ 0.19197798, -0.08141935]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14496903121471405, + 'throttle_input': 0.3809414803981781, + 'timestamp': 492.4686224684119, + 'timestamp_carla': 492469, + 'timestamp_device': 4230680, + 'timestamp_stream': 492.4686224684119, + 'transform': [array([-5.47377288e-01, -1.72542973e+01, 1.63989067e-02]), + array([-0.08190762, -1.68297708, -0.01637197])]} +{'AngularVelocity': array([ 0.02162029, -0.05550886, 6.1081624 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.420967102050781, + 'FR_Wheel_Angle': -12.978697776794434, + 'Location': array([ 2.21165991, -16.57623291, 0.16658387]), + 'Rotation': array([-9.54860374e-02, 3.69547424e+01, -3.17077637e-02]), + 'Velocity': array([-1.17102206, -0.65118933, 0.00173279]), + 'brake_input': 0.0, + 'camera_location': array([-5.81369877, 14.72430992, 1.96749115]), + 'camera_rotation': array([-8.20923138, 1.55083287, 3.38004208]), + 'current_gear_input': False, + 'focus_actor_dist': 3041.909912109375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.86516663e+02, -6.22343750e+01, -1.52587891e-05]), + 'frame': 15059, + 'frame_number': 15059, + 'framesequence': 57815, + 'gaze_dir': array([0.97633362, 0.18637085, 0.10865784]), + 'gaze_origin': array([-3.03123641, -0.16677628, 0.09490357]), + 'gaze_valid': True, + 'gaze_vergence': 197.85287475585938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97447205, 0.19955444, 0.10273743]), + 'left_gaze_origin': array([-2.94604349, 3.03066254, 0.09244081]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.442474365234375, + 'left_pupil_posn': array([ 0.19947124, -0.00477886]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97819519, 0.17318726, 0.11457825]), + 'right_gaze_origin': array([-3.11642933, -3.36421537, 0.09736633]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3871612548828125, + 'right_pupil_posn': array([ 0.18880796, -0.07901013]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13561205565929413, + 'throttle_input': 0.30951398611068726, + 'timestamp': 492.501262165606, + 'timestamp_carla': 492501, + 'timestamp_device': 4230714, + 'timestamp_stream': 492.501262165606, + 'transform': [array([-6.12548351e-01, -1.71565571e+01, 1.64239407e-02]), + array([-0.08016592, -1.41589248, -0.01622854])]} +{'AngularVelocity': array([-0.01377258, -0.02665729, 8.09767914]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.719727516174316, + 'FR_Wheel_Angle': -13.519868850708008, + 'Location': array([ 1.96043086, -16.72613907, 0.16684718]), + 'Rotation': array([-9.13127959e-02, 3.83668823e+01, -3.00598107e-02]), + 'Velocity': array([-1.41713166e+00, -8.06630671e-01, 1.14044186e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.77969456, 14.77031326, 1.92161524]), + 'camera_rotation': array([-8.46324635, 1.53370476, 3.55788398]), + 'current_gear_input': False, + 'focus_actor_dist': 3226.669189453125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-824.62304688, 128.11083984, 0. ]), + 'frame': 15060, + 'frame_number': 15060, + 'framesequence': 57819, + 'gaze_dir': array([0.97597504, 0.18655396, 0.11101532]), + 'gaze_origin': array([-3.03611922, -0.16393434, 0.09997559]), + 'gaze_valid': True, + 'gaze_vergence': 126.61782836914062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97488403, 0.19973755, 0.09848022]), + 'left_gaze_origin': array([-2.95645142, 3.03302312, 0.09995728]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5059051513671875, + 'left_pupil_posn': array([0.19806063, 0.0012486 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97706604, 0.17337036, 0.12355042]), + 'right_gaze_origin': array([-3.11578679, -3.36089182, 0.09999391]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.328826904296875, + 'right_pupil_posn': array([ 0.18659687, -0.07843006]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12748192250728607, + 'throttle_input': 0.2658579349517822, + 'timestamp': 492.5343627668917, + 'timestamp_carla': 492535, + 'timestamp_device': 4230747, + 'timestamp_stream': 492.5343627668917, + 'transform': [array([-6.76388204e-01, -1.70560322e+01, 1.63368881e-02]), + array([-0.07821249, -1.15555418, -0.01559332])]} +{'AngularVelocity': array([-0.0150023 , -0.0657981 , 8.50447941]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.287291526794434, + 'FR_Wheel_Angle': -11.30126667022705, + 'Location': array([ 1.60441923, -16.95399094, 0.1672747 ]), + 'Rotation': array([-8.87446404e-02, 4.03546867e+01, -2.11791992e-02]), + 'Velocity': array([-1.63364208, -1.04106605, 0.00215603]), + 'brake_input': 0.0, + 'camera_location': array([-5.75700378, 14.79609776, 1.88409519]), + 'camera_rotation': array([-8.68436623, 1.49497354, 3.60790634]), + 'current_gear_input': False, + 'focus_actor_dist': 3040.825439453125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-804.68096924, -48.36376953, 0. ]), + 'frame': 15061, + 'frame_number': 15061, + 'framesequence': 57823, + 'gaze_dir': array([0.97540283, 0.18479919, 0.11883545]), + 'gaze_origin': array([-3.04245234, -0.16012421, 0.10937347]), + 'gaze_valid': True, + 'gaze_vergence': 176.23306274414062, + 'handbrake_input': False, + 'left_eye_openness': 0.9613879323005676, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97291565, 0.2010498 , 0.11399841]), + 'left_gaze_origin': array([-2.9637208 , 3.03710485, 0.10855713]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.538909912109375, + 'left_pupil_posn': array([0.19370258, 0.00571978]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9662445783615112, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97789001, 0.16854858, 0.12367249]), + 'right_gaze_origin': array([-3.12118411, -3.35735345, 0.11018983]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3258056640625, + 'right_pupil_posn': array([ 0.18496335, -0.06720352]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1167699322104454, + 'throttle_input': 0.18252842128276825, + 'timestamp': 492.5678620673716, + 'timestamp_carla': 492568, + 'timestamp_device': 4230780, + 'timestamp_stream': 492.5678620673716, + 'transform': [array([-7.37726271e-01, -1.69533710e+01, 1.61233712e-02]), + array([-0.07583559, -0.90665305, -0.01436389])]} +{'AngularVelocity': array([ 0.04219167, -0.07847126, 5.27128792]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.889168739318848, + 'FR_Wheel_Angle': -7.782079696655273, + 'Location': array([ 1.25491869, -17.20585251, 0.16758274]), + 'Rotation': array([-6.76530227e-02, 4.19552765e+01, -6.62231632e-03]), + 'Velocity': array([-1.3734678 , -1.01410973, 0.0015637 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.73040771, 14.79497147, 1.86845243]), + 'camera_rotation': array([-8.76774979, 1.50993359, 3.91308856]), + 'current_gear_input': False, + 'focus_actor_dist': 2065.339111328125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-620.11499023, -995.39807129, 51.94996643]), + 'frame': 15062, + 'frame_number': 15062, + 'framesequence': 57827, + 'gaze_dir': array([0.97609711, 0.18208313, 0.11795807]), + 'gaze_origin': array([-3.04802179, -0.15785143, 0.11121293]), + 'gaze_valid': True, + 'gaze_vergence': 249.27549743652344, + 'handbrake_input': False, + 'left_eye_openness': 0.9964004158973694, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97428894, 0.19378662, 0.11489868]), + 'left_gaze_origin': array([-2.97615218, 3.04040694, 0.11189423]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.499420166015625, + 'left_pupil_posn': array([0.19225955, 0.00489652]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.994456946849823, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97790527, 0.17037964, 0.12101746]), + 'right_gaze_origin': array([-3.11989141, -3.35610986, 0.11053162]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.32611083984375, + 'right_pupil_posn': array([ 0.18152285, -0.06628156]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10492263734340668, + 'throttle_input': 0.1428549587726593, + 'timestamp': 492.60141506791115, + 'timestamp_carla': 492602, + 'timestamp_device': 4230814, + 'timestamp_stream': 492.60141506791115, + 'transform': [array([-7.94724107e-01, -1.68501740e+01, 1.57831572e-02]), + array([-0.07302155, -0.6764887 , -0.01251974])]} +{'AngularVelocity': array([0.0364135 , 0.02065184, 3.16488695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.1014404296875, + 'FR_Wheel_Angle': -6.650163173675537, + 'Location': array([ 0.95248592, -17.44834137, 0.16790371]), + 'Rotation': array([-5.55704162e-02, 4.29559059e+01, -1.12609854e-02]), + 'Velocity': array([-1.05192637, -0.84796584, 0.00166377]), + 'brake_input': 0.0, + 'camera_location': array([-5.66849613, 14.77150154, 1.88263535]), + 'camera_rotation': array([-8.57672977, 1.4807632 , 4.15283775]), + 'current_gear_input': False, + 'focus_actor_dist': 3087.62255859375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-8.29853577e+02, 1.36108398e+01, -1.52587891e-05]), + 'frame': 15063, + 'frame_number': 15063, + 'framesequence': 57831, + 'gaze_dir': array([0.9754715 , 0.18516541, 0.11855316]), + 'gaze_origin': array([-3.03975701, -0.15828095, 0.1044365 ]), + 'gaze_valid': True, + 'gaze_vergence': 286.1759338378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97436523, 0.19386292, 0.11407471]), + 'left_gaze_origin': array([-2.95930028, 3.03898501, 0.09876557]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5189971923828125, + 'left_pupil_posn': array([ 0.1951189 , -0.00030017]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97657776, 0.1764679 , 0.12303162]), + 'right_gaze_origin': array([-3.12021327, -3.35554671, 0.11010743]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.378021240234375, + 'right_pupil_posn': array([ 0.18114436, -0.0669831 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09280069172382355, + 'throttle_input': 0.1111009418964386, + 'timestamp': 492.63398776575923, + 'timestamp_carla': 492634, + 'timestamp_device': 4230847, + 'timestamp_stream': 492.63398776575923, + 'transform': [array([-8.44995260e-01, -1.67500706e+01, 1.53614990e-02]), + array([-0.07002993, -0.47451231, -0.01025894])]} +{'AngularVelocity': array([0.01969358, 0.03914464, 3.33434105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.228707313537598, + 'FR_Wheel_Angle': -8.973464012145996, + 'Location': array([ 0.73441285, -17.62981415, 0.1681945 ]), + 'Rotation': array([-5.63968681e-02, 4.36600266e+01, -2.19726544e-02]), + 'Velocity': array([-0.87913817, -0.7014482 , 0.00098194]), + 'brake_input': 0.0, + 'camera_location': array([-5.61461544, 14.71531391, 1.91612434]), + 'camera_rotation': array([-8.41485405, 1.37478936, 4.3289094 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3304.800537109375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-8.96751709e+02, 2.31651367e+02, 1.52587891e-05]), + 'frame': 15064, + 'frame_number': 15064, + 'framesequence': 57835, + 'gaze_dir': array([0.97654724, 0.18288422, 0.1127243 ]), + 'gaze_origin': array([-3.03247857, -0.16029511, 0.09601898]), + 'gaze_valid': True, + 'gaze_vergence': 200.4988555908203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97525024, 0.19418335, 0.10562134]), + 'left_gaze_origin': array([-2.94773722, 3.03600931, 0.09010316]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4989776611328125, + 'left_pupil_posn': array([ 0.19532931, -0.00492406]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97784424, 0.17158508, 0.11982727]), + 'right_gaze_origin': array([-3.11721969, -3.35659933, 0.10193481]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.318511962890625, + 'right_pupil_posn': array([ 0.18176126, -0.07497072]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08119144290685654, + 'throttle_input': 0.08332952111959457, + 'timestamp': 492.66732846572995, + 'timestamp_carla': 492668, + 'timestamp_device': 4230880, + 'timestamp_stream': 492.66732846572995, + 'transform': [array([-8.90910625e-01, -1.66480598e+01, 1.48312375e-02]), + array([-0.06695634, -0.29097563, -0.00754052])]} +{'AngularVelocity': array([-0.01262979, 0.01793738, 4.10545158]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.798847198486328, + 'FR_Wheel_Angle': -11.612523078918457, + 'Location': array([ 0.54463059, -17.78380013, 0.16845711]), + 'Rotation': array([-6.07886799e-02, 4.45304298e+01, -2.80456524e-02]), + 'Velocity': array([-0.80115139, -0.61466634, 0.00100067]), + 'brake_input': 0.0, + 'camera_location': array([-5.5840807 , 14.6709137 , 1.90160632]), + 'camera_rotation': array([-8.46450996, 1.16134953, 4.03413868]), + 'current_gear_input': False, + 'focus_actor_dist': 3039.588134765625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.39932495e+02, -1.79768066e+01, -2.89916992e-04]), + 'frame': 15065, + 'frame_number': 15065, + 'framesequence': 57839, + 'gaze_dir': array([0.97547913, 0.18621826, 0.11618805]), + 'gaze_origin': array([-3.03388214, -0.1604744 , 0.09632187]), + 'gaze_valid': True, + 'gaze_vergence': 171.1324462890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97389221, 0.199646 , 0.10798645]), + 'left_gaze_origin': array([-2.94979572, 3.03595448, 0.09426117]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4273834228515625, + 'left_pupil_posn': array([ 0.19584525, -0.00096631]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97706604, 0.17279053, 0.12438965]), + 'right_gaze_origin': array([-3.1179688 , -3.35690331, 0.09838258]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3589019775390625, + 'right_pupil_posn': array([ 0.18394887, -0.07670248]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07003998011350632, + 'throttle_input': 0.07539482414722443, + 'timestamp': 492.70069236680865, + 'timestamp_carla': 492701, + 'timestamp_device': 4230914, + 'timestamp_stream': 492.70069236680865, + 'transform': [array([-9.31335747e-01, -1.65467129e+01, 1.42365266e-02]), + array([-0.06406034, -0.13026626, -0.00455573])]} +{'AngularVelocity': array([-4.07319935e-03, 2.27298737e-02, 4.23388529e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.085221290588379, + 'FR_Wheel_Angle': -11.47260570526123, + 'Location': array([ 0.35811234, -17.93551826, 0.16896224]), + 'Rotation': array([-5.64583391e-02, 4.55231972e+01, -7.56835705e-03]), + 'Velocity': array([-0.79667151, -0.62842268, 0.00147429]), + 'brake_input': 0.0, + 'camera_location': array([-5.57143307, 14.62171936, 1.85757124]), + 'camera_rotation': array([-8.63051033, 1.1142534 , 3.84457827]), + 'current_gear_input': False, + 'focus_actor_dist': 3288.45458984375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-8.99995605e+02, 2.33828613e+02, -1.52587891e-05]), + 'frame': 15066, + 'frame_number': 15066, + 'framesequence': 57843, + 'gaze_dir': array([0.97579193, 0.183815 , 0.11755371]), + 'gaze_origin': array([-3.03171229, -0.16014862, 0.10024568]), + 'gaze_valid': True, + 'gaze_vergence': 191.5891571044922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97434998, 0.19606018, 0.11035156]), + 'left_gaze_origin': array([-2.94488239, 3.03652978, 0.09325562]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.469085693359375, + 'left_pupil_posn': array([ 0.19497883, -0.00063825]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97723389, 0.17156982, 0.12475586]), + 'right_gaze_origin': array([-3.11854267, -3.35682702, 0.10723571]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4085845947265625, + 'right_pupil_posn': array([ 0.18266606, -0.07003558]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.059694208204746246, + 'throttle_input': 0.059525445103645325, + 'timestamp': 492.7346321679652, + 'timestamp_carla': 492735, + 'timestamp_device': 4230947, + 'timestamp_stream': 492.7346321679652, + 'transform': [array([-9.66981471e-01, -1.64445705e+01, 1.35940742e-02]), + array([-0.06142389, 0.01059779, -0.00140701])]} +{'AngularVelocity': array([-0.01912688, 0.02293001, 3.37305331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.0195951461792, + 'FR_Wheel_Angle': -7.426102161407471, + 'Location': array([ 0.17432721, -18.09416199, 0.16919655]), + 'Rotation': array([-6.46340773e-02, 4.64002762e+01, -1.01928692e-02]), + 'Velocity': array([-8.46276939e-01, -7.40460694e-01, 6.66146283e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.59442616, 14.55686569, 1.85084856]), + 'camera_rotation': array([-8.82101822, 1.09646225, 3.95535207]), + 'current_gear_input': False, + 'focus_actor_dist': 3224.806396484375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-8.84737305e+02, 1.81830811e+02, -1.52587891e-05]), + 'frame': 15067, + 'frame_number': 15067, + 'framesequence': 57847, + 'gaze_dir': array([0.97601318, 0.18401337, 0.11524963]), + 'gaze_origin': array([-3.03041101, -0.16006547, 0.10031281]), + 'gaze_valid': True, + 'gaze_vergence': 157.62132263183594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97492981, 0.19598389, 0.10534668]), + 'left_gaze_origin': array([-2.94258118, 3.03672051, 0.09385072]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4797210693359375, + 'left_pupil_posn': array([0.19497883, 0.0002777 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97709656, 0.17204285, 0.12515259]), + 'right_gaze_origin': array([-3.11824036, -3.35685134, 0.10677491]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4019775390625, + 'right_pupil_posn': array([ 0.18261158, -0.07198143]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0490371435880661, + 'throttle_input': 0.03967345505952835, + 'timestamp': 492.7677964679897, + 'timestamp_carla': 492768, + 'timestamp_device': 4230980, + 'timestamp_stream': 492.7677964679897, + 'transform': [array([-9.96432185e-01, -1.63458691e+01, 1.29804416e-02]), + array([-0.05908113, 0.12618354, 0.00161744])]} +{'AngularVelocity': array([ 0.00234026, -0.02313492, 1.01947844]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.777984380722046, + 'FR_Wheel_Angle': -0.8604932427406311, + 'Location': array([ 8.22046306e-03, -1.82542057e+01, 1.69171557e-01]), + 'Rotation': array([-7.48042241e-02, 4.68178673e+01, -2.03857385e-02]), + 'Velocity': array([-8.61556232e-01, -8.63349497e-01, -2.38723747e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.59533787, 14.49778557, 1.88352919]), + 'camera_rotation': array([-8.75287342, 0.97682029, 3.46940732]), + 'current_gear_input': False, + 'focus_actor_dist': 2824.179443359375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.08228088e+02, -2.01948242e+02, -1.52587891e-05]), + 'frame': 15068, + 'frame_number': 15068, + 'framesequence': 57852, + 'gaze_dir': array([0.97549438, 0.18695831, 0.11468506]), + 'gaze_origin': array([-3.03128839, -0.16054231, 0.09726182]), + 'gaze_valid': True, + 'gaze_vergence': 156.7221221923828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97398376, 0.20063782, 0.10525513]), + 'left_gaze_origin': array([-2.94404149, 3.03652978, 0.0941681 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.495513916015625, + 'left_pupil_posn': array([ 1.95532322e-01, -1.67727470e-04]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.977005 , 0.17327881, 0.12411499]), + 'right_gaze_origin': array([-3.11853504, -3.35761428, 0.10035554]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3736114501953125, + 'right_pupil_posn': array([ 0.18477571, -0.07646084]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03944212198257446, + 'throttle_input': 0.0, + 'timestamp': 492.80186726525426, + 'timestamp_carla': 492802, + 'timestamp_device': 4231022, + 'timestamp_stream': 492.80186726525426, + 'transform': [array([-1.02099609e+00, -1.62456264e+01, 1.23820584e-02]), + array([-0.05690913, 0.22168878, 0.0045166 ])]} +{'AngularVelocity': array([ 0.01603368, 0.02682 , -0.78940439]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.6779321432113647, + 'FR_Wheel_Angle': 1.9331549406051636, + 'Location': array([ -0.20527658, -18.48155785, 0.16953979]), + 'Rotation': array([-7.84310549e-02, 4.68095207e+01, -2.09655743e-02]), + 'Velocity': array([-0.97915417, -1.07279742, 0.00142818]), + 'brake_input': 0.0, + 'camera_location': array([-5.61252022, 14.44553089, 1.92731714]), + 'camera_rotation': array([-8.54938126, 0.83416504, 3.10057855]), + 'current_gear_input': False, + 'focus_actor_dist': 2949.969970703125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.40722351e+02, -7.04423828e+01, 2.44140625e-04]), + 'frame': 15069, + 'frame_number': 15069, + 'framesequence': 57856, + 'gaze_dir': array([0.97687531, 0.1843338 , 0.10688019]), + 'gaze_origin': array([-3.02695489, -0.16353913, 0.09245377]), + 'gaze_valid': True, + 'gaze_vergence': 151.65435791015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97532654, 0.19825745, 0.09706116]), + 'left_gaze_origin': array([-2.9400804 , 3.03285527, 0.08973694]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5328521728515625, + 'left_pupil_posn': array([ 0.19691014, -0.00494266]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97842407, 0.17041016, 0.11669922]), + 'right_gaze_origin': array([-3.11382914, -3.35993361, 0.09517059]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4206695556640625, + 'right_pupil_posn': array([ 0.18527579, -0.08197558]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.028821682557463646, + 'throttle_input': 0.0, + 'timestamp': 492.8364238664508, + 'timestamp_carla': 492837, + 'timestamp_device': 4231055, + 'timestamp_stream': 492.8364238664508, + 'transform': [array([-1.03981078e+00, -1.61453953e+01, 1.18001550e-02]), + array([-0.05483958, 0.29380766, 0.00732422])]} +{'AngularVelocity': array([-0.05310971, -0.00376176, -3.09321117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.679876804351807, + 'FR_Wheel_Angle': 6.616227149963379, + 'Location': array([ -0.46214035, -18.76706696, 0.16992347]), + 'Rotation': array([-7.68737718e-02, 4.64219627e+01, -2.07824651e-02]), + 'Velocity': array([-1.05248153, -1.23589528, 0.00228079]), + 'brake_input': 0.0, + 'camera_location': array([-5.6677742 , 14.38576698, 1.96066594]), + 'camera_rotation': array([-8.3687849 , 0.70748156, 2.97025871]), + 'current_gear_input': False, + 'focus_actor_dist': 2764.012939453125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-788.9921875 , -239.86889648, 0. ]), + 'frame': 15070, + 'frame_number': 15070, + 'framesequence': 57859, + 'gaze_dir': array([0.97937775, 0.1726532 , 0.10418701]), + 'gaze_origin': array([-3.02788711, -0.1544075 , 0.08877487]), + 'gaze_valid': True, + 'gaze_vergence': 211.03956604003906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9786377 , 0.18133545, 0.09674072]), + 'left_gaze_origin': array([-2.93956304, 3.04473901, 0.08580323]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.509918212890625, + 'left_pupil_posn': array([ 0.18660688, -0.00921762]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9801178 , 0.16397095, 0.1116333 ]), + 'right_gaze_origin': array([-3.11621118, -3.35355401, 0.09174652]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.501617431640625, + 'right_pupil_posn': array([ 0.17502046, -0.08453584]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01820123940706253, + 'throttle_input': 0.0, + 'timestamp': 492.8672372661531, + 'timestamp_carla': 492867, + 'timestamp_device': 4231080, + 'timestamp_stream': 492.8672372661531, + 'transform': [array([-1.04638374e+00, -1.60578690e+01, 1.13846967e-02]), + array([-0.05056389, 0.3174291 , 0.00976563])]} +{'AngularVelocity': array([ 0.08170962, -0.0384089 , -6.05834723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.93262004852295, + 'FR_Wheel_Angle': 12.958691596984863, + 'Location': array([ -0.68004894, -19.0251236 , 0.17011447]), + 'Rotation': array([-7.51047581e-02, 4.54878387e+01, -1.75170861e-02]), + 'Velocity': array([-1.03364706e+00, -1.30866742e+00, 8.92086013e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.72399521, 14.37954235, 1.9984498 ]), + 'camera_rotation': array([-8.11515236, 0.58986205, 2.73510456]), + 'current_gear_input': False, + 'focus_actor_dist': 2823.052490234375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.64947998e+02, -1.64698486e+02, -1.06811523e-04]), + 'frame': 15071, + 'frame_number': 15071, + 'framesequence': 57863, + 'gaze_dir': array([0.98364258, 0.14956665, 0.09953308]), + 'gaze_origin': array([-3.04447341, -0.13994141, 0.09048691]), + 'gaze_valid': True, + 'gaze_vergence': 229.8616485595703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98240662, 0.16107178, 0.09446716]), + 'left_gaze_origin': array([-2.9737184 , 3.05629587, 0.0922638 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5302581787109375, + 'left_pupil_posn': array([ 0.17029941, -0.01288319]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98487854, 0.13806152, 0.104599 ]), + 'right_gaze_origin': array([-3.11522841, -3.33617878, 0.08871002]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.501373291015625, + 'right_pupil_posn': array([ 0.15598369, -0.08688247]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007141331676393747, + 'throttle_input': 0.0, + 'timestamp': 492.8999613672495, + 'timestamp_carla': 492900, + 'timestamp_device': 4231114, + 'timestamp_stream': 492.8999613672495, + 'transform': [array([-1.04806376e+00, -1.59664221e+01, 1.09010125e-02]), + array([-0.04809819, 0.32177231, 0.01220704])]} +{'AngularVelocity': array([ 0.06691924, -0.00779046, -6.5642314 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.32999324798584, + 'FR_Wheel_Angle': 18.293498992919922, + 'Location': array([ -0.88823807, -19.28434563, 0.17037407]), + 'Rotation': array([-5.26744165e-02, 4.39436836e+01, -2.72827167e-02]), + 'Velocity': array([-0.70286077, -0.95469445, 0.00100871]), + 'brake_input': 0.0, + 'camera_location': array([-5.79876709, 14.3651638 , 2.03854084]), + 'camera_rotation': array([-8.01608753, 0.55230892, 2.81852818]), + 'current_gear_input': False, + 'focus_actor_dist': 2875.991455078125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-702.87878418, -90.60375977, 0. ]), + 'frame': 15072, + 'frame_number': 15072, + 'framesequence': 57867, + 'gaze_dir': array([0.98413086, 0.14971924, 0.09408569]), + 'gaze_origin': array([-3.04581833, -0.13899001, 0.08990785]), + 'gaze_valid': True, + 'gaze_vergence': 192.36151123046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98301697, 0.16168213, 0.08674622]), + 'left_gaze_origin': array([-2.97996855, 3.05706501, 0.09337921]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.490386962890625, + 'left_pupil_posn': array([ 0.16972291, -0.01427889]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98524475, 0.13775635, 0.10142517]), + 'right_gaze_origin': array([-3.11166859, -3.33504486, 0.08643647]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4295196533203125, + 'right_pupil_posn': array([ 0.15530419, -0.0902667 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004266487900167704, + 'throttle_input': 0.0, + 'timestamp': 492.9335792660713, + 'timestamp_carla': 492934, + 'timestamp_device': 4231147, + 'timestamp_stream': 492.9335792660713, + 'transform': [array([-1.04876482e+00, -1.58737106e+01, 1.03866961e-02]), + array([-0.04815966, 0.32244414, 0.01446534])]} +{'AngularVelocity': array([ 0.023369 , 0.02231704, -5.93489885]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.334943771362305, + 'FR_Wheel_Angle': 22.83388328552246, + 'Location': array([ -0.99359494, -19.41942406, 0.17049342]), + 'Rotation': array([-4.89451326e-02, 4.28919640e+01, -3.30810472e-02]), + 'Velocity': array([-5.24300039e-01, -7.33276188e-01, -1.76820744e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.88462067, 14.32243347, 2.06310678]), + 'camera_rotation': array([-8.05154991, 0.57430536, 3.07304335]), + 'current_gear_input': False, + 'focus_actor_dist': 2651.867431640625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.63424438e+02, -3.02437988e+02, 1.22070312e-04]), + 'frame': 15073, + 'frame_number': 15073, + 'framesequence': 57871, + 'gaze_dir': array([0.98453522, 0.1492691 , 0.09059906]), + 'gaze_origin': array([-3.06631112, -0.1340439 , 0.09555054]), + 'gaze_valid': True, + 'gaze_vergence': 220.3369598388672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98310852, 0.16162109, 0.08569336]), + 'left_gaze_origin': array([-2.98262024, 3.06173873, 0.09204254]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5633087158203125, + 'left_pupil_posn': array([ 0.16628051, -0.01764953]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98596191, 0.13691711, 0.09550476]), + 'right_gaze_origin': array([-3.15000153, -3.32982659, 0.09905854]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4874267578125, + 'right_pupil_posn': array([ 0.15277088, -0.08921266]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.012103640474379063, + 'throttle_input': 0.0, + 'timestamp': 492.9672445654869, + 'timestamp_carla': 492967, + 'timestamp_device': 4231180, + 'timestamp_stream': 492.9672445654869, + 'transform': [array([-1.04928529e+00, -1.57820740e+01, 9.90577694e-03]), + array([-0.04944374, 0.32253534, 0.01644899])]} +{'AngularVelocity': array([-0.19698191, 0.05950363, -0.00118956]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.44124984741211, + 'FR_Wheel_Angle': 27.042892456054688, + 'Location': array([ -1.03799355, -19.47759628, 0.17043254]), + 'Rotation': array([-3.41236219e-02, 4.23998184e+01, -4.82788123e-02]), + 'Velocity': array([-6.12893564e-05, 2.19178022e-04, 1.03673781e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.01233864, 14.23901367, 2.06641769]), + 'camera_rotation': array([-8.12077332, 0.55665314, 3.43528628]), + 'current_gear_input': False, + 'focus_actor_dist': 2156.04248046875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-579.80999756, -781.88842773, 15.23049927]), + 'frame': 15074, + 'frame_number': 15074, + 'framesequence': 57875, + 'gaze_dir': array([0.98443604, 0.1493988 , 0.09106445]), + 'gaze_origin': array([-3.06852508, -0.13420258, 0.09846955]), + 'gaze_valid': True, + 'gaze_vergence': 173.71517944335938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98295593, 0.16368103, 0.08358765]), + 'left_gaze_origin': array([-2.98420882, 3.0608995 , 0.09511261]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.503753662109375, + 'left_pupil_posn': array([ 0.16627872, -0.01475751]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98591614, 0.13511658, 0.09854126]), + 'right_gaze_origin': array([-3.15284133, -3.3293047 , 0.10182648]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.482269287109375, + 'right_pupil_posn': array([ 0.15321589, -0.08855808]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01470381859689951, + 'throttle_input': 0.0, + 'timestamp': 493.00057166814804, + 'timestamp_carla': 493001, + 'timestamp_device': 4231214, + 'timestamp_stream': 493.00057166814804, + 'transform': [array([-1.04976118e+00, -1.56925554e+01, 9.49613564e-03]), + array([-0.05108298, 0.32253778, 0.01809693])]} +{'AngularVelocity': array([-0.06054355, 0.019859 , 0.00034588]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.959718704223633, + 'FR_Wheel_Angle': 27.40283203125, + 'Location': array([ -1.03806436, -19.47777176, 0.17057239]), + 'Rotation': array([-5.99963777e-02, 4.23999557e+01, -3.38134728e-02]), + 'Velocity': array([ 2.57170941e-05, 3.49638722e-05, -3.34710203e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.16388321, 14.13298798, 2.09620094]), + 'camera_rotation': array([-8.20541954, 0.3222867 , 3.51176095]), + 'current_gear_input': False, + 'focus_actor_dist': 2093.14794921875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-569.91357422, -835.07910156, 15.17958832]), + 'frame': 15075, + 'frame_number': 15075, + 'framesequence': 57879, + 'gaze_dir': array([0.98340607, 0.15436554, 0.09490204]), + 'gaze_origin': array([-3.0459199 , -0.13994752, 0.09258957]), + 'gaze_valid': True, + 'gaze_vergence': 265.8358459472656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.983078 , 0.16014099, 0.08891296]), + 'left_gaze_origin': array([-2.97412753, 3.05623484, 0.09219819]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5899658203125, + 'left_pupil_posn': array([ 0.17392886, -0.01440036]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98373413, 0.14859009, 0.10089111]), + 'right_gaze_origin': array([-3.1177125 , -3.33613014, 0.09298097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.43408203125, + 'right_pupil_posn': array([ 0.15573931, -0.08604801]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01508835144340992, + 'throttle_input': 0.0, + 'timestamp': 493.0332486666739, + 'timestamp_carla': 493033, + 'timestamp_device': 4231247, + 'timestamp_stream': 493.0332486666739, + 'transform': [array([-1.05022073e+00, -1.56059399e+01, 9.16107185e-03]), + array([-0.05270174, 0.32255745, 0.0194397 ])]} +{'AngularVelocity': array([ 8.53683159e-04, 2.55897595e-03, -9.84985471e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.755802154541016, + 'FR_Wheel_Angle': 27.1319637298584, + 'Location': array([ -1.04887331, -19.49271965, 0.17060214]), + 'Rotation': array([-7.05900043e-02, 4.22457848e+01, -2.68249493e-02]), + 'Velocity': array([-0.06450031, -0.09844332, -0.00102925]), + 'brake_input': 0.0, + 'camera_location': array([-6.28347683, 14.02267742, 2.17308068]), + 'camera_rotation': array([-8.00486469, 0.12698708, 3.42344999]), + 'current_gear_input': False, + 'focus_actor_dist': 2165.695556640625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-584.88708496, -755.10620117, 15.23560333]), + 'frame': 15076, + 'frame_number': 15076, + 'framesequence': 57883, + 'gaze_dir': array([0.97697449, 0.19302368, 0.0901413 ]), + 'gaze_origin': array([-3.04172444, -0.16126481, 0.08456116]), + 'gaze_valid': True, + 'gaze_vergence': 281.70489501953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97491455, 0.20384216, 0.08926392]), + 'left_gaze_origin': array([-2.9567399 , 3.03281569, 0.07991639]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5130462646484375, + 'left_pupil_posn': array([ 0.20107269, -0.02328622]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97903442, 0.1822052 , 0.09101868]), + 'right_gaze_origin': array([-3.12670922, -3.35534525, 0.08920594]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4449920654296875, + 'right_pupil_posn': array([ 0.18437958, -0.09121263]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.013623462989926338, + 'throttle_input': 0.0, + 'timestamp': 493.06714356690645, + 'timestamp_carla': 493067, + 'timestamp_device': 4231280, + 'timestamp_stream': 493.06714356690645, + 'transform': [array([-1.05067933e+00, -1.55173225e+01, 8.85959622e-03]), + array([-0.05419755, 0.32253614, 0.02059938])]} +{'AngularVelocity': array([ 0.01003239, -0.00240795, -0.74781698]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.75996208190918, + 'FR_Wheel_Angle': 27.14540672302246, + 'Location': array([ -1.06125641, -19.50965881, 0.17063393]), + 'Rotation': array([-6.86638877e-02, 4.20702171e+01, -2.85034087e-02]), + 'Velocity': array([-0.04981579, -0.07523523, -0.00072522]), + 'brake_input': 0.0, + 'camera_location': array([-6.42770195, 13.91525745, 2.21316457]), + 'camera_rotation': array([-7.67045927, 0.08503938, 3.22079563]), + 'current_gear_input': False, + 'focus_actor_dist': 2079.6220703125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-642.40148926, -845.4173584 , 15.15942383]), + 'frame': 15077, + 'frame_number': 15077, + 'framesequence': 57887, + 'gaze_dir': array([0.97838593, 0.18434906, 0.09311676]), + 'gaze_origin': array([-3.04627991, -0.16820146, 0.08844452]), + 'gaze_valid': True, + 'gaze_vergence': 326.60552978515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97659302, 0.19372559, 0.09346008]), + 'left_gaze_origin': array([-2.96610284, 3.02473021, 0.08534852]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5453948974609375, + 'left_pupil_posn': array([ 0.20414305, -0.02074528]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9782432317733765, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98017883, 0.17497253, 0.09277344]), + 'right_gaze_origin': array([-3.12645721, -3.3611331 , 0.09154053]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4172821044921875, + 'right_pupil_posn': array([ 0.18482912, -0.08795965]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.007910397835075855, + 'throttle_input': 0.0, + 'timestamp': 493.09963096678257, + 'timestamp_carla': 493100, + 'timestamp_device': 4231314, + 'timestamp_stream': 493.09963096678257, + 'transform': [array([-1.05112541e+00, -1.54335289e+01, 8.63996521e-03]), + array([-0.05542015, 0.32258332, 0.02148439])]} +{'AngularVelocity': array([0.08057058, 0.05779321, 0.02790607]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.83188819885254, + 'FR_Wheel_Angle': 27.264175415039062, + 'Location': array([ -1.0710541 , -19.52313995, 0.17062733]), + 'Rotation': array([-6.75369054e-02, 4.19301834e+01, -2.95104906e-02]), + 'Velocity': array([-0.03563125, -0.03742221, 0.0009085 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.53898048, 13.84258652, 2.22764444]), + 'camera_rotation': array([-7.32017994e+00, 7.11625302e-03, 2.72320104e+00]), + 'current_gear_input': False, + 'focus_actor_dist': 2799.42431640625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.63919983e+02, -1.26633789e+02, -1.52587891e-05]), + 'frame': 15078, + 'frame_number': 15078, + 'framesequence': 57891, + 'gaze_dir': array([0.97853851, 0.18487549, 0.08953857]), + 'gaze_origin': array([-3.04090667, -0.17249757, 0.08298492]), + 'gaze_valid': True, + 'gaze_vergence': 195.1505126953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97543335, 0.20010376, 0.09202576]), + 'left_gaze_origin': array([-2.95432758, 3.02047896, 0.07969361]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5272674560546875, + 'left_pupil_posn': array([ 0.20506036, -0.02411127]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9771603941917419, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98164368, 0.16964722, 0.08705139]), + 'right_gaze_origin': array([-3.12748599, -3.36547422, 0.08627625]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3040618896484375, + 'right_pupil_posn': array([ 0.19015646, -0.09203601]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005310220876708627, + 'throttle_input': 0.0, + 'timestamp': 493.13303446769714, + 'timestamp_carla': 493133, + 'timestamp_device': 4231347, + 'timestamp_stream': 493.13303446769714, + 'transform': [array([-1.05157328e+00, -1.53485498e+01, 8.44907761e-03]), + array([-0.05649249, 0.32259983, 0.02221681])]} +{'AngularVelocity': array([0.05626512, 0.05181883, 0.16944033]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.84686851501465, + 'FR_Wheel_Angle': 27.27772331237793, + 'Location': array([ -1.0764271 , -19.5304966 , 0.17068736]), + 'Rotation': array([-6.76257014e-02, 4.18584976e+01, -2.93273870e-02]), + 'Velocity': array([-0.02202691, -0.0183298 , 0.00057161]), + 'brake_input': 0.0, + 'camera_location': array([-6.55683994, 13.80189133, 2.29700756]), + 'camera_rotation': array([-6.78550577, -0.05138334, 2.42555451]), + 'current_gear_input': False, + 'focus_actor_dist': 3049.8466796875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-8.07905884e+02, 1.28494385e+02, -1.52587891e-05]), + 'frame': 15079, + 'frame_number': 15079, + 'framesequence': 57895, + 'gaze_dir': array([0.97885132, 0.18791199, 0.07975006]), + 'gaze_origin': array([-3.04771042, -0.17661211, 0.07861558]), + 'gaze_valid': True, + 'gaze_vergence': 212.41470336914062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97740173, 0.198349 , 0.07301331]), + 'left_gaze_origin': array([-2.96768212, 3.01712656, 0.07695466]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5063629150390625, + 'left_pupil_posn': array([ 0.2101742 , -0.02870059]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9803009 , 0.17747498, 0.08648682]), + 'right_gaze_origin': array([-3.12773919, -3.37035108, 0.08027649]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.319244384765625, + 'right_pupil_posn': array([ 0.19270945, -0.10277104]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011297952383756638, + 'throttle_input': 0.0, + 'timestamp': 493.1676191687584, + 'timestamp_carla': 493168, + 'timestamp_device': 4231380, + 'timestamp_stream': 493.1676191687584, + 'transform': [array([-1.05200970e+00, -1.52618103e+01, 8.28775391e-03]), + array([-0.05743506, 0.32253444, 0.02279664])]} +{'AngularVelocity': array([-0.07315357, -0.05524284, -0.72180611]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.849048614501953, + 'FR_Wheel_Angle': 27.278432846069336, + 'Location': array([ -1.07949066, -19.53484154, 0.17068245]), + 'Rotation': array([-6.83906823e-02, 4.18111076e+01, -2.81372070e-02]), + 'Velocity': array([-0.01054728, -0.03351733, -0.00028831]), + 'brake_input': 0.0, + 'camera_location': array([-6.61030197, 13.76823425, 2.32361197]), + 'camera_rotation': array([-6.62879372, -0.08299825, 2.45553708]), + 'current_gear_input': False, + 'focus_actor_dist': 3067.565673828125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-814.99768066, 153.63476562, 0. ]), + 'frame': 15080, + 'frame_number': 15080, + 'framesequence': 57899, + 'gaze_dir': array([0.97851562, 0.19054413, 0.07740784]), + 'gaze_origin': array([-3.04776645, -0.17995988, 0.07963791]), + 'gaze_valid': True, + 'gaze_vergence': 227.7100830078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97624207, 0.20343018, 0.07446289]), + 'left_gaze_origin': array([-2.96627975, 3.01335764, 0.07763367]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5859375, + 'left_pupil_posn': array([ 0.21274722, -0.03006268]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98078918, 0.17765808, 0.08035278]), + 'right_gaze_origin': array([-3.12925291, -3.37327766, 0.08164215]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.21734619140625, + 'right_pupil_posn': array([ 0.19663894, -0.1015296 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.020197151228785515, + 'throttle_input': 0.0, + 'timestamp': 493.20017686858773, + 'timestamp_carla': 493200, + 'timestamp_device': 4231414, + 'timestamp_stream': 493.20017686858773, + 'transform': [array([-1.05840731e+00, -1.51807213e+01, 8.12396966e-03]), + array([-0.0608843 , 0.34627202, 0.02319337])]} +{'AngularVelocity': array([-0.06572592, -0.04815789, -0.74639839]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.996030807495117, + 'FR_Wheel_Angle': 27.655101776123047, + 'Location': array([ -1.08375216, -19.54064369, 0.17071186]), + 'Rotation': array([-6.90941885e-02, 4.17491951e+01, -2.76184063e-02]), + 'Velocity': array([-0.01564476, -0.03867717, 0.0003162 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.66659164, 13.77921104, 2.35335803]), + 'camera_rotation': array([-6.67477465, -0.13766438, 2.05723143]), + 'current_gear_input': False, + 'focus_actor_dist': 3080.3798828125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-823.75714111, 173.57958984, 0. ]), + 'frame': 15081, + 'frame_number': 15081, + 'framesequence': 57903, + 'gaze_dir': array([0.97867584, 0.19032288, 0.07593536]), + 'gaze_origin': array([-3.04872298, -0.18164903, 0.07787324]), + 'gaze_valid': True, + 'gaze_vergence': 209.08404541015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97673035, 0.2026062 , 0.07026672]), + 'left_gaze_origin': array([-2.96670079, 3.01161957, 0.077742 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5057373046875, + 'left_pupil_posn': array([ 0.21404576, -0.02970314]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98062134, 0.17803955, 0.081604 ]), + 'right_gaze_origin': array([-3.13074517, -3.37491775, 0.07800446]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2396087646484375, + 'right_pupil_posn': array([ 0.19748747, -0.10569239]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0293527040630579, + 'throttle_input': 0.0, + 'timestamp': 493.2327388674021, + 'timestamp_carla': 493233, + 'timestamp_device': 4231447, + 'timestamp_stream': 493.2327388674021, + 'transform': [array([-1.07010531e+00, -1.51002350e+01, 7.97946937e-03]), + array([-0.06451114, 0.39069828, 0.02346803])]} +{'AngularVelocity': array([-0.07145294, -0.05651317, -0.93946898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.05266571044922, + 'FR_Wheel_Angle': 29.315536499023438, + 'Location': array([ -1.08984518, -19.54892921, 0.17070316]), + 'Rotation': array([-6.97362274e-02, 4.16585693e+01, -2.69165039e-02]), + 'Velocity': array([-2.33968198e-02, -5.36716208e-02, 9.32788826e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.69259071, 13.85177898, 2.397542 ]), + 'camera_rotation': array([-6.48439693, -0.08287023, 1.57906103]), + 'current_gear_input': False, + 'focus_actor_dist': 3018.536865234375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-807.74279785, 121.68188477, 0. ]), + 'frame': 15082, + 'frame_number': 15082, + 'framesequence': 57908, + 'gaze_dir': array([0.97904968, 0.19081116, 0.06938934]), + 'gaze_origin': array([-3.04615188, -0.1807068 , 0.07708741]), + 'gaze_valid': True, + 'gaze_vergence': 196.04495239257812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97703552, 0.20347595, 0.06298828]), + 'left_gaze_origin': array([-2.96096683, 3.01338983, 0.07786866]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4443359375, + 'left_pupil_posn': array([ 0.21284068, -0.03036833]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98106384, 0.17814636, 0.07579041]), + 'right_gaze_origin': array([-3.13133717, -3.37480354, 0.07630616]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.239349365234375, + 'right_pupil_posn': array([ 0.19765794, -0.10958052]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.039185769855976105, + 'throttle_input': 0.0, + 'timestamp': 493.2685949653387, + 'timestamp_carla': 493269, + 'timestamp_device': 4231489, + 'timestamp_stream': 493.2685949653387, + 'transform': [array([-1.08782327e+00, -1.50124626e+01, 7.83672277e-03]), + array([-0.06781011, 0.45823491, 0.02365114])]} +{'AngularVelocity': array([ 0.032363 , -0.05869603, -4.72797537]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.579286575317383, + 'FR_Wheel_Angle': 30.0623836517334, + 'Location': array([ -1.13540149, -19.61180115, 0.17086338]), + 'Rotation': array([-8.41410980e-02, 4.09505653e+01, -1.44958515e-02]), + 'Velocity': array([-0.24471006, -0.39653233, 0.00046105]), + 'brake_input': 0.0, + 'camera_location': array([-6.71141529, 13.95739746, 2.48352027]), + 'camera_rotation': array([-6.23325777, 0.0186842 , 1.61358333]), + 'current_gear_input': False, + 'focus_actor_dist': 2910.419921875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-7.90858765e+02, 2.26577148e+01, -1.52587891e-05]), + 'frame': 15083, + 'frame_number': 15083, + 'framesequence': 57911, + 'gaze_dir': array([0.97899628, 0.19471741, 0.05850983]), + 'gaze_origin': array([-3.04704905, -0.17793427, 0.07188492]), + 'gaze_valid': True, + 'gaze_vergence': 171.10105895996094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97727966, 0.20603943, 0.04960632]), + 'left_gaze_origin': array([-2.96340489, 3.01612878, 0.07270813]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.280242919921875, + 'left_pupil_posn': array([ 0.21283221, -0.03709579]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98071289, 0.18339539, 0.06741333]), + 'right_gaze_origin': array([-3.13069344, -3.37199712, 0.07106171]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2322540283203125, + 'right_pupil_posn': array([ 0.19650412, -0.11771476]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05008087679743767, + 'throttle_input': 0.0, + 'timestamp': 493.2991990670562, + 'timestamp_carla': 493299, + 'timestamp_device': 4231514, + 'timestamp_stream': 493.2991990670562, + 'transform': [array([-1.10698020e+00, -1.49382172e+01, 7.79167144e-03]), + array([-0.07025532, 0.53145814, 0.02371217])]} +{'AngularVelocity': array([ 0.1593558 , -0.029716 , -5.86896324]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.089750289916992, + 'FR_Wheel_Angle': 30.989171981811523, + 'Location': array([ -1.20945108, -19.71172333, 0.17093754]), + 'Rotation': array([-8.11767951e-02, 3.98004303e+01, -1.80358868e-02]), + 'Velocity': array([-3.49971682e-01, -5.29238641e-01, 3.32994445e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.67553616, 14.02019691, 2.57299042]), + 'camera_rotation': array([-5.86252165, 0.14093454, 2.12552881]), + 'current_gear_input': False, + 'focus_actor_dist': 2548.000732421875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.36046936e+02, -3.27852051e+02, 5.18798828e-04]), + 'frame': 15084, + 'frame_number': 15084, + 'framesequence': 57915, + 'gaze_dir': array([0.97875977, 0.19483185, 0.06203461]), + 'gaze_origin': array([-3.05554295, -0.17615433, 0.06442337]), + 'gaze_valid': True, + 'gaze_vergence': 169.07049560546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97706604, 0.20622253, 0.05299377]), + 'left_gaze_origin': array([-2.97976851, 3.01862049, 0.06625366]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2599639892578125, + 'left_pupil_posn': array([ 0.21150959, -0.04289293]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98045349, 0.18344116, 0.07107544]), + 'right_gaze_origin': array([-3.13131738, -3.37092924, 0.06259309]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1745758056640625, + 'right_pupil_posn': array([ 0.19591188, -0.12226546]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.058833587914705276, + 'throttle_input': 0.0, + 'timestamp': 493.3338135667145, + 'timestamp_carla': 493334, + 'timestamp_device': 4231547, + 'timestamp_stream': 493.3338135667145, + 'transform': [array([-1.13278592e+00, -1.48550806e+01, 7.72823300e-03]), + array([-0.07248196, 0.63001853, 0.02371218])]} +{'AngularVelocity': array([ 0.03340996, -0.01429415, -3.77586842]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.783597946166992, + 'FR_Wheel_Angle': 33.85133361816406, + 'Location': array([ -1.27731097, -19.80245018, 0.17091052]), + 'Rotation': array([-6.27216250e-02, 3.86954536e+01, -3.29894982e-02]), + 'Velocity': array([-2.10738495e-01, -3.20088118e-01, 1.78213115e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.66842079, 14.06172657, 2.58188653]), + 'camera_rotation': array([-5.63439369, 0.1896883 , 2.42825961]), + 'current_gear_input': False, + 'focus_actor_dist': 3002.861572265625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-841.48748779, 122.71411133, 0. ]), + 'frame': 15085, + 'frame_number': 15085, + 'framesequence': 57919, + 'gaze_dir': array([0.97824097, 0.19895172, 0.05778503]), + 'gaze_origin': array([-3.05242252, -0.17573319, 0.06098252]), + 'gaze_valid': True, + 'gaze_vergence': 265.18878173828125, + 'handbrake_input': False, + 'left_eye_openness': 0.9644083976745605, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97686768, 0.20724487, 0.05241394]), + 'left_gaze_origin': array([-2.97446609, 3.0191865 , 0.06130524]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2088470458984375, + 'left_pupil_posn': array([ 0.21356463, -0.0479455 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97961426, 0.19065857, 0.06315613]), + 'right_gaze_origin': array([-3.13037896, -3.37065315, 0.06065979]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17669677734375, + 'right_pupil_posn': array([ 0.19604921, -0.12361193]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06868495792150497, + 'throttle_input': 0.0, + 'timestamp': 493.36684116721153, + 'timestamp_carla': 493367, + 'timestamp_device': 4231580, + 'timestamp_stream': 493.36684116721153, + 'transform': [array([-1.16122389e+00, -1.47765827e+01, 7.71022774e-03]), + array([-0.07419634, 0.73853487, 0.02365114])]} +{'AngularVelocity': array([-0.09002686, 0.0096826 , -3.23983455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.098678588867188, + 'FR_Wheel_Angle': 33.822242736816406, + 'Location': array([ -1.32114589, -19.8610611 , 0.17096791]), + 'Rotation': array([-6.35070950e-02, 3.79246712e+01, -3.17687914e-02]), + 'Velocity': array([-1.75896481e-01, -2.59597808e-01, 1.80959702e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.65400124, 14.07217598, 2.54202294]), + 'camera_rotation': array([-5.76091576, 0.21595725, 2.76349831]), + 'current_gear_input': False, + 'focus_actor_dist': 1852.938720703125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-614.45593262, -995.38256836, 49.77427673]), + 'frame': 15086, + 'frame_number': 15086, + 'framesequence': 57923, + 'gaze_dir': array([0.97860718, 0.19516754, 0.06385803]), + 'gaze_origin': array([-3.05253482, -0.17482224, 0.06274262]), + 'gaze_valid': True, + 'gaze_vergence': 211.1181640625, + 'handbrake_input': False, + 'left_eye_openness': 0.9721387028694153, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97706604, 0.20516968, 0.05690002]), + 'left_gaze_origin': array([-2.97360396, 3.02013707, 0.06188202]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.272216796875, + 'left_pupil_posn': array([ 0.21099162, -0.04482388]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98014832, 0.18516541, 0.07081604]), + 'right_gaze_origin': array([-3.1314652 , -3.36978173, 0.06360321]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1866607666015625, + 'right_pupil_posn': array([ 0.19478214, -0.12023616]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0791039764881134, + 'throttle_input': 0.0, + 'timestamp': 493.4013306684792, + 'timestamp_carla': 493402, + 'timestamp_device': 4231614, + 'timestamp_stream': 493.4013306684792, + 'transform': [array([-1.19508314e+00, -1.46954918e+01, 7.69655220e-03]), + array([-0.07577411, 0.86754638, 0.02352908])]} +{'AngularVelocity': array([ 0.01938449, -0.00355959, -2.94847965]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.534048080444336, + 'FR_Wheel_Angle': 33.02944564819336, + 'Location': array([ -1.36684275, -19.9196167 , 0.17104973]), + 'Rotation': array([-6.70519620e-02, 3.71562805e+01, -2.90832482e-02]), + 'Velocity': array([-1.69467717e-01, -2.40131542e-01, 1.86424251e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.6669569 , 14.07018661, 2.45158744]), + 'camera_rotation': array([-6.12736225, 0.26230884, 2.88150907]), + 'current_gear_input': False, + 'focus_actor_dist': 3095.688720703125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-879.57250977, 225.51293945, 0. ]), + 'frame': 15087, + 'frame_number': 15087, + 'framesequence': 57927, + 'gaze_dir': array([0.97775269, 0.19593048, 0.07372284]), + 'gaze_origin': array([-3.05568933, -0.17494737, 0.07078858]), + 'gaze_valid': True, + 'gaze_vergence': 237.3612823486328, + 'handbrake_input': False, + 'left_eye_openness': 0.9825667142868042, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97511292, 0.20866394, 0.07489014]), + 'left_gaze_origin': array([-2.97984171, 3.01915002, 0.06918946]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1869659423828125, + 'left_pupil_posn': array([ 0.2111249 , -0.04030252]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98039246, 0.18319702, 0.07255554]), + 'right_gaze_origin': array([-3.1315372 , -3.36904454, 0.0723877 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.972808837890625, + 'right_pupil_posn': array([ 0.19580793, -0.10770905]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09049348533153534, + 'throttle_input': 0.0, + 'timestamp': 493.43386886641383, + 'timestamp_carla': 493434, + 'timestamp_device': 4231647, + 'timestamp_stream': 493.43386886641383, + 'transform': [array([-1.23112810e+00, -1.46197968e+01, 7.71924946e-03]), + array([-0.07721528, 1.00478637, 0.02334598])]} +{'AngularVelocity': array([ 7.13786867e-04, -2.10261205e-03, -2.03065681e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.223657608032227, + 'FR_Wheel_Angle': 32.349708557128906, + 'Location': array([ -1.40199256, -19.96327591, 0.17108734]), + 'Rotation': array([-6.49687573e-02, 3.65857468e+01, -3.02734319e-02]), + 'Velocity': array([-1.20195732e-01, -1.65474072e-01, -5.30052166e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.67096519, 14.03616905, 2.40622616]), + 'camera_rotation': array([-6.48727894, 0.22918546, 2.72898769]), + 'current_gear_input': False, + 'focus_actor_dist': 3334.75244140625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.45741394e+02, 4.63898193e+02, -1.98364258e-04]), + 'frame': 15088, + 'frame_number': 15088, + 'framesequence': 57931, + 'gaze_dir': array([0.9782486 , 0.19548035, 0.06801605]), + 'gaze_origin': array([-3.04856801, -0.17626038, 0.07508087]), + 'gaze_valid': True, + 'gaze_vergence': 220.94761657714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97547913, 0.207901 , 0.07208252]), + 'left_gaze_origin': array([-2.96625829, 3.01804209, 0.07346344]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.219146728515625, + 'left_pupil_posn': array([ 0.21166193, -0.03777158]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98101807, 0.18305969, 0.06394958]), + 'right_gaze_origin': array([-3.13087773, -3.37056303, 0.07669831]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0303802490234375, + 'right_pupil_posn': array([ 0.19651866, -0.1057241 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09974059462547302, + 'throttle_input': 0.0, + 'timestamp': 493.46692476794124, + 'timestamp_carla': 493467, + 'timestamp_device': 4231680, + 'timestamp_stream': 493.46692476794124, + 'transform': [array([-1.27136505e+00, -1.45437689e+01, 7.74919474e-03]), + array([-0.07833543, 1.15767336, 0.02313235])]} +{'AngularVelocity': array([-6.10148581e-03, -3.49686248e-04, -1.32750535e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.301477432250977, + 'FR_Wheel_Angle': 30.95347023010254, + 'Location': array([ -1.42696071, -19.9933033 , 0.17111991]), + 'Rotation': array([-6.53375834e-02, 3.61999016e+01, -2.95410063e-02]), + 'Velocity': array([-0.08448083, -0.11142725, 0.00027014]), + 'brake_input': 0.0, + 'camera_location': array([-6.68832207, 13.99854851, 2.38699102]), + 'camera_rotation': array([-6.61693668, 0.11463632, 2.41712499]), + 'current_gear_input': False, + 'focus_actor_dist': 2614.205810546875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-790.87518311, -233.17211914, 0. ]), + 'frame': 15089, + 'frame_number': 15089, + 'framesequence': 57935, + 'gaze_dir': array([0.97725677, 0.2000351 , 0.06960297]), + 'gaze_origin': array([-3.04952025, -0.17825699, 0.07775956]), + 'gaze_valid': True, + 'gaze_vergence': 321.69866943359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97544861, 0.20935059, 0.06819153]), + 'left_gaze_origin': array([-2.96819329, 3.01602507, 0.07770234]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1847686767578125, + 'left_pupil_posn': array([ 0.21566558, -0.03315663]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97906494, 0.1907196 , 0.0710144 ]), + 'right_gaze_origin': array([-3.13084722, -3.37253881, 0.07781678]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.889312744140625, + 'right_pupil_posn': array([ 0.1983794 , -0.10629725]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10827357321977615, + 'throttle_input': 0.0, + 'timestamp': 493.4997581653297, + 'timestamp_carla': 493500, + 'timestamp_device': 4231713, + 'timestamp_stream': 493.4997581653297, + 'transform': [array([-1.31441629e+00, -1.44691753e+01, 7.79720303e-03]), + array([-0.07906627, 1.3208766 , 0.02288821])]} +{'AngularVelocity': array([-6.23039203e-03, -2.20602815e-05, -8.86641324e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.012666702270508, + 'FR_Wheel_Angle': 30.548856735229492, + 'Location': array([ -1.44432676, -20.01360703, 0.17113754]), + 'Rotation': array([-6.61913604e-02, 3.59451332e+01, -2.81982385e-02]), + 'Velocity': array([-0.05829762, -0.07532105, -0.00012129]), + 'brake_input': 0.0, + 'camera_location': array([-6.66438198, 13.98233318, 2.41180539]), + 'camera_rotation': array([-6.39400625e+00, -5.40376967e-03, 2.31669044e+00]), + 'current_gear_input': False, + 'focus_actor_dist': 2632.569580078125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.08329956e+02, -2.10844727e+02, 1.52587891e-05]), + 'frame': 15090, + 'frame_number': 15090, + 'framesequence': 57939, + 'gaze_dir': array([0.97666931, 0.20446014, 0.06476593]), + 'gaze_origin': array([-3.05268264, -0.18178025, 0.07198106]), + 'gaze_valid': True, + 'gaze_vergence': 309.9861145019531, + 'handbrake_input': False, + 'left_eye_openness': 0.9955016374588013, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97480774, 0.21394348, 0.06280518]), + 'left_gaze_origin': array([-2.97188735, 3.01289845, 0.07215729]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1695709228515625, + 'left_pupil_posn': array([ 0.21931529, -0.03904021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9882845878601074, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97853088, 0.19497681, 0.06672668]), + 'right_gaze_origin': array([-3.13347793, -3.37645888, 0.07180481]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0294189453125, + 'right_pupil_posn': array([ 0.20270681, -0.11289561]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11647695302963257, + 'throttle_input': 0.0, + 'timestamp': 493.5332239679992, + 'timestamp_carla': 493533, + 'timestamp_device': 4231747, + 'timestamp_stream': 493.5332239679992, + 'transform': [array([-1.36116850e+00, -1.43941269e+01, 7.85446167e-03]), + array([-0.07949657, 1.4976691 , 0.02261355])]} +{'AngularVelocity': array([-0.0040334 , 0.0313782 , -1.13141203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.87239646911621, + 'FR_Wheel_Angle': 30.397512435913086, + 'Location': array([ -1.45808697, -20.02924347, 0.17116302]), + 'Rotation': array([-6.71066046e-02, 3.57382660e+01, -2.74353046e-02]), + 'Velocity': array([-5.25515452e-02, -5.51877916e-02, -3.56292730e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.63223076, 13.96453285, 2.43458271]), + 'camera_rotation': array([-6.25355673, -0.10781302, 2.56376147]), + 'current_gear_input': False, + 'focus_actor_dist': 2595.42236328125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.13065430e+02, -2.42796875e+02, -1.52587891e-05]), + 'frame': 15091, + 'frame_number': 15091, + 'framesequence': 57943, + 'gaze_dir': array([0.97689819, 0.20292664, 0.06647491]), + 'gaze_origin': array([-3.05285358, -0.18294373, 0.07171478]), + 'gaze_valid': True, + 'gaze_vergence': 418.65460205078125, + 'handbrake_input': False, + 'left_eye_openness': 0.996911346912384, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97546387, 0.21012878, 0.06562805]), + 'left_gaze_origin': array([-2.97188735, 3.01199961, 0.07184143]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1544036865234375, + 'left_pupil_posn': array([ 0.2201966 , -0.03904021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.975479245185852, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97833252, 0.19572449, 0.06732178]), + 'right_gaze_origin': array([-3.13381958, -3.37788725, 0.07158814]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0203399658203125, + 'right_pupil_posn': array([ 0.2023803 , -0.11200857]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12317880988121033, + 'throttle_input': 0.0, + 'timestamp': 493.5663128681481, + 'timestamp_carla': 493567, + 'timestamp_device': 4231780, + 'timestamp_stream': 493.5663128681481, + 'transform': [array([-1.40970445e+00, -1.43209372e+01, 7.93867093e-03]), + array([-0.07959219, 1.68069172, 0.02227786])]} +{'AngularVelocity': array([-0.01653788, 0.03676073, -0.94174898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.874502182006836, + 'FR_Wheel_Angle': 30.37610626220703, + 'Location': array([ -1.46498811, -20.03690338, 0.17116801]), + 'Rotation': array([-6.75642267e-02, 3.56337128e+01, -2.65808105e-02]), + 'Velocity': array([-0.04017568, -0.03932165, -0.00025196]), + 'brake_input': 0.0, + 'camera_location': array([-6.60888958, 13.99258995, 2.46613955]), + 'camera_rotation': array([-6.26452637, -0.22018923, 2.58821607]), + 'current_gear_input': False, + 'focus_actor_dist': 2766.100830078125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.52943176e+02, -6.91965332e+01, -1.52587891e-04]), + 'frame': 15092, + 'frame_number': 15092, + 'framesequence': 57947, + 'gaze_dir': array([0.97554016, 0.20392609, 0.08128357]), + 'gaze_origin': array([-3.05051517, -0.17719422, 0.08057175]), + 'gaze_valid': True, + 'gaze_vergence': 302.0284423828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97344971, 0.21400452, 0.08113098]), + 'left_gaze_origin': array([-2.9704926 , 3.01571202, 0.07958069]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1107177734375, + 'left_pupil_posn': array([ 0.21711838, -0.02867329]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97763062, 0.19384766, 0.08143616]), + 'right_gaze_origin': array([-3.13053775, -3.37010074, 0.08156281]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.001800537109375, + 'right_pupil_posn': array([ 0.19844258, -0.09928882]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1282326877117157, + 'throttle_input': 0.0, + 'timestamp': 493.6004532687366, + 'timestamp_carla': 493601, + 'timestamp_device': 4231813, + 'timestamp_stream': 493.6004532687366, + 'transform': [array([-1.46146846e+00, -1.42465353e+01, 8.03289376e-03]), + array([-0.07925751, 1.87520874, 0.02191164])]} +{'AngularVelocity': array([ 0.00722921, -0.0392859 , 0.28862542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.782297134399414, + 'FR_Wheel_Angle': 30.22446632385254, + 'Location': array([ -1.4705534 , -20.04330444, 0.17115062]), + 'Rotation': array([-6.82335868e-02, 3.55553398e+01, -2.54516602e-02]), + 'Velocity': array([-0.00493836, -0.01901664, -0.00123328]), + 'brake_input': 0.0, + 'camera_location': array([-6.59284973, 14.0153513 , 2.48921824]), + 'camera_rotation': array([-6.24375582, -0.32296139, 2.81011915]), + 'current_gear_input': False, + 'focus_actor_dist': 3733.3876953125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1086.30004883, 877.9621582 , 6.41590881]), + 'frame': 15093, + 'frame_number': 15093, + 'framesequence': 57952, + 'gaze_dir': array([0.97562408, 0.20384216, 0.08081818]), + 'gaze_origin': array([-3.05190134, -0.17828217, 0.07913208]), + 'gaze_valid': True, + 'gaze_vergence': 414.9358825683594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97410583, 0.21118164, 0.08071899]), + 'left_gaze_origin': array([-2.97291899, 3.0150423 , 0.07756958]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.14129638671875, + 'left_pupil_posn': array([ 0.21849859, -0.03072071]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97714233, 0.19650269, 0.08091736]), + 'right_gaze_origin': array([-3.13088417, -3.37160683, 0.08069459]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9803466796875, + 'right_pupil_posn': array([ 0.19849312, -0.10000372]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13123570382595062, + 'throttle_input': 0.0, + 'timestamp': 493.6356717683375, + 'timestamp_carla': 493636, + 'timestamp_device': 4231855, + 'timestamp_stream': 493.6356717683375, + 'transform': [array([-1.51576471e+00, -1.41710043e+01, 8.14882293e-03]), + array([-0.07843105, 2.07839656, 0.0214844 ])]} +{'AngularVelocity': array([ 0.04467751, -0.01459879, -1.39659512]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.748424530029297, + 'FR_Wheel_Angle': 30.20634651184082, + 'Location': array([ -1.49033582, -20.06544113, 0.1712514 ]), + 'Rotation': array([-7.31171742e-02, 3.52662582e+01, -2.16979980e-02]), + 'Velocity': array([-9.95494798e-02, -1.25803813e-01, 1.07374188e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.57136822, 14.03343582, 2.45992637]), + 'camera_rotation': array([-6.33862019, -0.44063517, 2.91618299]), + 'current_gear_input': False, + 'focus_actor_dist': 3727.111572265625, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1091.97998047, 877.39477539, 3.27377319]), + 'frame': 15094, + 'frame_number': 15094, + 'framesequence': 57955, + 'gaze_dir': array([0.97574615, 0.20291901, 0.08166504]), + 'gaze_origin': array([-3.05173039, -0.17874147, 0.07944184]), + 'gaze_valid': True, + 'gaze_vergence': 416.9696960449219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97424316, 0.21022034, 0.08148193]), + 'left_gaze_origin': array([-2.9721818 , 3.01468515, 0.07790986]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.083892822265625, + 'left_pupil_posn': array([ 0.21847796, -0.02991796]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97724915, 0.19561768, 0.08184814]), + 'right_gaze_origin': array([-3.13127899, -3.37216806, 0.08097382]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.990264892578125, + 'right_pupil_posn': array([ 0.19854593, -0.09963739]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13194982707500458, + 'throttle_input': 0.0, + 'timestamp': 493.6667385660112, + 'timestamp_carla': 493667, + 'timestamp_device': 4231880, + 'timestamp_stream': 493.6667385660112, + 'transform': [array([-1.56393480e+00, -1.41053991e+01, 8.29885434e-03]), + array([-0.07735872, 2.25803614, 0.02108767])]} +{'AngularVelocity': array([ 0.01875619, -0.00706259, -1.14640558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.856050491333008, + 'FR_Wheel_Angle': 30.428972244262695, + 'Location': array([ -1.51299787, -20.0909481 , 0.17125027]), + 'Rotation': array([-6.87253624e-02, 3.49476891e+01, -2.50549316e-02]), + 'Velocity': array([-0.08059343, -0.1017023 , 0.00010379]), + 'brake_input': 0.0, + 'camera_location': array([-6.54238033, 14.07436943, 2.40273952]), + 'camera_rotation': array([-6.43043852, -0.55927211, 2.67331862]), + 'current_gear_input': False, + 'focus_actor_dist': 3701.47607421875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1089.37329102, 859.02172852, 0. ]), + 'frame': 15095, + 'frame_number': 15095, + 'framesequence': 57959, + 'gaze_dir': array([0.97597504, 0.20230865, 0.08044434]), + 'gaze_origin': array([-3.05076623, -0.17922364, 0.08007661]), + 'gaze_valid': True, + 'gaze_vergence': 422.92626953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97444153, 0.20933533, 0.08145142]), + 'left_gaze_origin': array([-2.97019672, 3.01440144, 0.07917938]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0783538818359375, + 'left_pupil_posn': array([ 0.21851909, -0.02952456]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97750854, 0.19528198, 0.07943726]), + 'right_gaze_origin': array([-3.1313355 , -3.37284875, 0.08097382]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9877166748046875, + 'right_pupil_posn': array([ 0.19870317, -0.09963739]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13112583756446838, + 'throttle_input': 0.0, + 'timestamp': 493.70038556680083, + 'timestamp_carla': 493701, + 'timestamp_device': 4231913, + 'timestamp_stream': 493.70038556680083, + 'transform': [array([-1.61539567e+00, -1.40355053e+01, 8.43940675e-03]), + array([-0.07589706, 2.44894314, 0.02066042])]} +{'AngularVelocity': array([ 0.00708432, -0.00553812, 0.07469217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.950454711914062, + 'FR_Wheel_Angle': 30.51961898803711, + 'Location': array([ -1.53204453, -20.1122551 , 0.17131165]), + 'Rotation': array([-6.77213222e-02, 3.46798477e+01, -2.58483849e-02]), + 'Velocity': array([-6.44387305e-02, -8.07941109e-02, 2.62451158e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.51354504, 14.12388134, 2.37271237]), + 'camera_rotation': array([-6.49300289, -0.56117523, 2.68147326]), + 'current_gear_input': False, + 'focus_actor_dist': 3518.94140625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1047.50268555, 687.77172852, 0. ]), + 'frame': 15096, + 'frame_number': 15096, + 'framesequence': 57963, + 'gaze_dir': array([0.97583771, 0.20345306, 0.07905579]), + 'gaze_origin': array([-3.04890466, -0.17806625, 0.08195801]), + 'gaze_valid': True, + 'gaze_vergence': 314.51068115234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97459412, 0.21104431, 0.07485962]), + 'left_gaze_origin': array([-2.97010493, 3.01477075, 0.07991181]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.05963134765625, + 'left_pupil_posn': array([ 0.21849859, -0.02768791]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9770813 , 0.19586182, 0.08325195]), + 'right_gaze_origin': array([-3.12770414, -3.37090302, 0.08400422]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.03363037109375, + 'right_pupil_posn': array([ 0.19779432, -0.09929228]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12951445579528809, + 'throttle_input': 0.0, + 'timestamp': 493.7339722663164, + 'timestamp_carla': 493734, + 'timestamp_device': 4231947, + 'timestamp_stream': 493.7339722663164, + 'transform': [array([-1.66582334e+00, -1.39668999e+01, 8.59239604e-03]), + array([-0.07431246, 2.63503337, 0.02020266])]} +{'AngularVelocity': array([ 0.00852871, 0.00508623, -1.66708553]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.393672943115234, + 'FR_Wheel_Angle': 31.416786193847656, + 'Location': array([ -1.5437355 , -20.12531471, 0.17129532]), + 'Rotation': array([-6.70519620e-02, 3.45168877e+01, -2.62145977e-02]), + 'Velocity': array([-0.04535021, -0.05503343, 0.00027204]), + 'brake_input': 0.0, + 'camera_location': array([-6.50473499, 14.16694164, 2.3577373 ]), + 'camera_rotation': array([-6.65010405, -0.48206437, 2.83715701]), + 'current_gear_input': False, + 'focus_actor_dist': 3305.28076171875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.01229980e+03, 4.83260742e+02, 1.98364258e-04]), + 'frame': 15097, + 'frame_number': 15097, + 'framesequence': 57967, + 'gaze_dir': array([0.97568512, 0.20330048, 0.0813446 ]), + 'gaze_origin': array([-3.04872608, -0.17768785, 0.08255158]), + 'gaze_valid': True, + 'gaze_vergence': 348.3783264160156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97416687, 0.21150208, 0.07905579]), + 'left_gaze_origin': array([-2.96937728, 3.01485443, 0.08027344]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0286407470703125, + 'left_pupil_posn': array([ 0.21819723, -0.02711546]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97720337, 0.19509888, 0.08363342]), + 'right_gaze_origin': array([-3.12807488, -3.3702302 , 0.08482972]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.981781005859375, + 'right_pupil_posn': array([ 0.19759405, -0.09720945]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12667623162269592, + 'throttle_input': 0.0, + 'timestamp': 493.7663413658738, + 'timestamp_carla': 493767, + 'timestamp_device': 4231980, + 'timestamp_stream': 493.7663413658738, + 'transform': [array([-1.71321845e+00, -1.39018736e+01, 8.74818768e-03]), + array([-0.0726937 , 2.80899358, 0.01977541])]} +{'AngularVelocity': array([-0.09328035, 0.01557327, -1.53028691]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.902873992919922, + 'FR_Wheel_Angle': 33.963165283203125, + 'Location': array([ -1.55266213, -20.13534546, 0.17123741]), + 'Rotation': array([-6.86365664e-02, 3.43790741e+01, -2.42919922e-02]), + 'Velocity': array([-0.06911826, -0.08549041, 0.00018562]), + 'brake_input': 0.0, + 'camera_location': array([-6.48595715, 14.20987988, 2.35272074]), + 'camera_rotation': array([-6.64176416, -0.40208137, 2.85959458]), + 'current_gear_input': False, + 'focus_actor_dist': 3231.990966796875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.01055237e+03, 4.14979248e+02, 1.52587891e-05]), + 'frame': 15098, + 'frame_number': 15098, + 'framesequence': 57971, + 'gaze_dir': array([0.97615051, 0.19913483, 0.08604431]), + 'gaze_origin': array([-3.04634857, -0.17118683, 0.07936325]), + 'gaze_valid': True, + 'gaze_vergence': 428.43353271484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97471619, 0.20625305, 0.08580017]), + 'left_gaze_origin': array([-2.96641707, 3.02252984, 0.07932435]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.04083251953125, + 'left_pupil_posn': array([ 0.21190405, -0.02626348]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97758484, 0.1920166 , 0.08628845]), + 'right_gaze_origin': array([-3.12628031, -3.36490345, 0.07940216]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.921173095703125, + 'right_pupil_posn': array([ 0.19209003, -0.09801936]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12290415167808533, + 'throttle_input': 0.0, + 'timestamp': 493.8005289658904, + 'timestamp_carla': 493801, + 'timestamp_device': 4232013, + 'timestamp_stream': 493.8005289658904, + 'transform': [array([-1.76149237e+00, -1.38343544e+01, 8.89787637e-03]), + array([-0.070952 , 2.98505092, 0.01931764])]} +{'AngularVelocity': array([ 0.00506618, 0.0036574 , -0.66540319]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.25712776184082, + 'FR_Wheel_Angle': 35.975616455078125, + 'Location': array([ -1.57132113, -20.15732193, 0.17134681]), + 'Rotation': array([-6.89097717e-02, 3.40794334e+01, -2.36511230e-02]), + 'Velocity': array([-0.06623336, -0.0916851 , 0.00072264]), + 'brake_input': 0.0, + 'camera_location': array([-6.44647217, 14.24261475, 2.3646667 ]), + 'camera_rotation': array([-6.56205606, -0.29953697, 3.05478168]), + 'current_gear_input': False, + 'focus_actor_dist': 1770.2821044921875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-655.85809326, -994.78186035, 70.5668335 ]), + 'frame': 15099, + 'frame_number': 15099, + 'framesequence': 57975, + 'gaze_dir': array([0.97624969, 0.19976807, 0.08310699]), + 'gaze_origin': array([-3.04531717, -0.16930161, 0.07787476]), + 'gaze_valid': True, + 'gaze_vergence': 313.56610107421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97434998, 0.20944214, 0.08216858]), + 'left_gaze_origin': array([-2.96472955, 3.02508092, 0.07670594]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.026092529296875, + 'left_pupil_posn': array([ 0.20951283, -0.02836311]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97814941, 0.19009399, 0.08404541]), + 'right_gaze_origin': array([-3.1259048 , -3.36368418, 0.07904358]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.922760009765625, + 'right_pupil_posn': array([ 0.19233346, -0.09955442]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1188390851020813, + 'throttle_input': 0.019836727529764175, + 'timestamp': 493.83381796628237, + 'timestamp_carla': 493834, + 'timestamp_device': 4232047, + 'timestamp_stream': 493.83381796628237, + 'transform': [array([-1.80682933e+00, -1.37701435e+01, 8.94203130e-03]), + array([-0.06918298, 3.14965606, 0.01937868])]} +{'AngularVelocity': array([ 0.03182984, 0.04949509, -0.11352574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.85726547241211, + 'FR_Wheel_Angle': 36.84629440307617, + 'Location': array([ -1.58037734, -20.16845703, 0.17130065]), + 'Rotation': array([-6.75027594e-02, 3.39244080e+01, -2.58178692e-02]), + 'Velocity': array([-0.05712866, -0.06138161, -0.00075118]), + 'brake_input': 0.0, + 'camera_location': array([-6.4078207 , 14.24617386, 2.36022544]), + 'camera_rotation': array([-6.66517162, -0.32877079, 3.28975725]), + 'current_gear_input': False, + 'focus_actor_dist': 3442.7841796875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.08371704e+03, 6.27443848e+02, -3.05175781e-05]), + 'frame': 15100, + 'frame_number': 15100, + 'framesequence': 57979, + 'gaze_dir': array([0.97603607, 0.20022583, 0.08464813]), + 'gaze_origin': array([-3.04501748, -0.16859819, 0.07823792]), + 'gaze_valid': True, + 'gaze_vergence': 328.7332763671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97409058, 0.20942688, 0.08534241]), + 'left_gaze_origin': array([-2.96490812, 3.02527642, 0.07707367]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.02685546875, + 'left_pupil_posn': array([ 0.20968997, -0.02823591]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97798157, 0.19102478, 0.08395386]), + 'right_gaze_origin': array([-3.1251266 , -3.36247277, 0.07940216]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9215545654296875, + 'right_pupil_posn': array([ 0.19151533, -0.09801936]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11440778523683548, + 'throttle_input': 0.03967345505952835, + 'timestamp': 493.86703906580806, + 'timestamp_carla': 493867, + 'timestamp_device': 4232080, + 'timestamp_stream': 493.86703906580806, + 'transform': [array([-1.85010171e+00, -1.37076769e+01, 8.93522240e-03]), + array([-0.06750276, 3.30591798, 0.01965333])]} +{'AngularVelocity': array([ 2.05896169e-04, -8.70828144e-03, -9.88546431e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.917316436767578, + 'FR_Wheel_Angle': 36.813629150390625, + 'Location': array([ -1.5936873 , -20.1842556 , 0.17135471]), + 'Rotation': array([-6.85136244e-02, 3.36802635e+01, -2.45056134e-02]), + 'Velocity': array([-0.05049311, -0.07066936, 0.00021252]), + 'brake_input': 0.0, + 'camera_location': array([-6.39109612, 14.22726822, 2.32481241]), + 'camera_rotation': array([-6.87214661, -0.44798857, 3.18666077]), + 'current_gear_input': False, + 'focus_actor_dist': 3352.62646484375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.07239880e+03, 5.43681641e+02, -1.52587891e-05]), + 'frame': 15101, + 'frame_number': 15101, + 'framesequence': 57983, + 'gaze_dir': array([0.9757843 , 0.20066833, 0.08639526]), + 'gaze_origin': array([-3.04470778, -0.16840973, 0.07894745]), + 'gaze_valid': True, + 'gaze_vergence': 315.97979736328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97375488, 0.21025085, 0.08703613]), + 'left_gaze_origin': array([-2.96440291, 3.02521825, 0.07778779]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.045623779296875, + 'left_pupil_posn': array([ 0.20973527, -0.02708876]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97781372, 0.19108582, 0.08575439]), + 'right_gaze_origin': array([-3.1250124 , -3.3620379 , 0.08010712]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.92510986328125, + 'right_pupil_posn': array([ 0.19151533, -0.09696269]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10939054936170578, + 'throttle_input': 0.0476234070956707, + 'timestamp': 493.9004656672478, + 'timestamp_carla': 493901, + 'timestamp_device': 4232113, + 'timestamp_stream': 493.9004656672478, + 'transform': [array([-1.89142549e+00, -1.36462297e+01, 8.95669963e-03]), + array([-0.06597962, 3.45406508, 0.01977541])]} +{'AngularVelocity': array([-0.00671177, 0.03040398, -5.65189266]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.7789306640625, + 'FR_Wheel_Angle': 36.654483795166016, + 'Location': array([ -1.64456499, -20.24175453, 0.17150486]), + 'Rotation': array([-8.24198872e-02, 3.28277206e+01, -8.66699312e-03]), + 'Velocity': array([-0.31763572, -0.40216058, 0.00109172]), + 'brake_input': 0.0, + 'camera_location': array([-6.37266922, 14.21463966, 2.29031706]), + 'camera_rotation': array([-6.9528861 , -0.57146329, 3.04973459]), + 'current_gear_input': False, + 'focus_actor_dist': 3237.806640625, + 'focus_actor_name': 'Road_Marking_Town05_93', + 'focus_actor_pt': array([-1.04742627e+03, 4.37765625e+02, -1.52587891e-05]), + 'frame': 15102, + 'frame_number': 15102, + 'framesequence': 57987, + 'gaze_dir': array([0.97596741, 0.19853973, 0.08937073]), + 'gaze_origin': array([-3.04353786, -0.16865845, 0.0792923 ]), + 'gaze_valid': True, + 'gaze_vergence': 363.3906555175781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97468567, 0.20608521, 0.0866394 ]), + 'left_gaze_origin': array([-2.96331787, 3.02513289, 0.07823639]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.02947998046875, + 'left_pupil_posn': array([ 0.20979166, -0.02440631]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97724915, 0.19099426, 0.09210205]), + 'right_gaze_origin': array([-3.12375808, -3.36244965, 0.08034821]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0420379638671875, + 'right_pupil_posn': array([ 0.19019663, -0.09683692]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10384228080511093, + 'throttle_input': 0.0476234070956707, + 'timestamp': 493.93495746701956, + 'timestamp_carla': 493935, + 'timestamp_device': 4232147, + 'timestamp_stream': 493.93495746701956, + 'transform': [array([-1.93164062e+00, -1.35841770e+01, 9.01512150e-03]), + array([-0.0645726 , 3.59705138, 0.01968385])]} +{'AngularVelocity': array([ 5.40243927e-03, -5.77820502e-02, -7.04300308e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.751955032348633, + 'FR_Wheel_Angle': 36.617305755615234, + 'Location': array([ -1.73131752, -20.33925819, 0.17156902]), + 'Rotation': array([-7.61429444e-02, 3.13313198e+01, -1.54418927e-02]), + 'Velocity': array([-3.55823010e-01, -4.63501275e-01, 4.01391968e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.33467484, 14.18461037, 2.28611398]), + 'camera_rotation': array([-6.84317303, -0.65065849, 3.04083014]), + 'current_gear_input': False, + 'focus_actor_dist': 3409.337646484375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.08583960e+03, 6.11422607e+02, -1.52587891e-05]), + 'frame': 15103, + 'frame_number': 15103, + 'framesequence': 57991, + 'gaze_dir': array([0.97560883, 0.20089722, 0.08769989]), + 'gaze_origin': array([-3.04401255, -0.16836396, 0.07791214]), + 'gaze_valid': True, + 'gaze_vergence': 263.69403076171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97398376, 0.21069336, 0.08328247]), + 'left_gaze_origin': array([-2.96361089, 3.02506733, 0.07832032]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.038818359375, + 'left_pupil_posn': array([ 0.20986974, -0.02441895]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97723389, 0.19110107, 0.09211731]), + 'right_gaze_origin': array([-3.12441421, -3.36179519, 0.07750397]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0042266845703125, + 'right_pupil_posn': array([ 0.19139242, -0.10006475]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09796441346406937, + 'throttle_input': 0.0476234070956707, + 'timestamp': 493.9681804664433, + 'timestamp_carla': 493968, + 'timestamp_device': 4232180, + 'timestamp_stream': 493.9681804664433, + 'transform': [array([-1.96813142e+00, -1.35255089e+01, 9.13625676e-03]), + array([-0.06339099, 3.72564125, 0.01934815])]} +{'AngularVelocity': array([-0.03840825, -0.05669715, -5.54136133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.613027572631836, + 'FR_Wheel_Angle': 36.183135986328125, + 'Location': array([ -1.8274008 , -20.44173241, 0.17161494]), + 'Rotation': array([-6.60069436e-02, 2.97479076e+01, -2.63366699e-02]), + 'Velocity': array([-0.29302028, -0.36151576, 0.00128668]), + 'brake_input': 0.0, + 'camera_location': array([-6.29909325, 14.15829659, 2.28720403]), + 'camera_rotation': array([-6.85282421, -0.74185431, 2.89664793]), + 'current_gear_input': False, + 'focus_actor_dist': 3423.010986328125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.10131287e+03, 6.27848389e+02, 1.52587891e-05]), + 'frame': 15104, + 'frame_number': 15104, + 'framesequence': 57995, + 'gaze_dir': array([0.97579956, 0.20040131, 0.08675385]), + 'gaze_origin': array([-3.04385376, -0.16825105, 0.07803955]), + 'gaze_valid': True, + 'gaze_vergence': 264.1965637207031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97433472, 0.20965576, 0.08189392]), + 'left_gaze_origin': array([-2.96361089, 3.02506733, 0.07860718]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.050048828125, + 'left_pupil_posn': array([ 0.20987308, -0.02441895]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9772644 , 0.19114685, 0.09161377]), + 'right_gaze_origin': array([-3.12409687, -3.3615694 , 0.07747193]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0113525390625, + 'right_pupil_posn': array([ 0.19084775, -0.10050762]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.092178113758564, + 'throttle_input': 0.0476234070956707, + 'timestamp': 494.0002953670919, + 'timestamp_carla': 494001, + 'timestamp_device': 4232213, + 'timestamp_stream': 494.0002953670919, + 'transform': [array([-2.00132728e+00, -1.34696608e+01, 9.30629671e-03]), + array([-0.06234596, 3.84148335, 0.01879883])]} +{'AngularVelocity': array([ 0.04259207, -0.01607889, -4.60702991]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.73097038269043, + 'FR_Wheel_Angle': 34.73358154296875, + 'Location': array([ -1.88601387, -20.50121117, 0.17170665]), + 'Rotation': array([-6.38076216e-02, 2.88223209e+01, -2.87170392e-02]), + 'Velocity': array([-0.24012232, -0.27029663, 0.00055389]), + 'brake_input': 0.0, + 'camera_location': array([-6.26427174, 14.10238266, 2.28083348]), + 'camera_rotation': array([-7.01207685, -0.78364223, 3.12406063]), + 'current_gear_input': False, + 'focus_actor_dist': 3373.435546875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1088.98693848, 585.79272461, 0. ]), + 'frame': 15105, + 'frame_number': 15105, + 'framesequence': 57999, + 'gaze_dir': array([0.97573853, 0.20094299, 0.08644104]), + 'gaze_origin': array([-3.04387379, -0.16796112, 0.07826004]), + 'gaze_valid': True, + 'gaze_vergence': 316.1841125488281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97470093, 0.207901 , 0.08190918]), + 'left_gaze_origin': array([-2.96419382, 3.02578759, 0.07860871]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1011810302734375, + 'left_pupil_posn': array([ 0.21033275, -0.02489483]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97677612, 0.19398499, 0.0909729 ]), + 'right_gaze_origin': array([-3.12355375, -3.36170983, 0.07791138]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.01116943359375, + 'right_pupil_posn': array([ 0.19030476, -0.10006475]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08641011267900467, + 'throttle_input': 0.051590751856565475, + 'timestamp': 494.0339511670172, + 'timestamp_carla': 494034, + 'timestamp_device': 4232247, + 'timestamp_stream': 494.0339511670172, + 'transform': [array([-2.03390098e+00, -1.34120455e+01, 9.47931223e-03]), + array([-0.06139657, 3.953933 , 0.01815798])]} +{'AngularVelocity': array([-0.07579901, -0.01893865, -3.1067028 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.04718780517578, + 'FR_Wheel_Angle': 33.68022918701172, + 'Location': array([ -1.95155358, -20.56348801, 0.17177203]), + 'Rotation': array([-6.53990582e-02, 2.78621578e+01, -2.54211407e-02]), + 'Velocity': array([-2.24458858e-01, -2.39759281e-01, 4.40788244e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.26212025, 14.04551888, 2.23957181]), + 'camera_rotation': array([-7.24703503, -0.87232882, 2.96106291]), + 'current_gear_input': False, + 'focus_actor_dist': 3081.267578125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.02135095e+03, 3.06909912e+02, 1.52587891e-05]), + 'frame': 15106, + 'frame_number': 15106, + 'framesequence': 58003, + 'gaze_dir': array([0.97589874, 0.20008087, 0.08657837]), + 'gaze_origin': array([-3.04258418, -0.16779785, 0.07882843]), + 'gaze_valid': True, + 'gaze_vergence': 320.81732177734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97491455, 0.20683289, 0.08206177]), + 'left_gaze_origin': array([-2.96189737, 3.02602863, 0.07965546]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.110992431640625, + 'left_pupil_posn': array([ 0.20990539, -0.02374029]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97688293, 0.19332886, 0.09109497]), + 'right_gaze_origin': array([-3.12327123, -3.36162448, 0.07800141]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.024505615234375, + 'right_pupil_posn': array([ 0.18985152, -0.09989882]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08058717846870422, + 'throttle_input': 0.05555810034275055, + 'timestamp': 494.0677510686219, + 'timestamp_carla': 494068, + 'timestamp_device': 4232280, + 'timestamp_stream': 494.0677510686219, + 'transform': [array([-2.06447482e+00, -1.33550758e+01, 9.64897126e-03]), + array([-0.06060427, 4.05826044, 0.0175171 ])]} +{'AngularVelocity': array([ 0.02812986, -0.01305231, -4.04041195]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.705917358398438, + 'FR_Wheel_Angle': 33.271671295166016, + 'Location': array([ -2.01015687, -20.61607933, 0.17187542]), + 'Rotation': array([-6.98864907e-02, 2.70497952e+01, -2.04467736e-02]), + 'Velocity': array([-0.28192377, -0.28071639, 0.00028818]), + 'brake_input': 0.0, + 'camera_location': array([-6.24956894, 13.97620678, 2.20642042]), + 'camera_rotation': array([-7.29837084, -0.92603338, 2.88355875]), + 'current_gear_input': False, + 'focus_actor_dist': 2869.770263671875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-965.66162109, 108.52001953, 0. ]), + 'frame': 15107, + 'frame_number': 15107, + 'framesequence': 58007, + 'gaze_dir': array([0.97590637, 0.1991806 , 0.08844757]), + 'gaze_origin': array([-3.04295063, -0.16774368, 0.07797776]), + 'gaze_valid': True, + 'gaze_vergence': 217.99508666992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97514343, 0.20614624, 0.08119202]), + 'left_gaze_origin': array([-2.96340203, 3.02599025, 0.07770081]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1419830322265625, + 'left_pupil_posn': array([ 0.20956004, -0.02380276]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97666931, 0.19221497, 0.09570312]), + 'right_gaze_origin': array([-3.12249923, -3.36147761, 0.07825471]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.025421142578125, + 'right_pupil_posn': array([ 0.18947423, -0.09989285]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07564318180084229, + 'throttle_input': 0.07142747938632965, + 'timestamp': 494.10002476722, + 'timestamp_carla': 494100, + 'timestamp_device': 4232313, + 'timestamp_stream': 494.10002476722, + 'transform': [array([-2.09190822e+00, -1.33013668e+01, 9.83907655e-03]), + array([-0.0600237 , 4.15079784, 0.0168152 ])]} +{'AngularVelocity': array([-0.05797139, -0.05258669, -2.82194686]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.711624145507812, + 'FR_Wheel_Angle': 33.31764221191406, + 'Location': array([ -2.06438971, -20.6638279 , 0.17190094]), + 'Rotation': array([-6.23118132e-02, 2.63049259e+01, -2.57873535e-02]), + 'Velocity': array([-0.15794128, -0.17121597, 0.0003348 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.23151493, 13.88969517, 2.18619609]), + 'camera_rotation': array([-7.42389631, -1.03969359, 2.92492461]), + 'current_gear_input': False, + 'focus_actor_dist': 2949.4873046875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.86585754e+02, 1.91360352e+02, -1.52587891e-05]), + 'frame': 15108, + 'frame_number': 15108, + 'framesequence': 58011, + 'gaze_dir': array([0.97577667, 0.19867706, 0.09104156]), + 'gaze_origin': array([-3.04031396, -0.17087327, 0.08253861]), + 'gaze_valid': True, + 'gaze_vergence': 300.82244873046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9744873 , 0.2069397 , 0.08686829]), + 'left_gaze_origin': array([-2.95934916, 3.02237105, 0.08177643]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0532989501953125, + 'left_pupil_posn': array([ 0.21139979, -0.02032995]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97706604, 0.19041443, 0.09521484]), + 'right_gaze_origin': array([-3.12127852, -3.36411738, 0.08330078]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0753326416015625, + 'right_pupil_posn': array([ 0.19154775, -0.09439814]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07143162935972214, + 'throttle_input': 0.10713358968496323, + 'timestamp': 494.13416036590934, + 'timestamp_carla': 494134, + 'timestamp_device': 4232347, + 'timestamp_stream': 494.13416036590934, + 'transform': [array([-2.11922908e+00, -1.32452755e+01, 1.00148963e-02]), + array([-0.05960023, 4.2418437 , 0.01608278])]} +{'AngularVelocity': array([-0.09902186, -0.03401439, -1.64201713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.74687957763672, + 'FR_Wheel_Angle': 33.393375396728516, + 'Location': array([ -2.09527826, -20.6909523 , 0.17194134]), + 'Rotation': array([-6.25645295e-02, 2.58762798e+01, -2.47497521e-02]), + 'Velocity': array([-0.07444596, -0.0867658 , 0.00034841]), + 'brake_input': 0.0, + 'camera_location': array([-6.24735451, 13.81370449, 2.16718197]), + 'camera_rotation': array([-7.61930084, -1.2673068 , 2.72510219]), + 'current_gear_input': False, + 'focus_actor_dist': 2970.532470703125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.90533386e+02, 2.17611816e+02, -1.52587891e-05]), + 'frame': 15109, + 'frame_number': 15109, + 'framesequence': 58015, + 'gaze_dir': array([0.97510529, 0.20145416, 0.09185791]), + 'gaze_origin': array([-3.04089665, -0.1737732 , 0.08181611]), + 'gaze_valid': True, + 'gaze_vergence': 276.54058837890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97338867, 0.21138 , 0.08830261]), + 'left_gaze_origin': array([-2.95944524, 3.01951623, 0.08215027]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1194915771484375, + 'left_pupil_posn': array([ 0.21365905, -0.02018881]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9768219 , 0.19152832, 0.09541321]), + 'right_gaze_origin': array([-3.12234807, -3.36706257, 0.08148193]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.972686767578125, + 'right_pupil_posn': array([ 0.19524872, -0.09523249]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06690878421068192, + 'throttle_input': 0.1428549587726593, + 'timestamp': 494.1681427657604, + 'timestamp_carla': 494168, + 'timestamp_device': 4232380, + 'timestamp_stream': 494.1681427657604, + 'transform': [array([-2.14489770e+00, -1.31900139e+01, 1.02124596e-02]), + array([-0.05932702, 4.3263216 , 0.0152588 ])]} +{'AngularVelocity': array([-0.10566407, -0.03786132, -1.17869353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.27498435974121, + 'FR_Wheel_Angle': 36.5933837890625, + 'Location': array([ -2.10852337, -20.70257568, 0.17196834]), + 'Rotation': array([-6.46955520e-02, 2.56905117e+01, -2.21252404e-02]), + 'Velocity': array([-0.03605082, -0.052075 , 0.00028709]), + 'brake_input': 0.0, + 'camera_location': array([-6.22755527, 13.74376297, 2.17107797]), + 'camera_rotation': array([-7.47094917, -1.49491024, 2.63384342]), + 'current_gear_input': False, + 'focus_actor_dist': 2855.100830078125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-962.1272583 , 111.30688477, 0. ]), + 'frame': 15110, + 'frame_number': 15110, + 'framesequence': 58019, + 'gaze_dir': array([0.97528839, 0.20069122, 0.09152222]), + 'gaze_origin': array([-3.04233885, -0.17503968, 0.08011551]), + 'gaze_valid': True, + 'gaze_vergence': 199.13064575195312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97406006, 0.21018982, 0.08377075]), + 'left_gaze_origin': array([-2.96130395, 3.01862192, 0.08071899]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1203155517578125, + 'left_pupil_posn': array([ 0.21417069, -0.02019453]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9847390055656433, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97651672, 0.19119263, 0.09927368]), + 'right_gaze_origin': array([-3.12337351, -3.36870146, 0.07951202]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.993988037109375, + 'right_pupil_posn': array([ 0.19592535, -0.09834945]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06302683055400848, + 'throttle_input': 0.18649576604366302, + 'timestamp': 494.19995806738734, + 'timestamp_carla': 494200, + 'timestamp_device': 4232413, + 'timestamp_stream': 494.19995806738734, + 'transform': [array([-2.16776371e+00, -1.31385117e+01, 1.04705999e-02]), + array([-0.05919725, 4.40061998, 0.01422121])]} +{'AngularVelocity': array([0.09578236, 0.05175855, 0.18052243]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.105785369873047, + 'FR_Wheel_Angle': 41.23415756225586, + 'Location': array([ -2.11646533, -20.70983887, 0.17195179]), + 'Rotation': array([-6.64987192e-02, 2.55697956e+01, -2.09350549e-02]), + 'Velocity': array([-0.03147984, -0.01606591, 0.0006383 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.21936607, 13.67388916, 2.18539333]), + 'camera_rotation': array([-7.3487711 , -1.65074229, 2.63754368]), + 'current_gear_input': False, + 'focus_actor_dist': 3014.874755859375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-993.63995361, 274.0769043 , 0. ]), + 'frame': 15111, + 'frame_number': 15111, + 'framesequence': 58023, + 'gaze_dir': array([0.97531128, 0.20075989, 0.09111023]), + 'gaze_origin': array([-3.04375076, -0.17647628, 0.07907715]), + 'gaze_valid': True, + 'gaze_vergence': 235.12197875976562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97372437, 0.21099854, 0.08552551]), + 'left_gaze_origin': array([-2.96384287, 3.01713133, 0.07941132]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1176605224609375, + 'left_pupil_posn': array([ 0.21499145, -0.02233386]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9802777171134949, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97689819, 0.19052124, 0.09669495]), + 'right_gaze_origin': array([-3.1236589 , -3.37008381, 0.07874299]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.99578857421875, + 'right_pupil_posn': array([ 0.19717348, -0.09834945]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05941954255104065, + 'throttle_input': 0.2063324898481369, + 'timestamp': 494.2336684651673, + 'timestamp_carla': 494234, + 'timestamp_device': 4232447, + 'timestamp_stream': 494.2336684651673, + 'transform': [array([-2.19084620e+00, -1.30840368e+01, 1.07555576e-02]), + array([-0.05916993, 4.47458553, 0.01296998])]} +{'AngularVelocity': array([-0.1066858 , -0.04916469, -1.04525173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.970548629760742, + 'FR_Wheel_Angle': 41.97895812988281, + 'Location': array([ -2.12164354, -20.71515656, 0.17200881]), + 'Rotation': array([-6.74412847e-02, 2.54657326e+01, -1.90734882e-02]), + 'Velocity': array([-1.39529072e-02, -3.52929011e-02, -8.99314819e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.20583344, 13.63167953, 2.17215538]), + 'camera_rotation': array([-7.40310526, -1.80588543, 2.50583792]), + 'current_gear_input': False, + 'focus_actor_dist': 3130.387939453125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1019.22229004, 392.1706543 , 0. ]), + 'frame': 15112, + 'frame_number': 15112, + 'framesequence': 58027, + 'gaze_dir': array([0.9751358 , 0.20249176, 0.08937073]), + 'gaze_origin': array([-3.04443598, -0.17903748, 0.07774507]), + 'gaze_valid': True, + 'gaze_vergence': 303.1310119628906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97357178, 0.21150208, 0.08607483]), + 'left_gaze_origin': array([-2.96500874, 3.01279306, 0.0770691 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.086151123046875, + 'left_pupil_posn': array([ 0.21896756, -0.02548611]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.982592761516571, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97669983, 0.19348145, 0.09266663]), + 'right_gaze_origin': array([-3.12386346, -3.37086797, 0.07842102]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.000732421875, + 'right_pupil_posn': array([ 0.19789791, -0.09844053]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05572069436311722, + 'throttle_input': 0.22618448734283447, + 'timestamp': 494.26705526560545, + 'timestamp_carla': 494267, + 'timestamp_device': 4232480, + 'timestamp_stream': 494.26705526560545, + 'transform': [array([-2.21271944e+00, -1.30299730e+01, 1.10848611e-02]), + array([-0.05919725, 4.5436697 , 0.01153566])]} +{'AngularVelocity': array([-0.10720375, -0.04997289, -0.99972725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.97241973876953, + 'FR_Wheel_Angle': 41.981319427490234, + 'Location': array([ -2.12555289, -20.71900749, 0.17201141]), + 'Rotation': array([-6.78101107e-02, 2.53935089e+01, -1.87072735e-02]), + 'Velocity': array([-1.14702964e-02, -3.23600061e-02, -2.60162342e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.17190266, 13.58428955, 2.16448569]), + 'camera_rotation': array([-7.39388418, -1.89720023, 2.62934089]), + 'current_gear_input': False, + 'focus_actor_dist': 2979.125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-981.96936035, 250.99658203, 0. ]), + 'frame': 15113, + 'frame_number': 15113, + 'framesequence': 58031, + 'gaze_dir': array([0.97499847, 0.20349121, 0.08866882]), + 'gaze_origin': array([-3.04496479, -0.17995988, 0.07723923]), + 'gaze_valid': True, + 'gaze_vergence': 344.5562438964844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97349548, 0.21173096, 0.08625793]), + 'left_gaze_origin': array([-2.96575332, 3.01111627, 0.07623749]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.125091552734375, + 'left_pupil_posn': array([ 0.22068715, -0.02681971]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9847406148910522, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97650146, 0.19525146, 0.09107971]), + 'right_gaze_origin': array([-3.12417626, -3.37103605, 0.07824097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0250091552734375, + 'right_pupil_posn': array([ 0.19808817, -0.09861159]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05236976593732834, + 'throttle_input': 0.2658579349517822, + 'timestamp': 494.30102586746216, + 'timestamp_carla': 494301, + 'timestamp_device': 4232513, + 'timestamp_stream': 494.30102586746216, + 'transform': [array([-2.23409152e+00, -1.29746399e+01, 1.14441486e-02]), + array([-0.05926555, 4.61013985, 0.00994874])]} +{'AngularVelocity': array([-0.10767388, -0.0499196 , -1.01136446]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.971874237060547, + 'FR_Wheel_Angle': 41.97993469238281, + 'Location': array([ -2.12984133, -20.72320557, 0.17201152]), + 'Rotation': array([-6.80833235e-02, 2.53140774e+01, -1.83105450e-02]), + 'Velocity': array([-1.17722834e-02, -3.24901678e-02, 2.30216974e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.16018677, 13.53741455, 2.13582301]), + 'camera_rotation': array([-7.56998014, -2.01502299, 2.65229583]), + 'current_gear_input': False, + 'focus_actor_dist': 1684.566162109375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-658.13842773, -995.50683594, 57.79388428]), + 'frame': 15114, + 'frame_number': 15114, + 'framesequence': 58035, + 'gaze_dir': array([0.97441101, 0.20570374, 0.08999634]), + 'gaze_origin': array([-3.04492497, -0.18108597, 0.07769547]), + 'gaze_valid': True, + 'gaze_vergence': 308.09954833984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97283936, 0.21453857, 0.08674622]), + 'left_gaze_origin': array([-2.96535373, 3.01000071, 0.07714996]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1263885498046875, + 'left_pupil_posn': array([ 0.22200274, -0.02543473]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9755908250808716, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97598267, 0.1968689 , 0.09324646]), + 'right_gaze_origin': array([-3.12449646, -3.37217259, 0.07824097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.038848876953125, + 'right_pupil_posn': array([ 0.1998682 , -0.09861159]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.049476612359285355, + 'throttle_input': 0.3174487054347992, + 'timestamp': 494.3334549665451, + 'timestamp_carla': 494334, + 'timestamp_device': 4232547, + 'timestamp_stream': 494.3334549665451, + 'transform': [array([-2.25389242e+00, -1.29211769e+01, 1.18633462e-02]), + array([-0.05938849, 4.67080164, 0.0081482 ])]} +{'AngularVelocity': array([-0.09348434, -0.04286941, -1.13216722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.965713500976562, + 'FR_Wheel_Angle': 41.96868896484375, + 'Location': array([ -2.13566542, -20.7287674 , 0.17206508]), + 'Rotation': array([-6.87868297e-02, 2.52042923e+01, -1.76391564e-02]), + 'Velocity': array([-2.31573321e-02, -4.27052006e-02, -3.31497176e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.15196323, 13.50718021, 2.09637785]), + 'camera_rotation': array([-7.78683186, -2.1303277 , 2.51861548]), + 'current_gear_input': False, + 'focus_actor_dist': 1680.380126953125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-660.01629639, -994.7869873 , 55.00206757]), + 'frame': 15115, + 'frame_number': 15115, + 'framesequence': 58039, + 'gaze_dir': array([0.97411346, 0.20613861, 0.09199524]), + 'gaze_origin': array([-3.04469848, -0.18219605, 0.0786026 ]), + 'gaze_valid': True, + 'gaze_vergence': 251.75094604492188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97229004, 0.2166748 , 0.087677 ]), + 'left_gaze_origin': array([-2.96490049, 3.00900745, 0.07896424]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.12725830078125, + 'left_pupil_posn': array([ 0.22223973, -0.02308738]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9766350984573364, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97593689, 0.19560242, 0.09631348]), + 'right_gaze_origin': array([-3.12449646, -3.37339926, 0.07824097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.079010009765625, + 'right_pupil_posn': array([ 0.20143855, -0.09840393]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04707785323262215, + 'throttle_input': 0.3452201187610626, + 'timestamp': 494.36754466593266, + 'timestamp_carla': 494368, + 'timestamp_device': 4232580, + 'timestamp_stream': 494.36754466593266, + 'transform': [array([-2.27424121e+00, -1.28640852e+01, 1.23198600e-02]), + array([-0.05960023, 4.73222399, 0.00610352])]} +{'AngularVelocity': array([-0.40328139, 0.03759926, -4.21700811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.85818099975586, + 'FR_Wheel_Angle': 41.759830474853516, + 'Location': array([ -2.14941001, -20.74096107, 0.17211021]), + 'Rotation': array([-7.73313940e-02, 2.49782047e+01, -7.44628999e-03]), + 'Velocity': array([-2.32682660e-01, -2.41910636e-01, -4.85372548e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.13375473, 13.49276733, 2.09012485]), + 'camera_rotation': array([-7.81212425, -2.20005727, 2.46188354]), + 'current_gear_input': False, + 'focus_actor_dist': 2743.104736328125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.28583496e+02, 3.74648438e+01, 1.52587891e-05]), + 'frame': 15116, + 'frame_number': 15116, + 'framesequence': 58043, + 'gaze_dir': array([0.97425842, 0.20477295, 0.09331512]), + 'gaze_origin': array([-3.04326892, -0.1768631 , 0.07989884]), + 'gaze_valid': True, + 'gaze_vergence': 237.7858123779297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97203064, 0.21684265, 0.09004211]), + 'left_gaze_origin': array([-2.96268487, 3.01673603, 0.0797226 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.152923583984375, + 'left_pupil_posn': array([ 0.21590078, -0.02222991]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97648621, 0.19270325, 0.09658813]), + 'right_gaze_origin': array([-3.12385273, -3.37046242, 0.08007508]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2220458984375, + 'right_pupil_posn': array([ 0.19946945, -0.09626448]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.043964967131614685, + 'throttle_input': 0.37299153208732605, + 'timestamp': 494.4000421650708, + 'timestamp_carla': 494400, + 'timestamp_device': 4232613, + 'timestamp_stream': 494.4000421650708, + 'transform': [array([ -2.29324174, -12.80843735, 0.01283995]), + array([-5.97846434e-02, 4.78860521e+00, 3.84522090e-03])]} +{'AngularVelocity': array([ 0.0590977 , -0.01787968, -3.81758809]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82741928100586, + 'FR_Wheel_Angle': 41.73749923706055, + 'Location': array([ -2.19584584, -20.78384399, 0.17215259]), + 'Rotation': array([-7.79187903e-02, 2.41655407e+01, -7.72094820e-03]), + 'Velocity': array([-0.25572181, -0.2730456 , 0.00061695]), + 'brake_input': 0.0, + 'camera_location': array([-6.09735489, 13.48727417, 2.108459 ]), + 'camera_rotation': array([-7.73337889, -2.24966478, 2.41592669]), + 'current_gear_input': False, + 'focus_actor_dist': 2807.8701171875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.41351562e+02, 1.07026123e+02, -1.52587891e-05]), + 'frame': 15117, + 'frame_number': 15117, + 'framesequence': 58047, + 'gaze_dir': array([0.98114014, 0.17770386, 0.07570648]), + 'gaze_origin': array([-3.02065587, -0.15112916, 0.06890107]), + 'gaze_valid': True, + 'gaze_vergence': 379.8523254394531, + 'handbrake_input': False, + 'left_eye_openness': 0.9981332421302795, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98072815, 0.18174744, 0.0715332 ]), + 'left_gaze_origin': array([-2.94034433, 3.04313064, 0.06901856]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.235870361328125, + 'left_pupil_posn': array([ 0.19118285, -0.03057742]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9760811924934387, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98155212, 0.17366028, 0.07987976]), + 'right_gaze_origin': array([-3.10096765, -3.34538889, 0.06878357]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1436004638671875, + 'right_pupil_posn': array([ 0.16906261, -0.10536838]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04118167608976364, + 'throttle_input': 0.38887616991996765, + 'timestamp': 494.43387646600604, + 'timestamp_carla': 494434, + 'timestamp_device': 4232647, + 'timestamp_stream': 494.43387646600604, + 'transform': [array([ -2.31259942, -12.74902916, 0.01338948]), + array([-5.99280782e-02, 4.84492064e+00, 1.40381337e-03])]} +{'AngularVelocity': array([ 0.12150443, -0.03068744, -7.01017046]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73206901550293, + 'FR_Wheel_Angle': 41.59792709350586, + 'Location': array([ -2.27244544, -20.85170555, 0.17219158]), + 'Rotation': array([-8.32804888e-02, 2.28424797e+01, -2.96020554e-03]), + 'Velocity': array([-0.44489127, -0.45243317, 0.00054141]), + 'brake_input': 0.0, + 'camera_location': array([-6.06193733, 13.48769569, 2.10022998]), + 'camera_rotation': array([-7.6969943 , -2.22890067, 2.45812535]), + 'current_gear_input': False, + 'focus_actor_dist': 1886.6790771484375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-658.2989502 , -766.78735352, 15.23332977]), + 'frame': 15118, + 'frame_number': 15118, + 'framesequence': 58051, + 'gaze_dir': array([0.9801178 , 0.18008423, 0.08249664]), + 'gaze_origin': array([-3.02504754, -0.15206909, 0.06886826]), + 'gaze_valid': True, + 'gaze_vergence': 262.0732727050781, + 'handbrake_input': False, + 'left_eye_openness': 0.993293046951294, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97891235, 0.18901062, 0.07727051]), + 'left_gaze_origin': array([-2.94211125, 3.0417285 , 0.0674469 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22344970703125, + 'left_pupil_posn': array([ 0.19131219, -0.02926815]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9712923169136047, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98132324, 0.17115784, 0.08772278]), + 'right_gaze_origin': array([-3.10798359, -3.34586644, 0.07028961]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.143157958984375, + 'right_pupil_posn': array([ 0.17219424, -0.10378337]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.038325145840644836, + 'throttle_input': 0.40474554896354675, + 'timestamp': 494.4670489653945, + 'timestamp_carla': 494467, + 'timestamp_device': 4232680, + 'timestamp_stream': 494.4670489653945, + 'transform': [array([ -2.33123994, -12.68904972, 0.01397229]), + array([-6.00578487e-02, 4.89801979e+00, -1.14747090e-03])]} +{'AngularVelocity': array([ 0.03327451, -0.01959875, -4.28295755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81471061706543, + 'FR_Wheel_Angle': 41.7256965637207, + 'Location': array([ -2.35509872, -20.92300797, 0.17217003]), + 'Rotation': array([-0.06677192, 21.43432045, -0.02468872]), + 'Velocity': array([-0.30466214, -0.29762581, 0.00040141]), + 'brake_input': 0.0, + 'camera_location': array([-6.03325176, 13.48946571, 2.05481434]), + 'camera_rotation': array([-7.84238863, -2.20884132, 2.56956506]), + 'current_gear_input': False, + 'focus_actor_dist': 2394.058837890625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-782.27355957, -268.58203125, 0. ]), + 'frame': 15119, + 'frame_number': 15119, + 'framesequence': 58055, + 'gaze_dir': array([0.98023987, 0.17933655, 0.08294678]), + 'gaze_origin': array([-3.0246551 , -0.15187454, 0.06910248]), + 'gaze_valid': True, + 'gaze_vergence': 340.4642333984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97946167, 0.18559265, 0.07861328]), + 'left_gaze_origin': array([-2.94143391, 3.04241967, 0.06766205]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.217254638671875, + 'left_pupil_posn': array([ 0.19150603, -0.02915907]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9716693162918091, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98101807, 0.17308044, 0.08728027]), + 'right_gaze_origin': array([-3.10787678, -3.34616852, 0.07054291]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.160430908203125, + 'right_pupil_posn': array([ 0.17120266, -0.10309672]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03568834438920021, + 'throttle_input': 0.4126802384853363, + 'timestamp': 494.50223756581545, + 'timestamp_carla': 494503, + 'timestamp_device': 4232713, + 'timestamp_stream': 494.50223756581545, + 'transform': [array([ -2.35064602, -12.62346745, 0.01453612]), + array([-6.02149442e-02, 4.95199251e+00, -3.68829747e-03])]} +{'AngularVelocity': array([ 1.38320122e-02, -6.17862097e-04, -5.31811571e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8076114654541, + 'FR_Wheel_Angle': 41.713401794433594, + 'Location': array([ -2.43409824, -20.98727036, 0.17234813]), + 'Rotation': array([-0.06949034, 20.110569 , -0.02154541]), + 'Velocity': array([-3.10856611e-01, -2.84882128e-01, 2.83365254e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.03375053, 13.49719143, 2.0126338 ]), + 'camera_rotation': array([-8.10547352, -2.20028424, 2.60856628]), + 'current_gear_input': False, + 'focus_actor_dist': 2299.362060546875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.62824829e+02, -3.55282471e+02, 2.89916992e-04]), + 'frame': 15120, + 'frame_number': 15120, + 'framesequence': 58059, + 'gaze_dir': array([0.98018646, 0.17930603, 0.08367157]), + 'gaze_origin': array([-3.02527165, -0.15154953, 0.07025223]), + 'gaze_valid': True, + 'gaze_vergence': 337.9919738769531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97937012, 0.18577576, 0.07937622]), + 'left_gaze_origin': array([-2.9426713 , 3.04296565, 0.06863862]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21710205078125, + 'left_pupil_posn': array([ 0.19107151, -0.02850032]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9767388701438904, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98100281, 0.1728363 , 0.08796692]), + 'right_gaze_origin': array([-3.10787225, -3.34606504, 0.07186585]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1637725830078125, + 'right_pupil_posn': array([ 0.17120266, -0.10194027]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03279519081115723, + 'throttle_input': 0.4166475832462311, + 'timestamp': 494.5345344655216, + 'timestamp_carla': 494535, + 'timestamp_device': 4232747, + 'timestamp_stream': 494.5345344655216, + 'transform': [array([ -2.36818504, -12.5611248 , 0.01512323]), + array([-0.06033789, 4.99954224, -0.00620181])]} +{'AngularVelocity': array([ 0.01097364, -0.00547131, -3.85224223]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.856218338012695, + 'FR_Wheel_Angle': 41.79639434814453, + 'Location': array([ -2.49861073, -21.03758049, 0.17237414]), + 'Rotation': array([-0.06610256, 19.04648018, -0.02581787]), + 'Velocity': array([-2.27423072e-01, -2.01298773e-01, 3.94821145e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.99069405, 13.51517296, 1.99252141]), + 'camera_rotation': array([-8.16394043, -2.19351411, 2.65142512]), + 'current_gear_input': False, + 'focus_actor_dist': 1918.1044921875, + 'focus_actor_name': 'Road_Curb_Town05_210', + 'focus_actor_pt': array([-678.42224121, -720.15332031, 15.23999023]), + 'frame': 15121, + 'frame_number': 15121, + 'framesequence': 58064, + 'gaze_dir': array([0.98008728, 0.17918396, 0.0849762 ]), + 'gaze_origin': array([-3.02830815, -0.15121919, 0.07346421]), + 'gaze_valid': True, + 'gaze_vergence': 274.03564453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97938538, 0.18574524, 0.07925415]), + 'left_gaze_origin': array([-2.94938827, 3.04373026, 0.0735077 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2240753173828125, + 'left_pupil_posn': array([ 0.19056475, -0.02556288]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98078918, 0.17262268, 0.09069824]), + 'right_gaze_origin': array([-3.10722828, -3.34616852, 0.07342072]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.185821533203125, + 'right_pupil_posn': array([ 0.17123365, -0.10084653]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.029828792437911034, + 'throttle_input': 0.42061492800712585, + 'timestamp': 494.56962986662984, + 'timestamp_carla': 494570, + 'timestamp_device': 4232788, + 'timestamp_stream': 494.56962986662984, + 'transform': [array([ -2.38673353, -12.49111462, 0.01566157]), + array([-0.06039936, 5.04818678, -0.00860604])]} +{'AngularVelocity': array([-5.34253521e-03, 8.74998514e-04, -2.78629327e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.89632225036621, + 'FR_Wheel_Angle': 41.86015319824219, + 'Location': array([ -2.53930807, -21.06837082, 0.17238727]), + 'Rotation': array([-0.06567226, 18.38117218, -0.0258789 ]), + 'Velocity': array([-0.16585346, -0.14344481, -0.00025642]), + 'brake_input': 0.0, + 'camera_location': array([-5.94426632, 13.50990486, 1.99405408]), + 'camera_rotation': array([-8.11037064, -2.19322467, 2.72740698]), + 'current_gear_input': False, + 'focus_actor_dist': 2166.001220703125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.38078186e+02, -4.73581787e+02, -1.52587891e-05]), + 'frame': 15122, + 'frame_number': 15122, + 'framesequence': 58067, + 'gaze_dir': array([0.97990417, 0.17920685, 0.08693695]), + 'gaze_origin': array([-3.02858138, -0.15101777, 0.07369385]), + 'gaze_valid': True, + 'gaze_vergence': 259.96270751953125, + 'handbrake_input': False, + 'left_eye_openness': 0.9989081025123596, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97911072, 0.18644714, 0.08096313]), + 'left_gaze_origin': array([-2.94938827, 3.04419875, 0.0735077 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2598114013671875, + 'left_pupil_posn': array([ 0.19000518, -0.02488768]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9685734510421753, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98069763, 0.17196655, 0.09291077]), + 'right_gaze_origin': array([-3.1077745 , -3.34623408, 0.07388001]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2141876220703125, + 'right_pupil_posn': array([ 0.17153454, -0.10012293]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.026422927156090736, + 'throttle_input': 0.42061492800712585, + 'timestamp': 494.60280506685376, + 'timestamp_carla': 494603, + 'timestamp_device': 4232813, + 'timestamp_stream': 494.60280506685376, + 'transform': [array([ -2.40372181, -12.4225378 , 0.01618563]), + array([-0.06033789, 5.09098768, -0.01083951])]} +{'AngularVelocity': array([-0.00857402, 0.00259902, -1.91916394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.923704147338867, + 'FR_Wheel_Angle': 41.90410232543945, + 'Location': array([ -2.57224059, -21.09276772, 0.17245173]), + 'Rotation': array([-0.0666763 , 17.84629631, -0.02435303]), + 'Velocity': array([-0.11499229, -0.09763441, 0.00022723]), + 'brake_input': 0.0, + 'camera_location': array([-5.89817905, 13.51033211, 1.9716469 ]), + 'camera_rotation': array([-8.23162079, -2.26094127, 2.74499631]), + 'current_gear_input': False, + 'focus_actor_dist': 2262.119140625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.63373230e+02, -3.73395752e+02, -1.52587891e-05]), + 'frame': 15123, + 'frame_number': 15123, + 'framesequence': 58071, + 'gaze_dir': array([0.97684479, 0.19628906, 0.08402252]), + 'gaze_origin': array([-3.03140497, -0.16954881, 0.07199784]), + 'gaze_valid': True, + 'gaze_vergence': 248.32240295410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97434998, 0.20857239, 0.08436584]), + 'left_gaze_origin': array([-2.94824553, 3.0256319 , 0.07171784]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2060394287109375, + 'left_pupil_posn': array([ 0.2066623, -0.029109 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9793396 , 0.18400574, 0.0836792 ]), + 'right_gaze_origin': array([-3.11456466, -3.3647294 , 0.07227784]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1060333251953125, + 'right_pupil_posn': array([ 0.19226563, -0.10159731]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.022870570421218872, + 'throttle_input': 0.42061492800712585, + 'timestamp': 494.6340281665325, + 'timestamp_carla': 494634, + 'timestamp_device': 4232847, + 'timestamp_stream': 494.6340281665325, + 'transform': [array([ -2.41901946, -12.35566139, 0.01669663]), + array([-0.06018079, 5.12755966, -0.0129637 ])]} +{'AngularVelocity': array([-0.01051526, -0.01012298, -0.2023755 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.94308853149414, + 'FR_Wheel_Angle': 41.938201904296875, + 'Location': array([ -2.59808612, -21.11146736, 0.17249271]), + 'Rotation': array([-0.06789891, 17.43108559, -0.02255249]), + 'Velocity': array([-0.07059092, -0.06235437, 0.00030193]), + 'brake_input': 0.0, + 'camera_location': array([-5.86845779, 13.51899338, 1.93328094]), + 'camera_rotation': array([-8.42282486, -2.32383966, 2.84996414]), + 'current_gear_input': False, + 'focus_actor_dist': 1846.7747802734375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-697.94396973, -777.86169434, 15.23117828]), + 'frame': 15124, + 'frame_number': 15124, + 'framesequence': 58076, + 'gaze_dir': array([0.97094727, 0.2215271 , 0.09003448]), + 'gaze_origin': array([-3.03809762, -0.19033052, 0.07497483]), + 'gaze_valid': True, + 'gaze_vergence': 356.2606201171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96958923, 0.22877502, 0.08683777]), + 'left_gaze_origin': array([-2.95724964, 3.00117517, 0.07537537]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.328125, + 'left_pupil_posn': array([ 0.23372555, -0.02587402]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9723053 , 0.21427917, 0.0932312 ]), + 'right_gaze_origin': array([-3.11894536, -3.38183594, 0.07457428]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0690765380859375, + 'right_pupil_posn': array([ 0.2113291 , -0.10046768]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.019244972616434097, + 'throttle_input': 0.42061492800712585, + 'timestamp': 494.6681621670723, + 'timestamp_carla': 494669, + 'timestamp_device': 4232888, + 'timestamp_stream': 494.6681621670723, + 'transform': [array([ -2.43481684, -12.28015232, 0.01712083]), + array([-0.05990076, 5.16286707, -0.01480785])]} +{'AngularVelocity': array([-0.01843544, -0.00362651, 0.2203072 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.957246780395508, + 'FR_Wheel_Angle': 41.95824432373047, + 'Location': array([ -2.61023641, -21.12032127, 0.17249347]), + 'Rotation': array([-0.06860241, 17.23289299, -0.02145386]), + 'Velocity': array([-4.91002612e-02, -4.39741798e-02, -2.34985346e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.86039639, 13.51356697, 1.8997705 ]), + 'camera_rotation': array([-8.64822102, -2.35182762, 2.98301148]), + 'current_gear_input': False, + 'focus_actor_dist': 1904.3319091796875, + 'focus_actor_name': 'Road_Curb_Town05_210', + 'focus_actor_pt': array([-760.30535889, -728.09472656, 15.23999786]), + 'frame': 15125, + 'frame_number': 15125, + 'framesequence': 58079, + 'gaze_dir': array([0.97085571, 0.2191925 , 0.09671021]), + 'gaze_origin': array([-3.03859735, -0.19173433, 0.07575989]), + 'gaze_valid': True, + 'gaze_vergence': 471.9865417480469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97032166, 0.22302246, 0.09341431]), + 'left_gaze_origin': array([-2.95755172, 3.00090647, 0.07590485]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.292938232421875, + 'left_pupil_posn': array([ 0.23434484, -0.02325761]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97138977, 0.21536255, 0.1000061 ]), + 'right_gaze_origin': array([-3.11964273, -3.3843751 , 0.07561494]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.139373779296875, + 'right_pupil_posn': array([ 0.21105349, -0.09761822]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01384319644421339, + 'throttle_input': 0.42458227276802063, + 'timestamp': 494.6997808665037, + 'timestamp_carla': 494700, + 'timestamp_device': 4232913, + 'timestamp_stream': 494.6997808665037, + 'transform': [array([ -2.44806147, -12.20783901, 0.01752075]), + array([-0.05938849, 5.18911982, -0.01641977])]} +{'AngularVelocity': array([-0.01901587, -0.0040099 , 0.36602747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.963186264038086, + 'FR_Wheel_Angle': 41.966522216796875, + 'Location': array([ -2.62043357, -21.12770462, 0.17251129]), + 'Rotation': array([-0.06949034, 17.06840134, -0.02026367]), + 'Velocity': array([-0.03659269, -0.03336737, 0.00021271]), + 'brake_input': 0.0, + 'camera_location': array([-5.8339138 , 13.51780415, 1.8621887 ]), + 'camera_rotation': array([-8.73538113, -2.41810465, 3.03107476]), + 'current_gear_input': False, + 'focus_actor_dist': 2227.35498046875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.45592590e+02, -4.09079346e+02, 1.52587891e-05]), + 'frame': 15126, + 'frame_number': 15126, + 'framesequence': 58083, + 'gaze_dir': array([0.97002411, 0.222435 , 0.09750366]), + 'gaze_origin': array([-3.03873229, -0.19275513, 0.07536393]), + 'gaze_valid': True, + 'gaze_vergence': 386.7160949707031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96897888, 0.22850037, 0.09403992]), + 'left_gaze_origin': array([-2.9576478 , 3.00054646, 0.07604523]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2862548828125, + 'left_pupil_posn': array([ 0.23496401, -0.02283955]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97106934, 0.21636963, 0.10096741]), + 'right_gaze_origin': array([-3.11981678, -3.3860569 , 0.07468262]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.139129638671875, + 'right_pupil_posn': array([ 0.21415424, -0.09821761]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00867946445941925, + 'throttle_input': 0.42458227276802063, + 'timestamp': 494.734287366271, + 'timestamp_carla': 494735, + 'timestamp_device': 4232947, + 'timestamp_stream': 494.734287366271, + 'transform': [array([ -2.4606452 , -12.12647915, 0.01782789]), + array([-0.05862351, 5.2094264 , -0.01770385])]} +{'AngularVelocity': array([-0.01453272, -0.00587929, 0.45089245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.965360641479492, + 'FR_Wheel_Angle': 41.969886779785156, + 'Location': array([ -2.6300869 , -21.13464737, 0.17253292]), + 'Rotation': array([-0.07019385, 16.91068077, -0.01937866]), + 'Velocity': array([-0.03156761, -0.02898137, 0.00012447]), + 'brake_input': 0.0, + 'camera_location': array([-5.81498432, 13.52131748, 1.81616437]), + 'camera_rotation': array([-8.83929539, -2.47964287, 3.0207696 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2194.72119140625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.43259033e+02, -4.34942139e+02, -1.52587891e-05]), + 'frame': 15127, + 'frame_number': 15127, + 'framesequence': 58087, + 'gaze_dir': array([0.96996307, 0.22275543, 0.09742737]), + 'gaze_origin': array([-3.03865743, -0.19305268, 0.07568283]), + 'gaze_valid': True, + 'gaze_vergence': 362.0262451171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96905518, 0.22850037, 0.09335327]), + 'left_gaze_origin': array([-2.95750737, 3.00019407, 0.07612458]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2866973876953125, + 'left_pupil_posn': array([ 0.23542476, -0.02258646]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97087097, 0.2170105 , 0.10150146]), + 'right_gaze_origin': array([-3.11980748, -3.38629937, 0.07524109]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.073944091796875, + 'right_pupil_posn': array([ 0.21432102, -0.09803081]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0018494217656552792, + 'throttle_input': 0.43648430705070496, + 'timestamp': 494.7669120654464, + 'timestamp_carla': 494767, + 'timestamp_device': 4232980, + 'timestamp_stream': 494.7669120654464, + 'transform': [array([ -2.47017026, -12.04712105, 0.01813052]), + array([-0.05753068, 5.21833897, -0.01883766])]} +{'AngularVelocity': array([-0.01559005, -0.00536149, 0.45062736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.966772079467773, + 'FR_Wheel_Angle': 41.97160339355469, + 'Location': array([ -2.63760948, -21.14002609, 0.17254798]), + 'Rotation': array([-0.07043291, 16.78860855, -0.01907349]), + 'Velocity': array([-0.02933929, -0.02696948, 0.00029076]), + 'brake_input': 0.0, + 'camera_location': array([-5.81028938, 13.52879333, 1.77894711]), + 'camera_rotation': array([-8.99778366, -2.48427224, 3.24411011]), + 'current_gear_input': False, + 'focus_actor_dist': 2132.87255859375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-826.25549316, -486.15185547, 0. ]), + 'frame': 15128, + 'frame_number': 15128, + 'framesequence': 58091, + 'gaze_dir': array([0.96843719, 0.22896576, 0.09812927]), + 'gaze_origin': array([-3.03892446, -0.19394226, 0.07723847]), + 'gaze_valid': True, + 'gaze_vergence': 356.24078369140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96740723, 0.23504639, 0.09410095]), + 'left_gaze_origin': array([-2.95756078, 2.99931812, 0.07680817]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2905426025390625, + 'left_pupil_posn': array([ 0.23806226, -0.02204585]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96946716, 0.22288513, 0.10215759]), + 'right_gaze_origin': array([-3.12028837, -3.38720274, 0.07766876]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.10186767578125, + 'right_pupil_posn': array([ 0.21731961, -0.09634387]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004504532087594271, + 'throttle_input': 0.4404516816139221, + 'timestamp': 494.801168166101, + 'timestamp_carla': 494802, + 'timestamp_device': 4233013, + 'timestamp_stream': 494.801168166101, + 'transform': [array([ -2.47737265, -11.96129131, 0.01838547]), + array([-0.05615098, 5.21579885, -0.01978705])]} +{'AngularVelocity': array([-0.01563539, -0.00529237, 0.43586007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.966747283935547, + 'FR_Wheel_Angle': 41.97127914428711, + 'Location': array([ -2.64496708, -21.14525032, 0.17255825]), + 'Rotation': array([-0.07067879, 16.66932297, -0.01879883]), + 'Velocity': array([-0.02965549, -0.02703505, 0.00039251]), + 'brake_input': 0.0, + 'camera_location': array([-5.80252743, 13.53648949, 1.78718519]), + 'camera_rotation': array([-8.94459629, -2.51698446, 3.17226529]), + 'current_gear_input': False, + 'focus_actor_dist': 1810.9189453125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-750.77557373, -790.98400879, 15.22864532]), + 'frame': 15129, + 'frame_number': 15129, + 'framesequence': 58095, + 'gaze_dir': array([0.96713257, 0.2334671 , 0.10032654]), + 'gaze_origin': array([-3.03938842, -0.19476929, 0.07627793]), + 'gaze_valid': True, + 'gaze_vergence': 349.7984313964844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96566772, 0.2408905 , 0.09713745]), + 'left_gaze_origin': array([-2.95756078, 2.99823475, 0.07695008]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2822113037109375, + 'left_pupil_posn': array([ 0.23991132, -0.02154481]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96859741, 0.2260437 , 0.10351562]), + 'right_gaze_origin': array([-3.12121606, -3.38777351, 0.07560578]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.120452880859375, + 'right_pupil_posn': array([ 0.21982694, -0.09703457]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.011004974134266376, + 'throttle_input': 0.4444190263748169, + 'timestamp': 494.8344456665218, + 'timestamp_carla': 494835, + 'timestamp_device': 4233047, + 'timestamp_stream': 494.8344456665218, + 'transform': [array([ -2.48146081, -11.87537861, 0.01863503]), + array([-0.05480544, 5.20104504, -0.02066132])]} +{'AngularVelocity': array([-0.05065581, 0.03675105, -0.50046766]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.90414810180664, + 'FR_Wheel_Angle': 41.8133430480957, + 'Location': array([ -2.65193009, -21.15000153, 0.17256771]), + 'Rotation': array([-0.07158721, 16.55028534, -0.01794433]), + 'Velocity': array([-0.06577022, -0.04469868, 0.00063317]), + 'brake_input': 0.0, + 'camera_location': array([-5.81606674, 13.55355453, 1.76044929]), + 'camera_rotation': array([-9.0812006 , -2.54479933, 3.21363425]), + 'current_gear_input': False, + 'focus_actor_dist': 2144.97412109375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.53477905e+02, -4.64468506e+02, -1.52587891e-05]), + 'frame': 15130, + 'frame_number': 15130, + 'framesequence': 58099, + 'gaze_dir': array([0.96685791, 0.23458099, 0.10038757]), + 'gaze_origin': array([-3.03944039, -0.19559099, 0.07729569]), + 'gaze_valid': True, + 'gaze_vergence': 360.91748046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96566772, 0.24105835, 0.09669495]), + 'left_gaze_origin': array([-2.95776677, 2.99677753, 0.07823487]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2744293212890625, + 'left_pupil_posn': array([ 0.24162459, -0.02055621]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9680481 , 0.22810364, 0.1040802 ]), + 'right_gaze_origin': array([-3.12111378, -3.38795924, 0.07635652]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.120391845703125, + 'right_pupil_posn': array([ 0.22001231, -0.09666753]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01664479449391365, + 'throttle_input': 0.45235371589660645, + 'timestamp': 494.8673770688474, + 'timestamp_carla': 494868, + 'timestamp_device': 4233080, + 'timestamp_stream': 494.8673770688474, + 'transform': [array([ -2.48269033, -11.78783703, 0.01888097]), + array([-0.05358966, 5.17462921, -0.02152192])]} +{'AngularVelocity': array([ 0.0807356 , -0.00681036, -6.32060528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.799270629882812, + 'FR_Wheel_Angle': 41.68977355957031, + 'Location': array([ -2.71483779, -21.19145966, 0.17269607]), + 'Rotation': array([-8.30619261e-02, 1.55702038e+01, -4.36401321e-03]), + 'Velocity': array([-3.43002915e-01, -2.59170830e-01, 3.18088511e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.83541203, 13.5576458 , 1.71340454]), + 'camera_rotation': array([-9.23135567, -2.4836669 , 3.51271796]), + 'current_gear_input': False, + 'focus_actor_dist': 1835.358642578125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-767.10498047, -752.64294434, 15.2359848 ]), + 'frame': 15131, + 'frame_number': 15131, + 'framesequence': 58103, + 'gaze_dir': array([0.96648407, 0.23540497, 0.10194397]), + 'gaze_origin': array([-3.03998494, -0.1957451 , 0.07719651]), + 'gaze_valid': True, + 'gaze_vergence': 289.4119873046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96536255, 0.24224854, 0.09674072]), + 'left_gaze_origin': array([-2.95900273, 2.99637461, 0.07749481]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.154754638671875, + 'left_pupil_posn': array([ 0.24221468, -0.01999927]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96760559, 0.2285614 , 0.10714722]), + 'right_gaze_origin': array([-3.12096715, -3.38786459, 0.0768982 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.12066650390625, + 'right_pupil_posn': array([ 0.2203666 , -0.09626889]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.022650837898254395, + 'throttle_input': 0.45235371589660645, + 'timestamp': 494.9006279669702, + 'timestamp_carla': 494901, + 'timestamp_device': 4233113, + 'timestamp_stream': 494.9006279669702, + 'transform': [array([ -2.48093843, -11.69689751, 0.01910925]), + array([-0.05240121, 5.13552141, -0.02232106])]} +{'AngularVelocity': array([ 0.02884864, -0.02463146, -6.13979769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76132583618164, + 'FR_Wheel_Angle': 41.623374938964844, + 'Location': array([ -2.81334186, -21.25536156, 0.17276561]), + 'Rotation': array([-7.86496252e-02, 1.40838366e+01, -1.02539053e-02]), + 'Velocity': array([-4.36818451e-01, -3.27223480e-01, 1.83124532e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.81409454, 13.54445648, 1.69607115]), + 'camera_rotation': array([-9.1000452 , -2.43232894, 3.7394464 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1573.8798828125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-696.47039795, -995.13586426, 28.98464966]), + 'frame': 15132, + 'frame_number': 15132, + 'framesequence': 58107, + 'gaze_dir': array([0.96649933, 0.23560333, 0.1013031 ]), + 'gaze_origin': array([-3.04026437, -0.19706346, 0.07679139]), + 'gaze_valid': True, + 'gaze_vergence': 298.89105224609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96511841, 0.24324036, 0.09672546]), + 'left_gaze_origin': array([-2.95912933, 2.99408293, 0.07550659]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.261138916015625, + 'left_pupil_posn': array([ 0.24357176, -0.02173185]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9724661111831665, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96788025, 0.22796631, 0.10588074]), + 'right_gaze_origin': array([-3.12139916, -3.38820958, 0.07807618]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.101837158203125, + 'right_pupil_posn': array([ 0.22098553, -0.0955385 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.028785059228539467, + 'throttle_input': 0.45235371589660645, + 'timestamp': 494.93357626721263, + 'timestamp_carla': 494934, + 'timestamp_device': 4233147, + 'timestamp_stream': 494.93357626721263, + 'transform': [array([ -2.47600389, -11.604249 , 0.01932406]), + array([-0.0511786 , 5.08359385, -0.02304505])]} +{'AngularVelocity': array([ 0.04154561, -0.01771184, -5.27641773]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.773805618286133, + 'FR_Wheel_Angle': 41.65207290649414, + 'Location': array([ -2.91518283, -21.31842232, 0.17283459]), + 'Rotation': array([-0.07257076, 12.52794838, -0.01895141]), + 'Velocity': array([-4.12325352e-01, -2.90080935e-01, 3.76510608e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.81224823, 13.55155182, 1.68943751]), + 'camera_rotation': array([-9.13218117, -2.45392489, 3.71456623]), + 'current_gear_input': False, + 'focus_actor_dist': 1791.7144775390625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-760.83795166, -778.1439209 , 15.23114014]), + 'frame': 15133, + 'frame_number': 15133, + 'framesequence': 58111, + 'gaze_dir': array([0.96582794, 0.2381897 , 0.10179138]), + 'gaze_origin': array([-3.04047871, -0.19941178, 0.08059082]), + 'gaze_valid': True, + 'gaze_vergence': 324.0735778808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96516418, 0.24295044, 0.09693909]), + 'left_gaze_origin': array([-2.95955825, 2.98972631, 0.08226776]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1640472412109375, + 'left_pupil_posn': array([ 0.24840343, -0.01721787]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9664917 , 0.23342896, 0.10664368]), + 'right_gaze_origin': array([-3.12139916, -3.38855004, 0.07891388]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.085052490234375, + 'right_pupil_posn': array([ 0.22113848, -0.09487569]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03550523519515991, + 'throttle_input': 0.45235371589660645, + 'timestamp': 494.9668395668268, + 'timestamp_carla': 494967, + 'timestamp_device': 4233180, + 'timestamp_stream': 494.9668395668268, + 'transform': [array([ -2.46738338, -11.5081768 , 0.01951352]), + array([-0.04980574, 5.01638794, -0.02365295])]} +{'AngularVelocity': array([-8.29904247e-03, -3.40307085e-03, -4.64953566e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.797636032104492, + 'FR_Wheel_Angle': 41.70074462890625, + 'Location': array([ -3.02175045, -21.38057137, 0.17293079]), + 'Rotation': array([-0.06994797, 10.93190289, -0.02182007]), + 'Velocity': array([-0.36908892, -0.24748646, 0.00056467]), + 'brake_input': 0.0, + 'camera_location': array([-5.82547379, 13.58886147, 1.68117571]), + 'camera_rotation': array([-9.3221283 , -2.48418307, 3.45720458]), + 'current_gear_input': False, + 'focus_actor_dist': 1791.5491943359375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-763.85388184, -769.74768066, 15.23271942]), + 'frame': 15134, + 'frame_number': 15134, + 'framesequence': 58115, + 'gaze_dir': array([0.9655304 , 0.24169922, 0.09641266]), + 'gaze_origin': array([-3.04019332, -0.20153581, 0.08142319]), + 'gaze_valid': True, + 'gaze_vergence': 746.6295776367188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9644928 , 0.24555969, 0.09706116]), + 'left_gaze_origin': array([-2.95870233, 2.988904 , 0.083815 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2807464599609375, + 'left_pupil_posn': array([ 0.25030351, -0.02003205]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96656799, 0.23783875, 0.09576416]), + 'right_gaze_origin': array([-3.12168455, -3.39197564, 0.07903138]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0817413330078125, + 'right_pupil_posn': array([ 0.22443056, -0.09486151]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04218878969550133, + 'throttle_input': 0.45235371589660645, + 'timestamp': 494.9997157678008, + 'timestamp_carla': 495000, + 'timestamp_device': 4233213, + 'timestamp_stream': 494.9997157678008, + 'transform': [array([ -2.45503187, -11.41073704, 0.01968689]), + array([-0.04833725, 4.93455362, -0.02416521])]} +{'AngularVelocity': array([ 0.02992259, 0.00590926, -4.99864912]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.827404022216797, + 'FR_Wheel_Angle': 41.74342346191406, + 'Location': array([ -3.09225965, -21.41939354, 0.17300083]), + 'Rotation': array([-0.06973623, 9.87527466, -0.02194213]), + 'Velocity': array([-3.34974289e-01, -2.10256055e-01, 8.59546635e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.78992939, 13.63486195, 1.68257427]), + 'camera_rotation': array([-9.26238441, -2.40363121, 3.67370415]), + 'current_gear_input': False, + 'focus_actor_dist': 1614.956787109375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-715.42034912, -930.27429199, 14.95197296]), + 'frame': 15135, + 'frame_number': 15135, + 'framesequence': 58119, + 'gaze_dir': array([0.96505737, 0.2417984 , 0.10059357]), + 'gaze_origin': array([-3.04211211, -0.20460586, 0.07469788]), + 'gaze_valid': True, + 'gaze_vergence': 398.03570556640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96328735, 0.24923706, 0.09968567]), + 'left_gaze_origin': array([-2.96005559, 2.98859262, 0.07429657]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2358856201171875, + 'left_pupil_posn': array([ 0.24940717, -0.02453113]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96682739, 0.23435974, 0.10150146]), + 'right_gaze_origin': array([-3.1241684 , -3.3978045 , 0.07509919]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0894317626953125, + 'right_pupil_posn': array([ 0.22983885, -0.09722662]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04846949875354767, + 'throttle_input': 0.45235371589660645, + 'timestamp': 495.0342050679028, + 'timestamp_carla': 495035, + 'timestamp_device': 4233246, + 'timestamp_stream': 495.0342050679028, + 'transform': [array([ -2.43783927, -11.30595207, 0.01981016]), + array([-0.04684144, 4.83181572, -0.02450672])]} +{'AngularVelocity': array([ 0.05321649, -0.02517891, -6.94909143]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75349235534668, + 'FR_Wheel_Angle': 41.624046325683594, + 'Location': array([ -3.20508504, -21.47750664, 0.17316589]), + 'Rotation': array([-0.07739287, 8.23858452, -0.01278687]), + 'Velocity': array([-0.47488651, -0.28099519, 0.0011308 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.72876167, 13.69205189, 1.6927489 ]), + 'camera_rotation': array([-9.13005638, -2.25281072, 3.91735697]), + 'current_gear_input': False, + 'focus_actor_dist': 1535.994873046875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-694.26068115, -995.64868164, 27.45799255]), + 'frame': 15136, + 'frame_number': 15136, + 'framesequence': 58123, + 'gaze_dir': array([0.96481323, 0.2452774 , 0.09377289]), + 'gaze_origin': array([-3.04173756, -0.20413134, 0.07415161]), + 'gaze_valid': True, + 'gaze_vergence': 205.07066345214844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9627533 , 0.25601196, 0.08692932]), + 'left_gaze_origin': array([-2.95992279, 2.98905659, 0.07370148]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.236663818359375, + 'left_pupil_posn': array([ 0.24915385, -0.02521801]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96687317, 0.23454285, 0.10061646]), + 'right_gaze_origin': array([-3.12355208, -3.39731908, 0.07460175]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1117706298828125, + 'right_pupil_posn': array([ 0.2317729 , -0.10205448]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05550096556544304, + 'throttle_input': 0.45235371589660645, + 'timestamp': 495.0670602656901, + 'timestamp_carla': 495067, + 'timestamp_device': 4233280, + 'timestamp_stream': 495.0670602656901, + 'transform': [array([ -2.41722417, -11.20371151, 0.01993774]), + array([-0.04528415, 4.71726179, -0.02478675])]} +{'AngularVelocity': array([ 0.02591443, -0.0206582 , -5.10114574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81472396850586, + 'FR_Wheel_Angle': 41.72981643676758, + 'Location': array([ -3.30054498, -21.52383423, 0.1732291 ]), + 'Rotation': array([-0.06863657, 6.86121273, -0.02334595]), + 'Velocity': array([-0.35128963, -0.19721223, 0.00036175]), + 'brake_input': 0.0, + 'camera_location': array([-5.67390537, 13.75066566, 1.66547549]), + 'camera_rotation': array([-9.25926304, -2.10224533, 3.93998504]), + 'current_gear_input': False, + 'focus_actor_dist': 1580.9100341796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-714.51391602, -944.94104004, 15.22733307]), + 'frame': 15137, + 'frame_number': 15137, + 'framesequence': 58127, + 'gaze_dir': array([0.96499634, 0.24482727, 0.09327698]), + 'gaze_origin': array([-3.04166508, -0.20404512, 0.07465135]), + 'gaze_valid': True, + 'gaze_vergence': 227.41534423828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96353149, 0.25315857, 0.08657837]), + 'left_gaze_origin': array([-2.95998836, 2.9891665 , 0.07427826]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.266876220703125, + 'left_pupil_posn': array([ 0.24973643, -0.0251292 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96646118, 0.23649597, 0.09997559]), + 'right_gaze_origin': array([-3.12334156, -3.39725661, 0.07502442]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.15411376953125, + 'right_pupil_posn': array([ 0.23067403, -0.10185826]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06185491755604744, + 'throttle_input': 0.45235371589660645, + 'timestamp': 495.099746465683, + 'timestamp_carla': 495100, + 'timestamp_device': 4233313, + 'timestamp_stream': 495.099746465683, + 'transform': [array([ -2.3922112, -11.0996294, 0.0200556]), + array([-0.04367223, 4.58560371, -0.02502581])]} +{'AngularVelocity': array([-3.91421979e-03, -9.38287412e-04, -3.63827562e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.869688034057617, + 'FR_Wheel_Angle': 41.817901611328125, + 'Location': array([ -3.36442065, -21.55332184, 0.17326103]), + 'Rotation': array([-0.06656019, 5.94517756, -0.02471924]), + 'Velocity': array([-0.25215045, -0.13632302, 0.00025267]), + 'brake_input': 0.0, + 'camera_location': array([-5.62195206, 13.80802536, 1.62308109]), + 'camera_rotation': array([-9.46812344, -1.97889245, 3.86910057]), + 'current_gear_input': False, + 'focus_actor_dist': 1499.3504638671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -691.34802246, -1012.74902344, 17.32849121]), + 'frame': 15138, + 'frame_number': 15138, + 'framesequence': 58131, + 'gaze_dir': array([0.96395874, 0.2488327 , 0.09377289]), + 'gaze_origin': array([-3.04167271, -0.20436098, 0.0763031 ]), + 'gaze_valid': True, + 'gaze_vergence': 236.1808624267578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96362305, 0.25236511, 0.08786011]), + 'left_gaze_origin': array([-2.96056056, 2.98827529, 0.07758179]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2999420166015625, + 'left_pupil_posn': array([ 0.25344586, -0.02326763]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96429443, 0.24530029, 0.09968567]), + 'right_gaze_origin': array([-3.12278461, -3.39699721, 0.07502442]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2176055908203125, + 'right_pupil_posn': array([ 0.23019505, -0.1013 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06899625062942505, + 'throttle_input': 0.45235371589660645, + 'timestamp': 495.1326283663511, + 'timestamp_carla': 495133, + 'timestamp_device': 4233346, + 'timestamp_stream': 495.1326283663511, + 'transform': [array([ -2.36214232, -10.99263763, 0.02015383]), + array([-0.04190321, 4.43409491, -0.02517607])]} +{'AngularVelocity': array([-0.01017474, 0.00442631, -2.4967556 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.905590057373047, + 'FR_Wheel_Angle': 41.87514877319336, + 'Location': array([ -3.41382861, -21.57530403, 0.17331958]), + 'Rotation': array([-0.06731834, 5.23995113, -0.02282715]), + 'Velocity': array([-1.73883542e-01, -9.12963003e-02, -7.84587828e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.60053921, 13.85148907, 1.59001863]), + 'camera_rotation': array([-9.71218681, -1.86054325, 3.78051209]), + 'current_gear_input': False, + 'focus_actor_dist': 1449.3641357421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -682.62023926, -1051.90258789, 17.19526672]), + 'frame': 15139, + 'frame_number': 15139, + 'framesequence': 58135, + 'gaze_dir': array([0.96264648, 0.2516861 , 0.09895325]), + 'gaze_origin': array([-3.04144454, -0.20557863, 0.0800438 ]), + 'gaze_valid': True, + 'gaze_vergence': 233.62103271484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96009827, 0.26309204, 0.09466553]), + 'left_gaze_origin': array([-2.96064472, 2.98657846, 0.08056489]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2554473876953125, + 'left_pupil_posn': array([ 0.25283396, -0.02002072]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9651947 , 0.24028015, 0.10324097]), + 'right_gaze_origin': array([-3.12224436, -3.3977356 , 0.07952271]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.235015869140625, + 'right_pupil_posn': array([ 0.23451602, -0.09623635]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.075881227850914, + 'throttle_input': 0.4563210606575012, + 'timestamp': 495.1680365651846, + 'timestamp_carla': 495168, + 'timestamp_device': 4233380, + 'timestamp_stream': 495.1680365651846, + 'transform': [array([ -2.32417083, -10.87501335, 0.0201885 ]), + array([-0.04003857, 4.24943686, -0.02512143])]} +{'AngularVelocity': array([ 0.00711021, -0.02424222, -0.0003429 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.983531951904297, + 'FR_Wheel_Angle': 41.999977111816406, + 'Location': array([ -3.44088244, -21.58696175, 0.17332233]), + 'Rotation': array([-0.06313827, 4.85395241, -0.02856445]), + 'Velocity': array([-1.41074270e-05, 4.95648692e-06, 6.61699887e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.55971622, 13.89587021, 1.57633054]), + 'camera_rotation': array([-9.7771759 , -1.83195543, 3.67704868]), + 'current_gear_input': False, + 'focus_actor_dist': 1473.120849609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -693.90576172, -1019.53564453, 17.30432129]), + 'frame': 15140, + 'frame_number': 15140, + 'framesequence': 58139, + 'gaze_dir': array([0.97852325, 0.17965698, 0.09925079]), + 'gaze_origin': array([-3.04291248, -0.15343399, 0.08101273]), + 'gaze_valid': True, + 'gaze_vergence': 151.7172393798828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97624207, 0.19651794, 0.09120178]), + 'left_gaze_origin': array([-2.97764587, 3.04671049, 0.08708344]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.378448486328125, + 'left_pupil_posn': array([ 0.18545735, -0.0160799 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98080444, 0.16279602, 0.1072998 ]), + 'right_gaze_origin': array([-3.10817885, -3.35357833, 0.07494202]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.31964111328125, + 'right_pupil_posn': array([ 0.18014038, -0.0962981 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08514665067195892, + 'throttle_input': 0.4563210606575012, + 'timestamp': 495.199376065284, + 'timestamp_carla': 495200, + 'timestamp_device': 4233413, + 'timestamp_stream': 495.199376065284, + 'transform': [array([ -2.28521013, -10.76889896, 0.02026009]), + array([-0.03796219, 4.06566525, -0.0250463 ])]} +{'AngularVelocity': array([-0.02469401, 0.01732843, 0.00019519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.983530044555664, + 'FR_Wheel_Angle': 41.99998474121094, + 'Location': array([ -3.44091177, -21.58703041, 0.17334095]), + 'Rotation': array([-0.06894393, 4.8540411 , -0.0198059 ]), + 'Velocity': array([1.85083136e-05, 8.42326790e-06, 5.57330786e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.51164913, 13.95153522, 1.56627059]), + 'camera_rotation': array([-9.78729153, -1.89353788, 3.53777361]), + 'current_gear_input': False, + 'focus_actor_dist': 1529.498291015625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-598.4956665 , -922.90942383, 14.96109009]), + 'frame': 15141, + 'frame_number': 15141, + 'framesequence': 58143, + 'gaze_dir': array([ 0.9943924 , -0.01716614, 0.10320282]), + 'gaze_origin': array([-3.10772109e+00, 4.94384789e-04, 1.04438782e-01]), + 'gaze_valid': True, + 'gaze_vergence': 203.04080200195312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9941864 , -0.00273132, 0.10760498]), + 'left_gaze_origin': array([-3.07684946, 3.19963837, 0.12333679]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2173309326171875, + 'left_pupil_posn': array([ 0.01546299, -0.01075983]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99459839, -0.03160095, 0.09880066]), + 'right_gaze_origin': array([-3.13859272, -3.19864964, 0.08554077]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2365875244140625, + 'right_pupil_posn': array([ 0.00606644, -0.08587503]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09472335129976273, + 'throttle_input': 0.4563210606575012, + 'timestamp': 495.23228526860476, + 'timestamp_carla': 495233, + 'timestamp_device': 4233446, + 'timestamp_stream': 495.23228526860476, + 'transform': [array([ -2.23720717, -10.65549278, 0.02032032]), + array([-0.03524378, 3.84558702, -0.02493018])]} +{'AngularVelocity': array([-6.72513293e-03, 4.26675938e-03, 4.66081583e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.983531951904297, + 'FR_Wheel_Angle': 41.999996185302734, + 'Location': array([ -3.44092703, -21.5870533 , 0.17337914]), + 'Rotation': array([-0.07138231, 4.85410023, -0.01681518]), + 'Velocity': array([7.23918902e-06, 2.13206908e-06, 3.91573558e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.50057602, 13.98156166, 1.55502605]), + 'camera_rotation': array([-9.95178318, -2.15148997, 3.70779228]), + 'current_gear_input': False, + 'focus_actor_dist': 2064.057861328125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-3.07969940e+02, -3.38121338e+02, -1.52587891e-05]), + 'frame': 15142, + 'frame_number': 15142, + 'framesequence': 58147, + 'gaze_dir': array([ 0.98164368, -0.15893555, 0.10406494]), + 'gaze_origin': array([-3.06837416, 0.10412217, 0.08445359]), + 'gaze_valid': True, + 'gaze_vergence': 187.02780151367188, + 'handbrake_input': False, + 'left_eye_openness': 0.9540640115737915, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98388672, -0.14285278, 0.10748291]), + 'left_gaze_origin': array([-2.99524999, 3.29588008, 0.08846436]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.31231689453125, + 'left_pupil_posn': array([-0.09853154, -0.01954198]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97940063, -0.17501831, 0.10064697]), + 'right_gaze_origin': array([-3.14149785, -3.08763599, 0.08044282]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.37567138671875, + 'right_pupil_posn': array([-0.11807114, -0.08951902]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10459303855895996, + 'throttle_input': 0.4563210606575012, + 'timestamp': 495.26650316640735, + 'timestamp_carla': 495267, + 'timestamp_device': 4233480, + 'timestamp_stream': 495.26650316640735, + 'transform': [array([ -2.17948699, -10.53559685, 0.02036314]), + array([-0.03216336, 3.58726931, -0.02473894])]} +{'AngularVelocity': array([-1.92582724e-03, 1.03410333e-03, 5.62274317e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.43779182434082, + 'FR_Wheel_Angle': 38.875022888183594, + 'Location': array([ -3.4409306 , -21.58706093, 0.17339604]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([4.55511235e-06, 3.84953438e-07, 1.10360394e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.4877243 , 13.99167824, 1.54639494]), + 'camera_rotation': array([-9.99157619, -2.82646418, 3.89438486]), + 'current_gear_input': False, + 'focus_actor_dist': 2395.239990234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 41.2545166 , -12.17504883, 0. ]), + 'frame': 15143, + 'frame_number': 15143, + 'framesequence': 58151, + 'gaze_dir': array([ 0.9757309 , -0.19047546, 0.10623169]), + 'gaze_origin': array([-3.07347822, 0.13596269, 0.07628708]), + 'gaze_valid': True, + 'gaze_vergence': 164.7225341796875, + 'handbrake_input': False, + 'left_eye_openness': 0.9169758558273315, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97920227, -0.17181396, 0.1078186 ]), + 'left_gaze_origin': array([-3.00142074, 3.32518172, 0.08223267]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.40301513671875, + 'left_pupil_posn': array([-0.13029593, -0.02386904]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97225952, -0.20913696, 0.10464478]), + 'right_gaze_origin': array([-3.14553523, -3.05325627, 0.0703415 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.36578369140625, + 'right_pupil_posn': array([-0.15164411, -0.0971303 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11728263646364212, + 'throttle_input': 0.4563210606575012, + 'timestamp': 495.29968416690826, + 'timestamp_carla': 495300, + 'timestamp_device': 4233513, + 'timestamp_stream': 495.29968416690826, + 'transform': [array([ -2.11486626, -10.41762352, 0.02041174]), + array([-0.02871411, 3.30428839, -0.02447939])]} +{'AngularVelocity': array([-6.16261910e-04, 2.96809565e-04, -4.87366560e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.846982955932617, + 'FR_Wheel_Angle': 34.4323844909668, + 'Location': array([ -3.44093156, -21.58706093, 0.17337856]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([ 3.35270533e-06, -1.17977613e-07, -2.52673577e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.51092148, 13.99192238, 1.51562095]), + 'camera_rotation': array([-10.06954956, -3.54851413, 4.12553453]), + 'current_gear_input': False, + 'focus_actor_dist': 2627.75732421875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.93408356e+02, 2.12731689e+02, -1.52587891e-05]), + 'frame': 15144, + 'frame_number': 15144, + 'framesequence': 58155, + 'gaze_dir': array([ 0.97748566, -0.18418121, 0.1018219 ]), + 'gaze_origin': array([-3.07227731, 0.12788467, 0.08120728]), + 'gaze_valid': True, + 'gaze_vergence': 211.8063201904297, + 'handbrake_input': False, + 'left_eye_openness': 0.920417308807373, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97988892, -0.16996765, 0.10452271]), + 'left_gaze_origin': array([-2.99993467, 3.32060719, 0.08550568]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3204345703125, + 'left_pupil_posn': array([-0.12344575, -0.02307355]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9750824 , -0.19839478, 0.09912109]), + 'right_gaze_origin': array([-3.14461994, -3.06483793, 0.07690888]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4297943115234375, + 'right_pupil_posn': array([-0.14297205, -0.09383488]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.12942290306091309, + 'throttle_input': 0.4563210606575012, + 'timestamp': 495.3341234661639, + 'timestamp_carla': 495335, + 'timestamp_device': 4233546, + 'timestamp_stream': 495.3341234661639, + 'transform': [array([ -2.03783226, -10.29360294, 0.02043892]), + array([-0.02477309, 2.97331595, -0.0241174 ])]} +{'AngularVelocity': array([-1.39443320e-04, 4.00971076e-05, -8.97912287e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.11229133605957, + 'FR_Wheel_Angle': 30.435802459716797, + 'Location': array([ -3.44093204, -21.58706284, 0.17338149]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([ 3.40393740e-06, -3.01307296e-07, 1.56873110e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.55186844, 13.97755432, 1.49890125]), + 'camera_rotation': array([-10.17128468, -4.36003494, 4.50612164]), + 'current_gear_input': False, + 'focus_actor_dist': 2368.001220703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.74748199e+02, -3.62309570e+01, -1.52587891e-05]), + 'frame': 15145, + 'frame_number': 15145, + 'framesequence': 58159, + 'gaze_dir': array([ 0.97916412, -0.17628479, 0.09971619]), + 'gaze_origin': array([-3.0733645 , 0.12214356, 0.08084717]), + 'gaze_valid': True, + 'gaze_vergence': 217.88470458984375, + 'handbrake_input': False, + 'left_eye_openness': 0.9320491552352905, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98155212, -0.16213989, 0.10125732]), + 'left_gaze_origin': array([-3.00024271, 3.31620359, 0.08637543]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3063812255859375, + 'left_pupil_posn': array([-0.11774564, -0.02265787]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97677612, -0.19042969, 0.09817505]), + 'right_gaze_origin': array([-3.14648604, -3.07191634, 0.07531892]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3984222412109375, + 'right_pupil_posn': array([-0.13549238, -0.09620595]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.14321117103099823, + 'throttle_input': 0.40474554896354675, + 'timestamp': 495.36638206616044, + 'timestamp_carla': 495367, + 'timestamp_device': 4233580, + 'timestamp_stream': 495.36638206616044, + 'transform': [array([ -1.95586026, -10.17627335, 0.02046342]), + array([-0.02075694, 2.62684226, -0.02365294])]} +{'AngularVelocity': array([ 1.97569716e-05, 1.47486080e-05, -8.74682155e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.320789337158203, + 'FR_Wheel_Angle': 29.29886245727539, + 'Location': array([ -3.44093204, -21.58706284, 0.17336826]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([ 2.97320071e-06, -4.59389412e-07, -1.67871840e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.59041119, 13.9634819 , 1.51691926]), + 'camera_rotation': array([-9.92473602, -5.23035049, 4.51425219]), + 'current_gear_input': False, + 'focus_actor_dist': 2229.96435546875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 174.63262939, -164.31982422, 0. ]), + 'frame': 15146, + 'frame_number': 15146, + 'framesequence': 58163, + 'gaze_dir': array([ 0.98101807, -0.16471863, 0.10138702]), + 'gaze_origin': array([-3.08119059, 0.11818238, 0.07954178]), + 'gaze_valid': True, + 'gaze_vergence': 223.2446746826172, + 'handbrake_input': False, + 'left_eye_openness': 0.9478501677513123, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98355103, -0.15200806, 0.09754944]), + 'left_gaze_origin': array([-3.00185108, 3.31316996, 0.08373566]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3672943115234375, + 'left_pupil_posn': array([-0.11111832, -0.02249289]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97848511, -0.1774292 , 0.10522461]), + 'right_gaze_origin': array([-3.16053033, -3.07680511, 0.0753479 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.324188232421875, + 'right_pupil_posn': array([-0.12858903, -0.09999287]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.15679800510406494, + 'throttle_input': 0.37299153208732605, + 'timestamp': 495.3995376676321, + 'timestamp_carla': 495400, + 'timestamp_device': 4233613, + 'timestamp_stream': 495.3995376676321, + 'transform': [array([ -1.86086059, -10.05490208, 0.02042354]), + array([-0.0163583 , 2.23104119, -0.02291528])]} +{'AngularVelocity': array([ 4.02989554e-06, -6.69883184e-06, -8.73035515e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.109682083129883, + 'FR_Wheel_Angle': 29.534709930419922, + 'Location': array([ -3.44093204, -21.58706284, 0.17336829]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([ 2.77040522e-06, -4.59377759e-07, -3.20629857e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.63808155, 13.91913223, 1.54762828]), + 'camera_rotation': array([-9.68498898, -6.00611877, 4.96137094]), + 'current_gear_input': False, + 'focus_actor_dist': 2415.46435546875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 2.32578827e+02, 2.56245117e+01, -1.52587891e-05]), + 'frame': 15147, + 'frame_number': 15147, + 'framesequence': 58167, + 'gaze_dir': array([ 0.98440552, -0.14755249, 0.09507751]), + 'gaze_origin': array([-3.11343622, 0.11352692, 0.08893204]), + 'gaze_valid': True, + 'gaze_vergence': 278.721923828125, + 'handbrake_input': False, + 'left_eye_openness': 0.9772307276725769, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98623657, -0.13749695, 0.09169006]), + 'left_gaze_origin': array([-3.0144074 , 3.30733204, 0.08443909]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2853240966796875, + 'left_pupil_posn': array([-0.10054415, -0.02616453]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98257446, -0.15760803, 0.09846497]), + 'right_gaze_origin': array([-3.21246505, -3.08027816, 0.09342499]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.270050048828125, + 'right_pupil_posn': array([-0.12085706, -0.09903753]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.17108066380023956, + 'throttle_input': 0.32538339495658875, + 'timestamp': 495.4326309673488, + 'timestamp_carla': 495433, + 'timestamp_device': 4233646, + 'timestamp_stream': 495.4326309673488, + 'transform': [array([-1.75489533, -9.93345356, 0.02030213]), + array([-0.01184355, 1.79516888, -0.02180879])]} +{'AngularVelocity': array([ 5.44377463e-06, -1.13971273e-05, -1.03786724e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.150697708129883, + 'FR_Wheel_Angle': 30.936975479125977, + 'Location': array([ -3.44093204, -21.58706284, 0.17337315]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([ 4.14391025e-06, -3.19192168e-07, 8.96730227e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.69641399, 13.79810715, 1.60649455]), + 'camera_rotation': array([-9.47070599, -6.79677057, 5.58230925]), + 'current_gear_input': False, + 'focus_actor_dist': 2298.2041015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.15615005e+02, -7.82438965e+01, 1.52587891e-05]), + 'frame': 15148, + 'frame_number': 15148, + 'framesequence': 58171, + 'gaze_dir': array([ 0.98710632, -0.13422394, 0.08678436]), + 'gaze_origin': array([-3.16906166, 0.1078354 , 0.09834671]), + 'gaze_valid': True, + 'gaze_vergence': 333.1044921875, + 'handbrake_input': False, + 'left_eye_openness': 0.971947193145752, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98748779, -0.12840271, 0.09147644]), + 'left_gaze_origin': array([-3.12154412, 3.30387902, 0.10823212]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2719268798828125, + 'left_pupil_posn': array([-0.09339881, -0.03509712]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98672485, -0.14004517, 0.08209229]), + 'right_gaze_origin': array([-3.21657872, -3.0882082 , 0.08846131]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1246490478515625, + 'right_pupil_posn': array([-0.11234504, -0.1030407 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.18538163602352142, + 'throttle_input': 0.2896620035171509, + 'timestamp': 495.4657100662589, + 'timestamp_carla': 495466, + 'timestamp_device': 4233680, + 'timestamp_stream': 495.4657100662589, + 'transform': [array([-1.63766479, -9.81231308, 0.02008396]), + array([-0.00735611, 1.31846178, -0.02028565])]} +{'AngularVelocity': array([-1.10930145e-04, 2.03411273e-05, -9.13331041e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.946182250976562, + 'FR_Wheel_Angle': 30.08843994140625, + 'Location': array([ -3.44093204, -21.58706284, 0.17339027]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([ 3.15038483e-06, -3.18253882e-07, -6.25228204e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.74028492, 13.65123081, 1.68997741]), + 'camera_rotation': array([-9.07830429, -7.69031382, 5.56776619]), + 'current_gear_input': False, + 'focus_actor_dist': 1350.5548095703125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([ 33.38302612, -994.29333496, 49.97398376]), + 'frame': 15149, + 'frame_number': 15149, + 'framesequence': 58175, + 'gaze_dir': array([ 0.98957062, -0.11708069, 0.08362579]), + 'gaze_origin': array([-3.19833469, 0.10255356, 0.10138474]), + 'gaze_valid': True, + 'gaze_vergence': 229.94656372070312, + 'handbrake_input': False, + 'left_eye_openness': 0.9747306704521179, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98939514, -0.11479187, 0.08883667]), + 'left_gaze_origin': array([-3.20149541, 3.30000782, 0.12886964]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0922088623046875, + 'left_pupil_posn': array([-0.08448082, -0.03683913]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98974609, -0.11936951, 0.07841492]), + 'right_gaze_origin': array([-3.19517374, -3.09490061, 0.07389985]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1745452880859375, + 'right_pupil_posn': array([-0.10324281, -0.10990512]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.19995728135108948, + 'throttle_input': 0.2539559006690979, + 'timestamp': 495.4998436681926, + 'timestamp_carla': 495500, + 'timestamp_device': 4233713, + 'timestamp_stream': 495.4998436681926, + 'transform': [array([-1.50476253, -9.68819809, 0.01974272]), + array([-0.00284136, 0.78364432, -0.01825709])]} +{'AngularVelocity': array([ 9.00250961e-05, 3.87848522e-05, -9.66473635e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.514392852783203, + 'FR_Wheel_Angle': 26.176454544067383, + 'Location': array([ -3.44093204, -21.58706284, 0.17338017]), + 'Rotation': array([-0.07183993, 4.85412645, -0.01623535]), + 'Velocity': array([ 3.10911787e-06, -5.13066766e-07, 1.96929232e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.78971767, 13.46376419, 1.75490117]), + 'camera_rotation': array([-8.69903755, -8.57135677, 5.45835209]), + 'current_gear_input': False, + 'focus_actor_dist': 2187.134521484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.25754944e+02, -1.68647705e+02, 3.05175781e-05]), + 'frame': 15150, + 'frame_number': 15150, + 'framesequence': 58179, + 'gaze_dir': array([ 0.99189758, -0.0994873 , 0.07798767]), + 'gaze_origin': array([-3.19725561, 0.09069367, 0.09552994]), + 'gaze_valid': True, + 'gaze_vergence': 0.7396941781044006, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9909668 , -0.09959412, 0.08966064]), + 'left_gaze_origin': array([-3.22825503, 3.28963804, 0.13108826]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1399993896484375, + 'left_pupil_posn': array([-0.07067078, -0.04426754]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99282837, -0.09938049, 0.0663147 ]), + 'right_gaze_origin': array([-3.1662569 , -3.10825062, 0.05997162]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.071624755859375, + 'right_pupil_posn': array([-0.08921134, -0.11345851]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.21429488062858582, + 'throttle_input': 0.19839780032634735, + 'timestamp': 495.5319173671305, + 'timestamp_carla': 495532, + 'timestamp_device': 4233746, + 'timestamp_stream': 495.5319173671305, + 'transform': [array([-1.36916375, -9.57297611, 0.01934379]), + array([ 0.00120894, 0.24299422, -0.01595532])]} +{'AngularVelocity': array([ 0.06901124, -0.02904513, 0.87940919]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.4893798828125, + 'FR_Wheel_Angle': 21.756349563598633, + 'Location': array([ -3.44096875, -21.58703041, 0.17338176]), + 'Rotation': array([-0.07181261, 4.86013365, -0.01651001]), + 'Velocity': array([ 1.65481698e-02, 8.99583194e-03, -7.41100303e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.84332275, 13.2343998 , 1.80682254]), + 'camera_rotation': array([-8.38453484, -9.57824039, 5.39064455]), + 'current_gear_input': False, + 'focus_actor_dist': 2146.2451171875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.34264694e+02, -1.99109131e+02, -3.05175781e-05]), + 'frame': 15151, + 'frame_number': 15151, + 'framesequence': 58183, + 'gaze_dir': array([ 0.99302673, -0.09214783, 0.07292938]), + 'gaze_origin': array([-3.12051177, 0.07469101, 0.0732483 ]), + 'gaze_valid': True, + 'gaze_vergence': 334.4353332519531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99362183, -0.08352661, 0.07572937]), + 'left_gaze_origin': array([-3.0596559 , 3.27121425, 0.0796051 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0525970458984375, + 'left_pupil_posn': array([-0.05706412, -0.04644883]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99243164, -0.10076904, 0.07012939]), + 'right_gaze_origin': array([-3.18136764, -3.12183237, 0.06689148]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0244293212890625, + 'right_pupil_posn': array([-0.07420701, -0.11634827]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.22661826014518738, + 'throttle_input': 0.17062638700008392, + 'timestamp': 495.5653673671186, + 'timestamp_carla': 495566, + 'timestamp_device': 4233780, + 'timestamp_stream': 495.5653673671186, + 'transform': [array([-1.21729636, -9.45483494, 0.01880758]), + array([ 0.00492457, -0.35746592, -0.01315494])]} +{'AngularVelocity': array([ 0.0598025 , -0.03246865, 0.78742641]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.642650604248047, + 'FR_Wheel_Angle': 17.732839584350586, + 'Location': array([ -3.44235706, -21.58728218, 0.17338333]), + 'Rotation': array([-0.0719014 , 4.84904671, -0.01644898]), + 'Velocity': array([ 1.22313099e-02, 6.62718387e-03, -2.90870662e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.89534283, 13.01567841, 1.87022436]), + 'camera_rotation': array([ -8.23335552, -10.57048512, 5.01546288]), + 'current_gear_input': False, + 'focus_actor_dist': 2129.599609375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 273.64123535, -212.95532227, 0. ]), + 'frame': 15152, + 'frame_number': 15152, + 'framesequence': 58187, + 'gaze_dir': array([ 0.99416351, -0.07378387, 0.07801819]), + 'gaze_origin': array([-3.11887455, 0.06701127, 0.07077637]), + 'gaze_valid': True, + 'gaze_vergence': 263.6164855957031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99429321, -0.06587219, 0.08381653]), + 'left_gaze_origin': array([-3.07373977, 3.2625823 , 0.08469849]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0780792236328125, + 'left_pupil_posn': array([-0.04472077, -0.04478741]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99403381, -0.08169556, 0.07221985]), + 'right_gaze_origin': array([-3.16400933, -3.12855983, 0.05685425]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.004119873046875, + 'right_pupil_posn': array([-0.06364775, -0.11731398]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.23765985667705536, + 'throttle_input': 0.1269855797290802, + 'timestamp': 495.5982809662819, + 'timestamp_carla': 495599, + 'timestamp_device': 4233813, + 'timestamp_stream': 495.5982809662819, + 'transform': [array([-1.05878532, -9.34106541, 0.01818399]), + array([ 0.00797083, -0.97929788, -0.01003355])]} +{'AngularVelocity': array([ 0.04772186, -0.035295 , 0.71811038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.023697853088379, + 'FR_Wheel_Angle': 12.912445068359375, + 'Location': array([ -3.44477868, -21.58768845, 0.17338139]), + 'Rotation': array([-0.07186725, 4.83388519, -0.01641846]), + 'Velocity': array([ 0.008704 , 0.00463642, -0.00010694]), + 'brake_input': 0.0, + 'camera_location': array([-5.95291996, 12.77032661, 1.97301757]), + 'camera_rotation': array([ -7.87445641, -11.64774323, 4.52895927]), + 'current_gear_input': False, + 'focus_actor_dist': 2322.622802734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([343.98190308, -17.97558594, 0. ]), + 'frame': 15153, + 'frame_number': 15153, + 'framesequence': 58191, + 'gaze_dir': array([ 0.9954071 , -0.0533905 , 0.07915497]), + 'gaze_origin': array([-3.10194421, 0.0529007 , 0.05356751]), + 'gaze_valid': True, + 'gaze_vergence': 469.2950134277344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99549866, -0.04780579, 0.08178711]), + 'left_gaze_origin': array([-3.0425477 , 3.24880695, 0.06446991]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9378814697265625, + 'left_pupil_posn': array([-0.02733254, -0.05117941]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99531555, -0.05897522, 0.07652283]), + 'right_gaze_origin': array([-3.16134048, -3.14300537, 0.0426651 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8739166259765625, + 'right_pupil_posn': array([-0.04769301, -0.12701344]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.24928739666938782, + 'throttle_input': 0.0634927898645401, + 'timestamp': 495.6316471658647, + 'timestamp_carla': 495632, + 'timestamp_device': 4233846, + 'timestamp_stream': 495.6316471658647, + 'transform': [array([-0.88948548, -9.2288084 , 0.01737146]), + array([ 0.01126298, -1.63870776, -0.00611985])]} +{'AngularVelocity': array([ 0.03403953, -0.0358949 , 0.63368601]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.198250770568848, + 'FR_Wheel_Angle': 8.137195587158203, + 'Location': array([ -3.44762111, -21.5880909 , 0.17339233]), + 'Rotation': array([-0.07186725, 4.82083178, -0.01641846]), + 'Velocity': array([ 4.49894555e-03, 2.82205641e-03, -6.32476804e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.03174019, 12.47094727, 2.06348991]), + 'camera_rotation': array([ -7.50424623, -12.87388897, 4.36950302]), + 'current_gear_input': False, + 'focus_actor_dist': 2539.460693359375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([425.26263428, 198.32128906, 0. ]), + 'frame': 15154, + 'frame_number': 15154, + 'framesequence': 58195, + 'gaze_dir': array([ 0.99649048, -0.03864288, 0.0737381 ]), + 'gaze_origin': array([-3.0883522 , 0.03819504, 0.05049668]), + 'gaze_valid': True, + 'gaze_vergence': 348.99957275390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99649048, -0.03143311, 0.07749939]), + 'left_gaze_origin': array([-3.03793049, 3.23436737, 0.06082459]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9227142333984375, + 'left_pupil_posn': array([-0.01302958, -0.05486917]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99649048, -0.04585266, 0.06997681]), + 'right_gaze_origin': array([-3.13877416, -3.15797734, 0.04016876]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.911865234375, + 'right_pupil_posn': array([-0.03210008, -0.12588382]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.25948670506477356, + 'throttle_input': 0.0, + 'timestamp': 495.66388066858053, + 'timestamp_carla': 495664, + 'timestamp_device': 4233880, + 'timestamp_stream': 495.66388066858053, + 'transform': [array([-0.71872407, -9.1237936 , 0.01637035]), + array([ 1.34896226e-02, -2.29950023e+00, -1.51630328e-03])]} +{'AngularVelocity': array([ 0.01909402, -0.03694272, 0.5675621 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.99776554107666, + 'FR_Wheel_Angle': 3.479703903198242, + 'Location': array([ -3.45216966, -21.58860779, 0.17339191]), + 'Rotation': array([-0.07186725, 4.80706501, -0.01641846]), + 'Velocity': array([-0.00082335, 0.0011322 , 0.00014833]), + 'brake_input': 0.0, + 'camera_location': array([-6.20402145, 12.15962029, 2.09721971]), + 'camera_rotation': array([ -7.37804508, -14.1303587 , 4.33724928]), + 'current_gear_input': False, + 'focus_actor_dist': 2524.509033203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([469.01116943, 183.76586914, 0. ]), + 'frame': 15155, + 'frame_number': 15155, + 'framesequence': 58199, + 'gaze_dir': array([ 0.99756622, -0.01387024, 0.06694031]), + 'gaze_origin': array([-3.08851099, 0.02203674, 0.05201951]), + 'gaze_valid': True, + 'gaze_vergence': 172.33499145507812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99707031, -0.00485229, 0.07621765]), + 'left_gaze_origin': array([-3.0404954 , 3.21726394, 0.06333008]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0241851806640625, + 'left_pupil_posn': array([ 0.0064503 , -0.05770457]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99806213, -0.02288818, 0.05766296]), + 'right_gaze_origin': array([-3.13652682, -3.17319036, 0.04070893]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8640594482421875, + 'right_pupil_posn': array([-0.01251841, -0.12579048]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2686239182949066, + 'throttle_input': 0.0, + 'timestamp': 495.69783666729927, + 'timestamp_carla': 495698, + 'timestamp_device': 4233913, + 'timestamp_stream': 495.69783666729927, + 'transform': [array([-0.5323056 , -9.01730442, 0.01511003]), + array([ 0.01491713, -3.01638913, 0.00402832])]} +{'AngularVelocity': array([ 0.00468123, -0.03955364, 0.53861916]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.20744900405406952, + 'FR_Wheel_Angle': -0.24910350143909454, + 'Location': array([ -3.45821524, -21.58911324, 0.1733977 ]), + 'Rotation': array([-0.0719014 , 4.79919863, -0.01641846]), + 'Velocity': array([-0.00733862, -0.00020486, -0.00013163]), + 'brake_input': 0.0, + 'camera_location': array([-6.38834095, 11.8338995 , 2.16052961]), + 'camera_rotation': array([ -7.05473804, -15.57147598, 3.91782188]), + 'current_gear_input': False, + 'focus_actor_dist': 2250.482177734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([413.69299316, -73.32324219, 0. ]), + 'frame': 15156, + 'frame_number': 15156, + 'framesequence': 58203, + 'gaze_dir': array([0.99781799, 0.01412201, 0.0637207 ]), + 'gaze_origin': array([-3.09037018, 0.0040802 , 0.05415879]), + 'gaze_valid': True, + 'gaze_vergence': 211.62515258789062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99725342, 0.02033997, 0.07115173]), + 'left_gaze_origin': array([-3.03715372, 3.19990849, 0.06642761]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0381317138671875, + 'left_pupil_posn': array([ 0.02883983, -0.05576456]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99838257, 0.00790405, 0.05628967]), + 'right_gaze_origin': array([-3.14358687, -3.19174814, 0.04188995]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.853546142578125, + 'right_pupil_posn': array([ 0.00897741, -0.12822652]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2774132490158081, + 'throttle_input': 0.0, + 'timestamp': 495.73208536580205, + 'timestamp_carla': 495732, + 'timestamp_device': 4233946, + 'timestamp_stream': 495.73208536580205, + 'transform': [array([-0.3386682 , -8.91449928, 0.01376294]), + array([ 0.0156343 , -3.75663447, 0.00985717])]} +{'AngularVelocity': array([ 0.00390893, -0.04090214, 0.54523325]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.01792542077600956, + 'FR_Wheel_Angle': -0.017921680584549904, + 'Location': array([ -3.46607375, -21.589674 , 0.17340027]), + 'Rotation': array([-0.07196287, 4.79547405, -0.01629639]), + 'Velocity': array([-0.01512481, -0.00089886, -0.00019007]), + 'brake_input': 0.0, + 'camera_location': array([-6.56453323, 11.52462769, 2.26518321]), + 'camera_rotation': array([ -6.55445385, -17.06289864, 3.24450755]), + 'current_gear_input': False, + 'focus_actor_dist': 2264.884521484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([442.87954712, -53.80053711, 0. ]), + 'frame': 15157, + 'frame_number': 15157, + 'framesequence': 58207, + 'gaze_dir': array([ 0.99202728, -0.12088776, 0.03087616]), + 'gaze_origin': array([-3.23275852, 0.1021843 , 0.07762375]), + 'gaze_valid': True, + 'gaze_vergence': 152.1750946044922, + 'handbrake_input': False, + 'left_eye_openness': 0.970409631729126, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99345398, -0.10667419, 0.04069519]), + 'left_gaze_origin': array([-3.25209355, 3.29852486, 0.11122742]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0173797607421875, + 'left_pupil_posn': array([-0.08974028, -0.07817066]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9870460033416748, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99060059, -0.13510132, 0.02105713]), + 'right_gaze_origin': array([-3.21342349, -3.09415603, 0.04402008]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.92718505859375, + 'right_pupil_posn': array([-0.10129809, -0.15012825]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2839869558811188, + 'throttle_input': 0.0, + 'timestamp': 495.7634482681751, + 'timestamp_carla': 495764, + 'timestamp_device': 4233980, + 'timestamp_stream': 495.7634482681751, + 'transform': [array([-0.15761718, -8.82447815, 0.01254594]), + array([ 0.01565479, -4.44506359, 0.01513672])]} +{'AngularVelocity': array([ 0.00310595, -0.03724926, 0.52213937]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.01791887916624546, + 'FR_Wheel_Angle': -0.017864767462015152, + 'Location': array([ -3.47628808, -21.59043694, 0.17341277]), + 'Rotation': array([-0.07211313, 4.79159975, -0.01629639]), + 'Velocity': array([-2.96761673e-02, -2.20609386e-03, 4.40120675e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.6857481 , 11.2098999 , 2.43823171]), + 'camera_rotation': array([ -5.80667114, -18.38000679, 2.95074153]), + 'current_gear_input': False, + 'focus_actor_dist': 1604.37841796875, + 'focus_actor_name': 'Road_Sidewalk_Town05_207', + 'focus_actor_pt': array([ 507.45843506, -780.27075195, 15.23052216]), + 'frame': 15158, + 'frame_number': 15158, + 'framesequence': 58211, + 'gaze_dir': array([ 0.96625519, -0.25639343, 0.00566864]), + 'gaze_origin': array([-3.14718771, 0.19886093, 0.01146317]), + 'gaze_valid': True, + 'gaze_vergence': 121.5479507446289, + 'handbrake_input': False, + 'left_eye_openness': 0.8577377200126648, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9719696 , -0.23468018, 0.01387024]), + 'left_gaze_origin': array([-3.10551167, 3.38315296, 0.02257996]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0358734130859375, + 'left_pupil_posn': array([-0.19632047, -0.12113452]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9422405362129211, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96054077, -0.27810669, -0.00253296]), + 'right_gaze_origin': array([-3.18886423e+00, -2.98543096e+00, 3.46374523e-04]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0347747802734375, + 'right_pupil_posn': array([-0.22157443, -0.1853739 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2883266806602478, + 'throttle_input': 0.0, + 'timestamp': 495.7975130677223, + 'timestamp_carla': 495798, + 'timestamp_device': 4234013, + 'timestamp_stream': 495.7975130677223, + 'transform': [array([ 0.0417218 , -8.73115826, 0.01124147]), + array([ 0.01486932, -5.19897699, 0.02056884])]} +{'AngularVelocity': array([-0.01193349, 0.09990789, 0.4108583 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.017793580889701843, + 'FR_Wheel_Angle': -0.017791660502552986, + 'Location': array([ -3.53672838, -21.59539413, 0.17353958]), + 'Rotation': array([-0.08471483, 4.78869581, -0.01623535]), + 'Velocity': array([-0.45230374, -0.03794975, 0.00079829]), + 'brake_input': 0.0, + 'camera_location': array([-6.71934414, 10.91473007, 2.64150262]), + 'camera_rotation': array([ -4.85575867, -19.52573204, 2.58584976]), + 'current_gear_input': False, + 'focus_actor_dist': 1532.7559814453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 701.43585205, -976.51672363, 15.78740692]), + 'frame': 15159, + 'frame_number': 15159, + 'framesequence': 58215, + 'gaze_dir': array([ 0.94321442, -0.32970428, -0.03962708]), + 'gaze_origin': array([-3.16399717, 0.25133821, -0.01274185]), + 'gaze_valid': True, + 'gaze_vergence': 199.82716369628906, + 'handbrake_input': False, + 'left_eye_openness': 0.81641685962677, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94454956, -0.32662964, -0.03343201]), + 'left_gaze_origin': array([-3.12027454e+00, 3.43289185e+00, 4.80651885e-04]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.95953369140625, + 'left_pupil_posn': array([-0.25086564, -0.1554575 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.94187927, -0.33277893, -0.04582214]), + 'right_gaze_origin': array([-3.2077198 , -2.9302156 , -0.02596436]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1438751220703125, + 'right_pupil_posn': array([-0.29304469, -0.2259717 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2900845408439636, + 'throttle_input': 0.0, + 'timestamp': 495.83089566603303, + 'timestamp_carla': 495831, + 'timestamp_device': 4234046, + 'timestamp_stream': 495.83089566603303, + 'transform': [array([ 0.23799011, -8.64391327, 0.01004042]), + array([ 0.01320275, -5.9371829 , 0.02548217])]} +{'AngularVelocity': array([ 0.00113729, 0.05888927, -0.0420086 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.021547775715589523, + 'FR_Wheel_Angle': -0.021653950214385986, + 'Location': array([ -3.64914918, -21.60474014, 0.17364559]), + 'Rotation': array([-0.08136121, 4.7844348 , -0.01626587]), + 'Velocity': array([-0.58648795, -0.04865059, 0.00127385]), + 'brake_input': 0.0, + 'camera_location': array([-6.7319212 , 10.63925457, 2.81551361]), + 'camera_rotation': array([ -4.12876034, -20.53989983, 2.06229925]), + 'current_gear_input': False, + 'focus_actor_dist': 1158.1417236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 572.75842285, -1347.18383789, 16.01341248]), + 'frame': 15160, + 'frame_number': 15160, + 'framesequence': 58219, + 'gaze_dir': array([ 0.94563293, -0.32137299, -0.04956055]), + 'gaze_origin': array([-3.16145134, 0.23848954, -0.02114258]), + 'gaze_valid': True, + 'gaze_vergence': 347.9741516113281, + 'handbrake_input': False, + 'left_eye_openness': 0.8206198215484619, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94645691, -0.31828308, -0.05380249]), + 'left_gaze_origin': array([-3.11901259, 3.42523837, -0.00777435]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9954071044921875, + 'left_pupil_posn': array([-0.24245971, -0.16057599]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.94480896, -0.32446289, -0.0453186 ]), + 'right_gaze_origin': array([-3.20388985, -2.94825912, -0.0345108 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1496734619140625, + 'right_pupil_posn': array([-0.27753907, -0.23841929]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.290359228849411, + 'throttle_input': 0.0, + 'timestamp': 495.86435836553574, + 'timestamp_carla': 495865, + 'timestamp_device': 4234080, + 'timestamp_stream': 495.86435836553574, + 'transform': [array([ 0.43428314, -8.56036091, 0.0089221 ]), + array([ 0.01079853, -6.67139053, 0.02993773])]} +{'AngularVelocity': array([ 0.00906115, -0.04858586, 0.71966028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06970024108886719, + 'FR_Wheel_Angle': 0.06332958489656448, + 'Location': array([ -3.6436913 , -21.60424423, 0.17337073]), + 'Rotation': array([-0.03488177, 4.77419949, -0.01641846]), + 'Velocity': array([ 5.05944014e-01, 4.24803197e-02, -4.65059275e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.70149231, 10.32464314, 2.90921259]), + 'camera_rotation': array([ -3.52167273, -21.49834442, 1.92868972]), + 'current_gear_input': False, + 'focus_actor_dist': 1142.2894287109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 582.42401123, -1364.3137207 , 16.00985718]), + 'frame': 15161, + 'frame_number': 15161, + 'framesequence': 58223, + 'gaze_dir': array([ 0.9532547 , -0.29698944, -0.05532837]), + 'gaze_origin': array([-3.1585176 , 0.22253647, -0.03105011]), + 'gaze_valid': True, + 'gaze_vergence': 402.6389465332031, + 'handbrake_input': False, + 'left_eye_openness': 0.8121907114982605, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95425415, -0.29446411, -0.05174255]), + 'left_gaze_origin': array([-3.11618066, 3.41219187, -0.01792908]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.01263427734375, + 'left_pupil_posn': array([-0.22450823, -0.17114902]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9606146216392517, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95225525, -0.29951477, -0.05891418]), + 'right_gaze_origin': array([-3.20085478, -2.96711898, -0.04417115]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.146820068359375, + 'right_pupil_posn': array([-0.25605017, -0.24322855]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.29369184374809265, + 'throttle_input': 0.0, + 'timestamp': 495.8973908685148, + 'timestamp_carla': 495898, + 'timestamp_device': 4234113, + 'timestamp_stream': 495.8973908685148, + 'transform': [array([ 6.27964020e-01, -8.48179054e+00, 7.91404676e-03]), + array([ 0.00853774, -7.39234591, 0.03393554])]} +{'AngularVelocity': array([-0.00523806, 0.05175243, -0.00028687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.44420958, -21.58759308, 0.17323783]), + 'Rotation': array([-0.04730589, 4.78756666, -0.01629639]), + 'Velocity': array([ 0.91972941, 0.07666375, -0.00096084]), + 'brake_input': 0.0, + 'camera_location': array([-6.69105816, 10.00885296, 2.84872508]), + 'camera_rotation': array([ -3.44496274, -22.40368271, 2.0409255 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.9576416015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 605.76593018, -1339.04882812, 15.97792816]), + 'frame': 15162, + 'frame_number': 15162, + 'framesequence': 58227, + 'gaze_dir': array([ 0.95722198, -0.28520966, -0.0466156 ]), + 'gaze_origin': array([-3.15531778, 0.21459733, -0.02614441]), + 'gaze_valid': True, + 'gaze_vergence': 222.34915161132812, + 'handbrake_input': False, + 'left_eye_openness': 0.8096034526824951, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96118164, -0.27215576, -0.04518127]), + 'left_gaze_origin': array([-3.11439681, 3.40507507, -0.01500855]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0579681396484375, + 'left_pupil_posn': array([-0.21905839, -0.16493583]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9514598250389099, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95326233, -0.29826355, -0.04804993]), + 'right_gaze_origin': array([-3.19623876, -2.97588062, -0.03728028]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09356689453125, + 'right_pupil_posn': array([-0.24195039, -0.23465121]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.29876402020454407, + 'throttle_input': 0.0, + 'timestamp': 495.930674765259, + 'timestamp_carla': 495931, + 'timestamp_device': 4234146, + 'timestamp_stream': 495.930674765259, + 'transform': [array([ 8.23937953e-01, -8.40681267e+00, 6.98465342e-03]), + array([ 6.81652827e-03, -8.11895561e+00, 3.76281738e-02])]} +{'AngularVelocity': array([-0.00582829, 0.06260651, -0.00033643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.22537398, -21.56936073, 0.17311813]), + 'Rotation': array([-0.06444966, 4.78758621, -0.01608276]), + 'Velocity': array([ 0.9208197 , 0.07674875, -0.0011122 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.67492867, 9.73595619, 2.74349427]), + 'camera_rotation': array([ -3.8947854 , -23.32571793, 1.664204 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1287.945556640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 710.59564209, -1256.34375 , 15.84531403]), + 'frame': 15163, + 'frame_number': 15163, + 'framesequence': 58231, + 'gaze_dir': array([ 0.96468353, -0.26055145, -0.03829956]), + 'gaze_origin': array([-3.15058684, 0.20582201, -0.01690521]), + 'gaze_valid': True, + 'gaze_vergence': 807.4192504882812, + 'handbrake_input': False, + 'left_eye_openness': 0.8284420371055603, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96559143, -0.25704956, -0.03919983]), + 'left_gaze_origin': array([-3.10852528, 3.39734077, -0.00462799]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0341339111328125, + 'left_pupil_posn': array([-0.20143813, -0.15198064]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9268680810928345, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96377563, -0.26405334, -0.03739929]), + 'right_gaze_origin': array([-3.19264841, -2.98569655, -0.02918243]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0879669189453125, + 'right_pupil_posn': array([-0.22972709, -0.22584856]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3038727939128876, + 'throttle_input': 0.0, + 'timestamp': 495.9636871665716, + 'timestamp_carla': 495964, + 'timestamp_device': 4234180, + 'timestamp_stream': 495.9636871665716, + 'transform': [array([ 1.01943707e+00, -8.33671284e+00, 6.15186663e-03]), + array([ 5.56660397e-03, -8.84136391e+00, 4.09545787e-02])]} +{'AngularVelocity': array([-0.0018846, 0.0185907, -0.0001771]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.01882482, -21.55214882, 0.17295776]), + 'Rotation': array([-0.07302155, 4.78760481, -0.01599121]), + 'Velocity': array([ 8.40860367e-01, 7.00837150e-02, -7.22246128e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.73884964, 9.47122955, 2.61165857]), + 'camera_rotation': array([ -4.55574942, -24.51996231, 1.09927213]), + 'current_gear_input': False, + 'focus_actor_dist': 1255.5582275390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 692.67919922, -1269.82666016, 15.86772156]), + 'frame': 15164, + 'frame_number': 15164, + 'framesequence': 58235, + 'gaze_dir': array([ 0.96925354, -0.24465179, -0.02523804]), + 'gaze_origin': array([-3.14608335, 0.18817827, -0.00604935]), + 'gaze_valid': True, + 'gaze_vergence': 476.3029479980469, + 'handbrake_input': False, + 'left_eye_openness': 0.8361446857452393, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97080994, -0.23841858, -0.02601624]), + 'left_gaze_origin': array([-3.10385442, 3.37979746, 0.00610199]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1623382568359375, + 'left_pupil_posn': array([-0.1844852 , -0.13905263]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9177420735359192, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96769714, -0.25088501, -0.02445984]), + 'right_gaze_origin': array([-3.18831205, -3.0034411 , -0.01820068]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.173797607421875, + 'right_pupil_posn': array([-0.210567 , -0.21265352]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.31013521552085876, + 'throttle_input': 0.0, + 'timestamp': 495.9969592653215, + 'timestamp_carla': 495997, + 'timestamp_device': 4234213, + 'timestamp_stream': 495.9969592653215, + 'transform': [array([ 1.21794248e+00, -8.27050114e+00, 5.38103096e-03]), + array([ 4.72649047e-03, -9.57288456e+00, 4.40368503e-02])]} +{'AngularVelocity': array([ 8.25735799e-04, 4.29013046e-03, -1.29038513e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.257175445556641, + 'FR_Wheel_Angle': -5.565639019012451, + 'Location': array([ -2.83190751, -21.54100037, 0.17277659]), + 'Rotation': array([-0.07519355, 4.60841942, -0.01101685]), + 'Velocity': array([ 0.76572323, 0.02247744, -0.00097137]), + 'brake_input': 0.0, + 'camera_location': array([-6.82442665, 9.24667931, 2.53523707]), + 'camera_rotation': array([ -5.06593037, -25.79041481, 0.56729442]), + 'current_gear_input': False, + 'focus_actor_dist': 1237.3642578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 696.6831665 , -1286.33496094, 15.86953735]), + 'frame': 15165, + 'frame_number': 15165, + 'framesequence': 58239, + 'gaze_dir': array([ 0.97363281, -0.22702026, -0.01798248]), + 'gaze_origin': array([-3.14304614, 0.16945726, 0.00860062]), + 'gaze_valid': True, + 'gaze_vergence': 243.2627410888672, + 'handbrake_input': False, + 'left_eye_openness': 0.8427839875221252, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97654724, -0.21456909, -0.01731873]), + 'left_gaze_origin': array([-3.09972382, 3.36208057, 0.02469635]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9191436767578125, + 'left_pupil_posn': array([-0.16812134, -0.12339175]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9308714866638184, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97071838, -0.23947144, -0.01864624]), + 'right_gaze_origin': array([-3.18636775, -3.02316594, -0.00749512]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.925689697265625, + 'right_pupil_posn': array([-0.18851298, -0.20143056]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3166356384754181, + 'throttle_input': 0.0, + 'timestamp': 496.0301223658025, + 'timestamp_carla': 496030, + 'timestamp_device': 4234246, + 'timestamp_stream': 496.0301223658025, + 'transform': [array([ 1.41741693e+00, -8.20903778e+00, 4.67313733e-03]), + array([ 4.15275479e-03, -1.03063631e+01, 4.68749963e-02])]} +{'AngularVelocity': array([ 1.24571770e-02, 7.28612940e-04, -1.84372687e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.389118194580078, + 'FR_Wheel_Angle': -7.92324161529541, + 'Location': array([ -2.66275144, -21.53743362, 0.17261364]), + 'Rotation': array([-0.07546676, 4.21558523, -0.01150513]), + 'Velocity': array([ 0.6959095 , -0.00515288, -0.00075936]), + 'brake_input': 0.0, + 'camera_location': array([-6.84745789, 9.06524372, 2.52242994]), + 'camera_rotation': array([ -5.00372791, -26.79933167, 0.10586986]), + 'current_gear_input': False, + 'focus_actor_dist': 1185.3350830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 674.76055908, -1325.42114258, 15.90493011]), + 'frame': 15166, + 'frame_number': 15166, + 'framesequence': 58243, + 'gaze_dir': array([ 0.95844269, -0.28329468, -0.02935028]), + 'gaze_origin': array([-3.14994907, 0.20489502, 0.00971375]), + 'gaze_valid': True, + 'gaze_vergence': 191.40615844726562, + 'handbrake_input': False, + 'left_eye_openness': 0.837089478969574, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96287537, -0.26864624, -0.02598572]), + 'left_gaze_origin': array([-3.10780191, 3.39731908, 0.02519989]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0603790283203125, + 'left_pupil_posn': array([-0.21312684, -0.13083434]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9175283312797546, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95401001, -0.29794312, -0.03271484]), + 'right_gaze_origin': array([-3.19209623, -2.98752904, -0.0057724 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.995147705078125, + 'right_pupil_posn': array([-0.23221093, -0.20518124]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.32320934534072876, + 'throttle_input': 0.0, + 'timestamp': 496.0655326656997, + 'timestamp_carla': 496066, + 'timestamp_device': 4234280, + 'timestamp_stream': 496.0655326656997, + 'transform': [array([ 1.63214540e+00, -8.14847279e+00, 3.95202637e-03]), + array([ 3.64732090e-03, -1.10944033e+01, 4.96826023e-02])]} +{'AngularVelocity': array([ 1.14707109e-02, 1.22846584e-04, -1.70389736e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.650991439819336, + 'FR_Wheel_Angle': -7.87307071685791, + 'Location': array([ -2.52883148, -21.53705978, 0.17246254]), + 'Rotation': array([-0.07528234, 3.84359908, -0.01376343]), + 'Velocity': array([ 0.6407631 , -0.01065342, -0.00114302]), + 'brake_input': 0.0, + 'camera_location': array([-6.82584286, 8.90137672, 2.62555408]), + 'camera_rotation': array([ -4.42139292, -27.63794327, -0.16301428]), + 'current_gear_input': False, + 'focus_actor_dist': 1072.4827880859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 653.01623535, -1464.01538086, 15.9749527 ]), + 'frame': 15167, + 'frame_number': 15167, + 'framesequence': 58247, + 'gaze_dir': array([ 0.94566345, -0.3237915 , -0.02864838]), + 'gaze_origin': array([-3.16256499, 0.2412346 , -0.0101326 ]), + 'gaze_valid': True, + 'gaze_vergence': 460.6150817871094, + 'handbrake_input': False, + 'left_eye_openness': 0.8079350590705872, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94743347, -0.31842041, -0.03094482]), + 'left_gaze_origin': array([-3.11994648e+00, 3.42710137e+00, 1.50756841e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0014190673828125, + 'left_pupil_posn': array([-0.24543929, -0.14778316]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9969159960746765, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.94389343, -0.3291626 , -0.02635193]), + 'right_gaze_origin': array([-3.20518351, -2.94463205, -0.02177277]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.06707763671875, + 'right_pupil_posn': array([-0.27997726, -0.22154891]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.33135777711868286, + 'throttle_input': 0.0, + 'timestamp': 496.09775176644325, + 'timestamp_carla': 496098, + 'timestamp_device': 4234313, + 'timestamp_stream': 496.09775176644325, + 'transform': [array([ 1.82929289e+00, -8.09800053e+00, 3.37230670e-03]), + array([ 3.44924536e-03, -1.18171034e+01, 5.20629697e-02])]} +{'AngularVelocity': array([ 6.05590083e-03, -1.05797313e-03, -1.20534611e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.698764324188232, + 'FR_Wheel_Angle': -5.891770839691162, + 'Location': array([ -2.36827087, -21.53682899, 0.17231998]), + 'Rotation': array([-0.0748657 , 3.43594432, -0.01623535]), + 'Velocity': array([ 5.76216578e-01, -3.21855652e-03, -3.41448787e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.79707956, 8.73454571, 2.74546409]), + 'camera_rotation': array([ -3.91203165, -28.57434273, -0.26236147]), + 'current_gear_input': False, + 'focus_actor_dist': 1177.79150390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 789.04846191, -1458.66027832, 15.83853912]), + 'frame': 15168, + 'frame_number': 15168, + 'framesequence': 58250, + 'gaze_dir': array([ 0.94941711, -0.31228638, -0.0293808 ]), + 'gaze_origin': array([-3.16154957, 0.2320862 , -0.01899643]), + 'gaze_valid': True, + 'gaze_vergence': 156.8694610595703, + 'handbrake_input': False, + 'left_eye_openness': 0.8176058530807495, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95292664, -0.30253601, -0.01976013]), + 'left_gaze_origin': array([-3.1184268, 3.4198184, -0.0053421]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.999755859375, + 'left_pupil_posn': array([-0.23791915, -0.15641463]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9918739795684814, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.94590759, -0.32203674, -0.03900146]), + 'right_gaze_origin': array([-3.20467234, -2.9556458 , -0.03265076]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9194793701171875, + 'right_pupil_posn': array([-0.26687121, -0.22448313]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3400189280509949, + 'throttle_input': 0.0, + 'timestamp': 496.12476136535406, + 'timestamp_carla': 496125, + 'timestamp_device': 4234338, + 'timestamp_stream': 496.12476136535406, + 'transform': [array([ 1.99632514e+00, -8.05934906e+00, 2.88076396e-03]), + array([ 3.57218878e-03, -1.24292278e+01, 5.39855808e-02])]} +{'AngularVelocity': array([-0.00972323, -0.00530465, -0.07171755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.5805814266204834, + 'FR_Wheel_Angle': -2.9716601371765137, + 'Location': array([ -2.29335666, -21.53577995, 0.17234501]), + 'Rotation': array([-0.09310913, 3.3014822 , -0.01965331]), + 'Velocity': array([ 0.06304681, 0.00138663, -0.00023983]), + 'brake_input': 0.0, + 'camera_location': array([-6.88382339, 8.65369987, 2.67372632]), + 'camera_rotation': array([ -4.13423109, -29.55375862, -0.63451523]), + 'current_gear_input': False, + 'focus_actor_dist': 1263.4434814453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 876.61572266, -1420.55688477, 15.73863983]), + 'frame': 15169, + 'frame_number': 15169, + 'framesequence': 58254, + 'gaze_dir': array([ 0.95292664, -0.30199432, -0.02593994]), + 'gaze_origin': array([-3.1565218 , 0.22095719, -0.00692673]), + 'gaze_valid': True, + 'gaze_vergence': 350.97412109375, + 'handbrake_input': False, + 'left_eye_openness': 0.8154632449150085, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95466614, -0.296875 , -0.02172852]), + 'left_gaze_origin': array([-3.11297774, 3.41120028, 0.00994873]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.019378662109375, + 'left_pupil_posn': array([-0.22634107, -0.14139676]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9588263630867004, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95118713, -0.30711365, -0.03015137]), + 'right_gaze_origin': array([-3.20006561, -2.96928573, -0.02380219]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.997467041015625, + 'right_pupil_posn': array([-0.25529313, -0.21805227]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3487899601459503, + 'throttle_input': 0.0, + 'timestamp': 496.15769496560097, + 'timestamp_carla': 496158, + 'timestamp_device': 4234371, + 'timestamp_stream': 496.15769496560097, + 'transform': [array([ 2.20243120e+00, -8.01688004e+00, 2.34012608e-03]), + array([ 4.02298104e-03, -1.31847992e+01, 5.62438779e-02])]} +{'AngularVelocity': array([-0.00364471, -0.04682535, 1.26035953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.9761486053466797, + 'FR_Wheel_Angle': 1.1623318195343018, + 'Location': array([ -2.28755689, -21.53553009, 0.1722665 ]), + 'Rotation': array([-0.08038449, 3.2988534 , -0.01678467]), + 'Velocity': array([ 0.01230555, 0.00126686, -0.00012046]), + 'brake_input': 0.0, + 'camera_location': array([-7.07261944, 8.66899395, 2.67387319]), + 'camera_rotation': array([ -4.28051329, -30.06682587, -0.55362749]), + 'current_gear_input': False, + 'focus_actor_dist': 1231.8759765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 863.32806396, -1446.76647949, 15.76092529]), + 'frame': 15170, + 'frame_number': 15170, + 'framesequence': 58258, + 'gaze_dir': array([ 0.95690155, -0.28915405, -0.02629089]), + 'gaze_origin': array([-3.15471506, 0.2150055 , -0.00911026]), + 'gaze_valid': True, + 'gaze_vergence': 434.9012756347656, + 'handbrake_input': False, + 'left_eye_openness': 0.8159517645835876, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95770264, -0.2868042 , -0.02293396]), + 'left_gaze_origin': array([-3.11105514, 3.40475631, 0.0067688 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9289398193359375, + 'left_pupil_posn': array([-0.21630555, -0.14260602]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9454595446586609, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95610046, -0.29150391, -0.02964783]), + 'right_gaze_origin': array([-3.19837523, -2.97474527, -0.02498932]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9697113037109375, + 'right_pupil_posn': array([-0.24794805, -0.21873546]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3605273962020874, + 'throttle_input': 0.0, + 'timestamp': 496.1912802681327, + 'timestamp_carla': 496192, + 'timestamp_device': 4234405, + 'timestamp_stream': 496.1912802681327, + 'transform': [array([ 2.41568804e+00, -7.97911739e+00, 1.81013101e-03]), + array([ 4.77430178e-03, -1.39673738e+01, 5.84411435e-02])]} +{'AngularVelocity': array([-1.31200986e-05, -1.62929576e-02, 1.19750023e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.255927324295044, + 'FR_Wheel_Angle': 1.498258113861084, + 'Location': array([ -2.28567934, -21.5353756 , 0.1722327 ]), + 'Rotation': array([-0.07464714, 3.29899549, -0.01568603]), + 'Velocity': array([0.00663652, 0.00076081, 0.00030082]), + 'brake_input': 0.0, + 'camera_location': array([-7.10734272, 8.61099529, 2.70527625]), + 'camera_rotation': array([ -3.72166753, -30.28910446, -0.34394073]), + 'current_gear_input': False, + 'focus_actor_dist': 1200.6749267578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 845.46875 , -1462.26147461, 15.78401947]), + 'frame': 15171, + 'frame_number': 15171, + 'framesequence': 58262, + 'gaze_dir': array([ 0.9598465 , -0.27941895, -0.02398682]), + 'gaze_origin': array([-3.15411377, 0.20692064, -0.01485977]), + 'gaze_valid': True, + 'gaze_vergence': 405.2312927246094, + 'handbrake_input': False, + 'left_eye_openness': 0.8307151198387146, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96136475, -0.27450562, -0.02044678]), + 'left_gaze_origin': array([-3.11085820e+00, 3.39808345e+00, 1.19018558e-04]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.069061279296875, + 'left_pupil_posn': array([-0.20906752, -0.14632845]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.930551290512085, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95832825, -0.28433228, -0.02752686]), + 'right_gaze_origin': array([-3.19736934, -2.98424244, -0.02983856]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9449920654296875, + 'right_pupil_posn': array([-0.237068 , -0.2207365]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3731437027454376, + 'throttle_input': 0.0, + 'timestamp': 496.22515626624227, + 'timestamp_carla': 496226, + 'timestamp_device': 4234438, + 'timestamp_stream': 496.22515626624227, + 'transform': [array([ 2.63427830e+00, -7.94699669e+00, 1.28904334e-03]), + array([ 5.77150937e-03, -1.47709389e+01, 6.06078953e-02])]} +{'AngularVelocity': array([ 9.17076250e-04, -3.47007671e-03, 1.20320570e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.03615665435791, + 'FR_Wheel_Angle': 6.125274658203125, + 'Location': array([ -2.28492379, -21.53529167, 0.17222393]), + 'Rotation': array([-0.07275517, 3.29866838, -0.01525879]), + 'Velocity': array([-0.00076325, 0.00011811, 0.00013867]), + 'brake_input': 0.0, + 'camera_location': array([-7.19026804, 8.61492825, 2.67887211]), + 'camera_rotation': array([ -3.73803949, -30.44194984, -0.82094717]), + 'current_gear_input': False, + 'focus_actor_dist': 1372.0172119140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1003.77478027, -1375.53344727, 15.5970993 ]), + 'frame': 15172, + 'frame_number': 15172, + 'framesequence': 58267, + 'gaze_dir': array([ 0.96011353, -0.27812195, -0.02790833]), + 'gaze_origin': array([-3.15256596, 0.20580673, -0.01018601]), + 'gaze_valid': True, + 'gaze_vergence': 362.454833984375, + 'handbrake_input': False, + 'left_eye_openness': 0.8244153261184692, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96098328, -0.27552795, -0.0239563 ]), + 'left_gaze_origin': array([-3.108922 , 3.39625096, 0.00520935]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9478302001953125, + 'left_pupil_posn': array([-0.2065866, -0.1437552]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9375686645507812, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95924377, -0.28071594, -0.03186035]), + 'right_gaze_origin': array([-3.19621015, -2.9846375 , -0.02558136]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9290771484375, + 'right_pupil_posn': array([-0.23711705, -0.21884036]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3861812651157379, + 'throttle_input': 0.0, + 'timestamp': 496.2595233656466, + 'timestamp_carla': 496260, + 'timestamp_device': 4234480, + 'timestamp_stream': 496.2595233656466, + 'transform': [array([ 2.85964155e+00, -7.92073107e+00, 7.79590569e-04]), + array([ 6.88483007e-03, -1.56013384e+01, 6.27136081e-02])]} +{'AngularVelocity': array([-0.02307929, 0.07200768, 0.39454693]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.996980667114258, + 'FR_Wheel_Angle': 11.821972846984863, + 'Location': array([ -2.29055357, -21.53594589, 0.17222816]), + 'Rotation': array([-0.07595853, 3.2726686 , -0.01370239]), + 'Velocity': array([-0.11743743, -0.01778277, 0.00064458]), + 'brake_input': 0.0, + 'camera_location': array([-7.28161573, 8.62955952, 2.67263389]), + 'camera_rotation': array([ -3.8802166 , -30.33680534, -1.01573837]), + 'current_gear_input': False, + 'focus_actor_dist': 1276.80810546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 934.26794434, -1430.20739746, 15.68496704]), + 'frame': 15173, + 'frame_number': 15173, + 'framesequence': 58270, + 'gaze_dir': array([ 0.9603653 , -0.27685547, -0.03192902]), + 'gaze_origin': array([-3.15149307, 0.20472947, -0.00572357]), + 'gaze_valid': True, + 'gaze_vergence': 644.8121337890625, + 'handbrake_input': False, + 'left_eye_openness': 0.8283017873764038, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96131897, -0.27380371, -0.0296936 ]), + 'left_gaze_origin': array([-3.10782313, 3.39438009, 0.0100708 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8811492919921875, + 'left_pupil_posn': array([-0.20502985, -0.14094913]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9168887734413147, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95941162, -0.27990723, -0.03416443]), + 'right_gaze_origin': array([-3.19516325, -2.98492146, -0.02151795]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.95355224609375, + 'right_pupil_posn': array([-0.23621905, -0.21788633]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4006287157535553, + 'throttle_input': 0.0, + 'timestamp': 496.29217806831, + 'timestamp_carla': 496293, + 'timestamp_device': 4234505, + 'timestamp_stream': 496.29217806831, + 'transform': [array([ 3.07729387e+00, -7.90192127e+00, 3.23581684e-04]), + array([ 8.07328336e-03, -1.64057312e+01, 6.46667331e-02])]} +{'AngularVelocity': array([ 0.00590955, 0.03481207, -1.99738288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.700573921203613, + 'FR_Wheel_Angle': 16.344928741455078, + 'Location': array([ -2.32511997, -21.54130173, 0.17231044]), + 'Rotation': array([-0.08181883, 3.08824539, -0.01031494]), + 'Velocity': array([-2.89115041e-01, -5.40938526e-02, 6.83593753e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.29213953, 8.67348766, 2.71438384]), + 'camera_rotation': array([ -3.5898037 , -30.1160202 , -1.45073259]), + 'current_gear_input': False, + 'focus_actor_dist': 1184.56689453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 863.74371338, -1477.21691895, 15.77118683]), + 'frame': 15174, + 'frame_number': 15174, + 'framesequence': 58274, + 'gaze_dir': array([ 0.9600296 , -0.27796173, -0.03134918]), + 'gaze_origin': array([-3.15195465, 0.20741349, -0.00540848]), + 'gaze_valid': True, + 'gaze_vergence': 318.7326354980469, + 'handbrake_input': False, + 'left_eye_openness': 0.8225361704826355, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96237183, -0.27026367, -0.027771 ]), + 'left_gaze_origin': array([-3.10856342, 3.39768076, 0.01198731]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.941497802734375, + 'left_pupil_posn': array([-0.20922494, -0.14032185]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9191187024116516, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95768738, -0.28565979, -0.03492737]), + 'right_gaze_origin': array([-3.19534612, -2.98285389, -0.02280426]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9409942626953125, + 'right_pupil_posn': array([-0.23644972, -0.21798265]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4133000075817108, + 'throttle_input': 0.0, + 'timestamp': 496.3249309659004, + 'timestamp_carla': 496325, + 'timestamp_device': 4234538, + 'timestamp_stream': 496.3249309659004, + 'transform': [array([ 3.29877186e+00, -7.88914919e+00, -1.28192900e-04]), + array([ 9.13879275e-03, -1.72268524e+01, 6.65588379e-02])]} +{'AngularVelocity': array([ 6.70761988e-02, 2.80366838e-03, -2.85084581e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.983954429626465, + 'FR_Wheel_Angle': 19.039152145385742, + 'Location': array([ -2.41210055, -21.55723763, 0.17241669]), + 'Rotation': array([-0.08471483, 2.60871673, -0.00701904]), + 'Velocity': array([-5.05338252e-01, -1.06847577e-01, 2.86035531e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.3232336 , 8.71110725, 2.80365944]), + 'camera_rotation': array([ -3.25053477, -29.84018326, -1.60188353]), + 'current_gear_input': False, + 'focus_actor_dist': 1224.9033203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 910.15625 , -1461.57006836, 15.71979523]), + 'frame': 15175, + 'frame_number': 15175, + 'framesequence': 58279, + 'gaze_dir': array([ 0.95889282, -0.28220367, -0.02857971]), + 'gaze_origin': array([-3.1538372 , 0.20688631, -0.01276398]), + 'gaze_valid': True, + 'gaze_vergence': 333.5222473144531, + 'handbrake_input': False, + 'left_eye_openness': 0.8143812417984009, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96032715, -0.27778625, -0.02398682]), + 'left_gaze_origin': array([-3.11051822e+00, 3.39739108e+00, 1.71356206e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0243072509765625, + 'left_pupil_posn': array([-0.20943558, -0.1471777 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9150214791297913, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9574585 , -0.28662109, -0.03317261]), + 'right_gaze_origin': array([-3.19715595, -2.98361826, -0.02724152]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.90704345703125, + 'right_pupil_posn': array([-0.2387132 , -0.22015095]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4244880676269531, + 'throttle_input': 0.0, + 'timestamp': 496.3637472651899, + 'timestamp_carla': 496364, + 'timestamp_device': 4234580, + 'timestamp_stream': 496.3637472651899, + 'transform': [array([ 3.56412673e+00, -7.88160849e+00, -7.09190324e-04]), + array([ 9.68520809e-03, -1.82137947e+01, 6.86645508e-02])]} +{'AngularVelocity': array([ 0.02581037, -0.02880651, -2.89497161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.29884147644043, + 'FR_Wheel_Angle': 19.250038146972656, + 'Location': array([ -2.52870011, -21.57931328, 0.17249034]), + 'Rotation': array([-0.07598585, 1.88530815, -0.01254272]), + 'Velocity': array([-0.49825206, -0.10825683, 0.00086232]), + 'brake_input': 0.0, + 'camera_location': array([-7.38729048, 8.73841286, 2.83811593]), + 'camera_rotation': array([ -3.1949985 , -29.62783623, -1.66668272]), + 'current_gear_input': False, + 'focus_actor_dist': 1329.0792236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1015.86645508, -1421.48352051, 15.60124207]), + 'frame': 15176, + 'frame_number': 15176, + 'framesequence': 58283, + 'gaze_dir': array([ 0.95819092, -0.28362274, -0.03607178]), + 'gaze_origin': array([-3.15283394, 0.20654528, -0.00980606]), + 'gaze_valid': True, + 'gaze_vergence': 121.53208923339844, + 'handbrake_input': False, + 'left_eye_openness': 0.8267514109611511, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95977783, -0.27946472, -0.02651978]), + 'left_gaze_origin': array([-3.10876918, 3.39680958, 0.00753326]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9314117431640625, + 'left_pupil_posn': array([-0.20948106, -0.14719009]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8888968825340271, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.956604 , -0.28778076, -0.04562378]), + 'right_gaze_origin': array([-3.19689798, -2.98371887, -0.02714539]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9842071533203125, + 'right_pupil_posn': array([-0.23919755, -0.22105348]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4369579255580902, + 'throttle_input': 0.0, + 'timestamp': 496.3972236663103, + 'timestamp_carla': 496398, + 'timestamp_device': 4234613, + 'timestamp_stream': 496.3972236663103, + 'transform': [array([ 3.79485488e+00, -7.88149881e+00, -1.13574974e-03]), + array([ 9.89694335e-03, -1.90750313e+01, 7.04040378e-02])]} +{'AngularVelocity': array([ 0.01559051, -0.02733437, -2.61303425]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.285539627075195, + 'FR_Wheel_Angle': 19.22146987915039, + 'Location': array([ -2.64163566, -21.5992527 , 0.17256168]), + 'Rotation': array([-0.070952 , 1.19672978, -0.01547241]), + 'Velocity': array([-4.45941508e-01, -9.15824398e-02, 1.40743257e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.42310762, 8.77823639, 2.80825424]), + 'camera_rotation': array([ -3.32341266, -29.34903717, -2.00287485]), + 'current_gear_input': False, + 'focus_actor_dist': 1235.2723388671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 945.1328125 , -1470.59399414, 15.68836975]), + 'frame': 15177, + 'frame_number': 15177, + 'framesequence': 58287, + 'gaze_dir': array([ 0.95816803, -0.28420258, -0.03327942]), + 'gaze_origin': array([-3.15221167, 0.20614243, -0.00671387]), + 'gaze_valid': True, + 'gaze_vergence': 29.178974151611328, + 'handbrake_input': False, + 'left_eye_openness': 0.8150767683982849, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95835876, -0.28405762, -0.02900696]), + 'left_gaze_origin': array([-3.10837865, 3.39629245, 0.00819855]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9830780029296875, + 'left_pupil_posn': array([-0.20784134, -0.14376664]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9120781421661377, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95797729, -0.28434753, -0.03755188]), + 'right_gaze_origin': array([-3.19604492, -2.98400736, -0.02162628]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9533843994140625, + 'right_pupil_posn': array([-0.240529 , -0.21810305]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.44596701860427856, + 'throttle_input': 0.0, + 'timestamp': 496.430193066597, + 'timestamp_carla': 496431, + 'timestamp_device': 4234646, + 'timestamp_stream': 496.430193066597, + 'transform': [array([ 4.02323008e+00, -7.88703966e+00, -1.50199886e-03]), + array([ 1.00813583e-02, -1.99303589e+01, 7.18383566e-02])]} +{'AngularVelocity': array([-0.00597798, -0.00881449, -2.45490527]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.304655075073242, + 'FR_Wheel_Angle': 19.249902725219727, + 'Location': array([ -2.73896742, -21.61528587, 0.17265633]), + 'Rotation': array([-0.06860241, 0.59764588, -0.01626587]), + 'Velocity': array([-3.80340308e-01, -7.50115141e-02, 2.23884577e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.44122696, 8.79657555, 2.79568672]), + 'camera_rotation': array([ -3.40285468, -29.01134682, -2.21361613]), + 'current_gear_input': False, + 'focus_actor_dist': 1222.0390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 943.51177979, -1480.09277344, 15.6933136 ]), + 'frame': 15178, + 'frame_number': 15178, + 'framesequence': 58291, + 'gaze_dir': array([ 0.95709991, -0.28646088, -0.04175568]), + 'gaze_origin': array([-3.15150237e+00, 2.08447263e-01, -9.33837960e-04]), + 'gaze_valid': True, + 'gaze_vergence': 18.27520179748535, + 'handbrake_input': False, + 'left_eye_openness': 0.8228003978729248, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95735168, -0.28729248, -0.03018188]), + 'left_gaze_origin': array([-3.10723901, 3.39978337, 0.01496277]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9160919189453125, + 'left_pupil_posn': array([-0.21074277, -0.1444248 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.908954918384552, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95684814, -0.28562927, -0.05332947]), + 'right_gaze_origin': array([-3.19576597, -2.98288894, -0.01683045]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.883758544921875, + 'right_pupil_posn': array([-0.2425139 , -0.21509719]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4536576569080353, + 'throttle_input': 0.0, + 'timestamp': 496.46477576717734, + 'timestamp_carla': 496465, + 'timestamp_device': 4234680, + 'timestamp_stream': 496.46477576717734, + 'transform': [array([ 4.26308537e+00, -7.89850092e+00, -1.83691026e-03]), + array([ 1.01223402e-02, -2.08315849e+01, 7.29980394e-02])]} +{'AngularVelocity': array([ 0.03388732, -0.02560806, -1.80335152]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.32117462158203, + 'FR_Wheel_Angle': 19.274158477783203, + 'Location': array([ -2.81758451, -21.62750435, 0.17272854]), + 'Rotation': array([-0.06725687, 0.11708721, -0.01638794]), + 'Velocity': array([-0.27964428, -0.05129706, 0.00062605]), + 'brake_input': 0.0, + 'camera_location': array([-7.47454596, 8.81946564, 2.75943184]), + 'camera_rotation': array([ -3.72563577, -28.77842331, -2.50551701]), + 'current_gear_input': False, + 'focus_actor_dist': 1100.4967041015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 842.83282471, -1535.44726562, 15.81224823]), + 'frame': 15179, + 'frame_number': 15179, + 'framesequence': 58295, + 'gaze_dir': array([ 0.95718384, -0.28735352, -0.03445435]), + 'gaze_origin': array([-3.15027308, 0.20418702, 0.00544357]), + 'gaze_valid': True, + 'gaze_vergence': 64.5887451171875, + 'handbrake_input': False, + 'left_eye_openness': 0.8149920701980591, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95747375, -0.28694153, -0.02983093]), + 'left_gaze_origin': array([-3.10657501, 3.39484096, 0.02028809]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.96917724609375, + 'left_pupil_posn': array([-0.20789748, -0.13584089]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8959357738494873, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95689392, -0.2877655 , -0.03907776]), + 'right_gaze_origin': array([-3.19397163, -2.98646712, -0.00940094]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.79638671875, + 'right_pupil_posn': array([-0.23977655, -0.20956039]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.46224555373191833, + 'throttle_input': 0.0, + 'timestamp': 496.497161667794, + 'timestamp_carla': 496498, + 'timestamp_device': 4234713, + 'timestamp_stream': 496.497161667794, + 'transform': [array([ 4.48775911e+00, -7.91438341e+00, -2.09915149e-03]), + array([ 1.01155099e-02, -2.16788502e+01, 7.39135593e-02])]} +{'AngularVelocity': array([-0.05059241, 0.07540708, -1.70352972]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.31841468811035, + 'FR_Wheel_Angle': 19.259286880493164, + 'Location': array([ -2.8773849 , -21.63635445, 0.17280659]), + 'Rotation': array([-0.06878683, -0.24441524, -0.01504517]), + 'Velocity': array([-0.28297764, -0.04970972, 0.00049401]), + 'brake_input': 0.0, + 'camera_location': array([-7.5100379 , 8.79871464, 2.7381444 ]), + 'camera_rotation': array([ -3.84000731, -28.60775757, -2.55959225]), + 'current_gear_input': False, + 'focus_actor_dist': 1104.6055908203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 857.42297363, -1538.68310547, 15.79896545]), + 'frame': 15180, + 'frame_number': 15180, + 'framesequence': 58299, + 'gaze_dir': array([ 0.95698547, -0.28791046, -0.03564453]), + 'gaze_origin': array([-3.1499002 , 0.19924089, 0.00474854]), + 'gaze_valid': True, + 'gaze_vergence': 142.4797821044922, + 'handbrake_input': False, + 'left_eye_openness': 0.812830924987793, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95671082, -0.28840637, -0.03900146]), + 'left_gaze_origin': array([-3.1065371 , 3.39116669, 0.0210022 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9593963623046875, + 'left_pupil_posn': array([-0.20529574, -0.13289499]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8873230814933777, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95726013, -0.28741455, -0.0322876 ]), + 'right_gaze_origin': array([-3.19326329, -2.99268508, -0.01150513]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.865142822265625, + 'right_pupil_posn': array([-0.23603553, -0.21423137]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4701925814151764, + 'throttle_input': 0.0, + 'timestamp': 496.5293240658939, + 'timestamp_carla': 496530, + 'timestamp_device': 4234746, + 'timestamp_stream': 496.5293240658939, + 'transform': [array([ 4.71079874e+00, -7.93507814e+00, -2.34695431e-03]), + array([ 1.01018492e-02, -2.25232143e+01, 7.47375339e-02])]} +{'AngularVelocity': array([ 0.02238886, -0.03772246, -0.53513676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.32809829711914, + 'FR_Wheel_Angle': 19.288131713867188, + 'Location': array([ -2.96195984, -21.64804077, 0.17290542]), + 'Rotation': array([-0.07043291, -0.75482184, -0.01403809]), + 'Velocity': array([-0.2688019 , -0.04580815, 0.00066956]), + 'brake_input': 0.0, + 'camera_location': array([-7.48133612, 8.81093597, 2.73599815]), + 'camera_rotation': array([ -3.86738276, -28.33952522, -2.91947198]), + 'current_gear_input': False, + 'focus_actor_dist': 1071.2215576171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 836.8449707 , -1557.31640625, 15.82584381]), + 'frame': 15181, + 'frame_number': 15181, + 'framesequence': 58303, + 'gaze_dir': array([ 0.95947266, -0.27885437, -0.03896332]), + 'gaze_origin': array([-3.14833212, 0.19221498, 0.00543213]), + 'gaze_valid': True, + 'gaze_vergence': 30.654918670654297, + 'handbrake_input': False, + 'left_eye_openness': 0.8045153021812439, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95874023, -0.27987671, -0.04954529]), + 'left_gaze_origin': array([-3.10527515, 3.38482809, 0.02262421]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9933624267578125, + 'left_pupil_posn': array([-0.19751543, -0.12993562]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.878704845905304, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96020508, -0.27783203, -0.02838135]), + 'right_gaze_origin': array([-3.19138956, -3.0003984 , -0.01175995]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.902587890625, + 'right_pupil_posn': array([-0.22756088, -0.2178036 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4783410131931305, + 'throttle_input': 0.0, + 'timestamp': 496.5630000680685, + 'timestamp_carla': 496563, + 'timestamp_device': 4234779, + 'timestamp_stream': 496.5630000680685, + 'transform': [array([ 4.94408607e+00, -7.96197605e+00, -2.61497498e-03]), + array([ 1.00813583e-02, -2.34101772e+01, 7.55615085e-02])]} +{'AngularVelocity': array([-0.01202077, 0.00960885, 0.14983407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.357845306396484, + 'FR_Wheel_Angle': 19.309368133544922, + 'Location': array([ -3.00257373, -21.65343285, 0.17291771]), + 'Rotation': array([-0.06652604, -0.99963379, -0.01559448]), + 'Velocity': array([-0.16689335, -0.0285934 , 0.00020702]), + 'brake_input': 0.0, + 'camera_location': array([-7.45596504, 8.83457565, 2.75298429]), + 'camera_rotation': array([ -4.00302362, -27.85309219, -2.91396022]), + 'current_gear_input': False, + 'focus_actor_dist': 1022.9757080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 797.20959473, -1569.7244873 , 15.86937714]), + 'frame': 15182, + 'frame_number': 15182, + 'framesequence': 58307, + 'gaze_dir': array([ 0.97377014, -0.22601318, -0.02445221]), + 'gaze_origin': array([-3.14307261, 0.15283433, 0.00674057]), + 'gaze_valid': True, + 'gaze_vergence': 170.89797973632812, + 'handbrake_input': False, + 'left_eye_openness': 0.8147807717323303, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.974823 , -0.2223053 , -0.01701355]), + 'left_gaze_origin': array([-3.09804845, 3.34377933, 0.02231751]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9217987060546875, + 'left_pupil_posn': array([-0.15237081, -0.12888968]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.869452953338623, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97271729, -0.22972107, -0.03189087]), + 'right_gaze_origin': array([-3.18809676, -3.03811049, -0.00883637]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9001922607421875, + 'right_pupil_posn': array([-0.18133563, -0.20229578]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4853358566761017, + 'throttle_input': 0.0, + 'timestamp': 496.5967590659857, + 'timestamp_carla': 496597, + 'timestamp_device': 4234813, + 'timestamp_stream': 496.5967590659857, + 'transform': [array([ 5.17721176e+00, -7.99403906e+00, -2.87855137e-03]), + array([ 9.93109494e-03, -2.43005028e+01, 7.63549581e-02])]} +{'AngularVelocity': array([ 0.01096889, 0.00156739, -0.92697603]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.732656478881836, + 'FR_Wheel_Angle': 18.265657424926758, + 'Location': array([ -3.03817081, -21.65797806, 0.17296138]), + 'Rotation': array([-0.06915566, -1.23306262, -0.01391602]), + 'Velocity': array([-0.13803138, -0.02074431, 0.00015647]), + 'brake_input': 0.0, + 'camera_location': array([-7.41544199, 8.88081741, 2.75856638]), + 'camera_rotation': array([ -4.10147381, -27.29766655, -3.06351018]), + 'current_gear_input': False, + 'focus_actor_dist': 1159.72314453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 906.59100342, -1459.21276855, 15.72249603]), + 'frame': 15183, + 'frame_number': 15183, + 'framesequence': 58311, + 'gaze_dir': array([ 0.97272491, -0.22970581, -0.03012848]), + 'gaze_origin': array([-3.14088082, 0.15597993, 0.0075592 ]), + 'gaze_valid': True, + 'gaze_vergence': 184.76959228515625, + 'handbrake_input': False, + 'left_eye_openness': 0.8267259001731873, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9744873 , -0.22332764, -0.02191162]), + 'left_gaze_origin': array([-3.09774494, 3.34713912, 0.02461853]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9813079833984375, + 'left_pupil_posn': array([-0.15671378, -0.12987971]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8521603345870972, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97096252, -0.23608398, -0.03834534]), + 'right_gaze_origin': array([-3.18401647, -3.03517938, -0.00950012]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.90472412109375, + 'right_pupil_posn': array([-0.18356127, -0.20392013]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4916532337665558, + 'throttle_input': 0.0, + 'timestamp': 496.6295547671616, + 'timestamp_carla': 496630, + 'timestamp_device': 4234846, + 'timestamp_stream': 496.6295547671616, + 'transform': [array([ 5.40257454e+00, -8.02983761e+00, -3.11342231e-03]), + array([ 9.65788681e-03, -2.51650982e+01, 7.70568699e-02])]} +{'AngularVelocity': array([ 0.00132415, 0.00192293, -0.60102075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.541923522949219, + 'FR_Wheel_Angle': 18.21515464782715, + 'Location': array([ -3.06351519, -21.66094208, 0.17298613]), + 'Rotation': array([-0.06894393, -1.37780774, -0.01376343]), + 'Velocity': array([-8.76104161e-02, -1.25601301e-02, 7.87258105e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.40161943, 8.92759037, 2.7469089 ]), + 'camera_rotation': array([ -4.26567841, -26.77545547, -3.43391776]), + 'current_gear_input': False, + 'focus_actor_dist': 1076.2984619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 840.62402344, -1498.00646973, 15.80132294]), + 'frame': 15184, + 'frame_number': 15184, + 'framesequence': 58315, + 'gaze_dir': array([ 0.97244263, -0.23155212, -0.02523804]), + 'gaze_origin': array([-3.14094496, 0.15780641, 0.01250381]), + 'gaze_valid': True, + 'gaze_vergence': 116.51481628417969, + 'handbrake_input': False, + 'left_eye_openness': 0.8171170353889465, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97341919, -0.22839355, -0.01644897]), + 'left_gaze_origin': array([-3.0974977 , 3.34934115, 0.03003693]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.961456298828125, + 'left_pupil_posn': array([-0.15778184, -0.12449789]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8580083847045898, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97146606, -0.23471069, -0.0340271 ]), + 'right_gaze_origin': array([-3.18439198, -3.03372812, -0.0050293 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.804443359375, + 'right_pupil_posn': array([-0.18643385, -0.19886494]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.49650564789772034, + 'throttle_input': 0.0, + 'timestamp': 496.6629400663078, + 'timestamp_carla': 496663, + 'timestamp_device': 4234879, + 'timestamp_stream': 496.6629400663078, + 'transform': [array([ 5.63038015e+00, -8.07066345e+00, -3.35506443e-03]), + array([ 9.16611310e-03, -2.60429840e+01, 7.77282566e-02])]} +{'AngularVelocity': array([ 0.00163776, 0.00468546, -0.46155801]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.78874683380127, + 'FR_Wheel_Angle': 18.698976516723633, + 'Location': array([ -3.0805788 , -21.66292381, 0.17300087]), + 'Rotation': array([-0.06982502, -1.47644043, -0.01296997]), + 'Velocity': array([-0.0632236 , -0.00887108, -0.00027588]), + 'brake_input': 0.0, + 'camera_location': array([-7.38478279, 8.97611427, 2.70368528]), + 'camera_rotation': array([ -4.4241457 , -26.3381424 , -3.52144694]), + 'current_gear_input': False, + 'focus_actor_dist': 1081.3946533203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 854.0246582 , -1497.20507812, 15.78781128]), + 'frame': 15185, + 'frame_number': 15185, + 'framesequence': 58319, + 'gaze_dir': array([ 0.97254944, -0.23123169, -0.02429962]), + 'gaze_origin': array([-3.14074349, 0.15866472, 0.01378326]), + 'gaze_valid': True, + 'gaze_vergence': 234.6795654296875, + 'handbrake_input': False, + 'left_eye_openness': 0.8024985194206238, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97401428, -0.22573853, -0.01773071]), + 'left_gaze_origin': array([-3.09748244, 3.3500917 , 0.03104401]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.906463623046875, + 'left_pupil_posn': array([-0.15899742, -0.12274754]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.857182502746582, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97108459, -0.23672485, -0.03086853]), + 'right_gaze_origin': array([-3.18400455, -3.03276229, -0.00347748]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8323822021484375, + 'right_pupil_posn': array([-0.18608481, -0.19819927]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5006622672080994, + 'throttle_input': 0.0, + 'timestamp': 496.6960760653019, + 'timestamp_carla': 496696, + 'timestamp_device': 4234913, + 'timestamp_stream': 496.6960760653019, + 'transform': [array([ 5.85445166e+00, -8.11523342e+00, -3.58383171e-03]), + array([ 8.51041544e-03, -2.69103870e+01, 7.83386007e-02])]} +{'AngularVelocity': array([ 0.00266897, 0.00302778, -0.41116184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.16355323791504, + 'FR_Wheel_Angle': 19.0546932220459, + 'Location': array([ -3.09429812, -21.66454315, 0.17300636]), + 'Rotation': array([-0.07073344, -1.55889893, -0.0123291 ]), + 'Velocity': array([-0.05402719, -0.00772687, 0.00019697]), + 'brake_input': 0.0, + 'camera_location': array([-7.36893797, 9.03728104, 2.68288946]), + 'camera_rotation': array([ -4.51808786, -25.96001244, -3.49524021]), + 'current_gear_input': False, + 'focus_actor_dist': 1061.062255859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 843.99859619, -1506.64099121, 15.80104065]), + 'frame': 15186, + 'frame_number': 15186, + 'framesequence': 58323, + 'gaze_dir': array([ 0.97241211, -0.23194122, -0.02336884]), + 'gaze_origin': array([-3.14105225, 0.15907289, 0.01453095]), + 'gaze_valid': True, + 'gaze_vergence': 328.80743408203125, + 'handbrake_input': False, + 'left_eye_openness': 0.7980871796607971, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97384644, -0.22640991, -0.01873779]), + 'left_gaze_origin': array([-3.09771276, 3.3507309 , 0.03150025]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9293212890625, + 'left_pupil_posn': array([-0.15968567, -0.12149119]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8527489900588989, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97097778, -0.23747253, -0.02799988]), + 'right_gaze_origin': array([-3.18439198e+00, -3.03258514e+00, -2.43835454e-03]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8346710205078125, + 'right_pupil_posn': array([-0.18643385, -0.19793701]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5047822594642639, + 'throttle_input': 0.0, + 'timestamp': 496.72956296801567, + 'timestamp_carla': 496730, + 'timestamp_device': 4234946, + 'timestamp_stream': 496.72956296801567, + 'transform': [array([ 6.07866096e+00, -8.16419506e+00, -3.80094512e-03]), + array([ 7.67713226e-03, -2.77824116e+01, 7.88574070e-02])]} +{'AngularVelocity': array([ 0.00415562, 0.00136721, -0.40688795]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.168472290039062, + 'FR_Wheel_Angle': 19.05919075012207, + 'Location': array([ -3.10669398, -21.666008 , 0.17303547]), + 'Rotation': array([-0.07123204, -1.63400245, -0.01193237]), + 'Velocity': array([-0.05269128, -0.00739284, -0.00027554]), + 'brake_input': 0.0, + 'camera_location': array([-7.35172844, 9.10291862, 2.67553616]), + 'camera_rotation': array([ -4.70199776, -25.63070679, -3.3538518 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1055.2828369140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 847.99176025, -1512.00512695, 15.79889679]), + 'frame': 15187, + 'frame_number': 15187, + 'framesequence': 58327, + 'gaze_dir': array([ 0.97107697, -0.23681641, -0.02729034]), + 'gaze_origin': array([-3.14109874, 0.16037141, 0.01710434]), + 'gaze_valid': True, + 'gaze_vergence': 188.23928833007812, + 'handbrake_input': False, + 'left_eye_openness': 0.7851829528808594, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97369385, -0.22703552, -0.01924133]), + 'left_gaze_origin': array([-3.09798288, 3.35297251, 0.03592682]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.951019287109375, + 'left_pupil_posn': array([-0.1643396 , -0.12139356]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8572643995285034, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96846008, -0.24659729, -0.03533936]), + 'right_gaze_origin': array([-3.18421507e+00, -3.03222990e+00, -1.71813974e-03]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8411865234375, + 'right_pupil_posn': array([-0.18687272, -0.19761872]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5083529353141785, + 'throttle_input': 0.0, + 'timestamp': 496.7633574679494, + 'timestamp_carla': 496764, + 'timestamp_device': 4234979, + 'timestamp_stream': 496.7633574679494, + 'transform': [array([ 6.30242825e+00, -8.21738338e+00, -3.99517035e-03]), + array([ 6.57064142e-03, -2.86570091e+01, 7.92236254e-02])]} +{'AngularVelocity': array([-0.0115265 , 0.15847382, -1.53024304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.104713439941406, + 'FR_Wheel_Angle': 18.962797164916992, + 'Location': array([ -3.12854052, -21.66831017, 0.17312145]), + 'Rotation': array([-0.07934631, -1.76544189, -0.00723266]), + 'Velocity': array([-2.90665448e-01, -3.01375724e-02, 2.06947316e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.33180189, 9.19291496, 2.65373015]), + 'camera_rotation': array([ -4.78499126, -25.31624031, -3.42757797]), + 'current_gear_input': False, + 'focus_actor_dist': 997.2188110351562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 805.56207275, -1542.9119873 , 15.85176086]), + 'frame': 15188, + 'frame_number': 15188, + 'framesequence': 58331, + 'gaze_dir': array([ 0.96943665, -0.24353027, -0.02664185]), + 'gaze_origin': array([-3.14113808, 0.16194536, 0.02006607]), + 'gaze_valid': True, + 'gaze_vergence': 234.05723571777344, + 'handbrake_input': False, + 'left_eye_openness': 0.7832689881324768, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9723053, -0.2326355, -0.0218811]), + 'left_gaze_origin': array([-3.09822559, 3.35574675, 0.03949738]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9937744140625, + 'left_pupil_posn': array([-0.1689229 , -0.11785173]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8666579723358154, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96656799, -0.25442505, -0.03140259]), + 'right_gaze_origin': array([-3.18405032e+00, -3.03185606e+00, 6.34765660e-04]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8491973876953125, + 'right_pupil_posn': array([-0.18908012, -0.19702685]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5111362338066101, + 'throttle_input': 0.0, + 'timestamp': 496.79726286605, + 'timestamp_carla': 496798, + 'timestamp_device': 4235013, + 'timestamp_stream': 496.79726286605, + 'transform': [array([ 6.52414894e+00, -8.27428722e+00, -4.16519167e-03]), + array([ 5.34803793e-03, -2.95279274e+01, 7.94677511e-02])]} +{'AngularVelocity': array([-0.04773567, 0.03564254, -3.92786574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.052703857421875, + 'FR_Wheel_Angle': 18.885974884033203, + 'Location': array([ -3.21543241, -21.67746353, 0.17324837]), + 'Rotation': array([-0.08639506, -2.27124047, -0.00280762]), + 'Velocity': array([-0.55221218, -0.07859089, 0.00069064]), + 'brake_input': 0.0, + 'camera_location': array([-7.31533337, 9.2988739 , 2.65130734]), + 'camera_rotation': array([ -4.8578968 , -24.97570801, -3.27732086]), + 'current_gear_input': False, + 'focus_actor_dist': 986.1995849609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 807.02624512, -1556.63244629, 15.85508728]), + 'frame': 15189, + 'frame_number': 15189, + 'framesequence': 58335, + 'gaze_dir': array([ 0.96794128, -0.24889374, -0.02981567]), + 'gaze_origin': array([-3.14131713, 0.16493151, 0.02187653]), + 'gaze_valid': True, + 'gaze_vergence': 180.2238006591797, + 'handbrake_input': False, + 'left_eye_openness': 0.7943155169487, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97155762, -0.23564148, -0.02290344]), + 'left_gaze_origin': array([-3.09875822, 3.36024809, 0.0401535 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.98187255859375, + 'left_pupil_posn': array([-0.1747663 , -0.11950564]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8560256958007812, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96432495, -0.262146 , -0.03672791]), + 'right_gaze_origin': array([-3.18387628, -3.03038478, 0.00359955]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9293975830078125, + 'right_pupil_posn': array([-0.19108164, -0.1954 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5131321549415588, + 'throttle_input': 0.0, + 'timestamp': 496.8303434662521, + 'timestamp_carla': 496831, + 'timestamp_device': 4235046, + 'timestamp_stream': 496.8303434662521, + 'transform': [array([ 6.73752260e+00, -8.33291626e+00, -4.31316346e-03]), + array([ 4.08445299e-03, -3.03701859e+01, 7.96508566e-02])]} +{'AngularVelocity': array([ 0.03636184, 0.01156711, -3.44259262]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.933382034301758, + 'FR_Wheel_Angle': 18.475629806518555, + 'Location': array([ -3.34702253, -21.69068146, 0.17332363]), + 'Rotation': array([-0.07876574, -3.05850267, -0.00714111]), + 'Velocity': array([-0.61191994, -0.07212008, 0.00101774]), + 'brake_input': 0.0, + 'camera_location': array([-7.27579165, 9.39198875, 2.66842985]), + 'camera_rotation': array([ -4.83614254, -24.50456429, -2.99747276]), + 'current_gear_input': False, + 'focus_actor_dist': 955.2322998046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 788.70550537, -1575.81018066, 15.87989044]), + 'frame': 15190, + 'frame_number': 15190, + 'framesequence': 58339, + 'gaze_dir': array([ 0.96339417, -0.26647186, -0.02435303]), + 'gaze_origin': array([-3.14470243, 0.17534715, 0.02199249]), + 'gaze_valid': True, + 'gaze_vergence': 183.4913330078125, + 'handbrake_input': False, + 'left_eye_openness': 0.7852521538734436, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96768188, -0.25134277, -0.02020264]), + 'left_gaze_origin': array([-3.10164499, 3.36703062, 0.03844452]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1317901611328125, + 'left_pupil_posn': array([-0.18625885, -0.118891 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8788644075393677, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95910645, -0.28160095, -0.02850342]), + 'right_gaze_origin': array([-3.18775964, -3.0163362 , 0.00554047]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.962249755859375, + 'right_pupil_posn': array([-0.20622861, -0.1941402 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5141026377677917, + 'throttle_input': 0.0, + 'timestamp': 496.86268166825175, + 'timestamp_carla': 496863, + 'timestamp_device': 4235079, + 'timestamp_stream': 496.86268166825175, + 'transform': [array([ 6.94301128e+00, -8.39287663e+00, -4.44353092e-03]), + array([ 2.79354723e-03, -3.11851540e+01, 7.97729269e-02])]} +{'AngularVelocity': array([ 0.06606711, -0.0355082 , -2.33707547]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.522086143493652, + 'FR_Wheel_Angle': 13.130104064941406, + 'Location': array([ -3.46917391, -21.70012093, 0.17341658]), + 'Rotation': array([-0.07442857, -3.73098803, -0.01159668]), + 'Velocity': array([-5.99237680e-01, -4.70256209e-02, 4.04920575e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.23757362, 9.46016884, 2.7033534 ]), + 'camera_rotation': array([ -4.78677368, -24.10077858, -2.86177993]), + 'current_gear_input': False, + 'focus_actor_dist': 1007.09814453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 851.54644775, -1575.2121582 , 15.81755829]), + 'frame': 15191, + 'frame_number': 15191, + 'framesequence': 58343, + 'gaze_dir': array([ 0.9609375 , -0.27516174, -0.02524567]), + 'gaze_origin': array([-3.14559197, 0.17700501, 0.02021179]), + 'gaze_valid': True, + 'gaze_vergence': 134.3520965576172, + 'handbrake_input': False, + 'left_eye_openness': 0.7745712995529175, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96403503, -0.26541138, -0.01387024]), + 'left_gaze_origin': array([-3.10156274, 3.36877918, 0.03677368]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.200225830078125, + 'left_pupil_posn': array([-0.18858176, -0.12300634]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.857109785079956, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95783997, -0.28491211, -0.03662109]), + 'right_gaze_origin': array([-3.18962121, -3.01476908, 0.0036499 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91766357421875, + 'right_pupil_posn': array([-0.2122128 , -0.19393229]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5142307877540588, + 'throttle_input': 0.0, + 'timestamp': 496.896471966058, + 'timestamp_carla': 496897, + 'timestamp_device': 4235113, + 'timestamp_stream': 496.896471966058, + 'transform': [array([ 7.15417719e+00, -8.45798111e+00, -4.58747847e-03]), + array([ 1.35920756e-03, -3.20264702e+01, 7.98644871e-02])]} +{'AngularVelocity': array([-0.01290547, -0.01323816, -1.19831657]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.411363124847412, + 'FR_Wheel_Angle': 6.110230445861816, + 'Location': array([ -3.6055038 , -21.7031765 , 0.17353858]), + 'Rotation': array([-0.06695634, -4.22943258, -0.01620483]), + 'Velocity': array([-0.45205516, -0.00166805, 0.0016452 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.18096972, 9.53132725, 2.68447804]), + 'camera_rotation': array([ -4.79828262, -23.78316498, -2.96116829]), + 'current_gear_input': False, + 'focus_actor_dist': 1010.0642700195312, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 864.98919678, -1584.6114502 , 15.80756378]), + 'frame': 15192, + 'frame_number': 15192, + 'framesequence': 58347, + 'gaze_dir': array([ 0.96154785, -0.27295685, -0.02335358]), + 'gaze_origin': array([-3.14441323, 0.16964646, 0.02356186]), + 'gaze_valid': True, + 'gaze_vergence': 143.4179229736328, + 'handbrake_input': False, + 'left_eye_openness': 0.7716991305351257, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96636963, -0.25671387, -0.01457214]), + 'left_gaze_origin': array([-3.10017872, 3.36272168, 0.04250946]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1480255126953125, + 'left_pupil_posn': array([-0.18584925, -0.11740768]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8508352637290955, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95672607, -0.28919983, -0.03213501]), + 'right_gaze_origin': array([-3.18864775, -3.02342844, 0.00461426]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2028350830078125, + 'right_pupil_posn': array([-0.20308226, -0.19328773]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5142307877540588, + 'throttle_input': 0.0, + 'timestamp': 496.9290340654552, + 'timestamp_carla': 496929, + 'timestamp_device': 4235146, + 'timestamp_stream': 496.9290340654552, + 'transform': [array([ 7.35416174e+00, -8.52287197e+00, -4.71420260e-03]), + array([ 6.83018879e-06, -3.28269691e+01, 7.99560398e-02])]} +{'AngularVelocity': array([-0.01795076, -0.04745192, 0.64553863]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.2567235231399536, + 'FR_Wheel_Angle': -2.022777795791626, + 'Location': array([ -3.69594812, -21.6985302 , 0.17358398]), + 'Rotation': array([-0.06380762, -4.3454299 , -0.01565552]), + 'Velocity': array([-2.68257111e-01, 2.67091021e-02, 2.24637974e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.13597202, 9.63195896, 2.61289334]), + 'camera_rotation': array([ -5.05983114, -23.30202103, -3.03924322]), + 'current_gear_input': False, + 'focus_actor_dist': 1020.6305541992188, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 882.78991699, -1582.65771484, 15.78926849]), + 'frame': 15193, + 'frame_number': 15193, + 'framesequence': 58351, + 'gaze_dir': array([ 0.99163818, -0.12736511, -0.00442505]), + 'gaze_origin': array([-3.20660734, 0.07167435, 0.0761673 ]), + 'gaze_valid': True, + 'gaze_vergence': 149.6832733154297, + 'handbrake_input': False, + 'left_eye_openness': 0.8354395627975464, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99404907, -0.10888672, 0.00256348]), + 'left_gaze_origin': array([-3.19549108, 3.2676425 , 0.10713654]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1048583984375, + 'left_pupil_posn': array([-0.07148069, -0.08209276]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8745526671409607, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98922729, -0.14584351, -0.01141357]), + 'right_gaze_origin': array([-3.21772313, -3.1242938 , 0.04519806]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.97564697265625, + 'right_pupil_posn': array([-0.08147651, -0.16358709]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5142307877540588, + 'throttle_input': 0.0, + 'timestamp': 496.9634018652141, + 'timestamp_carla': 496964, + 'timestamp_device': 4235179, + 'timestamp_stream': 496.9634018652141, + 'transform': [array([ 7.56146717e+00, -8.59349251e+00, -4.86047752e-03]), + array([-1.34554715e-03, -3.36607704e+01, 8.00475851e-02])]} +{'AngularVelocity': array([-0.01674816, -0.01651542, 0.7881754 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.609274864196777, + 'FR_Wheel_Angle': -5.845779895782471, + 'Location': array([ -3.73982906, -21.69335938, 0.17363784]), + 'Rotation': array([-0.06356857, -4.33187962, -0.01159668]), + 'Velocity': array([-0.15226591, 0.02239885, 0.00051649]), + 'brake_input': 0.0, + 'camera_location': array([-7.10812664, 9.72761822, 2.56708384]), + 'camera_rotation': array([ -5.41532898, -22.73504066, -2.75237727]), + 'current_gear_input': False, + 'focus_actor_dist': 1216.8038330078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1009.23547363, -1355.63842773, 15.5847168 ]), + 'frame': 15194, + 'frame_number': 15194, + 'framesequence': 58355, + 'gaze_dir': array([ 0.99963379, -0.01058197, 0.01735687]), + 'gaze_origin': array([-3.17664266, -0.0279274 , 0.09173585]), + 'gaze_valid': True, + 'gaze_vergence': 182.47091674804688, + 'handbrake_input': False, + 'left_eye_openness': 0.8065896034240723, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99986267, 0.00637817, 0.01451111]), + 'left_gaze_origin': array([-3.1242907 , 3.15758705, 0.10873261]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.121246337890625, + 'left_pupil_posn': array([ 0.04526806, -0.05623436]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.87248694896698, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99940491, -0.02754211, 0.02020264]), + 'right_gaze_origin': array([-3.22899485, -3.21344185, 0.07473908]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0244140625, + 'right_pupil_posn': array([ 0.02031887, -0.14182019]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5141026377677917, + 'throttle_input': 0.0, + 'timestamp': 496.9957653656602, + 'timestamp_carla': 496996, + 'timestamp_device': 4235213, + 'timestamp_stream': 496.9957653656602, + 'transform': [array([ 7.75317955e+00, -8.66186428e+00, -4.97621531e-03]), + array([-2.47252826e-03, -3.44357147e+01, 8.01391304e-02])]} +{'AngularVelocity': array([-0.00783032, -0.0212935 , 0.8981837 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.614983558654785, + 'FR_Wheel_Angle': -8.113248825073242, + 'Location': array([ -3.76901913, -21.68909073, 0.1736661 ]), + 'Rotation': array([-0.06634846, -4.2874155 , -0.0090332 ]), + 'Velocity': array([-0.07427674, 0.01419743, 0.00023234]), + 'brake_input': 0.0, + 'camera_location': array([-7.04882765, 9.82166576, 2.58258462]), + 'camera_rotation': array([ -5.57145309, -22.07331657, -2.39571977]), + 'current_gear_input': False, + 'focus_actor_dist': 1543.06396484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1222.58447266, -1055.15002441, 15.26869202]), + 'frame': 15195, + 'frame_number': 15195, + 'framesequence': 58359, + 'gaze_dir': array([0.99629211, 0.07737732, 0.03307343]), + 'gaze_origin': array([-3.12525487, -0.08978425, 0.08421707]), + 'gaze_valid': True, + 'gaze_vergence': 178.23316955566406, + 'handbrake_input': False, + 'left_eye_openness': 0.8669203519821167, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99501038, 0.09481812, 0.0308075 ]), + 'left_gaze_origin': array([-3.07038593, 3.09430718, 0.09855653]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17755126953125, + 'left_pupil_posn': array([ 0.11835217, -0.04847288]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.920356035232544, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99757385, 0.05993652, 0.03533936]), + 'right_gaze_origin': array([-3.18012428, -3.27387571, 0.06987762]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2210693359375, + 'right_pupil_posn': array([ 0.0916363 , -0.13174593]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5134068131446838, + 'throttle_input': 0.0, + 'timestamp': 497.0294551663101, + 'timestamp_carla': 497030, + 'timestamp_device': 4235246, + 'timestamp_stream': 497.0294551663101, + 'transform': [array([ 7.94903326e+00, -8.73473740e+00, -5.09963976e-03]), + array([-3.57218878e-03, -3.52312050e+01, 8.02001655e-02])]} +{'AngularVelocity': array([-0.0037626 , -0.0237358 , 0.85033345]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.85374641418457, + 'FR_Wheel_Angle': -8.144672393798828, + 'Location': array([ -3.7874701 , -21.68612289, 0.17371804]), + 'Rotation': array([-0.06903272, -4.24850655, -0.00830078]), + 'Velocity': array([-5.12284189e-02, 1.03276800e-02, 9.70172841e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.97738504, 9.92947578, 2.58771586]), + 'camera_rotation': array([ -5.61584282, -21.26506805, -2.24266553]), + 'current_gear_input': False, + 'focus_actor_dist': 1462.8616943359375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([1089.88916016, -991.34039307, 46.34133148]), + 'frame': 15196, + 'frame_number': 15196, + 'framesequence': 58363, + 'gaze_dir': array([0.99559784, 0.08418274, 0.03708649]), + 'gaze_origin': array([-3.10119414, -0.09287949, 0.07860947]), + 'gaze_valid': True, + 'gaze_vergence': 179.6103057861328, + 'handbrake_input': False, + 'left_eye_openness': 0.925593376159668, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99420166, 0.1015625 , 0.03517151]), + 'left_gaze_origin': array([-3.05306268, 3.0931108 , 0.09471894]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.258544921875, + 'left_pupil_posn': array([ 0.12143171, -0.0467056 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9526622891426086, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99699402, 0.06680298, 0.03900146]), + 'right_gaze_origin': array([-3.14932585, -3.27886987, 0.06250001]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.223052978515625, + 'right_pupil_posn': array([ 0.09666646, -0.12971616]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5115939974784851, + 'throttle_input': 0.0, + 'timestamp': 497.06384056806564, + 'timestamp_carla': 497064, + 'timestamp_device': 4235279, + 'timestamp_stream': 497.06384056806564, + 'transform': [array([ 8.14482975e+00, -8.81054020e+00, -5.22878626e-03]), + array([-4.73332079e-03, -3.60302277e+01, 8.02612156e-02])]} +{'AngularVelocity': array([-7.15312199e-04, -2.72569899e-02, 7.65194774e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.008943557739258, + 'FR_Wheel_Angle': -7.342203617095947, + 'Location': array([ -3.80097437, -21.68403244, 0.17374714]), + 'Rotation': array([-0.07000261, -4.21795845, -0.00817871]), + 'Velocity': array([-3.44359428e-02, 7.29111768e-03, 3.45945336e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.92791033, 10.01855087, 2.60227895]), + 'camera_rotation': array([ -5.64304066, -20.55143547, -2.00256538]), + 'current_gear_input': False, + 'focus_actor_dist': 2336.281494140625, + 'focus_actor_name': 'Road_Marking_Town05_140', + 'focus_actor_pt': array([ 1.77402869e+03, -4.38749146e+02, -1.52587891e-05]), + 'frame': 15197, + 'frame_number': 15197, + 'framesequence': 58367, + 'gaze_dir': array([0.99533081, 0.08607483, 0.04091644]), + 'gaze_origin': array([-3.06766582, -0.09337388, 0.06611862]), + 'gaze_valid': True, + 'gaze_vergence': 209.40550231933594, + 'handbrake_input': False, + 'left_eye_openness': 0.9551199674606323, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99404907, 0.10115051, 0.04039001]), + 'left_gaze_origin': array([-3.01438165, 3.09594131, 0.0802887 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.245208740234375, + 'left_pupil_posn': array([ 0.12074316, -0.04849148]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9763618111610413, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99661255, 0.07099915, 0.04144287]), + 'right_gaze_origin': array([-3.12095046, -3.28268886, 0.05194855]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0722808837890625, + 'right_pupil_posn': array([ 0.09846127, -0.12977767]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5085909962654114, + 'throttle_input': 0.0, + 'timestamp': 497.0965551659465, + 'timestamp_carla': 497097, + 'timestamp_device': 4235313, + 'timestamp_stream': 497.0965551659465, + 'transform': [array([ 8.32707787e+00, -8.88361454e+00, -5.33052441e-03]), + array([-5.89445280e-03, -3.67771149e+01, 8.02917406e-02])]} +{'AngularVelocity': array([ 0.00066649, 0.03199645, -0.62085789]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.942373275756836, + 'FR_Wheel_Angle': -5.302030086517334, + 'Location': array([ -3.81142569, -21.68244553, 0.1737437 ]), + 'Rotation': array([-0.07070611, -4.2069416 , -0.00817871]), + 'Velocity': array([-0.05847253, 0.00735905, 0.00017299]), + 'brake_input': 0.0, + 'camera_location': array([-6.88811731, 10.09218216, 2.61673856]), + 'camera_rotation': array([ -5.68208885, -19.91361046, -1.57470083]), + 'current_gear_input': False, + 'focus_actor_dist': 2465.44140625, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 1.88056226e+03, -3.53337280e+02, 1.52587891e-05]), + 'frame': 15198, + 'frame_number': 15198, + 'framesequence': 58371, + 'gaze_dir': array([0.99539185, 0.08439636, 0.04272461]), + 'gaze_origin': array([-3.06575942, -0.09819337, 0.06643677]), + 'gaze_valid': True, + 'gaze_vergence': 206.2875213623047, + 'handbrake_input': False, + 'left_eye_openness': 0.9715290069580078, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99401855, 0.0993042 , 0.04521179]), + 'left_gaze_origin': array([-3.00307941, 3.09326649, 0.0758194 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2922515869140625, + 'left_pupil_posn': array([ 0.12198269, -0.04972279]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.985092282295227, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99676514, 0.06948853, 0.04023743]), + 'right_gaze_origin': array([-3.12843966, -3.28965306, 0.05705414]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1868896484375, + 'right_pupil_posn': array([ 0.10279858, -0.12603331]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5045442581176758, + 'throttle_input': 0.0, + 'timestamp': 497.12932496517897, + 'timestamp_carla': 497130, + 'timestamp_device': 4235346, + 'timestamp_stream': 497.12932496517897, + 'transform': [array([ 8.50545979e+00, -8.95734215e+00, -5.43130841e-03]), + array([-7.17169838e-03, -3.75107880e+01, 8.02917331e-02])]} +{'AngularVelocity': array([-0.00053369, -0.0054144 , 0.22601658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.678950309753418, + 'FR_Wheel_Angle': -5.736608505249023, + 'Location': array([ -3.83973289, -21.67915535, 0.17382045]), + 'Rotation': array([-0.07797343, -4.15619087, -0.00942993]), + 'Velocity': array([-0.20498899, 0.02589637, 0.00032396]), + 'brake_input': 0.0, + 'camera_location': array([-6.83745623, 10.20989323, 2.61769819]), + 'camera_rotation': array([ -5.65766382, -19.12025452, -1.43881857]), + 'current_gear_input': False, + 'focus_actor_dist': 2484.84375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 1.90618665e+03, -3.43645386e+02, 1.52587891e-05]), + 'frame': 15199, + 'frame_number': 15199, + 'framesequence': 58375, + 'gaze_dir': array([0.99585724, 0.08014679, 0.04006195]), + 'gaze_origin': array([-3.05719256, -0.09727326, 0.06253967]), + 'gaze_valid': True, + 'gaze_vergence': 206.43148803710938, + 'handbrake_input': False, + 'left_eye_openness': 0.97303307056427, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99455261, 0.09495544, 0.04283142]), + 'left_gaze_origin': array([-2.98808908, 3.09571075, 0.0694046 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2886810302734375, + 'left_pupil_posn': array([ 0.11883175, -0.05221617]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.986555278301239, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99716187, 0.06533813, 0.03729248]), + 'right_gaze_origin': array([-3.12629557, -3.29025769, 0.05567475]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1859130859375, + 'right_pupil_posn': array([ 0.10164392, -0.12726271]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.49927061796188354, + 'throttle_input': 0.0, + 'timestamp': 497.16512966528535, + 'timestamp_carla': 497165, + 'timestamp_device': 4235379, + 'timestamp_stream': 497.16512966528535, + 'transform': [array([ 8.69534874e+00, -9.03801823e+00, -5.56352595e-03]), + array([-8.70166067e-03, -3.82941818e+01, 8.02612305e-02])]} +{'AngularVelocity': array([-0.01108648, -0.03003905, -0.89105386]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.765924453735352, + 'FR_Wheel_Angle': -8.356636047363281, + 'Location': array([ -3.8815279 , -21.67382812, 0.17381389]), + 'Rotation': array([-0.07046705, -4.06607199, -0.00869751]), + 'Velocity': array([-1.29820436e-01, 1.96255948e-02, 1.24931330e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.78686619, 10.38040447, 2.6120429 ]), + 'camera_rotation': array([ -5.74211264, -18.22332191, -1.68103945]), + 'current_gear_input': False, + 'focus_actor_dist': 1433.2965087890625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([1087.5814209 , -990.83654785, 54.26032257]), + 'frame': 15200, + 'frame_number': 15200, + 'framesequence': 58379, + 'gaze_dir': array([0.99556732, 0.07701111, 0.04975128]), + 'gaze_origin': array([-3.07366562, -0.09162827, 0.07382355]), + 'gaze_valid': True, + 'gaze_vergence': 152.7432403564453, + 'handbrake_input': False, + 'left_eye_openness': 0.9694797992706299, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99409485, 0.09750366, 0.04742432]), + 'left_gaze_origin': array([-3.03854394, 3.10035419, 0.09336853]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21136474609375, + 'left_pupil_posn': array([ 0.11294699, -0.04036391]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.992997944355011, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99703979, 0.05651855, 0.05207825]), + 'right_gaze_origin': array([-3.10878778, -3.28361058, 0.05427857]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09674072265625, + 'right_pupil_posn': array([ 0.09758544, -0.12354052]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.49277016520500183, + 'throttle_input': 0.0, + 'timestamp': 497.1964919678867, + 'timestamp_carla': 497197, + 'timestamp_device': 4235413, + 'timestamp_stream': 497.1964919678867, + 'transform': [array([ 8.85736752e+00, -9.10852146e+00, -5.63131319e-03]), + array([-1.00676985e-02, -3.89643593e+01, 8.02001804e-02])]} +{'AngularVelocity': array([-0.00144235, 0.0028103 , -0.98420608]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.138710021972656, + 'FR_Wheel_Angle': -9.24085807800293, + 'Location': array([ -3.90472531, -21.67049217, 0.17382637]), + 'Rotation': array([-0.06872536, -3.99487448, -0.00827026]), + 'Velocity': array([-7.83854499e-02, 1.33315334e-02, -6.84738143e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.78034449, 10.55928993, 2.55202556]), + 'camera_rotation': array([ -6.06901217, -17.30280495, -1.65874887]), + 'current_gear_input': False, + 'focus_actor_dist': 1427.8330078125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([1090.89807129, -991.33770752, 66.60774231]), + 'frame': 15201, + 'frame_number': 15201, + 'framesequence': 58383, + 'gaze_dir': array([ 0.99662781, -0.05662537, 0.0552063 ]), + 'gaze_origin': array([-3.11906815e+00, -2.54821789e-04, 1.01048276e-01]), + 'gaze_valid': True, + 'gaze_vergence': 149.05023193359375, + 'handbrake_input': False, + 'left_eye_openness': 0.9681121110916138, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99786377, -0.03527832, 0.05487061]), + 'left_gaze_origin': array([-3.07042718, 3.19097447, 0.11663056]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.233123779296875, + 'left_pupil_posn': array([ 0.00537145, -0.0289464 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9859727621078491, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99539185, -0.07797241, 0.05554199]), + 'right_gaze_origin': array([-3.16770935, -3.19148421, 0.085466 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2187347412109375, + 'right_pupil_posn': array([-0.00984985, -0.1091367 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.48713037371635437, + 'throttle_input': 0.0, + 'timestamp': 497.2307127676904, + 'timestamp_carla': 497231, + 'timestamp_device': 4235446, + 'timestamp_stream': 497.2307127676904, + 'transform': [array([ 9.02950096e+00, -9.18501663e+00, -5.73524460e-03]), + array([-1.15020378e-02, -3.96778946e+01, 8.01391378e-02])]} +{'AngularVelocity': array([-1.01771066e-03, 3.59447068e-03, -1.14179325e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.131223678588867, + 'FR_Wheel_Angle': -9.185701370239258, + 'Location': array([ -3.92106676, -21.66802597, 0.17382839]), + 'Rotation': array([-0.06982502, -3.94073582, -0.0083313 ]), + 'Velocity': array([-0.06137523, 0.01040355, -0.00044553]), + 'brake_input': 0.0, + 'camera_location': array([-6.75447083, 10.75504684, 2.54491401]), + 'camera_rotation': array([ -6.18864298, -16.39318466, -1.61622751]), + 'current_gear_input': False, + 'focus_actor_dist': 2559.7021484375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.17401343e+03, -5.68987793e+02, 6.10351562e-04]), + 'frame': 15202, + 'frame_number': 15202, + 'framesequence': 58387, + 'gaze_dir': array([ 0.99625397, -0.06639862, 0.0537796 ]), + 'gaze_origin': array([-3.11385822, 0.01853943, 0.10065308]), + 'gaze_valid': True, + 'gaze_vergence': 234.8321075439453, + 'handbrake_input': False, + 'left_eye_openness': 0.9603675603866577, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99728394, -0.05418396, 0.04978943]), + 'left_gaze_origin': array([-3.03320169, 3.20866251, 0.10708924]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1786956787109375, + 'left_pupil_posn': array([-0.00664955, -0.02791905]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9991766214370728, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.995224 , -0.07861328, 0.05776978]), + 'right_gaze_origin': array([-3.19451475, -3.17158365, 0.09421692]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.20770263671875, + 'right_pupil_posn': array([-0.02959651, -0.10988081]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.0, + 'timestamp': 497.26497976854444, + 'timestamp_carla': 497265, + 'timestamp_device': 4235479, + 'timestamp_stream': 497.26497976854444, + 'transform': [array([ 9.19702530e+00, -9.26091766e+00, -5.83459856e-03]), + array([-1.29090566e-02, -4.03735352e+01, 8.00781175e-02])]} +{'AngularVelocity': array([-5.71646844e-04, -1.98520967e-04, 2.93132842e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.680529594421387, + 'FR_Wheel_Angle': -8.863173484802246, + 'Location': array([ -3.93794036, -21.66556358, 0.17388271]), + 'Rotation': array([-0.07043291, -3.88284445, -0.00839233]), + 'Velocity': array([-0.05472516, 0.00877913, 0.00026737]), + 'brake_input': 0.0, + 'camera_location': array([-6.68888521, 10.95625591, 2.59969687]), + 'camera_rotation': array([ -6.10991144, -15.43383789, -1.53269374]), + 'current_gear_input': False, + 'focus_actor_dist': 2127.90283203125, + 'focus_actor_name': 'Road_Sidewalk_Town05_214', + 'focus_actor_pt': array([1813.76867676, -794.95129395, 15.24003601]), + 'frame': 15203, + 'frame_number': 15203, + 'framesequence': 58391, + 'gaze_dir': array([ 0.9957962 , -0.07149506, 0.05517578]), + 'gaze_origin': array([-3.11174273, 0.02184448, 0.10249557]), + 'gaze_valid': True, + 'gaze_vergence': 219.99713134765625, + 'handbrake_input': False, + 'left_eye_openness': 0.9707098603248596, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99688721, -0.05712891, 0.05407715]), + 'left_gaze_origin': array([-3.01797032, 3.21192193, 0.10294953]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.231689453125, + 'left_pupil_posn': array([-0.01126182, -0.02843571]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9947052 , -0.08586121, 0.05627441]), + 'right_gaze_origin': array([-3.20551467, -3.16823268, 0.10204162]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.19281005859375, + 'right_pupil_posn': array([-0.03274202, -0.10495758]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4720053970813751, + 'throttle_input': 0.0, + 'timestamp': 497.2978962659836, + 'timestamp_carla': 497298, + 'timestamp_device': 4235513, + 'timestamp_stream': 497.2978962659836, + 'transform': [array([ 9.35338020e+00, -9.33290768e+00, -5.90826012e-03]), + array([-1.42204529e-02, -4.10235367e+01, 7.99865499e-02])]} +{'AngularVelocity': array([-2.22322764e-04, 1.24976446e-03, 2.77794451e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.691177368164062, + 'FR_Wheel_Angle': -8.866528511047363, + 'Location': array([ -3.94800162, -21.66410828, 0.17387378]), + 'Rotation': array([-0.07055585, -3.85119724, -0.00845337]), + 'Velocity': array([-0.04609906, 0.00737105, -0.0002708 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.64384985, 11.12153053, 2.64035678]), + 'camera_rotation': array([ -5.92125463, -14.63541222, -1.15887856]), + 'current_gear_input': False, + 'focus_actor_dist': 2516.312255859375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.15574365e+03, -5.97818237e+02, 6.10351562e-04]), + 'frame': 15204, + 'frame_number': 15204, + 'framesequence': 58395, + 'gaze_dir': array([ 0.99613953, -0.07326508, 0.04595184]), + 'gaze_origin': array([-3.10772634, 0.02129898, 0.10035706]), + 'gaze_valid': True, + 'gaze_vergence': 221.7814178466797, + 'handbrake_input': False, + 'left_eye_openness': 0.9677582383155823, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99714661, -0.05899048, 0.04693604]), + 'left_gaze_origin': array([-3.01596069, 3.21192193, 0.10101166]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.19110107421875, + 'left_pupil_posn': array([-0.01186311, -0.03307724]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9979583024978638, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99513245, -0.08753967, 0.04496765]), + 'right_gaze_origin': array([-3.19949198, -3.16932392, 0.09970246]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1585845947265625, + 'right_pupil_posn': array([-0.03274202, -0.10793948]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4649007022380829, + 'throttle_input': 0.0, + 'timestamp': 497.33035746589303, + 'timestamp_carla': 497331, + 'timestamp_device': 4235546, + 'timestamp_stream': 497.33035746589303, + 'transform': [array([ 9.50329971e+00, -9.40292931e+00, -5.98371495e-03]), + array([-1.53815849e-02, -4.16473045e+01, 7.99255371e-02])]} +{'AngularVelocity': array([2.69019132e-04, 2.88736192e-03, 2.75992543e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.69093132019043, + 'FR_Wheel_Angle': -8.866013526916504, + 'Location': array([ -3.96003079, -21.6623745 , 0.17390293]), + 'Rotation': array([-0.07110909, -3.8132031 , -0.00869751]), + 'Velocity': array([-0.04740818, 0.00751409, 0.00012578]), + 'brake_input': 0.0, + 'camera_location': array([-6.59672928, 11.27268982, 2.66242647]), + 'camera_rotation': array([ -5.6848073 , -13.93894577, -1.09354067]), + 'current_gear_input': False, + 'focus_actor_dist': 2031.5081787109375, + 'focus_actor_name': 'Road_Sidewalk_Town05_214', + 'focus_actor_pt': array([1739.71899414, -834.23474121, 15.23999786]), + 'frame': 15205, + 'frame_number': 15205, + 'framesequence': 58399, + 'gaze_dir': array([ 0.99529266, -0.08114624, 0.04790497]), + 'gaze_origin': array([-3.09628701, 0.02294083, 0.09573822]), + 'gaze_valid': True, + 'gaze_vergence': 143.90939331054688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99703979, -0.05911255, 0.04901123]), + 'left_gaze_origin': array([-2.99760604, 3.21483469, 0.09412232]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1850433349609375, + 'left_pupil_posn': array([-0.01908547, -0.03383958]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99354553, -0.10317993, 0.04679871]), + 'right_gaze_origin': array([-3.19496775, -3.16895318, 0.09735413]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.156036376953125, + 'right_pupil_posn': array([-0.0331018 , -0.10796642]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.45759454369544983, + 'throttle_input': 0.0, + 'timestamp': 497.36371436715126, + 'timestamp_carla': 497364, + 'timestamp_device': 4235579, + 'timestamp_stream': 497.36371436715126, + 'transform': [array([ 9.65303993e+00, -9.47378254e+00, -6.06744736e-03]), + array([-1.64539255e-02, -4.22706451e+01, 7.98644871e-02])]} +{'AngularVelocity': array([-0.03471611, -0.0071185 , 1.00526702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.627535820007324, + 'FR_Wheel_Angle': -8.812990188598633, + 'Location': array([ -4.01238298, -21.65471458, 0.17404442]), + 'Rotation': array([-0.08617649, -3.68164134, -0.01312256]), + 'Velocity': array([-0.40757635, 0.06242403, 0.00048902]), + 'brake_input': 0.0, + 'camera_location': array([-6.56504822, 11.42695618, 2.70630574]), + 'camera_rotation': array([ -5.4903245 , -13.20543289, -0.98046476]), + 'current_gear_input': False, + 'focus_actor_dist': 2542.547607421875, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.19528809e+03, -5.89186890e+02, 6.40869141e-04]), + 'frame': 15206, + 'frame_number': 15206, + 'framesequence': 58403, + 'gaze_dir': array([ 0.99591064, -0.07853699, 0.04098511]), + 'gaze_origin': array([-3.09330225, 0.02238922, 0.09312134]), + 'gaze_valid': True, + 'gaze_vergence': 167.0128631591797, + 'handbrake_input': False, + 'left_eye_openness': 0.9607506990432739, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99685669, -0.06278992, 0.04823303]), + 'left_gaze_origin': array([-2.99500751, 3.214432 , 0.09053498]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1717987060546875, + 'left_pupil_posn': array([-0.01577407, -0.04009902]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9975606203079224, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9949646 , -0.09428406, 0.03373718]), + 'right_gaze_origin': array([-3.19159698, -3.16965365, 0.09570771]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.19732666015625, + 'right_pupil_posn': array([-0.03395593, -0.1087147 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4497207701206207, + 'throttle_input': 0.0, + 'timestamp': 497.3988131657243, + 'timestamp_carla': 497399, + 'timestamp_device': 4235613, + 'timestamp_stream': 497.3988131657243, + 'transform': [array([ 9.80594254e+00, -9.54696369e+00, -6.16550446e-03]), + array([-1.74511317e-02, -4.29071693e+01, 7.98034593e-02])]} +{'AngularVelocity': array([-0.02111423, 0.0019881 , 1.9318105 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.580269813537598, + 'FR_Wheel_Angle': -8.757047653198242, + 'Location': array([ -4.14341497, -21.63661575, 0.17417407]), + 'Rotation': array([-0.08566423, -3.28009129, -0.01272583]), + 'Velocity': array([-6.85131311e-01, 1.01564735e-01, 6.42671599e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.48976278, 11.60228157, 2.71476936]), + 'camera_rotation': array([ -5.13846016, -12.57662201, -0.89662653]), + 'current_gear_input': False, + 'focus_actor_dist': 2127.3212890625, + 'focus_actor_name': 'Road_Sidewalk_Town05_214', + 'focus_actor_pt': array([1834.86376953, -782.54760742, 15.24005127]), + 'frame': 15207, + 'frame_number': 15207, + 'framesequence': 58407, + 'gaze_dir': array([ 0.9955368 , -0.08516693, 0.03844452]), + 'gaze_origin': array([-3.08074832, 0.02184753, 0.08586121]), + 'gaze_valid': True, + 'gaze_vergence': 251.03538513183594, + 'handbrake_input': False, + 'left_eye_openness': 0.963392972946167, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99647522, -0.07305908, 0.0410614 ]), + 'left_gaze_origin': array([-2.99353957, 3.21466064, 0.08908997]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.183563232421875, + 'left_pupil_posn': array([-0.01694655, -0.04009902]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99459839, -0.09727478, 0.03582764]), + 'right_gaze_origin': array([-3.16795659, -3.17096567, 0.08263245]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1326141357421875, + 'right_pupil_posn': array([-0.03702283, -0.11566055]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.44131597876548767, + 'throttle_input': 0.0, + 'timestamp': 497.43148916587234, + 'timestamp_carla': 497432, + 'timestamp_device': 4235646, + 'timestamp_stream': 497.43148916587234, + 'transform': [array([ 9.94414997e+00, -9.61376572e+00, -6.22814149e-03]), + array([-1.83117352e-02, -4.34823608e+01, 7.97424242e-02])]} +{'AngularVelocity': array([0.00651763, 0.0736037 , 2.45980287]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.5419697761535645, + 'FR_Wheel_Angle': -6.235484600067139, + 'Location': array([ -4.3506937 , -21.61098671, 0.17437938]), + 'Rotation': array([-0.08584864, -2.67956567, -0.00964355]), + 'Velocity': array([-1.03761113e+00, 1.27923816e-01, 9.09509661e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.42715597, 11.78344727, 2.73729181]), + 'camera_rotation': array([ -5.0080924 , -11.88788795, -0.98486394]), + 'current_gear_input': False, + 'focus_actor_dist': 2554.849609375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.21886157e+03, -5.80174438e+02, 6.40869141e-04]), + 'frame': 15208, + 'frame_number': 15208, + 'framesequence': 58411, + 'gaze_dir': array([ 0.99556732, -0.08634186, 0.03561401]), + 'gaze_origin': array([-3.08811426, 0.02389908, 0.09015199]), + 'gaze_valid': True, + 'gaze_vergence': 291.16644287109375, + 'handbrake_input': False, + 'left_eye_openness': 0.9666324257850647, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99655151, -0.07588196, 0.03346252]), + 'left_gaze_origin': array([-2.99285603, 3.21624923, 0.08893586]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.178680419921875, + 'left_pupil_posn': array([-0.01785094, -0.03941607]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99458313, -0.09680176, 0.0377655 ]), + 'right_gaze_origin': array([-3.18337274, -3.16845107, 0.09136811]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.107269287109375, + 'right_pupil_posn': array([-0.03951937, -0.11514676]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4345957934856415, + 'throttle_input': 0.0, + 'timestamp': 497.46597296744585, + 'timestamp_carla': 497466, + 'timestamp_device': 4235679, + 'timestamp_stream': 497.46597296744585, + 'transform': [array([ 1.00858479e+01, -9.68289852e+00, -6.31460175e-03]), + array([-1.90084148e-02, -4.40718765e+01, 7.97119141e-02])]} +{'AngularVelocity': array([-0.00896086, -0.11415781, 0.73085874]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.1499664783477783, + 'FR_Wheel_Angle': -1.6699028015136719, + 'Location': array([ -4.61021852, -21.59057045, 0.17457011]), + 'Rotation': array([-7.51662254e-02, -2.31549072e+00, -1.34277344e-03]), + 'Velocity': array([-1.01573730e+00, 6.39487505e-02, 8.09106801e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.39593029, 11.95747948, 2.7525022 ]), + 'camera_rotation': array([ -4.99387884, -11.28116798, -0.84507585]), + 'current_gear_input': False, + 'focus_actor_dist': 2521.595458984375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.19382495e+03, -5.91543213e+02, 6.10351562e-04]), + 'frame': 15209, + 'frame_number': 15209, + 'framesequence': 58415, + 'gaze_dir': array([ 0.99530792, -0.08916473, 0.03538513]), + 'gaze_origin': array([-3.08210301, 0.02406769, 0.08451539]), + 'gaze_valid': True, + 'gaze_vergence': 217.0250701904297, + 'handbrake_input': False, + 'left_eye_openness': 0.9639345407485962, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99594116, -0.0793457 , 0.04231262]), + 'left_gaze_origin': array([-2.98659372, 3.21759057, 0.0855774 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1535491943359375, + 'left_pupil_posn': array([-0.0194841 , -0.04364705]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9989286065101624, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99467468, -0.09898376, 0.02845764]), + 'right_gaze_origin': array([-3.1776123 , -3.16945505, 0.08345337]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.08489990234375, + 'right_pupil_posn': array([-0.04013336, -0.11643887]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.425898015499115, + 'throttle_input': 0.0, + 'timestamp': 497.49978986755013, + 'timestamp_carla': 497500, + 'timestamp_device': 4235713, + 'timestamp_stream': 497.49978986755013, + 'transform': [array([ 1.02207136e+01, -9.74915791e+00, -6.38948428e-03]), + array([-1.96777731e-02, -4.46323929e+01, 7.96813816e-02])]} +{'AngularVelocity': array([2.61839796e-02, 3.97011712e-02, 5.69424737e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -4.72127008, -21.5854435 , 0.17447689]), + 'Rotation': array([-0.03820807, -2.29287744, -0.00384521]), + 'Velocity': array([-0.13980268, 0.00548407, 0.00034457]), + 'brake_input': 0.0, + 'camera_location': array([-6.3419857 , 12.12871265, 2.73939657]), + 'camera_rotation': array([ -4.86897516, -10.73449039, -0.7823081 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2531.222412109375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.21039795e+03, -5.88733276e+02, 6.25610352e-04]), + 'frame': 15210, + 'frame_number': 15210, + 'framesequence': 58419, + 'gaze_dir': array([ 0.99514008, -0.09100342, 0.03481293]), + 'gaze_origin': array([-3.07071257, 0.02299881, 0.08419647]), + 'gaze_valid': True, + 'gaze_vergence': 230.98165893554688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99633789, -0.07739258, 0.03622437]), + 'left_gaze_origin': array([-2.97426915, 3.21675587, 0.08555298]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1215972900390625, + 'left_pupil_posn': array([-0.02078247, -0.03972566]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99394226, -0.10461426, 0.03340149]), + 'right_gaze_origin': array([-3.16715574, -3.17075801, 0.08283997]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0865478515625, + 'right_pupil_posn': array([-0.03869432, -0.11702657]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.41575369238853455, + 'throttle_input': 0.0, + 'timestamp': 497.53292336687446, + 'timestamp_carla': 497533, + 'timestamp_device': 4235746, + 'timestamp_stream': 497.53292336687446, + 'transform': [array([ 1.03487501e+01, -9.81216621e+00, -6.45347591e-03]), + array([-2.04769056e-02, -4.51630974e+01, 7.96203539e-02])]} +{'AngularVelocity': array([0.00953965, 0.06678759, 0.00162075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -4.73967075, -21.58469391, 0.17460833]), + 'Rotation': array([-0.05786536, -2.29287791, -0.00704956]), + 'Velocity': array([-0.05111066, 0.00202778, 0.00047277]), + 'brake_input': 0.0, + 'camera_location': array([-6.30255508, 12.29817867, 2.70244074]), + 'camera_rotation': array([ -5.13463545, -10.14851093, -0.56200236]), + 'current_gear_input': False, + 'focus_actor_dist': 2611.772216796875, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.28823853e+03, -5.50329468e+02, 6.86645508e-04]), + 'frame': 15211, + 'frame_number': 15211, + 'framesequence': 58423, + 'gaze_dir': array([ 0.99512482, -0.09020233, 0.0377121 ]), + 'gaze_origin': array([-3.09063673, 0.02019577, 0.09177933]), + 'gaze_valid': True, + 'gaze_vergence': 244.29754638671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99635315, -0.07765198, 0.03535461]), + 'left_gaze_origin': array([-2.98202991, 3.21320033, 0.08890076]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1009521484375, + 'left_pupil_posn': array([-0.01777709, -0.03667307]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99389648, -0.10275269, 0.04006958]), + 'right_gaze_origin': array([-3.19924307, -3.17280889, 0.09465791]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.95782470703125, + 'right_pupil_posn': array([-0.03691173, -0.1153245 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4061037302017212, + 'throttle_input': 0.0, + 'timestamp': 497.5654982663691, + 'timestamp_carla': 497566, + 'timestamp_device': 4235779, + 'timestamp_stream': 497.5654982663691, + 'transform': [array([ 1.04707317e+01, -9.87213612e+00, -6.51451107e-03]), + array([-2.12692078e-02, -4.56669273e+01, 7.95593187e-02])]} +{'AngularVelocity': array([0.0032583 , 0.02401838, 0.0026858 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038449489511549473, + 'FR_Wheel_Angle': 0.012817133218050003, + 'Location': array([ -4.74743986, -21.58436966, 0.17466433]), + 'Rotation': array([-0.06616404, -2.2928772 , -0.00787353]), + 'Velocity': array([-2.90433727e-02, 1.17042137e-03, 5.31673431e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.26878452, 12.46371269, 2.69502997]), + 'camera_rotation': array([-5.21379042, -9.36984825, -0.13891129]), + 'current_gear_input': False, + 'focus_actor_dist': 2545.130859375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.23259399e+03, -5.75760620e+02, 6.25610352e-04]), + 'frame': 15212, + 'frame_number': 15212, + 'framesequence': 58427, + 'gaze_dir': array([0.99546051, 0.08525085, 0.0379715 ]), + 'gaze_origin': array([-3.12304997, -0.11633149, 0.10941087]), + 'gaze_valid': True, + 'gaze_vergence': 166.86721801757812, + 'handbrake_input': False, + 'left_eye_openness': 0.9749660491943359, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99377441, 0.10261536, 0.04312134]), + 'left_gaze_origin': array([-3.03660154, 3.07167387, 0.11160126]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17901611328125, + 'left_pupil_posn': array([ 0.13628674, -0.03424585]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9970990419387817, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99714661, 0.06788635, 0.03282166]), + 'right_gaze_origin': array([-3.20949888, -3.30433655, 0.10722047]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.043914794921875, + 'right_pupil_posn': array([ 0.11619639, -0.10749054]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3970397412776947, + 'throttle_input': 0.0, + 'timestamp': 497.59915256872773, + 'timestamp_carla': 497599, + 'timestamp_device': 4235813, + 'timestamp_stream': 497.59915256872773, + 'transform': [array([ 1.05929308e+01, -9.93211269e+00, -5.95331192e-03]), + array([-1.67544540e-02, -4.61696167e+01, 7.74841234e-02])]} +{'AngularVelocity': array([ 0.0006827 , 0.01270208, -0.14373589]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07044526189565659, + 'FR_Wheel_Angle': 0.07049234956502914, + 'Location': array([ -4.74806595, -21.58431435, 0.17467959]), + 'Rotation': array([-0.06927177, -2.2968142 , -0.00814819]), + 'Velocity': array([-0.00303022, 0.00012667, 0.00010179]), + 'brake_input': 0.0, + 'camera_location': array([-6.23652744, 12.64898014, 2.66116381]), + 'camera_rotation': array([-5.4215169 , -8.52749729, -0.01862684]), + 'current_gear_input': False, + 'focus_actor_dist': 2543.443359375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 1.97472253e+03, -1.96039551e+02, 6.10351562e-05]), + 'frame': 15213, + 'frame_number': 15213, + 'framesequence': 58431, + 'gaze_dir': array([0.94586945, 0.32035828, 0.04983521]), + 'gaze_origin': array([-3.12505507, -0.2852791 , 0.11047288]), + 'gaze_valid': True, + 'gaze_vergence': 149.11680603027344, + 'handbrake_input': False, + 'left_eye_openness': 0.9397828578948975, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94314575, 0.32997131, 0.03968811]), + 'left_gaze_origin': array([-3.03572536, 2.8893404 , 0.11408387]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3212432861328125, + 'left_pupil_posn': array([ 0.34527087, -0.02787924]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.872398853302002, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94859314, 0.31074524, 0.0599823 ]), + 'right_gaze_origin': array([-3.21438456, -3.45989847, 0.10686188]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0787353515625, + 'right_pupil_posn': array([ 0.30511105, -0.11578536]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3874996602535248, + 'throttle_input': 0.0, + 'timestamp': 497.6337491683662, + 'timestamp_carla': 497634, + 'timestamp_device': 4235846, + 'timestamp_stream': 497.6337491683662, + 'transform': [array([ 1.07145920e+01, -9.99163246e+00, -5.21146785e-03]), + array([-1.18435472e-02, -4.66680107e+01, 7.47375339e-02])]} +{'AngularVelocity': array([ 6.69609872e-05, 5.00932755e-03, -1.43361047e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07043386995792389, + 'FR_Wheel_Angle': 0.07047964632511139, + 'Location': array([ -4.74957132, -21.58423805, 0.17469443]), + 'Rotation': array([-0.07110909, -2.29742432, -0.00820923]), + 'Velocity': array([-0.01104055, 0.00045844, 0.00034591]), + 'brake_input': 0.0, + 'camera_location': array([-6.21709681, 12.8670187 , 2.6204133 ]), + 'camera_rotation': array([-5.54379797, -7.40355492, -0.07173388]), + 'current_gear_input': False, + 'focus_actor_dist': 1025.2559814453125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([ 632.06628418, -991.89801025, 94.99907684]), + 'frame': 15214, + 'frame_number': 15214, + 'framesequence': 58436, + 'gaze_dir': array([0.90486908, 0.42185974, 0.0545578 ]), + 'gaze_origin': array([-3.15701914, -0.35883409, 0.1172287 ]), + 'gaze_valid': True, + 'gaze_vergence': 159.01014709472656, + 'handbrake_input': False, + 'left_eye_openness': 0.8338021039962769, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.89971924, 0.4339447 , 0.04647827]), + 'left_gaze_origin': array([-3.06878209, 2.81061578, 0.12063295]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.40386962890625, + 'left_pupil_posn': array([ 0.43725312, -0.03186524]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.7165217399597168, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91001892, 0.40977478, 0.06263733]), + 'right_gaze_origin': array([-3.24525619, -3.52828383, 0.11382446]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.063690185546875, + 'right_pupil_posn': array([ 0.39419186, -0.11866605]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3774285316467285, + 'throttle_input': 0.0, + 'timestamp': 497.6674632653594, + 'timestamp_carla': 497668, + 'timestamp_device': 4235888, + 'timestamp_stream': 497.6674632653594, + 'transform': [array([ 1.08293781e+01, -1.00474901e+01, -4.81132511e-03]), + array([-9.76717006e-03, -4.71359520e+01, 7.31506199e-02])]} +{'AngularVelocity': array([-1.08374428e-04, 2.63614184e-03, -1.47127286e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07041070610284805, + 'FR_Wheel_Angle': 0.07045519351959229, + 'Location': array([ -4.75405121, -21.58405495, 0.17470653]), + 'Rotation': array([-0.07177845, -2.29757738, -0.00820923]), + 'Velocity': array([-2.84210723e-02, 1.13108952e-03, 7.26604412e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.20096684, 13.08988762, 2.62155271]), + 'camera_rotation': array([-5.54321718, -6.02248001, 0.1163262 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3598.234375, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([1784.15515137, 1324.4708252 , 15.42106628]), + 'frame': 15215, + 'frame_number': 15215, + 'framesequence': 58440, + 'gaze_dir': array([0.88900757, 0.45516205, 0.04877472]), + 'gaze_origin': array([-3.16717625, -0.38200304, 0.12306672]), + 'gaze_valid': True, + 'gaze_vergence': 281.32904052734375, + 'handbrake_input': False, + 'left_eye_openness': 0.8109099864959717, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.88452148, 0.46395874, 0.04840088]), + 'left_gaze_origin': array([-3.07888651, 2.78605342, 0.12398987]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2960205078125, + 'left_pupil_posn': array([ 0.46891451, -0.03739202]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.6986716985702515, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.89349365, 0.44636536, 0.04914856]), + 'right_gaze_origin': array([-3.25546598, -3.5500598 , 0.12214356]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0899810791015625, + 'right_pupil_posn': array([ 0.42215848, -0.11564875]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3673757016658783, + 'throttle_input': 0.0, + 'timestamp': 497.70147796720266, + 'timestamp_carla': 497702, + 'timestamp_device': 4235921, + 'timestamp_stream': 497.70147796720266, + 'transform': [array([ 1.09414644e+01, -1.01015682e+01, -4.56745131e-03]), + array([-8.64018872e-03, -4.75900764e+01, 7.20825046e-02])]} +{'AngularVelocity': array([0.00774382, 0.14130673, 0.54579359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07001450657844543, + 'FR_Wheel_Angle': 0.0710701122879982, + 'Location': array([ -4.76485777, -21.58366203, 0.17472923]), + 'Rotation': array([-0.07378653, -2.28848314, -0.00823975]), + 'Velocity': array([-0.15877403, 0.00676721, 0.00032869]), + 'brake_input': 0.0, + 'camera_location': array([-6.19974327, 13.30272198, 2.6489954 ]), + 'camera_rotation': array([-5.47470379, -4.51217031, 0.34958977]), + 'current_gear_input': False, + 'focus_actor_dist': 3094.74072265625, + 'focus_actor_name': 'Road_Sidewalk_Town05_159', + 'focus_actor_pt': array([1397.80114746, 963.52026367, 15.08322144]), + 'frame': 15216, + 'frame_number': 15216, + 'framesequence': 58444, + 'gaze_dir': array([0.89878082, 0.43426514, 0.05760193]), + 'gaze_origin': array([-3.15966892, -0.36733475, 0.12575838]), + 'gaze_valid': True, + 'gaze_vergence': 169.47830200195312, + 'handbrake_input': False, + 'left_eye_openness': 0.8909825682640076, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.89173889, 0.44911194, 0.05555725]), + 'left_gaze_origin': array([-3.06968999, 2.80558944, 0.12359162]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.25128173828125, + 'left_pupil_posn': array([ 0.44454956, -0.03130138]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.7483370304107666, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.90582275, 0.41941833, 0.05964661]), + 'right_gaze_origin': array([-3.24964786, -3.54025888, 0.12792511]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0325927734375, + 'right_pupil_posn': array([ 0.40902817, -0.10721469]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3575609624385834, + 'throttle_input': 0.0, + 'timestamp': 497.73632196709514, + 'timestamp_carla': 497737, + 'timestamp_device': 4235954, + 'timestamp_stream': 497.73632196709514, + 'transform': [array([ 1.10525999e+01, -1.01546669e+01, -4.40713856e-03]), + array([-7.77958520e-03, -4.80374069e+01, 7.12890327e-02])]} +{'AngularVelocity': array([ 0.00417912, 0.03266779, -0.16824754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0782882571220398, + 'FR_Wheel_Angle': 0.07835548371076584, + 'Location': array([ -4.89526224, -21.57845879, 0.17493588]), + 'Rotation': array([-0.09060928, -2.27987695, -0.00802612]), + 'Velocity': array([-7.27245986e-01, 2.98362467e-02, 5.07583609e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.21643829, 13.52489662, 2.6594522 ]), + 'camera_rotation': array([-5.36824846, -3.00147295, 0.25419089]), + 'current_gear_input': False, + 'focus_actor_dist': 3776.530517578125, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([1718.19592285, 1571.55297852, 15.4850235 ]), + 'frame': 15217, + 'frame_number': 15217, + 'framesequence': 58448, + 'gaze_dir': array([0.9169693 , 0.3942337 , 0.05900574]), + 'gaze_origin': array([-3.14996791, -0.35293961, 0.12402725]), + 'gaze_valid': True, + 'gaze_vergence': 183.31033325195312, + 'handbrake_input': False, + 'left_eye_openness': 0.957108736038208, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91075134, 0.40867615, 0.05905151]), + 'left_gaze_origin': array([-3.05872822, 2.82462621, 0.12243653]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1445770263671875, + 'left_pupil_posn': array([ 0.41621721, -0.0285964 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8184443712234497, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92318726, 0.37979126, 0.05895996]), + 'right_gaze_origin': array([-3.24120808, -3.53050566, 0.12561798]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9808197021484375, + 'right_pupil_posn': array([ 0.38608646, -0.1040616 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.346720814704895, + 'throttle_input': 0.0, + 'timestamp': 497.7688534669578, + 'timestamp_carla': 497769, + 'timestamp_device': 4235988, + 'timestamp_stream': 497.7688534669578, + 'transform': [array([ 1.11530428e+01, -1.02020197e+01, -4.27425373e-03]), + array([-7.11022643e-03, -4.84385681e+01, 7.06786886e-02])]} +{'AngularVelocity': array([ 0.00376603, -0.00847994, 0.90917712]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.08689132332801819, + 'FR_Wheel_Angle': 0.08692574501037598, + 'Location': array([ -5.08160257, -21.57102585, 0.1750975 ]), + 'Rotation': array([-0.0841411 , -2.27709985, -0.00756836]), + 'Velocity': array([-8.97888064e-01, 3.59250866e-02, 6.60867663e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.25856209, 13.76688862, 2.67595196]), + 'camera_rotation': array([-5.15032434, -1.30431986, 0.09705559]), + 'current_gear_input': False, + 'focus_actor_dist': 4069.41650390625, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([1945.64318848, 1789.84667969, 15.26931763]), + 'frame': 15218, + 'frame_number': 15218, + 'framesequence': 58452, + 'gaze_dir': array([0.91384888, 0.39996338, 0.067276 ]), + 'gaze_origin': array([-3.15115309, -0.35586169, 0.12958984]), + 'gaze_valid': True, + 'gaze_vergence': 148.97862243652344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90612793, 0.41716003, 0.06985474]), + 'left_gaze_origin': array([-3.05884099, 2.82207942, 0.12943573]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.237335205078125, + 'left_pupil_posn': array([ 0.41900408, -0.02214372]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8466687202453613, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92156982, 0.38276672, 0.06469727]), + 'right_gaze_origin': array([-3.24346495, -3.53380299, 0.12974396]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0692901611328125, + 'right_pupil_posn': array([ 0.39182222, -0.0982877 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.33762016892433167, + 'throttle_input': 0.0, + 'timestamp': 497.8029933683574, + 'timestamp_carla': 497803, + 'timestamp_device': 4236021, + 'timestamp_stream': 497.8029933683574, + 'transform': [array([ 1.12551107e+01, -1.02494326e+01, -4.16849134e-03]), + array([-6.37939619e-03, -4.88428764e+01, 7.00988621e-02])]} +{'AngularVelocity': array([-0.00220748, -0.04232926, 0.96813989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.08682030439376831, + 'FR_Wheel_Angle': 0.0869075134396553, + 'Location': array([ -5.33963203, -21.56080246, 0.17531344]), + 'Rotation': array([-0.07626589, -2.28356934, -0.00720215]), + 'Velocity': array([-0.97101951, 0.03842733, 0.00111507]), + 'brake_input': 0.0, + 'camera_location': array([-6.30849838, 14.01327896, 2.71045041]), + 'camera_rotation': array([-4.91690969, 0.39385331, -0.04202391]), + 'current_gear_input': False, + 'focus_actor_dist': 3232.373046875, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([1478.02929688, 1095.23876953, 82.66798401]), + 'frame': 15219, + 'frame_number': 15219, + 'framesequence': 58456, + 'gaze_dir': array([0.89173126, 0.44548035, 0.07862854]), + 'gaze_origin': array([-3.16548872, -0.38663712, 0.14061813]), + 'gaze_valid': True, + 'gaze_vergence': 195.54135131835938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.88644409, 0.45504761, 0.08439636]), + 'left_gaze_origin': array([-3.07489944, 2.7858398 , 0.14006807]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.335174560546875, + 'left_pupil_posn': array([ 0.4650836 , -0.01707947]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.828845739364624, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.89701843, 0.43591309, 0.07286072]), + 'right_gaze_origin': array([-3.25607777, -3.55911446, 0.14116822]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0818634033203125, + 'right_pupil_posn': array([ 0.42571521, -0.08926189]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3281167149543762, + 'throttle_input': 0.0, + 'timestamp': 497.837554667145, + 'timestamp_carla': 497838, + 'timestamp_device': 4236054, + 'timestamp_stream': 497.837554667145, + 'transform': [array([ 1.13552074e+01, -1.02952423e+01, -4.06997651e-03]), + array([-5.52562252e-03, -4.92361412e+01, 6.95495456e-02])]} +{'AngularVelocity': array([ 0.00152386, -0.01903735, 1.05751288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.15236499905586243, + 'FR_Wheel_Angle': 0.17026478052139282, + 'Location': array([ -5.53008413, -21.55323982, 0.17544791]), + 'Rotation': array([-0.06964061, -2.29135156, -0.00689697]), + 'Velocity': array([-9.00950074e-01, 3.57003622e-02, 6.80828060e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.36607075, 14.28216171, 2.7647624 ]), + 'camera_rotation': array([-4.68436909, 2.14291549, -0.02313369]), + 'current_gear_input': False, + 'focus_actor_dist': 13117.7880859375, + 'focus_actor_name': 'BP_TerracedHouse_45', + 'focus_actor_pt': array([ 4971.31152344, 10359.92382812, 152.65499878]), + 'frame': 15220, + 'frame_number': 15220, + 'framesequence': 58460, + 'gaze_dir': array([0.90901947, 0.40856934, 0.07975006]), + 'gaze_origin': array([-3.15420842, -0.36365816, 0.13844453]), + 'gaze_valid': True, + 'gaze_vergence': 140.291015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90097046, 0.42546082, 0.08493042]), + 'left_gaze_origin': array([-3.06252289, 2.81188202, 0.1363205 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2342376708984375, + 'left_pupil_posn': array([ 0.42983282, -0.0148505 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.828314483165741, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91706848, 0.39167786, 0.0745697 ]), + 'right_gaze_origin': array([-3.24589396, -3.53919864, 0.14056854]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0175018310546875, + 'right_pupil_posn': array([ 0.39922023, -0.0862788 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.31758782267570496, + 'throttle_input': 0.0, + 'timestamp': 497.87020026519895, + 'timestamp_carla': 497871, + 'timestamp_device': 4236088, + 'timestamp_stream': 497.87020026519895, + 'transform': [array([ 1.14467669e+01, -1.03363256e+01, -3.96217359e-03]), + array([-4.76064160e-03, -4.95923042e+01, 6.90307468e-02])]} +{'AngularVelocity': array([-0.00279398, 0.00498184, -1.02573276]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17883019149303436, + 'FR_Wheel_Angle': 0.1791379451751709, + 'Location': array([ -5.75683451, -21.54426956, 0.17570281]), + 'Rotation': array([-0.06946302, -2.31512499, -0.00653076]), + 'Velocity': array([-0.87642831, 0.03409496, 0.00099189]), + 'brake_input': 0.0, + 'camera_location': array([-6.42318392, 14.56424999, 2.82613611]), + 'camera_rotation': array([-4.35925198, 4.07478857, -0.07260664]), + 'current_gear_input': False, + 'focus_actor_dist': 13211.7822265625, + 'focus_actor_name': 'BP_TerracedHouse_47', + 'focus_actor_pt': array([ 5219.56884766, 10363.53125 , 194.73999023]), + 'frame': 15221, + 'frame_number': 15221, + 'framesequence': 58464, + 'gaze_dir': array([0.91882324, 0.38763428, 0.07336426]), + 'gaze_origin': array([-3.14451241, -0.33763811, 0.1355278 ]), + 'gaze_valid': True, + 'gaze_vergence': 260.5061340332031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91563416, 0.39605713, 0.06881714]), + 'left_gaze_origin': array([-3.05313897, 2.84309268, 0.13114472]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1810302734375, + 'left_pupil_posn': array([ 0.40304601, -0.01512206]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8636494874954224, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92201233, 0.37921143, 0.07791138]), + 'right_gaze_origin': array([-3.23588586, -3.51836872, 0.13991089]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.045745849609375, + 'right_pupil_posn': array([ 0.37247348, -0.08916366]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3088168203830719, + 'throttle_input': 0.0, + 'timestamp': 497.9045967683196, + 'timestamp_carla': 497905, + 'timestamp_device': 4236121, + 'timestamp_stream': 497.9045967683196, + 'transform': [array([ 1.15402222e+01, -1.03773956e+01, -3.87214660e-03]), + array([-3.90686793e-03, -4.99521599e+01, 6.85119405e-02])]} +{'AngularVelocity': array([-0.00118866, 0.01370056, -1.04535329]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17875255644321442, + 'FR_Wheel_Angle': 0.1790158599615097, + 'Location': array([ -5.93172884, -21.53737259, 0.1758786 ]), + 'Rotation': array([-0.070952 , -2.32547021, -0.0062561 ]), + 'Velocity': array([-8.94323409e-01, 3.50660309e-02, 8.88385752e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.49481726, 14.83788681, 2.88308501]), + 'camera_rotation': array([-3.96954179, 5.84732676, -0.13332154]), + 'current_gear_input': False, + 'focus_actor_dist': 13179.572265625, + 'focus_actor_name': 'BP_TerracedHouse_45', + 'focus_actor_pt': array([ 5156.0234375 , 10359.92285156, 173.5255127 ]), + 'frame': 15222, + 'frame_number': 15222, + 'framesequence': 58468, + 'gaze_dir': array([0.91566467, 0.39396667, 0.07809448]), + 'gaze_origin': array([-3.14546013, -0.33964387, 0.14084016]), + 'gaze_valid': True, + 'gaze_vergence': 188.27059936523438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90962219, 0.40805054, 0.07791138]), + 'left_gaze_origin': array([-3.05330968, 2.8407135 , 0.13889924]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2581024169921875, + 'left_pupil_posn': array([ 0.40471053, -0.01009309]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8864731192588806, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92170715, 0.37988281, 0.07827759]), + 'right_gaze_origin': array([-3.23760986, -3.52000141, 0.14278108]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.145843505859375, + 'right_pupil_posn': array([ 0.37818146, -0.08503902]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.29876402020454407, + 'throttle_input': 0.0, + 'timestamp': 497.93773206695914, + 'timestamp_carla': 497938, + 'timestamp_device': 4236154, + 'timestamp_stream': 497.93773206695914, + 'transform': [array([ 1.16274424e+01, -1.04148359e+01, -3.76781449e-03]), + array([-3.05309449e-03, -5.02843323e+01, 6.79931417e-02])]} +{'AngularVelocity': array([-0.00178742, 0.00200532, -1.06450403]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1785854697227478, + 'FR_Wheel_Angle': 0.17886562645435333, + 'Location': array([ -6.14654112, -21.52885628, 0.17609885]), + 'Rotation': array([-0.07284396, -2.3384707 , -0.00585938]), + 'Velocity': array([-9.45871115e-01, 3.73044275e-02, 8.96835292e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.58153296, 15.08942604, 2.9336946 ]), + 'camera_rotation': array([-3.61816955, 7.42559195, -0.10976218]), + 'current_gear_input': False, + 'focus_actor_dist': 13016.6328125, + 'focus_actor_name': 'BP_TerracedHouse_45', + 'focus_actor_pt': array([ 4716.31542969, 10363.55566406, 324.86138916]), + 'frame': 15223, + 'frame_number': 15223, + 'framesequence': 58473, + 'gaze_dir': array([0.90530396, 0.41268158, 0.09938812]), + 'gaze_origin': array([-3.15210676, -0.3550545 , 0.1503235 ]), + 'gaze_valid': True, + 'gaze_vergence': 187.93394470214844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.89904785, 0.42570496, 0.10224915]), + 'left_gaze_origin': array([-3.0612154 , 2.8197999 , 0.14669037]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2519683837890625, + 'left_pupil_posn': array([ 4.27316189e-01, -3.47256660e-04]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8640009760856628, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91156006, 0.3996582 , 0.0965271 ]), + 'right_gaze_origin': array([-3.24299788, -3.5299089 , 0.15395661]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2092742919921875, + 'right_pupil_posn': array([ 0.39269078, -0.07040036]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.28889432549476624, + 'throttle_input': 0.0, + 'timestamp': 497.97915276512504, + 'timestamp_carla': 497980, + 'timestamp_device': 4236196, + 'timestamp_stream': 497.97915276512504, + 'transform': [array([ 1.17327681e+01, -1.04587984e+01, -3.64572508e-03]), + array([-1.85781135e-03, -5.06803551e+01, 6.73827976e-02])]} +{'AngularVelocity': array([-0.001054 , 0.03369676, 0.68299508]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1781521886587143, + 'FR_Wheel_Angle': 0.17839360237121582, + 'Location': array([ -6.39058638, -21.51913834, 0.17641464]), + 'Rotation': array([-0.07683963, -2.34899879, -0.00540161]), + 'Velocity': array([-1.0895685 , 0.04321051, 0.00121562]), + 'brake_input': 0.0, + 'camera_location': array([-6.73245716, 15.54548645, 3.08735871]), + 'camera_rotation': array([-2.71245241e+00, 1.00797844e+01, -4.97549726e-03]), + 'current_gear_input': False, + 'focus_actor_dist': 4319.04296875, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1442.76367188, 2300.91235352, 318.01049805]), + 'frame': 15224, + 'frame_number': 15224, + 'framesequence': 58475, + 'gaze_dir': array([0.91848755, 0.38562775, 0.08672333]), + 'gaze_origin': array([-3.14402795, -0.34050295, 0.14670181]), + 'gaze_valid': True, + 'gaze_vergence': 240.0542755126953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.914505 , 0.3959198 , 0.08311462]), + 'left_gaze_origin': array([-3.05354786, 2.83758092, 0.14268953]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.288055419921875, + 'left_pupil_posn': array([ 0.40542936, -0.00314808]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8730035424232483, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92247009, 0.37533569, 0.09033203]), + 'right_gaze_origin': array([-3.2345078 , -3.51858687, 0.15071411]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.00299072265625, + 'right_pupil_posn': array([ 0.37263608, -0.07645035]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2766258716583252, + 'throttle_input': 0.0, + 'timestamp': 497.9997048676014, + 'timestamp_carla': 498000, + 'timestamp_device': 4236212, + 'timestamp_stream': 497.9997048676014, + 'transform': [array([ 1.17834225e+01, -1.04792404e+01, -3.56422411e-03]), + array([-1.46849058e-03, -5.08681450e+01, 6.70776144e-02])]} +{'AngularVelocity': array([-0.00221027, -0.00784266, 0.69223803]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1777895838022232, + 'FR_Wheel_Angle': 0.1780688762664795, + 'Location': array([ -6.59471846, -21.51093864, 0.17661545]), + 'Rotation': array([-0.07782317, -2.36108398, -0.00500488]), + 'Velocity': array([-1.18340468, 0.04722508, 0.00128361]), + 'brake_input': 0.0, + 'camera_location': array([-6.73245716, 15.54548645, 3.08735871]), + 'camera_rotation': array([-2.71245241e+00, 1.00797844e+01, -4.97549726e-03]), + 'current_gear_input': False, + 'focus_actor_dist': 20211.9609375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 6285.89648438, 17428.203125 , 990.73101807]), + 'frame': 15225, + 'frame_number': 15225, + 'framesequence': 58480, + 'gaze_dir': array([0.92582703, 0.36499786, 0.09744263]), + 'gaze_origin': array([-3.13858509, -0.32327807, 0.14918137]), + 'gaze_valid': True, + 'gaze_vergence': 278.87152099609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92263794, 0.3739624 , 0.09416199]), + 'left_gaze_origin': array([-3.04684162, 2.86037159, 0.14582367]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1303558349609375, + 'left_pupil_posn': array([0.38254154, 0.00458831]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.90238356590271, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92901611, 0.35603333, 0.10072327]), + 'right_gaze_origin': array([-3.23032856, -3.50692749, 0.15253906]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.135589599609375, + 'right_pupil_posn': array([ 0.35581374, -0.06992769]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.27067476511001587, + 'throttle_input': 0.0, + 'timestamp': 498.03549026697874, + 'timestamp_carla': 498036, + 'timestamp_device': 4236254, + 'timestamp_stream': 498.03549026697874, + 'transform': [array([ 1.18691578e+01, -1.05127525e+01, -3.49361403e-03]), + array([-6.14717021e-04, -5.11818962e+01, 6.65282905e-02])]} +{'AngularVelocity': array([-0.00323813, -0.01140301, -0.85689211]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17760373651981354, + 'FR_Wheel_Angle': 0.1778864562511444, + 'Location': array([ -6.83887053, -21.50104904, 0.17683741]), + 'Rotation': array([-0.07589706, -2.38137817, -0.00454712]), + 'Velocity': array([-1.24698424e+00, 5.00704087e-02, 1.05179788e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.81820107, 15.73028946, 3.15297413]), + 'camera_rotation': array([-2.34608793, 11.05662346, 0.03727298]), + 'current_gear_input': False, + 'focus_actor_dist': 4266.208984375, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1494.78747559, 2232.52734375, 361.53729248]), + 'frame': 15226, + 'frame_number': 15226, + 'framesequence': 58483, + 'gaze_dir': array([0.9313736 , 0.35151672, 0.0941391 ]), + 'gaze_origin': array([-3.13439178, -0.31260988, 0.14913025]), + 'gaze_valid': True, + 'gaze_vergence': 261.9065856933594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92858887, 0.36013794, 0.08946228]), + 'left_gaze_origin': array([-3.0424974 , 2.87169814, 0.1453537 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.189727783203125, + 'left_pupil_posn': array([0.36967957, 0.0046882 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9094793200492859, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93415833, 0.34289551, 0.09881592]), + 'right_gaze_origin': array([-3.22628665, -3.49691772, 0.15290681]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0233917236328125, + 'right_pupil_posn': array([ 0.34342396, -0.0698849 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2600909471511841, + 'throttle_input': 0.0, + 'timestamp': 498.0668975673616, + 'timestamp_carla': 498067, + 'timestamp_device': 4236279, + 'timestamp_stream': 498.0668975673616, + 'transform': [array([ 1.19420433e+01, -1.05401754e+01, -3.39292525e-03]), + array([ 1.50264153e-04, -5.14445877e+01, 6.60705343e-02])]} +{'AngularVelocity': array([-0.00710636, -0.0405265 , -1.24897158]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17758841812610626, + 'FR_Wheel_Angle': 0.17787963151931763, + 'Location': array([ -7.09209776, -21.49077988, 0.17701152]), + 'Rotation': array([-0.07321279, -2.39465356, -0.00402832]), + 'Velocity': array([-1.25044715e+00, 5.01236096e-02, -8.49065778e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.89122772, 15.90327644, 3.23057675]), + 'camera_rotation': array([-1.88402557, 11.98588371, 0.22749704]), + 'current_gear_input': False, + 'focus_actor_dist': 36768.84375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([12348.11230469, 32821.640625 , 2149.56225586]), + 'frame': 15227, + 'frame_number': 15227, + 'framesequence': 58487, + 'gaze_dir': array([0.93717957, 0.33880615, 0.08241272]), + 'gaze_origin': array([-3.13013935, -0.30360338, 0.14762956]), + 'gaze_valid': True, + 'gaze_vergence': 208.05838012695312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9354248 , 0.34544373, 0.07507324]), + 'left_gaze_origin': array([-3.03938007, 2.88031316, 0.14266969]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0491485595703125, + 'left_pupil_posn': array([0.35958433, 0.00050336]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9236037135124207, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93893433, 0.33216858, 0.0897522 ]), + 'right_gaze_origin': array([-3.22089863, -3.48751998, 0.15258943]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1126861572265625, + 'right_pupil_posn': array([ 0.33085084, -0.07375121]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.25051426887512207, + 'throttle_input': 0.0, + 'timestamp': 498.0987107679248, + 'timestamp_carla': 498099, + 'timestamp_device': 4236312, + 'timestamp_stream': 498.0987107679248, + 'transform': [array([ 1.20134649e+01, -1.05658522e+01, -4.77830879e-03]), + array([-1.13517735e-02, -5.16979256e+01, 7.03124925e-02])]} +{'AngularVelocity': array([-0.00189731, -0.02933264, 0.74932539]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17758013308048248, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34519386, -21.48048782, 0.17732185]), + 'Rotation': array([-0.07140962, -2.40228295, -0.00360107]), + 'Velocity': array([-1.25136030e+00, 5.08999005e-02, 1.04003423e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.95934916, 16.07453537, 3.31643271]), + 'camera_rotation': array([-1.41516042, 12.93989658, 0.32669431]), + 'current_gear_input': False, + 'focus_actor_dist': 4238.8359375, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1512.25476074, 2206.12109375, 346.04150391]), + 'frame': 15228, + 'frame_number': 15228, + 'framesequence': 58491, + 'gaze_dir': array([0.91603088, 0.39426422, 0.07017517]), + 'gaze_origin': array([-3.14570332, -0.35230714, 0.14305039]), + 'gaze_valid': True, + 'gaze_vergence': 130.5653076171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90744019, 0.414505 , 0.06861877]), + 'left_gaze_origin': array([-3.05421162, 2.82154393, 0.14007874]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2281951904296875, + 'left_pupil_posn': array([ 0.416067 , -0.01133227]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8967596292495728, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92462158, 0.37402344, 0.07173157]), + 'right_gaze_origin': array([-3.23719501, -3.52615833, 0.14602204]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0093994140625, + 'right_pupil_posn': array([ 0.38507962, -0.08606458]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.24150517582893372, + 'throttle_input': 0.0, + 'timestamp': 498.13380796834826, + 'timestamp_carla': 498134, + 'timestamp_device': 4236346, + 'timestamp_stream': 498.13380796834826, + 'transform': [array([ 1.20897779e+01, -1.05920334e+01, -6.60230638e-03]), + array([-2.32226420e-02, -5.19636765e+01, 7.60497972e-02])]} +{'AngularVelocity': array([-1.11076725e-03, 4.00381116e-03, 2.95902846e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.40135479, -21.47801208, 0.17704619]), + 'Rotation': array([-0.01553185, -2.41748047, -0.00369263]), + 'Velocity': array([ 1.34831518e-01, -5.72352950e-03, 9.17196230e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.00701523, 16.22113228, 3.38352656]), + 'camera_rotation': array([-1.00960433, 13.78910446, 0.42345211]), + 'current_gear_input': False, + 'focus_actor_dist': 4214.69580078125, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1219.36279297, 2278. , 324.6081543 ]), + 'frame': 15229, + 'frame_number': 15229, + 'framesequence': 58495, + 'gaze_dir': array([0.92098236, 0.38365936, 0.06580353]), + 'gaze_origin': array([-3.14060378, -0.34162447, 0.14234772]), + 'gaze_valid': True, + 'gaze_vergence': 172.77330017089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91578674, 0.39717102, 0.05976868]), + 'left_gaze_origin': array([-3.04857802, 2.83834553, 0.13851166]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3126068115234375, + 'left_pupil_posn': array([ 0.40262067, -0.0113492 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8860265016555786, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92617798, 0.37014771, 0.07183838]), + 'right_gaze_origin': array([-3.23262954, -3.52159452, 0.14618377]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2283935546875, + 'right_pupil_posn': array([ 0.37462437, -0.08791065]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.23093967139720917, + 'throttle_input': 0.0, + 'timestamp': 498.1660566665232, + 'timestamp_carla': 498166, + 'timestamp_device': 4236379, + 'timestamp_stream': 498.1660566665232, + 'transform': [array([ 1.21576767e+01, -1.06140308e+01, -7.36698136e-03]), + array([-2.70338878e-02, -5.21953697e+01, 7.84606934e-02])]} +{'AngularVelocity': array([5.81548922e-03, 1.41262949e-01, 1.28573563e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34916496, -21.48022652, 0.17711373]), + 'Rotation': array([-0.04434159, -2.41748095, -0.00360107]), + 'Velocity': array([ 0.28620926, -0.01218159, -0.00051807]), + 'brake_input': 0.0, + 'camera_location': array([-7.0757494 , 16.37477303, 3.44790339]), + 'camera_rotation': array([-0.58794266, 14.70798492, 0.5684635 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4231.6455078125, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1233.30566406, 2295.15576172, 331.66918945]), + 'frame': 15230, + 'frame_number': 15230, + 'framesequence': 58499, + 'gaze_dir': array([0.92604065, 0.37253571, 0.05960846]), + 'gaze_origin': array([-3.13646507, -0.33196869, 0.14194641]), + 'gaze_valid': True, + 'gaze_vergence': 281.8918762207031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92268372, 0.38136292, 0.05654907]), + 'left_gaze_origin': array([-3.04432845, 2.84868789, 0.13787536]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2333526611328125, + 'left_pupil_posn': array([ 0.39292645, -0.01384962]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8974006772041321, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92939758, 0.3637085 , 0.06266785]), + 'right_gaze_origin': array([-3.22860098, -3.51262546, 0.14601746]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09259033203125, + 'right_pupil_posn': array([ 0.36218154, -0.08757281]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.22205878794193268, + 'throttle_input': 0.0, + 'timestamp': 498.1993451677263, + 'timestamp_carla': 498200, + 'timestamp_device': 4236412, + 'timestamp_stream': 498.1993451677263, + 'transform': [array([ 1.22255964e+01, -1.06347532e+01, -7.74209946e-03]), + array([-2.82974727e-02, -5.24225349e+01, 7.95287937e-02])]} +{'AngularVelocity': array([ 0.00222603, 0.04834958, -0.00037253]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.28635597, -21.48289299, 0.17717452]), + 'Rotation': array([-0.06396472, -2.41748047, -0.00360107]), + 'Velocity': array([ 2.75371134e-01, -1.17234821e-02, -2.67496100e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.10213852, 16.5366478 , 3.48990011]), + 'camera_rotation': array([-0.17822695, 15.65966415, 0.67947286]), + 'current_gear_input': False, + 'focus_actor_dist': 4222.62451171875, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1234.60766602, 2288.90893555, 329.94088745]), + 'frame': 15231, + 'frame_number': 15231, + 'framesequence': 58503, + 'gaze_dir': array([0.93534851, 0.34692383, 0.06850433]), + 'gaze_origin': array([-3.13224721, -0.32183915, 0.14098816]), + 'gaze_valid': True, + 'gaze_vergence': 346.7841796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93327332, 0.35324097, 0.06486511]), + 'left_gaze_origin': array([-3.03976464, 2.86218739, 0.1374878 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.268646240234375, + 'left_pupil_posn': array([ 0.37503695, -0.00936997]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9064040780067444, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93742371, 0.34060669, 0.07214355]), + 'right_gaze_origin': array([-3.22473001, -3.50586557, 0.14448853]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.178131103515625, + 'right_pupil_posn': array([ 0.34665406, -0.08410382]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2114749699831009, + 'throttle_input': 0.0, + 'timestamp': 498.23268746584654, + 'timestamp_carla': 498233, + 'timestamp_device': 4236446, + 'timestamp_stream': 498.23268746584654, + 'transform': [array([ 1.22913752e+01, -1.06533422e+01, -7.90432002e-03]), + array([-2.86253206e-02, -5.26373177e+01, 7.98644871e-02])]} +{'AngularVelocity': array([0.00330093, 0.02914139, 0.01474419]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1873062402009964, + 'FR_Wheel_Angle': 0.18772585690021515, + 'Location': array([ -7.22583008, -21.48547554, 0.17717151]), + 'Rotation': array([-0.07065147, -2.41690063, -0.00366211]), + 'Velocity': array([ 2.31129110e-01, -9.41741187e-03, 9.38987723e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.16250753, 16.70730209, 3.52747989]), + 'camera_rotation': array([ 0.1117897 , 16.61557579, 0.86115319]), + 'current_gear_input': False, + 'focus_actor_dist': 4164.27734375, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1279.29016113, 2215.58203125, 389.99316406]), + 'frame': 15232, + 'frame_number': 15232, + 'framesequence': 58507, + 'gaze_dir': array([0.93943024, 0.33672333, 0.06240082]), + 'gaze_origin': array([-3.12843251, -0.31114885, 0.1417595 ]), + 'gaze_valid': True, + 'gaze_vergence': 222.8916778564453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93540955, 0.34855652, 0.05905151]), + 'left_gaze_origin': array([-3.03588271, 2.87271738, 0.13642883]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3332366943359375, + 'left_pupil_posn': array([ 0.36178052, -0.01135027]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8988178968429565, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94345093, 0.32489014, 0.06575012]), + 'right_gaze_origin': array([-3.22098255, -3.49501514, 0.14709015]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.110931396484375, + 'right_pupil_posn': array([ 0.33697951, -0.08354151]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.20169682800769806, + 'throttle_input': 0.0, + 'timestamp': 498.26578606665134, + 'timestamp_carla': 498266, + 'timestamp_device': 4236479, + 'timestamp_stream': 498.26578606665134, + 'transform': [array([ 1.23545294e+01, -1.06697292e+01, -7.96401966e-03]), + array([-2.86253206e-02, -5.28384018e+01, 7.98644945e-02])]} +{'AngularVelocity': array([ 0.00030322, -0.00822189, 0.00950815]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18775002658367157, + 'FR_Wheel_Angle': 0.18812809884548187, + 'Location': array([ -7.18999386, -21.48694038, 0.17716019]), + 'Rotation': array([-0.07583559, -2.41491675, -0.00369263]), + 'Velocity': array([ 1.04408249e-01, -4.14608978e-03, -7.42816919e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.23696899, 16.8772831 , 3.57401371]), + 'camera_rotation': array([ 0.29199058, 17.53404617, 0.98307067]), + 'current_gear_input': False, + 'focus_actor_dist': 4144.0087890625, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1269.04138184, 2201.61962891, 379.24627686]), + 'frame': 15233, + 'frame_number': 15233, + 'framesequence': 58511, + 'gaze_dir': array([0.94415283, 0.32363892, 0.06014252]), + 'gaze_origin': array([-3.12572575, -0.30314866, 0.14132462]), + 'gaze_valid': True, + 'gaze_vergence': 208.37794494628906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93968201, 0.33596802, 0.06391907]), + 'left_gaze_origin': array([-3.032866 , 2.88086414, 0.13462068]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3536834716796875, + 'left_pupil_posn': array([ 0.35113728, -0.01487112]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9140787720680237, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94862366, 0.31130981, 0.05636597]), + 'right_gaze_origin': array([-3.21858525, -3.48716164, 0.14802857]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.289703369140625, + 'right_pupil_posn': array([ 0.32681119, -0.08016813]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.19146093726158142, + 'throttle_input': 0.0, + 'timestamp': 498.29859156534076, + 'timestamp_carla': 498299, + 'timestamp_device': 4236512, + 'timestamp_stream': 498.29859156534076, + 'transform': [array([ 1.24150429e+01, -1.06839113e+01, -7.98253994e-03]), + array([-2.85296980e-02, -5.30257874e+01, 7.97424242e-02])]} +{'AngularVelocity': array([ 5.12875413e-05, -1.69999562e-02, 6.23938721e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1879296451807022, + 'FR_Wheel_Angle': 0.1882895678281784, + 'Location': array([ -7.17399693, -21.48758698, 0.17714413]), + 'Rotation': array([-0.07431246, -2.41390991, -0.00369263]), + 'Velocity': array([ 0.05173467, -0.00200954, 0.0002754 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.29509926, 17.00779533, 3.60268831]), + 'camera_rotation': array([ 0.46148854, 18.30854416, 1.01255226]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.41064453125, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1284.67211914, 2225.82275391, 381.65731812]), + 'frame': 15234, + 'frame_number': 15234, + 'framesequence': 58515, + 'gaze_dir': array([0.94766235, 0.31387329, 0.0561676 ]), + 'gaze_origin': array([-3.12356353, -0.30031741, 0.13951646]), + 'gaze_valid': True, + 'gaze_vergence': 159.7165069580078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9440155 , 0.32646179, 0.04736328]), + 'left_gaze_origin': array([-3.03132486, 2.88503575, 0.1330841 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.35699462890625, + 'left_pupil_posn': array([ 0.34464681, -0.01247132]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9315047264099121, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9513092 , 0.30128479, 0.06497192]), + 'right_gaze_origin': array([-3.21580219, -3.48567057, 0.1459488 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2039642333984375, + 'right_pupil_posn': array([ 0.3218286 , -0.08684087]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1818659007549286, + 'throttle_input': 0.0, + 'timestamp': 498.3321112655103, + 'timestamp_carla': 498333, + 'timestamp_device': 4236546, + 'timestamp_stream': 498.3321112655103, + 'transform': [array([ 1.24748201e+01, -1.06963816e+01, -7.98744150e-03]), + array([-2.83862650e-02, -5.32055893e+01, 7.95593113e-02])]} +{'AngularVelocity': array([-0.00046194, 0.00334025, -0.00141408]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18802566826343536, + 'FR_Wheel_Angle': 0.1883491724729538, + 'Location': array([ -7.16691589, -21.48787308, 0.17716633]), + 'Rotation': array([-0.07302155, -2.41348267, -0.00369263]), + 'Velocity': array([ 1.72886383e-02, -7.39153998e-04, -4.91762148e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.35178471, 17.13931656, 3.61828351]), + 'camera_rotation': array([ 0.67431039, 19.01869774, 0.90352565]), + 'current_gear_input': False, + 'focus_actor_dist': 4146.685546875, + 'focus_actor_name': 'TreePine_862', + 'focus_actor_pt': array([1282.87463379, 2207.41625977, 375.659729 ]), + 'frame': 15235, + 'frame_number': 15235, + 'framesequence': 58519, + 'gaze_dir': array([0.90103912, 0.43170929, 0.03753662]), + 'gaze_origin': array([-3.1521554 , -0.37661517, 0.13229142]), + 'gaze_valid': True, + 'gaze_vergence': 155.4468231201172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.89344788, 0.44778442, 0.03474426]), + 'left_gaze_origin': array([-3.06090713, 2.79719114, 0.12789002]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4678802490234375, + 'left_pupil_posn': array([ 0.44847345, -0.03342164]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8469671010971069, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.90863037, 0.41563416, 0.04032898]), + 'right_gaze_origin': array([-3.24340391, -3.55042148, 0.13669282]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.214813232421875, + 'right_pupil_posn': array([ 0.41493106, -0.10774565]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.17130039632320404, + 'throttle_input': 0.0, + 'timestamp': 498.3655334673822, + 'timestamp_carla': 498366, + 'timestamp_device': 4236579, + 'timestamp_stream': 498.3655334673822, + 'transform': [array([ 1.25323610e+01, -1.07067165e+01, -7.98791833e-03]), + array([-2.82974727e-02, -5.33729172e+01, 7.93762133e-02])]} +{'AngularVelocity': array([ 0.00017452, -0.01262863, 0.00390867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18806971609592438, + 'FR_Wheel_Angle': 0.1883881539106369, + 'Location': array([ -7.16428518, -21.48797607, 0.17710826]), + 'Rotation': array([-0.07222924, -2.41330004, -0.00369263]), + 'Velocity': array([ 0.01140566, -0.00036323, -0.00077303]), + 'brake_input': 0.0, + 'camera_location': array([-7.39025021, 17.27423096, 3.62364697]), + 'camera_rotation': array([ 0.81274468, 19.70465469, 0.78731906]), + 'current_gear_input': False, + 'focus_actor_dist': 7323.84619140625, + 'focus_actor_name': 'TreePine_845', + 'focus_actor_pt': array([1210.30322266, 5473.41259766, 435.53070068]), + 'frame': 15236, + 'frame_number': 15236, + 'framesequence': 58523, + 'gaze_dir': array([0.9023819 , 0.42915344, 0.03314209]), + 'gaze_origin': array([-3.1499126 , -0.37340015, 0.13615189]), + 'gaze_valid': True, + 'gaze_vergence': 132.10594177246094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.89427185, 0.44670105, 0.02659607]), + 'left_gaze_origin': array([-3.05808282, 2.80270696, 0.12978822]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4990081787109375, + 'left_pupil_posn': array([ 0.44288838, -0.03177643]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8414451479911804, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91049194, 0.41160583, 0.03968811]), + 'right_gaze_origin': array([-3.24174213, -3.54950714, 0.14251557]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.335723876953125, + 'right_pupil_posn': array([ 0.41380513, -0.10607767]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.16121098399162292, + 'throttle_input': 0.0, + 'timestamp': 498.39916556701064, + 'timestamp_carla': 498400, + 'timestamp_device': 4236612, + 'timestamp_stream': 498.39916556701064, + 'transform': [array([ 1.25882568e+01, -1.07150640e+01, -7.98789971e-03]), + array([-2.82018501e-02, -5.35297089e+01, 7.91931003e-02])]} +{'AngularVelocity': array([ 0.00024995, -0.00898425, 0.00260018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18806861340999603, + 'FR_Wheel_Angle': 0.18838059902191162, + 'Location': array([ -7.16438532, -21.48796272, 0.17714924]), + 'Rotation': array([-0.07222924, -2.41330004, -0.00369263]), + 'Velocity': array([-0.00200931, 0.00016825, -0.00012067]), + 'brake_input': 0.0, + 'camera_location': array([-7.40261269, 17.38558769, 3.63400221]), + 'camera_rotation': array([ 0.93878895, 20.38551903, 0.70124418]), + 'current_gear_input': False, + 'focus_actor_dist': 8262.607421875, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1303.86132812, 6411.02148438, 463.21560669]), + 'frame': 15237, + 'frame_number': 15237, + 'framesequence': 58527, + 'gaze_dir': array([0.90545654, 0.42293549, 0.03045654]), + 'gaze_origin': array([-3.14708281, -0.36642537, 0.13773727]), + 'gaze_valid': True, + 'gaze_vergence': 139.5790252685547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.89900208, 0.43737793, 0.02182007]), + 'left_gaze_origin': array([-3.05558658, 2.81092834, 0.13249207]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.36651611328125, + 'left_pupil_posn': array([ 0.43581712, -0.02957428]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8593593835830688, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91191101, 0.40849304, 0.03909302]), + 'right_gaze_origin': array([-3.2385788 , -3.54377937, 0.14298248]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.25372314453125, + 'right_pupil_posn': array([ 0.40579212, -0.10649073]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1508835256099701, + 'throttle_input': 0.0, + 'timestamp': 498.43237616866827, + 'timestamp_carla': 498433, + 'timestamp_device': 4236646, + 'timestamp_stream': 498.43237616866827, + 'transform': [array([ 1.26415071e+01, -1.07212868e+01, -7.98265450e-03]), + array([-2.81403773e-02, -5.36732254e+01, 7.90099949e-02])]} +{'AngularVelocity': array([-0.00041249, 0.00609302, -0.00391345]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18803921341896057, + 'FR_Wheel_Angle': 0.18835125863552094, + 'Location': array([ -7.16668177, -21.48786736, 0.17713772]), + 'Rotation': array([-0.07202434, -2.41330004, -0.00369263]), + 'Velocity': array([-1.99617017e-02, 7.74060783e-04, -5.92851611e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.40584421, 17.49388313, 3.67202663]), + 'camera_rotation': array([ 1.16153502, 21.09771347, 0.65420669]), + 'current_gear_input': False, + 'focus_actor_dist': 8268.861328125, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1290.72143555, 6422.03662109, 464.09503174]), + 'frame': 15238, + 'frame_number': 15238, + 'framesequence': 58531, + 'gaze_dir': array([0.91890717, 0.39198303, 0.03768921]), + 'gaze_origin': array([-3.14245558, -0.36042941, 0.13470764]), + 'gaze_valid': True, + 'gaze_vergence': 125.79402160644531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91020203, 0.41271973, 0.03425598]), + 'left_gaze_origin': array([-3.04964757, 2.8182435 , 0.12904206]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3894195556640625, + 'left_pupil_posn': array([ 0.41689479, -0.02860188]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8659300804138184, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9276123 , 0.37124634, 0.04112244]), + 'right_gaze_origin': array([-3.23526335, -3.53910255, 0.14037323]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0789031982421875, + 'right_pupil_posn': array([ 0.39299464, -0.1020447 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.14117863774299622, + 'throttle_input': 0.0, + 'timestamp': 498.4653469659388, + 'timestamp_carla': 498466, + 'timestamp_device': 4236679, + 'timestamp_stream': 498.4653469659388, + 'transform': [array([ 1.26925497e+01, -1.07255783e+01, -7.98259676e-03]), + array([-2.80789062e-02, -5.38051186e+01, 7.88574144e-02])]} +{'AngularVelocity': array([-0.00027186, 0.00636653, -0.00401286]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18798716366291046, + 'FR_Wheel_Angle': 0.18835516273975372, + 'Location': array([ -7.17019844, -21.48771286, 0.17710324]), + 'Rotation': array([-0.0719014 , -2.41330004, -0.00369263]), + 'Velocity': array([-0.02636508, 0.00103596, 0.00085901]), + 'brake_input': 0.0, + 'camera_location': array([-7.4038887 , 17.58946419, 3.68070316]), + 'camera_rotation': array([ 1.29792023, 21.81664276, 0.68718046]), + 'current_gear_input': False, + 'focus_actor_dist': 7029.80859375, + 'focus_actor_name': 'TreePine_845', + 'focus_actor_pt': array([1284.13427734, 5169.50195312, 497.44018555]), + 'frame': 15239, + 'frame_number': 15239, + 'framesequence': 58535, + 'gaze_dir': array([0.92307281, 0.38175201, 0.04218292]), + 'gaze_origin': array([-3.1394031 , -0.35343629, 0.1367096 ]), + 'gaze_valid': True, + 'gaze_vergence': 131.38795471191406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91564941, 0.39884949, 0.04995728]), + 'left_gaze_origin': array([-3.04632735, 2.82538152, 0.12960815]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.42755126953125, + 'left_pupil_posn': array([ 0.40920401, -0.02985334]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8804180026054382, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93049622, 0.36465454, 0.03440857]), + 'right_gaze_origin': array([-3.23247838, -3.53225422, 0.14381103]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.219482421875, + 'right_pupil_posn': array([ 0.3828088 , -0.09300017]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.13174840807914734, + 'throttle_input': 0.0, + 'timestamp': 498.4986769668758, + 'timestamp_carla': 498499, + 'timestamp_device': 4236712, + 'timestamp_stream': 498.4986769668758, + 'transform': [array([ 1.27423811e+01, -1.07281036e+01, -7.99280126e-03]), + array([-2.79832836e-02, -5.39282837e+01, 7.87353292e-02])]} +{'AngularVelocity': array([-0.00023859, 0.00822871, -0.00485412]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18795165419578552, + 'FR_Wheel_Angle': 0.18828707933425903, + 'Location': array([ -7.17562056, -21.48748398, 0.17713016]), + 'Rotation': array([-0.0719014 , -2.41330004, -0.00369263]), + 'Velocity': array([-0.03678389, 0.00145742, 0.00022739]), + 'brake_input': 0.0, + 'camera_location': array([-7.37805939, 17.67427444, 3.67576671]), + 'camera_rotation': array([ 1.33467352, 22.4506321 , 0.67043793]), + 'current_gear_input': False, + 'focus_actor_dist': 7165.587890625, + 'focus_actor_name': 'TreePine_845', + 'focus_actor_pt': array([1314.19555664, 5302.14550781, 552.19104004]), + 'frame': 15240, + 'frame_number': 15240, + 'framesequence': 58539, + 'gaze_dir': array([0.9286499 , 0.36817169, 0.03954315]), + 'gaze_origin': array([-3.13620853, -0.34877092, 0.13673936]), + 'gaze_valid': True, + 'gaze_vergence': 130.50283813476562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92126465, 0.38746643, 0.03335571]), + 'left_gaze_origin': array([-3.04381132, 2.83127451, 0.13038178]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5187835693359375, + 'left_pupil_posn': array([ 0.39927447, -0.02454197]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8869428038597107, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93603516, 0.34887695, 0.04573059]), + 'right_gaze_origin': array([-3.22860599, -3.52881622, 0.14309694]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3001861572265625, + 'right_pupil_posn': array([ 0.37545812, -0.09853673]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.12136600911617279, + 'throttle_input': 0.0, + 'timestamp': 498.53171026706696, + 'timestamp_carla': 498532, + 'timestamp_device': 4236746, + 'timestamp_stream': 498.53171026706696, + 'transform': [array([ 1.27899733e+01, -1.07286901e+01, -8.00130796e-03]), + array([-2.79491320e-02, -5.40398102e+01, 7.86132887e-02])]} +{'AngularVelocity': array([ 0.00026489, -0.01012591, 0.00148603]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18795228004455566, + 'FR_Wheel_Angle': 0.18832877278327942, + 'Location': array([ -7.18215561, -21.4872036 , 0.17708717]), + 'Rotation': array([-0.07162136, -2.41336083, -0.00369263]), + 'Velocity': array([-0.02737733, 0.00121111, 0.00041776]), + 'brake_input': 0.0, + 'camera_location': array([-7.34733391, 17.7705555 , 3.68126512]), + 'camera_rotation': array([ 1.47970581, 23.08555984, 0.54737931]), + 'current_gear_input': False, + 'focus_actor_dist': 7160.19189453125, + 'focus_actor_name': 'TreePine_845', + 'focus_actor_pt': array([1358.0625 , 5292.76953125, 540.05511475]), + 'frame': 15241, + 'frame_number': 15241, + 'framesequence': 58543, + 'gaze_dir': array([0.90997314, 0.41316986, 0.0245285 ]), + 'gaze_origin': array([-3.14386082, -0.36364213, 0.1337883 ]), + 'gaze_valid': True, + 'gaze_vergence': 110.50608825683594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90034485, 0.43481445, 0.01719666]), + 'left_gaze_origin': array([-3.05100894, 2.81611204, 0.12693177]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.502197265625, + 'left_pupil_posn': array([ 0.42551327, -0.03456509]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8762965798377991, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91960144, 0.39152527, 0.03186035]), + 'right_gaze_origin': array([-3.23671293, -3.54339623, 0.14064485]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2805633544921875, + 'right_pupil_posn': array([ 0.40425909, -0.10943711]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11204565316438675, + 'throttle_input': 0.0, + 'timestamp': 498.5656500682235, + 'timestamp_carla': 498566, + 'timestamp_device': 4236779, + 'timestamp_stream': 498.5656500682235, + 'transform': [array([ 1.28371515e+01, -1.07275143e+01, -8.01698677e-03]), + array([-2.78603397e-02, -5.41445274e+01, 7.84912258e-02])]} +{'AngularVelocity': array([ 0.00036943, -0.00839745, 0.0014904 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18794319033622742, + 'FR_Wheel_Angle': 0.18831825256347656, + 'Location': array([ -7.18861818, -21.48693848, 0.17709976]), + 'Rotation': array([-0.07162136, -2.41336083, -0.00369263]), + 'Velocity': array([-0.02985849, 0.00131903, -0.00017825]), + 'brake_input': 0.0, + 'camera_location': array([-7.31828785, 17.87111092, 3.658427 ]), + 'camera_rotation': array([ 1.53419018, 23.84278297, 0.36354509]), + 'current_gear_input': False, + 'focus_actor_dist': 13194.181640625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 1637.18383789, 11347.421875 , 711.69140625]), + 'frame': 15242, + 'frame_number': 15242, + 'framesequence': 58547, + 'gaze_dir': array([0.91815186, 0.39405823, 0.03323364]), + 'gaze_origin': array([-3.14111185, -0.3620888 , 0.13782044]), + 'gaze_valid': True, + 'gaze_vergence': 105.61597442626953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91004944, 0.41389465, 0.02177429]), + 'left_gaze_origin': array([-3.04936552, 2.81613016, 0.13137206]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4192352294921875, + 'left_pupil_posn': array([ 0.41943121, -0.02588284]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.880327045917511, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92625427, 0.3742218 , 0.04469299]), + 'right_gaze_origin': array([-3.23285842, -3.54030776, 0.14426881]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.33172607421875, + 'right_pupil_posn': array([ 0.39393938, -0.10356855]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10115054994821548, + 'throttle_input': 0.0, + 'timestamp': 498.5977056659758, + 'timestamp_carla': 498598, + 'timestamp_device': 4236812, + 'timestamp_stream': 498.5977056659758, + 'transform': [array([ 1.28799896e+01, -1.07244940e+01, -8.02433025e-03]), + array([-2.78876610e-02, -5.42331009e+01, 7.83996582e-02])]} +{'AngularVelocity': array([ 0.00032661, -0.01128327, 0.00157694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18792743980884552, + 'FR_Wheel_Angle': 0.18830549716949463, + 'Location': array([ -7.19535398, -21.48666191, 0.17709476]), + 'Rotation': array([-0.07162136, -2.41336083, -0.00369263]), + 'Velocity': array([-0.03357776, 0.00147743, -0.0009479 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.27338791, 17.96554947, 3.59745526]), + 'camera_rotation': array([ 1.36730814, 24.5870285 , 0.15573491]), + 'current_gear_input': False, + 'focus_actor_dist': 8443.109375, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1180.39074707, 6619.79248047, 599.67779541]), + 'frame': 15243, + 'frame_number': 15243, + 'framesequence': 58551, + 'gaze_dir': array([0.92532349, 0.37714386, 0.0334549 ]), + 'gaze_origin': array([-3.13690186, -0.35512087, 0.14044954]), + 'gaze_valid': True, + 'gaze_vergence': 147.87078857421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91789246, 0.39530945, 0.03417969]), + 'left_gaze_origin': array([-3.04387522, 2.82369852, 0.13379671]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.50469970703125, + 'left_pupil_posn': array([ 0.40812421, -0.02708352]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8863251805305481, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93275452, 0.35897827, 0.0327301 ]), + 'right_gaze_origin': array([-3.22992873, -3.53394032, 0.14710237]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1608734130859375, + 'right_pupil_posn': array([ 0.38229573, -0.09584367]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09150059521198273, + 'throttle_input': 0.0, + 'timestamp': 498.6316747665405, + 'timestamp_carla': 498632, + 'timestamp_device': 4236846, + 'timestamp_stream': 498.6316747665405, + 'transform': [array([ 1.29237080e+01, -1.07195139e+01, -8.05124268e-03]), + array([-2.78876610e-02, -5.43172722e+01, 7.83081129e-02])]} +{'AngularVelocity': array([ 0.00032728, -0.00990606, 0.00111891]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18791954219341278, + 'FR_Wheel_Angle': 0.18829798698425293, + 'Location': array([ -7.20241261, -21.48636436, 0.17712058]), + 'Rotation': array([-0.07168283, -2.41345263, -0.00369263]), + 'Velocity': array([-0.03616523, 0.0015803 , -0.00072074]), + 'brake_input': 0.0, + 'camera_location': array([-7.20409489, 18.055233 , 3.58163357]), + 'camera_rotation': array([ 1.30705225, 25.28386879, -0.07364582]), + 'current_gear_input': False, + 'focus_actor_dist': 8314.30859375, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1226.47619629, 6487.23095703, 585.79833984]), + 'frame': 15244, + 'frame_number': 15244, + 'framesequence': 58555, + 'gaze_dir': array([0.92818451, 0.3706665 , 0.0253067 ]), + 'gaze_origin': array([-3.13330412, -0.34844896, 0.14089356]), + 'gaze_valid': True, + 'gaze_vergence': 142.2549591064453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.920578 , 0.38967896, 0.02610779]), + 'left_gaze_origin': array([-3.0398407 , 2.8326447 , 0.13465118]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4723968505859375, + 'left_pupil_posn': array([ 0.39893997, -0.02849185]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8858416676521301, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93579102, 0.35165405, 0.02450562]), + 'right_gaze_origin': array([-3.22676706, -3.52954268, 0.14713593]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1643829345703125, + 'right_pupil_posn': array([ 0.37666607, -0.09802902]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08133793622255325, + 'throttle_input': 0.0, + 'timestamp': 498.66562996804714, + 'timestamp_carla': 498666, + 'timestamp_device': 4236879, + 'timestamp_stream': 498.66562996804714, + 'transform': [array([ 1.29657173e+01, -1.07127218e+01, -8.07409268e-03]), + array([-2.78876610e-02, -5.43915558e+01, 7.82165602e-02])]} +{'AngularVelocity': array([0.00083504, 0.01819351, 0.01856311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18779197335243225, + 'FR_Wheel_Angle': 0.1880427449941635, + 'Location': array([ -7.21167517, -21.48598671, 0.17722651]), + 'Rotation': array([-0.07317864, -2.41333032, -0.00369263]), + 'Velocity': array([-0.08293194, 0.0034514 , 0.00103396]), + 'brake_input': 0.0, + 'camera_location': array([-7.13873482, 18.14237785, 3.57101059]), + 'camera_rotation': array([ 1.23775315, 26.04289055, -0.22702745]), + 'current_gear_input': False, + 'focus_actor_dist': 8238.216796875, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1192.50830078, 6420.86621094, 519.51556396]), + 'frame': 15245, + 'frame_number': 15245, + 'framesequence': 58559, + 'gaze_dir': array([0.93217468, 0.36045074, 0.02721405]), + 'gaze_origin': array([-3.12919092, -0.33640367, 0.14206086]), + 'gaze_valid': True, + 'gaze_vergence': 150.53887939453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92520142, 0.37858582, 0.02597046]), + 'left_gaze_origin': array([-3.03560972, 2.84652114, 0.13510439]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.677520751953125, + 'left_pupil_posn': array([ 0.38565123, -0.02597272]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8978790044784546, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93914795, 0.34231567, 0.02845764]), + 'right_gaze_origin': array([-3.2227726 , -3.51932836, 0.14901733]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2712249755859375, + 'right_pupil_posn': array([ 0.36503756, -0.0955714 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07135838270187378, + 'throttle_input': 0.0, + 'timestamp': 498.6987312659621, + 'timestamp_carla': 498699, + 'timestamp_device': 4236912, + 'timestamp_stream': 498.6987312659621, + 'transform': [array([ 1.30050545e+01, -1.07043467e+01, -8.08732957e-03]), + array([-2.78876610e-02, -5.44544868e+01, 7.81250149e-02])]} +{'AngularVelocity': array([-2.84156733e-04, -1.99600868e-02, 4.38663125e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18698878586292267, + 'FR_Wheel_Angle': 0.18727512657642365, + 'Location': array([ -7.26508856, -21.48381805, 0.17728309]), + 'Rotation': array([-0.08215351, -2.41687036, -0.003479 ]), + 'Velocity': array([-0.33881855, 0.01366072, 0.00062393]), + 'brake_input': 0.0, + 'camera_location': array([-7.05466557, 18.2059269 , 3.54109168]), + 'camera_rotation': array([ 1.09675753, 26.67326355, -0.39548051]), + 'current_gear_input': False, + 'focus_actor_dist': 8282.3154296875, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1193.99084473, 6467.04394531, 536.67352295]), + 'frame': 15246, + 'frame_number': 15246, + 'framesequence': 58563, + 'gaze_dir': array([0.93444824, 0.35492706, 0.02481079]), + 'gaze_origin': array([-3.1250422 , -0.32748261, 0.14951554]), + 'gaze_valid': True, + 'gaze_vergence': 183.80361938476562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93063354, 0.36549377, 0.01737976]), + 'left_gaze_origin': array([-3.03170037, 2.85802794, 0.1429535 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6403961181640625, + 'left_pupil_posn': array([ 0.37828588, -0.01871765]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8874871134757996, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93826294, 0.34436035, 0.03224182]), + 'right_gaze_origin': array([-3.21838403, -3.5129931 , 0.15607758]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3886871337890625, + 'right_pupil_posn': array([ 0.35530162, -0.09252393]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06112247332930565, + 'throttle_input': 0.0, + 'timestamp': 498.7319131679833, + 'timestamp_carla': 498732, + 'timestamp_device': 4236946, + 'timestamp_stream': 498.7319131679833, + 'transform': [array([ 1.30428944e+01, -1.06942043e+01, -8.10319837e-03]), + array([-2.79218126e-02, -5.45082054e+01, 7.80334547e-02])]} +{'AngularVelocity': array([ 0.0097803 , -0.03037369, 0.73779434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1865663230419159, + 'FR_Wheel_Angle': 0.18690453469753265, + 'Location': array([ -7.36981964, -21.47958946, 0.17733794]), + 'Rotation': array([-0.07788464, -2.41171288, -0.00357056]), + 'Velocity': array([-4.57077980e-01, 2.04168502e-02, 4.45232377e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.94644737, 18.22903061, 3.52209473]), + 'camera_rotation': array([ 1.00271952, 26.9309845 , -0.66597897]), + 'current_gear_input': False, + 'focus_actor_dist': 13311.1337890625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 1776.80114746, 11461.07128906, 730.81622314]), + 'frame': 15247, + 'frame_number': 15247, + 'framesequence': 58567, + 'gaze_dir': array([0.93710327, 0.34741974, 0.02882385]), + 'gaze_origin': array([-3.12402964, -0.32526931, 0.14718857]), + 'gaze_valid': True, + 'gaze_vergence': 157.54515075683594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93223572, 0.36120605, 0.0209198 ]), + 'left_gaze_origin': array([-3.03002644, 2.86084151, 0.14030915]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.594970703125, + 'left_pupil_posn': array([ 0.37249517, -0.01829112]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8990111351013184, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94197083, 0.33363342, 0.03672791]), + 'right_gaze_origin': array([-3.21803308, -3.51137996, 0.15406799]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.429840087890625, + 'right_pupil_posn': array([ 0.35257685, -0.09242809]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05176549777388573, + 'throttle_input': 0.0, + 'timestamp': 498.7644495666027, + 'timestamp_carla': 498765, + 'timestamp_device': 4236979, + 'timestamp_stream': 498.7644495666027, + 'transform': [array([ 1.30785255e+01, -1.06826801e+01, -8.12057499e-03]), + array([-2.79218126e-02, -5.45523567e+01, 7.79724121e-02])]} +{'AngularVelocity': array([-1.27965992e-04, -2.21966654e-02, 2.23149389e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.38468409, -21.47904015, 0.17715313]), + 'Rotation': array([-0.04117238, -2.40051293, -0.00350952]), + 'Velocity': array([ 3.39373171e-01, -1.43863345e-02, -1.21359823e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.83564138, 18.2395401 , 3.5173192 ]), + 'camera_rotation': array([ 1.16445839, 27.08239746, -0.93688428]), + 'current_gear_input': False, + 'focus_actor_dist': 8286.69140625, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1207.26635742, 6474.74169922, 540.86505127]), + 'frame': 15248, + 'frame_number': 15248, + 'framesequence': 58571, + 'gaze_dir': array([0.9382782 , 0.34468842, 0.02290344]), + 'gaze_origin': array([-3.12256336, -0.32224122, 0.14525528]), + 'gaze_valid': True, + 'gaze_vergence': 169.4536590576172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93309021, 0.35919189, 0.0171814 ]), + 'left_gaze_origin': array([-3.02777719, 2.86418772, 0.13872071]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6468963623046875, + 'left_pupil_posn': array([ 0.36882579, -0.02163804]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8965997695922852, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94346619, 0.33018494, 0.02862549]), + 'right_gaze_origin': array([-3.21734953, -3.50867033, 0.15178986]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4306640625, + 'right_pupil_posn': array([ 0.34988368, -0.09505558]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04231696575880051, + 'throttle_input': 0.0, + 'timestamp': 498.79886956885457, + 'timestamp_carla': 498799, + 'timestamp_device': 4237012, + 'timestamp_stream': 498.79886956885457, + 'transform': [array([ 1.31147270e+01, -1.06689463e+01, -8.15481134e-03]), + array([-2.78603397e-02, -5.45906754e+01, 7.79113770e-02])]} +{'AngularVelocity': array([ 3.45186866e-03, 8.60686302e-02, -1.28896545e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18807806074619293, + 'FR_Wheel_Angle': 0.18842124938964844, + 'Location': array([ -7.3412571 , -21.48091698, 0.17730542]), + 'Rotation': array([-0.07510476, -2.39447021, -0.00350952]), + 'Velocity': array([ 6.19848870e-05, 1.06217940e-05, -1.43943078e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.72652054, 18.22961426, 3.48350239]), + 'camera_rotation': array([ 1.07647192, 27.08672905, -1.24281728]), + 'current_gear_input': False, + 'focus_actor_dist': 8243.2939453125, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1214.31860352, 6433.30664062, 525.07897949]), + 'frame': 15249, + 'frame_number': 15249, + 'framesequence': 58575, + 'gaze_dir': array([0.93621063, 0.35025787, 0.02627563]), + 'gaze_origin': array([-3.12299061, -0.32548526, 0.15046006]), + 'gaze_valid': True, + 'gaze_vergence': 190.68890380859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93370056, 0.3575592 , 0.01844788]), + 'left_gaze_origin': array([-3.02867913, 2.8612566 , 0.14674836]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6269989013671875, + 'left_pupil_posn': array([ 0.37543344, -0.01494825]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8998926281929016, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9387207 , 0.34295654, 0.03410339]), + 'right_gaze_origin': array([-3.21730232, -3.51222706, 0.15417175]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4034881591796875, + 'right_pupil_posn': array([ 0.35175705, -0.09297717]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03259376809000969, + 'throttle_input': 0.0, + 'timestamp': 498.8321460671723, + 'timestamp_carla': 498832, + 'timestamp_device': 4237046, + 'timestamp_stream': 498.8321460671723, + 'transform': [array([ 1.31482353e+01, -1.06540670e+01, -8.17430485e-03]), + array([-2.78261900e-02, -5.46191101e+01, 7.78503418e-02])]} +{'AngularVelocity': array([-6.61404047e-04, -1.42981261e-02, 3.46696356e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1880781501531601, + 'FR_Wheel_Angle': 0.18842124938964844, + 'Location': array([ -7.34124804, -21.48091698, 0.17729618]), + 'Rotation': array([-0.07394362, -2.39447093, -0.00350952]), + 'Velocity': array([-6.98467693e-06, 1.36010458e-05, 3.07897899e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.61209774, 18.18234634, 3.41851211]), + 'camera_rotation': array([ 0.92243749, 26.85808563, -1.4441781 ]), + 'current_gear_input': False, + 'focus_actor_dist': 13314.505859375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 1793.91271973, 11465.95996094, 814.92303467]), + 'frame': 15250, + 'frame_number': 15250, + 'framesequence': 58579, + 'gaze_dir': array([0.93587494, 0.35138702, 0.02098083]), + 'gaze_origin': array([-3.12319446, -0.33275756, 0.1534401 ]), + 'gaze_valid': True, + 'gaze_vergence': 191.80511474609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93139648, 0.3636322 , 0.01538086]), + 'left_gaze_origin': array([-3.02765226, 2.85455942, 0.15030213]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.743255615234375, + 'left_pupil_posn': array([ 0.37861288, -0.01484692]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.891936182975769, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94035339, 0.33914185, 0.02658081]), + 'right_gaze_origin': array([-3.21873641, -3.52007437, 0.15657808]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.454193115234375, + 'right_pupil_posn': array([ 0.35963786, -0.09290528]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.022797327488660812, + 'throttle_input': 0.035706110298633575, + 'timestamp': 498.86382126808167, + 'timestamp_carla': 498864, + 'timestamp_device': 4237079, + 'timestamp_stream': 498.86382126808167, + 'transform': [array([ 1.31785908e+01, -1.06394911e+01, -8.35185964e-03]), + array([-2.77647171e-02, -5.46415558e+01, 7.85522461e-02])]} +{'AngularVelocity': array([-2.27017721e-04, -4.08424437e-03, 1.15502269e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18807817995548248, + 'FR_Wheel_Angle': 0.18842127919197083, + 'Location': array([ -7.34123516, -21.48091698, 0.17724888]), + 'Rotation': array([-0.07208581, -2.39447069, -0.00350952]), + 'Velocity': array([9.02451589e-08, 1.36453473e-05, 7.54474240e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.51263285, 18.12999725, 3.39630389]), + 'camera_rotation': array([ 0.82402813, 26.75509071, -1.32152736]), + 'current_gear_input': False, + 'focus_actor_dist': 8459.5458984375, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1233.40551758, 6654.77636719, 512.2923584 ]), + 'frame': 15251, + 'frame_number': 15251, + 'framesequence': 58583, + 'gaze_dir': array([0.93610382, 0.35050201, 0.02432251]), + 'gaze_origin': array([-3.1234498 , -0.33445206, 0.15217896]), + 'gaze_valid': True, + 'gaze_vergence': 177.91995239257812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93106079, 0.36434937, 0.01901245]), + 'left_gaze_origin': array([-3.0278244 , 2.85220361, 0.14712372]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6279144287109375, + 'left_pupil_posn': array([ 0.37940609, -0.01586378]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.885367751121521, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94114685, 0.33665466, 0.02963257]), + 'right_gaze_origin': array([-3.2190752 , -3.52110744, 0.15723421]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4352569580078125, + 'right_pupil_posn': array([ 0.36065722, -0.0912869 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014154484495520592, + 'throttle_input': 0.0952315554022789, + 'timestamp': 498.8973176665604, + 'timestamp_carla': 498898, + 'timestamp_device': 4237112, + 'timestamp_stream': 498.8973176665604, + 'transform': [array([ 1.32083969e+01, -1.06227093e+01, -8.62153992e-03]), + array([-2.76212841e-02, -5.46553040e+01, 7.95898438e-02])]} +{'AngularVelocity': array([ 1.29664713e-05, -1.03496865e-03, -1.32829437e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16380731761455536, + 'FR_Wheel_Angle': 0.16406749188899994, + 'Location': array([ -7.3412323 , -21.48091698, 0.17723605]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([ 9.40607833e-07, 3.96059477e-07, -5.16718836e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.45491123, 18.09378815, 3.38925195]), + 'camera_rotation': array([ 0.80405664, 26.67991829, -1.36708999]), + 'current_gear_input': False, + 'focus_actor_dist': 8191.76611328125, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1228.07080078, 6387.69824219, 508.21850586]), + 'frame': 15252, + 'frame_number': 15252, + 'framesequence': 58587, + 'gaze_dir': array([0.93508911, 0.35295105, 0.02562714]), + 'gaze_origin': array([-3.12446761, -0.33718491, 0.1492981 ]), + 'gaze_valid': True, + 'gaze_vergence': 141.6170196533203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92921448, 0.36909485, 0.01760864]), + 'left_gaze_origin': array([-3.0289278 , 2.84842992, 0.14437714]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5331573486328125, + 'left_pupil_posn': array([ 0.3822006 , -0.01645482]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8790591359138489, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94096375, 0.33680725, 0.03364563]), + 'right_gaze_origin': array([-3.22000766, -3.52279997, 0.15421906]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3216552734375, + 'right_pupil_posn': array([ 0.36376202, -0.09407961]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.005731376353651285, + 'throttle_input': 0.15475699305534363, + 'timestamp': 498.93242256715894, + 'timestamp_carla': 498933, + 'timestamp_device': 4237146, + 'timestamp_stream': 498.93242256715894, + 'transform': [array([ 1.32378254e+01, -1.06040697e+01, -8.82614125e-03]), + array([-2.74368692e-02, -5.46621780e+01, 8.02917555e-02])]} +{'AngularVelocity': array([-7.53629720e-05, -2.39411893e-04, -1.17496265e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16380730271339417, + 'FR_Wheel_Angle': 0.16406749188899994, + 'Location': array([ -7.34123087, -21.48091698, 0.17731918]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([2.67105179e-06, 6.34951277e-07, 3.48260393e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.41030264, 18.05174637, 3.35688853]), + 'camera_rotation': array([ 0.56821024, 26.44563866, -1.55056167]), + 'current_gear_input': False, + 'focus_actor_dist': 7409.85791015625, + 'focus_actor_name': 'TreePine_845', + 'focus_actor_pt': array([1122.79833984, 5615.58789062, 482.35736084]), + 'frame': 15253, + 'frame_number': 15253, + 'framesequence': 58591, + 'gaze_dir': array([0.93261719, 0.35918427, 0.02763367]), + 'gaze_origin': array([-3.12540913, -0.3418808 , 0.15191269]), + 'gaze_valid': True, + 'gaze_vergence': 137.7267303466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92578125, 0.37741089, 0.02148438]), + 'left_gaze_origin': array([-3.02897215, 2.84323597, 0.14874421]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7175140380859375, + 'left_pupil_posn': array([ 0.38722718, -0.01369321]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8832836747169495, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93945312, 0.34095764, 0.03378296]), + 'right_gaze_origin': array([-3.2218461 , -3.52699757, 0.15508118]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.342529296875, + 'right_pupil_posn': array([ 0.36995935, -0.09278452]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0012634663144126534, + 'throttle_input': 0.21824978291988373, + 'timestamp': 498.9649747684598, + 'timestamp_carla': 498965, + 'timestamp_device': 4237179, + 'timestamp_stream': 498.9649747684598, + 'transform': [array([ 1.32639666e+01, -1.05859766e+01, -8.86255223e-03]), + array([-2.72183027e-02, -5.46634102e+01, 8.03833082e-02])]} +{'AngularVelocity': array([ 4.58638460e-05, -6.08963237e-05, -1.24919752e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34123087, -21.48091698, 0.17729141]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([ 2.35478387e-06, 5.02777993e-07, -2.59910757e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.36878777, 18.00874901, 3.28640652]), + 'camera_rotation': array([ 0.25074989, 26.24275017, -1.57209182]), + 'current_gear_input': False, + 'focus_actor_dist': 8205.3076171875, + 'focus_actor_name': 'TreePine_15', + 'focus_actor_pt': array([1208.42102051, 6408.27490234, 514.66540527]), + 'frame': 15254, + 'frame_number': 15254, + 'framesequence': 58595, + 'gaze_dir': array([ 0.93432617, 0.35600281, -0.00632477]), + 'gaze_origin': array([-3.12852263, -0.35023269, 0.1262169 ]), + 'gaze_valid': True, + 'gaze_vergence': 182.3393096923828, + 'handbrake_input': False, + 'left_eye_openness': 0.9923582077026367, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.92909241, 0.36979675, -0.00184631]), + 'left_gaze_origin': array([-3.03348851, 2.82986021, 0.11962433]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.578369140625, + 'left_pupil_posn': array([ 0.39703429, -0.0495286 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8738913536071777, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.93955994, 0.34220886, -0.01080322]), + 'right_gaze_origin': array([-3.22355676, -3.53032541, 0.13280945]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4896240234375, + 'right_pupil_posn': array([ 0.36953151, -0.1162895 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005200354382395744, + 'throttle_input': 0.27775996923446655, + 'timestamp': 498.99910186603665, + 'timestamp_carla': 498999, + 'timestamp_device': 4237212, + 'timestamp_stream': 498.99910186603665, + 'transform': [array([ 1.32907419e+01, -1.05660181e+01, -8.71862378e-03]), + array([-2.67948303e-02, -5.46600494e+01, 7.96203613e-02])]} +{'AngularVelocity': array([ 5.28951132e-05, -1.74436955e-05, -1.25263687e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34123087, -21.48091698, 0.17728664]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([ 2.38273287e-06, 4.70566448e-07, -2.28341924e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.34546661, 17.99396515, 3.23582244]), + 'camera_rotation': array([ 3.64049058e-03, 2.61310291e+01, -1.57352006e+00]), + 'current_gear_input': False, + 'focus_actor_dist': 5202.8056640625, + 'focus_actor_name': 'BP_RepSpline76', + 'focus_actor_pt': array([ 868.98468018, 3435.47460938, 173.13076782]), + 'frame': 15255, + 'frame_number': 15255, + 'framesequence': 58599, + 'gaze_dir': array([ 0.91149902, 0.38791656, -0.13600159]), + 'gaze_origin': array([-3.14320612, -0.36130068, 0.05214768]), + 'gaze_valid': True, + 'gaze_vergence': 217.8509521484375, + 'handbrake_input': False, + 'left_eye_openness': 0.8883621692657471, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.90661621, 0.40002441, -0.13420105]), + 'left_gaze_origin': array([-3.05247211, 2.80168009, 0.04502716]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.651580810546875, + 'left_pupil_posn': array([ 0.42956853, -0.15025115]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.83204185962677, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.91638184, 0.37580872, -0.13780212]), + 'right_gaze_origin': array([-3.23394012, -3.5242815 , 0.05926819]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.29083251953125, + 'right_pupil_posn': array([ 0.37665439, -0.21883821]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004339732229709625, + 'throttle_input': 0.32538339495658875, + 'timestamp': 499.03207136690617, + 'timestamp_carla': 499032, + 'timestamp_device': 4237246, + 'timestamp_stream': 499.03207136690617, + 'transform': [array([ 1.33169842e+01, -1.05463781e+01, -8.36906396e-03]), + array([-2.60298494e-02, -5.46566582e+01, 7.80334473e-02])]} +{'AngularVelocity': array([-4.90571474e-05, 1.70420426e-05, -1.21901403e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34123087, -21.48091698, 0.1772866 ]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([2.59946091e-06, 5.92572576e-07, 1.42226301e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.32950544, 18.00194359, 3.16362405]), + 'camera_rotation': array([-0.44665337, 26.1008091 , -1.65926898]), + 'current_gear_input': False, + 'focus_actor_dist': 967.732177734375, + 'focus_actor_name': 'Road_Sidewalk_Town05_207', + 'focus_actor_pt': array([ 275.45751953, -764.0826416 , 15.23427582]), + 'frame': 15256, + 'frame_number': 15256, + 'framesequence': 58603, + 'gaze_dir': array([ 0.91230011, 0.3885498 , -0.12908936]), + 'gaze_origin': array([-3.14450216, -0.37289277, 0.05749512]), + 'gaze_valid': True, + 'gaze_vergence': 349.7606201171875, + 'handbrake_input': False, + 'left_eye_openness': 0.858591616153717, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.90917969, 0.39508057, -0.13153076]), + 'left_gaze_origin': array([-3.0528748 , 2.79508686, 0.05295868]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.712554931640625, + 'left_pupil_posn': array([ 0.4364481 , -0.14120162]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8159363865852356, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.91542053, 0.38201904, -0.12664795]), + 'right_gaze_origin': array([-3.23612976, -3.54087234, 0.06203156]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3250274658203125, + 'right_pupil_posn': array([ 0.38684785, -0.21621919]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0021240883506834507, + 'throttle_input': 0.3610894978046417, + 'timestamp': 499.06415846571326, + 'timestamp_carla': 499064, + 'timestamp_device': 4237279, + 'timestamp_stream': 499.06415846571326, + 'transform': [array([ 1.33434181e+01, -1.05266304e+01, -7.82520231e-03]), + array([-2.50531323e-02, -5.46532326e+01, 7.56225586e-02])]} +{'AngularVelocity': array([-6.04215020e-05, 3.99125111e-06, -1.27446647e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34123087, -21.48091698, 0.17728911]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([ 2.02414572e-06, 5.11839175e-07, -3.64467007e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.35164595, 18.04236031, 3.08417869]), + 'camera_rotation': array([-1.09346545, 26.18375015, -1.54131985]), + 'current_gear_input': False, + 'focus_actor_dist': 970.1595458984375, + 'focus_actor_name': 'Road_Sidewalk_Town05_207', + 'focus_actor_pt': array([ 278.20336914, -759.72052002, 15.23511505]), + 'frame': 15257, + 'frame_number': 15257, + 'framesequence': 58607, + 'gaze_dir': array([ 0.91429901, 0.38768768, -0.11663818]), + 'gaze_origin': array([-3.1435535 , -0.37814182, 0.06548692]), + 'gaze_valid': True, + 'gaze_vergence': 253.1209716796875, + 'handbrake_input': False, + 'left_eye_openness': 0.8683487176895142, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.91027832, 0.39790344, -0.11419678]), + 'left_gaze_origin': array([-3.05016184, 2.79339457, 0.06146393]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6268768310546875, + 'left_pupil_posn': array([ 0.43586946, -0.13189387]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8211298584938049, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9183197 , 0.37747192, -0.11907959]), + 'right_gaze_origin': array([-3.23694468, -3.54967833, 0.06950989]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.322601318359375, + 'right_pupil_posn': array([ 0.39431095, -0.2049197 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.3809414803981781, + 'timestamp': 499.0976033657789, + 'timestamp_carla': 499098, + 'timestamp_device': 4237312, + 'timestamp_stream': 499.0976033657789, + 'transform': [array([ 1.33727474e+01, -1.05054188e+01, -7.07748393e-03]), + array([-2.40149442e-02, -5.46518059e+01, 7.22351000e-02])]} +{'AngularVelocity': array([-5.29790523e-05, 3.83891984e-06, -1.25787519e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34123087, -21.48091698, 0.17726749]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([2.39564110e-06, 5.57962892e-07, 2.55484156e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.3666296 , 18.11447906, 3.0298388 ]), + 'camera_rotation': array([-1.55717373, 26.44872093, -1.3608079 ]), + 'current_gear_input': False, + 'focus_actor_dist': 980.0342407226562, + 'focus_actor_name': 'Road_Sidewalk_Town05_207', + 'focus_actor_pt': array([ 281.89093018, -747.89373779, 15.23738861]), + 'frame': 15258, + 'frame_number': 15258, + 'framesequence': 58611, + 'gaze_dir': array([ 0.91671753, 0.38316345, -0.11239624]), + 'gaze_origin': array([-3.14269185, -0.375898 , 0.06417618]), + 'gaze_valid': True, + 'gaze_vergence': 228.2462158203125, + 'handbrake_input': False, + 'left_eye_openness': 0.8816484808921814, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9119873 , 0.39485168, -0.11114502]), + 'left_gaze_origin': array([-3.04855657, 2.79845452, 0.06036377]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6279449462890625, + 'left_pupil_posn': array([ 0.43014848, -0.13006365]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8109905123710632, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.92144775, 0.37147522, -0.11364746]), + 'right_gaze_origin': array([-3.23682737, -3.55025053, 0.06798859]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.314117431640625, + 'right_pupil_posn': array([ 0.39363444, -0.20466137]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0005859553930349648, + 'throttle_input': 0.400778204202652, + 'timestamp': 499.13104216754436, + 'timestamp_carla': 499131, + 'timestamp_device': 4237346, + 'timestamp_stream': 499.13104216754436, + 'transform': [array([ 1.34038038e+01, -1.04835300e+01, -6.34759897e-03]), + array([-2.31338497e-02, -5.46522331e+01, 6.89086914e-02])]} +{'AngularVelocity': array([ 6.48817222e-05, -1.12956684e-06, -1.25276774e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34123087, -21.48091698, 0.17728412]), + 'Rotation': array([-0.07196287, -2.39447069, -0.00350952]), + 'Velocity': array([2.43223258e-06, 4.65211912e-07, 1.96140572e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.43550539, 18.23557663, 2.97885776]), + 'camera_rotation': array([-1.88270056, 26.9825573 , -1.33061635]), + 'current_gear_input': False, + 'focus_actor_dist': 945.389892578125, + 'focus_actor_name': 'Road_Sidewalk_Town05_207', + 'focus_actor_pt': array([ 282.07785034, -780.57501221, 15.23113251]), + 'frame': 15259, + 'frame_number': 15259, + 'framesequence': 58615, + 'gaze_dir': array([ 0.91847992, 0.38321686, -0.09621429]), + 'gaze_origin': array([-3.13989043, -0.36667559, 0.06749725]), + 'gaze_valid': True, + 'gaze_vergence': 177.4349822998047, + 'handbrake_input': False, + 'left_eye_openness': 0.8829540610313416, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.91215515, 0.39819336, -0.09693909]), + 'left_gaze_origin': array([-3.04453588, 2.81134963, 0.06372986]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.646026611328125, + 'left_pupil_posn': array([ 0.41964734, -0.1204282 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.831537663936615, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.92480469, 0.36824036, -0.0954895 ]), + 'right_gaze_origin': array([-3.23524475, -3.54470086, 0.07126465]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4580230712890625, + 'right_pupil_posn': array([ 0.39060748, -0.19715393]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00021973327966406941, + 'throttle_input': 0.4126802384853363, + 'timestamp': 499.165999468416, + 'timestamp_carla': 499166, + 'timestamp_device': 4237379, + 'timestamp_stream': 499.165999468416, + 'transform': [array([ 1.34378290e+01, -1.04594955e+01, -5.70020685e-03]), + array([-2.24918108e-02, -5.46525269e+01, 6.58569261e-02])]} + diff --git a/PythonAPI/data/trials/trial11.txt b/PythonAPI/data/trials/trial11.txt new file mode 100644 index 0000000..6882c42 --- /dev/null +++ b/PythonAPI/data/trials/trial11.txt @@ -0,0 +1,12596 @@ +{'AngularVelocity': array([3.04664845e-05, 1.11243298e-05, 1.06329589e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.99927211, -29.94470215, 0.17134807]), + 'Rotation': array([-1.34281516e-02, 9.18620605e+01, -6.29272386e-02]), + 'Velocity': array([ 5.41218560e-06, 1.01963522e-07, -2.78494204e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.01949501, 4.76162624, 2.02444744]), + 'camera_rotation': array([ -5.17965317, -35.55191803, -6.76672316]), + 'current_gear_input': False, + 'focus_actor_dist': 725.9010009765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST14', + 'focus_actor_pt': array([ 320.71124268, -2446.10351562, 147.92823792]), + 'frame': 17837, + 'frame_number': 17837, + 'framesequence': 68307, + 'gaze_dir': array([ 0.98674011, -0.11972809, 0.10927582]), + 'gaze_origin': array([-3.24565363, 0.07004929, 0.15892868]), + 'gaze_valid': True, + 'gaze_vergence': 266.2464904785156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98654175, -0.11634827, 0.11476135]), + 'left_gaze_origin': array([-3.28034544, 3.27185059, 0.20234071]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9675750732421875, + 'left_pupil_posn': array([-0.06718642, 0.00790268]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98693848, -0.12310791, 0.10379028]), + 'right_gaze_origin': array([-3.2109623 , -3.13175201, 0.11551666]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8554840087890625, + 'right_pupil_posn': array([-0.07822198, -0.07518351]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 579.9121505655348, + 'timestamp_carla': 579912, + 'timestamp_device': 23161, + 'timestamp_stream': 579.9121505655348, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.80028138e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-2.35076586e-05, -3.33331263e-05, 9.91760044e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.99927211, -29.94470215, 0.17131282]), + 'Rotation': array([-1.34281516e-02, 9.18620605e+01, -6.29272386e-02]), + 'Velocity': array([7.18760293e-06, 1.30093412e-07, 1.33054063e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.98665905, 5.0134387 , 2.10714078]), + 'camera_rotation': array([ -4.79678679, -34.72393417, -6.52327061]), + 'current_gear_input': False, + 'focus_actor_dist': 707.5048217773438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST14', + 'focus_actor_pt': array([ 303.93481445, -2456.00927734, 139.41899109]), + 'frame': 17838, + 'frame_number': 17838, + 'framesequence': 68310, + 'gaze_dir': array([ 0.98994446, -0.05078125, 0.13044739]), + 'gaze_origin': array([-3.12284184, 0.01383667, 0.1260498 ]), + 'gaze_valid': True, + 'gaze_vergence': 138.5561981201172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98948669, -0.03352356, 0.140625 ]), + 'left_gaze_origin': array([-3.10508728, 3.22070789, 0.15783691]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8891143798828125, + 'left_pupil_posn': array([-0.01157641, 0.01528472]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99040222, -0.06803894, 0.12026978]), + 'right_gaze_origin': array([-3.14059639, -3.19303465, 0.0942627 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8862457275390625, + 'right_pupil_posn': array([-0.00834674, -0.06806576]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 579.9350727684796, + 'timestamp_carla': 579935, + 'timestamp_device': 23186, + 'timestamp_stream': 579.9350727684796, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.79463570e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-2.53504659e-05, -3.99511227e-05, 1.15918347e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.99927211, -29.94470215, 0.17124531]), + 'Rotation': array([-1.34281516e-02, 9.18620605e+01, -6.29272386e-02]), + 'Velocity': array([ 5.13183886e-06, 1.40865993e-07, -1.53988556e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.9805069 , 5.2712326 , 2.21867537]), + 'camera_rotation': array([ -4.35074139, -34.08826065, -6.44087124]), + 'current_gear_input': False, + 'focus_actor_dist': 7584.8134765625, + 'focus_actor_name': 'SM_Mall3_455', + 'focus_actor_pt': array([4356.95507812, 3095.85766602, 438.16967773]), + 'frame': 17839, + 'frame_number': 17839, + 'framesequence': 68312, + 'gaze_dir': array([0.49401855, 0.04743195, 0.06072998]), + 'gaze_origin': array([-3.25974894, -0.09499589, 0.17325288]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.8318641185760498, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98803711, 0.09486389, 0.12145996]), + 'left_gaze_origin': array([-3.25663304, 3.1072681 , 0.21241762]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.7454715371131897, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.26286483, -3.29725957, 0.13408814]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7694091796875, + 'right_pupil_posn': array([ 0.11045718, -0.07102132]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 579.9574002660811, + 'timestamp_carla': 579958, + 'timestamp_device': 23202, + 'timestamp_stream': 579.9574002660811, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.79463570e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 3.10397809e-05, -2.35840366e-06, 1.14183995e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.99927211, -29.94470215, 0.17127585]), + 'Rotation': array([-1.34281516e-02, 9.18620605e+01, -6.29272386e-02]), + 'Velocity': array([5.57187013e-06, 9.92015714e-08, 1.61445729e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.98094654, 5.5292244 , 2.34253764]), + 'camera_rotation': array([ -3.76422644, -33.36887741, -6.35306644]), + 'current_gear_input': False, + 'focus_actor_dist': 9994.6923828125, + 'focus_actor_name': 'Veg_Tree_Cypress_Big3', + 'focus_actor_pt': array([4459.859375 , 5856.140625 , 689.02709961]), + 'frame': 17840, + 'frame_number': 17840, + 'framesequence': 68315, + 'gaze_dir': array([ 0., -0., 0.]), + 'gaze_origin': array([-3.16560388, -0.16244888, 0.14682694]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.7245348691940308, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([-3.11266661, 3.04074717, 0.17412721]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5918663144111633, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.21854091, -3.36564493, 0.11952667]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 579.9794346652925, + 'timestamp_carla': 579980, + 'timestamp_device': 23227, + 'timestamp_stream': 579.9794346652925, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.79635213e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-4.35869470e-06, 1.90316896e-05, 1.08018285e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.99927211, -29.94470215, 0.17134918]), + 'Rotation': array([-1.34281516e-02, 9.18620605e+01, -6.29272386e-02]), + 'Velocity': array([6.00563362e-06, 1.23937426e-07, 3.78846627e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.97589874, 5.80587959, 2.48386717]), + 'camera_rotation': array([ -3.1392982 , -32.50378418, -6.14186239]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ -163.10177612, -2987.9519043 , 136.77044678]), + 'frame': 17841, + 'frame_number': 17841, + 'framesequence': 68318, + 'gaze_dir': array([ 0., -0., 0.]), + 'gaze_origin': array([-3.19152403, -0.220533 , 0.07507935]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.671400249004364, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([-3.15003347, 2.99920511, 0.04035034]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5201379656791687, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.23301411, -3.44027138, 0.10980836]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.001188468188, + 'timestamp_carla': 580002, + 'timestamp_device': 23252, + 'timestamp_stream': 580.001188468188, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.79909860e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-2.33887276e-05, -3.80549900e-05, 1.12785747e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.99927211, -29.94470215, 0.17131755]), + 'Rotation': array([-1.34281516e-02, 9.18620605e+01, -6.29272386e-02]), + 'Velocity': array([ 5.14694466e-06, 1.39779942e-07, -2.37900866e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.96351767, 6.12772369, 2.61730552]), + 'camera_rotation': array([ -2.44302201, -31.36792946, -5.76767492]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ -163.31071472, -2988.03222656, 136.80247498]), + 'frame': 17842, + 'frame_number': 17842, + 'framesequence': 68321, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.45765116810798645, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.26622176, -3.50585365, 0.10021515]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.0249498672783, + 'timestamp_carla': 580025, + 'timestamp_device': 23277, + 'timestamp_stream': 580.0249498672783, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.78727359e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.04328483, -0.00144193, 0.72286415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.0868854522705078, + 'FR_Wheel_Angle': 1.2650315761566162, + 'Location': array([ -1.9992094 , -29.94524574, 0.1713158 ]), + 'Rotation': array([-1.40428683e-02, 9.18663025e+01, -6.28356859e-02]), + 'Velocity': array([ 1.55020575e-03, -3.36172730e-02, -7.55596120e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.95115423, 6.50891685, 2.72890472]), + 'camera_rotation': array([ -1.9379226 , -29.85335922, -5.38470507]), + 'current_gear_input': False, + 'focus_actor_dist': 729.30859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST14', + 'focus_actor_pt': array([ 196.62742615, -2351.03930664, 105.05871582]), + 'frame': 17843, + 'frame_number': 17843, + 'framesequence': 68324, + 'gaze_dir': array([ 0., -0., 0.]), + 'gaze_origin': array([-3.22290206, -0.34301758, 0.12600937]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.6561758518218994, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([-3.1733613 , 2.84514785, 0.15353547]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.4622800350189209, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.27244282, -3.531183 , 0.09848328]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8922271728515625, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.0534183681011, + 'timestamp_carla': 580054, + 'timestamp_device': 23302, + 'timestamp_stream': 580.0534183681011, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.73520242e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-2.60638539e-02, -1.15587107e-04, 7.38981187e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.4297847747802734, + 'FR_Wheel_Angle': 2.816009521484375, + 'Location': array([ -1.99893606, -29.94765091, 0.17131087]), + 'Rotation': array([-1.33666797e-02, 9.18686447e+01, -6.28356859e-02]), + 'Velocity': array([ 0.00154995, -0.02022221, -0.0001279 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.94050312, 6.96481609, 2.79394293]), + 'camera_rotation': array([ -1.60891247, -27.8483696 , -5.00811625]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ -163.78503418, -2988.18237305, 137.02359009]), + 'frame': 17844, + 'frame_number': 17844, + 'framesequence': 68326, + 'gaze_dir': array([0.45811462, 0.19843292, 0.02736664]), + 'gaze_origin': array([-3.22164774, -0.33597186, 0.12278367]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.7024916410446167, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91622925, 0.39686584, 0.05473328]), + 'left_gaze_origin': array([-3.1732223 , 2.8518784 , 0.14620057]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5421679019927979, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.27007318, -3.52382207, 0.09936676]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9982147216796875, + 'right_pupil_posn': array([ 0.37823391, -0.12874615]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.0735452659428, + 'timestamp_carla': 580074, + 'timestamp_device': 23319, + 'timestamp_stream': 580.0735452659428, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76503361e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([0.08641661, 0.02881856, 0.7705313 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.692638397216797, + 'FR_Wheel_Angle': 5.28313684463501, + 'Location': array([ -1.99994063, -29.92946625, 0.1712714 ]), + 'Rotation': array([-4.76064160e-03, 9.18945312e+01, -6.44531250e-02]), + 'Velocity': array([-1.92804467e-02, 2.31481090e-01, -1.05724335e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.92900896, 7.42422724, 2.87417555]), + 'camera_rotation': array([ -1.20252991, -25.86802292, -4.59736872]), + 'current_gear_input': False, + 'focus_actor_dist': 18530.888671875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 787.86883545, 15481.234375 , 1306.08728027]), + 'frame': 17845, + 'frame_number': 17845, + 'framesequence': 68329, + 'gaze_dir': array([0.46357727, 0.18668365, 0.01556396]), + 'gaze_origin': array([-3.21335673, -0.31983033, 0.11615448]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.7068988084793091, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92715454, 0.37336731, 0.03112793]), + 'left_gaze_origin': array([-3.1665225 , 2.87021947, 0.13425446]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1592864990234375, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5764485001564026, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.26019144, -3.5098803 , 0.09805451]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.061187744140625, + 'right_pupil_posn': array([ 0.35872924, -0.13512897]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.0969129651785, + 'timestamp_carla': 580097, + 'timestamp_device': 23344, + 'timestamp_stream': 580.0969129651785, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76892468e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([0.02792508, 0.02698569, 2.12282515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.6887125968933105, + 'FR_Wheel_Angle': 7.348718166351318, + 'Location': array([ -2.00837541, -29.82657623, 0.17121594]), + 'Rotation': array([ 7.54052866e-03, 9.21110687e+01, -6.78710863e-02]), + 'Velocity': array([-7.04033375e-02, 6.72319233e-01, 2.54187587e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.91995049, 7.86903954, 2.97218466]), + 'camera_rotation': array([ -0.69142681, -24.03091621, -3.98849654]), + 'current_gear_input': False, + 'focus_actor_dist': 13875.2705078125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 390.26223755, 10864.15332031, 708.37762451]), + 'frame': 17846, + 'frame_number': 17846, + 'framesequence': 68332, + 'gaze_dir': array([0.93643188, 0.34791565, 0.0446701 ]), + 'gaze_origin': array([-3.20099044, -0.2806496 , 0.11621857]), + 'gaze_valid': True, + 'gaze_vergence': 432.4599609375, + 'handbrake_input': False, + 'left_eye_openness': 0.7291401028633118, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93403625, 0.35429382, 0.04528809]), + 'left_gaze_origin': array([-3.15327311, 2.90936756, 0.12917481]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1558380126953125, + 'left_pupil_posn': array([ 0.34568119, -0.04541898]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.615906834602356, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93882751, 0.34153748, 0.04405212]), + 'right_gaze_origin': array([-3.24870753, -3.47066665, 0.10326234]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0139312744140625, + 'right_pupil_posn': array([ 0.32335782, -0.12341166]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.1191669665277, + 'timestamp_carla': 580120, + 'timestamp_device': 23369, + 'timestamp_stream': 580.1191669665277, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.77907144e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([0.08526165, 0.04492478, 3.67808533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.834433078765869, + 'FR_Wheel_Angle': 8.664944648742676, + 'Location': array([ -2.03202438, -29.59345627, 0.17118229]), + 'Rotation': array([ 1.78746041e-02, 9.27018890e+01, -7.26928562e-02]), + 'Velocity': array([-1.68222055e-01, 1.33244646e+00, 5.62643982e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.91055489, 8.2790823 , 3.0747335 ]), + 'camera_rotation': array([ -0.08651117, -22.44532394, -3.30349445]), + 'current_gear_input': False, + 'focus_actor_dist': 13953.0810546875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 325.74108887, 10933.37304688, 934.61895752]), + 'frame': 17847, + 'frame_number': 17847, + 'framesequence': 68335, + 'gaze_dir': array([0.94224548, 0.33312225, 0.03245544]), + 'gaze_origin': array([-3.18255639, -0.20892029, 0.11780014]), + 'gaze_valid': True, + 'gaze_vergence': 247.29673767089844, + 'handbrake_input': False, + 'left_eye_openness': 0.7829307913780212, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93841553, 0.34364319, 0.03556824]), + 'left_gaze_origin': array([-3.13573933, 2.98241425, 0.11701813]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.002532958984375, + 'left_pupil_posn': array([ 0.28761959, -0.0549773 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.725056529045105, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94607544, 0.32260132, 0.02934265]), + 'right_gaze_origin': array([-3.22937322, -3.40025496, 0.11858216]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0289764404296875, + 'right_pupil_posn': array([ 0.26912165, -0.11206722]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.1454286687076, + 'timestamp_carla': 580146, + 'timestamp_device': 23394, + 'timestamp_stream': 580.1454286687076, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.75549687e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([0.03445536, 0.0550677 , 6.34439087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.87540340423584, + 'FR_Wheel_Angle': 11.179144859313965, + 'Location': array([ -2.07282281, -29.27054214, 0.17118984]), + 'Rotation': array([ 2.23756991e-02, 9.36945496e+01, -7.98950195e-02]), + 'Velocity': array([-3.03660154e-01, 1.87061489e+00, 5.71737299e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.08596611, 8.73106956, 3.3168869 ]), + 'camera_rotation': array([ 1.27719748, -21.710495 , -2.41509604]), + 'current_gear_input': False, + 'focus_actor_dist': 13782.4443359375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 134.61961365, 10773.77050781, 824.81982422]), + 'frame': 17848, + 'frame_number': 17848, + 'framesequence': 68338, + 'gaze_dir': array([0.94957733, 0.31293488, 0.01441956]), + 'gaze_origin': array([-3.17342687, -0.16990358, 0.11001968]), + 'gaze_valid': True, + 'gaze_vergence': 248.8031005859375, + 'handbrake_input': False, + 'left_eye_openness': 0.8572597503662109, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94590759, 0.32415771, 0.0124054 ]), + 'left_gaze_origin': array([-3.12851882, 3.02399778, 0.10061494]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0594024658203125, + 'left_pupil_posn': array([ 0.25144863, -0.06844199]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.7827857136726379, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95324707, 0.30171204, 0.01643372]), + 'right_gaze_origin': array([-3.21833539, -3.36380482, 0.11942445]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0352935791015625, + 'right_pupil_posn': array([ 0.23611248, -0.116696 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.1720782667398, + 'timestamp_carla': 580172, + 'timestamp_device': 23419, + 'timestamp_stream': 580.1720782667398, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.73749161e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.03320255, -0.034013 , 8.59370136]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.71920394897461, + 'FR_Wheel_Angle': 10.529106140136719, + 'Location': array([ -2.16743255, -28.69687653, 0.17134899]), + 'Rotation': array([ 1.77653208e-02, 9.57654114e+01, -8.11157152e-02]), + 'Velocity': array([-4.72357392e-01, 2.34802556e+00, 5.25360112e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.23305988, 8.76819706, 3.4241116 ]), + 'camera_rotation': array([ 1.93634486, -22.67682457, -2.35038877]), + 'current_gear_input': False, + 'focus_actor_dist': 13751.61328125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 228.51574707, 10741.37304688, 803.78186035]), + 'frame': 17849, + 'frame_number': 17849, + 'framesequence': 68342, + 'gaze_dir': array([0.94985962, 0.31232452, 0.01409149]), + 'gaze_origin': array([-3.17988849, -0.1983925 , 0.09532319]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.8678621649742126, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95018005, 0.31140137, 0.0128479 ]), + 'left_gaze_origin': array([-3.13563085, 2.9948411 , 0.08852387]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.28271484375, + 'left_pupil_posn': array([ 0.27564192, -0.07896042]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.7980144023895264, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94953918, 0.31324768, 0.01533508]), + 'right_gaze_origin': array([-3.22414565, -3.39162612, 0.1021225 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0990447998046875, + 'right_pupil_posn': array([ 0.25094461, -0.12930906]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.2021229676902, + 'timestamp_carla': 580202, + 'timestamp_device': 23452, + 'timestamp_stream': 580.2021229676902, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76308808e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.0147818 , -0.04781587, 8.18614864]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.072611808776855, + 'FR_Wheel_Angle': 7.969624996185303, + 'Location': array([ -2.28326488, -28.0979805 , 0.17151417]), + 'Rotation': array([ 1.56479627e-02, 9.77214279e+01, -7.69042820e-02]), + 'Velocity': array([-5.94641387e-01, 2.71046138e+00, 4.93202184e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.35017109, 8.7582655 , 3.52288032]), + 'camera_rotation': array([ 2.56834221, -23.86494446, -2.4667356 ]), + 'current_gear_input': False, + 'focus_actor_dist': 14019.32421875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 478.06005859, 10991.79980469, 959.71783447]), + 'frame': 17850, + 'frame_number': 17850, + 'framesequence': 68345, + 'gaze_dir': array([0.94745636, 0.31951141, 0.00341797]), + 'gaze_origin': array([-3.19067311, -0.24593584, 0.08026734]), + 'gaze_valid': True, + 'gaze_vergence': 128.20864868164062, + 'handbrake_input': False, + 'left_eye_openness': 0.8788846731185913, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94464111, 0.32775879, 0.01475525]), + 'left_gaze_origin': array([-3.14311838, 2.94790816, 0.08190156]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2620086669921875, + 'left_pupil_posn': array([ 0.30739474, -0.09315038]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.81566321849823, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95027161, 0.31126404, -0.00791931]), + 'right_gaze_origin': array([-3.23822784, -3.43978 , 0.07863312]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.174041748046875, + 'right_pupil_posn': array([ 0.29099059, -0.14840472]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.2299768663943, + 'timestamp_carla': 580230, + 'timestamp_device': 23477, + 'timestamp_stream': 580.2299768663943, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.73234139e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.01982459, -0.09092823, 1.87824774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.752940058708191, + 'FR_Wheel_Angle': 0.8132272958755493, + 'Location': array([ -2.41118789, -27.42468262, 0.17167278]), + 'Rotation': array([ 1.16796233e-02, 9.89126358e+01, -5.31921312e-02]), + 'Velocity': array([-5.30300260e-01, 2.98378420e+00, 1.16909028e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.44851589, 8.79201698, 3.61318302]), + 'camera_rotation': array([ 3.14067101, -24.46267891, -2.59558487]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ 5690.71337891, 96663.5078125 , 6065.49609375]), + 'frame': 17851, + 'frame_number': 17851, + 'framesequence': 68349, + 'gaze_dir': array([9.47662354e-01, 3.18473816e-01, 2.05993652e-04]), + 'gaze_origin': array([-3.20346904, -0.29564285, 0.06267777]), + 'gaze_valid': True, + 'gaze_vergence': 132.65924072265625, + 'handbrake_input': False, + 'left_eye_openness': 0.8552352786064148, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94078064, 0.33895874, 0.00506592]), + 'left_gaze_origin': array([-3.15355849, 2.89686751, 0.07385712]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.194549560546875, + 'left_pupil_posn': array([ 0.33843291, -0.09914291]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8196828365325928, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95454407, 0.29798889, -0.00465393]), + 'right_gaze_origin': array([-3.25337982, -3.48815322, 0.05149841]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1612396240234375, + 'right_pupil_posn': array([ 0.32977295, -0.17431366]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005456709768623114, + 'throttle_input': 0.0, + 'timestamp': 580.2588413655758, + 'timestamp_carla': 580259, + 'timestamp_device': 23511, + 'timestamp_stream': 580.2588413655758, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.70369298e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.07118464, 0.00864907, -2.09389639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.4962053298950195, + 'FR_Wheel_Angle': -2.7331855297088623, + 'Location': array([ -2.51503038, -26.7373333 , 0.17192623]), + 'Rotation': array([-3.08724539e-03, 9.87446823e+01, -4.28771973e-02]), + 'Velocity': array([-3.78310770e-01, 2.89158750e+00, 1.25959399e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.59633446, 9.03207493, 3.70019555]), + 'camera_rotation': array([ 3.52825022, -23.79010201, -2.36283827]), + 'current_gear_input': False, + 'focus_actor_dist': 15288.5302734375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 900.10803223, 12228.89160156, 1149.65661621]), + 'frame': 17852, + 'frame_number': 17852, + 'framesequence': 68352, + 'gaze_dir': array([ 0.94933319, 0.31288147, -0.00518799]), + 'gaze_origin': array([-3.20368004, -0.30174333, 0.05949402]), + 'gaze_valid': True, + 'gaze_vergence': 104.65513610839844, + 'handbrake_input': False, + 'left_eye_openness': 0.8556879162788391, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94035339, 0.34007263, -0.00735474]), + 'left_gaze_origin': array([-3.15235138, 2.89156651, 0.07238312]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2475738525390625, + 'left_pupil_posn': array([ 0.33772445, -0.09894085]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8209384679794312, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95831299, 0.28569031, -0.00302124]), + 'right_gaze_origin': array([-3.25500822, -3.49505329, 0.04660492]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2161102294921875, + 'right_pupil_posn': array([ 0.33508503, -0.18256855]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00556657649576664, + 'throttle_input': 0.0, + 'timestamp': 580.2868080660701, + 'timestamp_carla': 580287, + 'timestamp_device': 23536, + 'timestamp_stream': 580.2868080660701, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.69751365e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.03135849, -0.00595586, -4.50872564]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.239977836608887, + 'FR_Wheel_Angle': -5.346947193145752, + 'Location': array([ -2.59191656, -26.08897591, 0.17209965]), + 'Rotation': array([-1.34281516e-02, 9.79415283e+01, -4.31213379e-02]), + 'Velocity': array([-2.41094455e-01, 2.67229939e+00, 6.07185357e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.63571644, 9.21060181, 3.68494511]), + 'camera_rotation': array([ 3.42643929, -22.81663132, -2.19373631]), + 'current_gear_input': False, + 'focus_actor_dist': 15266.1494140625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 804.51281738, 12213.11914062, 1142.35742188]), + 'frame': 17853, + 'frame_number': 17853, + 'framesequence': 68355, + 'gaze_dir': array([ 0.95167542, 0.30549622, -0.0216217 ]), + 'gaze_origin': array([-3.19685531, -0.2888962 , 0.06657944]), + 'gaze_valid': True, + 'gaze_vergence': 133.64236450195312, + 'handbrake_input': False, + 'left_eye_openness': 0.8698365092277527, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94500732, 0.32652283, -0.01791382]), + 'left_gaze_origin': array([-3.14544559, 2.90627599, 0.07815857]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.335968017578125, + 'left_pupil_posn': array([ 0.32667696, -0.10164714]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8229944109916687, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95834351, 0.2844696 , -0.02532959]), + 'right_gaze_origin': array([-3.24826527, -3.48406839, 0.05500031]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1581573486328125, + 'right_pupil_posn': array([ 0.3218832 , -0.17873216]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0056764427572488785, + 'throttle_input': 0.0, + 'timestamp': 580.3133820667863, + 'timestamp_carla': 580314, + 'timestamp_device': 23561, + 'timestamp_stream': 580.3133820667863, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.70865227e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.01305747, 0.03945243, -4.82611227]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.09229040145874, + 'FR_Wheel_Angle': -5.708333969116211, + 'Location': array([ -2.64153337, -25.49373817, 0.17219852]), + 'Rotation': array([-1.77653208e-02, 9.67858582e+01, -4.87670898e-02]), + 'Velocity': array([-1.46064714e-01, 2.42751384e+00, 1.71699518e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.65894127, 9.39018631, 3.66515017]), + 'camera_rotation': array([ 3.29091477, -21.78249931, -2.1723423 ]), + 'current_gear_input': False, + 'focus_actor_dist': 16106.1708984375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 706.14331055, 13075.92480469, 889.28637695]), + 'frame': 17854, + 'frame_number': 17854, + 'framesequence': 68358, + 'gaze_dir': array([ 0.95385742, 0.29885101, -0.01876831]), + 'gaze_origin': array([-3.18896294, -0.26128617, 0.07766266]), + 'gaze_valid': True, + 'gaze_vergence': 114.74465942382812, + 'handbrake_input': False, + 'left_eye_openness': 0.8949894905090332, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94885254, 0.31562805, -0.00611877]), + 'left_gaze_origin': array([-3.1377871 , 2.93545389, 0.09112091]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1988067626953125, + 'left_pupil_posn': array([ 0.30537534, -0.09329951]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8539168238639832, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9588623 , 0.28207397, -0.03141785]), + 'right_gaze_origin': array([-3.24013829, -3.45802641, 0.06420441]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.197723388671875, + 'right_pupil_posn': array([ 0.29922414, -0.16600907]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005841243080794811, + 'throttle_input': 0.0, + 'timestamp': 580.3408934660256, + 'timestamp_carla': 580341, + 'timestamp_device': 23586, + 'timestamp_stream': 580.3408934660256, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.70865227e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 1.26859290e-03, 7.05434009e-03, -4.65850401e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.51611852645874, + 'FR_Wheel_Angle': -6.154848098754883, + 'Location': array([ -2.67063046, -25.0328846 , 0.17226909]), + 'Rotation': array([-1.82434339e-02, 9.58651352e+01, -5.25512621e-02]), + 'Velocity': array([-9.20030475e-02, 2.23492098e+00, 2.21748342e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.67099094, 9.54545975, 3.66482425]), + 'camera_rotation': array([ 3.25244713, -20.83050919, -1.97781563]), + 'current_gear_input': False, + 'focus_actor_dist': 13863.8671875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 433.03051758, 10846.484375 , 789.75848389]), + 'frame': 17855, + 'frame_number': 17855, + 'framesequence': 68362, + 'gaze_dir': array([ 0.96070862, 0.27645874, -0.01631165]), + 'gaze_origin': array([-3.18177748, -0.23448029, 0.082827 ]), + 'gaze_valid': True, + 'gaze_vergence': 170.09466552734375, + 'handbrake_input': False, + 'left_eye_openness': 0.9268302321434021, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95574951, 0.29371643, -0.01577759]), + 'left_gaze_origin': array([-3.13231206, 2.9606874 , 0.09190217]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3460540771484375, + 'left_pupil_posn': array([ 0.27958035, -0.08616507]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8626716136932373, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96566772, 0.25920105, -0.0168457 ]), + 'right_gaze_origin': array([-3.23124266, -3.42964792, 0.07375184]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2324066162109375, + 'right_pupil_posn': array([ 0.27091575, -0.16034257]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.006189153995364904, + 'throttle_input': 0.0, + 'timestamp': 580.3675839677453, + 'timestamp_carla': 580368, + 'timestamp_device': 23619, + 'timestamp_stream': 580.3675839677453, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.71803628e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 3.29285953e-03, 4.92718909e-03, -4.43005228e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.8006720542907715, + 'FR_Wheel_Angle': -6.4420084953308105, + 'Location': array([ -2.69375372, -24.4706192 , 0.17235145]), + 'Rotation': array([-1.73350200e-02, 9.46661606e+01, -5.52063026e-02]), + 'Velocity': array([-3.27900387e-02, 1.99899471e+00, 3.88965593e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.69162273, 9.66232204, 3.67424297]), + 'camera_rotation': array([ 3.36581469, -20.09622574, -1.57892013]), + 'current_gear_input': False, + 'focus_actor_dist': 13891.9931640625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 530.06933594, 10869.78320312, 796.69152832]), + 'frame': 17856, + 'frame_number': 17856, + 'framesequence': 68365, + 'gaze_dir': array([ 0.96124268, 0.27457428, -0.01726532]), + 'gaze_origin': array([-3.17872572, -0.21509935, 0.08142624]), + 'gaze_valid': True, + 'gaze_vergence': 173.86012268066406, + 'handbrake_input': False, + 'left_eye_openness': 0.9007251858711243, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9564209 , 0.29148865, -0.01679993]), + 'left_gaze_origin': array([-3.12967372, 2.98071456, 0.08652039]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.242767333984375, + 'left_pupil_posn': array([ 0.26531184, -0.08936703]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8772109746932983, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96606445, 0.25765991, -0.01773071]), + 'right_gaze_origin': array([-3.22777748, -3.41091347, 0.07633209]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2203521728515625, + 'right_pupil_posn': array([ 0.25691164, -0.15803349]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0065370649099349976, + 'throttle_input': 0.0, + 'timestamp': 580.3945552669466, + 'timestamp_carla': 580395, + 'timestamp_device': 23644, + 'timestamp_stream': 580.3945552669466, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.72288102e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 9.14137252e-03, -2.45227176e-03, -5.04096079e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.388491153717041, + 'FR_Wheel_Angle': -7.090383529663086, + 'Location': array([ -2.70217252, -24.03318787, 0.17241573]), + 'Rotation': array([-1.77311692e-02, 9.36745605e+01, -5.66101000e-02]), + 'Velocity': array([9.61192232e-03, 1.78689539e+00, 2.38437642e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.73069763, 9.73804855, 3.71586823]), + 'camera_rotation': array([ 3.59362864, -19.77189064, -1.09913158]), + 'current_gear_input': False, + 'focus_actor_dist': 13818.43359375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 377.27423096, 10803.69824219, 779.57312012]), + 'frame': 17857, + 'frame_number': 17857, + 'framesequence': 68368, + 'gaze_dir': array([ 0.96162415, 0.27368164, -0.01326752]), + 'gaze_origin': array([-3.17899799, -0.21382065, 0.07614212]), + 'gaze_valid': True, + 'gaze_vergence': 219.0512237548828, + 'handbrake_input': False, + 'left_eye_openness': 0.9087634086608887, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95796204, 0.28668213, -0.01072693]), + 'left_gaze_origin': array([-3.13076496, 2.98210764, 0.08103638]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.223785400390625, + 'left_pupil_posn': array([ 0.265414 , -0.09275639]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8578248620033264, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96528625, 0.26068115, -0.01580811]), + 'right_gaze_origin': array([-3.22723103, -3.40974879, 0.07124787]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.15283203125, + 'right_pupil_posn': array([ 0.25436497, -0.15912902]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.006884975824505091, + 'throttle_input': 0.0, + 'timestamp': 580.4223466664553, + 'timestamp_carla': 580423, + 'timestamp_device': 23669, + 'timestamp_stream': 580.4223466664553, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.71937180e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 0.02090158, -0.01103417, -5.95235777]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.391282081604004, + 'FR_Wheel_Angle': -8.983485221862793, + 'Location': array([ -2.69910192, -23.62644005, 0.17242207]), + 'Rotation': array([-1.23284906e-02, 9.25845718e+01, -5.32531738e-02]), + 'Velocity': array([7.19995424e-02, 1.71625912e+00, 7.04479171e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.75794983, 9.75636101, 3.72238779]), + 'camera_rotation': array([ 3.59512448, -19.96617317, -0.83943301]), + 'current_gear_input': False, + 'focus_actor_dist': 13881.6484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 315.6656189 , 10865.34863281, 859.14538574]), + 'frame': 17858, + 'frame_number': 17858, + 'framesequence': 68371, + 'gaze_dir': array([ 0.96260071, 0.27007294, -0.00976562]), + 'gaze_origin': array([-3.18092155, -0.22218858, 0.07110367]), + 'gaze_valid': True, + 'gaze_vergence': 162.60983276367188, + 'handbrake_input': False, + 'left_eye_openness': 0.9032801389694214, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95761108, 0.28793335, -0.00741577]), + 'left_gaze_origin': array([-3.13193846, 2.97241855, 0.07778626]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.265167236328125, + 'left_pupil_posn': array([ 0.26913798, -0.0937227 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.867034375667572, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96759033, 0.25221252, -0.01211548]), + 'right_gaze_origin': array([-3.22990417, -3.41679573, 0.06442109]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16229248046875, + 'right_pupil_posn': array([ 0.25990093, -0.16316998]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007031464949250221, + 'throttle_input': 0.0, + 'timestamp': 580.4496026672423, + 'timestamp_carla': 580450, + 'timestamp_device': 23694, + 'timestamp_stream': 580.4496026672423, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.72333923e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 4.63173352e-03, -2.27497108e-02, -7.82797432e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.011148452758789, + 'FR_Wheel_Angle': -12.967838287353516, + 'Location': array([ -2.68296432, -23.28607368, 0.17242694]), + 'Rotation': array([-9.37101897e-03, 9.13740234e+01, -4.74243164e-02]), + 'Velocity': array([ 1.62018389e-01, 1.69409692e+00, -8.60214204e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.76656628, 9.78408623, 3.68979311]), + 'camera_rotation': array([ 3.35992694, -20.0713253 , -0.74654841]), + 'current_gear_input': False, + 'focus_actor_dist': 13878.5732421875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 414.98596191, 10856.74316406, 890.71807861]), + 'frame': 17859, + 'frame_number': 17859, + 'framesequence': 68375, + 'gaze_dir': array([ 0.9621582 , 0.27131653, -0.00998688]), + 'gaze_origin': array([-3.18171239, -0.228743 , 0.06828919]), + 'gaze_valid': True, + 'gaze_vergence': 124.42210388183594, + 'handbrake_input': False, + 'left_eye_openness': 0.8924089074134827, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95643616, 0.29191589, -0.00163269]), + 'left_gaze_origin': array([-3.13281274, 2.96495676, 0.0764389 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1533355712890625, + 'left_pupil_posn': array([ 0.27380705, -0.09688854]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.867414653301239, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96788025, 0.25071716, -0.01834106]), + 'right_gaze_origin': array([-3.23061228, -3.42244291, 0.06013947]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.22491455078125, + 'right_pupil_posn': array([ 0.2653265 , -0.16438437]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007269509136676788, + 'throttle_input': 0.0, + 'timestamp': 580.4767242670059, + 'timestamp_carla': 580477, + 'timestamp_device': 23727, + 'timestamp_stream': 580.4767242670059, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.72806942e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-1.76386291e-03, -4.40258440e-03, -1.04086294e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.054655075073242, + 'FR_Wheel_Angle': -16.564661026000977, + 'Location': array([ -2.64014482, -22.89556313, 0.17243755]), + 'Rotation': array([-9.24807601e-03, 8.93968353e+01, -4.15344238e-02]), + 'Velocity': array([2.98130363e-01, 1.66703212e+00, 2.43077273e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.74661446, 9.87137222, 3.6319778 ]), + 'camera_rotation': array([ 3.01986551, -19.8263607 , -0.74078053]), + 'current_gear_input': False, + 'focus_actor_dist': 13882.2548828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 423.38043213, 10863.38769531, 826.88800049]), + 'frame': 17860, + 'frame_number': 17860, + 'framesequence': 68378, + 'gaze_dir': array([ 0.96527863, 0.25967407, -0.0078125 ]), + 'gaze_origin': array([-3.18296742, -0.23746568, 0.06870499]), + 'gaze_valid': True, + 'gaze_vergence': 103.90985107421875, + 'handbrake_input': False, + 'left_eye_openness': 0.9031740427017212, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95895386, 0.2835083 , 0.00325012]), + 'left_gaze_origin': array([-3.13251066, 2.95710301, 0.07842255]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.03985595703125, + 'left_pupil_posn': array([ 0.27414215, -0.09505045]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8783954977989197, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97160339, 0.23583984, -0.01887512]), + 'right_gaze_origin': array([-3.23342466, -3.43203425, 0.05898743]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.073089599609375, + 'right_pupil_posn': array([ 0.26914978, -0.16372085]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0074892425909638405, + 'throttle_input': 0.0, + 'timestamp': 580.5057255662978, + 'timestamp_carla': 580506, + 'timestamp_device': 23752, + 'timestamp_stream': 580.5057255662978, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.71311517e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-5.45473024e-03, 3.73331760e-03, -1.17167606e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.13396644592285, + 'FR_Wheel_Angle': -17.70901107788086, + 'Location': array([ -2.57112932, -22.51276588, 0.17240562]), + 'Rotation': array([-1.07370568e-02, 8.69520874e+01, -4.25109901e-02]), + 'Velocity': array([ 4.07616466e-01, 1.63671255e+00, -1.51605607e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.74661446, 9.87137222, 3.6319778 ]), + 'camera_rotation': array([ 3.01986551, -19.8263607 , -0.74078053]), + 'current_gear_input': False, + 'focus_actor_dist': 17522.56640625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 715.65124512, 14492.50585938, 945.36962891]), + 'frame': 17861, + 'frame_number': 17861, + 'framesequence': 68382, + 'gaze_dir': array([ 0.96604919, 0.25752258, -0.00350952]), + 'gaze_origin': array([-3.18175817, -0.23705062, 0.07402726]), + 'gaze_valid': True, + 'gaze_vergence': 149.978515625, + 'handbrake_input': False, + 'left_eye_openness': 0.9162313342094421, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 9.60922241e-01, 2.76794434e-01, -1.52587891e-04]), + 'left_gaze_origin': array([-3.13111138, 2.9577837 , 0.085141 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0379486083984375, + 'left_pupil_posn': array([ 0.27452135, -0.08605623]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8779114484786987, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97117615, 0.23825073, -0.00686646]), + 'right_gaze_origin': array([-3.23240542, -3.431885 , 0.06291351]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0257110595703125, + 'right_pupil_posn': array([ 0.26658571, -0.16178083]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007635731250047684, + 'throttle_input': 0.0, + 'timestamp': 580.5380303673446, + 'timestamp_carla': 580538, + 'timestamp_device': 23786, + 'timestamp_stream': 580.5380303673446, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.75370407e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-7.80713861e-04, -2.45119929e-02, -1.17580357e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.36821746826172, + 'FR_Wheel_Angle': -17.851682662963867, + 'Location': array([ -2.46426487, -22.066782 , 0.17220065]), + 'Rotation': array([-9.06366017e-03, 8.39219666e+01, -3.93676721e-02]), + 'Velocity': array([ 5.59264541e-01, 1.81166136e+00, -1.31529802e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.68185997, 10.0219326 , 3.57251668]), + 'camera_rotation': array([ 2.65231943, -19.10003853, -0.92636091]), + 'current_gear_input': False, + 'focus_actor_dist': 17749.572265625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 767.2701416 , 14713.21777344, 1032.16821289]), + 'frame': 17862, + 'frame_number': 17862, + 'framesequence': 68386, + 'gaze_dir': array([ 0.96804047, 0.24956512, -0.00222778]), + 'gaze_origin': array([-3.17757416, -0.22866137, 0.08055039]), + 'gaze_valid': True, + 'gaze_vergence': 122.22705841064453, + 'handbrake_input': False, + 'left_eye_openness': 0.9058207273483276, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9622345 , 0.2721405 , 0.00447083]), + 'left_gaze_origin': array([-3.12604523, 2.96665978, 0.09269562]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9498443603515625, + 'left_pupil_posn': array([ 0.26435792, -0.08031988]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8847797513008118, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97384644, 0.22698975, -0.00892639]), + 'right_gaze_origin': array([-3.22910333, -3.42398238, 0.06840515]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1126708984375, + 'right_pupil_posn': array([ 0.25927877, -0.15555036]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0077272867783904076, + 'throttle_input': 0.0, + 'timestamp': 580.565323267132, + 'timestamp_carla': 580566, + 'timestamp_device': 23819, + 'timestamp_stream': 580.565323267132, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.74775292e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ -0.04750233, -0.02901903, -14.301651 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.668256759643555, + 'FR_Wheel_Angle': -18.940210342407227, + 'Location': array([ -2.32846761, -21.61591339, 0.17202708]), + 'Rotation': array([-1.27246417e-02, 8.07194519e+01, -3.13110314e-02]), + 'Velocity': array([ 7.64773667e-01, 2.00260544e+00, -9.79356701e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.58725548, 10.21164703, 3.53157425]), + 'camera_rotation': array([ 2.35489202, -18.10238647, -0.95402765]), + 'current_gear_input': False, + 'focus_actor_dist': 13846.6689453125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 501.23937988, 10826.56054688, 778.61132812]), + 'frame': 17863, + 'frame_number': 17863, + 'framesequence': 68390, + 'gaze_dir': array([0.97292328, 0.23040771, 0.00434113]), + 'gaze_origin': array([-3.17273426, -0.21705934, 0.0876236 ]), + 'gaze_valid': True, + 'gaze_vergence': 181.51809692382812, + 'handbrake_input': False, + 'left_eye_openness': 0.9288336634635925, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96903992, 0.2467804 , 0.00639343]), + 'left_gaze_origin': array([-3.12090635, 2.97998834, 0.09981842]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.02099609375, + 'left_pupil_posn': array([ 0.25049472, -0.0704149 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.889724612236023, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97680664, 0.21403503, 0.00228882]), + 'right_gaze_origin': array([-3.22456217, -3.41410685, 0.07542878]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0563201904296875, + 'right_pupil_posn': array([ 0.24316192, -0.14835036]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007837153971195221, + 'throttle_input': 0.0, + 'timestamp': 580.5989868678153, + 'timestamp_carla': 580599, + 'timestamp_device': 23852, + 'timestamp_stream': 580.5989868678153, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76476632e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-5.54627515e-02, -3.59340385e-03, -1.72125053e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.486949920654297, + 'FR_Wheel_Angle': -20.131629943847656, + 'Location': array([ -2.14628482, -21.13876724, 0.1718806 ]), + 'Rotation': array([-2.59752087e-02, 7.69710617e+01, -2.61840820e-02]), + 'Velocity': array([ 9.65474069e-01, 2.02061677e+00, -5.94139099e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.47127056, 10.39009762, 3.4713316 ]), + 'camera_rotation': array([ 2.06051087, -17.05938911, -0.75438821]), + 'current_gear_input': False, + 'focus_actor_dist': 16146.4453125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 651.96630859, 13118.12304688, 909.85296631]), + 'frame': 17864, + 'frame_number': 17864, + 'framesequence': 68394, + 'gaze_dir': array([0.97538757, 0.21925354, 0.01174927]), + 'gaze_origin': array([-3.16866374, -0.20426483, 0.09173813]), + 'gaze_valid': True, + 'gaze_vergence': 135.06874084472656, + 'handbrake_input': False, + 'left_eye_openness': 0.9347183108329773, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97160339, 0.23551941, 0.02201843]), + 'left_gaze_origin': array([-3.11547732, 2.99241662, 0.10402985]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.90008544921875, + 'left_pupil_posn': array([ 0.23808718, -0.06639791]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9079894423484802, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97917175, 0.20298767, 0.0014801 ]), + 'right_gaze_origin': array([-3.22185087, -3.40094614, 0.07944641]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0092315673828125, + 'right_pupil_posn': array([ 0.2300123 , -0.13911998]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00794702023267746, + 'throttle_input': 0.0, + 'timestamp': 580.6337084658444, + 'timestamp_carla': 580634, + 'timestamp_device': 23886, + 'timestamp_stream': 580.6337084658444, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76579636e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-8.52471516e-02, 1.27632432e-02, -1.83153000e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.855669021606445, + 'FR_Wheel_Angle': -22.483095169067383, + 'Location': array([ -1.977543 , -20.78120232, 0.17172877]), + 'Rotation': array([-3.82968672e-02, 7.38315277e+01, -2.11486798e-02]), + 'Velocity': array([ 1.11137903e+00, 1.90889478e+00, -1.12833979e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.34754372, 10.56639671, 3.41910386]), + 'camera_rotation': array([ 1.71863937, -16.10442352, -0.4399465 ]), + 'current_gear_input': False, + 'focus_actor_dist': 13814.9716796875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 441.24731445, 10795.76269531, 819.83892822]), + 'frame': 17865, + 'frame_number': 17865, + 'framesequence': 68398, + 'gaze_dir': array([0.97559357, 0.21808624, 0.01127625]), + 'gaze_origin': array([-3.16246033, -0.19393082, 0.09581452]), + 'gaze_valid': True, + 'gaze_vergence': 137.06663513183594, + 'handbrake_input': False, + 'left_eye_openness': 0.9533830285072327, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97071838, 0.23973083, 0.01451111]), + 'left_gaze_origin': array([-3.10907316, 3.00093412, 0.10610047]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8890838623046875, + 'left_pupil_posn': array([ 0.22988272, -0.06136751]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.933509111404419, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98046875, 0.19644165, 0.00804138]), + 'right_gaze_origin': array([-3.21584797, -3.38879561, 0.08552857]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8735198974609375, + 'right_pupil_posn': array([ 0.22297609, -0.13624835]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.6655752658844, + 'timestamp_carla': 580666, + 'timestamp_device': 23919, + 'timestamp_stream': 580.6655752658844, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.78601445e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ -0.05367037, 0.03991963, -19.18054199]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.38437271118164, + 'FR_Wheel_Angle': -24.742860794067383, + 'Location': array([ -1.76641595, -20.41951561, 0.17154618]), + 'Rotation': array([-5.42248674e-02, 7.00594025e+01, -2.13317871e-02]), + 'Velocity': array([ 1.20017850e+00, 1.65442777e+00, -1.50654314e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.23237991, 10.74221134, 3.36862946]), + 'camera_rotation': array([ 1.37129021, -15.29211807, -0.08529769]), + 'current_gear_input': False, + 'focus_actor_dist': 13870.6298828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 229.1663208 , 10863.95410156, 718.89123535]), + 'frame': 17866, + 'frame_number': 17866, + 'framesequence': 68401, + 'gaze_dir': array([0.97657013, 0.21245575, 0.02484131]), + 'gaze_origin': array([-3.14975977, -0.18859865, 0.09375077]), + 'gaze_valid': True, + 'gaze_vergence': 134.7487335205078, + 'handbrake_input': False, + 'left_eye_openness': 0.9503845572471619, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97167969, 0.23498535, 0.02429199]), + 'left_gaze_origin': array([-3.08658004, 3.00666976, 0.09979096]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8983612060546875, + 'left_pupil_posn': array([ 0.22340405, -0.05527759]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9184911847114563, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98146057, 0.18992615, 0.02539062]), + 'right_gaze_origin': array([-3.2129395 , -3.38386703, 0.08771057]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.917449951171875, + 'right_pupil_posn': array([ 0.21774805, -0.13075852]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.6966945677996, + 'timestamp_carla': 580697, + 'timestamp_device': 23944, + 'timestamp_stream': 580.6966945677996, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.80138779e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ -0.02820365, 0.03038741, -19.21847153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.3354377746582, + 'FR_Wheel_Angle': -26.57591438293457, + 'Location': array([ -1.54347026, -20.1072464 , 0.17133456]), + 'Rotation': array([-6.39988706e-02, 6.62249756e+01, -2.47802660e-02]), + 'Velocity': array([ 1.24023044e+00, 1.40871811e+00, -1.32636540e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.13635254, 10.91545105, 3.31304193]), + 'camera_rotation': array([ 0.96104854, -14.5427866 , 0.13835765]), + 'current_gear_input': False, + 'focus_actor_dist': 13919.3408203125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 111.87451172, 10911.62695312, 808.9944458 ]), + 'frame': 17867, + 'frame_number': 17867, + 'framesequence': 68406, + 'gaze_dir': array([0.98023224, 0.1937027 , 0.0385437 ]), + 'gaze_origin': array([-3.09751678, -0.17652893, 0.08584747]), + 'gaze_valid': True, + 'gaze_vergence': 262.74163818359375, + 'handbrake_input': False, + 'left_eye_openness': 0.9641223549842834, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97798157, 0.20452881, 0.04142761]), + 'left_gaze_origin': array([-2.98371887, 3.02000284, 0.07447053]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9098052978515625, + 'left_pupil_posn': array([ 0.21055937, -0.04957187]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9480808973312378, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98248291, 0.18287659, 0.03565979]), + 'right_gaze_origin': array([-3.21131468, -3.3730607 , 0.09722443]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.807830810546875, + 'right_pupil_posn': array([ 0.19958377, -0.11690366]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.7330274656415, + 'timestamp_carla': 580733, + 'timestamp_device': 23986, + 'timestamp_stream': 580.7330274656415, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76804737e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-1.13733355e-02, 1.22837387e-02, -1.90428848e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.64997863769531, + 'FR_Wheel_Angle': -27.865041732788086, + 'Location': array([ -1.31327236, -19.83969116, 0.17107376]), + 'Rotation': array([-6.93947151e-02, 6.23735771e+01, -2.54211407e-02]), + 'Velocity': array([ 1.25405085, 1.18051505, -0.00154431]), + 'brake_input': 0.0, + 'camera_location': array([-8.03113747, 11.10815334, 3.23172379]), + 'camera_rotation': array([ 0.55417418, -13.76147079, 0.12241641]), + 'current_gear_input': False, + 'focus_actor_dist': 13926.6025390625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 194.61749268, 10912.83789062, 892.51177979]), + 'frame': 17868, + 'frame_number': 17868, + 'framesequence': 68409, + 'gaze_dir': array([0.9808197 , 0.19082642, 0.03844452]), + 'gaze_origin': array([-3.06872106, -0.16621323, 0.08522263]), + 'gaze_valid': True, + 'gaze_vergence': 290.01446533203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97921753, 0.19810486, 0.04333496]), + 'left_gaze_origin': array([-2.95686817, 3.03121352, 0.07551423]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9873199462890625, + 'left_pupil_posn': array([ 0.20281422, -0.04479992]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98242188, 0.18354797, 0.03355408]), + 'right_gaze_origin': array([-3.18057418, -3.36363983, 0.09493104]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8720550537109375, + 'right_pupil_posn': array([ 0.18980277, -0.1120131 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.7666202671826, + 'timestamp_carla': 580767, + 'timestamp_device': 24011, + 'timestamp_stream': 580.7666202671826, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.77167115e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 2.61920225e-03, 6.23175362e-03, -1.81555214e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.33000946044922, + 'FR_Wheel_Angle': -28.185747146606445, + 'Location': array([ -1.10316074, -19.63067055, 0.1708007 ]), + 'Rotation': array([-7.18672499e-02, 5.89706612e+01, -2.77404822e-02]), + 'Velocity': array([ 1.23106742e+00, 1.01237726e+00, -1.02796080e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.92985535, 11.27758121, 3.15513015]), + 'camera_rotation': array([ 0.20595068, -13.01672077, 0.14820835]), + 'current_gear_input': False, + 'focus_actor_dist': 13904.859375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ 46.50093079, 10899.24609375, 794.21313477]), + 'frame': 17869, + 'frame_number': 17869, + 'framesequence': 68413, + 'gaze_dir': array([0.98155975, 0.18480682, 0.04634094]), + 'gaze_origin': array([-3.05902338, -0.16281281, 0.08534012]), + 'gaze_valid': True, + 'gaze_vergence': 199.35211181640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97868347, 0.19915771, 0.05007935]), + 'left_gaze_origin': array([-2.94110274, 3.03444982, 0.07355347]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.88275146484375, + 'left_pupil_posn': array([ 0.19600117, -0.03982496]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98443604, 0.17045593, 0.04260254]), + 'right_gaze_origin': array([-3.17694402, -3.36007547, 0.09712677]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8832550048828125, + 'right_pupil_posn': array([ 0.18764913, -0.10751033]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.7983360663056, + 'timestamp_carla': 580799, + 'timestamp_device': 24044, + 'timestamp_stream': 580.7983360663056, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.78616718e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 1.35510881e-02, -3.30617502e-02, -1.62848091e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.41948318481445, + 'FR_Wheel_Angle': -28.244813919067383, + 'Location': array([ -0.89166868, -19.44434166, 0.17049167]), + 'Rotation': array([-7.35816211e-02, 5.56400299e+01, -2.95715295e-02]), + 'Velocity': array([ 1.18712282, 0.8695243 , -0.00192966]), + 'brake_input': 0.0, + 'camera_location': array([-7.81647778, 11.42870998, 3.12094831]), + 'camera_rotation': array([ -0.09351212, -12.37005997, 0.34269908]), + 'current_gear_input': False, + 'focus_actor_dist': 15464.34765625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ -36.64331055, 12456.78417969, 896.89892578]), + 'frame': 17870, + 'frame_number': 17870, + 'framesequence': 68417, + 'gaze_dir': array([0.98258972, 0.17901611, 0.04793549]), + 'gaze_origin': array([-3.04253793, -0.15853424, 0.08440247]), + 'gaze_valid': True, + 'gaze_vergence': 248.92294311523438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9803009 , 0.19125366, 0.0491333 ]), + 'left_gaze_origin': array([-2.95425582, 3.03973866, 0.08221284]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.970001220703125, + 'left_pupil_posn': array([ 0.191311 , -0.03500462]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98487854, 0.16677856, 0.04673767]), + 'right_gaze_origin': array([-3.13082004, -3.35680699, 0.08659211]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8939361572265625, + 'right_pupil_posn': array([ 0.18117833, -0.10630894]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.8311520665884, + 'timestamp_carla': 580831, + 'timestamp_device': 24077, + 'timestamp_stream': 580.8311520665884, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.78616718e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 3.74340871e-03, -3.29004750e-02, -1.56656771e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.09610366821289, + 'FR_Wheel_Angle': -27.894420623779297, + 'Location': array([ -0.59856915, -19.21901321, 0.17016582]), + 'Rotation': array([-7.23863393e-02, 5.12588577e+01, -2.38342267e-02]), + 'Velocity': array([ 1.19584548, 0.74543524, -0.00159832]), + 'brake_input': 0.0, + 'camera_location': array([-7.72093391, 11.60214996, 3.06497884]), + 'camera_rotation': array([ -0.37601554, -11.65634537, 0.5690794 ]), + 'current_gear_input': False, + 'focus_actor_dist': 15444.935546875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ -122.05426788, 12441.00683594, 832.19641113]), + 'frame': 17871, + 'frame_number': 17871, + 'framesequence': 68421, + 'gaze_dir': array([0.98339844, 0.168396 , 0.06395721]), + 'gaze_origin': array([-3.00359678, -0.1530121 , 0.07505264]), + 'gaze_valid': True, + 'gaze_vergence': 145.9897003173828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98010254, 0.18904114, 0.0602417 ]), + 'left_gaze_origin': array([-2.96035624, 3.04540873, 0.08850556]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9271392822265625, + 'left_pupil_posn': array([ 0.18106246, -0.02449429]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98669434, 0.14775085, 0.06767273]), + 'right_gaze_origin': array([-3.04683709, -3.3514328 , 0.06159974]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9397430419921875, + 'right_pupil_posn': array([ 0.17421257, -0.10396099]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.8636314682662, + 'timestamp_carla': 580864, + 'timestamp_device': 24111, + 'timestamp_stream': 580.8636314682662, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.78750177e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 9.0209851e-03, -4.8554033e-02, -1.4671628e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.72350311279297, + 'FR_Wheel_Angle': -26.343292236328125, + 'Location': array([ -0.33554581, -19.04100037, 0.1698381 ]), + 'Rotation': array([-7.15257376e-02, 4.76226768e+01, -2.25219708e-02]), + 'Velocity': array([ 1.21364093e+00, 6.86344922e-01, -1.20049471e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.62398243, 11.80393028, 3.02727389]), + 'camera_rotation': array([ -0.70034707, -10.80984497, 1.02190363]), + 'current_gear_input': False, + 'focus_actor_dist': 15502.4384765625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ -154.79327393, 12490.38378906, 998.72198486]), + 'frame': 17872, + 'frame_number': 17872, + 'framesequence': 68425, + 'gaze_dir': array([0.98613739, 0.15260315, 0.0645752 ]), + 'gaze_origin': array([-3.05207753, -0.14407884, 0.09248963]), + 'gaze_valid': True, + 'gaze_vergence': 299.87054443359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98570251, 0.15766907, 0.05926514]), + 'left_gaze_origin': array([-2.93560338, 3.05607605, 0.08250733]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9521484375, + 'left_pupil_posn': array([ 0.17353272, -0.02333117]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98657227, 0.14753723, 0.06988525]), + 'right_gaze_origin': array([-3.16855168, -3.34423375, 0.10247193]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.868316650390625, + 'right_pupil_posn': array([ 0.16196001, -0.09816623]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.8971458673477, + 'timestamp_carla': 580897, + 'timestamp_device': 24144, + 'timestamp_stream': 580.8971458673477, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.77968238e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([ 1.46874576e-03, -5.96651360e-02, -1.44128599e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.528413772583008, + 'FR_Wheel_Angle': -24.26463508605957, + 'Location': array([ -0.09633035, -18.89165688, 0.1695139 ]), + 'Rotation': array([-6.77213222e-02, 4.46238403e+01, -1.76391583e-02]), + 'Velocity': array([ 1.31529939, 0.69864243, -0.0015605 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.54384899, 12.02930737, 2.97435641]), + 'camera_rotation': array([-1.04983413, -9.8029213 , 1.586326 ]), + 'current_gear_input': False, + 'focus_actor_dist': 15358.224609375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([ -142.4349823 , 12351.30859375, 897.72961426]), + 'frame': 17873, + 'frame_number': 17873, + 'framesequence': 68429, + 'gaze_dir': array([0.9875412 , 0.1420517 , 0.06674957]), + 'gaze_origin': array([-3.03875971, -0.13297425, 0.09573441]), + 'gaze_valid': True, + 'gaze_vergence': 160.3587646484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98616028, 0.14750671, 0.07550049]), + 'left_gaze_origin': array([-2.96248174, 3.06682754, 0.09673768]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.920318603515625, + 'left_pupil_posn': array([ 0.16274977, -0.02253067]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98892212, 0.13659668, 0.05799866]), + 'right_gaze_origin': array([-3.11503768, -3.33277631, 0.09473114]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8794403076171875, + 'right_pupil_posn': array([ 0.14917231, -0.08765781]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.9312751665711, + 'timestamp_carla': 580932, + 'timestamp_device': 24177, + 'timestamp_stream': 580.9312751665711, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76976380e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-5.93921589e-03, -2.39744503e-02, -1.39834766e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.526527404785156, + 'FR_Wheel_Angle': -21.559492111206055, + 'Location': array([ 0.26177391, -18.68398666, 0.1690499 ]), + 'Rotation': array([-6.46682307e-02, 4.07384529e+01, -1.22070303e-02]), + 'Velocity': array([ 1.5000428 , 0.74515051, -0.00210119]), + 'brake_input': 0.0, + 'camera_location': array([-7.45790672, 12.29025745, 2.8846581 ]), + 'camera_rotation': array([-1.47504079, -8.75368309, 2.05370879]), + 'current_gear_input': False, + 'focus_actor_dist': 6650.3251953125, + 'focus_actor_name': 'TreePine_848', + 'focus_actor_pt': array([-207.32337952, 3655.67260742, 432.67907715]), + 'frame': 17874, + 'frame_number': 17874, + 'framesequence': 68433, + 'gaze_dir': array([0.98657227, 0.14849091, 0.06652832]), + 'gaze_origin': array([-3.03086424, -0.13874665, 0.09409333]), + 'gaze_valid': True, + 'gaze_vergence': 166.70767211914062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98448181, 0.15820312, 0.0758667 ]), + 'left_gaze_origin': array([-2.96646285, 3.0616014 , 0.09882202]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8588409423828125, + 'left_pupil_posn': array([ 0.16708744, -0.02209485]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98866272, 0.13877869, 0.05718994]), + 'right_gaze_origin': array([-3.09526539, -3.33909464, 0.08936463]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9020233154296875, + 'right_pupil_posn': array([ 0.15661883, -0.08789277]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.9645237661898, + 'timestamp_carla': 580965, + 'timestamp_device': 24211, + 'timestamp_stream': 580.9645237661898, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76976380e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-7.90193584e-03, 5.25864474e-02, -1.14778891e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.42451286315918, + 'FR_Wheel_Angle': -18.183853149414062, + 'Location': array([ 0.60628837, -18.49650192, 0.16867889]), + 'Rotation': array([-7.06787929e-02, 3.77017365e+01, -1.66625995e-02]), + 'Velocity': array([ 1.50182128, 0.72655118, -0.00171981]), + 'brake_input': 0.0, + 'camera_location': array([-7.37554455, 12.56904411, 2.81765962]), + 'camera_rotation': array([-1.80186522, -7.69026756, 2.35997915]), + 'current_gear_input': False, + 'focus_actor_dist': 6658.73193359375, + 'focus_actor_name': 'TreePine_848', + 'focus_actor_pt': array([-375.85656738, 3663.41113281, 373.65008545]), + 'frame': 17875, + 'frame_number': 17875, + 'framesequence': 68437, + 'gaze_dir': array([0.95948792, 0.28056335, 0.01831055]), + 'gaze_origin': array([-3.0831728 , -0.23561327, 0.07096405]), + 'gaze_valid': True, + 'gaze_vergence': 165.9004669189453, + 'handbrake_input': False, + 'left_eye_openness': 0.9786033630371094, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95458984, 0.29704285, 0.02259827]), + 'left_gaze_origin': array([-3.00213933, 2.94872904, 0.07363434]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9046478271484375, + 'left_pupil_posn': array([ 0.28742313, -0.06298721]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9310222864151001, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96438599, 0.26408386, 0.01402283]), + 'right_gaze_origin': array([-3.16420603, -3.41995549, 0.06829377]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.004638671875, + 'right_pupil_posn': array([ 0.26328969, -0.13732171]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 580.9977357685566, + 'timestamp_carla': 580998, + 'timestamp_device': 24244, + 'timestamp_stream': 580.9977357685566, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76976380e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-5.37953805e-03, -1.20930541e-02, -7.87662840e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.194377899169922, + 'FR_Wheel_Angle': -15.117695808410645, + 'Location': array([ 0.92916977, -18.32626343, 0.16834641]), + 'Rotation': array([-7.90389478e-02, 3.53761330e+01, -2.14233398e-02]), + 'Velocity': array([ 1.36434829, 0.6549468 , -0.00141968]), + 'brake_input': 0.0, + 'camera_location': array([-7.2835865 , 12.8575592 , 2.76046443]), + 'camera_rotation': array([-2.05795646, -6.62248659, 2.65795469]), + 'current_gear_input': False, + 'focus_actor_dist': 4801.29638671875, + 'focus_actor_name': 'BP_Block05_13', + 'focus_actor_pt': array([-1043.90551758, 1731.62988281, 24.25350952]), + 'frame': 17876, + 'frame_number': 17876, + 'framesequence': 68441, + 'gaze_dir': array([ 0.93661499, 0.34932709, -0.02028656]), + 'gaze_origin': array([-3.10042667, -0.28422779, 0.04110031]), + 'gaze_valid': True, + 'gaze_vergence': 170.4943389892578, + 'handbrake_input': False, + 'left_eye_openness': 0.9428271651268005, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.93058777, 0.36552429, -0.01977539]), + 'left_gaze_origin': array([-3.02052927, 2.89287448, 0.04449616]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9999237060546875, + 'left_pupil_posn': array([ 0.35063112, -0.10025251]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.864094078540802, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.94264221, 0.33312988, -0.02079773]), + 'right_gaze_origin': array([-3.18032384, -3.4613297 , 0.03770447]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0606842041015625, + 'right_pupil_posn': array([ 0.31756389, -0.17910564]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007983642630279064, + 'throttle_input': 0.0, + 'timestamp': 581.0310901664197, + 'timestamp_carla': 581031, + 'timestamp_device': 24277, + 'timestamp_stream': 581.0310901664197, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76976380e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-4.95033630e-04, -1.99032370e-02, -6.08445501e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.660969734191895, + 'FR_Wheel_Angle': -11.57931137084961, + 'Location': array([ 1.19635296, -18.18682671, 0.16800705]), + 'Rotation': array([-7.58629069e-02, 3.38274536e+01, -2.03857403e-02]), + 'Velocity': array([ 1.36080217, 0.66527516, -0.00175387]), + 'brake_input': 0.0, + 'camera_location': array([-7.23033047, 13.14268017, 2.69467306]), + 'camera_rotation': array([-2.42254496, -5.48809481, 3.11867905]), + 'current_gear_input': False, + 'focus_actor_dist': 1105.41455078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -466.68151855, -1926.08459473, 59.58631134]), + 'frame': 17877, + 'frame_number': 17877, + 'framesequence': 68445, + 'gaze_dir': array([ 0.93976593, 0.34130859, -0.01796722]), + 'gaze_origin': array([-3.09517002, -0.26635209, 0.05001831]), + 'gaze_valid': True, + 'gaze_vergence': 1.0830167531967163, + 'handbrake_input': False, + 'left_eye_openness': 0.9531704187393188, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.93981934, 0.34130859, -0.01528931]), + 'left_gaze_origin': array([-3.01541901, 2.91951299, 0.05222321]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.947601318359375, + 'left_pupil_posn': array([ 0.33514071, -0.09416378]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9101927280426025, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.93971252, 0.34130859, -0.02064514]), + 'right_gaze_origin': array([-3.1749208 , -3.4522171 , 0.04781342]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.989044189453125, + 'right_pupil_posn': array([ 0.30198562, -0.16859579]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.008203376084566116, + 'throttle_input': 0.0, + 'timestamp': 581.0648466683924, + 'timestamp_carla': 581065, + 'timestamp_device': 24310, + 'timestamp_stream': 581.0648466683924, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76602547e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.00633612, 0.01947085, -4.63451672]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.953287124633789, + 'FR_Wheel_Angle': -7.68076229095459, + 'Location': array([ 1.5122757 , -18.01950836, 0.16762646]), + 'Rotation': array([-7.36977383e-02, 3.24797668e+01, -2.09655724e-02]), + 'Velocity': array([ 1.36317348, 0.7001403 , -0.00143076]), + 'brake_input': 0.0, + 'camera_location': array([-7.17084885, 13.43903637, 2.62992358]), + 'camera_rotation': array([-2.86710143, -4.34107065, 3.47781062]), + 'current_gear_input': False, + 'focus_actor_dist': 1094.5340576171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -475.58581543, -1940.31225586, 53.6336441 ]), + 'frame': 17878, + 'frame_number': 17878, + 'framesequence': 68449, + 'gaze_dir': array([ 0.95406342, 0.29937744, -0.00273895]), + 'gaze_origin': array([-3.08946466, -0.25647509, 0.05622635]), + 'gaze_valid': True, + 'gaze_vergence': 264.7120666503906, + 'handbrake_input': False, + 'left_eye_openness': 0.9751178026199341, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9511261 , 0.30877686, 0.00117493]), + 'left_gaze_origin': array([-3.0081377 , 2.9310503 , 0.05790406]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0498199462890625, + 'left_pupil_posn': array([ 0.30868435, -0.08263385]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9127241969108582, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95700073, 0.28997803, -0.00665283]), + 'right_gaze_origin': array([-3.17079163, -3.44400024, 0.05454865]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0026397705078125, + 'right_pupil_posn': array([ 0.28428829, -0.15618289]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.008935820311307907, + 'throttle_input': 0.0, + 'timestamp': 581.0986096672714, + 'timestamp_carla': 581099, + 'timestamp_device': 24344, + 'timestamp_stream': 581.0986096672714, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76385083e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.01188398, 0.01102324, -2.13232327]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.215032577514648, + 'FR_Wheel_Angle': -3.4977481365203857, + 'Location': array([ 1.81449091, -17.85314751, 0.16729118]), + 'Rotation': array([-7.89159983e-02, 3.16899185e+01, -2.38037072e-02]), + 'Velocity': array([ 1.23248553, 0.68021637, -0.00168385]), + 'brake_input': 0.0, + 'camera_location': array([-7.09998226, 13.75481987, 2.56005907]), + 'camera_rotation': array([-3.21019554, -3.15571809, 3.74735332]), + 'current_gear_input': False, + 'focus_actor_dist': 1131.894775390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -460.65856934, -1896.68286133, 59.33335876]), + 'frame': 17879, + 'frame_number': 17879, + 'framesequence': 68453, + 'gaze_dir': array([ 0.95639038, 0.29173279, -0.00494385]), + 'gaze_origin': array([-3.08531046, -0.24160387, 0.05721894]), + 'gaze_valid': True, + 'gaze_vergence': 203.82168579101562, + 'handbrake_input': False, + 'left_eye_openness': 0.9822640419006348, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95301819, 0.30290222, 0.00115967]), + 'left_gaze_origin': array([-3.00425124, 2.94713593, 0.05795594]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9971771240234375, + 'left_pupil_posn': array([ 0.29432523, -0.08304179]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.934191107749939, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95976257, 0.28056335, -0.01104736]), + 'right_gaze_origin': array([-3.16636968, -3.43034387, 0.05648194]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9719390869140625, + 'right_pupil_posn': array([ 0.27252495, -0.15369153]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.010620441287755966, + 'throttle_input': 0.01190203707665205, + 'timestamp': 581.1317199654877, + 'timestamp_carla': 581132, + 'timestamp_device': 24377, + 'timestamp_stream': 581.1317199654877, + 'transform': [array([-9.59253848e-01, -1.66797905e+01, 9.76751279e-03]), + array([-0.06292653, 1.86204588, 0.01342775])]} +{'AngularVelocity': array([-0.01752308, -0.0074363 , 0.12341363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.08377624, -17.69502831, 0.16698287]), + 'Rotation': array([-8.07806402e-02, 3.14543991e+01, -2.61535626e-02]), + 'Velocity': array([ 1.09192145, 0.66695637, -0.00139296]), + 'brake_input': 0.0, + 'camera_location': array([-7.04603577, 14.06126404, 2.49711275]), + 'camera_rotation': array([-3.53089333, -1.90925527, 4.04484081]), + 'current_gear_input': False, + 'focus_actor_dist': 1101.662841796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -466.3588562 , -1930.11535645, 51.53156281]), + 'frame': 17880, + 'frame_number': 17880, + 'framesequence': 68457, + 'gaze_dir': array([0.96300507, 0.2690506 , 0.00305176]), + 'gaze_origin': array([-3.08066201, -0.23023607, 0.06442489]), + 'gaze_valid': True, + 'gaze_vergence': 203.68923950195312, + 'handbrake_input': False, + 'left_eye_openness': 0.9695398807525635, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 9.59289551e-01, 2.82394409e-01, -9.15527344e-04]), + 'left_gaze_origin': array([-2.99979734, 2.96157098, 0.06413879]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.891326904296875, + 'left_pupil_posn': array([ 0.27581263, -0.07093716]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9379001259803772, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96672058, 0.25570679, 0.00701904]), + 'right_gaze_origin': array([-3.16152644, -3.42204309, 0.064711 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.90350341796875, + 'right_pupil_posn': array([ 0.25923872, -0.1471144 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01300088595598936, + 'throttle_input': 0.07539482414722443, + 'timestamp': 581.1655299663544, + 'timestamp_carla': 581166, + 'timestamp_device': 24410, + 'timestamp_stream': 581.1655299663544, + 'transform': [array([-9.60171342e-01, -1.66802616e+01, 9.62947868e-03]), + array([-0.06283091, 1.86628056, 0.0140381 ])]} +{'AngularVelocity': array([-0.02045694, -0.03219142, 0.04699447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.12154390662908554, + 'Location': array([ 2.32527828, -17.54741859, 0.16744477]), + 'Rotation': array([-0.05029751, 31.45453262, 0.04317623]), + 'Velocity': array([9.91090298e-01, 6.05970502e-01, 4.46748716e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.01534271, 14.36455154, 2.40025401]), + 'camera_rotation': array([-3.93239236, -0.66630304, 4.16367626]), + 'current_gear_input': False, + 'focus_actor_dist': 1102.405517578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -465.29486084, -1928.72131348, 53.97716522]), + 'frame': 17881, + 'frame_number': 17881, + 'framesequence': 68461, + 'gaze_dir': array([0.97063446, 0.23977661, 0.00932312]), + 'gaze_origin': array([-3.077636 , -0.22187501, 0.06872864]), + 'gaze_valid': True, + 'gaze_vergence': 161.02215576171875, + 'handbrake_input': False, + 'left_eye_openness': 0.9821029901504517, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96697998, 0.2542572 , 0.01721191]), + 'left_gaze_origin': array([-2.99532032, 2.9706285 , 0.07001801]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.001678466796875, + 'left_pupil_posn': array([ 0.25886762, -0.06741834]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9260569214820862, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97428894, 0.22529602, 0.00143433]), + 'right_gaze_origin': array([-3.15995169, -3.41437864, 0.06743927]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8874359130859375, + 'right_pupil_posn': array([ 0.24393964, -0.13759458]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015692617744207382, + 'throttle_input': 0.09919890016317368, + 'timestamp': 581.197965465486, + 'timestamp_carla': 581198, + 'timestamp_device': 24444, + 'timestamp_stream': 581.197965465486, + 'transform': [array([-9.60132897e-01, -1.66807632e+01, 9.59638599e-03]), + array([-0.06283091, 1.86627376, 0.0142212 ])]} +{'AngularVelocity': array([ 1.03523351e-01, -1.68335170e-01, -2.64452519e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.12290391325950623, + 'FR_Wheel_Angle': 0.12305037677288055, + 'Location': array([ 2.38311005, -17.51182175, 0.1675732 ]), + 'Rotation': array([-0.08731031, 31.42948341, 0.04394007]), + 'Velocity': array([-1.16670381e-04, -7.22007608e-05, 3.29315699e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.99989128, 14.68875122, 2.35732293]), + 'camera_rotation': array([-4.2681098 , 0.73172194, 4.08307171]), + 'current_gear_input': False, + 'focus_actor_dist': 1123.85693359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -462.55981445, -1905.69482422, 52.89152527]), + 'frame': 17882, + 'frame_number': 17882, + 'framesequence': 68465, + 'gaze_dir': array([0.97283173, 0.23097229, 0.01163483]), + 'gaze_origin': array([-3.07538772, -0.20312579, 0.07199784]), + 'gaze_valid': True, + 'gaze_vergence': 247.76589965820312, + 'handbrake_input': False, + 'left_eye_openness': 0.9832108020782471, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97091675, 0.23875427, 0.01759338]), + 'left_gaze_origin': array([-2.99612904, 2.99147964, 0.07418366]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9317474365234375, + 'left_pupil_posn': array([ 0.24390733, -0.06335187]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9385878443717957, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9747467 , 0.22319031, 0.00567627]), + 'right_gaze_origin': array([-3.15464664, -3.39773107, 0.06981201]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9156341552734375, + 'right_pupil_posn': array([ 0.22652912, -0.13475096]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01807306334376335, + 'throttle_input': 0.10713358968496323, + 'timestamp': 581.2310585677624, + 'timestamp_carla': 581231, + 'timestamp_device': 24477, + 'timestamp_stream': 581.2310585677624, + 'transform': [array([-9.60063636e-01, -1.66812344e+01, 9.60319489e-03]), + array([-0.06283091, 1.86610663, 0.01419069])]} +{'AngularVelocity': array([ 3.53908315e-02, -5.76148443e-02, -2.02625324e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.12290409952402115, + 'FR_Wheel_Angle': 0.12305056303739548, + 'Location': array([ 2.38328004, -17.51170731, 0.16735321]), + 'Rotation': array([-0.05670423, 31.42969704, 0.0438759 ]), + 'Velocity': array([-3.89426023e-05, -2.47007974e-05, -1.37968353e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.95131683, 15.01090622, 2.30528855]), + 'camera_rotation': array([-4.62231684, 2.2774415 , 4.11006308]), + 'current_gear_input': False, + 'focus_actor_dist': 1097.6485595703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -472.34002686, -1935.73022461, 52.02590942]), + 'frame': 17883, + 'frame_number': 17883, + 'framesequence': 68469, + 'gaze_dir': array([0.97947693, 0.20033264, 0.01219177]), + 'gaze_origin': array([-3.10285807, -0.17683792, 0.08797836]), + 'gaze_valid': True, + 'gaze_vergence': 163.5160369873047, + 'handbrake_input': False, + 'left_eye_openness': 0.981643557548523, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97615051, 0.21696472, 0.00621033]), + 'left_gaze_origin': array([-3.06104136, 3.01622176, 0.09992065]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9940032958984375, + 'left_pupil_posn': array([ 0.21426105, -0.05297923]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9207901358604431, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98280334, 0.18370056, 0.01817322]), + 'right_gaze_origin': array([-3.14467478, -3.3698976 , 0.07603607]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9730377197265625, + 'right_pupil_posn': array([ 0.19934046, -0.13179541]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0206732377409935, + 'throttle_input': 0.10713358968496323, + 'timestamp': 581.2653780654073, + 'timestamp_carla': 581266, + 'timestamp_device': 24510, + 'timestamp_stream': 581.2653780654073, + 'transform': [array([-9.60036278e-01, -1.66816673e+01, 9.62099060e-03]), + array([-0.06283091, 1.86615086, 0.01406862])]} +{'AngularVelocity': array([ 8.56195949e-03, -1.40602086e-02, -1.71159609e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.12290418148040771, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.38332653, -17.51167679, 0.16729201]), + 'Rotation': array([-0.04842604, 31.42992973, 0.04385982]), + 'Velocity': array([-8.17047385e-06, -5.87956947e-06, -1.72356944e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.93904972, 15.31873703, 2.22330379]), + 'camera_rotation': array([-5.059237 , 3.78170085, 4.21267176]), + 'current_gear_input': False, + 'focus_actor_dist': 1100.2777099609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.70227051, -1932.27441406, 47.50526428]), + 'frame': 17884, + 'frame_number': 17884, + 'framesequence': 68473, + 'gaze_dir': array([0.98197937, 0.18728638, 0.01943207]), + 'gaze_origin': array([-3.059196 , -0.15908051, 0.08168183]), + 'gaze_valid': True, + 'gaze_vergence': 164.84649658203125, + 'handbrake_input': False, + 'left_eye_openness': 0.9851879477500916, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97944641, 0.19961548, 0.02839661]), + 'left_gaze_origin': array([-3.01275969, 3.03464055, 0.09328003]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.959564208984375, + 'left_pupil_posn': array([ 0.19811356, -0.05093181]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9789623618125916, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98451233, 0.17495728, 0.01046753]), + 'right_gaze_origin': array([-3.10563231, -3.35280156, 0.07008362]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9434814453125, + 'right_pupil_posn': array([ 0.18043578, -0.12029445]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0230903048068285, + 'throttle_input': 0.10713358968496323, + 'timestamp': 581.2987106665969, + 'timestamp_carla': 581299, + 'timestamp_device': 24544, + 'timestamp_stream': 581.2987106665969, + 'transform': [array([-9.60094452e-01, -1.66820316e+01, 9.65761207e-03]), + array([-0.06283091, 1.86658835, 0.01391602])]} +{'AngularVelocity': array([ 0.0019687 , -0.00328082, 0.00012296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.38371563, -17.51144028, 0.16728137]), + 'Rotation': array([-0.0461994 , 31.43017197, 0.04386555]), + 'Velocity': array([0.00283514, 0.00172944, 0.00057076]), + 'brake_input': 0.0, + 'camera_location': array([-6.93270397, 15.59144974, 2.13757539]), + 'camera_rotation': array([-5.48751688, 5.06119204, 4.32888508]), + 'current_gear_input': False, + 'focus_actor_dist': 1089.2607421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -480.01702881, -1946.88476562, 48.48947906]), + 'frame': 17885, + 'frame_number': 17885, + 'framesequence': 68477, + 'gaze_dir': array([0.98620605, 0.16305542, 0.02523804]), + 'gaze_origin': array([-3.03842783, -0.14452592, 0.07838821]), + 'gaze_valid': True, + 'gaze_vergence': 225.2999725341797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98425293, 0.17404175, 0.03079224]), + 'left_gaze_origin': array([-2.97188282, 3.05115819, 0.08364105]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.922332763671875, + 'left_pupil_posn': array([ 0.1786505, -0.0462575]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98815918, 0.15206909, 0.01968384]), + 'right_gaze_origin': array([-3.10497308, -3.34020996, 0.07313538]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.829071044921875, + 'right_pupil_posn': array([ 0.16292787, -0.11650634]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.025598928332328796, + 'throttle_input': 0.10713358968496323, + 'timestamp': 581.3323114663363, + 'timestamp_carla': 581332, + 'timestamp_device': 24577, + 'timestamp_stream': 581.3323114663363, + 'transform': [array([-9.60164905e-01, -1.66823292e+01, 9.69820004e-03]), + array([-0.06283091, 1.86707675, 0.01373292])]} +{'AngularVelocity': array([ 1.53601097e-04, -3.38576880e-04, -3.01904638e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.38407612, -17.51122093, 0.16729416]), + 'Rotation': array([-0.0461994 , 31.43017197, 0.04386555]), + 'Velocity': array([2.32551047e-05, 1.30698827e-05, 4.58940531e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.91593933, 15.83856392, 2.06717062]), + 'camera_rotation': array([-5.88220644, 6.20835066, 4.53817034]), + 'current_gear_input': False, + 'focus_actor_dist': 1090.7216796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -478.72244263, -1944.97363281, 47.74687195]), + 'frame': 17886, + 'frame_number': 17886, + 'framesequence': 68481, + 'gaze_dir': array([0.98862457, 0.14572906, 0.03512573]), + 'gaze_origin': array([-3.04023528, -0.12733002, 0.0837616 ]), + 'gaze_valid': True, + 'gaze_vergence': 220.740478515625, + 'handbrake_input': False, + 'left_eye_openness': 0.9997227191925049, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98750305, 0.15501404, 0.02828979]), + 'left_gaze_origin': array([-2.9386704 , 3.06975412, 0.07572021]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9967803955078125, + 'left_pupil_posn': array([ 0.1604656 , -0.03768337]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9988634586334229, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98974609, 0.13644409, 0.04196167]), + 'right_gaze_origin': array([-3.14179993, -3.32441401, 0.09180298]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9806365966796875, + 'right_pupil_posn': array([ 0.14644134, -0.11136496]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02862025983631611, + 'throttle_input': 0.10713358968496323, + 'timestamp': 581.365251865238, + 'timestamp_carla': 581365, + 'timestamp_device': 24610, + 'timestamp_stream': 581.365251865238, + 'transform': [array([-9.60294306e-01, -1.66825256e+01, 9.74370912e-03]), + array([-0.06283091, 1.86782146, 0.01354981])]} +{'AngularVelocity': array([ 0.0003876 , -0.00039213, -0.00095243]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1778489202260971, + 'FR_Wheel_Angle': 0.17815537750720978, + 'Location': array([ 2.38407946, -17.51122475, 0.16729309]), + 'Rotation': array([-0.04610378, 31.43016243, 0.04387706]), + 'Velocity': array([ 6.48510650e-06, 4.53436496e-06, -1.75140690e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.89516068, 16.06421471, 2.00029969]), + 'camera_rotation': array([-6.23643351, 7.29907703, 4.78666258]), + 'current_gear_input': False, + 'focus_actor_dist': 1087.3184814453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -481.45516968, -1948.95214844, 51.85209656]), + 'frame': 17887, + 'frame_number': 17887, + 'framesequence': 68485, + 'gaze_dir': array([0.98949432, 0.13624573, 0.04584503]), + 'gaze_origin': array([-3.03583455, -0.11281814, 0.08611756]), + 'gaze_valid': True, + 'gaze_vergence': 179.16726684570312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98745728, 0.14828491, 0.05393982]), + 'left_gaze_origin': array([-2.98961496, 3.08303547, 0.09543152]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9831390380859375, + 'left_pupil_posn': array([ 0.14770901, -0.03507936]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99153137, 0.12420654, 0.03775024]), + 'right_gaze_origin': array([-3.08205438, -3.30867171, 0.07680359]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9717864990234375, + 'right_pupil_posn': array([ 0.1318841 , -0.10140383]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0315866582095623, + 'throttle_input': 0.1111009418964386, + 'timestamp': 581.3992511667311, + 'timestamp_carla': 581399, + 'timestamp_device': 24644, + 'timestamp_stream': 581.3992511667311, + 'transform': [array([-9.60440040e-01, -1.66826210e+01, 9.77951009e-03]), + array([-0.06283091, 1.86862445, 0.01336671])]} +{'AngularVelocity': array([ 1.44686797e-04, 2.13625026e-03, -1.46165907e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17785359919071198, + 'FR_Wheel_Angle': 0.178162083029747, + 'Location': array([ 2.38471651, -17.51079941, 0.16728196]), + 'Rotation': array([-0.04589887, 31.4338913 , 0.04380121]), + 'Velocity': array([ 0.00146065, 0.00079252, -0.00023417]), + 'brake_input': 0.0, + 'camera_location': array([-6.86003304, 16.24999237, 1.9411509 ]), + 'camera_rotation': array([-6.50634241, 8.24666882, 5.04208994]), + 'current_gear_input': False, + 'focus_actor_dist': 1074.2996826171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -488.72189331, -1964.27514648, 57.7522049 ]), + 'frame': 17888, + 'frame_number': 17888, + 'framesequence': 68490, + 'gaze_dir': array([0.9911499 , 0.12685394, 0.03705597]), + 'gaze_origin': array([-3.07073474, -0.10264663, 0.09954224]), + 'gaze_valid': True, + 'gaze_vergence': 193.2838134765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98982239, 0.13485718, 0.04521179]), + 'left_gaze_origin': array([-3.01987004, 3.09387064, 0.10747376]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.914703369140625, + 'left_pupil_posn': array([ 0.13875961, -0.03541899]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99247742, 0.11885071, 0.02890015]), + 'right_gaze_origin': array([-3.12159896, -3.29916406, 0.09161072]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.874969482421875, + 'right_pupil_posn': array([ 0.12172747, -0.10144377]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03556016832590103, + 'throttle_input': 0.13492026925086975, + 'timestamp': 581.4363612681627, + 'timestamp_carla': 581437, + 'timestamp_device': 24685, + 'timestamp_stream': 581.4363612681627, + 'transform': [array([-9.60599184e-01, -1.66825905e+01, 9.79024824e-03]), + array([-0.06286506, 1.86947477, 0.0131836 ])]} +{'AngularVelocity': array([ 0.00023054, 0.00180136, -0.14643811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17785149812698364, + 'FR_Wheel_Angle': 0.1781555563211441, + 'Location': array([ 2.3846066 , -17.51087952, 0.16727893]), + 'Rotation': array([-0.04593302, 31.43398666, 0.04379928]), + 'Velocity': array([-0.00270855, -0.00174868, -0.00010707]), + 'brake_input': 0.0, + 'camera_location': array([-6.8002243 , 16.39792442, 1.86611009]), + 'camera_rotation': array([-6.76075315, 8.9827776 , 5.22604322]), + 'current_gear_input': False, + 'focus_actor_dist': 1069.7078857421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -493.88604736, -1971.8527832 , 43.80799866]), + 'frame': 17889, + 'frame_number': 17889, + 'framesequence': 68494, + 'gaze_dir': array([0.99170685, 0.11859131, 0.04740906]), + 'gaze_origin': array([-3.02318048, -0.09207001, 0.08697128]), + 'gaze_valid': True, + 'gaze_vergence': 207.8180694580078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99000549, 0.13031006, 0.05371094]), + 'left_gaze_origin': array([-2.96352553, 3.10550094, 0.09253998]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.03411865234375, + 'left_pupil_posn': array([ 0.12642121, -0.03095067]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9934082 , 0.10687256, 0.04110718]), + 'right_gaze_origin': array([-3.08283544, -3.28964114, 0.08140259]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0188751220703125, + 'right_pupil_posn': array([ 0.11271238, -0.09820628]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04024781286716461, + 'throttle_input': 0.16269169747829437, + 'timestamp': 581.468200866133, + 'timestamp_carla': 581468, + 'timestamp_device': 24719, + 'timestamp_stream': 581.468200866133, + 'transform': [array([-9.60899651e-01, -1.66822948e+01, 9.89925396e-03]), + array([-0.06283091, 1.87092686, 0.01281739])]} +{'AngularVelocity': array([ 0.00046191, 0.00158747, -0.14582992]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17783230543136597, + 'FR_Wheel_Angle': 0.17813651263713837, + 'Location': array([ 2.38337111, -17.51164436, 0.16728213]), + 'Rotation': array([-0.04593302, 31.43398666, 0.04379928]), + 'Velocity': array([-7.86877610e-03, -4.89878235e-03, 1.33132935e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.74710083, 16.53016281, 1.80809164]), + 'camera_rotation': array([-7.07380819, 9.64985085, 5.42275476]), + 'current_gear_input': False, + 'focus_actor_dist': 1066.5064697265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -498.78744507, -1976.04504395, 50.54016113]), + 'frame': 17890, + 'frame_number': 17890, + 'framesequence': 68497, + 'gaze_dir': array([0.99367523, 0.10202789, 0.04579163]), + 'gaze_origin': array([-3.04430246, -0.08652344, 0.09827653]), + 'gaze_valid': True, + 'gaze_vergence': 319.6853332519531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99263 , 0.11183167, 0.0466156 ]), + 'left_gaze_origin': array([-2.99104166, 3.11052561, 0.10433808]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.095550537109375, + 'left_pupil_posn': array([ 0.11818659, -0.02655268]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99472046, 0.09222412, 0.04496765]), + 'right_gaze_origin': array([-3.09756327, -3.28357267, 0.09221497]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.95458984375, + 'right_pupil_posn': array([ 0.1025331 , -0.09572256]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.044898830354213715, + 'throttle_input': 0.19839780032634735, + 'timestamp': 581.4968241676688, + 'timestamp_carla': 581497, + 'timestamp_device': 24744, + 'timestamp_stream': 581.4968241676688, + 'transform': [array([-9.59472358e-01, -1.66817074e+01, 1.00115584e-02]), + array([-0.06292653, 1.86456048, 0.01217653])]} +{'AngularVelocity': array([-8.18693894e-04, -8.97415885e-05, 1.34451434e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1778120994567871, + 'FR_Wheel_Angle': 0.17811541259288788, + 'Location': array([ 2.38102007, -17.51310921, 0.16728923]), + 'Rotation': array([-0.04589887, 31.43567085, 0.04380765]), + 'Velocity': array([-0.01301198, -0.00800236, 0.00063689]), + 'brake_input': 0.0, + 'camera_location': array([-6.69892311, 16.63902664, 1.74563801]), + 'camera_rotation': array([-7.39828968, 10.2030859 , 5.57013941]), + 'current_gear_input': False, + 'focus_actor_dist': 1069.0391845703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -494.4659729 , -1972.48608398, 43.78573608]), + 'frame': 17891, + 'frame_number': 17891, + 'framesequence': 68501, + 'gaze_dir': array([0.99393463, 0.09394073, 0.05447388]), + 'gaze_origin': array([-3.02381229, -0.07914658, 0.09515076]), + 'gaze_valid': True, + 'gaze_vergence': 185.44442749023438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99235535, 0.11097717, 0.0539093 ]), + 'left_gaze_origin': array([-2.9560411 , 3.11782408, 0.09626771]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9826202392578125, + 'left_pupil_posn': array([ 0.10789287, -0.02194405]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99551392, 0.0769043 , 0.05503845]), + 'right_gaze_origin': array([-3.09158349, -3.27611709, 0.09403381]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9805908203125, + 'right_pupil_posn': array([ 0.0971036 , -0.09074247]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04923856630921364, + 'throttle_input': 0.23411917686462402, + 'timestamp': 581.5294664688408, + 'timestamp_carla': 581530, + 'timestamp_device': 24777, + 'timestamp_stream': 581.5294664688408, + 'transform': [array([-9.59750831e-01, -1.66809082e+01, 1.00954240e-02]), + array([-0.062988 , 1.86569107, 0.01190186])]} +{'AngularVelocity': array([-0.00026483, -0.00085924, 0.14238958]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17779316008090973, + 'FR_Wheel_Angle': 0.1780969500541687, + 'Location': array([ 2.37738299, -17.51534081, 0.16729729]), + 'Rotation': array([-0.04589887, 31.43553352, 0.04379231]), + 'Velocity': array([-1.78180244e-02, -1.09199844e-02, -5.28907767e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.63593292, 16.74010086, 1.71016932]), + 'camera_rotation': array([-7.51028442, 10.65075874, 5.53628922]), + 'current_gear_input': False, + 'focus_actor_dist': 1066.989013671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -496.41186523, -1974.75415039, 47.58097839]), + 'frame': 17892, + 'frame_number': 17892, + 'framesequence': 68505, + 'gaze_dir': array([0.99549103, 0.07849121, 0.05014801]), + 'gaze_origin': array([-3.06554818, -0.07491913, 0.10728913]), + 'gaze_valid': True, + 'gaze_vergence': 179.7188720703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99401855, 0.09593201, 0.05209351]), + 'left_gaze_origin': array([-3.03939843, 3.12188578, 0.12253571]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.91156005859375, + 'left_pupil_posn': array([ 0.1000638 , -0.02149272]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9969635 , 0.06105042, 0.04820251]), + 'right_gaze_origin': array([-3.09169769, -3.27172399, 0.09204254]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.962005615234375, + 'right_pupil_posn': array([ 0.08888102, -0.09251821]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05454878509044647, + 'throttle_input': 0.2658579349517822, + 'timestamp': 581.5618121661246, + 'timestamp_carla': 581562, + 'timestamp_device': 24810, + 'timestamp_stream': 581.5618121661246, + 'transform': [array([-9.61778224e-01, -1.66792431e+01, 1.03129577e-02]), + array([-0.06317241, 1.87436366, 0.01098634])]} +{'AngularVelocity': array([-0.00050632, -0.00052818, 0.13860145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1560630202293396, + 'FR_Wheel_Angle': 0.15373478829860687, + 'Location': array([ 2.37256098, -17.51830101, 0.16730617]), + 'Rotation': array([-0.04589887, 31.43541527, 0.04377316]), + 'Velocity': array([-2.34687459e-02, -1.43750235e-02, 3.74793999e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.53515816, 16.82349586, 1.67830408]), + 'camera_rotation': array([-7.56594372, 10.93183804, 5.50422049]), + 'current_gear_input': False, + 'focus_actor_dist': 1073.8009033203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -490.19241333, -1966.01379395, 41.76355743]), + 'frame': 17893, + 'frame_number': 17893, + 'framesequence': 68509, + 'gaze_dir': array([0.99546051, 0.07363892, 0.05872345]), + 'gaze_origin': array([-3.0706706 , -0.07256088, 0.10794983]), + 'gaze_valid': True, + 'gaze_vergence': 238.5038604736328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99438477, 0.08670044, 0.06051636]), + 'left_gaze_origin': array([-3.04038095, 3.12381911, 0.12167664]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8528289794921875, + 'left_pupil_posn': array([ 0.09860194, -0.01929224]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99653625, 0.06057739, 0.05693054]), + 'right_gaze_origin': array([-3.10096002, -3.26894069, 0.09422303]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9766998291015625, + 'right_pupil_posn': array([ 0.08402431, -0.08980572]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.059822384268045425, + 'throttle_input': 0.2896620035171509, + 'timestamp': 581.5958408676088, + 'timestamp_carla': 581596, + 'timestamp_device': 24844, + 'timestamp_stream': 581.5958408676088, + 'transform': [array([-9.64101672e-01, -1.66756878e+01, 1.07500460e-02]), + array([-0.06341831, 1.88375735, 0.00900269])]} +{'AngularVelocity': array([ 0.00046919, -0.00173012, 0.1463746 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1713799089193344, + 'FR_Wheel_Angle': 0.2882438004016876, + 'Location': array([ 2.36666417, -17.52191734, 0.16729164]), + 'Rotation': array([-0.04589887, 31.43541527, 0.04377316]), + 'Velocity': array([-0.02546543, -0.01559327, -0.00016968]), + 'brake_input': 0.0, + 'camera_location': array([-6.43937683, 16.87328148, 1.64620721]), + 'camera_rotation': array([-7.73408937, 11.05301666, 5.60131359]), + 'current_gear_input': False, + 'focus_actor_dist': 1071.658935546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -490.7958374 , -1967.40356445, 50.53374481]), + 'frame': 17894, + 'frame_number': 17894, + 'framesequence': 68513, + 'gaze_dir': array([0.99551392, 0.06819916, 0.06414795]), + 'gaze_origin': array([-3.05414152, -0.06338272, 0.10739289]), + 'gaze_valid': True, + 'gaze_vergence': 190.0627899169922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99429321, 0.0783844 , 0.07229614]), + 'left_gaze_origin': array([-3.01689768, 3.13468361, 0.11896516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9607086181640625, + 'left_pupil_posn': array([ 0.09030271, -0.01710558]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99673462, 0.05801392, 0.05599976]), + 'right_gaze_origin': array([-3.09138513, -3.26144886, 0.09582063]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9526824951171875, + 'right_pupil_posn': array([ 0.07593167, -0.0826906 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06535233557224274, + 'throttle_input': 0.3174487054347992, + 'timestamp': 581.6280399672687, + 'timestamp_carla': 581628, + 'timestamp_device': 24877, + 'timestamp_stream': 581.6280399672687, + 'transform': [array([-9.64446366e-01, -1.66708755e+01, 1.12020113e-02]), + array([-0.06390325, 1.88366616, 0.00698853])]} +{'AngularVelocity': array([-1.29250868e-04, -1.66395179e-03, 1.33544594e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9889823198318481, + 'FR_Wheel_Angle': 2.370102643966675, + 'Location': array([ 2.3608346 , -17.52554131, 0.16729064]), + 'Rotation': array([-0.04571445, 31.43320084, 0.04371253]), + 'Velocity': array([-0.02344321, -0.01494749, -0.00035827]), + 'brake_input': 0.0, + 'camera_location': array([-6.34096718, 16.90081215, 1.60438573]), + 'camera_rotation': array([-7.95046282, 11.06078911, 5.60217428]), + 'current_gear_input': False, + 'focus_actor_dist': 1073.43603515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -488.84625244, -1964.21630859, 53.42494202]), + 'frame': 17895, + 'frame_number': 17895, + 'framesequence': 68517, + 'gaze_dir': array([0.99559784, 0.04917145, 0.07894897]), + 'gaze_origin': array([-3.06180429, -0.05121231, 0.11973572]), + 'gaze_valid': True, + 'gaze_vergence': 213.88092041015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99461365, 0.05722046, 0.08634949]), + 'left_gaze_origin': array([-3.02034163, 3.14475107, 0.13221741]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.93792724609375, + 'left_pupil_posn': array([ 0.0777179 , -0.00363612]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99658203, 0.04112244, 0.07154846]), + 'right_gaze_origin': array([-3.10326695, -3.24717569, 0.10725403]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.880767822265625, + 'right_pupil_posn': array([ 0.05926907, -0.07200062]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07047944515943527, + 'throttle_input': 0.3452201187610626, + 'timestamp': 581.6617460660636, + 'timestamp_carla': 581662, + 'timestamp_device': 24910, + 'timestamp_stream': 581.6617460660636, + 'transform': [array([-9.67444301e-01, -1.66639442e+01, 1.16848275e-02]), + array([-0.06444966, 1.89452577, 0.00476075])]} +{'AngularVelocity': array([ 0.0121351 , -0.00860292, -0.34809172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.083179473876953, + 'FR_Wheel_Angle': 4.442366600036621, + 'Location': array([ 2.33090806, -17.5450058 , 0.16739109]), + 'Rotation': array([-0.05557042, 31.38993645, 0.04423287]), + 'Velocity': array([-0.21619278, -0.14452493, 0.00071452]), + 'brake_input': 0.0, + 'camera_location': array([-6.23988533, 16.91985321, 1.55289781]), + 'camera_rotation': array([-8.20030403, 10.9648447 , 5.53429985]), + 'current_gear_input': False, + 'focus_actor_dist': 1092.4794921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -476.54156494, -1939.08361816, 65.79125214]), + 'frame': 17896, + 'frame_number': 17896, + 'framesequence': 68521, + 'gaze_dir': array([0.99546051, 0.04653931, 0.08178711]), + 'gaze_origin': array([-3.06021976, -0.05159302, 0.11947937]), + 'gaze_valid': True, + 'gaze_vergence': 112.94220733642578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99417114, 0.05311584, 0.09368896]), + 'left_gaze_origin': array([-3.00908828, 3.14537811, 0.12905426]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.930633544921875, + 'left_pupil_posn': array([ 0.07688057, -0.00422788]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99674988, 0.03996277, 0.06988525]), + 'right_gaze_origin': array([-3.11135101, -3.24856424, 0.10990448]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.926177978515625, + 'right_pupil_posn': array([ 0.05899537, -0.06906462]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.075789675116539, + 'throttle_input': 0.37299153208732605, + 'timestamp': 581.6961185671389, + 'timestamp_carla': 581696, + 'timestamp_device': 24944, + 'timestamp_stream': 581.6961185671389, + 'transform': [array([-9.68060732e-01, -1.66554585e+01, 1.20818894e-02]), + array([-0.0647297 , 1.89423287, 0.0029297 ])]} +{'AngularVelocity': array([ 0.02208039, -0.02010684, -0.30733407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.294539451599121, + 'FR_Wheel_Angle': 4.45684814453125, + 'Location': array([ 2.28810644, -17.57321548, 0.16736552]), + 'Rotation': array([-0.04779083, 31.31410027, 0.04217966]), + 'Velocity': array([-0.17084675, -0.11467413, 0.00075697]), + 'brake_input': 0.0, + 'camera_location': array([-6.16597176, 16.92514229, 1.50450611]), + 'camera_rotation': array([-8.46720028, 10.85062408, 5.48521042]), + 'current_gear_input': False, + 'focus_actor_dist': 1096.32080078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -473.54348755, -1933.51818848, 64.2122345 ]), + 'frame': 17897, + 'frame_number': 17897, + 'framesequence': 68525, + 'gaze_dir': array([0.99539185, 0.04918671, 0.08169556]), + 'gaze_origin': array([-3.06092548, -0.05166702, 0.12135011]), + 'gaze_valid': True, + 'gaze_vergence': 262.1291809082031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99453735, 0.05679321, 0.08753967]), + 'left_gaze_origin': array([-3.00366235, 3.14539528, 0.12779999]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.933502197265625, + 'left_pupil_posn': array([ 0.07742679, -0.00204706]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99624634, 0.0415802 , 0.07585144]), + 'right_gaze_origin': array([-3.11818862, -3.24872923, 0.11490021]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9044952392578125, + 'right_pupil_posn': array([ 0.06051254, -0.06906462]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08139286935329437, + 'throttle_input': 0.3968108594417572, + 'timestamp': 581.729738265276, + 'timestamp_carla': 581730, + 'timestamp_device': 24977, + 'timestamp_stream': 581.729738265276, + 'transform': [array([-9.73943889e-01, -1.66448498e+01, 1.24320313e-02]), + array([-6.50643781e-02, 1.91651726e+00, 1.34277751e-03])]} +{'AngularVelocity': array([ 0.00496854, -0.00140698, -0.20467171]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.2085089683532715, + 'FR_Wheel_Angle': 4.327394485473633, + 'Location': array([ 2.25575113, -17.59445572, 0.16739532]), + 'Rotation': array([-0.04464211, 31.25816345, 0.0409284 ]), + 'Velocity': array([-0.11885241, -0.07936306, 0.00033169]), + 'brake_input': 0.0, + 'camera_location': array([-6.09441185, 16.93356514, 1.45819843]), + 'camera_rotation': array([-8.65538597, 10.7614727 , 5.41491938]), + 'current_gear_input': False, + 'focus_actor_dist': 1090.6005859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -472.57403564, -1938.61413574, 59.222435 ]), + 'frame': 17898, + 'frame_number': 17898, + 'framesequence': 68529, + 'gaze_dir': array([0.99513245, 0.04953003, 0.08452606]), + 'gaze_origin': array([-3.06408477, -0.05183945, 0.122361 ]), + 'gaze_valid': True, + 'gaze_vergence': 262.3992004394531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99424744, 0.05752563, 0.09024048]), + 'left_gaze_origin': array([-3.00393534, 3.14537811, 0.12899323]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.95513916015625, + 'left_pupil_posn': array([ 0.07742679, -0.00034511]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99601746, 0.04153442, 0.07881165]), + 'right_gaze_origin': array([-3.1242342 , -3.24905705, 0.11572877]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9044189453125, + 'right_pupil_posn': array([ 0.06112301, -0.06866777]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0867946445941925, + 'throttle_input': 0.40871289372444153, + 'timestamp': 581.7625895664096, + 'timestamp_carla': 581763, + 'timestamp_device': 25010, + 'timestamp_stream': 581.7625895664096, + 'transform': [array([-9.82313991e-01, -1.66322060e+01, 1.28256604e-02]), + array([-6.56176209e-02, 1.94878840e+00, -4.37125913e-04])]} +{'AngularVelocity': array([ 0.00017254, 0.00337401, -0.11202168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.142764091491699, + 'FR_Wheel_Angle': 2.8870880603790283, + 'Location': array([ 2.23254156, -17.60957527, 0.16740237]), + 'Rotation': array([-0.04479921, 31.22119331, 0.04028452]), + 'Velocity': array([-0.08124924, -0.05319896, 0.00013604]), + 'brake_input': 0.0, + 'camera_location': array([-6.01433754, 16.9194355 , 1.41812563]), + 'camera_rotation': array([-8.81790352, 10.69592571, 5.44728947]), + 'current_gear_input': False, + 'focus_actor_dist': 1090.4088134765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -471.92559814, -1937.53540039, 58.78321075]), + 'frame': 17899, + 'frame_number': 17899, + 'framesequence': 68533, + 'gaze_dir': array([0.99465179, 0.05088043, 0.08930969]), + 'gaze_origin': array([-3.06474924, -0.0521698 , 0.12311783]), + 'gaze_valid': True, + 'gaze_vergence': 290.6455383300781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99380493, 0.05924988, 0.09391785]), + 'left_gaze_origin': array([-3.00393534, 3.14494634, 0.12899323]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.96112060546875, + 'left_pupil_posn': array([0.07805872, 0.00161451]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99549866, 0.04251099, 0.08470154]), + 'right_gaze_origin': array([-3.12556314, -3.24928617, 0.11724244]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9073333740234375, + 'right_pupil_posn': array([ 0.06192946, -0.06667089]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09173864126205444, + 'throttle_input': 0.4166475832462311, + 'timestamp': 581.7947447672486, + 'timestamp_carla': 581795, + 'timestamp_device': 25044, + 'timestamp_stream': 581.7947447672486, + 'transform': [array([-9.88682389e-01, -1.66173172e+01, 1.33824246e-02]), + array([-0.06632113, 1.97100508, -0.00295063])]} +{'AngularVelocity': array([ 0.0032512 , -0.00903264, 0.00038978]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.9534290432929993, + 'FR_Wheel_Angle': -1.350760817527771, + 'Location': array([ 2.21912956, -17.61798096, 0.16743445]), + 'Rotation': array([-0.04387713, 31.21117592, 0.03985806]), + 'Velocity': array([-0.02284263, -0.01382449, 0.00051752]), + 'brake_input': 0.0, + 'camera_location': array([-5.9312439 , 16.91495323, 1.3913734 ]), + 'camera_rotation': array([-8.97441769, 10.60895824, 5.39496231]), + 'current_gear_input': False, + 'focus_actor_dist': 1089.3016357421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -473.0619812 , -1937.54174805, 60.82466125]), + 'frame': 17900, + 'frame_number': 17900, + 'framesequence': 68537, + 'gaze_dir': array([0.99451447, 0.05125427, 0.09057617]), + 'gaze_origin': array([-3.06836176, -0.05426026, 0.12556382]), + 'gaze_valid': True, + 'gaze_vergence': 321.6993713378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99397278, 0.06114197, 0.09092712]), + 'left_gaze_origin': array([-2.99930453, 3.1429491 , 0.12795106]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9904327392578125, + 'left_pupil_posn': array([0.07901037, 0.00360513]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99505615, 0.04136658, 0.09022522]), + 'right_gaze_origin': array([-3.13741946, -3.25146961, 0.12317658]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9087677001953125, + 'right_pupil_posn': array([ 0.06432033, -0.06586063]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09582202136516571, + 'throttle_input': 0.4166475832462311, + 'timestamp': 581.8296973668039, + 'timestamp_carla': 581830, + 'timestamp_device': 25077, + 'timestamp_stream': 581.8296973668039, + 'transform': [array([-9.97924030e-01, -1.65990887e+01, 1.36912148e-02]), + array([-0.06679925, 2.00439334, -0.00444645])]} +{'AngularVelocity': array([-0.00565578, 0.00998188, -0.12793432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.439746618270874, + 'FR_Wheel_Angle': -3.681896924972534, + 'Location': array([ 2.21711516, -17.61916924, 0.16743183]), + 'Rotation': array([-0.04550272, 31.21210861, 0.04016236]), + 'Velocity': array([-7.90356752e-03, -4.51744860e-03, 6.62279126e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.8393364 , 16.90253639, 1.37475932]), + 'camera_rotation': array([-9.00003719, 10.56934834, 5.41949081]), + 'current_gear_input': False, + 'focus_actor_dist': 1087.5911865234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -471.9491272 , -1937.53613281, 59.41448212]), + 'frame': 17901, + 'frame_number': 17901, + 'framesequence': 68541, + 'gaze_dir': array([0.99223328, 0.03735352, 0.11843872]), + 'gaze_origin': array([-3.05748224, -0.04775391, 0.12864381]), + 'gaze_valid': True, + 'gaze_vergence': 492.0851745605469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99188232, 0.04368591, 0.11936951]), + 'left_gaze_origin': array([-3.00424504, 3.14869237, 0.1388962 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.90777587890625, + 'left_pupil_posn': array([0.07166147, 0.01945585]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99258423, 0.03102112, 0.11750793]), + 'right_gaze_origin': array([-3.11071944, -3.24420023, 0.11839142]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.039520263671875, + 'right_pupil_posn': array([ 0.05290425, -0.05445588]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09988708794116974, + 'throttle_input': 0.42061492800712585, + 'timestamp': 581.8621314652264, + 'timestamp_carla': 581862, + 'timestamp_device': 25110, + 'timestamp_stream': 581.8621314652264, + 'transform': [array([-1.01052392e+00, -1.65792599e+01, 1.40719507e-02]), + array([-0.06725687, 2.05189896, -0.00614033])]} +{'AngularVelocity': array([-0.00137518, 0.00551486, -0.1109363 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.386738300323486, + 'FR_Wheel_Angle': -6.418211460113525, + 'Location': array([ 2.21500707, -17.62035179, 0.16743709]), + 'Rotation': array([-0.04708732, 31.21636009, 0.04018584]), + 'Velocity': array([-0.01189875, -0.00630802, -0.00012734]), + 'brake_input': 0.0, + 'camera_location': array([-5.73607635, 16.88804817, 1.34935117]), + 'camera_rotation': array([-9.02399731, 10.48438644, 5.48923683]), + 'current_gear_input': False, + 'focus_actor_dist': 1133.5191650390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -472.77227783, -1886.36621094, 88.57501221]), + 'frame': 17902, + 'frame_number': 17902, + 'framesequence': 68545, + 'gaze_dir': array([0.99200439, 0.03730774, 0.120224 ]), + 'gaze_origin': array([-3.06098652, -0.05004044, 0.12962265]), + 'gaze_valid': True, + 'gaze_vergence': 226.6560821533203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9909668 , 0.04289246, 0.12704468]), + 'left_gaze_origin': array([-3.00738239, 3.14657307, 0.13970186]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.995391845703125, + 'left_pupil_posn': array([0.07331944, 0.01789361]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99304199, 0.03172302, 0.11340332]), + 'right_gaze_origin': array([-3.11459064, -3.2466538 , 0.11954346]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9525146484375, + 'right_pupil_posn': array([ 0.05440927, -0.05182528]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10338450968265533, + 'throttle_input': 0.4285496175289154, + 'timestamp': 581.8942662663758, + 'timestamp_carla': 581894, + 'timestamp_device': 25144, + 'timestamp_stream': 581.8942662663758, + 'transform': [array([-1.02603161e+00, -1.65572147e+01, 1.43808359e-02]), + array([-0.06787159, 2.1110692 , -0.00754052])]} +{'AngularVelocity': array([ 0.00121701, 0.00473044, -0.04845392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.220942497253418, + 'FR_Wheel_Angle': -9.787193298339844, + 'Location': array([ 2.21096134, -17.62248039, 0.16744709]), + 'Rotation': array([-0.0478523 , 31.22834778, 0.03995747]), + 'Velocity': array([-0.02383715, -0.01148479, 0.00029465]), + 'brake_input': 0.0, + 'camera_location': array([-5.63751602, 16.87345123, 1.31588387]), + 'camera_rotation': array([-9.20165062, 10.36662865, 5.45812511]), + 'current_gear_input': False, + 'focus_actor_dist': 1136.1639404296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -473.21582031, -1881.6204834 , 89.97408295]), + 'frame': 17903, + 'frame_number': 17903, + 'framesequence': 68549, + 'gaze_dir': array([0.99222565, 0.03874207, 0.11805725]), + 'gaze_origin': array([-3.06703067, -0.05118561, 0.13155822]), + 'gaze_valid': True, + 'gaze_vergence': 441.826904296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99163818, 0.04374695, 0.12133789]), + 'left_gaze_origin': array([-3.00468922, 3.14644313, 0.13937226]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9958038330078125, + 'left_pupil_posn': array([0.07410014, 0.01856965]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99281311, 0.03373718, 0.11477661]), + 'right_gaze_origin': array([-3.12937164, -3.24881458, 0.1237442 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.017974853515625, + 'right_pupil_posn': array([ 0.05645084, -0.05364764]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10647907853126526, + 'throttle_input': 0.4404516816139221, + 'timestamp': 581.9290009662509, + 'timestamp_carla': 581929, + 'timestamp_device': 25177, + 'timestamp_stream': 581.9290009662509, + 'transform': [array([-1.04382110e+00, -1.65300102e+01, 1.48699665e-02]), + array([-0.06878683, 2.17765617, -0.00987645])]} +{'AngularVelocity': array([0.00417034, 0.00186602, 0.01244503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.426553726196289, + 'FR_Wheel_Angle': -13.019344329833984, + 'Location': array([ 2.20430517, -17.62573242, 0.16737652]), + 'Rotation': array([-0.04782498, 31.25709915, 0.03970567]), + 'Velocity': array([-0.03030263, -0.01290783, -0.00015344]), + 'brake_input': 0.0, + 'camera_location': array([-5.55042839, 16.85424423, 1.28364074]), + 'camera_rotation': array([-9.32719612, 10.23263836, 5.44862795]), + 'current_gear_input': False, + 'focus_actor_dist': 1126.72314453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -471.00311279, -1888.7935791 , 84.31684875]), + 'frame': 17904, + 'frame_number': 17904, + 'framesequence': 68553, + 'gaze_dir': array([0.99181366, 0.04184723, 0.12030792]), + 'gaze_origin': array([-3.07215977, -0.05154877, 0.13247529]), + 'gaze_valid': True, + 'gaze_vergence': 354.73651123046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99107361, 0.04872131, 0.12405396]), + 'left_gaze_origin': array([-3.00003219, 3.14614582, 0.13723603]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.997802734375, + 'left_pupil_posn': array([0.07471919, 0.01857841]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99255371, 0.03497314, 0.11656189]), + 'right_gaze_origin': array([-3.14428735, -3.24924326, 0.12771454]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0081787109375, + 'right_pupil_posn': array([ 0.05879152, -0.05276859]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10986664146184921, + 'throttle_input': 0.45235371589660645, + 'timestamp': 581.9622514657676, + 'timestamp_carla': 581962, + 'timestamp_device': 25210, + 'timestamp_stream': 581.9622514657676, + 'transform': [array([-1.06165099e+00, -1.65013237e+01, 1.52018834e-02]), + array([-0.06936739, 2.2432704 , -0.01139276])]} +{'AngularVelocity': array([0.0041532 , 0.0017885 , 0.08368067]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.760406494140625, + 'FR_Wheel_Angle': -14.608930587768555, + 'Location': array([ 2.19598079, -17.6295166 , 0.16747035]), + 'Rotation': array([-0.04766106, 31.30201149, 0.03959687]), + 'Velocity': array([-0.03240596, -0.01277438, -0.00019559]), + 'brake_input': 0.0, + 'camera_location': array([-5.48897362, 16.83820534, 1.23674929]), + 'camera_rotation': array([-9.56423855, 10.12660503, 5.39242697]), + 'current_gear_input': False, + 'focus_actor_dist': 1118.810302734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -471.42797852, -1894.33666992, 84.48840332]), + 'frame': 17905, + 'frame_number': 17905, + 'framesequence': 68557, + 'gaze_dir': array([0.99147797, 0.04386139, 0.12217712]), + 'gaze_origin': array([-3.07025313, -0.0558342 , 0.13355333]), + 'gaze_valid': True, + 'gaze_vergence': 298.2341613769531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99072266, 0.05389404, 0.12466431]), + 'left_gaze_origin': array([-3.00076294, 3.14108777, 0.13828889]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9976806640625, + 'left_pupil_posn': array([0.07773864, 0.02018005]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99223328, 0.03382874, 0.11968994]), + 'right_gaze_origin': array([-3.13974333, -3.25275588, 0.12881775]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0555877685546875, + 'right_pupil_posn': array([ 0.06290054, -0.05110168]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11268655210733414, + 'throttle_input': 0.45235371589660645, + 'timestamp': 581.9952661655843, + 'timestamp_carla': 581996, + 'timestamp_device': 25244, + 'timestamp_stream': 581.9952661655843, + 'transform': [array([-1.08174157e+00, -1.64702015e+01, 1.54315187e-02]), + array([-0.06973623, 2.31752992, -0.01242412])]} +{'AngularVelocity': array([0.00406033, 0.00277397, 0.0889419 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.786270141601562, + 'FR_Wheel_Angle': -15.283597946166992, + 'Location': array([ 2.18990803, -17.6321888 , 0.16746837]), + 'Rotation': array([-0.04753811, 31.33797264, 0.0395742 ]), + 'Velocity': array([-0.0299354 , -0.01144962, 0.0001936 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.44385529, 16.81674576, 1.18534994]), + 'camera_rotation': array([-9.85752678, 10.01375961, 5.29309273]), + 'current_gear_input': False, + 'focus_actor_dist': 1109.4200439453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.62579346, -1901.05065918, 82.28701782]), + 'frame': 17906, + 'frame_number': 17906, + 'framesequence': 68561, + 'gaze_dir': array([0.99114227, 0.04218292, 0.12567139]), + 'gaze_origin': array([-3.0705049 , -0.05686188, 0.13435899]), + 'gaze_valid': True, + 'gaze_vergence': 411.5008239746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99050903, 0.0486145 , 0.12852478]), + 'left_gaze_origin': array([-3.00500512, 3.14014149, 0.14054413]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.013214111328125, + 'left_pupil_posn': array([0.0790565 , 0.02198058]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99177551, 0.03575134, 0.12281799]), + 'right_gaze_origin': array([-3.13600492, -3.25386524, 0.12817384]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.031585693359375, + 'right_pupil_posn': array([ 0.06176174, -0.04950929]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11545152217149734, + 'throttle_input': 0.4563210606575012, + 'timestamp': 582.028007466346, + 'timestamp_carla': 582028, + 'timestamp_device': 25277, + 'timestamp_stream': 582.028007466346, + 'transform': [array([-1.10694635e+00, -1.64356976e+01, 1.58251002e-02]), + array([-0.07085638, 2.41216302, -0.01426827])]} +{'AngularVelocity': array([0.00445199, 0.00347256, 0.07523929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.602542877197266, + 'FR_Wheel_Angle': -16.011770248413086, + 'Location': array([ 2.18274832, -17.63529778, 0.16747008]), + 'Rotation': array([-0.04753811, 31.38209534, 0.03947684]), + 'Velocity': array([-0.02523123, -0.0093008 , 0.00049043]), + 'brake_input': 0.0, + 'camera_location': array([-5.42304039, 16.82209015, 1.14671457]), + 'camera_rotation': array([-10.0810585 , 9.94083786, 5.12841415]), + 'current_gear_input': False, + 'focus_actor_dist': 1112.52734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -469.3380127 , -1894.40063477, 80.59356689]), + 'frame': 17907, + 'frame_number': 17907, + 'framesequence': 68565, + 'gaze_dir': array([0.99099731, 0.04351807, 0.12636566]), + 'gaze_origin': array([-3.07025623, -0.05762787, 0.13497086]), + 'gaze_valid': True, + 'gaze_vergence': 488.57684326171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99058533, 0.04986572, 0.12739563]), + 'left_gaze_origin': array([-3.00882888, 3.13963342, 0.14226075]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.00518798828125, + 'left_pupil_posn': array([0.07990026, 0.02328181]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9914093 , 0.03717041, 0.12533569]), + 'right_gaze_origin': array([-3.13168359, -3.25488901, 0.12768097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.031524658203125, + 'right_pupil_posn': array([ 0.0628047 , -0.04946482]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11797846108675003, + 'throttle_input': 0.4563210606575012, + 'timestamp': 582.0618568658829, + 'timestamp_carla': 582062, + 'timestamp_device': 25310, + 'timestamp_stream': 582.0618568658829, + 'transform': [array([-1.12926555e+00, -1.63979473e+01, 1.60222817e-02]), + array([-0.07119789, 2.49191737, -0.01519034])]} +{'AngularVelocity': array([0.00500807, 0.00514273, 0.0951177 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.417003631591797, + 'FR_Wheel_Angle': -17.299713134765625, + 'Location': array([ 2.1772511 , -17.6376133 , 0.16748737]), + 'Rotation': array([-0.04769521, 31.41893387, 0.03923621]), + 'Velocity': array([-0.02478382, -0.00857633, 0.00015547]), + 'brake_input': 0.0, + 'camera_location': array([-5.40834618, 16.83095551, 1.12103832]), + 'camera_rotation': array([-10.31048393, 9.88556767, 5.07654905]), + 'current_gear_input': False, + 'focus_actor_dist': 1101.6397705078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.27557373, -1902.11303711, 77.67634583]), + 'frame': 17908, + 'frame_number': 17908, + 'framesequence': 68569, + 'gaze_dir': array([0.99053192, 0.04420471, 0.12976074]), + 'gaze_origin': array([-3.0741694 , -0.05745926, 0.13620912]), + 'gaze_valid': True, + 'gaze_vergence': 470.30078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99023438, 0.05097961, 0.12971497]), + 'left_gaze_origin': array([-3.01233387, 3.1397934 , 0.14418183]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0059661865234375, + 'left_pupil_posn': array([0.07990026, 0.02543879]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99082947, 0.03742981, 0.12980652]), + 'right_gaze_origin': array([-3.13600492, -3.2547121 , 0.12823638]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0293426513671875, + 'right_pupil_posn': array([ 0.06316984, -0.04907298]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12078005820512772, + 'throttle_input': 0.4563210606575012, + 'timestamp': 582.0958544686437, + 'timestamp_carla': 582096, + 'timestamp_device': 25344, + 'timestamp_stream': 582.0958544686437, + 'transform': [array([-1.15692747e+00, -1.63564644e+01, 1.62783135e-02]), + array([-0.07183993, 2.59293795, -0.01639929])]} +{'AngularVelocity': array([0.00574455, 0.00772292, 0.1496301 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.133230209350586, + 'FR_Wheel_Angle': -17.656476974487305, + 'Location': array([ 2.17189264, -17.63982201, 0.16748309]), + 'Rotation': array([-0.04809819, 31.45701218, 0.03888111]), + 'Velocity': array([-0.03219115, -0.01112991, -0.00025103]), + 'brake_input': 0.0, + 'camera_location': array([-5.36509895, 16.83734894, 1.11224627]), + 'camera_rotation': array([-10.31734848, 9.84727955, 5.09847307]), + 'current_gear_input': False, + 'focus_actor_dist': 1095.3800048828125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.38116455, -1904.85339355, 77.36399841]), + 'frame': 17909, + 'frame_number': 17909, + 'framesequence': 68573, + 'gaze_dir': array([0.99005127, 0.04464722, 0.13314819]), + 'gaze_origin': array([-3.07672668, -0.05745697, 0.13693391]), + 'gaze_valid': True, + 'gaze_vergence': 378.05322265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98931885, 0.05154419, 0.13633728]), + 'left_gaze_origin': array([-3.01777673, 3.13986397, 0.14563142]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0052032470703125, + 'left_pupil_posn': array([0.07997608, 0.02548981]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99078369, 0.03775024, 0.12995911]), + 'right_gaze_origin': array([-3.13567662, -3.25477767, 0.12823638]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0317230224609375, + 'right_pupil_posn': array([ 0.06343579, -0.04676127]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12387463450431824, + 'throttle_input': 0.4563210606575012, + 'timestamp': 582.1273531652987, + 'timestamp_carla': 582128, + 'timestamp_device': 25377, + 'timestamp_stream': 582.1273531652987, + 'transform': [array([ -1.18657529, -16.31464005, 0.0166086 ]), + array([-0.0726937 , 2.70190263, -0.01787461])]} +{'AngularVelocity': array([ 4.61823161e-04, -2.51109898e-02, 2.65587926e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.101669311523438, + 'FR_Wheel_Angle': -17.64070701599121, + 'Location': array([ 2.11027074, -17.66584778, 0.16766483]), + 'Rotation': array([-7.00026080e-02, 3.19160919e+01, 2.40299925e-02]), + 'Velocity': array([-5.13663232e-01, -1.92039147e-01, 3.85313033e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.31553459, 16.84049606, 1.10066974]), + 'camera_rotation': array([-10.30596256, 9.79613495, 5.08743143]), + 'current_gear_input': False, + 'focus_actor_dist': 1092.6119384765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.10821533, -1903.81103516, 81.05421448]), + 'frame': 17910, + 'frame_number': 17910, + 'framesequence': 68577, + 'gaze_dir': array([0.98987579, 0.04554749, 0.13407898]), + 'gaze_origin': array([-3.07472992, -0.05793457, 0.13693391]), + 'gaze_valid': True, + 'gaze_vergence': 354.8388671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98910522, 0.05325317, 0.137146 ]), + 'left_gaze_origin': array([-3.01777673, 3.13960433, 0.14563142]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0140838623046875, + 'left_pupil_posn': array([0.08018458, 0.02588809]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99064636, 0.0378418 , 0.13101196]), + 'right_gaze_origin': array([-3.13168359, -3.25547338, 0.12823638]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.038665771484375, + 'right_pupil_posn': array([ 0.0644294 , -0.04579043]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1268959641456604, + 'throttle_input': 0.4563210606575012, + 'timestamp': 582.1628395654261, + 'timestamp_carla': 582163, + 'timestamp_device': 25410, + 'timestamp_stream': 582.1628395654261, + 'transform': [array([ -1.22345293, -16.26408195, 0.01685214]), + array([-0.07358162, 2.83736205, -0.01912454])]} +{'AngularVelocity': array([-1.27465313e-03, -6.81140572e-02, 3.01682734e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.40578269958496, + 'FR_Wheel_Angle': -17.862031936645508, + 'Location': array([ 1.98720443, -17.71842766, 0.1670039 ]), + 'Rotation': array([-8.54798108e-02, 3.27794609e+01, -2.58178674e-02]), + 'Velocity': array([-5.61486602e-01, -2.15250328e-01, 4.47616563e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.27550697, 16.84689331, 1.08445179]), + 'camera_rotation': array([-10.28400326, 9.70174313, 5.14248371]), + 'current_gear_input': False, + 'focus_actor_dist': 1087.214111328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -471.18170166, -1905.40344238, 82.51158905]), + 'frame': 17911, + 'frame_number': 17911, + 'framesequence': 68581, + 'gaze_dir': array([0.99014282, 0.05164337, 0.12995911]), + 'gaze_origin': array([-3.09439087, -0.06544876, 0.13571778]), + 'gaze_valid': True, + 'gaze_vergence': 442.05230712890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9899292 , 0.05867004, 0.12879944]), + 'left_gaze_origin': array([-3.01264977, 3.13209248, 0.13537905]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22650146484375, + 'left_pupil_posn': array([0.08753586, 0.01959115]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99035645, 0.0446167 , 0.13111877]), + 'right_gaze_origin': array([-3.1761322 , -3.26299 , 0.13605653]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0352630615234375, + 'right_pupil_posn': array([ 0.07234585, -0.05141413]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13165685534477234, + 'throttle_input': 0.4563210606575012, + 'timestamp': 582.1958854682744, + 'timestamp_carla': 582196, + 'timestamp_device': 25444, + 'timestamp_stream': 582.1958854682744, + 'transform': [array([ -1.2614522 , -16.21364594, 0.01708353]), + array([-0.07458566, 2.97679162, -0.0202037 ])]} +{'AngularVelocity': array([-0.04947511, -0.07677084, 3.94121051]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.336702346801758, + 'FR_Wheel_Angle': -16.590734481811523, + 'Location': array([ 1.8470546 , -17.78021049, 0.16719921]), + 'Rotation': array([-7.85540044e-02, 3.37941933e+01, -1.95617657e-02]), + 'Velocity': array([-0.60834348, -0.25650761, 0.00113049]), + 'brake_input': 0.0, + 'camera_location': array([-5.20769119, 16.84357834, 1.08608174]), + 'camera_rotation': array([-10.24037266, 9.60062313, 5.31382513]), + 'current_gear_input': False, + 'focus_actor_dist': 1064.7889404296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -472.3192749 , -1924.16345215, 79.05498505]), + 'frame': 17912, + 'frame_number': 17912, + 'framesequence': 68585, + 'gaze_dir': array([0.96828461, 0.21526337, 0.12552643]), + 'gaze_origin': array([-3.08541274, -0.18865128, 0.11999971]), + 'gaze_valid': True, + 'gaze_vergence': 172.7998504638672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96438599, 0.23277283, 0.12556458]), + 'left_gaze_origin': array([-3.02446604, 3.00099039, 0.12566987]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1175537109375, + 'left_pupil_posn': array([0.22944689, 0.00740159]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97218323, 0.19775391, 0.12548828]), + 'right_gaze_origin': array([-3.14635944, -3.37829304, 0.11432953]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1116943359375, + 'right_pupil_posn': array([ 0.21169078, -0.06508946]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13718681037425995, + 'throttle_input': 0.4563210606575012, + 'timestamp': 582.2279714681208, + 'timestamp_carla': 582228, + 'timestamp_device': 25477, + 'timestamp_stream': 582.2279714681208, + 'transform': [array([ -1.30216622, -16.16156387, 0.01728286]), + array([-0.0757468 , 3.12604046, -0.02113944])]} +{'AngularVelocity': array([-0.03728759, -0.06629366, 2.42572498]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.888282775878906, + 'FR_Wheel_Angle': -9.430631637573242, + 'Location': array([ 1.74037004, -17.83268738, 0.16733101]), + 'Rotation': array([-7.19901919e-02, 3.44387550e+01, -1.11694327e-02]), + 'Velocity': array([-0.51096559, -0.26141313, 0.00133647]), + 'brake_input': 0.0, + 'camera_location': array([-5.17265892, 16.84236145, 1.07310402]), + 'camera_rotation': array([-10.47501659, 9.49546719, 5.26448536]), + 'current_gear_input': False, + 'focus_actor_dist': 1078.8929443359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -643.13897705, -1970.26025391, 62.54389954]), + 'frame': 17913, + 'frame_number': 17913, + 'framesequence': 68590, + 'gaze_dir': array([0.95210266, 0.27739716, 0.12732697]), + 'gaze_origin': array([-3.09809661, -0.23635712, 0.12525864]), + 'gaze_valid': True, + 'gaze_vergence': 168.4681854248047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9468689 , 0.29368591, 0.13098145]), + 'left_gaze_origin': array([-3.03749561, 2.94789124, 0.13128662]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1288909912109375, + 'left_pupil_posn': array([0.28809881, 0.00679237]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95733643, 0.2611084 , 0.12367249]), + 'right_gaze_origin': array([-3.15869761, -3.42060542, 0.11923065]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.071929931640625, + 'right_pupil_posn': array([ 0.26321614, -0.06392407]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14330272376537323, + 'throttle_input': 0.4325169622898102, + 'timestamp': 582.2684360668063, + 'timestamp_carla': 582269, + 'timestamp_device': 25519, + 'timestamp_stream': 582.2684360668063, + 'transform': [array([ -1.35906184, -16.09185791, 0.01738979]), + array([-0.07721528, 3.33438325, -0.02171318])]} +{'AngularVelocity': array([ 0.00877698, 0.01736379, -0.22933544]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.6713368892669678, + 'FR_Wheel_Angle': -1.6795523166656494, + 'Location': array([ 1.63552225, -17.89473343, 0.16744289]), + 'Rotation': array([-6.87253624e-02, 3.47569771e+01, -9.46044829e-03]), + 'Velocity': array([-0.40151405, -0.25356263, 0.00054817]), + 'brake_input': 0.0, + 'camera_location': array([-5.14949417, 16.83236694, 1.06250668]), + 'camera_rotation': array([-10.61425686, 9.45589447, 5.33952284]), + 'current_gear_input': False, + 'focus_actor_dist': 1109.8382568359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -720.89178467, -1970.98876953, 55.34732056]), + 'frame': 17914, + 'frame_number': 17914, + 'framesequence': 68593, + 'gaze_dir': array([0.95330048, 0.27446747, 0.12508392]), + 'gaze_origin': array([-3.09770584, -0.23732148, 0.12402193]), + 'gaze_valid': True, + 'gaze_vergence': 206.0393829345703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94906616, 0.28820801, 0.12721252]), + 'left_gaze_origin': array([-3.03737807, 2.9484849 , 0.12950288]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09600830078125, + 'left_pupil_posn': array([0.28758383, 0.00543594]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95753479, 0.26072693, 0.12295532]), + 'right_gaze_origin': array([-3.15803409, -3.42312789, 0.11854096]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.108489990234375, + 'right_pupil_posn': array([ 0.26288867, -0.06548238]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15135960280895233, + 'throttle_input': 0.42458227276802063, + 'timestamp': 582.2960080653429, + 'timestamp_carla': 582296, + 'timestamp_device': 25544, + 'timestamp_stream': 582.2960080653429, + 'transform': [array([ -1.40201867, -16.04159927, 0.01745858]), + array([-0.07849253, 3.49157953, -0.02225277])]} +{'AngularVelocity': array([ 0.13767898, -0.15492775, -0.30633003]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.57132196, -17.93771744, 0.16744675]), + 'Rotation': array([-5.50854728e-02, 3.47883835e+01, -1.37634268e-02]), + 'Velocity': array([ 5.68028027e-03, 3.71360919e-03, -5.76019283e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.10544395, 16.83495712, 1.09510159]), + 'camera_rotation': array([-10.42192554, 9.49135494, 5.29111814]), + 'current_gear_input': False, + 'focus_actor_dist': 1103.273681640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -718.27978516, -1970.16174316, 50.50311279]), + 'frame': 17915, + 'frame_number': 17915, + 'framesequence': 68597, + 'gaze_dir': array([0.95265198, 0.27593994, 0.12615204]), + 'gaze_origin': array([-3.09805536, -0.23731233, 0.12032166]), + 'gaze_valid': True, + 'gaze_vergence': 155.13412475585938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94699097, 0.29399109, 0.12944031]), + 'left_gaze_origin': array([-3.03659225, 2.95050669, 0.12578431]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0618896484375, + 'left_pupil_posn': array([0.28525233, 0.00324708]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95831299, 0.25788879, 0.12286377]), + 'right_gaze_origin': array([-3.15951848, -3.42513132, 0.11485901]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0753936767578125, + 'right_pupil_posn': array([ 0.26648104, -0.06756651]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1564134657382965, + 'throttle_input': 0.4166475832462311, + 'timestamp': 582.3290720656514, + 'timestamp_carla': 582329, + 'timestamp_device': 25577, + 'timestamp_stream': 582.3290720656514, + 'transform': [array([ -1.45756888, -15.97906113, 0.0174702 ]), + array([-0.07989955, 3.69457769, -0.02237571])]} +{'AngularVelocity': array([-0.04099707, 0.07310283, -0.19813204]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.61396492, -17.90814209, 0.16738373]), + 'Rotation': array([-5.46893217e-02, 3.47889595e+01, -1.74560510e-02]), + 'Velocity': array([ 0.24064869, 0.16686603, -0.00037634]), + 'brake_input': 0.0, + 'camera_location': array([-5.11285973, 16.85206795, 1.10082853]), + 'camera_rotation': array([-10.43612576, 9.47579288, 5.13576603]), + 'current_gear_input': False, + 'focus_actor_dist': 1099.1697998046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -721.73602295, -1971.05908203, 55.77026367]), + 'frame': 17916, + 'frame_number': 17916, + 'framesequence': 68602, + 'gaze_dir': array([0.95108795, 0.28144073, 0.12640381]), + 'gaze_origin': array([-3.09822631, -0.23696062, 0.12218323]), + 'gaze_valid': True, + 'gaze_vergence': 194.1241455078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94648743, 0.29589844, 0.12882996]), + 'left_gaze_origin': array([-3.03679514, 2.95164967, 0.12787019]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17138671875, + 'left_pupil_posn': array([0.2875607 , 0.00451165]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95568848, 0.26698303, 0.12397766]), + 'right_gaze_origin': array([-3.15965748, -3.42557096, 0.11649628]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0907745361328125, + 'right_pupil_posn': array([ 0.26743746, -0.06683528]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1613391488790512, + 'throttle_input': 0.40871289372444153, + 'timestamp': 582.3675805665553, + 'timestamp_carla': 582368, + 'timestamp_device': 25619, + 'timestamp_stream': 582.3675805665553, + 'transform': [array([ -1.52749383, -15.90320969, 0.01733342]), + array([-0.081088 , 3.94958091, -0.02202737])]} +{'AngularVelocity': array([-0.03915107, 0.0588293 , -1.17899585]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4588097631931305, + 'FR_Wheel_Angle': 0.4611095190048218, + 'Location': array([ 1.66921699, -17.86974907, 0.16739364]), + 'Rotation': array([-6.96747527e-02, 3.47873802e+01, -1.87072735e-02]), + 'Velocity': array([ 0.2013132 , 0.14089505, -0.00040256]), + 'brake_input': 0.0, + 'camera_location': array([-5.14067268, 16.85589981, 1.12096047]), + 'camera_rotation': array([-10.4365015 , 9.38845634, 5.03048229]), + 'current_gear_input': False, + 'focus_actor_dist': 1097.87451171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -730.28436279, -1970.78491211, 56.52845001]), + 'frame': 17917, + 'frame_number': 17917, + 'framesequence': 68606, + 'gaze_dir': array([0.94861603, 0.28890991, 0.12850952]), + 'gaze_origin': array([-3.09958959, -0.24037401, 0.12089691]), + 'gaze_valid': True, + 'gaze_vergence': 234.6409912109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94526672, 0.29740906, 0.1341095 ]), + 'left_gaze_origin': array([-3.03817153, 2.94936538, 0.12731324]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0984954833984375, + 'left_pupil_posn': array([0.29391384, 0.00320077]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95196533, 0.28041077, 0.12290955]), + 'right_gaze_origin': array([-3.16100788, -3.43011355, 0.11448059]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0624847412109375, + 'right_pupil_posn': array([ 0.27127051, -0.06662464]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16564227640628815, + 'throttle_input': 0.3928435146808624, + 'timestamp': 582.402693066746, + 'timestamp_carla': 582403, + 'timestamp_device': 25652, + 'timestamp_stream': 582.402693066746, + 'transform': [array([ -1.59592986, -15.83121681, 0.01726936]), + array([-0.08203056, 4.19838858, -0.02174051])]} +{'AngularVelocity': array([-0.0020969 , 0.00513995, -1.33096349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.46030551195144653, + 'FR_Wheel_Angle': 0.46263259649276733, + 'Location': array([ 1.69846749, -17.84933853, 0.16739097]), + 'Rotation': array([-7.87930563e-02, 3.47949600e+01, -1.87988244e-02]), + 'Velocity': array([ 0.06959419, 0.04876524, -0.00057235]), + 'brake_input': 0.0, + 'camera_location': array([-5.1648674 , 16.86124611, 1.17063057]), + 'camera_rotation': array([-10.25346565, 9.18557835, 4.84645176]), + 'current_gear_input': False, + 'focus_actor_dist': 1096.735107421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -740.9822998 , -1970.10693359, 59.26093292]), + 'frame': 17918, + 'frame_number': 17918, + 'framesequence': 68610, + 'gaze_dir': array([0.94878387, 0.29211426, 0.11976624]), + 'gaze_origin': array([-3.09844828, -0.2422844 , 0.12083665]), + 'gaze_valid': True, + 'gaze_vergence': 270.36767578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94538879, 0.30232239, 0.12176514]), + 'left_gaze_origin': array([-3.03713989, 2.94756341, 0.12873383]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.212310791015625, + 'left_pupil_posn': array([0.29558444, 0.00249535]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95217896, 0.28190613, 0.11776733]), + 'right_gaze_origin': array([-3.15975666, -3.43213224, 0.11293946]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0693511962890625, + 'right_pupil_posn': array([ 0.27420092, -0.0719955 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1676931083202362, + 'throttle_input': 0.3769741356372833, + 'timestamp': 582.4357848651707, + 'timestamp_carla': 582436, + 'timestamp_device': 25685, + 'timestamp_stream': 582.4357848651707, + 'transform': [array([ -1.66416037, -15.76094437, 0.01723946]), + array([-0.08270676, 4.44553757, -0.02152194])]} +{'AngularVelocity': array([-0.00148727, 0.01091752, 1.09732664]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.45782071352005005, + 'FR_Wheel_Angle': 0.45934200286865234, + 'Location': array([ 1.68943906, -17.85519028, 0.16747269]), + 'Rotation': array([-8.67912099e-02, 3.47665291e+01, -1.88598596e-02]), + 'Velocity': array([-0.16913681, -0.11606034, 0.00019643]), + 'brake_input': 0.0, + 'camera_location': array([-5.16748238, 16.86805344, 1.19698536]), + 'camera_rotation': array([-10.07185078, 9.0358305 , 4.73530054]), + 'current_gear_input': False, + 'focus_actor_dist': 1090.052734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -741.43536377, -1970.86254883, 54.44617462]), + 'frame': 17919, + 'frame_number': 17919, + 'framesequence': 68614, + 'gaze_dir': array([0.94590759, 0.30247498, 0.11664581]), + 'gaze_origin': array([-3.10039473, -0.243351 , 0.11798477]), + 'gaze_valid': True, + 'gaze_vergence': 237.99404907226562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94204712, 0.31317139, 0.12026978]), + 'left_gaze_origin': array([-3.03851032, 2.94596434, 0.12495423]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22601318359375, + 'left_pupil_posn': array([ 0.30016696, -0.00219274]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94976807, 0.29177856, 0.11302185]), + 'right_gaze_origin': array([-3.16227889, -3.43266606, 0.11101533]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.08209228515625, + 'right_pupil_posn': array([ 0.27866399, -0.07446659]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16793116927146912, + 'throttle_input': 0.37299153208732605, + 'timestamp': 582.4691915661097, + 'timestamp_carla': 582469, + 'timestamp_device': 25719, + 'timestamp_stream': 582.4691915661097, + 'transform': [array([ -1.73585129, -15.68798161, 0.01714142]), + array([-0.08294582, 4.70402765, -0.02099602])]} +{'AngularVelocity': array([ 0.0489496 , -0.0640055 , -0.12938313]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4549006521701813, + 'FR_Wheel_Angle': 0.4568713307380676, + 'Location': array([ 1.58619976, -17.92739105, 0.16765682]), + 'Rotation': array([-9.57933962e-02, 3.47539940e+01, -1.85241681e-02]), + 'Velocity': array([-0.56841415, -0.39773262, 0.00083296]), + 'brake_input': 0.0, + 'camera_location': array([-5.15039062, 16.87032318, 1.19734478]), + 'camera_rotation': array([-9.93246746, 8.93056107, 4.88335943]), + 'current_gear_input': False, + 'focus_actor_dist': 1089.888427734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -753.7487793 , -1970.90039062, 54.69068146]), + 'frame': 17920, + 'frame_number': 17920, + 'framesequence': 68617, + 'gaze_dir': array([0.94641876, 0.30041504, 0.11726379]), + 'gaze_origin': array([-3.10020757, -0.24727327, 0.12179261]), + 'gaze_valid': True, + 'gaze_vergence': 178.02972412109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94114685, 0.31590271, 0.12010193]), + 'left_gaze_origin': array([-3.03742528, 2.94258881, 0.12882844]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.20330810546875, + 'left_pupil_posn': array([0.3000493 , 0.00128824]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95169067, 0.28492737, 0.11442566]), + 'right_gaze_origin': array([-3.16299009, -3.43713546, 0.11475678]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0767822265625, + 'right_pupil_posn': array([ 0.28278673, -0.07223618]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16710714995861053, + 'throttle_input': 0.3650568425655365, + 'timestamp': 582.4986279681325, + 'timestamp_carla': 582499, + 'timestamp_device': 25744, + 'timestamp_stream': 582.4986279681325, + 'transform': [array([ -1.80220377, -15.62270737, 0.01682995]), + array([-0.0823311 , 4.94389963, -0.01964363])]} +{'AngularVelocity': array([ 0.01373502, -0.01855266, -0.09108834]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5552520751953125, + 'FR_Wheel_Angle': 0.6919798254966736, + 'Location': array([ 1.44517744, -18.02587128, 0.16776031]), + 'Rotation': array([-8.36834759e-02, 3.47278328e+01, -1.87072754e-02]), + 'Velocity': array([-0.65383393, -0.457284 , 0.00126506]), + 'brake_input': 0.0, + 'camera_location': array([-5.1875267 , 16.84418106, 1.16544032]), + 'camera_rotation': array([-10.16343021, 8.69815445, 4.97050047]), + 'current_gear_input': False, + 'focus_actor_dist': 1082.6751708984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -751.99804688, -1970.06445312, 57.59877014]), + 'frame': 17921, + 'frame_number': 17921, + 'framesequence': 68621, + 'gaze_dir': array([0.94307709, 0.30862427, 0.12284088]), + 'gaze_origin': array([-3.09976053, -0.24685058, 0.1276001 ]), + 'gaze_valid': True, + 'gaze_vergence': 177.73275756835938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93795776, 0.32196045, 0.12863159]), + 'left_gaze_origin': array([-3.03839421, 2.94006824, 0.13581239]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2758026123046875, + 'left_pupil_posn': array([0.3054086 , 0.00630307]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9505435824394226, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94819641, 0.29528809, 0.11705017]), + 'right_gaze_origin': array([-3.16112685, -3.43376946, 0.11938782]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16583251953125, + 'right_pupil_posn': array([ 0.28259611, -0.06614614]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.165294349193573, + 'throttle_input': 0.35712215304374695, + 'timestamp': 582.5302146673203, + 'timestamp_carla': 582530, + 'timestamp_device': 25777, + 'timestamp_stream': 582.5302146673203, + 'transform': [array([ -1.87435949, -15.55099583, 0.01674266]), + array([-0.08212619, 5.20271015, -0.01900159])]} +{'AngularVelocity': array([ 0.02446599, -0.03401767, -0.47104385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9785302877426147, + 'FR_Wheel_Angle': 2.1832172870635986, + 'Location': array([ 1.28693795, -18.13728905, 0.16791283]), + 'Rotation': array([-7.71196634e-02, 3.46565361e+01, -1.75476074e-02]), + 'Velocity': array([-0.66491163, -0.47646871, 0.00079496]), + 'brake_input': 0.0, + 'camera_location': array([-5.21710396, 16.82400894, 1.14676106]), + 'camera_rotation': array([-10.23361683, 8.48854637, 4.91684198]), + 'current_gear_input': False, + 'focus_actor_dist': 1079.696533203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -760.15795898, -1971.41809082, 58.93914795]), + 'frame': 17922, + 'frame_number': 17922, + 'framesequence': 68625, + 'gaze_dir': array([0.94271088, 0.3126297 , 0.115448 ]), + 'gaze_origin': array([-3.09913349, -0.24918976, 0.1312294 ]), + 'gaze_valid': True, + 'gaze_vergence': 176.52957153320312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93792725, 0.32444763, 0.1224823 ]), + 'left_gaze_origin': array([-3.03768182, 2.93763447, 0.13991241]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.190155029296875, + 'left_pupil_posn': array([0.30895627, 0.00609863]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94749451, 0.30081177, 0.1084137 ]), + 'right_gaze_origin': array([-3.16058517, -3.43601418, 0.12254639]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.185028076171875, + 'right_pupil_posn': array([ 0.28500605, -0.06604242]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16274911165237427, + 'throttle_input': 0.3531548082828522, + 'timestamp': 582.563776768744, + 'timestamp_carla': 582564, + 'timestamp_device': 25810, + 'timestamp_stream': 582.563776768744, + 'transform': [array([ -1.95210016, -15.47314548, 0.01664108]), + array([-0.08168906, 5.47958279, -0.01838688])]} +{'AngularVelocity': array([ 0.01759187, -0.00560139, -0.55960953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.433664321899414, + 'FR_Wheel_Angle': 2.6054959297180176, + 'Location': array([ 1.14044726, -18.2422924 , 0.16805755]), + 'Rotation': array([-7.08563775e-02, 3.45234222e+01, -1.81274358e-02]), + 'Velocity': array([-0.59086037, -0.42716396, 0.00075329]), + 'brake_input': 0.0, + 'camera_location': array([-5.2038765 , 16.81140518, 1.1598295 ]), + 'camera_rotation': array([-9.96358585, 8.32388496, 4.96920061]), + 'current_gear_input': False, + 'focus_actor_dist': 1075.8687744140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -763.10827637, -1970.70019531, 50.17120361]), + 'frame': 17923, + 'frame_number': 17923, + 'framesequence': 68629, + 'gaze_dir': array([0.9414444 , 0.31666565, 0.11518097]), + 'gaze_origin': array([-3.09972095, -0.25241929, 0.12573166]), + 'gaze_valid': True, + 'gaze_vergence': 278.0500183105469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93832397, 0.32667542, 0.11315918]), + 'left_gaze_origin': array([-3.03896642, 2.93488789, 0.13413849]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.313446044921875, + 'left_pupil_posn': array([0.31301153, 0.00479609]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94456482, 0.30665588, 0.11720276]), + 'right_gaze_origin': array([-3.16047525, -3.43972635, 0.11732484]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.196685791015625, + 'right_pupil_posn': array([ 0.28822052, -0.072999 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15998414158821106, + 'throttle_input': 0.3531548082828522, + 'timestamp': 582.5981256663799, + 'timestamp_carla': 582598, + 'timestamp_device': 25843, + 'timestamp_stream': 582.5981256663799, + 'transform': [array([ -2.03287578, -15.39185715, 0.01653391]), + array([-0.08111532, 5.76544571, -0.01776533])]} +{'AngularVelocity': array([ 0.00838784, 0.0021231 , -0.72610515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.4787144660949707, + 'FR_Wheel_Angle': 3.825026035308838, + 'Location': array([ 1.01101029, -18.33550644, 0.16821136]), + 'Rotation': array([-6.92990944e-02, 3.43717422e+01, -1.81274377e-02]), + 'Velocity': array([-0.51920819, -0.38020271, 0.00087045]), + 'brake_input': 0.0, + 'camera_location': array([-5.19042969, 16.78070831, 1.1993196 ]), + 'camera_rotation': array([-9.82649708, 8.23588753, 5.02098894]), + 'current_gear_input': False, + 'focus_actor_dist': 1069.3306884765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -766.69219971, -1971.66577148, 54.71337128]), + 'frame': 17924, + 'frame_number': 17924, + 'framesequence': 68633, + 'gaze_dir': array([0.94161987, 0.31908417, 0.10700226]), + 'gaze_origin': array([-3.09977746, -0.25444794, 0.12788393]), + 'gaze_valid': True, + 'gaze_vergence': 329.885986328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.938797 , 0.32643127, 0.10993958]), + 'left_gaze_origin': array([-3.03803134, 2.93445134, 0.13622895]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3073272705078125, + 'left_pupil_posn': array([0.31499755, 0.00175726]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94444275, 0.31173706, 0.10406494]), + 'right_gaze_origin': array([-3.16152358, -3.44334722, 0.11953889]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.195404052734375, + 'right_pupil_posn': array([ 0.29066026, -0.07280183]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15734735131263733, + 'throttle_input': 0.3491874635219574, + 'timestamp': 582.6308513656259, + 'timestamp_carla': 582631, + 'timestamp_device': 25877, + 'timestamp_stream': 582.6308513656259, + 'transform': [array([ -2.11078572, -15.31286716, 0.01648345]), + array([-0.0806577 , 6.03920555, -0.01735552])]} +{'AngularVelocity': array([ 0.00938698, 0.0089573 , -1.253227 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.485541343688965, + 'FR_Wheel_Angle': 4.688114166259766, + 'Location': array([ 0.89758819, -18.41838646, 0.16833203]), + 'Rotation': array([-6.88209832e-02, 3.41725273e+01, -1.80053674e-02]), + 'Velocity': array([-4.43330795e-01, -3.30596983e-01, 1.91631319e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.19260025, 16.74588013, 1.20825529]), + 'camera_rotation': array([-9.906847 , 8.09075451, 5.00274754]), + 'current_gear_input': False, + 'focus_actor_dist': 1065.11279296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -770.49060059, -1970.63745117, 48.34597778]), + 'frame': 17925, + 'frame_number': 17925, + 'framesequence': 68637, + 'gaze_dir': array([0.94178772, 0.31984711, 0.10316467]), + 'gaze_origin': array([-3.09993148, -0.25602114, 0.12665024]), + 'gaze_valid': True, + 'gaze_vergence': 271.4161376953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9389801 , 0.32647705, 0.10821533]), + 'left_gaze_origin': array([-3.03785419, 2.93285537, 0.13356781]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2618408203125, + 'left_pupil_posn': array([ 0.31663036, -0.00199795]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94459534, 0.31321716, 0.09811401]), + 'right_gaze_origin': array([-3.162009 , -3.44489765, 0.11973267]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2260284423828125, + 'right_pupil_posn': array([ 0.29171705, -0.07340825]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15505845844745636, + 'throttle_input': 0.3452201187610626, + 'timestamp': 582.6645483672619, + 'timestamp_carla': 582665, + 'timestamp_device': 25910, + 'timestamp_stream': 582.6645483672619, + 'transform': [array([ -2.19196987, -15.23003864, 0.01642304]), + array([-0.0802274 , 6.32245827, -0.01695254])]} +{'AngularVelocity': array([ 0.01586699, 0.00530625, -0.42375821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.313426971435547, + 'FR_Wheel_Angle': 4.4076828956604, + 'Location': array([ 0.80253446, -18.48797798, 0.16846958]), + 'Rotation': array([-6.88483045e-02, 3.39879227e+01, -1.88293438e-02]), + 'Velocity': array([-0.37585971, -0.27733716, 0.00053527]), + 'brake_input': 0.0, + 'camera_location': array([-5.19150543, 16.69421959, 1.24944663]), + 'camera_rotation': array([-9.76855659, 7.96180248, 5.15391111]), + 'current_gear_input': False, + 'focus_actor_dist': 1058.6943359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -770.69116211, -1970.03161621, 43.50003052]), + 'frame': 17926, + 'frame_number': 17926, + 'framesequence': 68641, + 'gaze_dir': array([0.97563171, 0.19152832, 0.10404968]), + 'gaze_origin': array([-3.07835555, -0.16487427, 0.12640305]), + 'gaze_valid': True, + 'gaze_vergence': 125.72370147705078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97122192, 0.21569824, 0.10096741]), + 'left_gaze_origin': array([-3.01751113, 3.03761601, 0.13256684]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1174468994140625, + 'left_pupil_posn': array([0.19367111, 0.00713998]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9800415 , 0.1673584 , 0.10713196]), + 'right_gaze_origin': array([-3.13919997, -3.36736488, 0.12023927]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.24114990234375, + 'right_pupil_posn': array([ 0.19755292, -0.06821704]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15280619263648987, + 'throttle_input': 0.3452201187610626, + 'timestamp': 582.697880666703, + 'timestamp_carla': 582698, + 'timestamp_device': 25943, + 'timestamp_stream': 582.697880666703, + 'transform': [array([ -2.27329421, -15.14666748, 0.01637666]), + array([-0.07992687, 6.60426331, -0.01661102])]} +{'AngularVelocity': array([ 0.01393985, -0.01153811, -0.50283414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.3753743171691895, + 'FR_Wheel_Angle': 1.921433448791504, + 'Location': array([ 0.71878678, -18.54840279, 0.16856918]), + 'Rotation': array([-6.91829845e-02, 3.38567085e+01, -1.95922814e-02]), + 'Velocity': array([-0.31786406, -0.22763896, 0.00038155]), + 'brake_input': 0.0, + 'camera_location': array([-5.18328285, 16.62224388, 1.28390431]), + 'camera_rotation': array([-9.62219906, 7.77102757, 5.14386559]), + 'current_gear_input': False, + 'focus_actor_dist': 973.002685546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -615.97814941, -1970.03857422, 58.52019501]), + 'frame': 17927, + 'frame_number': 17927, + 'framesequence': 68645, + 'gaze_dir': array([0.99364471, 0.04236603, 0.10404205]), + 'gaze_origin': array([-3.13820362, -0.03712311, 0.15174332]), + 'gaze_valid': True, + 'gaze_vergence': 710.1739501953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99339294, 0.04675293, 0.10466003]), + 'left_gaze_origin': array([-3.05189681, 3.15269947, 0.14869843]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3223114013671875, + 'left_pupil_posn': array([0.07131708, 0.01182318]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99389648, 0.03797913, 0.10342407]), + 'right_gaze_origin': array([-3.22451043, -3.22694564, 0.15478821]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1647796630859375, + 'right_pupil_posn': array([ 0.04443848, -0.05570471]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.150187686085701, + 'throttle_input': 0.3452201187610626, + 'timestamp': 582.7313464656472, + 'timestamp_carla': 582732, + 'timestamp_device': 25977, + 'timestamp_stream': 582.7313464656472, + 'transform': [array([ -2.35578322, -15.0615778 , 0.01633659]), + array([-0.07961951, 6.88799524, -0.01630366])]} +{'AngularVelocity': array([ 0.06212848, -0.10889946, 0.15493606]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.7016804218292236, + 'FR_Wheel_Angle': -1.9831933975219727, + 'Location': array([ 0.67191505, -18.58075714, 0.16853103]), + 'Rotation': array([-5.29134721e-02, 3.38374748e+01, -1.99584942e-02]), + 'Velocity': array([ 0.07028827, 0.04708511, -0.00048745]), + 'brake_input': 0.0, + 'camera_location': array([-5.18158531, 16.54994011, 1.28675056]), + 'camera_rotation': array([-9.60070419, 7.49879837, 4.95530653]), + 'current_gear_input': False, + 'focus_actor_dist': 939.7816162109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -473.87265015, -1939.26586914, 72.98266602]), + 'frame': 17928, + 'frame_number': 17928, + 'framesequence': 68649, + 'gaze_dir': array([0.9932785 , 0.03920746, 0.10814667]), + 'gaze_origin': array([-3.09934855, -0.04154129, 0.13774644]), + 'gaze_valid': True, + 'gaze_vergence': 262.5829772949219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99253845, 0.05070496, 0.11077881]), + 'left_gaze_origin': array([-3.04455113, 3.14929223, 0.14611512]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.296112060546875, + 'left_pupil_posn': array([0.0700928 , 0.01226622]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99401855, 0.02770996, 0.10551453]), + 'right_gaze_origin': array([-3.15414596, -3.23237467, 0.12937775]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2011871337890625, + 'right_pupil_posn': array([ 0.04810572, -0.05817652]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14610432088375092, + 'throttle_input': 0.3452201187610626, + 'timestamp': 582.7642377652228, + 'timestamp_carla': 582764, + 'timestamp_device': 26010, + 'timestamp_stream': 582.7642377652228, + 'transform': [array([ -2.43714929, -14.97659016, 0.01632385]), + array([-0.07919604, 7.16552973, -0.01608511])]} +{'AngularVelocity': array([-0.00840664, 0.00572171, 0.00281281]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.448064804077148, + 'FR_Wheel_Angle': -4.7390456199646, + 'Location': array([ 0.65173429, -18.59350586, 0.16866244]), + 'Rotation': array([-7.22019225e-02, 3.38615150e+01, -1.91345196e-02]), + 'Velocity': array([-0.10537203, -0.06411725, 0.00030856]), + 'brake_input': 0.0, + 'camera_location': array([-5.1914196 , 16.47119713, 1.29549551]), + 'camera_rotation': array([-9.55220318, 7.1428051 , 4.85477448]), + 'current_gear_input': False, + 'focus_actor_dist': 936.18310546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -471.91809082, -1932.8605957 , 77.77909851]), + 'frame': 17929, + 'frame_number': 17929, + 'framesequence': 68653, + 'gaze_dir': array([0.99253845, 0.04884338, 0.11118317]), + 'gaze_origin': array([-3.09519887, -0.04504471, 0.14167404]), + 'gaze_valid': True, + 'gaze_vergence': 296.40087890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99163818, 0.05732727, 0.11549377]), + 'left_gaze_origin': array([-3.04767942, 3.14693451, 0.1534134 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.306915283203125, + 'left_pupil_posn': array([0.07604825, 0.01691347]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99343872, 0.0403595 , 0.10687256]), + 'right_gaze_origin': array([-3.14271855, -3.23702383, 0.1299347 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2243194580078125, + 'right_pupil_posn': array([ 0.05338573, -0.05438304]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13971374928951263, + 'throttle_input': 0.34125277400016785, + 'timestamp': 582.7979222685099, + 'timestamp_carla': 582798, + 'timestamp_device': 26043, + 'timestamp_stream': 582.7979222685099, + 'transform': [array([ -2.51980877, -14.88817883, 0.01631949]), + array([-0.07830811, 7.44452906, -0.0158802 ])]} +{'AngularVelocity': array([-0.00292987, -0.00208654, -1.08058405]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.051177978515625, + 'FR_Wheel_Angle': -6.7219624519348145, + 'Location': array([ 0.63272858, -18.60508537, 0.16869369]), + 'Rotation': array([-7.11364150e-02, 3.39067230e+01, -1.82800256e-02]), + 'Velocity': array([-5.95633574e-02, -3.45624164e-02, 2.38609300e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.20629501, 16.4088707 , 1.33248758]), + 'camera_rotation': array([-9.45427227, 6.71573591, 4.60997105]), + 'current_gear_input': False, + 'focus_actor_dist': 926.9610595703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -478.28643799, -1935.07885742, 81.36030579]), + 'frame': 17930, + 'frame_number': 17930, + 'framesequence': 68657, + 'gaze_dir': array([0.99407959, 0.04414368, 0.09837341]), + 'gaze_origin': array([-3.08123493, -0.05216752, 0.13178025]), + 'gaze_valid': True, + 'gaze_vergence': 209.22616577148438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99291992, 0.05506897, 0.10516357]), + 'left_gaze_origin': array([-3.02428126, 3.1422503 , 0.14140016]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.220703125, + 'left_pupil_posn': array([0.0766989 , 0.00808901]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99523926, 0.03321838, 0.09158325]), + 'right_gaze_origin': array([-3.13818836, -3.24658537, 0.12216035]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.209625244140625, + 'right_pupil_posn': array([ 0.05893695, -0.06234729]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13158361613750458, + 'throttle_input': 0.34125277400016785, + 'timestamp': 582.8324518688023, + 'timestamp_carla': 582833, + 'timestamp_device': 26077, + 'timestamp_stream': 582.8324518688023, + 'transform': [array([ -2.60290337, -14.79612637, 0.01631847]), + array([-0.07690109, 7.72145414, -0.01564797])]} +{'AngularVelocity': array([-0.00552034, 0.00404416, -1.08180523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.48342227935791, + 'FR_Wheel_Angle': -6.980396270751953, + 'Location': array([ 0.6209771 , -18.61203575, 0.16871367]), + 'Rotation': array([-7.22019225e-02, 3.39387817e+01, -1.80969201e-02]), + 'Velocity': array([-4.70432602e-02, -2.70520300e-02, 3.73077382e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.15172386, 16.34911728, 1.41844404]), + 'camera_rotation': array([-8.96776485, 6.26079273, 4.71520329]), + 'current_gear_input': False, + 'focus_actor_dist': 919.6273193359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.03659058, -1931.17626953, 72.10876465]), + 'frame': 17931, + 'frame_number': 17931, + 'framesequence': 68661, + 'gaze_dir': array([0.99363708, 0.05031586, 0.09988403]), + 'gaze_origin': array([-3.08466339, -0.05542679, 0.12714769]), + 'gaze_valid': True, + 'gaze_vergence': 253.00799560546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99308777, 0.06283569, 0.09898376]), + 'left_gaze_origin': array([-3.01557159, 3.13821435, 0.1311554 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2048797607421875, + 'left_pupil_posn': array([0.08098531, 0.0059371 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9941864 , 0.03779602, 0.1007843 ]), + 'right_gaze_origin': array([-3.15375543, -3.24906778, 0.12313996]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.170257568359375, + 'right_pupil_posn': array([ 0.06359911, -0.06661773]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11993774026632309, + 'throttle_input': 0.33728542923927307, + 'timestamp': 582.8646612651646, + 'timestamp_carla': 582865, + 'timestamp_device': 26110, + 'timestamp_stream': 582.8646612651646, + 'transform': [array([ -2.67731929, -14.70880604, 0.01638962]), + array([-0.07495449, 7.96506119, -0.0155865 ])]} +{'AngularVelocity': array([-0.07495307, 0.21843493, 0.44480431]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.454956531524658, + 'FR_Wheel_Angle': -6.936031818389893, + 'Location': array([ 0.6018517 , -18.62339973, 0.16878295]), + 'Rotation': array([-8.21261927e-02, 3.39900093e+01, -2.02941913e-02]), + 'Velocity': array([-2.95538962e-01, -1.71110079e-01, 6.22940061e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.10490608, 16.29642868, 1.47616577]), + 'camera_rotation': array([-8.48541641, 5.83610392, 4.86220026]), + 'current_gear_input': False, + 'focus_actor_dist': 916.8275146484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -474.18310547, -1924.68774414, 80.99184418]), + 'frame': 17932, + 'frame_number': 17932, + 'framesequence': 68665, + 'gaze_dir': array([0.99364471, 0.05636597, 0.09656525]), + 'gaze_origin': array([-3.07432413, -0.05746231, 0.12340318]), + 'gaze_valid': True, + 'gaze_vergence': 259.58673095703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99273682, 0.06803894, 0.09907532]), + 'left_gaze_origin': array([-3.01001 , 3.13604283, 0.12695312]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.23028564453125, + 'left_pupil_posn': array([0.08480036, 0.00189537]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99455261, 0.04469299, 0.09405518]), + 'right_gaze_origin': array([-3.13863826, -3.25096774, 0.11985322]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.13397216796875, + 'right_pupil_posn': array([ 0.06637609, -0.06624591]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10574664175510406, + 'throttle_input': 0.3174487054347992, + 'timestamp': 582.8970583677292, + 'timestamp_carla': 582897, + 'timestamp_device': 26143, + 'timestamp_stream': 582.8970583677292, + 'transform': [array([ -2.74737 , -14.61944675, 0.01648566]), + array([-0.07214729, 8.18874931, -0.01556601])]} +{'AngularVelocity': array([-0.03437347, 0.03217709, 2.44742131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.395236015319824, + 'FR_Wheel_Angle': -6.875100612640381, + 'Location': array([ 0.48765883, -18.69150925, 0.16898334]), + 'Rotation': array([-9.11830217e-02, 3.42857018e+01, -2.19116230e-02]), + 'Velocity': array([-0.63213062, -0.37190634, 0.0007696 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.04284477, 16.25705719, 1.51802599]), + 'camera_rotation': array([-8.18390465, 5.38519382, 4.87729454]), + 'current_gear_input': False, + 'focus_actor_dist': 908.3921508789062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -476.00741577, -1924.22265625, 85.57807922]), + 'frame': 17933, + 'frame_number': 17933, + 'framesequence': 68669, + 'gaze_dir': array([0.99337769, 0.06236267, 0.09585571]), + 'gaze_origin': array([-3.05854034, -0.06353989, 0.10731049]), + 'gaze_valid': True, + 'gaze_vergence': 274.282470703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99235535, 0.07154846, 0.10049438]), + 'left_gaze_origin': array([-3.00416565, 3.13146663, 0.11638337]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2207183837890625, + 'left_pupil_posn': array([ 0.09075069, -0.0052439 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99440002, 0.05317688, 0.09121704]), + 'right_gaze_origin': array([-3.11291504, -3.25854635, 0.09823762]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1785888671875, + 'right_pupil_posn': array([ 0.07213318, -0.07569599]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09111606329679489, + 'throttle_input': 0.29364460706710815, + 'timestamp': 582.931765768677, + 'timestamp_carla': 582932, + 'timestamp_device': 26177, + 'timestamp_stream': 582.931765768677, + 'transform': [array([ -2.8162744 , -14.52210522, 0.01653109]), + array([-0.06860241, 8.40192795, -0.01532012])]} +{'AngularVelocity': array([ 0.00951435, -0.04461791, 1.67458427]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.743241786956787, + 'FR_Wheel_Angle': -3.6430211067199707, + 'Location': array([ 0.31288949, -18.79848862, 0.16916728]), + 'Rotation': array([-8.78293961e-02, 3.47054787e+01, -1.85241681e-02]), + 'Velocity': array([-8.15572798e-01, -5.04536450e-01, 6.63537940e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.96175194, 16.22782707, 1.5311985 ]), + 'camera_rotation': array([-7.92357922, 4.93301487, 4.82568932]), + 'current_gear_input': False, + 'focus_actor_dist': 901.904052734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -477.66464233, -1921.47998047, 89.60575867]), + 'frame': 17934, + 'frame_number': 17934, + 'framesequence': 68674, + 'gaze_dir': array([0.99378204, 0.0639267 , 0.09034729]), + 'gaze_origin': array([-3.063164 , -0.06604691, 0.10949402]), + 'gaze_valid': True, + 'gaze_vergence': 278.9502868652344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99287415, 0.07481384, 0.09263611]), + 'left_gaze_origin': array([-3.01586318, 3.12787962, 0.12168732]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1966094970703125, + 'left_pupil_posn': array([ 0.09316492, -0.00484204]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99468994, 0.05303955, 0.08805847]), + 'right_gaze_origin': array([-3.11046457, -3.25997329, 0.09730072]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.23065185546875, + 'right_pupil_posn': array([ 0.07412839, -0.07874405]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07335429638624191, + 'throttle_input': 0.26189059019088745, + 'timestamp': 582.9669694676995, + 'timestamp_carla': 582967, + 'timestamp_device': 26218, + 'timestamp_stream': 582.9669694676995, + 'transform': [array([ -2.87848878, -14.42175388, 0.01653861]), + array([-0.06454528, 8.58584499, -0.01483518])]} +{'AngularVelocity': array([ 0.02326733, -0.0405998 , -0.89601821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.8155879974365234, + 'FR_Wheel_Angle': 3.6334550380706787, + 'Location': array([ 0.13470753, -18.9201088 , 0.16931216]), + 'Rotation': array([-7.48315454e-02, 3.47569542e+01, -9.91821196e-03]), + 'Velocity': array([-7.17089891e-01, -5.26730776e-01, 7.14187627e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.9242382 , 16.19606018, 1.48087931]), + 'camera_rotation': array([-8.01848412, 4.49566412, 4.74256182]), + 'current_gear_input': False, + 'focus_actor_dist': 898.4276123046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -475.90130615, -1913.91101074, 88.84127808]), + 'frame': 17935, + 'frame_number': 17935, + 'framesequence': 68678, + 'gaze_dir': array([0.99376678, 0.0657196 , 0.08932495]), + 'gaze_origin': array([-3.06190133, -0.06631622, 0.11075593]), + 'gaze_valid': True, + 'gaze_vergence': 265.7276611328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9927063 , 0.07546997, 0.09391785]), + 'left_gaze_origin': array([-3.01836419, 3.12759089, 0.12561341]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2404937744140625, + 'left_pupil_posn': array([ 0.09437525, -0.0037477 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99482727, 0.05596924, 0.08473206]), + 'right_gaze_origin': array([-3.10543823, -3.26022363, 0.09589844]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.239227294921875, + 'right_pupil_posn': array([ 0.07442451, -0.07833374]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05802789703011513, + 'throttle_input': 0.19839780032634735, + 'timestamp': 583.002396967262, + 'timestamp_carla': 583003, + 'timestamp_device': 26252, + 'timestamp_stream': 583.002396967262, + 'transform': [array([ -2.93307114, -14.31927872, 0.01648046]), + array([-0.06057011, 8.73754025, -0.0140497 ])]} +{'AngularVelocity': array([ 1.27105205e-03, -1.76624246e-02, -2.07891417e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.14596939086914, + 'FR_Wheel_Angle': 9.693706512451172, + 'Location': array([ 2.04267493e-03, -1.90199986e+01, 1.69435695e-01]), + 'Rotation': array([-6.87253624e-02, 3.44624939e+01, -1.11389151e-02]), + 'Velocity': array([-6.02384269e-01, -4.87665176e-01, 5.30214282e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.86627388, 16.14485359, 1.41179788]), + 'camera_rotation': array([-8.07441711, 4.21563005, 5.05685759]), + 'current_gear_input': False, + 'focus_actor_dist': 893.559814453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -473.99569702, -1907.60302734, 86.62063599]), + 'frame': 17936, + 'frame_number': 17936, + 'framesequence': 68681, + 'gaze_dir': array([0.9937973 , 0.06802368, 0.0869751 ]), + 'gaze_origin': array([-3.05301666, -0.06738053, 0.10194321]), + 'gaze_valid': True, + 'gaze_vergence': 237.70947265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99263 , 0.07992554, 0.09106445]), + 'left_gaze_origin': array([-3.00310373, 3.12554789, 0.10817872]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.169219970703125, + 'left_pupil_posn': array([ 0.09573841, -0.01328766]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9949646 , 0.05612183, 0.08288574]), + 'right_gaze_origin': array([-3.10292983, -3.26030898, 0.09570771]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.232025146484375, + 'right_pupil_posn': array([ 0.07595766, -0.07902408]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.040009766817092896, + 'throttle_input': 0.1587243527173996, + 'timestamp': 583.0317146666348, + 'timestamp_carla': 583032, + 'timestamp_device': 26277, + 'timestamp_stream': 583.0317146666348, + 'transform': [array([ -2.97061419, -14.23346615, 0.01635555]), + array([-0.05706623, 8.8316803 , -0.01314128])]} +{'AngularVelocity': array([-0.01131917, -0.0118349 , -2.92008138]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.115077018737793, + 'FR_Wheel_Angle': 14.230597496032715, + 'Location': array([ -0.12493491, -19.12295151, 0.16958252]), + 'Rotation': array([-6.64987192e-02, 3.38931770e+01, -1.39465332e-02]), + 'Velocity': array([-0.47378024, -0.42054859, 0.0005145 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.85015297, 16.0557003 , 1.35668802]), + 'camera_rotation': array([-8.33924389, 3.93771577, 5.58067989]), + 'current_gear_input': False, + 'focus_actor_dist': 881.0656127929688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -472.46841431, -1909.26196289, 83.78829956]), + 'frame': 17937, + 'frame_number': 17937, + 'framesequence': 68685, + 'gaze_dir': array([0.99333954, 0.06832886, 0.09220886]), + 'gaze_origin': array([-3.05891061, -0.07056199, 0.11253357]), + 'gaze_valid': True, + 'gaze_vergence': 340.5496826171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99258423, 0.0774231 , 0.09359741]), + 'left_gaze_origin': array([-3.01178741, 3.12310672, 0.12149201]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2736968994140625, + 'left_pupil_posn': array([ 0.09848368, -0.00349534]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99409485, 0.05923462, 0.09082031]), + 'right_gaze_origin': array([-3.10603333, -3.26423049, 0.10357514]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.220947265625, + 'right_pupil_posn': array([ 0.077878 , -0.07338488]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02693563885986805, + 'throttle_input': 0.1269855797290802, + 'timestamp': 583.0660007670522, + 'timestamp_carla': 583066, + 'timestamp_device': 26310, + 'timestamp_stream': 583.0660007670522, + 'transform': [array([ -3.00722289, -14.13234997, 0.01616975]), + array([-0.05319351, 8.91265392, -0.01167962])]} +{'AngularVelocity': array([-0.03701756, -0.01364993, -3.06208324]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.938994407653809, + 'FR_Wheel_Angle': 18.026586532592773, + 'Location': array([ -0.2366658 , -19.21803474, 0.16974208]), + 'Rotation': array([-6.70178160e-02, 3.31841545e+01, -1.66320745e-02]), + 'Velocity': array([-0.36160919, -0.34155402, 0.00061857]), + 'brake_input': 0.0, + 'camera_location': array([-4.92025948, 15.98627186, 1.25169563]), + 'camera_rotation': array([-8.91601944, 3.6124258 , 5.33682775]), + 'current_gear_input': False, + 'focus_actor_dist': 877.9356079101562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -471.67562866, -1903.07666016, 83.8404541 ]), + 'frame': 17938, + 'frame_number': 17938, + 'framesequence': 68689, + 'gaze_dir': array([0.99237823, 0.07238007, 0.09941101]), + 'gaze_origin': array([-3.07274032, -0.07180177, 0.12654114]), + 'gaze_valid': True, + 'gaze_vergence': 478.1235656738281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99179077, 0.07878113, 0.10057068]), + 'left_gaze_origin': array([-2.99805927, 3.12159443, 0.12747499]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2941436767578125, + 'left_pupil_posn': array([0.10179186, 0.00540537]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9929657 , 0.065979 , 0.09825134]), + 'right_gaze_origin': array([-3.14742136, -3.26519799, 0.1256073 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.106597900390625, + 'right_pupil_posn': array([ 0.08004415, -0.06337619]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01228675339370966, + 'throttle_input': 0.10713358968496323, + 'timestamp': 583.0978490673006, + 'timestamp_carla': 583098, + 'timestamp_device': 26343, + 'timestamp_stream': 583.0978490673006, + 'transform': [array([ -3.03341842, -14.03768635, 0.01596022]), + array([-0.04989453, 8.95645428, -0.01014965])]} +{'AngularVelocity': array([-0.02876105, -0.03025201, -3.13003826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.323461532592773, + 'FR_Wheel_Angle': 22.69603729248047, + 'Location': array([ -0.30596226, -19.27952957, 0.16983096]), + 'Rotation': array([-6.88209832e-02, 3.26178322e+01, -1.60217248e-02]), + 'Velocity': array([-2.99137026e-01, -3.02982718e-01, 2.68754957e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.99062157, 15.91938019, 1.21523154]), + 'camera_rotation': array([-9.14483738, 3.34361744, 5.19432402]), + 'current_gear_input': False, + 'focus_actor_dist': 867.8426513671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.48748779, -1902.70776367, 81.90115356]), + 'frame': 17939, + 'frame_number': 17939, + 'framesequence': 68693, + 'gaze_dir': array([0.99211884, 0.07369232, 0.10105896]), + 'gaze_origin': array([-3.06219888, -0.07253647, 0.12001343]), + 'gaze_valid': True, + 'gaze_vergence': 462.7921142578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99143982, 0.0796051 , 0.10336304]), + 'left_gaze_origin': array([-2.9947741 , 3.12155175, 0.1260666 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.24285888671875, + 'left_pupil_posn': array([0.10244 , 0.00529343]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99279785, 0.06777954, 0.09875488]), + 'right_gaze_origin': array([-3.12962341, -3.26662469, 0.11396027]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0759429931640625, + 'right_pupil_posn': array([ 0.08088267, -0.06701422]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.002471999265253544, + 'throttle_input': 0.08729686588048935, + 'timestamp': 583.1315912678838, + 'timestamp_carla': 583132, + 'timestamp_device': 26377, + 'timestamp_stream': 583.1315912678838, + 'transform': [array([ -3.05262136, -13.93690395, 0.0156434 ]), + array([-4.65682261e-02, 8.96898174e+00, -8.25086609e-03])]} +{'AngularVelocity': array([-0.0405332 , -0.00444609, -2.33559704]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.41299819946289, + 'FR_Wheel_Angle': 27.227750778198242, + 'Location': array([ -0.37738854, -19.34521675, 0.16992855]), + 'Rotation': array([-6.98250234e-02, 3.18991814e+01, -1.64184589e-02]), + 'Velocity': array([-2.57183790e-01, -2.67872185e-01, 2.46391282e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.01285744, 15.87672424, 1.25582314]), + 'camera_rotation': array([-8.90677071, 3.08589792, 4.96609831]), + 'current_gear_input': False, + 'focus_actor_dist': 865.5127563476562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -469.10638428, -1894.88110352, 80.06008911]), + 'frame': 17940, + 'frame_number': 17940, + 'framesequence': 68697, + 'gaze_dir': array([0.99209595, 0.0789566 , 0.09681702]), + 'gaze_origin': array([-3.05427957, -0.07292786, 0.11533585]), + 'gaze_valid': True, + 'gaze_vergence': 295.3411865234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99137878, 0.08953857, 0.0954895 ]), + 'left_gaze_origin': array([-2.99325895, 3.12126327, 0.12256623]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22357177734375, + 'left_pupil_posn': array([0.10283756, 0.00306183]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99281311, 0.06837463, 0.09814453]), + 'right_gaze_origin': array([-3.11530018, -3.26711917, 0.10810547]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1787261962890625, + 'right_pupil_posn': array([ 0.08427715, -0.07141066]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.013403729535639286, + 'throttle_input': 0.07142747938632965, + 'timestamp': 583.165161266923, + 'timestamp_carla': 583165, + 'timestamp_device': 26410, + 'timestamp_stream': 583.165161266923, + 'transform': [array([ -3.06465173, -13.8364954 , 0.01525062]), + array([-4.41025272e-02, 8.95391083e+00, -6.11984730e-03])]} +{'AngularVelocity': array([-0.07589659, -0.01030006, -3.72311163]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.270864486694336, + 'FR_Wheel_Angle': 29.66029930114746, + 'Location': array([ -0.43299565, -19.39843369, 0.17001472]), + 'Rotation': array([-7.05558509e-02, 3.12295246e+01, -1.62353497e-02]), + 'Velocity': array([-0.21594056, -0.23830163, 0.00058551]), + 'brake_input': 0.0, + 'camera_location': array([-5.03750038, 15.80848503, 1.27302408]), + 'camera_rotation': array([-8.742239 , 2.89244437, 5.1715579 ]), + 'current_gear_input': False, + 'focus_actor_dist': 859.1509399414062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -469.05459595, -1890.93798828, 80.31886292]), + 'frame': 17941, + 'frame_number': 17941, + 'framesequence': 68702, + 'gaze_dir': array([0.99227905, 0.07923889, 0.09486389]), + 'gaze_origin': array([-3.05413818, -0.07464219, 0.11665802]), + 'gaze_valid': True, + 'gaze_vergence': 322.77813720703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99147034, 0.08905029, 0.09510803]), + 'left_gaze_origin': array([-2.9951508 , 3.12088013, 0.12256623]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2068328857421875, + 'left_pupil_posn': array([0.10346079, 0.00153971]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99308777, 0.06942749, 0.09461975]), + 'right_gaze_origin': array([-3.1131258 , -3.27016449, 0.11074982]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1831817626953125, + 'right_pupil_posn': array([ 0.08614874, -0.06932855]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.020270396023988724, + 'throttle_input': 0.05555810034275055, + 'timestamp': 583.2033675685525, + 'timestamp_carla': 583204, + 'timestamp_device': 26452, + 'timestamp_stream': 583.2033675685525, + 'transform': [array([ -3.07257771, -13.72263145, 0.0146566 ]), + array([-4.29072455e-02, 8.91504002e+00, -3.42192128e-03])]} +{'AngularVelocity': array([ 0.03326643, 0.00845057, -3.46506524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.45803451538086, + 'FR_Wheel_Angle': 31.705148696899414, + 'Location': array([ -0.48085853, -19.44485855, 0.17007381]), + 'Rotation': array([-7.13208318e-02, 3.05991402e+01, -1.70288105e-02]), + 'Velocity': array([-1.76388666e-01, -1.85935378e-01, 9.81807680e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.0637989 , 15.72031116, 1.29556751]), + 'camera_rotation': array([-8.6464653 , 2.70190263, 5.30396414]), + 'current_gear_input': False, + 'focus_actor_dist': 861.40380859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.56964111, -1877.94836426, 80.64054871]), + 'frame': 17942, + 'frame_number': 17942, + 'framesequence': 68705, + 'gaze_dir': array([0.99221802, 0.08470917, 0.09055328]), + 'gaze_origin': array([-3.07244515, -0.07888947, 0.11749727]), + 'gaze_valid': True, + 'gaze_vergence': 276.0744934082031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99102783, 0.09481812, 0.09417725]), + 'left_gaze_origin': array([-3.01010466, 3.11505747, 0.12353516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1118621826171875, + 'left_pupil_posn': array([ 0.10923707, -0.00296247]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9934082 , 0.07460022, 0.08692932]), + 'right_gaze_origin': array([-3.13478565, -3.27283621, 0.11145936]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.244598388671875, + 'right_pupil_posn': array([ 0.09041297, -0.07334936]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.027942748740315437, + 'throttle_input': 0.0317387655377388, + 'timestamp': 583.2322222664952, + 'timestamp_carla': 583233, + 'timestamp_device': 26477, + 'timestamp_stream': 583.2322222664952, + 'transform': [array([ -3.07600093, -13.63727665, 0.01414712]), + array([-4.26067188e-02, 8.87685108e+00, -1.13380642e-03])]} +{'AngularVelocity': array([ 0.02392315, 0.00671153, -3.03027654]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.086181640625, + 'FR_Wheel_Angle': 36.154781341552734, + 'Location': array([ -0.51857144, -19.48201942, 0.17013462]), + 'Rotation': array([-7.10476264e-02, 3.00607357e+01, -1.67541504e-02]), + 'Velocity': array([-0.1349026 , -0.14888354, 0.00056443]), + 'brake_input': 0.0, + 'camera_location': array([-5.07026482, 15.65123272, 1.38879275]), + 'camera_rotation': array([-8.40069485, 2.61931539, 5.26959848]), + 'current_gear_input': False, + 'focus_actor_dist': 849.2944946289062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -467.66308594, -1878.71044922, 78.62004852]), + 'frame': 17943, + 'frame_number': 17943, + 'framesequence': 68709, + 'gaze_dir': array([0.99285889, 0.08648682, 0.08150482]), + 'gaze_origin': array([-3.0490334 , -0.08165894, 0.10432512]), + 'gaze_valid': True, + 'gaze_vergence': 325.9480895996094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99203491, 0.09619141, 0.08128357]), + 'left_gaze_origin': array([-2.96840692, 3.112813 , 0.1000763 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2154388427734375, + 'left_pupil_posn': array([ 0.11124909, -0.01308143]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99368286, 0.07678223, 0.08172607]), + 'right_gaze_origin': array([-3.12966037, -3.27613091, 0.10857392]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2450103759765625, + 'right_pupil_posn': array([ 0.09293747, -0.07884157]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03259376809000969, + 'throttle_input': 0.019836727529764175, + 'timestamp': 583.266362067312, + 'timestamp_carla': 583267, + 'timestamp_device': 26510, + 'timestamp_stream': 583.266362067312, + 'transform': [array([ -3.07559657, -13.53670502, 0.01368116]), + array([-4.26067188e-02, 8.81451416e+00, 1.12915295e-03])]} +{'AngularVelocity': array([ 0.03418358, 0.01335317, -2.82395101]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.028661727905273, + 'FR_Wheel_Angle': 36.91707992553711, + 'Location': array([ -0.54802388, -19.5124836 , 0.17016704]), + 'Rotation': array([-7.17511326e-02, 2.95727119e+01, -1.61437970e-02]), + 'Velocity': array([-1.09054856e-01, -1.23360343e-01, -8.01086401e-07]), + 'brake_input': 0.0, + 'camera_location': array([-5.07614708, 15.58094788, 1.45936918]), + 'camera_rotation': array([-8.18072224, 2.56501055, 5.32091427]), + 'current_gear_input': False, + 'focus_actor_dist': 842.6027221679688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -465.84194946, -1876.58032227, 75.0149231 ]), + 'frame': 17944, + 'frame_number': 17944, + 'framesequence': 68713, + 'gaze_dir': array([0.99185181, 0.09812927, 0.08057404]), + 'gaze_origin': array([-3.02557397, -0.08393937, 0.0928421 ]), + 'gaze_valid': True, + 'gaze_vergence': 330.0973205566406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99084473, 0.10762024, 0.0813446 ]), + 'left_gaze_origin': array([-2.95844436, 3.11169147, 0.09480744]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.351409912109375, + 'left_pupil_posn': array([ 0.11595333, -0.01579785]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99285889, 0.08863831, 0.07980347]), + 'right_gaze_origin': array([-3.09270334, -3.2795701 , 0.09087677]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2476348876953125, + 'right_pupil_posn': array([ 0.09832752, -0.08420682]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.037647634744644165, + 'throttle_input': 0.01190203707665205, + 'timestamp': 583.2982762679458, + 'timestamp_carla': 583299, + 'timestamp_device': 26543, + 'timestamp_stream': 583.2982762679458, + 'transform': [array([-3.07206297e+00, -1.34433441e+01, 1.32807922e-02]), + array([-4.28799242e-02, 8.74468517e+00, 3.08227795e-03])]} +{'AngularVelocity': array([ 0.04457843, -0.00751854, -3.90068793]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.735937118530273, + 'FR_Wheel_Angle': 36.58605194091797, + 'Location': array([ -0.59645241, -19.56082726, 0.17027535]), + 'Rotation': array([-7.95580372e-02, 2.87946625e+01, -8.17871094e-03]), + 'Velocity': array([-0.23286708, -0.26147273, 0.00032183]), + 'brake_input': 0.0, + 'camera_location': array([-5.08197975, 15.57547951, 1.4671818 ]), + 'camera_rotation': array([-8.181036 , 2.3485558, 4.5658679]), + 'current_gear_input': False, + 'focus_actor_dist': 819.6643676757812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.0625 , -1890.69165039, 78.24893188]), + 'frame': 17945, + 'frame_number': 17945, + 'framesequence': 68718, + 'gaze_dir': array([0.99160767, 0.09892273, 0.08289337]), + 'gaze_origin': array([-3.05062199, -0.08819962, 0.10168 ]), + 'gaze_valid': True, + 'gaze_vergence': 476.2274475097656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99093628, 0.10554504, 0.08297729]), + 'left_gaze_origin': array([-2.97348356, 3.10654473, 0.10276337]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.358551025390625, + 'left_pupil_posn': array([ 0.1207484 , -0.01227367]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99227905, 0.09230042, 0.08280945]), + 'right_gaze_origin': array([-3.12776041, -3.28294373, 0.10059662]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.255859375, + 'right_pupil_posn': array([ 0.10075057, -0.08347285]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04231696575880051, + 'throttle_input': 0.0, + 'timestamp': 583.333447765559, + 'timestamp_carla': 583334, + 'timestamp_device': 26585, + 'timestamp_stream': 583.333447765559, + 'transform': [array([-3.06486011e+00, -1.33412285e+01, 1.28616998e-02]), + array([-4.33033966e-02, 8.65577507e+00, 4.94385185e-03])]} +{'AngularVelocity': array([ 0.0183312 , -0.00812207, -2.69830608]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.736913681030273, + 'FR_Wheel_Angle': 36.598045349121094, + 'Location': array([ -0.65148717, -19.61446762, 0.17028251]), + 'Rotation': array([-7.16213584e-02, 2.79248028e+01, -1.62353478e-02]), + 'Velocity': array([-1.64135262e-01, -1.78993016e-01, 3.40461725e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.08254242, 15.58495617, 1.41321301]), + 'camera_rotation': array([-8.31078243, 2.16180062, 4.18290663]), + 'current_gear_input': False, + 'focus_actor_dist': 824.9345092773438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -467.0178833 , -1875.04956055, 80.86080933]), + 'frame': 17946, + 'frame_number': 17946, + 'framesequence': 68722, + 'gaze_dir': array([0.99160004, 0.09975433, 0.08187103]), + 'gaze_origin': array([-3.05416441, -0.08946534, 0.10341187]), + 'gaze_valid': True, + 'gaze_vergence': 394.0204772949219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99084473, 0.10772705, 0.08129883]), + 'left_gaze_origin': array([-2.97269011, 3.10503244, 0.10203248]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3557891845703125, + 'left_pupil_posn': array([ 0.1215899 , -0.01272476]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99235535, 0.09178162, 0.08244324]), + 'right_gaze_origin': array([-3.13563871, -3.28396344, 0.10479126]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.227813720703125, + 'right_pupil_posn': array([ 0.10239589, -0.08266163]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04771874472498894, + 'throttle_input': 0.0, + 'timestamp': 583.3720056675375, + 'timestamp_carla': 583372, + 'timestamp_device': 26618, + 'timestamp_stream': 583.3720056675375, + 'transform': [array([-3.05345583e+00, -1.32304535e+01, 1.23908613e-02]), + array([-4.38498110e-02, 8.54611492e+00, 6.89697545e-03])]} +{'AngularVelocity': array([ 0.0087914 , 0.0097208 , -1.32088697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.785493850708008, + 'FR_Wheel_Angle': 36.67501449584961, + 'Location': array([ -0.67575562, -19.63784409, 0.1702908 ]), + 'Rotation': array([-6.86024129e-02, 2.75454350e+01, -1.89208966e-02]), + 'Velocity': array([-0.0880518 , -0.09171268, -0.00022352]), + 'brake_input': 0.0, + 'camera_location': array([-5.08226967, 15.58835602, 1.33602917]), + 'camera_rotation': array([-8.4238224 , 1.97188938, 4.09761667]), + 'current_gear_input': False, + 'focus_actor_dist': 835.8329467773438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -467.90484619, -1853.61499023, 77.86756897]), + 'frame': 17947, + 'frame_number': 17947, + 'framesequence': 68726, + 'gaze_dir': array([0.99004364, 0.11100769, 0.08570862]), + 'gaze_origin': array([-3.05360579, -0.09386216, 0.10937806]), + 'gaze_valid': True, + 'gaze_vergence': 268.0626525878906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98890686, 0.12251282, 0.08396912]), + 'left_gaze_origin': array([-2.9736681 , 3.0997467 , 0.11043396]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2915496826171875, + 'left_pupil_posn': array([ 0.12784505, -0.00557268]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99118042, 0.09950256, 0.08744812]), + 'right_gaze_origin': array([-3.13354349, -3.28747106, 0.10832215]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.30572509765625, + 'right_pupil_posn': array([ 0.10989857, -0.07924497]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05383465439081192, + 'throttle_input': 0.0, + 'timestamp': 583.4042254686356, + 'timestamp_carla': 583404, + 'timestamp_device': 26652, + 'timestamp_stream': 583.4042254686356, + 'transform': [array([-3.04095054e+00, -1.31388912e+01, 1.20970728e-02]), + array([-4.40683775e-02, 8.44407082e+00, 8.39233678e-03])]} +{'AngularVelocity': array([-0.11580509, -0.01400424, -2.00523639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.595821380615234, + 'FR_Wheel_Angle': 36.22990798950195, + 'Location': array([ -0.69183868, -19.65315437, 0.17032711]), + 'Rotation': array([-7.06787929e-02, 2.72838287e+01, -1.58996582e-02]), + 'Velocity': array([-6.36847913e-02, -7.61175081e-02, 5.59234613e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.09786606, 15.57983303, 1.26876509]), + 'camera_rotation': array([-8.82404423, 1.71350467, 4.03007412]), + 'current_gear_input': False, + 'focus_actor_dist': 816.6758422851562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.63464355, -1862.39013672, 80.27120972]), + 'frame': 17948, + 'frame_number': 17948, + 'framesequence': 68730, + 'gaze_dir': array([0.98942566, 0.11466217, 0.0880661 ]), + 'gaze_origin': array([-3.02488327, -0.09820404, 0.10489197]), + 'gaze_valid': True, + 'gaze_vergence': 300.3787841796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98829651, 0.12507629, 0.0872345 ]), + 'left_gaze_origin': array([-2.95439482, 3.09540105, 0.10927735]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3951568603515625, + 'left_pupil_posn': array([ 0.13226151, -0.00253713]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99055481, 0.10424805, 0.08889771]), + 'right_gaze_origin': array([-3.0953722 , -3.29180908, 0.1005066 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3059844970703125, + 'right_pupil_posn': array([ 0.1128279, -0.0765636]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05938291549682617, + 'throttle_input': 0.0, + 'timestamp': 583.4372158683836, + 'timestamp_carla': 583438, + 'timestamp_device': 26685, + 'timestamp_stream': 583.4372158683836, + 'transform': [array([-3.02528691e+00, -1.30462179e+01, 1.17885014e-02]), + array([-0.04410253, 8.32982922, 0.0098877 ])]} +{'AngularVelocity': array([ 0.01470073, 0.01139904, -0.74749255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.02537727355957, + 'FR_Wheel_Angle': 35.1374626159668, + 'Location': array([ -0.7061305 , -19.66650391, 0.17037463]), + 'Rotation': array([-7.32127950e-02, 2.70563736e+01, -1.33361816e-02]), + 'Velocity': array([-5.24485298e-02, -5.15640974e-02, 9.12189498e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.12319374, 15.5449152 , 1.2624054 ]), + 'camera_rotation': array([-9.01746082, 1.47596014, 4.29530478]), + 'current_gear_input': False, + 'focus_actor_dist': 815.0484619140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -467.237854 , -1854.56079102, 76.54840088]), + 'frame': 17949, + 'frame_number': 17949, + 'framesequence': 68734, + 'gaze_dir': array([0.98869324, 0.12302399, 0.08472443]), + 'gaze_origin': array([-3.03685236, -0.10253907, 0.10411607]), + 'gaze_valid': True, + 'gaze_vergence': 252.01588439941406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98754883, 0.134552 , 0.08132935]), + 'left_gaze_origin': array([-2.9536593 , 3.0912919 , 0.10253602]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.40130615234375, + 'left_pupil_posn': array([ 0.13746524, -0.0073384 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98983765, 0.11149597, 0.08811951]), + 'right_gaze_origin': array([-3.12004566, -3.29637003, 0.10569611]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.32354736328125, + 'right_pupil_posn': array([ 0.11979139, -0.0797658 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.066212959587574, + 'throttle_input': 0.0, + 'timestamp': 583.4671811684966, + 'timestamp_carla': 583467, + 'timestamp_device': 26718, + 'timestamp_stream': 583.4671811684966, + 'transform': [array([-3.00800419e+00, -1.29629955e+01, 1.14875408e-02]), + array([-0.04384981, 8.21527481, 0.0111084 ])]} +{'AngularVelocity': array([ 0.00513646, 0.00649427, -0.5358274 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.120845794677734, + 'FR_Wheel_Angle': 31.73319435119629, + 'Location': array([ -0.7165103 , -19.67578316, 0.17038429]), + 'Rotation': array([-7.30556995e-02, 2.69115677e+01, -1.34887705e-02]), + 'Velocity': array([-4.03123759e-02, -3.72510217e-02, -3.45230092e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.14116669, 15.50776386, 1.32305634]), + 'camera_rotation': array([-8.81556797, 1.27173102, 4.41067839]), + 'current_gear_input': False, + 'focus_actor_dist': 788.3721313476562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -462.17651367, -1871.92529297, 72.4234314 ]), + 'frame': 17950, + 'frame_number': 17950, + 'framesequence': 68737, + 'gaze_dir': array([0.98828888, 0.12755585, 0.08325195]), + 'gaze_origin': array([-3.04272103, -0.10702821, 0.10058518]), + 'gaze_valid': True, + 'gaze_vergence': 343.6712951660156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9879303 , 0.13327026, 0.07875061]), + 'left_gaze_origin': array([-2.96289539, 3.08683801, 0.09931489]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4664306640625, + 'left_pupil_posn': array([ 0.14402652, -0.01153731]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98864746, 0.12184143, 0.0877533 ]), + 'right_gaze_origin': array([-3.12254643, -3.3008945 , 0.10185548]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.301483154296875, + 'right_pupil_posn': array([ 0.12246752, -0.0836786 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07278665155172348, + 'throttle_input': 0.0, + 'timestamp': 583.4980663657188, + 'timestamp_carla': 583498, + 'timestamp_device': 26743, + 'timestamp_stream': 583.4980663657188, + 'transform': [array([-2.98756742e+00, -1.28781796e+01, 1.12822335e-02]), + array([-0.04348781, 8.08825779, 0.01229859])]} +{'AngularVelocity': array([ 0.0037351 , 0.00539204, -0.5000295 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.18417739868164, + 'FR_Wheel_Angle': 27.157987594604492, + 'Location': array([ -0.72604358, -19.68375778, 0.17039932]), + 'Rotation': array([-7.36021176e-02, 2.67956085e+01, -1.28784152e-02]), + 'Velocity': array([-4.19340134e-02, -3.58154029e-02, 1.97124482e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.13393211, 15.45444012, 1.37022507]), + 'camera_rotation': array([-8.62321568, 1.10293949, 4.28199053]), + 'current_gear_input': False, + 'focus_actor_dist': 798.9228515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -465.45336914, -1853.40246582, 72.7963562 ]), + 'frame': 17951, + 'frame_number': 17951, + 'framesequence': 68741, + 'gaze_dir': array([0.98841858, 0.12763977, 0.08175659]), + 'gaze_origin': array([-3.09864211, -0.11239625, 0.11318589]), + 'gaze_valid': True, + 'gaze_vergence': 466.3882751464844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98802185, 0.13261414, 0.07873535]), + 'left_gaze_origin': array([-3.00112915, 3.081949 , 0.10848236]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.43353271484375, + 'left_pupil_posn': array([ 0.14789128, -0.01325929]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98881531, 0.12266541, 0.08477783]), + 'right_gaze_origin': array([-3.19615483, -3.30674171, 0.1178894 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.262115478515625, + 'right_pupil_posn': array([ 0.12815332, -0.08622098]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07866451144218445, + 'throttle_input': 0.0, + 'timestamp': 583.5311347655952, + 'timestamp_carla': 583531, + 'timestamp_device': 26777, + 'timestamp_stream': 583.5311347655952, + 'transform': [array([-2.96254516e+00, -1.27885132e+01, 1.10601801e-02]), + array([-0.04311898, 7.94150591, 0.01342774])]} +{'AngularVelocity': array([-0.04897976, 0.08476757, -4.56271124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.32430076599121, + 'FR_Wheel_Angle': 23.002864837646484, + 'Location': array([ -0.77317071, -19.71914101, 0.17055228]), + 'Rotation': array([-9.21050981e-02, 2.63287277e+01, 5.96771832e-04]), + 'Velocity': array([-4.33394283e-01, -3.41329306e-01, 3.69501096e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.11832428, 15.38282871, 1.39246666]), + 'camera_rotation': array([-8.52290058, 0.94054419, 4.28627682]), + 'current_gear_input': False, + 'focus_actor_dist': 810.9196166992188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -465.68786621, -1832.28540039, 73.60546875]), + 'frame': 17952, + 'frame_number': 17952, + 'framesequence': 68745, + 'gaze_dir': array([0.98838043, 0.13208771, 0.07473755]), + 'gaze_origin': array([-3.10739446, -0.11676256, 0.11495362]), + 'gaze_valid': True, + 'gaze_vergence': 269.2825622558594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98820496, 0.1366272 , 0.06896973]), + 'left_gaze_origin': array([-3.00800037, 3.07662368, 0.10909881]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3171539306640625, + 'left_pupil_posn': array([ 0.15327179, -0.0154022 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98855591, 0.12754822, 0.08050537]), + 'right_gaze_origin': array([-3.20678878, -3.31014872, 0.12080842]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2845306396484375, + 'right_pupil_posn': array([ 0.13211942, -0.08968353]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08457900583744049, + 'throttle_input': 0.0, + 'timestamp': 583.564150866121, + 'timestamp_carla': 583564, + 'timestamp_device': 26810, + 'timestamp_stream': 583.564150866121, + 'transform': [array([-2.93475127e+00, -1.27001867e+01, 1.08631132e-02]), + array([-0.04290725, 7.78558111, 0.0144043 ])]} +{'AngularVelocity': array([ 0.01435802, -0.04354473, -4.42508745]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.549564361572266, + 'FR_Wheel_Angle': 18.926332473754883, + 'Location': array([ -0.89483124, -19.80543709, 0.17065951]), + 'Rotation': array([-8.62721130e-02, 2.53345299e+01, -6.89697359e-03]), + 'Velocity': array([-5.60981095e-01, -4.16494727e-01, 3.87678127e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.13874054, 15.27515221, 1.376109 ]), + 'camera_rotation': array([-8.56550789, 0.84982926, 4.34200287]), + 'current_gear_input': False, + 'focus_actor_dist': 1439.16455078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -646.35302734, -1224.13952637, 17.20249939]), + 'frame': 17953, + 'frame_number': 17953, + 'framesequence': 68749, + 'gaze_dir': array([0.98777008, 0.13955688, 0.06924438]), + 'gaze_origin': array([-3.11690307, -0.1214058 , 0.12131119]), + 'gaze_valid': True, + 'gaze_vergence': 545.1698608398438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98770142, 0.14138794, 0.06652832]), + 'left_gaze_origin': array([-3.00722671, 3.07160497, 0.11158906]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3400726318359375, + 'left_pupil_posn': array([ 0.16011989, -0.01666915]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98783875, 0.13772583, 0.07196045]), + 'right_gaze_origin': array([-3.22657943, -3.31441641, 0.13103333]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.28204345703125, + 'right_pupil_posn': array([ 0.13725829, -0.08729792]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08853419870138168, + 'throttle_input': 0.0, + 'timestamp': 583.5986597687006, + 'timestamp_carla': 583599, + 'timestamp_device': 26843, + 'timestamp_stream': 583.5986597687006, + 'transform': [array([-2.90347719e+00, -1.26091871e+01, 1.06689259e-02]), + array([-0.04308483, 7.61566734, 0.0152588 ])]} +{'AngularVelocity': array([ 1.98640358e-02, 2.17927061e-03, -4.03932476e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.278103828430176, + 'FR_Wheel_Angle': 14.601346969604492, + 'Location': array([ -1.06241107, -19.91140175, 0.17087875]), + 'Rotation': array([-8.88675898e-02, 2.42652779e+01, -9.85717773e-03]), + 'Velocity': array([-0.85028827, -0.54351676, 0.0014124 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.17750359, 15.15941525, 1.34764838]), + 'camera_rotation': array([-8.67815113, 0.81565046, 4.192976 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1330.3106689453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -619.23590088, -1321.22692871, 17.19987488]), + 'frame': 17954, + 'frame_number': 17954, + 'framesequence': 68753, + 'gaze_dir': array([0.98641968, 0.14841461, 0.06965637]), + 'gaze_origin': array([-3.08815241, -0.12740861, 0.11139832]), + 'gaze_valid': True, + 'gaze_vergence': 248.83251953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98597717, 0.15438843, 0.0632782 ]), + 'left_gaze_origin': array([-3.00579715, 3.06626296, 0.11018066]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.344482421875, + 'left_pupil_posn': array([ 0.16535771, -0.01604235]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98686218, 0.1424408 , 0.07603455]), + 'right_gaze_origin': array([-3.17050815, -3.32108021, 0.11261597]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.39105224609375, + 'right_pupil_posn': array([ 0.14476001, -0.09110022]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09113437682390213, + 'throttle_input': 0.0, + 'timestamp': 583.6313570663333, + 'timestamp_carla': 583632, + 'timestamp_device': 26877, + 'timestamp_stream': 583.6313570663333, + 'transform': [array([-2.87254715e+00, -1.25242090e+01, 1.05143161e-02]), + array([-0.04369955, 7.45125008, 0.0159607 ])]} +{'AngularVelocity': array([ 0.03974713, -0.03678979, -2.7451036 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.665886878967285, + 'FR_Wheel_Angle': 10.001080513000488, + 'Location': array([ -1.24105096, -20.01327133, 0.17101932]), + 'Rotation': array([-7.97766075e-02, 2.33969479e+01, -1.64184589e-02]), + 'Velocity': array([-0.88410282, -0.50628299, 0.0010035 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.16837311, 15.048069 , 1.37245905]), + 'camera_rotation': array([-8.55539227, 0.77376193, 3.96563959]), + 'current_gear_input': False, + 'focus_actor_dist': 803.3944091796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.70098877, -1815.59741211, 62.99044037]), + 'frame': 17955, + 'frame_number': 17955, + 'framesequence': 68757, + 'gaze_dir': array([0.98519897, 0.15679932, 0.06825256]), + 'gaze_origin': array([-3.07643819, -0.13304138, 0.10320892]), + 'gaze_valid': True, + 'gaze_vergence': 167.54588317871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98483276, 0.1630249 , 0.05932617]), + 'left_gaze_origin': array([-2.98774576, 3.06080031, 0.10042877]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30322265625, + 'left_pupil_posn': array([ 0.17171538, -0.01892555]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98556519, 0.15057373, 0.07717896]), + 'right_gaze_origin': array([-3.16513062, -3.32688308, 0.10598908]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.353515625, + 'right_pupil_posn': array([ 0.15159667, -0.09607816]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09223304688930511, + 'throttle_input': 0.0, + 'timestamp': 583.6645663678646, + 'timestamp_carla': 583665, + 'timestamp_device': 26910, + 'timestamp_stream': 583.6645663678646, + 'transform': [array([-2.84049058e+00, -1.24391670e+01, 1.03632547e-02]), + array([-0.04467627, 7.28337431, 0.01657105])]} +{'AngularVelocity': array([ 2.25625443e-03, -1.77547298e-02, -2.78527188e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.697451591491699, + 'FR_Wheel_Angle': 5.382007598876953, + 'Location': array([ -1.46714568, -20.12836838, 0.17123233]), + 'Rotation': array([-6.98250234e-02, 2.26780548e+01, -2.00195294e-02]), + 'Velocity': array([-0.80587304, -0.39673287, 0.0010301 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.15647602, 14.93552399, 1.39137328]), + 'camera_rotation': array([-8.46532249, 0.68654823, 3.64086246]), + 'current_gear_input': False, + 'focus_actor_dist': 756.7302856445312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -460.77276611, -1852.56420898, 67.94927979]), + 'frame': 17956, + 'frame_number': 17956, + 'framesequence': 68761, + 'gaze_dir': array([0.98457336, 0.15872955, 0.07268524]), + 'gaze_origin': array([-3.0408411 , -0.13933717, 0.09762955]), + 'gaze_valid': True, + 'gaze_vergence': 122.36511993408203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98455811, 0.16337585, 0.06271362]), + 'left_gaze_origin': array([-2.97000885, 3.05570531, 0.1009201 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.452301025390625, + 'left_pupil_posn': array([ 0.17611575, -0.01388419]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98458862, 0.15408325, 0.08265686]), + 'right_gaze_origin': array([-3.11167312, -3.33437967, 0.094339 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4469757080078125, + 'right_pupil_posn': array([ 0.15529835, -0.09324837]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.092361219227314, + 'throttle_input': 0.0, + 'timestamp': 583.69851526618, + 'timestamp_carla': 583699, + 'timestamp_device': 26943, + 'timestamp_stream': 583.69851526618, + 'transform': [array([-2.80763555e+00, -1.23535328e+01, 1.02252765e-02]), + array([-0.04596034, 7.11306572, 0.01705934])]} +{'AngularVelocity': array([-0.00786643, -0.01542933, -1.65645289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.3911889791488647, + 'FR_Wheel_Angle': 0.7723055481910706, + 'Location': array([ -1.62195456, -20.19883537, 0.17137741]), + 'Rotation': array([-6.72910213e-02, 2.24550171e+01, -1.93786621e-02]), + 'Velocity': array([-7.33471274e-01, -3.23436767e-01, 6.96411123e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.15924263, 14.84350014, 1.37367332]), + 'camera_rotation': array([-8.71424866, 0.6482864 , 3.32200646]), + 'current_gear_input': False, + 'focus_actor_dist': 770.1965942382812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -463.56707764, -1830.3203125 , 71.96720123]), + 'frame': 17957, + 'frame_number': 17957, + 'framesequence': 68765, + 'gaze_dir': array([0.98379517, 0.16447449, 0.07077026]), + 'gaze_origin': array([-3.03064513, -0.14562531, 0.09580536]), + 'gaze_valid': True, + 'gaze_vergence': 214.75550842285156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98350525, 0.16918945, 0.06385803]), + 'left_gaze_origin': array([-2.94052601, 3.04836583, 0.09255219]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4332122802734375, + 'left_pupil_posn': array([ 0.18270588, -0.01587474]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98408508, 0.15975952, 0.0776825 ]), + 'right_gaze_origin': array([-3.12076426, -3.33961654, 0.09905854]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.430267333984375, + 'right_pupil_posn': array([ 0.16119468, -0.09139788]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0919950008392334, + 'throttle_input': 0.0, + 'timestamp': 583.7315243668854, + 'timestamp_carla': 583732, + 'timestamp_device': 26977, + 'timestamp_stream': 583.7315243668854, + 'transform': [array([-2.77592158e+00, -1.22715158e+01, 1.01143839e-02]), + array([-0.04733321, 6.94993639, 0.01745606])]} +{'AngularVelocity': array([-0.02875894, -0.0126831 , -1.124089 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.027848422527313232, + 'FR_Wheel_Angle': 0.0025329904165118933, + 'Location': array([ -1.78090131, -20.26527023, 0.17153423]), + 'Rotation': array([-6.58840016e-02, 2.24280014e+01, -1.56860333e-02]), + 'Velocity': array([-6.31315291e-01, -2.61783957e-01, 5.82637789e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.1291523 , 14.78059769, 1.3696655 ]), + 'camera_rotation': array([-8.69796562, 0.67385679, 3.1021235 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1339.3792724609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -635.74121094, -1281.92626953, 17.20658875]), + 'frame': 17958, + 'frame_number': 17958, + 'framesequence': 68770, + 'gaze_dir': array([0.98213196, 0.17514801, 0.06837463]), + 'gaze_origin': array([-3.05897069, -0.15026246, 0.10208359]), + 'gaze_valid': True, + 'gaze_vergence': 118.5036392211914, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98225403, 0.17732239, 0.06103516]), + 'left_gaze_origin': array([-2.97954726, 3.04356265, 0.10286408]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.521759033203125, + 'left_pupil_posn': array([ 0.19082713, -0.0170871 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98200989, 0.17297363, 0.07571411]), + 'right_gaze_origin': array([-3.13839436, -3.34408736, 0.1013031 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.40869140625, + 'right_pupil_posn': array([ 0.16759706, -0.09420538]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09102451056241989, + 'throttle_input': 0.0, + 'timestamp': 583.7654397673905, + 'timestamp_carla': 583766, + 'timestamp_device': 27018, + 'timestamp_stream': 583.7654397673905, + 'transform': [array([-2.74384785e+00, -1.21885195e+01, 1.00139612e-02]), + array([-0.04877438, 6.78584051, 0.01776124])]} +{'AngularVelocity': array([-0.0056086 , 0.00833233, -0.99001741]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.002535630948841572, + 'FR_Wheel_Angle': 0.002536161569878459, + 'Location': array([ -1.91878641, -20.32228088, 0.17170483]), + 'Rotation': array([-6.71339259e-02, 2.24185600e+01, -1.30310049e-02]), + 'Velocity': array([-0.56942028, -0.23386793, 0.00096642]), + 'brake_input': 0.0, + 'camera_location': array([-5.08849335, 14.75447559, 1.37092054]), + 'camera_rotation': array([-8.64834404, 0.69061738, 2.74635029]), + 'current_gear_input': False, + 'focus_actor_dist': 735.1292724609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -460.96383667, -1849.78710938, 69.56935883]), + 'frame': 17959, + 'frame_number': 17959, + 'framesequence': 68773, + 'gaze_dir': array([0.98236084, 0.1737442 , 0.06855774]), + 'gaze_origin': array([-3.04694009, -0.15556946, 0.09757462]), + 'gaze_valid': True, + 'gaze_vergence': 289.6760559082031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98377991, 0.16778564, 0.0632782 ]), + 'left_gaze_origin': array([-2.97319818, 3.03887033, 0.10133363]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.550689697265625, + 'left_pupil_posn': array([ 0.19621289, -0.01775777]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98094177, 0.17970276, 0.07383728]), + 'right_gaze_origin': array([-3.12068176, -3.35000944, 0.09381562]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.517822265625, + 'right_pupil_posn': array([ 0.16773665, -0.09534466]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0902005136013031, + 'throttle_input': 0.0, + 'timestamp': 583.7993878684938, + 'timestamp_carla': 583800, + 'timestamp_device': 27043, + 'timestamp_stream': 583.7993878684938, + 'transform': [array([-2.71229720e+00, -1.21067162e+01, 9.93209798e-03]), + array([-0.05007894, 6.62522268, 0.01800538])]} +{'AngularVelocity': array([-0.0096495 , 0.00925212, -1.31166649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0012681572698056698, + 'FR_Wheel_Angle': -0.0012680157087743282, + 'Location': array([ -2.04665709, -20.37498665, 0.17185047]), + 'Rotation': array([-6.94630221e-02, 2.24231644e+01, -1.20849609e-02]), + 'Velocity': array([-5.46365738e-01, -2.26984605e-01, 5.12609491e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.02440071, 14.75065613, 1.34989357]), + 'camera_rotation': array([-8.75049591, 0.73272628, 2.50989676]), + 'current_gear_input': False, + 'focus_actor_dist': 1345.310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -643.33752441, -1261.42590332, 17.20900726]), + 'frame': 17960, + 'frame_number': 17960, + 'framesequence': 68777, + 'gaze_dir': array([0.9822998 , 0.16780853, 0.08285522]), + 'gaze_origin': array([-3.05725813, -0.15031281, 0.10952531]), + 'gaze_valid': True, + 'gaze_vergence': 272.3948974609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98208618, 0.17182922, 0.07730103]), + 'left_gaze_origin': array([-2.97507644, 3.04284668, 0.10856781]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4458160400390625, + 'left_pupil_posn': array([ 0.18821514, -0.00790775]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98251343, 0.16378784, 0.08840942]), + 'right_gaze_origin': array([-3.13943958, -3.34347272, 0.1104828 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4285125732421875, + 'right_pupil_posn': array([ 0.165411 , -0.0824939]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0901089608669281, + 'throttle_input': 0.0, + 'timestamp': 583.8313858658075, + 'timestamp_carla': 583832, + 'timestamp_device': 27077, + 'timestamp_stream': 583.8313858658075, + 'transform': [array([-2.68290925e+00, -1.20307417e+01, 9.89545789e-03]), + array([-0.05102834, 6.47650051, 0.01815797])]} +{'AngularVelocity': array([ 0.00902081, -0.02191641, 0.07957942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.006333358120173216, + 'FR_Wheel_Angle': -0.006333284080028534, + 'Location': array([ -2.18381643, -20.43173218, 0.17202544]), + 'Rotation': array([-7.39777759e-02, 2.24324036e+01, -1.26037607e-02]), + 'Velocity': array([-6.12453759e-01, -2.52670735e-01, 5.55429433e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.95939255, 14.76419067, 1.32585657]), + 'camera_rotation': array([-8.93059444, 0.83643788, 2.59173703]), + 'current_gear_input': False, + 'focus_actor_dist': 1583.4503173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -704.6072998 , -1021.90698242, 17.30073547]), + 'frame': 17961, + 'frame_number': 17961, + 'framesequence': 68781, + 'gaze_dir': array([0.98175812, 0.17179108, 0.08042908]), + 'gaze_origin': array([-3.0526309 , -0.15536347, 0.10803452]), + 'gaze_valid': True, + 'gaze_vergence': 69.13449096679688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98214722, 0.17529297, 0.06817627]), + 'left_gaze_origin': array([-2.9694171 , 3.03752303, 0.10587921]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.468597412109375, + 'left_pupil_posn': array([ 0.19327605, -0.00742519]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98136902, 0.16828918, 0.09268188]), + 'right_gaze_origin': array([-3.13584471, -3.34824991, 0.11018983]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.442108154296875, + 'right_pupil_posn': array([ 0.169752 , -0.08519125]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0905667319893837, + 'throttle_input': 0.0, + 'timestamp': 583.8639886677265, + 'timestamp_carla': 583864, + 'timestamp_device': 27110, + 'timestamp_stream': 583.8639886677265, + 'transform': [array([-2.65302229e+00, -1.19544544e+01, 9.87073872e-03]), + array([-0.05170453, 6.32643843, 0.01824952])]} +{'AngularVelocity': array([ 0.00901758, -0.01939183, -0.10829704]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.006331839598715305, + 'FR_Wheel_Angle': 0.0037991907447576523, + 'Location': array([ -2.32746696, -20.49092293, 0.17217433]), + 'Rotation': array([-7.19287172e-02, 2.24302845e+01, -1.29394522e-02]), + 'Velocity': array([-0.61718792, -0.25427172, 0.00063548]), + 'brake_input': 0.0, + 'camera_location': array([-4.906847 , 14.7869873 , 1.26884818]), + 'camera_rotation': array([-9.26664734, 0.79478133, 2.40112686]), + 'current_gear_input': False, + 'focus_actor_dist': 1470.525634765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -676.20935059, -1123.9720459 , 17.20718384]), + 'frame': 17962, + 'frame_number': 17962, + 'framesequence': 68785, + 'gaze_dir': array([0.98047638, 0.17177582, 0.09448242]), + 'gaze_origin': array([-3.05337167, -0.16181794, 0.11263275]), + 'gaze_valid': True, + 'gaze_vergence': 142.32876586914062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97984314, 0.18147278, 0.08340454]), + 'left_gaze_origin': array([-2.96735549, 3.0315721 , 0.11272737]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.48626708984375, + 'left_pupil_posn': array([0.19519854, 0.0019694 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98110962, 0.16207886, 0.1055603 ]), + 'right_gaze_origin': array([-3.13938785, -3.35520792, 0.11253816]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.45867919921875, + 'right_pupil_posn': array([ 0.17684746, -0.0792917 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0919950008392334, + 'throttle_input': 0.0, + 'timestamp': 583.8977390676737, + 'timestamp_carla': 583898, + 'timestamp_device': 27143, + 'timestamp_stream': 583.8977390676737, + 'transform': [array([-2.62180805e+00, -1.18766623e+01, 9.84943379e-03]), + array([-0.05212117, 6.17128563, 0.01831055])]} +{'AngularVelocity': array([-0.00663652, 0.00566093, -0.01912038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.6477764844894409, + 'FR_Wheel_Angle': 0.867082417011261, + 'Location': array([ -2.49282455, -20.55927467, 0.17234744]), + 'Rotation': array([-7.17784539e-02, 2.24212341e+01, -1.28173828e-02]), + 'Velocity': array([-6.43683016e-01, -2.69787520e-01, 4.14199807e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.86600018, 14.83090973, 1.20284879]), + 'camera_rotation': array([-9.67087078, 0.76131701, 2.20248461]), + 'current_gear_input': False, + 'focus_actor_dist': 1682.2867431640625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-735.30126953, -912.34643555, 14.99866486]), + 'frame': 17963, + 'frame_number': 17963, + 'framesequence': 68789, + 'gaze_dir': array([0.98026276, 0.17636871, 0.08853912]), + 'gaze_origin': array([-3.05621266, -0.1638054 , 0.11311112]), + 'gaze_valid': True, + 'gaze_vergence': 143.3070831298828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98014832, 0.18177795, 0.07899475]), + 'left_gaze_origin': array([-2.97137308, 3.0293963 , 0.11431427]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.471649169921875, + 'left_pupil_posn': array([ 0.19975555, -0.00031734]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9803772 , 0.17095947, 0.0980835 ]), + 'right_gaze_origin': array([-3.14105225, -3.35700703, 0.11190797]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4546051025390625, + 'right_pupil_posn': array([ 0.17820418, -0.08156812]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09395428746938705, + 'throttle_input': 0.0, + 'timestamp': 583.9302316680551, + 'timestamp_carla': 583931, + 'timestamp_device': 27177, + 'timestamp_stream': 583.9302316680551, + 'transform': [array([-2.59127069e+00, -1.18028889e+01, 9.85933281e-03]), + array([-0.05236706, 6.02121592, 0.01831055])]} +{'AngularVelocity': array([ 0.00954731, -0.03857549, -0.63655132]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.068997859954834, + 'FR_Wheel_Angle': 3.8582959175109863, + 'Location': array([ -2.64525819, -20.62394714, 0.1725594 ]), + 'Rotation': array([-7.71196634e-02, 2.23330956e+01, -1.15661630e-02]), + 'Velocity': array([-0.78196156, -0.34300426, 0.00086244]), + 'brake_input': 0.0, + 'camera_location': array([-4.80724049, 14.88895988, 1.16303277]), + 'camera_rotation': array([-9.88393211, 0.89512014, 2.4537909 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1409.9483642578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -656.14855957, -1165.7199707 , 17.19754028]), + 'frame': 17964, + 'frame_number': 17964, + 'framesequence': 68793, + 'gaze_dir': array([0.97931671, 0.18076324, 0.09043121]), + 'gaze_origin': array([-3.05887175, -0.16434938, 0.11067581]), + 'gaze_valid': True, + 'gaze_vergence': 49.25139236450195, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97988892, 0.18186951, 0.08200073]), + 'left_gaze_origin': array([-2.97669077, 3.02873397, 0.11105958]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.481536865234375, + 'left_pupil_posn': array([ 0.2032764 , -0.00328922]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97874451, 0.17965698, 0.09886169]), + 'right_gaze_origin': array([-3.14105225, -3.35743284, 0.11029206]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4295501708984375, + 'right_pupil_posn': array([ 0.17856061, -0.08156812]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09571215510368347, + 'throttle_input': 0.0, + 'timestamp': 583.9638320654631, + 'timestamp_carla': 583964, + 'timestamp_device': 27210, + 'timestamp_stream': 583.9638320654631, + 'transform': [array([-2.55914235e+00, -1.17277441e+01, 9.87470616e-03]), + array([-0.05255147, 5.86511612, 0.01824952])]} +{'AngularVelocity': array([ 0.03421665, -0.01632845, -2.37064147]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.266979217529297, + 'FR_Wheel_Angle': 8.785146713256836, + 'Location': array([ -2.86614037, -20.72454071, 0.17279258]), + 'Rotation': array([-7.80349076e-02, 2.19116936e+01, -8.48388672e-03]), + 'Velocity': array([-0.91055274, -0.44534221, 0.00091577]), + 'brake_input': 0.0, + 'camera_location': array([-4.7501173 , 14.94718742, 1.11734653]), + 'camera_rotation': array([-10.12191677, 1.15691614, 2.81346393]), + 'current_gear_input': False, + 'focus_actor_dist': 1367.8402099609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -650.11132812, -1200.60717773, 17.2003479 ]), + 'frame': 17965, + 'frame_number': 17965, + 'framesequence': 68798, + 'gaze_dir': array([0.97799683, 0.18523407, 0.09533691]), + 'gaze_origin': array([-3.0559206 , -0.1654419 , 0.10772782]), + 'gaze_valid': True, + 'gaze_vergence': 239.58639526367188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97705078, 0.1934967 , 0.08895874]), + 'left_gaze_origin': array([-2.97031283, 3.02691364, 0.10596466]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5583038330078125, + 'left_pupil_posn': array([ 0.20344079, -0.00474691]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97894287, 0.17697144, 0.10171509]), + 'right_gaze_origin': array([-3.14152837, -3.35779738, 0.10949098]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4266204833984375, + 'right_pupil_posn': array([ 0.18295527, -0.08002055]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09693899750709534, + 'throttle_input': 0.0, + 'timestamp': 583.9997480660677, + 'timestamp_carla': 584000, + 'timestamp_device': 27252, + 'timestamp_stream': 583.9997480660677, + 'transform': [array([-2.52432585e+00, -1.16486969e+01, 9.87960771e-03]), + array([-0.05279053, 5.69772005, 0.01815797])]} +{'AngularVelocity': array([-0.03246334, 0.05224461, -5.71928406]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.791926383972168, + 'FR_Wheel_Angle': 15.492560386657715, + 'Location': array([ -3.09573317, -20.839077 , 0.173059 ]), + 'Rotation': array([-8.30346048e-02, 2.09718151e+01, -3.57055757e-03]), + 'Velocity': array([-1.12828028e+00, -6.21061146e-01, 1.05773925e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.73281956, 14.99783707, 1.05018687]), + 'camera_rotation': array([-10.53070354, 1.47942078, 3.02110839]), + 'current_gear_input': False, + 'focus_actor_dist': 1361.72900390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -657.97802734, -1201.91186523, 17.20864105]), + 'frame': 17966, + 'frame_number': 17966, + 'framesequence': 68801, + 'gaze_dir': array([0.97729492, 0.18695068, 0.09901428]), + 'gaze_origin': array([-3.05532694, -0.16498567, 0.11062165]), + 'gaze_valid': True, + 'gaze_vergence': 191.0321807861328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97673035, 0.19432068, 0.09074402]), + 'left_gaze_origin': array([-2.96714354, 3.02719903, 0.10709687]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4678802490234375, + 'left_pupil_posn': array([ 0.20420623, -0.00140858]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9778595 , 0.17958069, 0.10728455]), + 'right_gaze_origin': array([-3.14351058, -3.3571701 , 0.11414643]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4705352783203125, + 'right_pupil_posn': array([ 0.18287516, -0.07670975]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09728690981864929, + 'throttle_input': 0.0, + 'timestamp': 584.0311512686312, + 'timestamp_carla': 584031, + 'timestamp_device': 27277, + 'timestamp_stream': 584.0311512686312, + 'transform': [array([-2.49404025e+00, -1.15806227e+01, 9.92437359e-03]), + array([-0.05313204, 5.55318308, 0.01806642])]} +{'AngularVelocity': array([ 0.0097911 , 0.02264228, -9.2610321 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.45037841796875, + 'FR_Wheel_Angle': 19.722278594970703, + 'Location': array([ -3.38545346, -20.99146652, 0.17336799]), + 'Rotation': array([-8.54798108e-02, 1.91855621e+01, -5.24902344e-03]), + 'Velocity': array([-1.34978998, -0.77061898, 0.00161012]), + 'brake_input': 0.0, + 'camera_location': array([-4.7244606 , 15.03920269, 0.99101919]), + 'camera_rotation': array([-10.79976463, 1.87320316, 2.99402332]), + 'current_gear_input': False, + 'focus_actor_dist': 1301.63037109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -645.96356201, -1253.45227051, 17.20966339]), + 'frame': 17967, + 'frame_number': 17967, + 'framesequence': 68805, + 'gaze_dir': array([0.97719574, 0.18769836, 0.09861755]), + 'gaze_origin': array([-3.05504155, -0.16422883, 0.11098405]), + 'gaze_valid': True, + 'gaze_vergence': 187.8949737548828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97676086, 0.19430542, 0.09034729]), + 'left_gaze_origin': array([-2.9666965 , 3.02833414, 0.10680085]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5035858154296875, + 'left_pupil_posn': array([ 0.2039243, -0.0017432]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97763062, 0.18109131, 0.10688782]), + 'right_gaze_origin': array([-3.14338684, -3.35679173, 0.11516725]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4361572265625, + 'right_pupil_posn': array([ 0.18262148, -0.0760901 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09728690981864929, + 'throttle_input': 0.0, + 'timestamp': 584.0633741654456, + 'timestamp_carla': 584064, + 'timestamp_device': 27310, + 'timestamp_stream': 584.0633741654456, + 'transform': [array([-2.46306729e+00, -1.15117807e+01, 9.95887723e-03]), + array([-0.05358966, 5.40629911, 0.01794435])]} +{'AngularVelocity': array([ 0.04749826, -0.02588167, -11.06668472]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.17057991027832, + 'FR_Wheel_Angle': 22.545711517333984, + 'Location': array([ -3.68500996, -21.14403915, 0.17366192]), + 'Rotation': array([-8.37381110e-02, 1.70851917e+01, -1.34582520e-02]), + 'Velocity': array([-1.48448586, -0.80913311, 0.00208707]), + 'brake_input': 0.0, + 'camera_location': array([-4.72114086, 15.08575058, 0.97728628]), + 'camera_rotation': array([-10.80535889, 2.24393606, 2.82844472]), + 'current_gear_input': False, + 'focus_actor_dist': 1234.8642578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -631.23693848, -1312.33154297, 17.20968628]), + 'frame': 17968, + 'frame_number': 17968, + 'framesequence': 68806, + 'gaze_dir': array([0.97724915, 0.18798065, 0.09767151]), + 'gaze_origin': array([-3.0547173 , -0.16400911, 0.11107255]), + 'gaze_valid': True, + 'gaze_vergence': 215.6969757080078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97679138, 0.19415283, 0.09039307]), + 'left_gaze_origin': array([-2.96606302, 3.02882409, 0.10675507]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5002899169921875, + 'left_pupil_posn': array([ 0.20382798, -0.00232637]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97770691, 0.18180847, 0.10494995]), + 'right_gaze_origin': array([-3.14337158, -3.35684228, 0.11539002]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.442474365234375, + 'right_pupil_posn': array([ 0.18260968, -0.07589304]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09728690981864929, + 'throttle_input': 0.0, + 'timestamp': 584.0970848686993, + 'timestamp_carla': 584097, + 'timestamp_device': 27318, + 'timestamp_stream': 584.0970848686993, + 'transform': [array([-2.43087149e+00, -1.14408464e+01, 9.97821800e-03]), + array([-0.0540746 , 5.25455236, 0.01782227])]} +{'AngularVelocity': array([ 0.07510713, -0.05766775, -9.75483894]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.957910537719727, + 'FR_Wheel_Angle': 26.363937377929688, + 'Location': array([ -3.99205685, -21.29465866, 0.17384666]), + 'Rotation': array([-0.05987344, 14.59963799, -0.02923584]), + 'Velocity': array([-1.10292494, -0.59484363, 0.00137146]), + 'brake_input': 0.0, + 'camera_location': array([-4.68444347, 15.14393616, 0.96151453]), + 'camera_rotation': array([-10.80076885, 2.46557784, 2.48991632]), + 'current_gear_input': False, + 'focus_actor_dist': 1228.4498291015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -634.00317383, -1313.09899902, 17.21277618]), + 'frame': 17969, + 'frame_number': 17969, + 'framesequence': 68806, + 'gaze_dir': array([0.97724915, 0.18798065, 0.09767151]), + 'gaze_origin': array([-3.0547173 , -0.16400911, 0.11107255]), + 'gaze_valid': True, + 'gaze_vergence': 215.6969757080078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97679138, 0.19415283, 0.09039307]), + 'left_gaze_origin': array([-2.96606302, 3.02882409, 0.10675507]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5002899169921875, + 'left_pupil_posn': array([ 0.20382798, -0.00232637]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97770691, 0.18180847, 0.10494995]), + 'right_gaze_origin': array([-3.14337158, -3.35684228, 0.11539002]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.442474365234375, + 'right_pupil_posn': array([ 0.18260968, -0.07589304]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09743340313434601, + 'throttle_input': 0.0, + 'timestamp': 584.1301866658032, + 'timestamp_carla': 584130, + 'timestamp_device': 27318, + 'timestamp_stream': 584.1301866658032, + 'transform': [array([-2.39947128e+00, -1.13722458e+01, 1.00051304e-02]), + array([-0.05453223, 5.10744715, 0.01770021])]} +{'AngularVelocity': array([-0.19772616, 0.09169333, -0.00149151]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.859621047973633, + 'FR_Wheel_Angle': 29.005290985107422, + 'Location': array([ -4.12072325, -21.35641098, 0.17369559]), + 'Rotation': array([-0.015566 , 13.45956039, -0.06399536]), + 'Velocity': array([-4.97822439e-05, 3.81038728e-04, -3.56141623e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.70796394, 15.20173454, 0.89575893]), + 'camera_rotation': array([-11.20754719, 2.58561707, 2.37995815]), + 'current_gear_input': False, + 'focus_actor_dist': 1243.7408447265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -640.05236816, -1291.70593262, 17.21341705]), + 'frame': 17970, + 'frame_number': 17970, + 'framesequence': 68816, + 'gaze_dir': array([0.97023773, 0.20165253, 0.13362122]), + 'gaze_origin': array([-3.05984974, -0.17213058, 0.13386306]), + 'gaze_valid': True, + 'gaze_vergence': 271.8269348144531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96922302, 0.20999146, 0.12843323]), + 'left_gaze_origin': array([-2.97362089, 3.01527119, 0.13192445]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4641571044921875, + 'left_pupil_posn': array([0.21717775, 0.02412939]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97125244, 0.1933136 , 0.1388092 ]), + 'right_gaze_origin': array([-3.14607882, -3.35953236, 0.1358017 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.52520751953125, + 'right_pupil_posn': array([ 0.19045413, -0.04994309]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09833064675331116, + 'throttle_input': 0.0, + 'timestamp': 584.1646651662886, + 'timestamp_carla': 584165, + 'timestamp_device': 27402, + 'timestamp_stream': 584.1646651662886, + 'transform': [array([-2.36670780e+00, -1.13018980e+01, 1.00243948e-02]), + array([-0.05486691, 4.95506907, 0.01757814])]} +{'AngularVelocity': array([-0.09989002, 0.08427946, -0.00099071]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.602893829345703, + 'FR_Wheel_Angle': 30.023048400878906, + 'Location': array([ -4.12094116, -21.35662842, 0.17393824]), + 'Rotation': array([-0.05492838, 13.45946407, -0.03192138]), + 'Velocity': array([ 2.09382524e-05, 1.57945673e-04, -1.15982999e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.71038246, 15.25979233, 0.86875284]), + 'camera_rotation': array([-11.42974758, 2.67214179, 2.57496977]), + 'current_gear_input': False, + 'focus_actor_dist': 1830.0152587890625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-855.05023193, -737.08337402, 15.23892975]), + 'frame': 17971, + 'frame_number': 17971, + 'framesequence': 68821, + 'gaze_dir': array([0.97177887, 0.19564056, 0.13114166]), + 'gaze_origin': array([-3.05965424, -0.17723465, 0.12676163]), + 'gaze_valid': True, + 'gaze_vergence': 194.32083129882812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97106934, 0.20462036, 0.12301636]), + 'left_gaze_origin': array([-2.9738481 , 3.01242089, 0.12416687]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.48162841796875, + 'left_pupil_posn': array([0.21688306, 0.01936972]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9724884 , 0.18666077, 0.13926697]), + 'right_gaze_origin': array([-3.14546084, -3.36689019, 0.12935638]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.454498291015625, + 'right_pupil_posn': array([ 0.19346666, -0.0561341 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09933774918317795, + 'throttle_input': 0.0, + 'timestamp': 584.1976184658706, + 'timestamp_carla': 584198, + 'timestamp_device': 27443, + 'timestamp_stream': 584.1976184658706, + 'transform': [array([-2.33535552e+00, -1.12356911e+01, 1.00621600e-02]), + array([-0.05508547, 4.81030416, 0.01745606])]} +{'AngularVelocity': array([-0.02734466, 0.02051025, 0.00017168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.630353927612305, + 'FR_Wheel_Angle': 30.0086727142334, + 'Location': array([ -4.12101316, -21.35671806, 0.17401859]), + 'Rotation': array([-0.06796038, 13.45962429, -0.0218811 ]), + 'Velocity': array([ 2.10131147e-05, 1.02869781e-05, -4.54364854e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.67378426, 15.32265472, 0.89040047]), + 'camera_rotation': array([-11.34696579, 2.72611332, 2.69597268]), + 'current_gear_input': False, + 'focus_actor_dist': 1657.6085205078125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-786.44787598, -889.00854492, 15.06147003]), + 'frame': 17972, + 'frame_number': 17972, + 'framesequence': 68825, + 'gaze_dir': array([0.97086334, 0.19937134, 0.13231659]), + 'gaze_origin': array([-3.06061888, -0.17979051, 0.12061921]), + 'gaze_valid': True, + 'gaze_vergence': 255.80947875976562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96907043, 0.21040344, 0.12884521]), + 'left_gaze_origin': array([-2.97485375, 3.01012731, 0.12012482]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.519622802734375, + 'left_pupil_posn': array([0.21905243, 0.01541936]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97265625, 0.18833923, 0.13578796]), + 'right_gaze_origin': array([-3.146384 , -3.3697083 , 0.12111359]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.522003173828125, + 'right_pupil_posn': array([ 0.19753659, -0.05989146]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10078433156013489, + 'throttle_input': 0.0, + 'timestamp': 584.2304538674653, + 'timestamp_carla': 584231, + 'timestamp_device': 27476, + 'timestamp_stream': 584.2304538674653, + 'transform': [array([-2.30389404e+00, -1.11707220e+01, 1.01002306e-02]), + array([-0.05520159, 4.66614246, 0.017334 ])]} +{'AngularVelocity': array([ 0.01649439, -0.00778534, -0.77171165]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.94325065612793, + 'FR_Wheel_Angle': 30.64283561706543, + 'Location': array([ -4.13840675, -21.36541939, 0.17404258]), + 'Rotation': array([-0.07363626, 13.2782793 , -0.01693726]), + 'Velocity': array([-0.07391407, -0.04192843, 0.00085823]), + 'brake_input': 0.0, + 'camera_location': array([-4.66454124, 15.37988472, 0.8581599 ]), + 'camera_rotation': array([-11.54296398, 2.7632494 , 2.86819005]), + 'current_gear_input': False, + 'focus_actor_dist': 1706.6322021484375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-806.98040771, -837.36254883, 15.19294739]), + 'frame': 17973, + 'frame_number': 17973, + 'framesequence': 68829, + 'gaze_dir': array([0.96986389, 0.20235443, 0.13502502]), + 'gaze_origin': array([-3.0602746 , -0.1826027 , 0.12119446]), + 'gaze_valid': True, + 'gaze_vergence': 232.15609741210938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96783447, 0.21455383, 0.13130188]), + 'left_gaze_origin': array([-2.97478199, 3.00528574, 0.12043609]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.478240966796875, + 'left_pupil_posn': array([0.22295499, 0.01653677]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97189331, 0.19015503, 0.13874817]), + 'right_gaze_origin': array([-3.14576745, -3.37049103, 0.12195282]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5601806640625, + 'right_pupil_posn': array([ 0.19952047, -0.05856252]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10173650830984116, + 'throttle_input': 0.0, + 'timestamp': 584.2637150660157, + 'timestamp_carla': 584264, + 'timestamp_device': 27510, + 'timestamp_stream': 584.2637150660157, + 'transform': [array([-2.27187276e+00, -1.11059103e+01, 1.01329805e-02]), + array([-0.05532453, 4.52045298, 0.01721192])]} +{'AngularVelocity': array([-0.00112361, -0.01044459, 0.62238324]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.952621459960938, + 'FR_Wheel_Angle': 32.34010314941406, + 'Location': array([ -4.15081453, -21.37164307, 0.17407601]), + 'Rotation': array([-0.07135499, 13.14848614, -0.01882934]), + 'Velocity': array([-4.39247116e-02, -2.68282313e-02, -6.49738286e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.65473175, 15.42864513, 0.81118739]), + 'camera_rotation': array([-11.90780544, 2.90222287, 3.02600932]), + 'current_gear_input': False, + 'focus_actor_dist': 1677.8411865234375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-800.32788086, -859.02099609, 15.13793182]), + 'frame': 17974, + 'frame_number': 17974, + 'framesequence': 68833, + 'gaze_dir': array([0.96979523, 0.20397949, 0.13291168]), + 'gaze_origin': array([-3.06047678, -0.18573837, 0.12147828]), + 'gaze_valid': True, + 'gaze_vergence': 198.68190002441406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96788025, 0.21694946, 0.12695312]), + 'left_gaze_origin': array([-2.9747088 , 3.00336933, 0.12037659]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4615325927734375, + 'left_pupil_posn': array([0.22453785, 0.01651227]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97171021, 0.19100952, 0.13887024]), + 'right_gaze_origin': array([-3.146245 , -3.37484598, 0.12257997]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5088958740234375, + 'right_pupil_posn': array([ 0.20336139, -0.05968487]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10186468809843063, + 'throttle_input': 0.0, + 'timestamp': 584.2978858686984, + 'timestamp_carla': 584298, + 'timestamp_device': 27543, + 'timestamp_stream': 584.2978858686984, + 'transform': [array([-2.23906684e+00, -1.10403576e+01, 1.01557346e-02]), + array([-0.05557042, 4.37209511, 0.01708986])]} +{'AngularVelocity': array([-0.01108723, -0.00106206, 0.66613787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.569828033447266, + 'FR_Wheel_Angle': 33.0910758972168, + 'Location': array([ -4.1589818 , -21.37585449, 0.17408779]), + 'Rotation': array([-0.07113642, 13.05739212, -0.01876831]), + 'Velocity': array([-0.02674043, -0.01760618, 0.00068589]), + 'brake_input': 0.0, + 'camera_location': array([-4.62150002, 15.48930931, 0.75447249]), + 'camera_rotation': array([-12.0069046 , 3.12586045, 2.91283774]), + 'current_gear_input': False, + 'focus_actor_dist': 1466.6278076171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -732.46789551, -1052.94775391, 17.24595642]), + 'frame': 17975, + 'frame_number': 17975, + 'framesequence': 68837, + 'gaze_dir': array([0.96883392, 0.20469666, 0.13850403]), + 'gaze_origin': array([-3.06090713, -0.18659823, 0.12080079]), + 'gaze_valid': True, + 'gaze_vergence': 184.55645751953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96618652, 0.22019958, 0.1341095 ]), + 'left_gaze_origin': array([-2.97490239, 3.00238061, 0.11878204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.463287353515625, + 'left_pupil_posn': array([0.22460866, 0.01680756]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97148132, 0.18919373, 0.14289856]), + 'right_gaze_origin': array([-3.14691186, -3.37557673, 0.12281953]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5902099609375, + 'right_pupil_posn': array([ 0.20508838, -0.05731416]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10186468809843063, + 'throttle_input': 0.0, + 'timestamp': 584.3305755667388, + 'timestamp_carla': 584331, + 'timestamp_device': 27576, + 'timestamp_stream': 584.3305755667388, + 'transform': [array([-2.20800567e+00, -1.09785891e+01, 1.01905251e-02]), + array([-0.05587777, 4.23235035, 0.01696778])]} +{'AngularVelocity': array([-0.01255268, -0.00196534, 0.88132584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.58189582824707, + 'FR_Wheel_Angle': 33.09829330444336, + 'Location': array([ -4.16485023, -21.37892723, 0.17407748]), + 'Rotation': array([-0.07175113, 12.98794651, -0.01834106]), + 'Velocity': array([-0.02252663, -0.01523622, -0.00051758]), + 'brake_input': 0.0, + 'camera_location': array([-4.60703468, 15.54154778, 0.67589241]), + 'camera_rotation': array([-12.22114754, 3.39495802, 2.78526306]), + 'current_gear_input': False, + 'focus_actor_dist': 1576.2440185546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-772.53491211, -943.97436523, 15.2006073 ]), + 'frame': 17976, + 'frame_number': 17976, + 'framesequence': 68841, + 'gaze_dir': array([0.96664429, 0.2101593 , 0.14515686]), + 'gaze_origin': array([-3.06210804, -0.18780671, 0.12420884]), + 'gaze_valid': True, + 'gaze_vergence': 166.05213928222656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9624176 , 0.2278595 , 0.14770508]), + 'left_gaze_origin': array([-2.97471642, 3.00189209, 0.11989747]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4543609619140625, + 'left_pupil_posn': array([0.22606707, 0.01744157]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97087097, 0.19245911, 0.14260864]), + 'right_gaze_origin': array([-3.14949965, -3.37750578, 0.12852021]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5486907958984375, + 'right_pupil_posn': array([ 0.20930624, -0.04958558]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10230415314435959, + 'throttle_input': 0.05555810034275055, + 'timestamp': 584.3635049685836, + 'timestamp_carla': 584364, + 'timestamp_device': 27610, + 'timestamp_stream': 584.3635049685836, + 'transform': [array([-2.17680693e+00, -1.09176989e+01, 1.01127625e-02]), + array([-0.05636955, 4.09268618, 0.01730348])]} +{'AngularVelocity': array([ 0.00878599, 0.00412292, -1.36408603]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.582103729248047, + 'FR_Wheel_Angle': 33.09840393066406, + 'Location': array([ -4.17095995, -21.38198662, 0.17409103]), + 'Rotation': array([-0.07216778, 12.90272331, -0.0180664 ]), + 'Velocity': array([-0.0236927 , -0.01232514, 0.00015937]), + 'brake_input': 0.0, + 'camera_location': array([-4.58801079, 15.58974075, 0.62730575]), + 'camera_rotation': array([-12.54448891, 3.57572842, 2.68377352]), + 'current_gear_input': False, + 'focus_actor_dist': 1652.8233642578125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-810.79058838, -869.87939453, 15.1115036 ]), + 'frame': 17977, + 'frame_number': 17977, + 'framesequence': 68845, + 'gaze_dir': array([0.96605682, 0.21282959, 0.14556885]), + 'gaze_origin': array([-3.0629878 , -0.19339219, 0.12809068]), + 'gaze_valid': True, + 'gaze_vergence': 197.15614318847656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96392822, 0.2263031 , 0.13999939]), + 'left_gaze_origin': array([-2.97661471, 2.99603724, 0.1260605 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3602447509765625, + 'left_pupil_posn': array([0.23258138, 0.02418 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96818542, 0.19935608, 0.15113831]), + 'right_gaze_origin': array([-3.1493609 , -3.3828218 , 0.13012084]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.588287353515625, + 'right_pupil_posn': array([ 0.21235049, -0.0510689 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10387890785932541, + 'throttle_input': 0.09126421064138412, + 'timestamp': 584.398029666394, + 'timestamp_carla': 584398, + 'timestamp_device': 27643, + 'timestamp_stream': 584.398029666394, + 'transform': [array([-2.14418411e+00, -1.08553963e+01, 9.98287182e-03]), + array([-0.0567657 , 3.94747853, 0.01782228])]} +{'AngularVelocity': array([ 0.00861166, 0.00415474, -1.38955033]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.581947326660156, + 'FR_Wheel_Angle': 33.097801208496094, + 'Location': array([ -4.17661238, -21.38489532, 0.17410526]), + 'Rotation': array([-0.07235219, 12.83633614, -0.01782226]), + 'Velocity': array([-2.60897074e-02, -1.37254214e-02, -5.77545143e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.5425415 , 15.65307999, 0.59272957]), + 'camera_rotation': array([-12.69204807, 3.69768739, 2.43223739]), + 'current_gear_input': False, + 'focus_actor_dist': 1525.5201416015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-771.61132812, -985.12072754, 17.19525146]), + 'frame': 17978, + 'frame_number': 17978, + 'framesequence': 68849, + 'gaze_dir': array([0.96453094, 0.2191925 , 0.14626312]), + 'gaze_origin': array([-3.06357741, -0.19683991, 0.12745363]), + 'gaze_valid': True, + 'gaze_vergence': 195.94476318359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96224976, 0.23284912, 0.14082336]), + 'left_gaze_origin': array([-2.97729969, 2.9927125 , 0.1264679 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4341583251953125, + 'left_pupil_posn': array([0.23686743, 0.02404404]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96681213, 0.20553589, 0.15170288]), + 'right_gaze_origin': array([-3.14985514, -3.38639235, 0.12843934]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.6166534423828125, + 'right_pupil_posn': array([ 0.21712387, -0.05223131]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10636921972036362, + 'throttle_input': 0.10713358968496323, + 'timestamp': 584.4297361671925, + 'timestamp_carla': 584430, + 'timestamp_device': 27676, + 'timestamp_stream': 584.4297361671925, + 'transform': [array([-2.11394835e+00, -1.07991810e+01, 9.97592881e-03]), + array([-0.05679302, 3.81383061, 0.01794435])]} +{'AngularVelocity': array([-0.16363148, 0.14307013, -4.72874212]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.428070068359375, + 'FR_Wheel_Angle': 32.829078674316406, + 'Location': array([ -4.19751453, -21.39525986, 0.17419964]), + 'Rotation': array([-8.62379670e-02, 1.25883274e+01, -2.22778297e-03]), + 'Velocity': array([-0.35823089, -0.2008571 , 0.00037276]), + 'brake_input': 0.0, + 'camera_location': array([-4.48283386, 15.70171165, 0.56332409]), + 'camera_rotation': array([-12.93822193, 3.83625484, 2.526618 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1506.91845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-773.08581543, -999.18969727, 17.38247681]), + 'frame': 17979, + 'frame_number': 17979, + 'framesequence': 68853, + 'gaze_dir': array([0.96394348, 0.22353363, 0.14414978]), + 'gaze_origin': array([-3.06387424, -0.19987489, 0.12450028]), + 'gaze_valid': True, + 'gaze_vergence': 473.18609619140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96269226, 0.22973633, 0.14291382]), + 'left_gaze_origin': array([-2.97769189, 2.99013066, 0.12098389]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.404937744140625, + 'left_pupil_posn': array([0.24268162, 0.01796907]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9651947 , 0.21733093, 0.14538574]), + 'right_gaze_origin': array([-3.1500566 , -3.38988042, 0.12801667]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.613555908203125, + 'right_pupil_posn': array([ 0.21849823, -0.05165052]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10906095057725906, + 'throttle_input': 0.1111009418964386, + 'timestamp': 584.4624257683754, + 'timestamp_carla': 584463, + 'timestamp_device': 27710, + 'timestamp_stream': 584.4624257683754, + 'transform': [array([-2.08220911e+00, -1.07420301e+01, 1.00369258e-02]), + array([-0.05660861, 3.67454004, 0.01773072])]} +{'AngularVelocity': array([ 0.01020725, -0.07214577, -6.69219875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.372957229614258, + 'FR_Wheel_Angle': 32.761878967285156, + 'Location': array([ -4.31610727, -21.45327377, 0.17431851]), + 'Rotation': array([-8.62106457e-02, 1.12501860e+01, -5.12695359e-03]), + 'Velocity': array([-5.36069393e-01, -3.10439378e-01, 4.17890551e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.42347145, 15.74232292, 0.50756782]), + 'camera_rotation': array([-13.20737934, 4.03419447, 2.73342252]), + 'current_gear_input': False, + 'focus_actor_dist': 1390.6171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -738.14056396, -1104.96984863, 17.26498413]), + 'frame': 17980, + 'frame_number': 17980, + 'framesequence': 68857, + 'gaze_dir': array([0.97041321, 0.1989975 , 0.13578796]), + 'gaze_origin': array([-3.05869532, -0.18389589, 0.11754838]), + 'gaze_valid': True, + 'gaze_vergence': 157.03594970703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96931458, 0.21110535, 0.12590027]), + 'left_gaze_origin': array([-2.97290802, 3.00580454, 0.11267548]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5141448974609375, + 'left_pupil_posn': array([0.22143877, 0.01393235]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97151184, 0.18688965, 0.14567566]), + 'right_gaze_origin': array([-3.14448261, -3.37359643, 0.12242127]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.551910400390625, + 'right_pupil_posn': array([ 0.20034361, -0.0598042 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11228369921445847, + 'throttle_input': 0.1111009418964386, + 'timestamp': 584.4977278672159, + 'timestamp_carla': 584498, + 'timestamp_device': 27743, + 'timestamp_stream': 584.4977278672159, + 'transform': [array([-2.04716706e+00, -1.06811924e+01, 1.01270862e-02]), + array([-0.0563354 , 3.52190232, 0.01730348])]} +{'AngularVelocity': array([-0.14150289, 0.08794072, -8.8972826 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.239992141723633, + 'FR_Wheel_Angle': 32.427921295166016, + 'Location': array([ -4.47986031, -21.52860832, 0.17448547]), + 'Rotation': array([-8.56642276e-02, 9.42829609e+00, -7.26318359e-03]), + 'Velocity': array([-8.08830500e-01, -4.07708168e-01, 6.94665883e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.38710022, 15.78196335, 0.43912101]), + 'camera_rotation': array([-13.51772881, 4.23663044, 2.61416221]), + 'current_gear_input': False, + 'focus_actor_dist': 1195.877685546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -641.64294434, -1271.88781738, 17.20995331]), + 'frame': 17981, + 'frame_number': 17981, + 'framesequence': 68861, + 'gaze_dir': array([0.96974182, 0.2024231 , 0.13571167]), + 'gaze_origin': array([-3.05871987, -0.18487932, 0.11823349]), + 'gaze_valid': True, + 'gaze_vergence': 205.0859832763672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96815491, 0.21429443, 0.1293335 ]), + 'left_gaze_origin': array([-2.97266555, 3.00509214, 0.1127243 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.52154541015625, + 'left_pupil_posn': array([0.22316194, 0.01273757]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97132874, 0.19055176, 0.14208984]), + 'right_gaze_origin': array([-3.14477396, -3.37485075, 0.12374268]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5807952880859375, + 'right_pupil_posn': array([ 0.20235622, -0.05791712]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11567126214504242, + 'throttle_input': 0.1111009418964386, + 'timestamp': 584.530570268631, + 'timestamp_carla': 584531, + 'timestamp_device': 27776, + 'timestamp_stream': 584.530570268631, + 'transform': [array([-2.01367307e+00, -1.06252003e+01, 1.03038596e-02]), + array([-0.0559051 , 3.37709188, 0.01663209])]} +{'AngularVelocity': array([ 0.09335809, -0.07862149, -7.92422724]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.400951385498047, + 'FR_Wheel_Angle': 31.046178817749023, + 'Location': array([ -4.67602634, -21.60874939, 0.17463633]), + 'Rotation': array([-0.07608147, 7.35315943, -0.02056885]), + 'Velocity': array([-0.76048344, -0.34053904, 0.00077579]), + 'brake_input': 0.0, + 'camera_location': array([-4.35955429, 15.81047058, 0.37933373]), + 'camera_rotation': array([-13.73331738, 4.39507246, 2.38525176]), + 'current_gear_input': False, + 'focus_actor_dist': 1138.8343505859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -626.92956543, -1321.28857422, 17.20765686]), + 'frame': 17982, + 'frame_number': 17982, + 'framesequence': 68865, + 'gaze_dir': array([0.96663666, 0.20932007, 0.14689636]), + 'gaze_origin': array([-3.06082082, -0.18916702, 0.12088242]), + 'gaze_valid': True, + 'gaze_vergence': 164.21170043945312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96591187, 0.21948242, 0.13722229]), + 'left_gaze_origin': array([-2.97483087, 3.00254703, 0.11605531]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.484893798828125, + 'left_pupil_posn': array([0.22797441, 0.01924402]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96736145, 0.19915771, 0.15657043]), + 'right_gaze_origin': array([-3.14681125, -3.38088083, 0.12570953]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.597412109375, + 'right_pupil_posn': array([ 0.2084837 , -0.05434835]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11915037035942078, + 'throttle_input': 0.1111009418964386, + 'timestamp': 584.562400367111, + 'timestamp_carla': 584563, + 'timestamp_device': 27810, + 'timestamp_stream': 584.562400367111, + 'transform': [array([-1.98021722e+00, -1.05713177e+01, 1.05403895e-02]), + array([-0.05542015, 3.23345137, 0.01571656])]} +{'AngularVelocity': array([ 0.80164582, -0.60050774, 0.0195687 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.13700294494629, + 'FR_Wheel_Angle': 28.75537109375, + 'Location': array([ -4.79854107, -21.65332794, 0.1746075 ]), + 'Rotation': array([-0.05173185, 6.140872 , -0.04486084]), + 'Velocity': array([-0.00774158, -0.00412007, -0.00010247]), + 'brake_input': 0.0, + 'camera_location': array([-4.34030533, 15.81951332, 0.31117526]), + 'camera_rotation': array([-13.92450809, 4.42985964, 2.22406793]), + 'current_gear_input': False, + 'focus_actor_dist': 1239.464111328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -669.50921631, -1223.44140625, 17.2257843 ]), + 'frame': 17983, + 'frame_number': 17983, + 'framesequence': 68869, + 'gaze_dir': array([0.96590424, 0.21633148, 0.14150238]), + 'gaze_origin': array([-3.0604074 , -0.19163209, 0.12228547]), + 'gaze_valid': True, + 'gaze_vergence': 231.98243713378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96307373, 0.22935486, 0.14089966]), + 'left_gaze_origin': array([-2.97347593, 2.99796939, 0.11784516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6015472412109375, + 'left_pupil_posn': array([0.23235798, 0.01563728]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96873474, 0.20330811, 0.1421051 ]), + 'right_gaze_origin': array([-3.14733911, -3.38123322, 0.12672578]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5914306640625, + 'right_pupil_posn': array([ 0.21226764, -0.05275881]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.12317880988121033, + 'throttle_input': 0.1111009418964386, + 'timestamp': 584.5977007672191, + 'timestamp_carla': 584598, + 'timestamp_device': 27843, + 'timestamp_stream': 584.5977007672191, + 'transform': [array([ -1.94192076, -10.51214695, 0.01073868]), + array([-0.05496253, 3.07019305, 0.01483155])]} +{'AngularVelocity': array([-0.08098643, 0.07319484, -0.00074866]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.763933181762695, + 'FR_Wheel_Angle': 25.11000633239746, + 'Location': array([ -4.79859018, -21.65340805, 0.17468372]), + 'Rotation': array([-0.05919725, 6.1408453 , -0.02923584]), + 'Velocity': array([1.34635857e-05, 1.89771556e-04, 7.62498385e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.29650307, 15.82703114, 0.27273753]), + 'camera_rotation': array([-14.08020878, 4.37556505, 2.22973347]), + 'current_gear_input': False, + 'focus_actor_dist': 1143.571044921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -641.30493164, -1310.26257324, 17.21943665]), + 'frame': 17984, + 'frame_number': 17984, + 'framesequence': 68873, + 'gaze_dir': array([0.96474457, 0.2193222 , 0.14524078]), + 'gaze_origin': array([-3.06187916, -0.19758911, 0.12165833]), + 'gaze_valid': True, + 'gaze_vergence': 444.0913391113281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96336365, 0.2260437 , 0.14427185]), + 'left_gaze_origin': array([-2.9751482 , 2.99414086, 0.11697083]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6475830078125, + 'left_pupil_posn': array([0.23825276, 0.01602143]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96612549, 0.21260071, 0.14620972]), + 'right_gaze_origin': array([-3.14861012, -3.38931894, 0.12634583]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.6788482666015625, + 'right_pupil_posn': array([ 0.21666336, -0.05226433]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.12788476049900055, + 'throttle_input': 0.1111009418964386, + 'timestamp': 584.6297900676727, + 'timestamp_carla': 584630, + 'timestamp_device': 27876, + 'timestamp_stream': 584.6297900676727, + 'transform': [array([ -1.90579069, -10.45873356, 0.01097082]), + array([-0.05444343, 2.91724396, 0.01394655])]} +{'AngularVelocity': array([-0.02752422, 0.02323409, -0.00021533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.970735549926758, + 'FR_Wheel_Angle': 20.951927185058594, + 'Location': array([ -4.79865122, -21.65346336, 0.17471367]), + 'Rotation': array([-0.06872536, 6.1408143 , -0.02059936]), + 'Velocity': array([ 4.90188131e-06, 7.02900579e-05, -2.87675386e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.25180435, 15.8184042 , 0.2700671 ]), + 'camera_rotation': array([-14.14552593, 4.22681618, 2.28506541]), + 'current_gear_input': False, + 'focus_actor_dist': 1156.2354736328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -645.06707764, -1292.00708008, 17.21860504]), + 'frame': 17985, + 'frame_number': 17985, + 'framesequence': 68877, + 'gaze_dir': array([0.96276855, 0.23067474, 0.14064789]), + 'gaze_origin': array([-3.06253529, -0.20253985, 0.12026979]), + 'gaze_valid': True, + 'gaze_vergence': 366.24267578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96102905, 0.23873901, 0.13931274]), + 'left_gaze_origin': array([-2.97592163, 2.98802209, 0.11510011]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6879730224609375, + 'left_pupil_posn': array([0.24578571, 0.01281375]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96450806, 0.22261047, 0.14198303]), + 'right_gaze_origin': array([-3.14914894, -3.39310169, 0.12543945]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.6748809814453125, + 'right_pupil_posn': array([ 0.22376049, -0.05488467]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1327921450138092, + 'throttle_input': 0.11903563141822815, + 'timestamp': 584.6625462658703, + 'timestamp_carla': 584663, + 'timestamp_device': 27910, + 'timestamp_stream': 584.6625462658703, + 'transform': [array([ -1.86741638, -10.40455627, 0.01118719]), + array([-0.05386287, 2.75587273, 0.01309205])]} +{'AngularVelocity': array([-0.00346895, 0.00271057, -0.35307774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.89334774017334, + 'FR_Wheel_Angle': 18.549848556518555, + 'Location': array([ -4.80570269, -21.65530968, 0.17474297]), + 'Rotation': array([-0.07428513, 6.09709311, -0.01608277]), + 'Velocity': array([-0.0575962 , -0.01676398, -0.00043586]), + 'brake_input': 0.0, + 'camera_location': array([-4.21581459, 15.80338001, 0.26040998]), + 'camera_rotation': array([-14.25051308, 4.06169319, 2.31705904]), + 'current_gear_input': False, + 'focus_actor_dist': 1095.150634765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -630.12487793, -1346.54516602, 17.21742249]), + 'frame': 17986, + 'frame_number': 17986, + 'framesequence': 68881, + 'gaze_dir': array([0.96109009, 0.23687744, 0.14181519]), + 'gaze_origin': array([-3.06418467, -0.20663759, 0.11973267]), + 'gaze_valid': True, + 'gaze_vergence': 307.5350341796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96003723, 0.24395752, 0.13713074]), + 'left_gaze_origin': array([-2.97912145, 2.98203611, 0.11495362]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.73602294921875, + 'left_pupil_posn': array([0.2523669 , 0.01338983]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96214294, 0.22979736, 0.14649963]), + 'right_gaze_origin': array([-3.14924788, -3.39531112, 0.12451173]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.6613006591796875, + 'right_pupil_posn': array([ 0.22710967, -0.05644441]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.13843196630477905, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.6960989683867, + 'timestamp_carla': 584696, + 'timestamp_device': 27943, + 'timestamp_stream': 584.6960989683867, + 'transform': [array([ -1.82640779, -10.34946537, 0.01137613]), + array([-0.05325498, 2.58455229, 0.01232911])]} +{'AngularVelocity': array([ 0.00190776, -0.0053585 , -0.24651337]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.385629653930664, + 'FR_Wheel_Angle': 16.161378860473633, + 'Location': array([ -4.81785011, -21.65830803, 0.17476031]), + 'Rotation': array([-0.07287128, 6.02643394, -0.01647949]), + 'Velocity': array([-0.04456453, -0.01212384, 0.00026661]), + 'brake_input': 0.0, + 'camera_location': array([-4.17882538, 15.78858566, 0.25133303]), + 'camera_rotation': array([-14.29915047, 3.79741383, 2.31519604]), + 'current_gear_input': False, + 'focus_actor_dist': 1089.2567138671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -628.7522583 , -1346.81713867, 17.21606445]), + 'frame': 17987, + 'frame_number': 17987, + 'framesequence': 68885, + 'gaze_dir': array([0.95769501, 0.24869537, 0.14421844]), + 'gaze_origin': array([-3.06615233, -0.2099129 , 0.11244507]), + 'gaze_valid': True, + 'gaze_vergence': 243.58636474609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95484924, 0.26074219, 0.14234924]), + 'left_gaze_origin': array([-2.98037744, 2.97879958, 0.10841065]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6909637451171875, + 'left_pupil_posn': array([0.25696254, 0.0084691 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96054077, 0.23664856, 0.14608765]), + 'right_gaze_origin': array([-3.15192747, -3.39862514, 0.1164795 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.6327972412109375, + 'right_pupil_posn': array([ 0.23561025, -0.0607239 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1448957920074463, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.730250865221, + 'timestamp_carla': 584731, + 'timestamp_device': 27976, + 'timestamp_stream': 584.730250865221, + 'transform': [array([ -1.78270411, -10.2938385 , 0.01154312]), + array([-0.05257879, 2.40317869, 0.01165772])]} +{'AngularVelocity': array([ 0.03986562, -0.01775611, 0.76968992]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.344688415527344, + 'FR_Wheel_Angle': 12.148725509643555, + 'Location': array([ -4.82088327, -21.65899277, 0.17474341]), + 'Rotation': array([-0.07168283, 6.01500893, -0.01693725]), + 'Velocity': array([ 0.00369388, 0.00381845, -0.00043383]), + 'brake_input': 0.0, + 'camera_location': array([-4.15077209, 15.73570347, 0.22134781]), + 'camera_rotation': array([-14.38147449, 3.33678436, 2.35651851]), + 'current_gear_input': False, + 'focus_actor_dist': 1108.542236328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -640.37188721, -1324.85668945, 17.2221756 ]), + 'frame': 17988, + 'frame_number': 17988, + 'framesequence': 68889, + 'gaze_dir': array([0.96524811, 0.21793365, 0.14298248]), + 'gaze_origin': array([-3.05969167, -0.18653032, 0.1117096 ]), + 'gaze_valid': True, + 'gaze_vergence': 161.3260040283203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96209717, 0.23542786, 0.1375885 ]), + 'left_gaze_origin': array([-2.97131824, 3.01097417, 0.10767823]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6504974365234375, + 'left_pupil_posn': array([0.22252941, 0.01128572]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96839905, 0.20043945, 0.14837646]), + 'right_gaze_origin': array([-3.14806557, -3.38403463, 0.11574098]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.6187896728515625, + 'right_pupil_posn': array([ 0.21619558, -0.06194842]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1531907021999359, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.7625277675688, + 'timestamp_carla': 584763, + 'timestamp_device': 28010, + 'timestamp_stream': 584.7625277675688, + 'transform': [array([ -1.73908663, -10.24160862, 0.01172403]), + array([-0.05173185, 2.22333765, 0.01101685])]} +{'AngularVelocity': array([ 0.03284955, -0.03499089, 0.62056035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.015279769897461, + 'FR_Wheel_Angle': 8.062238693237305, + 'Location': array([ -4.82498169, -21.65973663, 0.17477065]), + 'Rotation': array([-0.07250928, 5.99742079, -0.01647949]), + 'Velocity': array([0.00518963, 0.00280816, 0.00027766]), + 'brake_input': 0.0, + 'camera_location': array([-4.14121437, 15.67311859, 0.1703414 ]), + 'camera_rotation': array([-14.49568939, 2.7737155 , 2.4686892 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1074.043212890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -584.57885742, -1335.78051758, 17.16853333]), + 'frame': 17989, + 'frame_number': 17989, + 'framesequence': 68893, + 'gaze_dir': array([0.98840332, 0.04154205, 0.14421082]), + 'gaze_origin': array([-3.12690282, -0.04896699, 0.14116211]), + 'gaze_valid': True, + 'gaze_vergence': 137.3245391845703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98696899, 0.06427002, 0.14749146]), + 'left_gaze_origin': array([-3.10712457, 3.14927554, 0.1585663 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6055450439453125, + 'left_pupil_posn': array([0.06715 , 0.02092415]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98983765, 0.01881409, 0.14093018]), + 'right_gaze_origin': array([-3.14668131, -3.24720931, 0.12375794]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5916290283203125, + 'right_pupil_posn': array([ 0.06290674, -0.0492171 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.16084474325180054, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.7963729687035, + 'timestamp_carla': 584797, + 'timestamp_device': 28043, + 'timestamp_stream': 584.7963729687035, + 'transform': [array([ -1.69085073, -10.18727303, 0.01186914]), + array([-0.05084392, 2.02565861, 0.01046753])]} +{'AngularVelocity': array([ 0.0222202, -0.0370874, 0.6047554]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.678300380706787, + 'FR_Wheel_Angle': 4.396080017089844, + 'Location': array([ -4.82835722, -21.66020393, 0.17476948]), + 'Rotation': array([-0.07254343, 5.9858551 , -0.01629639]), + 'Velocity': array([ 8.13454017e-03, 2.56793248e-03, -9.62257400e-06]), + 'brake_input': 0.0, + 'camera_location': array([-4.11745167, 15.59999657, 0.1698074 ]), + 'camera_rotation': array([-14.53869247, 2.20640755, 2.62725639]), + 'current_gear_input': False, + 'focus_actor_dist': 1078.1033935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -385.89199829, -1279.49658203, 16.95323181]), + 'frame': 17990, + 'frame_number': 17990, + 'framesequence': 68897, + 'gaze_dir': array([ 0.98687744, -0.05063629, 0.15218353]), + 'gaze_origin': array([-3.15462804, 0.03648224, 0.14411241]), + 'gaze_valid': True, + 'gaze_vergence': 156.77780151367188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98895264, -0.03482056, 0.14396667]), + 'left_gaze_origin': array([-3.11342025, 3.22803974, 0.15399781]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6442413330078125, + 'left_pupil_posn': array([-0.01586103, 0.02308291]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98480225, -0.06645203, 0.16040039]), + 'right_gaze_origin': array([-3.19583607, -3.15507531, 0.13422699]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.6456756591796875, + 'right_pupil_posn': array([-0.03343439, -0.05143368]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1710989773273468, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.828974366188, + 'timestamp_carla': 584829, + 'timestamp_device': 28076, + 'timestamp_stream': 584.828974366188, + 'transform': [array([ -1.64150786, -10.13535023, 0.01200849]), + array([-0.04980574, 1.82463825, 0.01000977])]} +{'AngularVelocity': array([ 0.01225449, -0.03770399, 0.55657125]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9862059354782104, + 'FR_Wheel_Angle': 1.616552472114563, + 'Location': array([ -4.83156586, -21.66054344, 0.17477714]), + 'Rotation': array([-0.07260491, 5.97854137, -0.01623535]), + 'Velocity': array([7.59094581e-03, 1.73995446e-03, 4.10747525e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.11494541, 15.4876461 , 0.18650205]), + 'camera_rotation': array([-14.38554573, 1.33805418, 2.72408128]), + 'current_gear_input': False, + 'focus_actor_dist': 1202.62158203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -277.08493042, -1139.39367676, 16.80735016]), + 'frame': 17991, + 'frame_number': 17991, + 'framesequence': 68901, + 'gaze_dir': array([ 0.98815918, -0.0422287 , 0.14642334]), + 'gaze_origin': array([-3.12988043, 0.0256424 , 0.13336717]), + 'gaze_valid': True, + 'gaze_vergence': 186.58883666992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98898315, -0.02516174, 0.14579773]), + 'left_gaze_origin': array([-3.08348703, 3.22031116, 0.14390565]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.53778076171875, + 'left_pupil_posn': array([-0.00803101, 0.0175516 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98733521, -0.05929565, 0.14704895]), + 'right_gaze_origin': array([-3.17627406, -3.16902614, 0.12282868]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.645843505859375, + 'right_pupil_posn': array([-0.0208891 , -0.05500579]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.18259835243225098, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.8619143664837, + 'timestamp_carla': 584862, + 'timestamp_device': 28110, + 'timestamp_stream': 584.8619143664837, + 'transform': [array([ -1.58828676, -10.08338833, 0.0121327 ]), + array([-0.04861728, 1.60905361, 0.00961304])]} +{'AngularVelocity': array([-0.00484501, -0.01877383, 0.4764109 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.16389407217502594, + 'FR_Wheel_Angle': -0.13416361808776855, + 'Location': array([ -4.83622265, -21.66094971, 0.17477676]), + 'Rotation': array([-0.07321279, 5.97527266, -0.01620483]), + 'Velocity': array([-0.01628794, -0.0020201 , 0.00063485]), + 'brake_input': 0.0, + 'camera_location': array([-4.11116791, 15.31517696, 0.21226779]), + 'camera_rotation': array([-14.16512871, 0.27681515, 3.08268547]), + 'current_gear_input': False, + 'focus_actor_dist': 1160.8155517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -263.60968018, -1175.62182617, 16.8030014 ]), + 'frame': 17992, + 'frame_number': 17992, + 'framesequence': 68905, + 'gaze_dir': array([ 0.98822021, -0.02706909, 0.15029907]), + 'gaze_origin': array([-3.11664057, 0.01273041, 0.12630083]), + 'gaze_valid': True, + 'gaze_vergence': 354.82659912109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98817444, -0.01844788, 0.15213013]), + 'left_gaze_origin': array([-3.06208658, 3.20891881, 0.13421021]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.582763671875, + 'left_pupil_posn': array([0.00790334, 0.01542938]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98826599, -0.03569031, 0.14846802]), + 'right_gaze_origin': array([-3.17119479, -3.18345809, 0.11839142]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.595001220703125, + 'right_pupil_posn': array([-0.00879514, -0.05511928]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1937498301267624, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.8958326652646, + 'timestamp_carla': 584896, + 'timestamp_device': 28143, + 'timestamp_stream': 584.8958326652646, + 'transform': [array([ -1.529953 , -10.03049088, 0.01221382]), + array([-0.04742883, 1.37401736, 0.0093689 ])]} +{'AngularVelocity': array([-1.18494019e-04, 2.15681326e-02, 5.48267722e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.06531686335802078, + 'FR_Wheel_Angle': -0.04864642396569252, + 'Location': array([ -4.85134554, -21.6625843 , 0.17481823]), + 'Rotation': array([-0.07483155, 5.9828043 , -0.0161438 ]), + 'Velocity': array([-0.09499484, -0.00989096, 0.00053858]), + 'brake_input': 0.0, + 'camera_location': array([-4.07962227, 15.13846588, 0.25431982]), + 'camera_rotation': array([-13.91797161, -0.63422453, 3.58663297]), + 'current_gear_input': False, + 'focus_actor_dist': 1246.63525390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -257.4961853 , -1083.7713623 , 16.77332306]), + 'frame': 17993, + 'frame_number': 17993, + 'framesequence': 68909, + 'gaze_dir': array([ 0.98986816, -0.01207733, 0.14067078]), + 'gaze_origin': array([-3.12566614, 0.00611877, 0.12470475]), + 'gaze_valid': True, + 'gaze_vergence': 220.54702758789062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99021912, 0.00230408, 0.13946533]), + 'left_gaze_origin': array([-3.07312799, 3.20184636, 0.13131867]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.422515869140625, + 'left_pupil_posn': array([0.01582754, 0.00918424]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98951721, -0.02645874, 0.14187622]), + 'right_gaze_origin': array([-3.17820454, -3.18960881, 0.11809083]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.484222412109375, + 'right_pupil_posn': array([ 0.00261402, -0.06067228]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.20643940567970276, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.9284570664167, + 'timestamp_carla': 584929, + 'timestamp_device': 28176, + 'timestamp_stream': 584.9284570664167, + 'transform': [array([-1.4701581 , -9.98020458, 0.01229399]), + array([-0.0461994 , 1.13426685, 0.0091858 ])]} +{'AngularVelocity': array([-0.00208296, 0.03579522, 0.55169398]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04868416488170624, + 'FR_Wheel_Angle': -0.04866042360663414, + 'Location': array([ -4.86499929, -21.66407585, 0.17481788]), + 'Rotation': array([-0.07254343, 5.98731804, -0.01617432]), + 'Velocity': array([-0.07263173, -0.00770928, 0.00025308]), + 'brake_input': 0.0, + 'camera_location': array([-4.06441784, 14.94296932, 0.29116192]), + 'camera_rotation': array([-13.59284782, -1.47237802, 3.85658288]), + 'current_gear_input': False, + 'focus_actor_dist': 1170.671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -250.93318176, -1154.3828125 , 16.78466797]), + 'frame': 17994, + 'frame_number': 17994, + 'framesequence': 68913, + 'gaze_dir': array([ 0.98999023, -0.00151825, 0.14074707]), + 'gaze_origin': array([-3.08168197, -0.00533981, 0.10525665]), + 'gaze_valid': True, + 'gaze_vergence': 355.7371520996094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98994446, 0.00744629, 0.14117432]), + 'left_gaze_origin': array([-3.01690078, 3.19207788, 0.10740509]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.409576416015625, + 'left_pupil_posn': array([0.02804363, 0.00257403]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99003601, -0.01048279, 0.14031982]), + 'right_gaze_origin': array([-3.14646316, -3.20275736, 0.10310823]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.394775390625, + 'right_pupil_posn': array([ 0.01278925, -0.06459558]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2178838551044464, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.9618615657091, + 'timestamp_carla': 584962, + 'timestamp_device': 28210, + 'timestamp_stream': 584.9618615657091, + 'transform': [array([-1.40525758, -9.92938423, 0.01234941]), + array([-0.04507925, 0.87524241, 0.00906372])]} +{'AngularVelocity': array([-0.00272507, 0.04206048, 0.60457128]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.051250506192445755, + 'FR_Wheel_Angle': -0.051226481795310974, + 'Location': array([ -4.87586021, -21.66530228, 0.17480689]), + 'Rotation': array([-0.07244781, 5.99266529, -0.01617432]), + 'Velocity': array([-0.06555782, -0.00696204, -0.00023744]), + 'brake_input': 0.0, + 'camera_location': array([-4.04601288, 14.73118305, 0.33945566]), + 'camera_rotation': array([-13.31805515, -2.42759562, 3.96041155]), + 'current_gear_input': False, + 'focus_actor_dist': 1231.946044921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -241.62818909, -1087.30285645, 16.75818634]), + 'frame': 17995, + 'frame_number': 17995, + 'framesequence': 68917, + 'gaze_dir': array([0.98838806, 0.01594543, 0.15081024]), + 'gaze_origin': array([-3.0532968 , -0.01693115, 0.0902382 ]), + 'gaze_valid': True, + 'gaze_vergence': 374.610595703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98808289, 0.02430725, 0.15194702]), + 'left_gaze_origin': array([-2.97936869, 3.18081379, 0.08861389]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.386444091796875, + 'left_pupil_posn': array([0.04187703, 0.00027281]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98869324, 0.00758362, 0.14967346]), + 'right_gaze_origin': array([-3.12722468, -3.2146759 , 0.09186249]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4973297119140625, + 'right_pupil_posn': array([ 0.02639675, -0.06489611]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2297128289937973, + 'throttle_input': 0.12300297617912292, + 'timestamp': 584.9955847673118, + 'timestamp_carla': 584996, + 'timestamp_device': 28243, + 'timestamp_stream': 584.9955847673118, + 'transform': [array([-1.33607912, -9.8788271 , 0.01237825]), + array([-0.04410253, 0.60030115, 0.00903321])]} +{'AngularVelocity': array([-0.00297893, 0.03976314, 0.51962906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03202124685049057, + 'FR_Wheel_Angle': 0.0448467954993248, + 'Location': array([ -4.88686991, -21.66655922, 0.17484382]), + 'Rotation': array([-0.07281664, 5.99818754, -0.01617432]), + 'Velocity': array([-0.06412979, -0.00697757, 0.00047337]), + 'brake_input': 0.0, + 'camera_location': array([-4.01430702, 14.53003025, 0.36225334]), + 'camera_rotation': array([-13.09405899, -3.39750671, 3.90249848]), + 'current_gear_input': False, + 'focus_actor_dist': 1457.1639404296875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-237.36863708, -855.77880859, 15.1007309 ]), + 'frame': 17996, + 'frame_number': 17996, + 'framesequence': 68921, + 'gaze_dir': array([0.98859406, 0.02902222, 0.1465683 ]), + 'gaze_origin': array([-3.07608199, -0.03184128, 0.1035759 ]), + 'gaze_valid': True, + 'gaze_vergence': 170.7061004638672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98747253, 0.04673767, 0.15065002]), + 'left_gaze_origin': array([-3.03329635, 3.16569686, 0.11422425]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.52508544921875, + 'left_pupil_posn': array([0.0533421 , 0.00506347]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98971558, 0.01130676, 0.14248657]), + 'right_gaze_origin': array([-3.11886764, -3.22937918, 0.09292756]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.43194580078125, + 'right_pupil_posn': array([ 0.04400957, -0.06357455]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.24068118631839752, + 'throttle_input': 0.12300297617912292, + 'timestamp': 585.0293961651623, + 'timestamp_carla': 585030, + 'timestamp_device': 28276, + 'timestamp_stream': 585.0293961651623, + 'transform': [array([-1.26320922, -9.82891655, 0.01238916]), + array([-0.0433034 , 0.31182238, 0.00906372])]} +{'AngularVelocity': array([-0.00396224, 0.04211799, 0.58688354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3050820529460907, + 'FR_Wheel_Angle': 0.621505618095398, + 'Location': array([ -4.89597654, -21.66758919, 0.1748331 ]), + 'Rotation': array([-0.07321279, 6.00164795, -0.01620483]), + 'Velocity': array([-0.07094223, -0.00771421, -0.00015846]), + 'brake_input': 0.0, + 'camera_location': array([-3.97506905, 14.3374691 , 0.39097026]), + 'camera_rotation': array([-12.83785915, -4.18469667, 3.7753737 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1438.295654296875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-223.6222229 , -869.23205566, 15.06580353]), + 'frame': 17997, + 'frame_number': 17997, + 'framesequence': 68925, + 'gaze_dir': array([0.98970795, 0.03884888, 0.13696289]), + 'gaze_origin': array([-3.12654114, -0.042276 , 0.12458954]), + 'gaze_valid': True, + 'gaze_vergence': 216.0838623046875, + 'handbrake_input': False, + 'left_eye_openness': 0.9088228344917297, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98861694, 0.05230713, 0.14105225]), + 'left_gaze_origin': array([-3.08428812, 3.15483546, 0.1330063 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.348846435546875, + 'left_pupil_posn': array([0.0655688 , 0.00529325]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8967632055282593, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99079895, 0.02539062, 0.13287354]), + 'right_gaze_origin': array([-3.16879463, -3.23938775, 0.11617279]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3536834716796875, + 'right_pupil_posn': array([ 0.05377364, -0.06001902]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.25161290168762207, + 'throttle_input': 0.12300297617912292, + 'timestamp': 585.0631252676249, + 'timestamp_carla': 585064, + 'timestamp_device': 28310, + 'timestamp_stream': 585.0631252676249, + 'transform': [array([-1.18710017, -9.77994728, 0.01238447]), + array([-0.04263404, 0.01162499, 0.00915527])]} +{'AngularVelocity': array([-0.01977524, 0.0264164 , 0.07775988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.481283664703369, + 'FR_Wheel_Angle': 5.699979782104492, + 'Location': array([ -4.96974564, -21.67678452, 0.17497154]), + 'Rotation': array([-0.08258381, 5.96657705, -0.01443481]), + 'Velocity': array([-3.93035740e-01, -5.77968806e-02, 2.18820569e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.87293434, 14.13736916, 0.42903212]), + 'camera_rotation': array([-12.40754318, -4.93984222, 3.85519934]), + 'current_gear_input': False, + 'focus_actor_dist': 1331.159912109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-210.76904297, -971.3104248 , 16.50759888]), + 'frame': 17998, + 'frame_number': 17998, + 'framesequence': 68929, + 'gaze_dir': array([ 0.99058533, -0.01454163, 0.13285828]), + 'gaze_origin': array([-3.15379715e+00, -1.04141235e-03, 1.14555366e-01]), + 'gaze_valid': True, + 'gaze_vergence': 87.8083267211914, + 'handbrake_input': False, + 'left_eye_openness': 0.9136490821838379, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98858643, 0.00886536, 0.15036011]), + 'left_gaze_origin': array([-3.15919971, 3.20000935, 0.14037476]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2069244384765625, + 'left_pupil_posn': array([ 0.01276457, -0.00877094]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8974937200546265, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99258423, -0.03794861, 0.11535645]), + 'right_gaze_origin': array([-3.14839482, -3.20209217, 0.08873597]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.304290771484375, + 'right_pupil_posn': array([ 0.01277149, -0.07100523]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.26237985491752625, + 'throttle_input': 0.12300297617912292, + 'timestamp': 585.0964806675911, + 'timestamp_carla': 585097, + 'timestamp_device': 28343, + 'timestamp_stream': 585.0964806675911, + 'transform': [array([-1.10848475, -9.732337 , 0.01238005]), + array([-0.04205347, -0.29742432, 0.00924683])]} +{'AngularVelocity': array([-0.00665853, -0.03412072, -2.88840222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.516120910644531, + 'FR_Wheel_Angle': 11.070622444152832, + 'Location': array([ -5.09399414, -21.69696426, 0.17509837]), + 'Rotation': array([-0.08178468, 5.61825323, -0.01159668]), + 'Velocity': array([-0.56521362, -0.11246154, 0.00080366]), + 'brake_input': 0.0, + 'camera_location': array([-3.859375 , 13.90022087, 0.37868604]), + 'camera_rotation': array([-12.65835476, -5.79729509, 3.99067068]), + 'current_gear_input': False, + 'focus_actor_dist': 1306.5426025390625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-116.77783966, -994.7130127 , 27.40328217]), + 'frame': 17999, + 'frame_number': 17999, + 'framesequence': 68933, + 'gaze_dir': array([ 0.98989868, -0.0817337 , 0.11378479]), + 'gaze_origin': array([-3.1784997 , 0.06249695, 0.12050477]), + 'gaze_valid': True, + 'gaze_vergence': 147.59576416015625, + 'handbrake_input': False, + 'left_eye_openness': 0.9305605888366699, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99108887, -0.06111145, 0.11824036]), + 'left_gaze_origin': array([-3.14251399, 3.25605798, 0.12559663]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.157073974609375, + 'left_pupil_posn': array([-0.04782003, -0.01784515]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9824714660644531, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9887085 , -0.10235596, 0.10932922]), + 'right_gaze_origin': array([-3.21448517, -3.13106394, 0.11541291]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.23248291015625, + 'right_pupil_posn': array([-0.05917406, -0.07526922]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2718466818332672, + 'throttle_input': 0.12300297617912292, + 'timestamp': 585.1282916665077, + 'timestamp_carla': 585129, + 'timestamp_device': 28376, + 'timestamp_stream': 585.1282916665077, + 'transform': [array([-1.03046596, -9.68765259, 0.01240379]), + array([-0.04153438, -0.6031698 , 0.00924683])]} +{'AngularVelocity': array([-0.02637547, 0.02897494, -2.18837547]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.691642761230469, + 'FR_Wheel_Angle': 14.991915702819824, + 'Location': array([ -5.23184729, -21.72344589, 0.1752388 ]), + 'Rotation': array([-0.081088 , 5.07707834, -0.01016235]), + 'Velocity': array([-0.69786084, -0.1589908 , 0.00076893]), + 'brake_input': 0.0, + 'camera_location': array([-3.98207951, 13.62600899, 0.2453849 ]), + 'camera_rotation': array([-13.46875668, -6.954741 , 3.96156383]), + 'current_gear_input': False, + 'focus_actor_dist': 1177.5877685546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -24.72877502, -1133.34729004, 16.55044556]), + 'frame': 18000, + 'frame_number': 18000, + 'framesequence': 68937, + 'gaze_dir': array([ 0.99036407, -0.06774902, 0.11962128]), + 'gaze_origin': array([-3.13683939, 0.05357667, 0.12161256]), + 'gaze_valid': True, + 'gaze_vergence': 200.59815979003906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99142456, -0.05189514, 0.11979675]), + 'left_gaze_origin': array([-3.11348724, 3.2473526 , 0.13531801]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1821441650390625, + 'left_pupil_posn': array([-0.03511214, -0.00240421]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98930359, -0.08360291, 0.1194458 ]), + 'right_gaze_origin': array([-3.1601913 , -3.14019966, 0.10790711]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3006439208984375, + 'right_pupil_posn': array([-0.05030519, -0.07001507]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2806360125541687, + 'throttle_input': 0.12300297617912292, + 'timestamp': 585.1623665653169, + 'timestamp_carla': 585163, + 'timestamp_device': 28410, + 'timestamp_stream': 585.1623665653169, + 'transform': [array([-0.94402128, -9.64066887, 0.0123704 ]), + array([-0.04129532, -0.94092715, 0.0093689 ])]} +{'AngularVelocity': array([ 0.01562274, -0.02025888, -2.95201182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.214066505432129, + 'FR_Wheel_Angle': 18.016939163208008, + 'Location': array([ -5.39259005, -21.75699425, 0.17537044]), + 'Rotation': array([-0.07617027, 4.22758007, -0.01199341]), + 'Velocity': array([-0.6903885 , -0.17048176, 0.00087438]), + 'brake_input': 0.0, + 'camera_location': array([-4.10362244, 13.33642006, 0.20820872]), + 'camera_rotation': array([-13.62673855, -8.32937813, 3.53164315]), + 'current_gear_input': False, + 'focus_actor_dist': 1075.7606201171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -30.32124329, -1231.19873047, 16.58115387]), + 'frame': 18001, + 'frame_number': 18001, + 'framesequence': 68941, + 'gaze_dir': array([ 0.99124146, -0.04741669, 0.12268066]), + 'gaze_origin': array([-3.11715102, 0.0360054 , 0.11624146]), + 'gaze_valid': True, + 'gaze_vergence': 264.4632873535156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99116516, -0.03735352, 0.12719727]), + 'left_gaze_origin': array([-3.06067514, 3.23150039, 0.12308655]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2245941162109375, + 'left_pupil_posn': array([-0.01497996, -0.00143266]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99131775, -0.05747986, 0.11816406]), + 'right_gaze_origin': array([-3.1736269 , -3.15948939, 0.10939636]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2798614501953125, + 'right_pupil_posn': array([-0.03193122, -0.06900024]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2887478470802307, + 'throttle_input': 0.09919890016317368, + 'timestamp': 585.1960884667933, + 'timestamp_carla': 585197, + 'timestamp_device': 28443, + 'timestamp_stream': 585.1960884667933, + 'transform': [array([-0.85583067, -9.59510803, 0.01231789]), + array([-0.04123385, -1.28452933, 0.00958252])]} +{'AngularVelocity': array([ 6.33026939e-03, -6.72084047e-04, -2.97429419e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.512651443481445, + 'FR_Wheel_Angle': 18.061172485351562, + 'Location': array([ -5.55027866, -21.78979111, 0.17551498]), + 'Rotation': array([-0.07296008, 3.30709481, -0.01541138]), + 'Velocity': array([-0.67241609, -0.15863843, 0.0009526 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.14916897, 13.06380081, 0.30783772]), + 'camera_rotation': array([-13.01431656, -9.6451664 , 3.37999225]), + 'current_gear_input': False, + 'focus_actor_dist': 1059.8677978515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -21.69003296, -1243.59533691, 16.57563019]), + 'frame': 18002, + 'frame_number': 18002, + 'framesequence': 68945, + 'gaze_dir': array([ 0.99240112, -0.0246582 , 0.12016296]), + 'gaze_origin': array([-3.10069537, 0.02398987, 0.10066681]), + 'gaze_valid': True, + 'gaze_vergence': 333.0841064453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99212646, -0.01698303, 0.12397766]), + 'left_gaze_origin': array([-3.01756597, 3.22018147, 0.09778289]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.212554931640625, + 'left_pupil_posn': array([ 0.00149655, -0.01117516]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99267578, -0.03233337, 0.11634827]), + 'right_gaze_origin': array([-3.1838243 , -3.17220163, 0.10355073]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.22027587890625, + 'right_pupil_posn': array([-0.0161081 , -0.07596636]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.2957060635089874, + 'throttle_input': 0.09919890016317368, + 'timestamp': 585.2284750677645, + 'timestamp_carla': 585229, + 'timestamp_device': 28476, + 'timestamp_stream': 585.2284750677645, + 'transform': [array([-0.76885831, -9.55219936, 0.01228018]), + array([-0.04126117, -1.6224463 , 0.00976563])]} +{'AngularVelocity': array([ 9.82767157e-03, 3.93202754e-06, -1.90228784e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.887584686279297, + 'FR_Wheel_Angle': 13.719080924987793, + 'Location': array([ -5.70318508, -21.81798363, 0.17563362]), + 'Rotation': array([-0.07082906, 2.47467852, -0.0194397 ]), + 'Velocity': array([-6.23836815e-01, -1.19179383e-01, 9.86957530e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.17993069, 12.79490566, 0.47641724]), + 'camera_rotation': array([-12.24973202, -10.82205296, 3.41013718]), + 'current_gear_input': False, + 'focus_actor_dist': 1125.984130859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ 6.02722168e-03, -1.17456763e+03, 1.65360413e+01]), + 'frame': 18003, + 'frame_number': 18003, + 'framesequence': 68949, + 'gaze_dir': array([ 0.99222565, -0.00823212, 0.12353516]), + 'gaze_origin': array([-3.0887773 , 0.00854874, 0.07963486]), + 'gaze_valid': True, + 'gaze_vergence': 272.7541198730469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99253845, 0.0032196 , 0.1217804 ]), + 'left_gaze_origin': array([-3.00854492, 3.20548725, 0.07666627]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9968109130859375, + 'left_pupil_posn': array([ 0.0157485 , -0.02049458]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99191284, -0.01968384, 0.12528992]), + 'right_gaze_origin': array([-3.16900945, -3.18839002, 0.08260345]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.10479736328125, + 'right_pupil_posn': array([ 0.0016005 , -0.08813775]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3009979724884033, + 'throttle_input': 0.09919890016317368, + 'timestamp': 585.2607974670827, + 'timestamp_carla': 585261, + 'timestamp_device': 28510, + 'timestamp_stream': 585.2607974670827, + 'transform': [array([-0.68022335, -9.51019096, 0.01222731]), + array([-0.04147291, -1.96592104, 0.00997925])]} +{'AngularVelocity': array([-0.00432713, -0.01407433, -0.83154857]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.747396469116211, + 'FR_Wheel_Angle': 11.984979629516602, + 'Location': array([ -5.83667183, -21.8366909 , 0.17576523]), + 'Rotation': array([-0.06839068, 1.93552625, -0.02005005]), + 'Velocity': array([-5.20538568e-01, -7.81197399e-02, 5.17721171e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.24309158, 12.49069786, 0.59950322]), + 'camera_rotation': array([-11.69684887, -12.13336945, 3.51365304]), + 'current_gear_input': False, + 'focus_actor_dist': 1323.8250732421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 54.79742432, -977.65454102, 16.48860931]), + 'frame': 18004, + 'frame_number': 18004, + 'framesequence': 68953, + 'gaze_dir': array([0.99397278, 0.01036072, 0.10835266]), + 'gaze_origin': array([-3.09647775, -0.00906601, 0.07835618]), + 'gaze_valid': True, + 'gaze_vergence': 233.66378784179688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99331665, 0.02197266, 0.11322021]), + 'left_gaze_origin': array([-3.0552218 , 3.18800354, 0.08782959]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.044677734375, + 'left_pupil_posn': array([ 0.0338006 , -0.02882242]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99462891, -0.00125122, 0.10348511]), + 'right_gaze_origin': array([-3.1377337 , -3.20613575, 0.06888276]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1357879638671875, + 'right_pupil_posn': array([ 0.01961339, -0.0949738 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3049897849559784, + 'throttle_input': 0.1428549587726593, + 'timestamp': 585.2939403653145, + 'timestamp_carla': 585294, + 'timestamp_device': 28543, + 'timestamp_stream': 585.2939403653145, + 'transform': [array([-0.5879367 , -9.46797466, 0.01214474]), + array([-0.04196468, -2.32261515, 0.01025391])]} +{'AngularVelocity': array([-0.04180834, 0.02401925, -2.80804729]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.58681869506836, + 'FR_Wheel_Angle': 13.38552474975586, + 'Location': array([ -5.94588041, -21.85046577, 0.17589092]), + 'Rotation': array([-0.06826774, 1.49913204, -0.0168457 ]), + 'Velocity': array([-0.46005985, -0.07172865, 0.00054688]), + 'brake_input': 0.0, + 'camera_location': array([-4.32911015, 12.19355011, 0.67030323]), + 'camera_rotation': array([-11.48521519, -13.4105978 , 3.4852066 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1233.2318115234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 49.47470093, -1064.40795898, 16.45780945]), + 'frame': 18005, + 'frame_number': 18005, + 'framesequence': 68957, + 'gaze_dir': array([ 0.99497223, -0.00460815, 0.09745026]), + 'gaze_origin': array([-3.10886240e+00, 2.61611957e-03, 7.95333907e-02]), + 'gaze_valid': True, + 'gaze_vergence': 140.03433227539062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99456787, 0.01698303, 0.10264587]), + 'left_gaze_origin': array([-3.06351328, 3.20231175, 0.08695984]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.083404541015625, + 'left_pupil_posn': array([ 0.01546073, -0.03488696]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99537659, -0.02619934, 0.09225464]), + 'right_gaze_origin': array([-3.15421152, -3.19707942, 0.07210694]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1335601806640625, + 'right_pupil_posn': array([ 0.01194322, -0.09923661]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.30782800912857056, + 'throttle_input': 0.18252842128276825, + 'timestamp': 585.3281737677753, + 'timestamp_carla': 585329, + 'timestamp_device': 28576, + 'timestamp_stream': 585.3281737677753, + 'transform': [array([-0.49150664, -9.42521954, 0.01204546]), + array([-0.04247694, -2.69429779, 0.01055908])]} +{'AngularVelocity': array([-0.01283693, 0.07866175, -1.74986231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.150795936584473, + 'FR_Wheel_Angle': 15.105467796325684, + 'Location': array([ -6.029737 , -21.86149597, 0.175974 ]), + 'Rotation': array([-0.06967475, 1.12221587, -0.01486206]), + 'Velocity': array([-4.46453273e-01, -6.78686202e-02, 1.67875289e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.39278316, 11.88061523, 0.72786987]), + 'camera_rotation': array([-11.19493866, -14.68062019, 3.24299383]), + 'current_gear_input': False, + 'focus_actor_dist': 1157.9959716796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 82.97213745, -1145.55627441, 16.444664 ]), + 'frame': 18006, + 'frame_number': 18006, + 'framesequence': 68961, + 'gaze_dir': array([ 0.98321533, -0.16355133, 0.07669067]), + 'gaze_origin': array([-3.14626622, 0.12946627, 0.06945725]), + 'gaze_valid': True, + 'gaze_vergence': 120.4150161743164, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98666382, -0.13952637, 0.08374023]), + 'left_gaze_origin': array([-3.09133005, 3.32318139, 0.07280732]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2323760986328125, + 'left_pupil_posn': array([-0.12300664, -0.05789769]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97976685, -0.18757629, 0.06964111]), + 'right_gaze_origin': array([-3.20120263, -3.0642488 , 0.06610718]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.22955322265625, + 'right_pupil_posn': array([-0.13304716, -0.11777973]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.30989715456962585, + 'throttle_input': 0.21428243815898895, + 'timestamp': 585.3604073673487, + 'timestamp_carla': 585361, + 'timestamp_device': 28610, + 'timestamp_stream': 585.3604073673487, + 'transform': [array([-0.39952177, -9.38554287, 0.01200165]), + array([-0.04251109, -3.04791927, 0.01074219])]} +{'AngularVelocity': array([ 0.00820736, -0.01255926, -1.8179028 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.396160125732422, + 'FR_Wheel_Angle': 15.396292686462402, + 'Location': array([ -6.12919712, -21.87455559, 0.17608207]), + 'Rotation': array([-0.07059 , 0.63350463, -0.01464844]), + 'Velocity': array([-0.39246961, -0.06186488, 0.00041373]), + 'brake_input': 0.0, + 'camera_location': array([-4.44863319, 11.53104401, 0.8142038 ]), + 'camera_rotation': array([-10.71231747, -16.13737106, 3.06318188]), + 'current_gear_input': False, + 'focus_actor_dist': 1113.1148681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 268.54107666, -1259.56005859, 16.286026 ]), + 'frame': 18007, + 'frame_number': 18007, + 'framesequence': 68965, + 'gaze_dir': array([ 0.95981598, -0.27587128, 0.04864502]), + 'gaze_origin': array([-3.15583658, 0.21563873, 0.03799057]), + 'gaze_valid': True, + 'gaze_vergence': 186.02044677734375, + 'handbrake_input': False, + 'left_eye_openness': 0.9147820472717285, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96412659, -0.26037598, 0.05148315]), + 'left_gaze_origin': array([-3.11045861, 3.4051559 , 0.04196778]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1461639404296875, + 'left_pupil_posn': array([-0.21619689, -0.09233165]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95550537, -0.29136658, 0.04580688]), + 'right_gaze_origin': array([-3.20121455, -2.97387862, 0.03401337]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9830474853515625, + 'right_pupil_posn': array([-0.23795485, -0.1522634 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.31123387813568115, + 'throttle_input': 0.24205386638641357, + 'timestamp': 585.3948571681976, + 'timestamp_carla': 585395, + 'timestamp_device': 28643, + 'timestamp_stream': 585.3948571681976, + 'transform': [array([-0.30009139, -9.34364605, 0.01195743]), + array([-0.04241547, -3.42913485, 0.01083374])]} +{'AngularVelocity': array([ 0.00632861, -0.00691885, -2.00255919]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.034849166870117, + 'FR_Wheel_Angle': 14.395234107971191, + 'Location': array([ -6.22283936, -21.88629913, 0.17620128]), + 'Rotation': array([-0.07378653, 0.1810222 , -0.01309204]), + 'Velocity': array([-0.4243558 , -0.06287297, 0.00091473]), + 'brake_input': 0.0, + 'camera_location': array([-4.46731472, 11.15850258, 0.93211746]), + 'camera_rotation': array([-10.03319931, -17.50298119, 3.03042865]), + 'current_gear_input': False, + 'focus_actor_dist': 1022.5619506835938, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 359.18966675, -1413.72753906, 16.24793243]), + 'frame': 18008, + 'frame_number': 18008, + 'framesequence': 68969, + 'gaze_dir': array([ 0.92539978, -0.37804413, 0.00497437]), + 'gaze_origin': array([-3.18436289e+00, 2.86188513e-01, 6.50024449e-04]), + 'gaze_valid': True, + 'gaze_vergence': 113.67186737060547, + 'handbrake_input': False, + 'left_eye_openness': 0.8573789000511169, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.93525696, -0.35391235, 0.00515747]), + 'left_gaze_origin': array([-3.14011693, 3.4700501 , 0.00357208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.19635009765625, + 'left_pupil_posn': array([-0.30239457, -0.1416626 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9155426 , -0.4021759 , 0.00479126]), + 'right_gaze_origin': array([-3.22860885e+00, -2.89767313e+00, -2.27203383e-03]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1344757080078125, + 'right_pupil_posn': array([-0.32525939, -0.20065928]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3124241232872009, + 'throttle_input': 0.26189059019088745, + 'timestamp': 585.4283468686044, + 'timestamp_carla': 585429, + 'timestamp_device': 28676, + 'timestamp_stream': 585.4283468686044, + 'transform': [array([-0.2019638 , -9.30328274, 0.01198601]), + array([-0.04205347, -3.80437469, 0.01068116])]} +{'AngularVelocity': array([-0.03968452, 0.12472633, -2.17198753]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.911630630493164, + 'FR_Wheel_Angle': 10.595516204833984, + 'Location': array([ -6.32097769, -21.89631271, 0.17637569]), + 'Rotation': array([-0.07934631, -0.23312379, -0.01251221]), + 'Velocity': array([-0.60321778, -0.06257029, 0.00062699]), + 'brake_input': 0.0, + 'camera_location': array([-4.46601772, 10.7846365 , 1.00207067]), + 'camera_rotation': array([ -9.46354103, -18.83884048, 2.72634172]), + 'current_gear_input': False, + 'focus_actor_dist': 869.377685546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 367.09887695, -1612.38452148, 16.30965424]), + 'frame': 18009, + 'frame_number': 18009, + 'framesequence': 68973, + 'gaze_dir': array([ 0.92487335, -0.37876892, -0.01431274]), + 'gaze_origin': array([-3.18637633, 0.29442063, -0.00755997]), + 'gaze_valid': True, + 'gaze_vergence': 87.07355499267578, + 'handbrake_input': False, + 'left_eye_openness': 0.866148054599762, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 9.35287476e-01, -3.53866577e-01, -6.10351562e-04]), + 'left_gaze_origin': array([-3.14186263, 3.4801147 , -0.00552521]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2199859619140625, + 'left_pupil_posn': array([-0.30995226, -0.16008341]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.91445923, -0.40367126, -0.02801514]), + 'right_gaze_origin': array([-3.2308898 , -2.8912735 , -0.00959473]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1729736328125, + 'right_pupil_posn': array([-0.32996106, -0.20811236]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.31302836537361145, + 'throttle_input': 0.2737926244735718, + 'timestamp': 585.4599839672446, + 'timestamp_carla': 585460, + 'timestamp_device': 28710, + 'timestamp_stream': 585.4599839672446, + 'transform': [array([-0.10758957, -9.26525593, 0.01207258]), + array([-0.04168464, -4.16432858, 0.01031494])]} +{'AngularVelocity': array([ 0.01859919, -0.07043666, -1.54247713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.14693021774292, + 'FR_Wheel_Angle': 7.322257995605469, + 'Location': array([ -6.44917059, -21.90487671, 0.17646149]), + 'Rotation': array([-0.07693525, -0.6278075 , -0.01473999]), + 'Velocity': array([-5.91454983e-01, -4.00996245e-02, 1.55014990e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.50395775, 10.37174606, 1.02313733]), + 'camera_rotation': array([ -9.20521641, -20.59491539, 2.1685164 ]), + 'current_gear_input': False, + 'focus_actor_dist': 800.5902099609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 339.44378662, -1675.59228516, 16.35916138]), + 'frame': 18010, + 'frame_number': 18010, + 'framesequence': 68977, + 'gaze_dir': array([ 0.93456268, -0.35556793, -0.00200653]), + 'gaze_origin': array([-3.17796874, 0.27088699, -0.00613327]), + 'gaze_valid': True, + 'gaze_vergence': 246.80987548828125, + 'handbrake_input': False, + 'left_eye_openness': 0.8846720457077026, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.93887329, -0.34423828, -0.00146484]), + 'left_gaze_origin': array([-3.13292551e+00, 3.46118164e+00, -2.33459490e-04]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1066131591796875, + 'left_pupil_posn': array([-0.28293931, -0.14438581]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.93025208, -0.36689758, -0.00254822]), + 'right_gaze_origin': array([-3.22301197, -2.91940784, -0.01203308]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2517852783203125, + 'right_pupil_posn': array([-0.30679071, -0.20840085]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3133396506309509, + 'throttle_input': 0.2856946587562561, + 'timestamp': 585.4936969652772, + 'timestamp_carla': 585494, + 'timestamp_device': 28743, + 'timestamp_stream': 585.4936969652772, + 'transform': [array([-5.25619509e-03, -9.22482681e+00, 1.21232793e-02]), + array([-0.04147291, -4.55363798, 0.00997925])]} +{'AngularVelocity': array([ 0.05183962, -0.38278338, -0.09266487]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.569672107696533, + 'FR_Wheel_Angle': 4.287515163421631, + 'Location': array([ -6.54919624, -21.90854454, 0.17640515]), + 'Rotation': array([-0.06113019, -0.83920288, -0.01763916]), + 'Velocity': array([-0.12955549, -0.00503629, -0.00182964]), + 'brake_input': 0.0, + 'camera_location': array([-4.52502537, 9.95575237, 1.02430856]), + 'camera_rotation': array([ -9.08167839, -22.36410713, 1.88238037]), + 'current_gear_input': False, + 'focus_actor_dist': 860.3051147460938, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 390.09155273, -1634.3515625 , 16.29456329]), + 'frame': 18011, + 'frame_number': 18011, + 'framesequence': 68981, + 'gaze_dir': array([ 0.94052887, -0.33951569, -0.00470734]), + 'gaze_origin': array([-3.17155790e+00, 2.54302233e-01, -3.08227551e-04]), + 'gaze_valid': True, + 'gaze_vergence': 281.8707580566406, + 'handbrake_input': False, + 'left_eye_openness': 0.9056966304779053, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94380188, -0.33049011, -0.00144958]), + 'left_gaze_origin': array([-3.1263597 , 3.44601607, 0.0045517 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0316009521484375, + 'left_pupil_posn': array([-0.26561552, -0.14107239]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.93725586, -0.34854126, -0.00796509]), + 'right_gaze_origin': array([-3.21675587, -2.93741179, -0.00516815]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0482330322265625, + 'right_pupil_posn': array([-0.2889992 , -0.20227575]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3138340711593628, + 'throttle_input': 0.29364460706710815, + 'timestamp': 585.5263529680669, + 'timestamp_carla': 585527, + 'timestamp_device': 28776, + 'timestamp_stream': 585.5263529680669, + 'transform': [array([ 0.0959523 , -9.18567562, 0.01219532]), + array([-0.04107676, -4.93768406, 0.00961304])]} +{'AngularVelocity': array([-1.87809039e-02, 8.42599869e-02, -4.56457274e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9233527183532715, + 'FR_Wheel_Angle': 1.5586397647857666, + 'Location': array([ -6.54920816, -21.90853882, 0.17642723]), + 'Rotation': array([-0.05694328, -0.83914185, -0.01553345]), + 'Velocity': array([6.28484777e-05, 1.30356741e-04, 8.07152072e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.53418159, 9.56356716, 0.99242896]), + 'camera_rotation': array([ -8.95096207, -23.96863365, 1.7537595 ]), + 'current_gear_input': False, + 'focus_actor_dist': 836.8032836914062, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 386.65545654, -1657.83422852, 16.30620575]), + 'frame': 18012, + 'frame_number': 18012, + 'framesequence': 68985, + 'gaze_dir': array([ 0.95055389, -0.31035614, -0.00209808]), + 'gaze_origin': array([-3.16614985e+00, 2.40380108e-01, 1.52130134e-03]), + 'gaze_valid': True, + 'gaze_vergence': 278.3055725097656, + 'handbrake_input': False, + 'left_eye_openness': 0.9113897681236267, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95327759, -0.30198669, -0.00643921]), + 'left_gaze_origin': array([-3.11994791, 3.43177366, 0.01016998]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0020904541015625, + 'left_pupil_posn': array([-0.2447477 , -0.13157153]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9478302 , -0.31872559, 0.00224304]), + 'right_gaze_origin': array([-3.21235204, -2.95101333, -0.00712738]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.987884521484375, + 'right_pupil_posn': array([-0.26949674, -0.20366168]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.31421858072280884, + 'throttle_input': 0.29761195182800293, + 'timestamp': 585.5601421669126, + 'timestamp_carla': 585561, + 'timestamp_device': 28810, + 'timestamp_stream': 585.5601421669126, + 'transform': [array([ 0.20290267, -9.1451683 , 0.01223682]), + array([-0.04059181, -5.34249735, 0.00933838])]} +{'AngularVelocity': array([-6.15382520e-03, 2.93475576e-02, -3.99500277e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18169212341308594, + 'FR_Wheel_Angle': 0.18201231956481934, + 'Location': array([ -6.54927826, -21.90855598, 0.17643714]), + 'Rotation': array([-0.06802185, -0.83914179, -0.013031 ]), + 'Velocity': array([ 2.21081536e-05, 4.39757860e-05, -1.14047597e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.54197216, 9.14512253, 0.97761434]), + 'camera_rotation': array([ -8.76547527, -25.57590675, 1.77689171]), + 'current_gear_input': False, + 'focus_actor_dist': 845.588134765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 396.81774902, -1648.44616699, 16.29290009]), + 'frame': 18013, + 'frame_number': 18013, + 'framesequence': 68989, + 'gaze_dir': array([ 0.95654297, -0.29134369, -0.00183868]), + 'gaze_origin': array([-3.16253448e+00, 2.25306720e-01, -2.69317650e-04]), + 'gaze_valid': True, + 'gaze_vergence': 272.0003967285156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 9.59747314e-01, -2.80838013e-01, -3.05175781e-05]), + 'left_gaze_origin': array([-3.11684132, 3.41809082, 0.00583344]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0813446044921875, + 'left_pupil_posn': array([-0.22928697, -0.13548839]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95333862, -0.30184937, -0.00364685]), + 'right_gaze_origin': array([-3.20822787, -2.96747756, -0.00637207]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1367645263671875, + 'right_pupil_posn': array([-0.25045896, -0.19967747]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3149510324001312, + 'throttle_input': 0.29761195182800293, + 'timestamp': 585.5935568660498, + 'timestamp_carla': 585594, + 'timestamp_device': 28843, + 'timestamp_stream': 585.5935568660498, + 'transform': [array([ 0.31117019, -9.10510254, 0.01228136]), + array([-0.03991563, -5.75124502, 0.00909424])]} +{'AngularVelocity': array([-1.70686597e-03, 7.28149898e-03, -1.86450834e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.28759679198265076, + 'FR_Wheel_Angle': 0.32172608375549316, + 'Location': array([ -6.54930401, -21.90856171, 0.17650475]), + 'Rotation': array([-0.07158721, -0.83914179, -0.01217651]), + 'Velocity': array([ 7.23741914e-06, -3.34100321e-07, -2.72090547e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.5658474 , 8.70299911, 0.98938233]), + 'camera_rotation': array([ -8.59098434, -27.07868195, 2.05283809]), + 'current_gear_input': False, + 'focus_actor_dist': 857.2577514648438, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 415.85876465, -1644.07727051, 16.27255249]), + 'frame': 18014, + 'frame_number': 18014, + 'framesequence': 68992, + 'gaze_dir': array([ 0.96227264, -0.27143097, -0.00670624]), + 'gaze_origin': array([-3.15892434e+00, 2.12479413e-01, -1.85928342e-03]), + 'gaze_valid': True, + 'gaze_vergence': 175.30960083007812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96673584, -0.25572205, -0.00215149]), + 'left_gaze_origin': array([-3.11400175e+00, 3.40697026e+00, 2.36358657e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1112823486328125, + 'left_pupil_posn': array([-0.21636009, -0.13959825]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95780945, -0.28713989, -0.01126099]), + 'right_gaze_origin': array([-3.20384693, -2.98201156, -0.00608215]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.061187744140625, + 'right_pupil_posn': array([-0.23147273, -0.19891524]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3157750070095062, + 'throttle_input': 0.29761195182800293, + 'timestamp': 585.6203489676118, + 'timestamp_carla': 585621, + 'timestamp_device': 28868, + 'timestamp_stream': 585.6203489676118, + 'transform': [array([ 0.39823258, -9.07270241, 0.01226477]), + array([-0.03936921, -6.07803679, 0.00906372])]} +{'AngularVelocity': array([-5.15357300e-04, 8.74525631e-06, -2.58592208e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 1.7521064281463623, + 'Location': array([ -6.54928207, -21.90856171, 0.17651145]), + 'Rotation': array([-0.07211313, -0.83914185, -0.01202393]), + 'Velocity': array([ 1.59741892e-03, -2.47253447e-05, -2.12543790e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.57364655, 8.2615509 , 0.99147928]), + 'camera_rotation': array([ -8.67807579, -28.50253296, 2.03498793]), + 'current_gear_input': False, + 'focus_actor_dist': 844.4444580078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 415.2253418 , -1654.94873047, 16.27695465]), + 'frame': 18015, + 'frame_number': 18015, + 'framesequence': 68996, + 'gaze_dir': array([ 0.97001648, -0.24241638, 0.00437927]), + 'gaze_origin': array([-3.15507364e+00, 1.97180942e-01, -1.07421889e-03]), + 'gaze_valid': True, + 'gaze_vergence': 156.6688232421875, + 'handbrake_input': False, + 'left_eye_openness': 0.9074200987815857, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97322083, -0.22944641, 0.01371765]), + 'left_gaze_origin': array([-3.10944700e+00, 3.39247632e+00, 2.76947021e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0937042236328125, + 'left_pupil_posn': array([-0.19501311, -0.13550258]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96681213, -0.25538635, -0.00495911]), + 'right_gaze_origin': array([-3.20070052, -2.99811411, -0.00491791]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.93878173828125, + 'right_pupil_posn': array([-0.2111305 , -0.19128954]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3166356384754181, + 'throttle_input': 0.29761195182800293, + 'timestamp': 585.6546179652214, + 'timestamp_carla': 585655, + 'timestamp_device': 28901, + 'timestamp_stream': 585.6546179652214, + 'transform': [array([ 0.51412231, -9.03176498, 0.01225801]), + array([-0.03850861, -6.51366568, 0.00906372])]} +{'AngularVelocity': array([-6.85529812e-05, 9.01499356e-04, -2.12429859e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.5913825035095215, + 'FR_Wheel_Angle': 6.63319730758667, + 'Location': array([ -6.54876518, -21.90856552, 0.17651783]), + 'Rotation': array([-0.07232487, -0.83880609, -0.01199341]), + 'Velocity': array([ 3.60696572e-06, -5.63840160e-07, 3.70349910e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.61588383, 7.85815144, 0.9728545 ]), + 'camera_rotation': array([ -8.9328146 , -29.96483803, 1.6680876 ]), + 'current_gear_input': False, + 'focus_actor_dist': 890.4570922851562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 451.59619141, -1619.38232422, 16.2285614 ]), + 'frame': 18016, + 'frame_number': 18016, + 'framesequence': 69000, + 'gaze_dir': array([ 0.97409058, -0.22534943, 0.01303101]), + 'gaze_origin': array([-3.15256834e+00, 1.79579169e-01, -6.31713890e-04]), + 'gaze_valid': True, + 'gaze_vergence': 232.83938598632812, + 'handbrake_input': False, + 'left_eye_openness': 0.9198763370513916, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97711182, -0.21228027, 0.01298523]), + 'left_gaze_origin': array([-3.1082232 , 3.37554955, 0.00392303]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.96746826171875, + 'left_pupil_posn': array([-0.1773203 , -0.12793803]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97106934, -0.23841858, 0.01307678]), + 'right_gaze_origin': array([-3.19691348, -3.01639128, -0.00518646]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9435577392578125, + 'right_pupil_posn': array([-0.1924687 , -0.19084263]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3185217082500458, + 'throttle_input': 0.29761195182800293, + 'timestamp': 585.6867694668472, + 'timestamp_carla': 585687, + 'timestamp_device': 28935, + 'timestamp_stream': 585.6867694668472, + 'transform': [array([ 0.62589586, -8.99339104, 0.01228786]), + array([-0.03741577, -6.93280172, 0.00900269])]} +{'AngularVelocity': array([ 0.03267645, -0.00807202, 0.18876278]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.424461364746094, + 'FR_Wheel_Angle': 10.823187828063965, + 'Location': array([ -6.54832792, -21.908535 , 0.17652164]), + 'Rotation': array([-0.07211313, -0.83700562, -0.01217651]), + 'Velocity': array([0.00860827, 0.00415633, 0.00027265]), + 'brake_input': 0.0, + 'camera_location': array([-4.68424463, 7.53446817, 0.89905304]), + 'camera_rotation': array([ -9.23549461, -31.24596977, 1.19149375]), + 'current_gear_input': False, + 'focus_actor_dist': 901.5261840820312, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 470.95904541, -1616.27160645, 16.20828247]), + 'frame': 18017, + 'frame_number': 18017, + 'framesequence': 69004, + 'gaze_dir': array([ 0.97473907, -0.22293854, 0.0093689 ]), + 'gaze_origin': array([-3.15008879, 0.17273484, 0.01176148]), + 'gaze_valid': True, + 'gaze_vergence': 352.7650451660156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97665405, -0.21459961, 0.00776672]), + 'left_gaze_origin': array([-3.10656452, 3.36927962, 0.01860657]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0193023681640625, + 'left_pupil_posn': array([-0.17038566, -0.11823511]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9728241 , -0.23127747, 0.01097107]), + 'right_gaze_origin': array([-3.19361281, -3.02380991, 0.00491638]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9757843017578125, + 'right_pupil_posn': array([-0.18797874, -0.18532944]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3207922875881195, + 'throttle_input': 0.269825279712677, + 'timestamp': 585.7203153669834, + 'timestamp_carla': 585721, + 'timestamp_device': 28968, + 'timestamp_stream': 585.7203153669834, + 'transform': [array([ 0.74579453, -8.95356941, 0.01226033]), + array([-0.03622049, -7.38145494, 0.00912476])]} +{'AngularVelocity': array([ 0.03805705, -0.06520411, 0.81672412]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.892480850219727, + 'FR_Wheel_Angle': 13.75454044342041, + 'Location': array([ -6.53610706, -21.90774345, 0.17646766]), + 'Rotation': array([-0.0655903 , -0.78274542, -0.01470947]), + 'Velocity': array([1.80952758e-01, 1.97818633e-02, 1.71580308e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.74067354, 7.2603488 , 0.82548076]), + 'camera_rotation': array([ -9.44371986, -32.32932663, 0.67279112]), + 'current_gear_input': False, + 'focus_actor_dist': 833.4664306640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 435.24316406, -1672.7208252 , 16.26338959]), + 'frame': 18018, + 'frame_number': 18018, + 'framesequence': 69008, + 'gaze_dir': array([ 0.96588898, -0.25566101, 0.03878021]), + 'gaze_origin': array([-3.15319443, 0.19041139, 0.03044815]), + 'gaze_valid': True, + 'gaze_vergence': 197.1696319580078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96833801, -0.24526978, 0.04618835]), + 'left_gaze_origin': array([-3.10724187, 3.37844706, 0.03782654]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0915679931640625, + 'left_pupil_posn': array([-0.18884796, -0.09895277]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96343994, -0.26605225, 0.03137207]), + 'right_gaze_origin': array([-3.19914699, -2.9976244 , 0.02306976]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.965850830078125, + 'right_pupil_posn': array([-0.21662217, -0.1607213 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3241981565952301, + 'throttle_input': 0.24205386638641357, + 'timestamp': 585.7540474683046, + 'timestamp_carla': 585755, + 'timestamp_device': 29001, + 'timestamp_stream': 585.7540474683046, + 'transform': [array([ 0.86988354, -8.91398525, 0.01215662]), + array([-0.0349774 , -7.84492779, 0.00958252])]} +{'AngularVelocity': array([ 0.05567746, -0.0459809 , 3.30339384]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.2254056930542, + 'FR_Wheel_Angle': 15.249229431152344, + 'Location': array([ -6.44395018, -21.89856339, 0.17629825]), + 'Rotation': array([-0.05358966, -0.39099121, -0.0218811 ]), + 'Velocity': array([ 0.60821903, 0.08422702, -0.00071716]), + 'brake_input': 0.0, + 'camera_location': array([-4.79165649, 7.05396938, 0.7888689 ]), + 'camera_rotation': array([ -9.46706486, -33.22219467, 0.52976495]), + 'current_gear_input': False, + 'focus_actor_dist': 1014.0196533203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 615.46789551, -1600.41955566, 16.05986023]), + 'frame': 18019, + 'frame_number': 18019, + 'framesequence': 69012, + 'gaze_dir': array([ 0.97166443, -0.23054504, 0.04747009]), + 'gaze_origin': array([-3.1508975 , 0.17811432, 0.03108979]), + 'gaze_valid': True, + 'gaze_vergence': 139.44931030273438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97583008, -0.21144104, 0.05497742]), + 'left_gaze_origin': array([-3.10604715, 3.36851358, 0.03809052]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.040252685546875, + 'left_pupil_posn': array([-0.17618066, -0.09531784]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96749878, -0.24964905, 0.03996277]), + 'right_gaze_origin': array([-3.19574738, -3.01228499, 0.02408905]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9556121826171875, + 'right_pupil_posn': array([-0.19463134, -0.15566289]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.32743918895721436, + 'throttle_input': 0.21824978291988373, + 'timestamp': 585.7870397679508, + 'timestamp_carla': 585788, + 'timestamp_device': 29034, + 'timestamp_stream': 585.7870397679508, + 'transform': [array([ 0.99466383, -8.8758688 , 0.01200361]), + array([-0.03372064, -8.31014824, 0.01028443])]} +{'AngularVelocity': array([0.01232327, 0.01690076, 6.09681606]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.469785690307617, + 'FR_Wheel_Angle': 15.417906761169434, + 'Location': array([ -6.24280882, -21.87535286, 0.17605063]), + 'Rotation': array([-0.04751079, 0.6227321 , -0.02697754]), + 'Velocity': array([ 1.0848223 , 0.16754697, -0.00153568]), + 'brake_input': 0.0, + 'camera_location': array([-4.85309696, 6.91771793, 0.74817032]), + 'camera_rotation': array([ -9.57694244, -33.83699799, 0.47892243]), + 'current_gear_input': False, + 'focus_actor_dist': 1072.207275390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 663.81640625, -1558.08398438, 15.99719238]), + 'frame': 18020, + 'frame_number': 18020, + 'framesequence': 69016, + 'gaze_dir': array([ 0.97433472, -0.21855927, 0.05146027]), + 'gaze_origin': array([-3.14891529, 0.1688759 , 0.03613663]), + 'gaze_valid': True, + 'gaze_vergence': 201.6315155029297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97747803, -0.20388794, 0.05426025]), + 'left_gaze_origin': array([-3.10464025, 3.36017013, 0.04300385]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.071502685546875, + 'left_pupil_posn': array([-0.16473359, -0.08823466]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97119141, -0.23323059, 0.04866028]), + 'right_gaze_origin': array([-3.19319034, -3.02241826, 0.02926941]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.991241455078125, + 'right_pupil_posn': array([-0.18485188, -0.15200317]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.33163243532180786, + 'throttle_input': 0.1904631108045578, + 'timestamp': 585.8203122653067, + 'timestamp_carla': 585821, + 'timestamp_device': 29068, + 'timestamp_stream': 585.8203122653067, + 'transform': [array([ 1.12389433, -8.838274 , 0.01176252]), + array([-0.03249804, -8.79123306, 0.01135254])]} +{'AngularVelocity': array([-0.03594312, 0.0741615 , 6.92508268]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.905139923095703, + 'FR_Wheel_Angle': 14.379999160766602, + 'Location': array([ -5.9825778 , -21.840065 , 0.17581581]), + 'Rotation': array([-0.0478523 , 1.88506746, -0.02944946]), + 'Velocity': array([ 1.44551897e+00, 2.49787375e-01, -1.19790074e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.89391947, 6.838027 , 0.73154074]), + 'camera_rotation': array([ -9.59472179, -34.26275635, 0.28869522]), + 'current_gear_input': False, + 'focus_actor_dist': 1085.3040771484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 680.70526123, -1549.9230957 , 15.9776535 ]), + 'frame': 18021, + 'frame_number': 18021, + 'framesequence': 69020, + 'gaze_dir': array([ 0.97483063, -0.21730042, 0.04732513]), + 'gaze_origin': array([-3.1488266 , 0.16274033, 0.03966446]), + 'gaze_valid': True, + 'gaze_vergence': 198.16395568847656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97787476, -0.20280457, 0.05119324]), + 'left_gaze_origin': array([-3.1043961 , 3.35594964, 0.04668427]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0908966064453125, + 'left_pupil_posn': array([-0.16124189, -0.08760679]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9717865 , -0.23179626, 0.04345703]), + 'right_gaze_origin': array([-3.19325733, -3.03046894, 0.03264466]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0054779052734375, + 'right_pupil_posn': array([-0.17888403, -0.15084183]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.33650320768356323, + 'throttle_input': 0.17856107652187347, + 'timestamp': 585.8533308655024, + 'timestamp_carla': 585854, + 'timestamp_device': 29101, + 'timestamp_stream': 585.8533308655024, + 'transform': [array([ 1.25549471, -8.80205345, 0.01145275]), + array([-0.03131641, -9.28055096, 0.01272583])]} +{'AngularVelocity': array([-0.04845924, 0.09295377, 6.50418758]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.214024543762207, + 'FR_Wheel_Angle': 12.360294342041016, + 'Location': array([ -5.61893225, -21.78500938, 0.17551014]), + 'Rotation': array([-0.06024227, 3.49953747, -0.02368164]), + 'Velocity': array([ 1.57144415e+00, 2.86541700e-01, -1.29934307e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.91811323, 6.77536583, 0.74938607]), + 'camera_rotation': array([ -9.46479034, -34.45596695, 0.04315449]), + 'current_gear_input': False, + 'focus_actor_dist': 1036.0645751953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 651.13848877, -1584.74609375, 16.01907349]), + 'frame': 18022, + 'frame_number': 18022, + 'framesequence': 69024, + 'gaze_dir': array([ 0.97615051, -0.2113266 , 0.04588318]), + 'gaze_origin': array([-3.1471734 , 0.16040574, 0.03866348]), + 'gaze_valid': True, + 'gaze_vergence': 169.53639221191406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9798584 , -0.19361877, 0.04856873]), + 'left_gaze_origin': array([-3.1045289 , 3.35359979, 0.04634705]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0941314697265625, + 'left_pupil_posn': array([-0.15864456, -0.08792675]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97244263, -0.22903442, 0.04319763]), + 'right_gaze_origin': array([-3.18981791, -3.03278828, 0.03097992]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0011444091796875, + 'right_pupil_posn': array([-0.17410576, -0.15208614]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3410809636116028, + 'throttle_input': 0.1745937317609787, + 'timestamp': 585.8875962682068, + 'timestamp_carla': 585888, + 'timestamp_device': 29134, + 'timestamp_stream': 585.8875962682068, + 'transform': [array([ 1.39526725, -8.7658596 , 0.01102959]), + array([-0.03030555, -9.79970741, 0.01452637])]} +{'AngularVelocity': array([ 0.02250851, -0.01976623, 5.94346142]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.38071060180664, + 'FR_Wheel_Angle': 11.371711730957031, + 'Location': array([ -5.19636631, -21.71435738, 0.1751208 ]), + 'Rotation': array([-0.07107495, 5.16283274, -0.02090454]), + 'Velocity': array([ 1.57724726e+00, 3.15318495e-01, -4.41913609e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.9193511 , 6.77054071, 0.8036589 ]), + 'camera_rotation': array([ -9.33189583, -34.47108078, -0.22837268]), + 'current_gear_input': False, + 'focus_actor_dist': 1032.83984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 654.18725586, -1585.36206055, 16.01630402]), + 'frame': 18023, + 'frame_number': 18023, + 'framesequence': 69028, + 'gaze_dir': array([ 0.97688293, -0.20815277, 0.0459137 ]), + 'gaze_origin': array([-3.1477294 , 0.15895769, 0.03827667]), + 'gaze_valid': True, + 'gaze_vergence': 194.697509765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9797821 , -0.19360352, 0.05030823]), + 'left_gaze_origin': array([-3.10494089, 3.35189366, 0.04505158]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0944366455078125, + 'left_pupil_posn': array([-0.15525508, -0.08938289]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97398376, -0.22270203, 0.04151917]), + 'right_gaze_origin': array([-3.19051814, -3.03397846, 0.03150177]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0300750732421875, + 'right_pupil_posn': array([-0.17324281, -0.15132761]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3455488979816437, + 'throttle_input': 0.1745937317609787, + 'timestamp': 585.9203410670161, + 'timestamp_carla': 585921, + 'timestamp_device': 29168, + 'timestamp_stream': 585.9203410670161, + 'transform': [array([ 1.53173065, -8.73265839, 0.01061291]), + array([ -0.02938347, -10.3060112 , 0.01635742])]} +{'AngularVelocity': array([-4.03846148e-03, 1.30361049e-02, 5.00044012e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.29781436920166, + 'FR_Wheel_Angle': 10.043671607971191, + 'Location': array([ -4.83827257, -21.64814186, 0.17479667]), + 'Rotation': array([-0.0740051 , 6.42301178, -0.01934815]), + 'Velocity': array([ 1.49795651, 0.31670102, -0.00165951]), + 'brake_input': 0.0, + 'camera_location': array([-4.93804216, 6.78671455, 0.80759406]), + 'camera_rotation': array([ -9.26292419, -34.40917206, -0.72631305]), + 'current_gear_input': False, + 'focus_actor_dist': 1044.064697265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 669.56048584, -1577.83837891, 15.99845123]), + 'frame': 18024, + 'frame_number': 18024, + 'framesequence': 69032, + 'gaze_dir': array([ 0.97729492, -0.20637512, 0.04494476]), + 'gaze_origin': array([-3.14818668, 0.15789108, 0.03831482]), + 'gaze_valid': True, + 'gaze_vergence': 186.47640991210938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98039246, -0.19082642, 0.04890442]), + 'left_gaze_origin': array([-3.10531926, 3.35113716, 0.04491577]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1065521240234375, + 'left_pupil_posn': array([-0.15446311, -0.08973646]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97419739, -0.22192383, 0.04098511]), + 'right_gaze_origin': array([-3.19105387, -3.03535485, 0.03171387]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0287628173828125, + 'right_pupil_posn': array([-0.17130953, -0.1517632 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3498336970806122, + 'throttle_input': 0.1745937317609787, + 'timestamp': 585.9545817673206, + 'timestamp_carla': 585955, + 'timestamp_device': 29201, + 'timestamp_stream': 585.9545817673206, + 'transform': [array([ 1.67717528, -8.69955826, 0.01011402]), + array([ -0.02862532, -10.8451395 , 0.01846314])]} +{'AngularVelocity': array([-0.0229139 , 0.00690896, 3.59158731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.3328375816345215, + 'FR_Wheel_Angle': 7.219973087310791, + 'Location': array([ -4.50451469, -21.5832634 , 0.17447822]), + 'Rotation': array([-0.07760461, 7.43285322, -0.01553345]), + 'Velocity': array([ 1.37542987e+00, 2.86549568e-01, -9.75036586e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.9576683 , 6.83835411, 0.79068613]), + 'camera_rotation': array([ -9.27030087, -34.21144485, -0.9785893 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1029.326171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 663.15631104, -1585.17248535, 16.00731659]), + 'frame': 18025, + 'frame_number': 18025, + 'framesequence': 69036, + 'gaze_dir': array([ 0.97754669, -0.20517731, 0.04557037]), + 'gaze_origin': array([-3.14619398, 0.1560318 , 0.0397583 ]), + 'gaze_valid': True, + 'gaze_vergence': 203.79281616210938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98016357, -0.19163513, 0.05032349]), + 'left_gaze_origin': array([-3.10517764, 3.34990239, 0.04515991]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.11871337890625, + 'left_pupil_posn': array([-0.15247178, -0.08956742]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97492981, -0.21871948, 0.04081726]), + 'right_gaze_origin': array([-3.18721008, -3.03783894, 0.03435669]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0006256103515625, + 'right_pupil_posn': array([-0.16983438, -0.14880824]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3533494472503662, + 'throttle_input': 0.1745937317609787, + 'timestamp': 585.9882593676448, + 'timestamp_carla': 585989, + 'timestamp_device': 29234, + 'timestamp_stream': 585.9882593676448, + 'transform': [array([ 1.82266235, -8.66862774, 0.00962555]), + array([ -0.0280106 , -11.38387585, 0.02053833])]} +{'AngularVelocity': array([-0.01742022, -0.00114512, 0.66623783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.436075210571289, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -4.19669342, -21.52987671, 0.17416634]), + 'Rotation': array([-7.86154717e-02, 7.91099358e+00, -6.68334914e-03]), + 'Velocity': array([ 1.26259995, 0.19456384, -0.00136642]), + 'brake_input': 0.0, + 'camera_location': array([-4.9830575 , 6.89600563, 0.78578138]), + 'camera_rotation': array([ -9.33307076, -33.86777878, -0.97663534]), + 'current_gear_input': False, + 'focus_actor_dist': 1025.31201171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 665.0645752 , -1584.99780273, 16.00540161]), + 'frame': 18026, + 'frame_number': 18026, + 'framesequence': 69040, + 'gaze_dir': array([ 0.97550201, -0.21557617, 0.0404892 ]), + 'gaze_origin': array([-3.14725518, 0.16513063, 0.043499 ]), + 'gaze_valid': True, + 'gaze_vergence': 191.7388153076172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97883606, -0.19999695, 0.04302979]), + 'left_gaze_origin': array([-3.10584259, 3.35909915, 0.0512909 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1414642333984375, + 'left_pupil_posn': array([-0.16314638, -0.0866698 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97216797, -0.2311554 , 0.03794861]), + 'right_gaze_origin': array([-3.18866754, -3.02883768, 0.03570709]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0239715576171875, + 'right_pupil_posn': array([-0.17896849, -0.15072322]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.35611438751220703, + 'throttle_input': 0.1745937317609787, + 'timestamp': 586.0211176685989, + 'timestamp_carla': 586022, + 'timestamp_device': 29268, + 'timestamp_stream': 586.0211176685989, + 'transform': [array([ 1.96670401, -8.63997078, 0.00916744]), + array([ -0.02752566, -11.91666698, 0.02249145])]} +{'AngularVelocity': array([ 0.01620349, 0.00120534, -1.19884181]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.421020746231079, + 'FR_Wheel_Angle': -3.936674118041992, + 'Location': array([ -3.91450286, -21.49371719, 0.17387713]), + 'Rotation': array([-7.86154717e-02, 7.79070187e+00, -5.55419922e-03]), + 'Velocity': array([ 1.1528157 , 0.1182449 , -0.00139362]), + 'brake_input': 0.0, + 'camera_location': array([-4.97682476, 6.95433044, 0.8114779 ]), + 'camera_rotation': array([ -9.27625656, -33.60770035, -1.00283301]), + 'current_gear_input': False, + 'focus_actor_dist': 975.2786865234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 632.76519775, -1617.51611328, 16.04871368]), + 'frame': 18027, + 'frame_number': 18027, + 'framesequence': 69043, + 'gaze_dir': array([ 0.96066284, -0.27037811, 0.06005096]), + 'gaze_origin': array([-3.15730619, 0.20367433, 0.05005265]), + 'gaze_valid': True, + 'gaze_vergence': 151.25341796875, + 'handbrake_input': False, + 'left_eye_openness': 0.9215304851531982, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9657135 , -0.25149536, 0.06425476]), + 'left_gaze_origin': array([-3.11482096, 3.39334416, 0.05858612]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1639404296875, + 'left_pupil_posn': array([-0.20738113, -0.07833719]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95561218, -0.28926086, 0.05584717]), + 'right_gaze_origin': array([-3.19979119, -2.98599553, 0.04151917]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9369354248046875, + 'right_pupil_posn': array([-0.2266506 , -0.14183152]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.35908079147338867, + 'throttle_input': 0.16665904223918915, + 'timestamp': 586.0438564680517, + 'timestamp_carla': 586044, + 'timestamp_device': 29293, + 'timestamp_stream': 586.0438564680517, + 'transform': [array([ 2.06847525, -8.62130451, 0.00888559]), + array([ -0.02712268, -12.29354286, 0.02374268])]} +{'AngularVelocity': array([ 1.34194177e-02, 6.54935284e-05, -2.52867699e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.5225114822387695, + 'FR_Wheel_Angle': -7.351992130279541, + 'Location': array([ -3.65654039, -21.47112083, 0.17363377]), + 'Rotation': array([-7.82739669e-02, 7.30941010e+00, -6.77490234e-03]), + 'Velocity': array([ 1.04898155e+00, 5.75460531e-02, -3.64251115e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.97751331, 6.96388245, 0.84662986]), + 'camera_rotation': array([ -9.21733952, -33.39153671, -0.83947712]), + 'current_gear_input': False, + 'focus_actor_dist': 1186.5655517578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 851.98498535, -1560.5144043 , 15.81196594]), + 'frame': 18028, + 'frame_number': 18028, + 'framesequence': 69046, + 'gaze_dir': array([ 0.95746613, -0.28476715, 0.04473114]), + 'gaze_origin': array([-3.15836668, 0.21265717, 0.04889603]), + 'gaze_valid': True, + 'gaze_vergence': 191.98312377929688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95954895, -0.27648926, 0.05281067]), + 'left_gaze_origin': array([-3.11425638, 3.3997345 , 0.05512696]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.050933837890625, + 'left_pupil_posn': array([-0.21313405, -0.0872215 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9553833 , -0.29304504, 0.03665161]), + 'right_gaze_origin': array([-3.20247674, -2.97442031, 0.0426651 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0238189697265625, + 'right_pupil_posn': array([-0.24347824, -0.14603817]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3614062964916229, + 'throttle_input': 0.1587243527173996, + 'timestamp': 586.0667187683284, + 'timestamp_carla': 586067, + 'timestamp_device': 29318, + 'timestamp_stream': 586.0667187683284, + 'transform': [array([ 2.17028141, -8.60273933, 0.00861992]), + array([ -0.02664457, -12.66864014, 0.02490234])]} +{'AngularVelocity': array([ 9.74325556e-03, -9.61693411e-04, -3.04338574e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.381996154785156, + 'FR_Wheel_Angle': -9.807539939880371, + 'Location': array([ -3.45904064, -21.46039009, 0.17342369]), + 'Rotation': array([-0.07791879, 6.74939823, -0.00836182]), + 'Velocity': array([ 9.67170000e-01, 2.17812657e-02, -8.90507654e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.97420263, 6.98447895, 0.87075019]), + 'camera_rotation': array([ -9.15827942, -33.17290115, -0.6390782 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1049.6092529296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 741.75427246, -1638.56347656, 15.94831085]), + 'frame': 18029, + 'frame_number': 18029, + 'framesequence': 69048, + 'gaze_dir': array([ 0.9562149 , -0.28911591, 0.04423523]), + 'gaze_origin': array([-3.15944147, 0.21603319, 0.04886399]), + 'gaze_valid': True, + 'gaze_vergence': 300.07415771484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95831299, -0.2815094 , 0.04858398]), + 'left_gaze_origin': array([-3.11610126, 3.40368962, 0.05406494]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1160125732421875, + 'left_pupil_posn': array([-0.21718568, -0.08730841]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95411682, -0.29672241, 0.03988647]), + 'right_gaze_origin': array([-3.20278192, -2.97162318, 0.04366303]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0563201904296875, + 'right_pupil_posn': array([-0.24719018, -0.14696467]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3641529679298401, + 'throttle_input': 0.13492026925086975, + 'timestamp': 586.0880529657006, + 'timestamp_carla': 586089, + 'timestamp_device': 29334, + 'timestamp_stream': 586.0880529657006, + 'transform': [array([ 2.26772261e+00, -8.58665752e+00, 8.38094670e-03]), + array([ -0.02618694, -13.02895546, 0.02597046])]} +{'AngularVelocity': array([ 7.11118057e-03, -1.39313971e-03, -3.54053497e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.499845504760742, + 'FR_Wheel_Angle': -12.269665718078613, + 'Location': array([ -3.24453449, -21.45576286, 0.17319188]), + 'Rotation': array([-0.07748166, 5.95546865, -0.00878906]), + 'Velocity': array([ 0.87725651, -0.0178093 , -0.00098662]), + 'brake_input': 0.0, + 'camera_location': array([-4.98489523, 7.01122856, 0.88500899]), + 'camera_rotation': array([ -9.13139534, -33.05355072, -0.66745293]), + 'current_gear_input': False, + 'focus_actor_dist': 1065.15185546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 760.98779297, -1633.53540039, 15.92752838]), + 'frame': 18030, + 'frame_number': 18030, + 'framesequence': 69051, + 'gaze_dir': array([ 0.9552002 , -0.29205322, 0.04656982]), + 'gaze_origin': array([-3.15987325, 0.2186432 , 0.05056458]), + 'gaze_valid': True, + 'gaze_vergence': 262.8469543457031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95753479, -0.28359985, 0.05168152]), + 'left_gaze_origin': array([-3.11670399, 3.40718842, 0.05670624]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.109619140625, + 'left_pupil_posn': array([-0.22092104, -0.08520126]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9528656 , -0.30050659, 0.04145813]), + 'right_gaze_origin': array([-3.20304251, -2.96990228, 0.04442291]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0555267333984375, + 'right_pupil_posn': array([-0.24907106, -0.14550984]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3674672842025757, + 'throttle_input': 0.1111009418964386, + 'timestamp': 586.1109478659928, + 'timestamp_carla': 586111, + 'timestamp_device': 29359, + 'timestamp_stream': 586.1109478659928, + 'transform': [array([ 2.37191629e+00, -8.56975460e+00, 8.09135381e-03]), + array([ -0.02568834, -13.4126215 , 0.02719116])]} +{'AngularVelocity': array([ 4.71596420e-03, -1.45954185e-03, -3.95671034e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.636964797973633, + 'FR_Wheel_Angle': -14.731013298034668, + 'Location': array([ -3.05106187, -21.45884323, 0.17299667]), + 'Rotation': array([-0.07705819, 5.0582056 , -0.00900268]), + 'Velocity': array([ 0.79450554, -0.05098824, -0.00088496]), + 'brake_input': 0.0, + 'camera_location': array([-5.00646114, 7.0179081 , 0.905747 ]), + 'camera_rotation': array([ -9.04853821, -33.02922058, -0.70918554]), + 'current_gear_input': False, + 'focus_actor_dist': 1092.0986328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 790.49224854, -1624.03112793, 15.89505005]), + 'frame': 18031, + 'frame_number': 18031, + 'framesequence': 69054, + 'gaze_dir': array([ 0.95565796, -0.29099274, 0.04413605]), + 'gaze_origin': array([-3.15981317, 0.21918106, 0.05053788]), + 'gaze_valid': True, + 'gaze_vergence': 339.86163330078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95785522, -0.2833252 , 0.04707336]), + 'left_gaze_origin': array([-3.11671782, 3.4078598 , 0.05662842]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.102325439453125, + 'left_pupil_posn': array([-0.2207225 , -0.08529735]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95346069, -0.29866028, 0.04119873]), + 'right_gaze_origin': array([-3.20290852, -2.96949792, 0.04444733]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0335845947265625, + 'right_pupil_posn': array([-0.24928111, -0.14704239]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3715689778327942, + 'throttle_input': 0.0634927898645401, + 'timestamp': 586.1329193674028, + 'timestamp_carla': 586133, + 'timestamp_device': 29384, + 'timestamp_stream': 586.1329193674028, + 'transform': [array([ 2.47450376e+00, -8.55507469e+00, 7.78463343e-03]), + array([ -0.02529902, -13.79202843, 0.02850341])]} +{'AngularVelocity': array([ 7.25789275e-03, -1.52688497e-03, -4.18859720e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.246482849121094, + 'FR_Wheel_Angle': -16.514514923095703, + 'Location': array([ -2.87550998, -21.4685173 , 0.17281948]), + 'Rotation': array([-0.07662789, 4.0794611 , -0.00942993]), + 'Velocity': array([ 0.71833724, -0.07670201, -0.00087493]), + 'brake_input': 0.0, + 'camera_location': array([-5.04195166, 6.99960184, 0.92779666]), + 'camera_rotation': array([ -8.86890411, -33.01767349, -0.5569436 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1079.308349609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 783.52008057, -1630.40197754, 15.9041748 ]), + 'frame': 18032, + 'frame_number': 18032, + 'framesequence': 69056, + 'gaze_dir': array([ 0.95592499, -0.29077148, 0.03955078]), + 'gaze_origin': array([-3.15994358, 0.21910021, 0.05002594]), + 'gaze_valid': True, + 'gaze_vergence': 259.5045166015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95762634, -0.28437805, 0.04548645]), + 'left_gaze_origin': array([-3.11708689, 3.40810275, 0.05577698]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0970001220703125, + 'left_pupil_posn': array([-0.22035325, -0.08853793]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95422363, -0.29716492, 0.03361511]), + 'right_gaze_origin': array([-3.20280004, -2.96990228, 0.0442749 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0394287109375, + 'right_pupil_posn': array([-0.24937224, -0.14772987]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.3763664662837982, + 'throttle_input': 0.0317387655377388, + 'timestamp': 586.15605776757, + 'timestamp_carla': 586157, + 'timestamp_device': 29401, + 'timestamp_stream': 586.15605776757, + 'transform': [array([ 2.58212805e+00, -8.54017544e+00, 7.42715830e-03]), + array([ -0.02480725, -14.1886158 , 0.02999878])]} +{'AngularVelocity': array([ 0.02285345, 0.01675351, -2.59525776]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.053159713745117, + 'FR_Wheel_Angle': -17.71997833251953, + 'Location': array([ -2.72157645, -21.48213768, 0.17267834]), + 'Rotation': array([-0.07849253, 3.12110066, -0.01187134]), + 'Velocity': array([ 0.58653665, -0.08203861, -0.00081207]), + 'brake_input': 0.0, + 'camera_location': array([-5.08286428, 6.98985767, 0.94881046]), + 'camera_rotation': array([ -8.75527763, -33.10098648, -0.52004308]), + 'current_gear_input': False, + 'focus_actor_dist': 1071.3050537109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 781.15704346, -1635.57788086, 15.90829468]), + 'frame': 18033, + 'frame_number': 18033, + 'framesequence': 69059, + 'gaze_dir': array([ 0.95575714, -0.29133606, 0.03984833]), + 'gaze_origin': array([-3.15947914, 0.21587449, 0.04842911]), + 'gaze_valid': True, + 'gaze_vergence': 439.07769775390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95777893, -0.28466797, 0.04020691]), + 'left_gaze_origin': array([-3.11727762, 3.40621519, 0.05348359]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.029876708984375, + 'left_pupil_posn': array([-0.21944463, -0.08804166]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95373535, -0.29800415, 0.03948975]), + 'right_gaze_origin': array([-3.20168018, -2.97446609, 0.04337464]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.04754638671875, + 'right_pupil_posn': array([-0.24635774, -0.14999354]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.38200631737709045, + 'throttle_input': 0.0, + 'timestamp': 586.1771568655968, + 'timestamp_carla': 586178, + 'timestamp_device': 29426, + 'timestamp_stream': 586.1771568655968, + 'transform': [array([ 2.68235540e+00, -8.52798557e+00, 7.12835276e-03]), + array([ -0.02398762, -14.55888081, 0.03134155])]} +{'AngularVelocity': array([-0.01222646, -0.02901031, -2.76128983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.42461585998535, + 'FR_Wheel_Angle': -17.858415603637695, + 'Location': array([ -2.5888083 , -21.49757195, 0.17251632]), + 'Rotation': array([-0.07492717, 2.24197221, -0.01098633]), + 'Velocity': array([ 0.5734449 , -0.09417593, -0.00081321]), + 'brake_input': 0.0, + 'camera_location': array([-5.12730694, 6.98445988, 0.96457791]), + 'camera_rotation': array([ -8.64315987, -33.2052803 , -0.6889199 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1094.9442138671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 808.83959961, -1629.37219238, 15.87876892]), + 'frame': 18034, + 'frame_number': 18034, + 'framesequence': 69062, + 'gaze_dir': array([ 0.95671082, -0.28940582, 0.02947235]), + 'gaze_origin': array([-3.15845561, 0.21223603, 0.04578857]), + 'gaze_valid': True, + 'gaze_vergence': 439.3305358886719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95870972, -0.28289795, 0.02842712]), + 'left_gaze_origin': array([-3.11607075, 3.40276814, 0.0520401 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0648956298828125, + 'left_pupil_posn': array([-0.21627229, -0.0919019 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95471191, -0.2959137 , 0.03051758]), + 'right_gaze_origin': array([-3.20084095, -2.97829604, 0.03953705]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9698486328125, + 'right_pupil_posn': array([-0.24319595, -0.15654421]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.38803064823150635, + 'throttle_input': 0.0, + 'timestamp': 586.2004244662821, + 'timestamp_carla': 586201, + 'timestamp_device': 29451, + 'timestamp_stream': 586.2004244662821, + 'transform': [array([ 2.79410386e+00, -8.51584530e+00, 6.75296783e-03]), + array([ -0.02294943, -14.971735 , 0.03295898])]} +{'AngularVelocity': array([ 0.0548368 , 0.07126942, -3.66503096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.404146194458008, + 'FR_Wheel_Angle': -17.840211868286133, + 'Location': array([ -2.44972205, -21.51588249, 0.17237106]), + 'Rotation': array([-0.07192872, 1.31531239, -0.00991821]), + 'Velocity': array([ 5.67471802e-01, -1.02650389e-01, -5.26819204e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.16029501, 6.9726305 , 0.98473281]), + 'camera_rotation': array([ -8.52617264, -33.2166214 , -0.79709554]), + 'current_gear_input': False, + 'focus_actor_dist': 1007.8447875976562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 734.60894775, -1669.26171875, 15.96613312]), + 'frame': 18035, + 'frame_number': 18035, + 'framesequence': 69064, + 'gaze_dir': array([ 0.95690155, -0.28818512, 0.03505707]), + 'gaze_origin': array([-3.15914798, 0.21135102, 0.04416275]), + 'gaze_valid': True, + 'gaze_vergence': 489.9240417480469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95857239, -0.2824707 , 0.03643799]), + 'left_gaze_origin': array([-3.11663842, 3.40193033, 0.04955597]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.063873291015625, + 'left_pupil_posn': array([-0.21509689, -0.09243 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95523071, -0.29389954, 0.03367615]), + 'right_gaze_origin': array([-3.20165706, -2.97922826, 0.03876953]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0338134765625, + 'right_pupil_posn': array([-0.24236161, -0.15443695]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.394604355096817, + 'throttle_input': 0.0, + 'timestamp': 586.2212974652648, + 'timestamp_carla': 586222, + 'timestamp_device': 29468, + 'timestamp_stream': 586.2212974652648, + 'transform': [array([ 2.89542556e+00, -8.50623417e+00, 6.39783824e-03]), + array([ -0.02215713, -15.34646988, 0.0345459 ])]} +{'AngularVelocity': array([ 0.01213097, 0.01883289, -4.48164654]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.30021858215332, + 'FR_Wheel_Angle': -17.594348907470703, + 'Location': array([ -2.29399014, -21.53906441, 0.17220959]), + 'Rotation': array([-0.06996845, 0.27203232, -0.00830078]), + 'Velocity': array([ 6.69691503e-01, -1.31997496e-01, -4.78444097e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.23893785, 6.95980453, 0.98261458]), + 'camera_rotation': array([ -8.49986267, -33.23010635, -0.90664405]), + 'current_gear_input': False, + 'focus_actor_dist': 1070.794921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 796.84533691, -1643.62744141, 15.89562988]), + 'frame': 18036, + 'frame_number': 18036, + 'framesequence': 69067, + 'gaze_dir': array([ 0.95740509, -0.28578186, 0.04036713]), + 'gaze_origin': array([-3.15856338, 0.20799181, 0.04397126]), + 'gaze_valid': True, + 'gaze_vergence': 377.9288635253906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95956421, -0.27832031, 0.04208374]), + 'left_gaze_origin': array([-3.11666131, 3.39925551, 0.04894257]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.076416015625, + 'left_pupil_posn': array([-0.21297461, -0.09121394]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95524597, -0.29324341, 0.03865051]), + 'right_gaze_origin': array([-3.20046544, -2.98327184, 0.03899994]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0895538330078125, + 'right_pupil_posn': array([-0.23791254, -0.15222883]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4002625048160553, + 'throttle_input': 0.0, + 'timestamp': 586.2449010685086, + 'timestamp_carla': 586245, + 'timestamp_device': 29493, + 'timestamp_stream': 586.2449010685086, + 'transform': [array([ 3.01103926e+00, -8.49687386e+00, 5.93875861e-03]), + array([ -0.0215151 , -15.77454948, 0.03646851])]} +{'AngularVelocity': array([ 0.01409924, 0.00878909, -3.53369451]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.567363739013672, + 'FR_Wheel_Angle': -14.584033012390137, + 'Location': array([ -2.14349508, -21.56271362, 0.1720797 ]), + 'Rotation': array([-0.07333574, -0.67773443, -0.01251221]), + 'Velocity': array([ 6.19130611e-01, -1.14547104e-01, -5.19504538e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.29132318, 6.95819092, 0.96646219]), + 'camera_rotation': array([ -8.52757263, -33.29133224, -1.14100361]), + 'current_gear_input': False, + 'focus_actor_dist': 1122.42041015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 847.94354248, -1622.19519043, 15.83757782]), + 'frame': 18037, + 'frame_number': 18037, + 'framesequence': 69070, + 'gaze_dir': array([ 0.95849609, -0.28232574, 0.0370636 ]), + 'gaze_origin': array([-3.15695286, 0.20392381, 0.04703674]), + 'gaze_valid': True, + 'gaze_vergence': 171.3535919189453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96109009, -0.27235413, 0.04603577]), + 'left_gaze_origin': array([-3.11451602, 3.39452505, 0.05366516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.00244140625, + 'left_pupil_posn': array([-0.20934725, -0.09117627]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9559021 , -0.29229736, 0.02809143]), + 'right_gaze_origin': array([-3.19938993, -2.98667765, 0.04040832]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.04290771484375, + 'right_pupil_posn': array([-0.23353547, -0.14942491]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4065798223018646, + 'throttle_input': 0.0, + 'timestamp': 586.266437266022, + 'timestamp_carla': 586267, + 'timestamp_device': 29518, + 'timestamp_stream': 586.266437266022, + 'transform': [array([ 3.11729646e+00, -8.48972034e+00, 5.51277166e-03]), + array([ -0.02114626, -16.16849136, 0.03829956])]} +{'AngularVelocity': array([-0.06246129, -0.1017523 , -0.00017798]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.329405784606934, + 'FR_Wheel_Angle': -9.953034400939941, + 'Location': array([ -2.09365845, -21.56998062, 0.17216331]), + 'Rotation': array([-0.09621687, -0.94198614, -0.02337646]), + 'Velocity': array([-4.09169734e-05, 2.96272599e-04, 5.04496784e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.3447237 , 6.97356701, 0.97947979]), + 'camera_rotation': array([ -8.5048008 , -33.30593872, -1.50704765]), + 'current_gear_input': False, + 'focus_actor_dist': 1071.63818359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 806.13830566, -1644.21655273, 15.88661957]), + 'frame': 18038, + 'frame_number': 18038, + 'framesequence': 69072, + 'gaze_dir': array([ 0.95858765, -0.28176117, 0.03935242]), + 'gaze_origin': array([-3.15683746, 0.20291063, 0.04821472]), + 'gaze_valid': True, + 'gaze_vergence': 232.92196655273438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96179199, -0.27029419, 0.04335022]), + 'left_gaze_origin': array([-3.11464858, 3.39346933, 0.05619202]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.116912841796875, + 'left_pupil_posn': array([-0.20881349, -0.08716118]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9553833 , -0.29322815, 0.03535461]), + 'right_gaze_origin': array([-3.19902682, -2.98764825, 0.04023743]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0400390625, + 'right_pupil_posn': array([-0.23213929, -0.15036798]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.41381269693374634, + 'throttle_input': 0.0, + 'timestamp': 586.2882266677916, + 'timestamp_carla': 586289, + 'timestamp_device': 29534, + 'timestamp_stream': 586.2882266677916, + 'transform': [array([ 3.22562695e+00, -8.48393822e+00, 5.06151188e-03]), + array([ -0.02081159, -16.57077026, 0.04022217])]} +{'AngularVelocity': array([-1.67221259e-02, -3.34308110e-02, 1.20494428e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.7801740169525146, + 'FR_Wheel_Angle': -1.585208773612976, + 'Location': array([ -2.0935328 , -21.56998062, 0.17205708]), + 'Rotation': array([-0.07739287, -0.94198614, -0.01412964]), + 'Velocity': array([-1.63847344e-05, 1.27921769e-04, 2.55657069e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.39085388, 6.9890852 , 1.02721584]), + 'camera_rotation': array([ -8.40955353, -33.21373749, -1.70970821]), + 'current_gear_input': False, + 'focus_actor_dist': 1079.989501953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 818.89196777, -1643.48400879, 15.87374115]), + 'frame': 18039, + 'frame_number': 18039, + 'framesequence': 69075, + 'gaze_dir': array([ 0.95973206, -0.27788544, 0.03886414]), + 'gaze_origin': array([-3.15673614, 0.20209199, 0.04824295]), + 'gaze_valid': True, + 'gaze_vergence': 236.843505859375, + 'handbrake_input': False, + 'left_eye_openness': 0.9224556088447571, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96305847, -0.26599121, 0.04176331]), + 'left_gaze_origin': array([-3.11457062, 3.39296722, 0.0572464 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1240081787109375, + 'left_pupil_posn': array([-0.20726019, -0.0861181 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95640564, -0.28977966, 0.03596497]), + 'right_gaze_origin': array([-3.19890165, -2.98878336, 0.0392395 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0595550537109375, + 'right_pupil_posn': array([-0.22982299, -0.15151739]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4194525182247162, + 'throttle_input': 0.0, + 'timestamp': 586.3107499666512, + 'timestamp_carla': 586311, + 'timestamp_device': 29559, + 'timestamp_stream': 586.3107499666512, + 'transform': [array([ 3.33825302e+00, -8.47946072e+00, 4.58597159e-03]), + array([ -0.020634 , -16.98964119, 0.04220581])]} +{'AngularVelocity': array([-5.42182568e-03, -9.98554286e-03, -7.63727166e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16380730271339417, + 'FR_Wheel_Angle': 0.11279640346765518, + 'Location': array([ -2.09350753, -21.56999397, 0.17202458]), + 'Rotation': array([-0.07352015, -0.94198602, -0.01220703]), + 'Velocity': array([-4.83247459e-06, 4.94892561e-07, -1.80302886e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.43979597, 6.99953508, 1.06999588]), + 'camera_rotation': array([ -8.29754543, -33.06726074, -1.76619446]), + 'current_gear_input': False, + 'focus_actor_dist': 1080.788330078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 822.43212891, -1640.69287109, 15.86929321]), + 'frame': 18040, + 'frame_number': 18040, + 'framesequence': 69078, + 'gaze_dir': array([ 0.95955658, -0.27835083, 0.04042053]), + 'gaze_origin': array([-3.15673089, 0.20152435, 0.04797974]), + 'gaze_valid': True, + 'gaze_vergence': 263.1883544921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96217346, -0.26872253, 0.04463196]), + 'left_gaze_origin': array([-3.11466837, 3.39284849, 0.05673371]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1262359619140625, + 'left_pupil_posn': array([-0.20650512, -0.08641219]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9569397 , -0.28797913, 0.03620911]), + 'right_gaze_origin': array([-3.19879317, -2.98979974, 0.03922577]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0596160888671875, + 'right_pupil_posn': array([-0.23008257, -0.15059221]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.42602622509002686, + 'throttle_input': 0.0, + 'timestamp': 586.3333476670086, + 'timestamp_carla': 586334, + 'timestamp_device': 29584, + 'timestamp_stream': 586.3333476670086, + 'transform': [array([ 3.45182300e+00, -8.47650623e+00, 4.11516195e-03]), + array([ -0.02053838, -17.41274452, 0.04415894])]} +{'AngularVelocity': array([-1.29131996e-03, -1.99995190e-03, -1.19274591e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015379038639366627, + 'FR_Wheel_Angle': 0.03588976711034775, + 'Location': array([ -2.09349823, -21.5700016 , 0.17202114]), + 'Rotation': array([-0.07244781, -0.94198614, -0.0116272 ]), + 'Velocity': array([ 9.87555836e-07, 5.01030570e-07, -1.08939112e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.49261522, 7.00304556, 1.11085629]), + 'camera_rotation': array([ -8.18407536, -32.94038391, -1.95417726]), + 'current_gear_input': False, + 'focus_actor_dist': 1112.8052978515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 856.47717285, -1628.96484375, 15.83152008]), + 'frame': 18041, + 'frame_number': 18041, + 'framesequence': 69080, + 'gaze_dir': array([ 0.95980072, -0.2774353 , 0.04108429]), + 'gaze_origin': array([-3.15681314, 0.20130157, 0.04767761]), + 'gaze_valid': True, + 'gaze_vergence': 268.0390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96232605, -0.26806641, 0.0453186 ]), + 'left_gaze_origin': array([-3.114856 , 3.39278889, 0.05612946]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1250152587890625, + 'left_pupil_posn': array([-0.20605898, -0.08659863]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95727539, -0.2868042 , 0.03684998]), + 'right_gaze_origin': array([-3.19877052, -2.99018574, 0.03922577]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0673980712890625, + 'right_pupil_posn': array([-0.22956336, -0.15036798]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4327280521392822, + 'throttle_input': 0.0, + 'timestamp': 586.35433556512, + 'timestamp_carla': 586355, + 'timestamp_device': 29601, + 'timestamp_stream': 586.35433556512, + 'transform': [array([ 3.55779958e+00, -8.47516441e+00, 3.69747146e-03]), + array([ -0.02047691, -17.80826569, 0.04592896])]} +{'AngularVelocity': array([-2.63409427e-04, -4.72062966e-04, -1.29541440e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.19063231348991394, + 'FR_Wheel_Angle': 0.37940603494644165, + 'Location': array([ -2.09349704, -21.5700016 , 0.17202197]), + 'Rotation': array([-0.07244781, -0.94198614, -0.0116272 ]), + 'Velocity': array([2.11718498e-06, 4.42000442e-07, 2.58600430e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.5170002 , 7.00958824, 1.13383508]), + 'camera_rotation': array([ -8.04372215, -32.89984512, -2.41616344]), + 'current_gear_input': False, + 'focus_actor_dist': 1130.24169921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 876.77850342, -1622.46142578, 15.8091507 ]), + 'frame': 18042, + 'frame_number': 18042, + 'framesequence': 69083, + 'gaze_dir': array([ 0.95990753, -0.27706909, 0.04067993]), + 'gaze_origin': array([-3.1568737 , 0.20117569, 0.04749222]), + 'gaze_valid': True, + 'gaze_vergence': 252.42410278320312, + 'handbrake_input': False, + 'left_eye_openness': 0.9165720343589783, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96264648, -0.26693726, 0.04498291]), + 'left_gaze_origin': array([-3.11500883, 3.39255071, 0.05608368]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1130218505859375, + 'left_pupil_posn': array([-0.20603776, -0.08683014]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95716858, -0.28720093, 0.03637695]), + 'right_gaze_origin': array([-3.19873834, -2.99019933, 0.03890076]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0750579833984375, + 'right_pupil_posn': array([-0.22916734, -0.15065718]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.438789039850235, + 'throttle_input': 0.0, + 'timestamp': 586.3778105676174, + 'timestamp_carla': 586378, + 'timestamp_device': 29626, + 'timestamp_stream': 586.3778105676174, + 'transform': [array([ 3.67681503e+00, -8.47527409e+00, 3.22210300e-03]), + array([ -0.02047691, -18.2532692 , 0.04785156])]} +{'AngularVelocity': array([-9.29634625e-05, -1.50926644e-04, -1.21394596e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.6392362117767334, + 'FR_Wheel_Angle': 3.322366714477539, + 'Location': array([ -2.09349656, -21.5700016 , 0.17202099]), + 'Rotation': array([-0.07244781, -0.94198614, -0.0116272 ]), + 'Velocity': array([2.53693202e-06, 4.25488111e-07, 1.90296007e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.5351615 , 7.02057791, 1.14826405]), + 'camera_rotation': array([ -7.9154582 , -32.86222076, -2.80583239]), + 'current_gear_input': False, + 'focus_actor_dist': 1127.117431640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 878.74298096, -1626.36425781, 15.80857849]), + 'frame': 18043, + 'frame_number': 18043, + 'framesequence': 69086, + 'gaze_dir': array([ 0.96109009, -0.27348328, 0.03672028]), + 'gaze_origin': array([-3.1561625 , 0.20078202, 0.04869385]), + 'gaze_valid': True, + 'gaze_vergence': 206.22808837890625, + 'handbrake_input': False, + 'left_eye_openness': 0.9242073893547058, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96351624, -0.26399231, 0.04391479]), + 'left_gaze_origin': array([-3.11361861, 3.39192677, 0.05896759]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1509246826171875, + 'left_pupil_posn': array([-0.20399547, -0.08695555]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95866394, -0.28297424, 0.02952576]), + 'right_gaze_origin': array([-3.19870639, -2.99036264, 0.03842011]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.080169677734375, + 'right_pupil_posn': array([-0.22799468, -0.15131438]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4445570409297943, + 'throttle_input': 0.0, + 'timestamp': 586.3997491672635, + 'timestamp_carla': 586400, + 'timestamp_device': 29651, + 'timestamp_stream': 586.3997491672635, + 'transform': [array([ 3.78832078e+00, -8.47683811e+00, 2.80826562e-03]), + array([ -0.02057253, -18.67098236, 0.04956054])]} +{'AngularVelocity': array([ 3.20488507e-05, -5.10735626e-05, -1.07648093e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.9525465965271, + 'FR_Wheel_Angle': 9.491571426391602, + 'Location': array([ -2.09349656, -21.5700016 , 0.17202015]), + 'Rotation': array([-0.07244781, -0.94198614, -0.0116272 ]), + 'Velocity': array([2.63870697e-06, 2.21491206e-07, 2.02375057e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.54722977, 7.02399683, 1.16254151]), + 'camera_rotation': array([ -7.80366135, -32.80860519, -2.85890102]), + 'current_gear_input': False, + 'focus_actor_dist': 1089.2841796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 847.63623047, -1640.74890137, 15.84436035]), + 'frame': 18044, + 'frame_number': 18044, + 'framesequence': 69088, + 'gaze_dir': array([ 0.96085358, -0.27409363, 0.03848267]), + 'gaze_origin': array([-3.15639114, 0.20002748, 0.0483223 ]), + 'gaze_valid': True, + 'gaze_vergence': 246.94613647460938, + 'handbrake_input': False, + 'left_eye_openness': 0.9220594167709351, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96351624, -0.26409912, 0.04325867]), + 'left_gaze_origin': array([-3.1141541 , 3.39117908, 0.05868225]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.207244873046875, + 'left_pupil_posn': array([-0.20383489, -0.08590555]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95819092, -0.28408813, 0.03370667]), + 'right_gaze_origin': array([-3.19862843, -2.99112415, 0.03796234]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0983123779296875, + 'right_pupil_posn': array([-0.22749192, -0.15189242]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.45014193654060364, + 'throttle_input': 0.0, + 'timestamp': 586.4221305660903, + 'timestamp_carla': 586423, + 'timestamp_device': 29668, + 'timestamp_stream': 586.4221305660903, + 'transform': [array([ 3.90228271e+00, -8.47987652e+00, 2.39439006e-03]), + array([ -0.02075694, -19.09866905, 0.05123901])]} +{'AngularVelocity': array([ 0.04396519, -0.00862478, 0.21859416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.296441078186035, + 'FR_Wheel_Angle': 14.539665222167969, + 'Location': array([ -2.09427953, -21.5700531 , 0.1720081 ]), + 'Rotation': array([-0.07254343, -0.94326788, -0.01174927]), + 'Velocity': array([3.92675383e-06, 4.67592804e-03, 2.82297115e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.57176971, 7.03572893, 1.18341804]), + 'camera_rotation': array([ -7.72399426, -32.77523804, -2.82124972]), + 'current_gear_input': False, + 'focus_actor_dist': 1123.76806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 884.92907715, -1630.87548828, 15.804039 ]), + 'frame': 18045, + 'frame_number': 18045, + 'framesequence': 69091, + 'gaze_dir': array([ 0.96229553, -0.26927185, 0.0369339 ]), + 'gaze_origin': array([-3.15635467, 0.19937517, 0.04751969]), + 'gaze_valid': True, + 'gaze_vergence': 215.79421997070312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96385193, -0.26269531, 0.04415894]), + 'left_gaze_origin': array([-3.1141541 , 3.39071679, 0.05791321]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.205902099609375, + 'left_pupil_posn': array([-0.2005896 , -0.08764815]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96073914, -0.27584839, 0.02970886]), + 'right_gaze_origin': array([-3.19855499, -2.99196625, 0.03712616]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1258697509765625, + 'right_pupil_posn': array([-0.22641504, -0.15212369]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.45530566573143005, + 'throttle_input': 0.0, + 'timestamp': 586.4434923678637, + 'timestamp_carla': 586444, + 'timestamp_device': 29693, + 'timestamp_stream': 586.4434923678637, + 'transform': [array([ 4.01113605e+00, -8.48408699e+00, 2.02810275e-03]), + array([ -0.020996 , -19.50794983, 0.05273438])]} +{'AngularVelocity': array([ 0.05413568, -0.005862 , 0.23821449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.186732292175293, + 'FR_Wheel_Angle': 18.090524673461914, + 'Location': array([ -2.09573984, -21.57021141, 0.17202517]), + 'Rotation': array([-0.07263223, -0.95120209, -0.01168823]), + 'Velocity': array([-0.00662308, 0.0050718 , 0.00010959]), + 'brake_input': 0.0, + 'camera_location': array([-5.61430931, 7.04665518, 1.19325507]), + 'camera_rotation': array([ -7.76579475, -32.7746315 , -2.93439102]), + 'current_gear_input': False, + 'focus_actor_dist': 1123.863525390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 888.12438965, -1628.99731445, 15.80023193]), + 'frame': 18046, + 'frame_number': 18046, + 'framesequence': 69093, + 'gaze_dir': array([ 0.96189117, -0.27090454, 0.03581238]), + 'gaze_origin': array([-3.15615869, 0.19775392, 0.04728165]), + 'gaze_valid': True, + 'gaze_vergence': 228.48080444335938, + 'handbrake_input': False, + 'left_eye_openness': 0.9170185327529907, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96292114, -0.2664032 , 0.04229736]), + 'left_gaze_origin': array([-3.11378789, 3.38963342, 0.05771027]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2058563232421875, + 'left_pupil_posn': array([-0.19968277, -0.08783984]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96086121, -0.27540588, 0.02932739]), + 'right_gaze_origin': array([-3.19852901, -2.9941256 , 0.03685303]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1427764892578125, + 'right_pupil_posn': array([-0.22619325, -0.15312552]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4598834216594696, + 'throttle_input': 0.0, + 'timestamp': 586.4660385660827, + 'timestamp_carla': 586467, + 'timestamp_device': 29709, + 'timestamp_stream': 586.4660385660827, + 'transform': [array([ 4.12601137e+00, -8.48988724e+00, 1.64871209e-03]), + array([ -0.02133068, -19.94062614, 0.05422974])]} +{'AngularVelocity': array([ 0.05400289, -0.00446747, 0.14771281]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.42403793334961, + 'FR_Wheel_Angle': 19.462074279785156, + 'Location': array([ -2.1000154 , -21.57071304, 0.17203686]), + 'Rotation': array([-0.07308302, -0.97769159, -0.01141357]), + 'Velocity': array([-0.02358206, 0.00249234, 0.00055842]), + 'brake_input': 0.0, + 'camera_location': array([-5.64363146, 7.06027079, 1.19697118]), + 'camera_rotation': array([ -7.84138441, -32.75451279, -3.01202893]), + 'current_gear_input': False, + 'focus_actor_dist': 1099.2105712890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 871.10601807, -1644.02319336, 15.82230377]), + 'frame': 18047, + 'frame_number': 18047, + 'framesequence': 69096, + 'gaze_dir': array([ 0.96192932, -0.27082062, 0.03536224]), + 'gaze_origin': array([-3.15606928, 0.19622727, 0.04763184]), + 'gaze_valid': True, + 'gaze_vergence': 216.93878173828125, + 'handbrake_input': False, + 'left_eye_openness': 0.9123643636703491, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96318054, -0.26547241, 0.04237366]), + 'left_gaze_origin': array([-3.11368728, 3.388901 , 0.05847321]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2079315185546875, + 'left_pupil_posn': array([-0.19943327, -0.08764815]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9606781 , -0.27616882, 0.02835083]), + 'right_gaze_origin': array([-3.19845152, -2.99644637, 0.03679047]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1429595947265625, + 'right_pupil_posn': array([-0.22426724, -0.15312552]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4646626114845276, + 'throttle_input': 0.0, + 'timestamp': 586.4891035668552, + 'timestamp_carla': 586490, + 'timestamp_device': 29734, + 'timestamp_stream': 586.4891035668552, + 'transform': [array([ 4.24342871e+00, -8.49722385e+00, 1.28534320e-03]), + array([ -0.02172683, -20.38373566, 0.05563355])]} +{'AngularVelocity': array([ 0.05975756, -0.00796015, 0.06399583]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.49336051940918, + 'FR_Wheel_Angle': 19.541044235229492, + 'Location': array([ -2.10977983, -21.57194138, 0.1720531 ]), + 'Rotation': array([-0.07311717, -1.03793347, -0.0112915 ]), + 'Velocity': array([-3.90651822e-02, 9.48619418e-05, 1.84011456e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.6703763 , 7.07147455, 1.21533895]), + 'camera_rotation': array([ -7.86038637, -32.69220734, -3.01801634]), + 'current_gear_input': False, + 'focus_actor_dist': 1078.405517578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 856.91992188, -1655.41821289, 15.8403244 ]), + 'frame': 18048, + 'frame_number': 18048, + 'framesequence': 69099, + 'gaze_dir': array([ 0.96349335, -0.26508331, 0.03476715]), + 'gaze_origin': array([-3.154181 , 0.19256134, 0.04707718]), + 'gaze_valid': True, + 'gaze_vergence': 215.86004638671875, + 'handbrake_input': False, + 'left_eye_openness': 0.9101398587226868, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96647644, -0.25352478, 0.04019165]), + 'left_gaze_origin': array([-3.11354232, 3.38803267, 0.05797882]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2235107421875, + 'left_pupil_posn': array([-0.1989975 , -0.08764815]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96051025, -0.27664185, 0.02934265]), + 'right_gaze_origin': array([-3.19481969, -3.0029099 , 0.03617554]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1450347900390625, + 'right_pupil_posn': array([-0.21550024, -0.1535306 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4701010286808014, + 'throttle_input': 0.0, + 'timestamp': 586.5105312652886, + 'timestamp_carla': 586511, + 'timestamp_device': 29759, + 'timestamp_stream': 586.5105312652886, + 'transform': [array([ 4.35245514e+00, -8.50532722e+00, 9.71260073e-04]), + array([ -0.02209566, -20.79601479, 0.05688476])]} +{'AngularVelocity': array([ 0.06017975, -0.00839415, 0.05275109]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.5341796875, + 'FR_Wheel_Angle': 19.5670108795166, + 'Location': array([ -2.11863184, -21.57308006, 0.17205058]), + 'Rotation': array([-0.07272785, -1.0925293 , -0.01150513]), + 'Velocity': array([-0.04156685, -0.0002692 , 0.00023646]), + 'brake_input': 0.0, + 'camera_location': array([-5.68573093, 7.09953737, 1.22689319]), + 'camera_rotation': array([ -7.84816027, -32.63309479, -3.17056632]), + 'current_gear_input': False, + 'focus_actor_dist': 1070.0413818359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 851.82727051, -1655.59228516, 15.8454361 ]), + 'frame': 18049, + 'frame_number': 18049, + 'framesequence': 69102, + 'gaze_dir': array([ 0.96366882, -0.26433563, 0.03574371]), + 'gaze_origin': array([-3.15416574, 0.18942414, 0.04638748]), + 'gaze_valid': True, + 'gaze_vergence': 195.70008850097656, + 'handbrake_input': False, + 'left_eye_openness': 0.9111615419387817, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96635437, -0.25354004, 0.0430603 ]), + 'left_gaze_origin': array([-3.11315465, 3.38546443, 0.05797882]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2286529541015625, + 'left_pupil_posn': array([-0.19667494, -0.08788693]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96098328, -0.27513123, 0.02842712]), + 'right_gaze_origin': array([-3.19517708, -3.00661635, 0.03479614]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2013092041015625, + 'right_pupil_posn': array([-0.21296602, -0.15357029]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.47436752915382385, + 'throttle_input': 0.0, + 'timestamp': 586.5327222682536, + 'timestamp_carla': 586533, + 'timestamp_device': 29784, + 'timestamp_stream': 586.5327222682536, + 'transform': [array([ 4.46521664e+00, -8.51498890e+00, 6.55994401e-04]), + array([ -0.02249181, -21.22328186, 0.05810547])]} +{'AngularVelocity': array([ 0.06063448, -0.00667937, 0.0282812 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.661760330200195, + 'FR_Wheel_Angle': 19.741209030151367, + 'Location': array([ -2.13102555, -21.57467461, 0.17206368]), + 'Rotation': array([-0.07254343, -1.16973889, -0.01159668]), + 'Velocity': array([-4.54638563e-02, -7.93864776e-04, 8.99314837e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.71450186, 7.14784861, 1.21286571]), + 'camera_rotation': array([ -7.88143682, -32.51943207, -3.41227341]), + 'current_gear_input': False, + 'focus_actor_dist': 1074.643310546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 860.56091309, -1656.10131836, 15.8369751 ]), + 'frame': 18050, + 'frame_number': 18050, + 'framesequence': 69104, + 'gaze_dir': array([ 0.9644165 , -0.26171112, 0.03500366]), + 'gaze_origin': array([-3.15388894, 0.18832016, 0.04661179]), + 'gaze_valid': True, + 'gaze_vergence': 193.47708129882812, + 'handbrake_input': False, + 'left_eye_openness': 0.916150689125061, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96664429, -0.25244141, 0.04295349]), + 'left_gaze_origin': array([-3.11285567, 3.38438892, 0.05847321]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2479705810546875, + 'left_pupil_posn': array([-0.19444185, -0.08788693]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96218872, -0.27098083, 0.02705383]), + 'right_gaze_origin': array([-3.19492221, -3.0077486 , 0.03475036]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.190216064453125, + 'right_pupil_posn': array([-0.21180117, -0.15357029]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4788537621498108, + 'throttle_input': 0.0, + 'timestamp': 586.5545134656131, + 'timestamp_carla': 586555, + 'timestamp_device': 29801, + 'timestamp_stream': 586.5545134656131, + 'transform': [array([ 4.57574034e+00, -8.52570248e+00, 3.64360807e-04]), + array([ -0.02288796, -21.64293098, 0.0592346 ])]} +{'AngularVelocity': array([ 0.06259385, -0.00668561, -0.00196016]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.664413452148438, + 'FR_Wheel_Angle': 19.747760772705078, + 'Location': array([ -2.14140916, -21.57599068, 0.17206909]), + 'Rotation': array([-0.07263223, -1.23522937, -0.01147461]), + 'Velocity': array([-0.05209961, -0.0016026 , -0.0001034 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.7507596 , 7.20560694, 1.20777547]), + 'camera_rotation': array([ -7.96796846, -32.29620361, -3.50021553]), + 'current_gear_input': False, + 'focus_actor_dist': 1052.0308837890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 842.76922607, -1663.74645996, 15.8572464 ]), + 'frame': 18051, + 'frame_number': 18051, + 'framesequence': 69107, + 'gaze_dir': array([ 0.96391296, -0.26342773, 0.03582764]), + 'gaze_origin': array([-3.153512 , 0.18535386, 0.04704437]), + 'gaze_valid': True, + 'gaze_vergence': 167.00831604003906, + 'handbrake_input': False, + 'left_eye_openness': 0.9129837155342102, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96609497, -0.25415039, 0.04519653]), + 'left_gaze_origin': array([-3.11229277, 3.37927127, 0.05908203]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2762298583984375, + 'left_pupil_posn': array([-0.19150269, -0.08766901]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96173096, -0.27270508, 0.02645874]), + 'right_gaze_origin': array([-3.19473147, -3.00856352, 0.03500672]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2030029296875, + 'right_pupil_posn': array([-0.21182108, -0.15263724]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4830469787120819, + 'throttle_input': 0.0, + 'timestamp': 586.5776483677328, + 'timestamp_carla': 586578, + 'timestamp_device': 29826, + 'timestamp_stream': 586.5776483677328, + 'transform': [array([ 4.69280005e+00, -8.53837872e+00, 6.68144203e-05]), + array([ -0.02333876, -22.08833885, 0.06033324])]} +{'AngularVelocity': array([ 0.04959209, 0.03944688, -3.33199072]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.642181396484375, + 'FR_Wheel_Angle': 19.767955780029297, + 'Location': array([ -2.20223475, -21.58333015, 0.17226166]), + 'Rotation': array([-0.09487815, -1.61074829, 0.00176209]), + 'Velocity': array([-5.80008686e-01, -8.37565958e-02, 5.41496265e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.76005936, 7.2517724 , 1.21311796]), + 'camera_rotation': array([ -7.97246981, -32.01335144, -3.43150449]), + 'current_gear_input': False, + 'focus_actor_dist': 1042.024658203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 837.64923096, -1669.31542969, 15.86426544]), + 'frame': 18052, + 'frame_number': 18052, + 'framesequence': 69110, + 'gaze_dir': array([ 0.96432495, -0.26208496, 0.03448486]), + 'gaze_origin': array([-3.1526804 , 0.1850403 , 0.04781647]), + 'gaze_valid': True, + 'gaze_vergence': 154.7377471923828, + 'handbrake_input': False, + 'left_eye_openness': 0.90768963098526, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96636963, -0.25323486, 0.04455566]), + 'left_gaze_origin': array([-3.11086893, 3.37841511, 0.0594635 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2833099365234375, + 'left_pupil_posn': array([-0.19021469, -0.08786249]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96228027, -0.27093506, 0.02441406]), + 'right_gaze_origin': array([-3.19449162, -3.00833464, 0.03616944]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1972503662109375, + 'right_pupil_posn': array([-0.21166199, -0.15197051]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4877346158027649, + 'throttle_input': 0.0, + 'timestamp': 586.5992688685656, + 'timestamp_carla': 586600, + 'timestamp_device': 29851, + 'timestamp_stream': 586.5992688685656, + 'transform': [array([ 4.80193233e+00, -8.55142689e+00, -1.87587735e-04]), + array([ -0.02374174, -22.50452423, 0.06130981])]} +{'AngularVelocity': array([ 0.08158622, -0.05623698, -3.80209041]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.735271453857422, + 'FR_Wheel_Angle': 19.841859817504883, + 'Location': array([ -2.32294273, -21.59768677, 0.17231934]), + 'Rotation': array([-0.08496755, -2.3782351 , -0.00408936]), + 'Velocity': array([-6.41553998e-01, -8.98812488e-02, 2.23217008e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.75285673, 7.30409431, 1.22272122]), + 'camera_rotation': array([ -7.94178152, -31.7839756 , -3.59952903]), + 'current_gear_input': False, + 'focus_actor_dist': 1032.232666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 831.42248535, -1670.74572754, 15.87091827]), + 'frame': 18053, + 'frame_number': 18053, + 'framesequence': 69112, + 'gaze_dir': array([ 0.96406555, -0.26316071, 0.03343964]), + 'gaze_origin': array([-3.15237832, 0.18456955, 0.04828873]), + 'gaze_valid': True, + 'gaze_vergence': 169.82647705078125, + 'handbrake_input': False, + 'left_eye_openness': 0.9092356562614441, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96629333, -0.25382996, 0.04263306]), + 'left_gaze_origin': array([-3.11067057, 3.37761712, 0.05951691]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.310577392578125, + 'left_pupil_posn': array([-0.19021469, -0.08788693]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96183777, -0.27249146, 0.02424622]), + 'right_gaze_origin': array([-3.19408584, -3.00847793, 0.03706055]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1983642578125, + 'right_pupil_posn': array([-0.21176332, -0.15197051]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4921475946903229, + 'throttle_input': 0.0, + 'timestamp': 586.621407866478, + 'timestamp_carla': 586622, + 'timestamp_device': 29868, + 'timestamp_stream': 586.621407866478, + 'transform': [array([ 4.91341543e+00, -8.56599331e+00, -4.39453113e-04]), + array([ -0.02410374, -22.93066216, 0.06225585])]} +{'AngularVelocity': array([ 0.04294607, -0.00691324, -4.53214455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.267332077026367, + 'FR_Wheel_Angle': 18.535839080810547, + 'Location': array([ -2.48961878, -21.61474037, 0.17243953]), + 'Rotation': array([-0.08095822, -3.41885471, -0.00592041]), + 'Velocity': array([-7.78325200e-01, -9.51777473e-02, 2.92825687e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.76314068, 7.3754344 , 1.21550417]), + 'camera_rotation': array([ -8.02758884, -31.54150772, -3.96989942]), + 'current_gear_input': False, + 'focus_actor_dist': 1020.4884643554688, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 824.25415039, -1675.99133301, 15.87982941]), + 'frame': 18054, + 'frame_number': 18054, + 'framesequence': 69115, + 'gaze_dir': array([ 0.96424866, -0.26277161, 0.03231812]), + 'gaze_origin': array([-3.15137959, 0.18582307, 0.05405655]), + 'gaze_valid': True, + 'gaze_vergence': 125.7128677368164, + 'handbrake_input': False, + 'left_eye_openness': 0.9073541760444641, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96505737, -0.25866699, 0.04170227]), + 'left_gaze_origin': array([-3.10898304, 3.37922692, 0.06721497]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.363494873046875, + 'left_pupil_posn': array([-0.18922132, -0.08272207]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96343994, -0.26687622, 0.02293396]), + 'right_gaze_origin': array([-3.19377589, -3.00758076, 0.04089813]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1468048095703125, + 'right_pupil_posn': array([-0.2139923, -0.1497618]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.49613940715789795, + 'throttle_input': 0.0, + 'timestamp': 586.643343668431, + 'timestamp_carla': 586644, + 'timestamp_device': 29893, + 'timestamp_stream': 586.643343668431, + 'transform': [array([ 5.02354240e+00, -8.58159161e+00, -6.76307653e-04]), + array([ -0.0244794 , -23.35259247, 0.06314088])]} +{'AngularVelocity': array([ 0.07357418, -0.05451301, -2.52616096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.582226753234863, + 'FR_Wheel_Angle': 7.907848358154297, + 'Location': array([ -2.66997528, -21.62544441, 0.17261016]), + 'Rotation': array([-0.07388216, -4.34164619, -0.01651001]), + 'Velocity': array([-0.74428719, -0.02457112, 0.00092384]), + 'brake_input': 0.0, + 'camera_location': array([-5.77671576, 7.43709946, 1.21822596]), + 'camera_rotation': array([ -8.10804176, -31.24019814, -4.11170912]), + 'current_gear_input': False, + 'focus_actor_dist': 984.619873046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 793.75177002, -1688.10925293, 15.91425323]), + 'frame': 18055, + 'frame_number': 18055, + 'framesequence': 69117, + 'gaze_dir': array([ 0.96400452, -0.26266479, 0.03784943]), + 'gaze_origin': array([-3.15170431, 0.18719789, 0.05786057]), + 'gaze_valid': True, + 'gaze_vergence': 156.87371826171875, + 'handbrake_input': False, + 'left_eye_openness': 0.9070970416069031, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96708679, -0.24998474, 0.04730225]), + 'left_gaze_origin': array([-3.10973382, 3.37982368, 0.07076569]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.25140380859375, + 'left_pupil_posn': array([-0.19269323, -0.07865095]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96092224, -0.27534485, 0.02839661]), + 'right_gaze_origin': array([-3.19367528, -3.0054276 , 0.04495545]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0593109130859375, + 'right_pupil_posn': array([-0.21257508, -0.14450908]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5011383891105652, + 'throttle_input': 0.0, + 'timestamp': 586.6653071679175, + 'timestamp_carla': 586666, + 'timestamp_device': 29909, + 'timestamp_stream': 586.6653071679175, + 'transform': [array([ 5.13352156e+00, -8.59839439e+00, -9.05323017e-04]), + array([ -0.02477309, -23.77503395, 0.06399535])]} +{'AngularVelocity': array([-0.03649631, -0.00807313, -1.01246846]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.6506457328796387, + 'FR_Wheel_Angle': 3.2708749771118164, + 'Location': array([ -2.81814718, -21.62220573, 0.17268746]), + 'Rotation': array([-0.06677192, -4.67053413, -0.01760864]), + 'Velocity': array([-0.5982495 , 0.02127271, 0.00071361]), + 'brake_input': 0.0, + 'camera_location': array([-5.778543 , 7.48528385, 1.25860465]), + 'camera_rotation': array([ -8.02058792, -31.00193024, -4.0326705 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1014.0070190429688, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 824.7409668, -1677.1619873, 15.879776 ]), + 'frame': 18056, + 'frame_number': 18056, + 'framesequence': 69120, + 'gaze_dir': array([ 0.96391296, -0.26351929, 0.03417206]), + 'gaze_origin': array([-3.15161395, 0.18747178, 0.05727158]), + 'gaze_valid': True, + 'gaze_vergence': 181.7872314453125, + 'handbrake_input': False, + 'left_eye_openness': 0.9074245095252991, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96739197, -0.24993896, 0.04074097]), + 'left_gaze_origin': array([-3.10965729, 3.37977004, 0.06988068]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2476043701171875, + 'left_pupil_posn': array([-0.19329011, -0.07953107]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96043396, -0.27709961, 0.02760315]), + 'right_gaze_origin': array([-3.1935699 , -3.00482631, 0.04466248]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1571197509765625, + 'right_pupil_posn': array([-0.21291184, -0.14708292]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5067049264907837, + 'throttle_input': 0.0, + 'timestamp': 586.6879223659635, + 'timestamp_carla': 586688, + 'timestamp_device': 29934, + 'timestamp_stream': 586.6879223659635, + 'transform': [array([ 5.24655247e+00, -8.61699677e+00, -1.13813393e-03]), + array([ -0.02502581, -24.21045685, 0.06484984])]} +{'AngularVelocity': array([-0.01385595, -0.01292199, 0.01409465]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.23597405850887299, + 'FR_Wheel_Angle': -0.2815997302532196, + 'Location': array([ -2.93826318, -21.61491966, 0.1728276 ]), + 'Rotation': array([-0.06490728, -4.77191353, -0.01300048]), + 'Velocity': array([-4.45877135e-01, 3.36321928e-02, 4.22143930e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.77336359, 7.53379202, 1.29748809]), + 'camera_rotation': array([ -7.88517952, -30.82116508, -4.10440826]), + 'current_gear_input': False, + 'focus_actor_dist': 998.3677368164062, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 813.63970947, -1683.1817627 , 15.89285278]), + 'frame': 18057, + 'frame_number': 18057, + 'framesequence': 69123, + 'gaze_dir': array([ 0.96295929, -0.26690674, 0.03450775]), + 'gaze_origin': array([-3.15171814, 0.18685304, 0.05429383]), + 'gaze_valid': True, + 'gaze_vergence': 170.77853393554688, + 'handbrake_input': False, + 'left_eye_openness': 0.8977140784263611, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96656799, -0.25294495, 0.04188538]), + 'left_gaze_origin': array([-3.10979486, 3.37795138, 0.06922455]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.281097412109375, + 'left_pupil_posn': array([-0.19335604, -0.08030701]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95935059, -0.28086853, 0.02713013]), + 'right_gaze_origin': array([-3.1936419 , -3.00424504, 0.0393631 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1993560791015625, + 'right_pupil_posn': array([-0.21433932, -0.15052736]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5118686556816101, + 'throttle_input': 0.0, + 'timestamp': 586.7105384655297, + 'timestamp_carla': 586711, + 'timestamp_device': 29959, + 'timestamp_stream': 586.7105384655297, + 'transform': [array([ 5.35934448e+00, -8.63690376e+00, -1.36116019e-03]), + array([ -0.02521023, -24.64623642, 0.06567384])]} +{'AngularVelocity': array([0.01350513, 0.06915704, 0.78835768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.313907504081726, + 'FR_Wheel_Angle': -1.5676994323730469, + 'Location': array([ -3.03106093, -21.60714722, 0.17293414]), + 'Rotation': array([-0.06658751, -4.7439599 , -0.00921631]), + 'Velocity': array([-0.39477694, 0.0362266 , 0.00101638]), + 'brake_input': 0.0, + 'camera_location': array([-5.76313257, 7.60624504, 1.31358087]), + 'camera_rotation': array([ -7.82709599, -30.70007324, -4.294765 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1016.8843994140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 836.355896 , -1681.46350098, 15.86978912]), + 'frame': 18058, + 'frame_number': 18058, + 'framesequence': 69126, + 'gaze_dir': array([ 0.96268463, -0.26798248, 0.03487396]), + 'gaze_origin': array([-3.15186071, 0.18632661, 0.05257263]), + 'gaze_valid': True, + 'gaze_vergence': 198.7691650390625, + 'handbrake_input': False, + 'left_eye_openness': 0.8915897011756897, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96566772, -0.25639343, 0.04150391]), + 'left_gaze_origin': array([-3.11007404, 3.37774968, 0.0670578 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2920989990234375, + 'left_pupil_posn': array([-0.19274747, -0.08144963]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95970154, -0.27957153, 0.02824402]), + 'right_gaze_origin': array([-3.19364786, -3.00509644, 0.03808746]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2014312744140625, + 'right_pupil_posn': array([-0.21497571, -0.15162611]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5171422362327576, + 'throttle_input': 0.0, + 'timestamp': 586.732629865408, + 'timestamp_carla': 586733, + 'timestamp_device': 29984, + 'timestamp_stream': 586.732629865408, + 'transform': [array([ 5.46925449e+00, -8.65758991e+00, -1.56482693e-03]), + array([ -0.02536049, -25.07217026, 0.06643676])]} +{'AngularVelocity': array([-0.00279219, -0.00846469, 1.32733881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.0625579357147217, + 'FR_Wheel_Angle': -2.9982430934906006, + 'Location': array([ -3.11224794, -21.59907913, 0.1730267 ]), + 'Rotation': array([-0.06878683, -4.68319893, -0.0083313 ]), + 'Velocity': array([-0.31761038, 0.03561947, 0.00100544]), + 'brake_input': 0.0, + 'camera_location': array([-5.76850557, 7.67161846, 1.31926227]), + 'camera_rotation': array([ -7.83811283, -30.5461235 , -4.34649277]), + 'current_gear_input': False, + 'focus_actor_dist': 1020.442626953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 844.41748047, -1683.71520996, 15.86260986]), + 'frame': 18059, + 'frame_number': 18059, + 'framesequence': 69128, + 'gaze_dir': array([ 0.9623642 , -0.26935577, 0.03376007]), + 'gaze_origin': array([-3.15184546, 0.18604662, 0.05213165]), + 'gaze_valid': True, + 'gaze_vergence': 240.38429260253906, + 'handbrake_input': False, + 'left_eye_openness': 0.888959527015686, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96504211, -0.25915527, 0.03875732]), + 'left_gaze_origin': array([-3.10998082, 3.37772369, 0.06601868]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2723846435546875, + 'left_pupil_posn': array([-0.19274747, -0.08193278]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95968628, -0.27955627, 0.02876282]), + 'right_gaze_origin': array([-3.19371033, -3.00563073, 0.03824463]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.193634033203125, + 'right_pupil_posn': array([-0.21558553, -0.1525501 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5219031572341919, + 'throttle_input': 0.0, + 'timestamp': 586.7544907666743, + 'timestamp_carla': 586755, + 'timestamp_device': 30001, + 'timestamp_stream': 586.7544907666743, + 'transform': [array([ 5.57771826e+00, -8.67923927e+00, -1.74459454e-03]), + array([-2.53946427e-02, -2.54937649e+01, 6.71081543e-02])]} +{'AngularVelocity': array([ 0.00248161, 0.01672367, -0.06663936]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.02514910697937, + 'FR_Wheel_Angle': -1.794727087020874, + 'Location': array([ -3.18510222, -21.591362 , 0.1731084 ]), + 'Rotation': array([-0.07085638, -4.62622261, -0.00701904]), + 'Velocity': array([-3.17601025e-01, 3.36400829e-02, 1.86796184e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.76734781, 7.70500803, 1.32398367]), + 'camera_rotation': array([ -7.84923935, -30.43669701, -4.32728052]), + 'current_gear_input': False, + 'focus_actor_dist': 1006.7368774414062, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 835.75042725, -1691.19384766, 15.8737793 ]), + 'frame': 18060, + 'frame_number': 18060, + 'framesequence': 69131, + 'gaze_dir': array([ 0.96195984, -0.27093506, 0.03244019]), + 'gaze_origin': array([-3.15178084, 0.18536912, 0.05256424]), + 'gaze_valid': True, + 'gaze_vergence': 218.36146545410156, + 'handbrake_input': False, + 'left_eye_openness': 0.8877213597297668, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96458435, -0.26087952, 0.03875732]), + 'left_gaze_origin': array([-3.1099031 , 3.37730432, 0.06661225]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2778167724609375, + 'left_pupil_posn': array([-0.19295996, -0.08246911]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95933533, -0.2809906 , 0.02612305]), + 'right_gaze_origin': array([-3.19365859, -3.00656605, 0.03851623]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.198486328125, + 'right_pupil_posn': array([-0.21555895, -0.15237534]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5258583426475525, + 'throttle_input': 0.0, + 'timestamp': 586.7770237661898, + 'timestamp_carla': 586778, + 'timestamp_device': 30026, + 'timestamp_stream': 586.7770237661898, + 'transform': [array([ 5.68908548e+00, -8.70270252e+00, -1.90937042e-03]), + array([-2.53604911e-02, -2.59278965e+01, 6.76879883e-02])]} +{'AngularVelocity': array([ 0.00071964, -0.00648798, 0.23892827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7801071405410767, + 'FR_Wheel_Angle': -0.7997732162475586, + 'Location': array([ -3.27160144, -21.58341599, 0.17322697]), + 'Rotation': array([-0.07422366, -4.57657003, -0.00631714]), + 'Velocity': array([-0.38972488, 0.03461273, 0.00070469]), + 'brake_input': 0.0, + 'camera_location': array([-5.76603699, 7.77118111, 1.33583415]), + 'camera_rotation': array([ -7.80372953, -30.16572762, -4.34903479]), + 'current_gear_input': False, + 'focus_actor_dist': 994.4097900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 828.59222412, -1699.0135498 , 15.88361359]), + 'frame': 18061, + 'frame_number': 18061, + 'framesequence': 69133, + 'gaze_dir': array([ 0.96186829, -0.2712326 , 0.03237152]), + 'gaze_origin': array([-3.1518352 , 0.18541108, 0.05213165]), + 'gaze_valid': True, + 'gaze_vergence': 216.6409912109375, + 'handbrake_input': False, + 'left_eye_openness': 0.8845144510269165, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96487427, -0.25990295, 0.03788757]), + 'left_gaze_origin': array([-3.10998082, 3.37677479, 0.06601868]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.280548095703125, + 'left_pupil_posn': array([-0.19315392, -0.08268189]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9588623 , -0.28256226, 0.02685547]), + 'right_gaze_origin': array([-3.19368911, -3.0059526 , 0.03824463]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.199005126953125, + 'right_pupil_posn': array([-0.21562964, -0.15286493]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.530161440372467, + 'throttle_input': 0.0, + 'timestamp': 586.7984586656094, + 'timestamp_carla': 586799, + 'timestamp_device': 30043, + 'timestamp_stream': 586.7984586656094, + 'transform': [array([ 5.79458857e+00, -8.72607422e+00, -2.04441068e-03]), + array([-2.52990201e-02, -2.63403816e+01, 6.81762695e-02])]} +{'AngularVelocity': array([-0.00229213, -0.03117452, 0.17941608]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8133753538131714, + 'FR_Wheel_Angle': -0.8044008016586304, + 'Location': array([ -3.39547825, -21.57243156, 0.17336895]), + 'Rotation': array([-0.07925751, -4.55908442, -0.0067749 ]), + 'Velocity': array([-0.58311445, 0.05206576, 0.00072633]), + 'brake_input': 0.0, + 'camera_location': array([-5.7560358 , 7.84304047, 1.35313797]), + 'camera_rotation': array([ -7.76393032, -29.87302971, -4.27903223]), + 'current_gear_input': False, + 'focus_actor_dist': 999.2266845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 836.64697266, -1697.70581055, 15.87518311]), + 'frame': 18062, + 'frame_number': 18062, + 'framesequence': 69136, + 'gaze_dir': array([ 0.96022797, -0.27700806, 0.03191376]), + 'gaze_origin': array([-3.15291214, 0.18550034, 0.04859925]), + 'gaze_valid': True, + 'gaze_vergence': 204.99331665039062, + 'handbrake_input': False, + 'left_eye_openness': 0.8705450296401978, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96340942, -0.26528931, 0.03791809]), + 'left_gaze_origin': array([-3.11113143, 3.37711787, 0.06234284]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2603759765625, + 'left_pupil_posn': array([-0.19575089, -0.08570039]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95704651, -0.28872681, 0.02590942]), + 'right_gaze_origin': array([-3.19469309, -3.00611734, 0.03485565]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.201202392578125, + 'right_pupil_posn': array([-0.21747327, -0.15544653]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5332010984420776, + 'throttle_input': 0.0, + 'timestamp': 586.820981066674, + 'timestamp_carla': 586822, + 'timestamp_device': 30068, + 'timestamp_stream': 586.820981066674, + 'transform': [array([ 5.90487432e+00, -8.75166035e+00, -2.18471512e-03]), + array([-2.52990201e-02, -2.67727871e+01, 6.86340258e-02])]} +{'AngularVelocity': array([-0.00206292, -0.0225029 , 0.2039828 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.775000274181366, + 'FR_Wheel_Angle': -0.7690274715423584, + 'Location': array([ -3.56130147, -21.55796051, 0.1735398 ]), + 'Rotation': array([-0.07882721, -4.51883125, -0.00656128]), + 'Velocity': array([-7.46418417e-01, 6.57815337e-02, 7.32917746e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.76555729, 7.90664911, 1.36519849]), + 'camera_rotation': array([ -7.72902775, -29.56552315, -4.24172068]), + 'current_gear_input': False, + 'focus_actor_dist': 1002.11181640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 844.21002197, -1701.87207031, 15.86915588]), + 'frame': 18063, + 'frame_number': 18063, + 'framesequence': 69139, + 'gaze_dir': array([ 0.98140717, -0.19132233, -0.00590515]), + 'gaze_origin': array([-3.12691283, 0.12695237, 0.02960816]), + 'gaze_valid': True, + 'gaze_vergence': 219.7571258544922, + 'handbrake_input': False, + 'left_eye_openness': 0.9184008836746216, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98394775, -0.17843628, -0.0019989 ]), + 'left_gaze_origin': array([-3.11171126, 3.32114887, 0.04688568]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1708984375, + 'left_pupil_posn': array([-0.12764543, -0.10730565]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9961873888969421, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97886658, -0.20420837, -0.0098114 ]), + 'right_gaze_origin': array([-3.1421144 , -3.06724405, 0.01233063]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2332305908203125, + 'right_pupil_posn': array([-0.14531511, -0.17381978]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5367717742919922, + 'throttle_input': 0.0, + 'timestamp': 586.8433539681137, + 'timestamp_carla': 586844, + 'timestamp_device': 30093, + 'timestamp_stream': 586.8433539681137, + 'transform': [array([ 6.01380968e+00, -8.77807808e+00, -2.30987533e-03]), + array([-2.53331698e-02, -2.72011280e+01, 6.90307543e-02])]} +{'AngularVelocity': array([0.0023861 , 0.00773569, 0.40395966]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.020218849182129, + 'FR_Wheel_Angle': -2.4460511207580566, + 'Location': array([ -3.76142597, -21.5404911 , 0.17374706]), + 'Rotation': array([-0.08465336, -4.45742893, -0.00714111]), + 'Velocity': array([-1.00085509e+00, 9.32168365e-02, 3.38010781e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.77847481, 7.97723484, 1.37617028]), + 'camera_rotation': array([ -7.7417593 , -29.25348663, -4.27506828]), + 'current_gear_input': False, + 'focus_actor_dist': 782.0523071289062, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 611.5569458 , -1701.78015137, 16.22582245]), + 'frame': 18064, + 'frame_number': 18064, + 'framesequence': 69141, + 'gaze_dir': array([ 0.98397827, -0.17721558, -0.01428223]), + 'gaze_origin': array([-3.2081728 , 0.12376863, 0.04757309]), + 'gaze_valid': True, + 'gaze_vergence': 247.11563110351562, + 'handbrake_input': False, + 'left_eye_openness': 0.9155194759368896, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98620605, -0.16497803, -0.01235962]), + 'left_gaze_origin': array([-3.13076639, 3.30925465, 0.04967194]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1867218017578125, + 'left_pupil_posn': array([-0.1146515 , -0.11104953]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9857743382453918, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98175049, -0.18945312, -0.01620483]), + 'right_gaze_origin': array([-3.28557897, -3.06171727, 0.04547425]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2031402587890625, + 'right_pupil_posn': array([-0.1437583 , -0.18225443]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.539426863193512, + 'throttle_input': 0.0, + 'timestamp': 586.8656477667391, + 'timestamp_carla': 586866, + 'timestamp_device': 30109, + 'timestamp_stream': 586.8656477667391, + 'transform': [array([ 6.12166977e+00, -8.80533218e+00, -2.42927554e-03]), + array([-2.54219621e-02, -2.76264496e+01, 6.93969727e-02])]} +{'AngularVelocity': array([-0.02111237, -0.04679814, 1.43754208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.00998067855835, + 'FR_Wheel_Angle': -6.145535469055176, + 'Location': array([ -3.98144221, -21.51766014, 0.17390315]), + 'Rotation': array([-0.07168283, -4.20047235, -0.00927734]), + 'Velocity': array([-8.74560595e-01, 1.09775200e-01, 7.38658884e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.77906227, 8.03956223, 1.39302945]), + 'camera_rotation': array([ -7.71505356, -28.94960213, -4.27058554]), + 'current_gear_input': False, + 'focus_actor_dist': 744.3623657226562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 575.00280762, -1705.17883301, 16.13655853]), + 'frame': 18065, + 'frame_number': 18065, + 'framesequence': 69144, + 'gaze_dir': array([ 0.98191071, -0.18849945, -0.01717377]), + 'gaze_origin': array([-3.12750554, 0.123555 , 0.02643891]), + 'gaze_valid': True, + 'gaze_vergence': 1437.6790771484375, + 'handbrake_input': False, + 'left_eye_openness': 0.9254087805747986, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98228455, -0.18664551, -0.01641846]), + 'left_gaze_origin': array([-3.11817646, 3.31366587, 0.04484558]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1466522216796875, + 'left_pupil_posn': array([-0.11776853, -0.11260176]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9623438715934753, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98153687, -0.19035339, -0.01792908]), + 'right_gaze_origin': array([-3.13683486, -3.06655598, 0.00803223]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.223175048828125, + 'right_pupil_posn': array([-0.14866656, -0.18101978]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5414777398109436, + 'throttle_input': 0.0, + 'timestamp': 586.887989167124, + 'timestamp_carla': 586889, + 'timestamp_device': 30134, + 'timestamp_stream': 586.887989167124, + 'transform': [array([ 6.22896147e+00, -8.83347797e+00, -2.54346849e-03]), + array([-2.5565397e-02, -2.8050663e+01, 6.9732666e-02])]} +{'AngularVelocity': array([-0.04098095, -0.01906775, 1.77483094]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.848126411437988, + 'FR_Wheel_Angle': -8.328840255737305, + 'Location': array([ -4.16425562, -21.49425697, 0.17404567]), + 'Rotation': array([-0.06463408, -3.77453732, -0.00720215]), + 'Velocity': array([-6.93217516e-01, 1.02645248e-01, 4.69140999e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.75792933, 8.10687351, 1.40407836]), + 'camera_rotation': array([ -7.62665033, -28.68509293, -4.31128788]), + 'current_gear_input': False, + 'focus_actor_dist': 730.8416137695312, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 568.75549316, -1717.04443359, 16.14688873]), + 'frame': 18066, + 'frame_number': 18066, + 'framesequence': 69147, + 'gaze_dir': array([ 0.9801178 , -0.19784546, -0.01462555]), + 'gaze_origin': array([-3.13937545, 0.12814561, 0.02853394]), + 'gaze_valid': True, + 'gaze_vergence': 675.2308349609375, + 'handbrake_input': False, + 'left_eye_openness': 0.9256578683853149, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98042297, -0.19650269, -0.01249695]), + 'left_gaze_origin': array([-3.1176424 , 3.31926274, 0.04432526]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1827545166015625, + 'left_pupil_posn': array([-0.12475127, -0.11243618]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9605128169059753, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97981262, -0.19918823, -0.01675415]), + 'right_gaze_origin': array([-3.16110849, -3.06297159, 0.01274262]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3052825927734375, + 'right_pupil_posn': array([-0.15444064, -0.1811986 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5431623458862305, + 'throttle_input': 0.0, + 'timestamp': 586.9101488664746, + 'timestamp_carla': 586911, + 'timestamp_device': 30159, + 'timestamp_stream': 586.9101488664746, + 'transform': [array([ 6.33452702e+00, -8.86216068e+00, -2.65071867e-03]), + array([-2.57839635e-02, -2.84691391e+01, 7.00378418e-02])]} +{'AngularVelocity': array([-3.76981683e-02, -1.02241558e-03, 1.30697942e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.798046112060547, + 'FR_Wheel_Angle': -6.827893257141113, + 'Location': array([ -4.3192215 , -21.47336197, 0.17419906]), + 'Rotation': array([-6.25030547e-02, -3.33032322e+00, -2.68554711e-03]), + 'Velocity': array([-0.48565409, 0.06540193, 0.00059725]), + 'brake_input': 0.0, + 'camera_location': array([-5.74053478, 8.16125393, 1.41464961]), + 'camera_rotation': array([ -7.51560497, -28.50590324, -4.45157194]), + 'current_gear_input': False, + 'focus_actor_dist': 746.5877685546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 589.41687012, -1716.94628906, 16.12641907]), + 'frame': 18067, + 'frame_number': 18067, + 'framesequence': 69150, + 'gaze_dir': array([ 0.97913361, -0.20284271, -0.01096344]), + 'gaze_origin': array([-3.15680385, 0.13363419, 0.02977219]), + 'gaze_valid': True, + 'gaze_vergence': 43.16727066040039, + 'handbrake_input': False, + 'left_eye_openness': 0.9223722219467163, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97923279, -0.20259094, -0.00648499]), + 'left_gaze_origin': array([-3.11489892, 3.32443571, 0.04421692]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2833709716796875, + 'left_pupil_posn': array([-0.12950319, -0.1117692 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9722645878791809, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97903442, -0.20309448, -0.01544189]), + 'right_gaze_origin': array([-3.19870925, -3.05716705, 0.01532745]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2108001708984375, + 'right_pupil_posn': array([-0.16050738, -0.18456173]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5447188019752502, + 'throttle_input': 0.0, + 'timestamp': 586.932420168072, + 'timestamp_carla': 586933, + 'timestamp_device': 30184, + 'timestamp_stream': 586.932420168072, + 'transform': [array([ 6.43973255e+00, -8.89170742e+00, -2.75278091e-03]), + array([-2.60298494e-02, -2.88872757e+01, 7.03125075e-02])]} +{'AngularVelocity': array([ 0.00095691, 0.02456122, -0.2511833 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.467233180999756, + 'FR_Wheel_Angle': -6.329427719116211, + 'Location': array([ -4.40701866, -21.46267319, 0.17427142]), + 'Rotation': array([-6.06657378e-02, -3.17373753e+00, -1.89208984e-03]), + 'Velocity': array([-2.81040430e-01, 3.56147699e-02, 2.79283529e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.73233128, 8.21492863, 1.42378926]), + 'camera_rotation': array([ -7.48803139, -28.31953621, -4.427001 ]), + 'current_gear_input': False, + 'focus_actor_dist': 768.7842407226562, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 615.3560791 , -1712.79418945, 16.22582245]), + 'frame': 18068, + 'frame_number': 18068, + 'framesequence': 69152, + 'gaze_dir': array([ 0.98000336, -0.19864655, -0.00809479]), + 'gaze_origin': array([-3.15152359, 0.13653947, 0.02964936]), + 'gaze_valid': True, + 'gaze_vergence': 93.62281799316406, + 'handbrake_input': False, + 'left_eye_openness': 0.9164941310882568, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97979736, -0.19992065, -0.00170898]), + 'left_gaze_origin': array([-3.11448836, 3.32836461, 0.04524994]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.23089599609375, + 'left_pupil_posn': array([-0.13028014, -0.1103642 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9650100469589233, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98020935, -0.19737244, -0.01448059]), + 'right_gaze_origin': array([-3.18855906, -3.05528593, 0.01404877]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.267181396484375, + 'right_pupil_posn': array([-0.16078466, -0.18189609]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5460554957389832, + 'throttle_input': 0.0, + 'timestamp': 586.953633967787, + 'timestamp_carla': 586954, + 'timestamp_device': 30201, + 'timestamp_stream': 586.953633967787, + 'transform': [array([ 6.53908253e+00, -8.92048454e+00, -2.83903116e-03]), + array([-2.62415856e-02, -2.92831306e+01, 7.05566406e-02])]} +{'AngularVelocity': array([ 0.00405561, 0.04897691, -0.3799744 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.368997573852539, + 'FR_Wheel_Angle': -8.899166107177734, + 'Location': array([ -4.45140982, -21.45676041, 0.17432018]), + 'Rotation': array([-0.06350709, -3.09323144, -0.00326538]), + 'Velocity': array([-1.50073320e-01, 2.17733849e-02, -4.00066383e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.73528242, 8.27208424, 1.43624723]), + 'camera_rotation': array([ -7.53595209, -28.12078094, -4.23768425]), + 'current_gear_input': False, + 'focus_actor_dist': 787.891845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 635.77679443, -1703.27990723, 16.07579803]), + 'frame': 18069, + 'frame_number': 18069, + 'framesequence': 69155, + 'gaze_dir': array([ 0.97818756, -0.20738983, -0.00184631]), + 'gaze_origin': array([-3.15277433, 0.14278412, 0.03202896]), + 'gaze_valid': True, + 'gaze_vergence': 132.34725952148438, + 'handbrake_input': False, + 'left_eye_openness': 0.9079601168632507, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97924805, -0.20246887, 0.00788879]), + 'left_gaze_origin': array([-3.11538267, 3.33507538, 0.04748688]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.325958251953125, + 'left_pupil_posn': array([-0.13996041, -0.10846317]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9621065855026245, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97712708, -0.21231079, -0.01158142]), + 'right_gaze_origin': array([-3.19016576, -3.04950738, 0.01657104]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2323455810546875, + 'right_pupil_posn': array([-0.16567779, -0.1769793 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.547080934047699, + 'throttle_input': 0.0, + 'timestamp': 586.9814299680293, + 'timestamp_carla': 586982, + 'timestamp_device': 30226, + 'timestamp_stream': 586.9814299680293, + 'transform': [array([ 6.66789246e+00, -8.95905113e+00, -3.00823199e-03]), + array([-2.65830941e-02, -2.97977772e+01, 7.08618090e-02])]} +{'AngularVelocity': array([0.04337565, 0.02440636, 0.75089574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.729836463928223, + 'FR_Wheel_Angle': -10.745892524719238, + 'Location': array([ -4.47899675, -21.45271873, 0.17438109]), + 'Rotation': array([-0.06929909, -3.00167871, -0.0045166 ]), + 'Velocity': array([-1.24912307e-01, 2.38715485e-02, 1.06792446e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.72244787, 8.32418728, 1.45268512]), + 'camera_rotation': array([ -7.53783035, -27.90146255, -4.03133345]), + 'current_gear_input': False, + 'focus_actor_dist': 818.36572265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 670.52313232, -1699.56677246, 16.04011536]), + 'frame': 18070, + 'frame_number': 18070, + 'framesequence': 69158, + 'gaze_dir': array([ 0.97769165, -0.20970154, -0.00532532]), + 'gaze_origin': array([-3.15407801, 0.14469987, 0.03101501]), + 'gaze_valid': True, + 'gaze_vergence': 67.41114807128906, + 'handbrake_input': False, + 'left_eye_openness': 0.9109323620796204, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97731018, -0.21173096, 0.00416565]), + 'left_gaze_origin': array([-3.11614847, 3.33697391, 0.04513397]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2093658447265625, + 'left_pupil_posn': array([-0.13973284, -0.11112905]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9606925845146179, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97807312, -0.20767212, -0.01481628]), + 'right_gaze_origin': array([-3.19200754, -3.04757404, 0.01689606]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2562255859375, + 'right_pupil_posn': array([-0.17025781, -0.17852283]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.547813355922699, + 'throttle_input': 0.0, + 'timestamp': 587.0037078671157, + 'timestamp_carla': 587004, + 'timestamp_device': 30251, + 'timestamp_stream': 587.0037078671157, + 'transform': [array([ 6.77000713e+00, -8.99059105e+00, -3.08847427e-03]), + array([-2.68289819e-02, -3.02069168e+01, 7.11059570e-02])]} +{'AngularVelocity': array([0.08859739, 0.12588783, 1.70462894]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.33339786529541, + 'FR_Wheel_Angle': -11.022855758666992, + 'Location': array([ -4.51600933, -21.44738388, 0.17447577]), + 'Rotation': array([-0.07961951, -2.8535161 , -0.00842285]), + 'Velocity': array([-3.55085790e-01, 6.24905899e-02, -1.75476071e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.70436621, 8.37463951, 1.45802581]), + 'camera_rotation': array([ -7.46267796, -27.71053696, -3.9057281 ]), + 'current_gear_input': False, + 'focus_actor_dist': 802.7796020507812, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 660.88903809, -1707.75585938, 16.05252075]), + 'frame': 18071, + 'frame_number': 18071, + 'framesequence': 69161, + 'gaze_dir': array([ 0.97618866, -0.21661377, -0.00579071]), + 'gaze_origin': array([-3.15465117, 0.14644395, 0.03020096]), + 'gaze_valid': True, + 'gaze_vergence': 80.52019500732422, + 'handbrake_input': False, + 'left_eye_openness': 0.9126404523849487, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97665405, -0.21473694, 0.00271606]), + 'left_gaze_origin': array([-3.11654973, 3.34013987, 0.04418945]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.270904541015625, + 'left_pupil_posn': array([-0.14576399, -0.11175478]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9703176021575928, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97572327, -0.2184906 , -0.01429749]), + 'right_gaze_origin': array([-3.19275212, -3.04725218, 0.01621247]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2394561767578125, + 'right_pupil_posn': array([-0.17157137, -0.17965698]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.01190203707665205, + 'timestamp': 587.0266310684383, + 'timestamp_carla': 587027, + 'timestamp_device': 30276, + 'timestamp_stream': 587.0266310684383, + 'transform': [array([ 6.87441444e+00, -9.02412796e+00, -3.23312753e-03]), + array([-2.73753963e-02, -3.06276550e+01, 7.15637133e-02])]} +{'AngularVelocity': array([ 0.0216822 , -0.0230223 , 3.27739906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.233375549316406, + 'FR_Wheel_Angle': -10.952689170837402, + 'Location': array([ -4.66950512, -21.42547798, 0.17467067]), + 'Rotation': array([-0.09042487, -2.26953173, -0.01132202]), + 'Velocity': array([-7.63778746e-01, 1.27160162e-01, 5.48954005e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.68315744, 8.43965149, 1.46859181]), + 'camera_rotation': array([ -7.43085623, -27.54328918, -3.88022256]), + 'current_gear_input': False, + 'focus_actor_dist': 808.1681518554688, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 671.41638184, -1711.82714844, 16.04354095]), + 'frame': 18072, + 'frame_number': 18072, + 'framesequence': 69163, + 'gaze_dir': array([ 0.9757309 , -0.21884918, -0.00235748]), + 'gaze_origin': array([-3.15522933, 0.14765473, 0.0310791 ]), + 'gaze_valid': True, + 'gaze_vergence': 368.888671875, + 'handbrake_input': False, + 'left_eye_openness': 0.8989222645759583, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97662354, -0.21490479, 0.00189209]), + 'left_gaze_origin': array([-3.11725783, 3.34207797, 0.04667054]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2336883544921875, + 'left_pupil_posn': array([-0.14855868, -0.10766184]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9565972685813904, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97483826, -0.22279358, -0.00660706]), + 'right_gaze_origin': array([-3.19320083, -3.04676843, 0.01548767]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2394866943359375, + 'right_pupil_posn': array([-0.17193359, -0.18059111]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.03967345505952835, + 'timestamp': 587.0485358685255, + 'timestamp_carla': 587049, + 'timestamp_device': 30293, + 'timestamp_stream': 587.0485358685255, + 'transform': [array([ 6.97362661e+00, -9.05708122e+00, -3.33238603e-03]), + array([-2.77373958e-02, -3.10293808e+01, 7.18689039e-02])]} +{'AngularVelocity': array([-0.00721011, -0.02679381, 3.19901514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.647513389587402, + 'FR_Wheel_Angle': -8.016536712646484, + 'Location': array([ -4.83120823, -21.40483665, 0.17483482]), + 'Rotation': array([-0.08496755, -1.65985096, -0.00686645]), + 'Velocity': array([-0.89501011, 0.12417173, 0.00092214]), + 'brake_input': 0.0, + 'camera_location': array([-5.65946436, 8.51169395, 1.46906698]), + 'camera_rotation': array([ -7.42268705, -27.28268051, -3.82814193]), + 'current_gear_input': False, + 'focus_actor_dist': 830.37744140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 696.93054199, -1707.35693359, 16.016716 ]), + 'frame': 18073, + 'frame_number': 18073, + 'framesequence': 69167, + 'gaze_dir': array([ 0.98218536, -0.18695831, 0.00489807]), + 'gaze_origin': array([-3.14335775, 0.11620865, 0.03966446]), + 'gaze_valid': True, + 'gaze_vergence': 138.1498565673828, + 'handbrake_input': False, + 'left_eye_openness': 0.8988526463508606, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98472595, -0.1733551 , 0.01609802]), + 'left_gaze_origin': array([-3.12606835, 3.31358957, 0.06209717]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2743377685546875, + 'left_pupil_posn': array([-0.12128913, -0.09853685]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9575708508491516, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97964478, -0.20056152, -0.00630188]), + 'right_gaze_origin': array([-3.16064763, -3.08117223, 0.01723175]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2054901123046875, + 'right_pupil_posn': array([-0.13383293, -0.16779339]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.051590751856565475, + 'timestamp': 587.0731960684061, + 'timestamp_carla': 587074, + 'timestamp_device': 30326, + 'timestamp_stream': 587.0731960684061, + 'transform': [array([ 7.08500528e+00, -9.09591866e+00, -3.55293276e-03]), + array([-2.83589438e-02, -3.14843559e+01, 7.25707859e-02])]} +{'AngularVelocity': array([-0.00416668, -0.0442792 , 1.15933764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.093806028366089, + 'FR_Wheel_Angle': -2.328490734100342, + 'Location': array([ -5.03314734, -21.38784409, 0.1749683 ]), + 'Rotation': array([-0.0730557 , -1.19354248, 0.00263787]), + 'Velocity': array([-0.81652218, 0.0536777 , 0.0011323 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.62472773, 8.60026169, 1.47958839]), + 'camera_rotation': array([ -7.4152832 , -26.92562675, -3.66643906]), + 'current_gear_input': False, + 'focus_actor_dist': 884.3518676757812, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 741.83862305, -1662.61743164, 15.95665741]), + 'frame': 18074, + 'frame_number': 18074, + 'framesequence': 69169, + 'gaze_dir': array([ 0.98938751, -0.14170074, 0.0280304 ]), + 'gaze_origin': array([-3.09103417, 0.06809159, 0.04815674]), + 'gaze_valid': True, + 'gaze_vergence': 209.88035583496094, + 'handbrake_input': False, + 'left_eye_openness': 0.9497551321983337, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99142456, -0.12705994, 0.03022766]), + 'left_gaze_origin': array([-2.99122334, 3.25661182, 0.04479065]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.252685546875, + 'left_pupil_posn': array([-0.06562865, -0.07331288]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9834128022193909, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98735046, -0.15634155, 0.02583313]), + 'right_gaze_origin': array([-3.19084477, -3.1204288 , 0.05152283]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.201263427734375, + 'right_pupil_posn': array([-0.0903464, -0.1450305]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.059525445103645325, + 'timestamp': 587.0991206653416, + 'timestamp_carla': 587100, + 'timestamp_device': 30343, + 'timestamp_stream': 587.0991206653416, + 'transform': [array([ 7.19845009e+00, -9.13543320e+00, -3.67063517e-03]), + array([-2.89326794e-02, -3.19457054e+01, 7.27844164e-02])]} +{'AngularVelocity': array([ 0.01433357, -0.01062119, -0.11191151]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5329470038414001, + 'FR_Wheel_Angle': 0.4611451029777527, + 'Location': array([ -5.20689678, -21.38191414, 0.17509635]), + 'Rotation': array([-0.06692219, -1.10919178, 0.00232867]), + 'Velocity': array([-0.68156278, 0.01085168, 0.0007704 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.53515291, 8.81984615, 1.48728061]), + 'camera_rotation': array([ -7.3663516 , -26.0556736 , -3.51430631]), + 'current_gear_input': False, + 'focus_actor_dist': 1090.505859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 920.98138428, -1542.80761719, 15.73754883]), + 'frame': 18075, + 'frame_number': 18075, + 'framesequence': 69173, + 'gaze_dir': array([ 0.99097443, -0.13159943, 0.02314758]), + 'gaze_origin': array([-3.21206307, 0.07476959, 0.08707963]), + 'gaze_valid': True, + 'gaze_vergence': 25.648225784301758, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99082947, -0.13096619, 0.03276062]), + 'left_gaze_origin': array([-3.24360347, 3.26853943, 0.12412262]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.236663818359375, + 'left_pupil_posn': array([-0.06775039, -0.0709039 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99111938, -0.13223267, 0.01353455]), + 'right_gaze_origin': array([-3.18052244, -3.11900043, 0.05003662]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.203216552734375, + 'right_pupil_posn': array([-0.09275818, -0.14321756]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.059525445103645325, + 'timestamp': 587.1278545670211, + 'timestamp_carla': 587128, + 'timestamp_device': 30376, + 'timestamp_stream': 587.1278545670211, + 'transform': [array([ 7.32243109e+00, -9.18048954e+00, -3.96118173e-03]), + array([-2.99367178e-02, -3.24536476e+01, 7.36083910e-02])]} +{'AngularVelocity': array([0.0087347 , 0.00713992, 0.16311263]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.045673295855522156, + 'FR_Wheel_Angle': 0.045702602714300156, + 'Location': array([ -5.35073662, -21.3794136 , 0.17522617]), + 'Rotation': array([-0.06591816, -1.11712635, -0.00259399]), + 'Velocity': array([-5.61679780e-01, 1.04365088e-02, 2.16388697e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.45671129, 8.9949255 , 1.48732996]), + 'camera_rotation': array([ -7.36656332, -25.37537956, -3.50735879]), + 'current_gear_input': False, + 'focus_actor_dist': 1059.816162109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 887.6973877 , -1535.49902344, 15.76791382]), + 'frame': 18076, + 'frame_number': 18076, + 'framesequence': 69176, + 'gaze_dir': array([ 0.99105072, -0.13184357, 0.01700592]), + 'gaze_origin': array([-3.21469355, 0.07904892, 0.0907074 ]), + 'gaze_valid': True, + 'gaze_vergence': 50.16001892089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99110413, -0.12998962, 0.02810669]), + 'left_gaze_origin': array([-3.25089145, 3.27445531, 0.12971345]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1273040771484375, + 'left_pupil_posn': array([-0.07242703, -0.07104552]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99099731, -0.13369751, 0.00590515]), + 'right_gaze_origin': array([-3.17849588, -3.11635756, 0.05170136]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.169891357421875, + 'right_pupil_posn': array([-0.0941996 , -0.14337242]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.059525445103645325, + 'timestamp': 587.1546764671803, + 'timestamp_carla': 587155, + 'timestamp_device': 30401, + 'timestamp_stream': 587.1546764671803, + 'transform': [array([ 7.43452215e+00, -9.22122383e+00, -4.04603966e-03]), + array([-3.03328689e-02, -3.29107780e+01, 7.37609789e-02])]} +{'AngularVelocity': array([0.01238153, 0.03431625, 0.40352595]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06969962269067764, + 'FR_Wheel_Angle': 0.0710044577717781, + 'Location': array([ -5.47518826, -21.37707901, 0.17536926]), + 'Rotation': array([-0.07107495, -1.11010754, -0.00366211]), + 'Velocity': array([-5.66070855e-01, 1.12243649e-02, 1.60846714e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.39586258, 9.20053673, 1.4979037 ]), + 'camera_rotation': array([ -7.40824795, -24.6353054 , -3.21070051]), + 'current_gear_input': False, + 'focus_actor_dist': 1005.1181030273438, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 839.24462891, -1552.72119141, 15.82183075]), + 'frame': 18077, + 'frame_number': 18077, + 'framesequence': 69179, + 'gaze_dir': array([ 0.9905014 , -0.13549042, 0.02162933]), + 'gaze_origin': array([-3.22364902, 0.08384629, 0.09742585]), + 'gaze_valid': True, + 'gaze_vergence': 190.6132049560547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99084473, -0.1318512 , 0.02861023]), + 'left_gaze_origin': array([-3.23496127, 3.27923751, 0.12797546]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2414703369140625, + 'left_pupil_posn': array([-0.07740629, -0.06632817]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99015808, -0.13912964, 0.01464844]), + 'right_gaze_origin': array([-3.21233678, -3.11154509, 0.06687623]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17938232421875, + 'right_pupil_posn': array([-0.09784895, -0.1390599 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.059525445103645325, + 'timestamp': 587.1807787679136, + 'timestamp_carla': 587181, + 'timestamp_device': 30426, + 'timestamp_stream': 587.1807787679136, + 'transform': [array([ 7.54412603e+00, -9.26317310e+00, -4.14495450e-03]), + array([-3.03670187e-02, -3.33628082e+01, 7.40661621e-02])]} +{'AngularVelocity': array([-8.03279225e-04, -6.37850026e-03, 1.06909847e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07101593911647797, + 'FR_Wheel_Angle': 0.07106193900108337, + 'Location': array([ -5.60884809, -21.3746376 , 0.1755141 ]), + 'Rotation': array([-0.07119789, -1.09484851, -0.00387573]), + 'Velocity': array([-0.5468908 , 0.00955061, 0.00092345]), + 'brake_input': 0.0, + 'camera_location': array([-5.39586258, 9.20053673, 1.4979037 ]), + 'camera_rotation': array([ -7.40824795, -24.6353054 , -3.21070051]), + 'current_gear_input': False, + 'focus_actor_dist': 1044.0968017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 877.22564697, -1532.93383789, 15.77735901]), + 'frame': 18078, + 'frame_number': 18078, + 'framesequence': 69183, + 'gaze_dir': array([ 0.9900589 , -0.13885498, 0.02024841]), + 'gaze_origin': array([-3.21776533, 0.08635712, 0.09515152]), + 'gaze_valid': True, + 'gaze_vergence': 117.20740509033203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99028015, -0.13606262, 0.02862549]), + 'left_gaze_origin': array([-3.21964884, 3.28209686, 0.12191468]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2628021240234375, + 'left_pupil_posn': array([-0.08011442, -0.06851196]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98983765, -0.14164734, 0.01187134]), + 'right_gaze_origin': array([-3.21588135, -3.10938287, 0.06838837]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2206573486328125, + 'right_pupil_posn': array([-0.10074443, -0.13876069]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.212052565068, + 'timestamp_carla': 587213, + 'timestamp_device': 30459, + 'timestamp_stream': 587.212052565068, + 'transform': [array([ 7.67405796e+00, -9.31396961e+00, -4.10896307e-03]), + array([-2.98479255e-02, -3.38997879e+01, 7.39135593e-02])]} +{'AngularVelocity': array([-0.00114436, -0.03588941, -0.01973492]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07086160778999329, + 'FR_Wheel_Angle': 0.07092345505952835, + 'Location': array([ -5.77689219, -21.37140846, 0.17572956]), + 'Rotation': array([-0.07586291, -1.09619129, -0.0038147 ]), + 'Velocity': array([-6.71992660e-01, 1.28152836e-02, 6.56375894e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.32260275, 9.39132404, 1.52487946]), + 'camera_rotation': array([ -7.28495646, -23.88498688, -2.82028151]), + 'current_gear_input': False, + 'focus_actor_dist': 1030.5306396484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 872.30090332, -1546.88037109, 15.78712463]), + 'frame': 18079, + 'frame_number': 18079, + 'framesequence': 69186, + 'gaze_dir': array([ 0.98976135, -0.14111328, 0.01956177]), + 'gaze_origin': array([-3.21402597, 0.08784866, 0.0941536 ]), + 'gaze_valid': True, + 'gaze_vergence': 174.78549194335938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99003601, -0.13825989, 0.02626038]), + 'left_gaze_origin': array([-3.21114969, 3.28376484, 0.11894074]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.26727294921875, + 'left_pupil_posn': array([-0.08195388, -0.06868112]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98948669, -0.14396667, 0.01286316]), + 'right_gaze_origin': array([-3.21690226, -3.10806751, 0.06936646]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2200164794921875, + 'right_pupil_posn': array([-0.10239244, -0.13914883]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.2396740652621, + 'timestamp_carla': 587240, + 'timestamp_device': 30484, + 'timestamp_stream': 587.2396740652621, + 'transform': [array([ 7.78577137e+00, -9.35785770e+00, -4.08285111e-03]), + array([-2.95747183e-02, -3.43600006e+01, 7.35778660e-02])]} +{'AngularVelocity': array([0.00788905, 0.08574219, 0.86244923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0708727315068245, + 'FR_Wheel_Angle': 0.07089054584503174, + 'Location': array([ -5.92209959, -21.36860085, 0.17583862]), + 'Rotation': array([-0.07211313, -1.09460437, -0.0038147 ]), + 'Velocity': array([-0.68895721, 0.01478813, 0.00110991]), + 'brake_input': 0.0, + 'camera_location': array([-5.24173069, 9.58233261, 1.53884637]), + 'camera_rotation': array([ -7.15898037, -23.20775223, -2.68710876]), + 'current_gear_input': False, + 'focus_actor_dist': 1051.7510986328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 894.378479 , -1533.93579102, 15.76076508]), + 'frame': 18080, + 'frame_number': 18080, + 'framesequence': 69190, + 'gaze_dir': array([ 0.98970032, -0.14164734, 0.01912689]), + 'gaze_origin': array([-3.20974207, 0.08886567, 0.0931427 ]), + 'gaze_valid': True, + 'gaze_vergence': 230.59303283691406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99015808, -0.1375885 , 0.02546692]), + 'left_gaze_origin': array([-3.20234561, 3.28492904, 0.11653747]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2698974609375, + 'left_pupil_posn': array([-0.08327043, -0.06871104]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98924255, -0.14570618, 0.01278687]), + 'right_gaze_origin': array([-3.21713877, -3.10719776, 0.06974793]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2194976806640625, + 'right_pupil_posn': array([-0.10274732, -0.13921368]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.2711008675396, + 'timestamp_carla': 587272, + 'timestamp_device': 30518, + 'timestamp_stream': 587.2711008675396, + 'transform': [array([ 7.91295433e+00, -9.40985775e+00, -4.02433379e-03]), + array([-2.88438872e-02, -3.48883095e+01, 7.33337328e-02])]} +{'AngularVelocity': array([-0.0042645 , -0.01814561, 1.23729944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0709117203950882, + 'FR_Wheel_Angle': 0.07089909166097641, + 'Location': array([ -6.05270433, -21.36583519, 0.17597289]), + 'Rotation': array([-0.07119789, -1.09210193, -0.00357056]), + 'Velocity': array([-0.62239516, 0.01254366, 0.00069695]), + 'brake_input': 0.0, + 'camera_location': array([-5.17967224, 9.78879738, 1.54851866]), + 'camera_rotation': array([ -7.10868979, -22.51710129, -2.52554154]), + 'current_gear_input': False, + 'focus_actor_dist': 1071.12255859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 913.59143066, -1520.33276367, 15.73699951]), + 'frame': 18081, + 'frame_number': 18081, + 'framesequence': 69194, + 'gaze_dir': array([ 0.98937988, -0.14369202, 0.01917267]), + 'gaze_origin': array([-3.20833659, 0.09024812, 0.09264145]), + 'gaze_valid': True, + 'gaze_vergence': 247.25897216796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99032593, -0.1363678 , 0.02555847]), + 'left_gaze_origin': array([-3.1997242 , 3.28605366, 0.11587983]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2597198486328125, + 'left_pupil_posn': array([-0.08586729, -0.06871581]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98843384, -0.15101624, 0.01278687]), + 'right_gaze_origin': array([-3.21694946, -3.10555744, 0.06940307]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2237701416015625, + 'right_pupil_posn': array([-0.10345709, -0.13934386]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.3040138669312, + 'timestamp_carla': 587305, + 'timestamp_device': 30551, + 'timestamp_stream': 587.3040138669312, + 'transform': [array([ 8.04525757e+00, -9.46560764e+00, -3.97926336e-03]), + array([-2.80106049e-02, -3.54406700e+01, 7.30590671e-02])]} +{'AngularVelocity': array([-0.00078642, -0.03522945, -0.01470692]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07087764143943787, + 'FR_Wheel_Angle': 0.07094942033290863, + 'Location': array([ -6.22312498, -21.36261177, 0.17617965]), + 'Rotation': array([-0.07244781, -1.08599842, -0.00320435]), + 'Velocity': array([-0.66895926, 0.0126369 , 0.00122352]), + 'brake_input': 0.0, + 'camera_location': array([-5.11270761, 9.9946003 , 1.54335904]), + 'camera_rotation': array([ -7.10860109, -21.77797699, -2.16775537]), + 'current_gear_input': False, + 'focus_actor_dist': 1083.490234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 927.81030273, -1511.75024414, 15.71990967]), + 'frame': 18082, + 'frame_number': 18082, + 'framesequence': 69198, + 'gaze_dir': array([ 0.98877716, -0.14809418, 0.01612091]), + 'gaze_origin': array([-3.20713067, 0.09331818, 0.09321595]), + 'gaze_valid': True, + 'gaze_vergence': 257.37921142578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99014282, -0.13842773, 0.02114868]), + 'left_gaze_origin': array([-3.19735885, 3.2910676 , 0.11641694]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2949981689453125, + 'left_pupil_posn': array([-0.09161973, -0.06857967]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9874115 , -0.15776062, 0.01109314]), + 'right_gaze_origin': array([-3.21690226, -3.10443139, 0.07001495]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.22344970703125, + 'right_pupil_posn': array([-0.10494256, -0.14048433]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5479415655136108, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.3369318656623, + 'timestamp_carla': 587338, + 'timestamp_device': 30584, + 'timestamp_stream': 587.3369318656623, + 'transform': [array([ 8.17658520e+00, -9.52256775e+00, -3.93592846e-03]), + array([-2.71568298e-02, -3.59916534e+01, 7.27844164e-02])]} +{'AngularVelocity': array([-0.00034454, 0.00459099, -0.01382389]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07096100598573685, + 'FR_Wheel_Angle': 0.07101262360811234, + 'Location': array([ -6.34738922, -21.36023712, 0.17629226]), + 'Rotation': array([-0.06882098, -1.08905017, -0.00317383]), + 'Velocity': array([-5.94048500e-01, 1.13159399e-02, 4.08673281e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.05359697, 10.20999813, 1.53364837]), + 'camera_rotation': array([ -7.19113684, -20.96273422, -1.94634104]), + 'current_gear_input': False, + 'focus_actor_dist': 1062.0982666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 912.0333252 , -1518.83605957, 15.73800659]), + 'frame': 18083, + 'frame_number': 18083, + 'framesequence': 69203, + 'gaze_dir': array([ 0.98641205, -0.16364288, 0.01074982]), + 'gaze_origin': array([-3.18315077, 0.10183487, 0.0911232 ]), + 'gaze_valid': True, + 'gaze_vergence': 317.26873779296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98768616, -0.1557312 , 0.01472473]), + 'left_gaze_origin': array([-3.17096424, 3.29712844, 0.11335754]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2955780029296875, + 'left_pupil_posn': array([-0.10026079, -0.06733441]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98513794, -0.17155457, 0.0067749 ]), + 'right_gaze_origin': array([-3.1953373 , -3.09345865, 0.06888886]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2185516357421875, + 'right_pupil_posn': array([-0.11863083, -0.1394875 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.547831654548645, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.3731000684202, + 'timestamp_carla': 587374, + 'timestamp_device': 30626, + 'timestamp_stream': 587.3731000684202, + 'transform': [array([ 8.31868553e+00, -9.58574104e+00, -3.96533962e-03]), + array([-2.65489444e-02, -3.65899239e+01, 7.26623461e-02])]} +{'AngularVelocity': array([-0.00044141, 0.01322963, -0.00992334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07097424566745758, + 'FR_Wheel_Angle': 0.07102484256029129, + 'Location': array([ -6.453866 , -21.35819626, 0.1763794 ]), + 'Rotation': array([-0.07019385, -1.09158313, -0.00296021]), + 'Velocity': array([-5.82882285e-01, 1.11348312e-02, 1.89900398e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.98244047, 10.39784241, 1.53009367]), + 'camera_rotation': array([ -7.23892117, -20.23792839, -1.74839759]), + 'current_gear_input': False, + 'focus_actor_dist': 1004.8561401367188, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 867.3605957 , -1549.85449219, 15.79303741]), + 'frame': 18084, + 'frame_number': 18084, + 'framesequence': 69206, + 'gaze_dir': array([ 0.98674774, -0.16159058, 0.01241302]), + 'gaze_origin': array([-3.18675423, 0.10367508, 0.09166107]), + 'gaze_valid': True, + 'gaze_vergence': 392.3073425292969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98754883, -0.15640259, 0.01628113]), + 'left_gaze_origin': array([-3.17668629, 3.29942775, 0.11395875]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2742919921875, + 'left_pupil_posn': array([-0.10026079, -0.06729662]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98594666, -0.16677856, 0.00854492]), + 'right_gaze_origin': array([-3.19682169, -3.09207773, 0.06936341]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2191925048828125, + 'right_pupil_posn': array([-0.11979657, -0.1389153 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5474837422370911, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.4058090671897, + 'timestamp_carla': 587406, + 'timestamp_device': 30651, + 'timestamp_stream': 587.4058090671897, + 'transform': [array([ 8.44594955e+00, -9.64384079e+00, -3.95584106e-03]), + array([-2.58522648e-02, -3.71281815e+01, 7.25708082e-02])]} +{'AngularVelocity': array([ 1.54361886e-04, -7.29229720e-03, 5.39210081e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06979384273290634, + 'FR_Wheel_Angle': 0.06984034925699234, + 'Location': array([ -6.56756687, -21.3560276 , 0.17642517]), + 'Rotation': array([-0.06967475, -1.09020984, -0.0027771 ]), + 'Velocity': array([-5.36990404e-01, 1.03562986e-02, 3.73373012e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.90856266, 10.5641222 , 1.54134071]), + 'camera_rotation': array([ -7.15445185, -19.58165359, -1.44167852]), + 'current_gear_input': False, + 'focus_actor_dist': 1017.00390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 880.59509277, -1538.08447266, 15.77583313]), + 'frame': 18085, + 'frame_number': 18085, + 'framesequence': 69210, + 'gaze_dir': array([ 0.98703766, -0.15989685, 0.01182556]), + 'gaze_origin': array([-3.20164108, 0.10568009, 0.094339 ]), + 'gaze_valid': True, + 'gaze_vergence': 328.7483825683594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98760986, -0.15600586, 0.0165863 ]), + 'left_gaze_origin': array([-3.18970966, 3.3022325 , 0.11484987]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17401123046875, + 'left_pupil_posn': array([-0.10138965, -0.06944764]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98646545, -0.16378784, 0.00706482]), + 'right_gaze_origin': array([-3.21357298, -3.09087253, 0.07382813]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2301483154296875, + 'right_pupil_posn': array([-0.12036413, -0.1389153 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5467513203620911, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.4390591681004, + 'timestamp_carla': 587440, + 'timestamp_device': 30684, + 'timestamp_stream': 587.4390591681004, + 'transform': [array([ 8.57421017e+00, -9.70392990e+00, -3.96196358e-03]), + array([-2.50872839e-02, -3.76732712e+01, 7.25097656e-02])]} +{'AngularVelocity': array([2.01539238e-04, 8.59561935e-03, 2.30035052e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.047016505151987076, + 'FR_Wheel_Angle': 0.04577794298529625, + 'Location': array([ -6.68424034, -21.35375977, 0.17660163]), + 'Rotation': array([-0.06869804, -1.07180762, -0.00256348]), + 'Velocity': array([-0.46303701, 0.00889174, 0.00070695]), + 'brake_input': 0.0, + 'camera_location': array([-4.85569572, 10.72229385, 1.53235948]), + 'camera_rotation': array([ -7.1744442 , -18.98781967, -1.2259357 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1032.3729248046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 896.55041504, -1525.62548828, 15.75569153]), + 'frame': 18086, + 'frame_number': 18086, + 'framesequence': 69214, + 'gaze_dir': array([ 0.98597717, -0.1662674 , 0.01213074]), + 'gaze_origin': array([-3.20149779, 0.10792847, 0.09632722]), + 'gaze_valid': True, + 'gaze_vergence': 27.813440322875977, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98594666, -0.16604614, 0.01765442]), + 'left_gaze_origin': array([-3.20555115, 3.30452275, 0.12208863]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2264404296875, + 'left_pupil_posn': array([-0.10406542, -0.06776142]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98600769, -0.16648865, 0.00660706]), + 'right_gaze_origin': array([-3.1974442 , -3.08866596, 0.0705658 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.213714599609375, + 'right_pupil_posn': array([-0.12549299, -0.13776004]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5449385046958923, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.4706519655883, + 'timestamp_carla': 587471, + 'timestamp_device': 30717, + 'timestamp_stream': 587.4706519655883, + 'transform': [array([ 8.69511032e+00, -9.76187706e+00, -3.94300465e-03]), + array([-2.43223030e-02, -3.81891937e+01, 7.23876953e-02])]} +{'AngularVelocity': array([-0.00146496, 0.00849476, -0.18112792]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04582247883081436, + 'FR_Wheel_Angle': 0.04584542289376259, + 'Location': array([ -6.77466393, -21.35195351, 0.17669189]), + 'Rotation': array([-0.06744128, -1.08428955, -0.00250244]), + 'Velocity': array([-0.36928532, 0.00710368, 0.00095455]), + 'brake_input': 0.0, + 'camera_location': array([-4.81269264, 10.8628931 , 1.53389573]), + 'camera_rotation': array([ -7.30160141, -18.33678055, -0.99441499]), + 'current_gear_input': False, + 'focus_actor_dist': 1037.380126953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 906.97406006, -1526.30078125, 15.74562073]), + 'frame': 18087, + 'frame_number': 18087, + 'framesequence': 69218, + 'gaze_dir': array([ 0.98628998, -0.16443634, 0.01100922]), + 'gaze_origin': array([-3.20000458, 0.10901414, 0.09621583]), + 'gaze_valid': True, + 'gaze_vergence': 136.09661865234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98657227, -0.16229248, 0.01786804]), + 'left_gaze_origin': array([-3.21154809, 3.30588698, 0.12404481]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.20648193359375, + 'left_pupil_posn': array([-0.10511422, -0.06838214]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98600769, -0.1665802 , 0.00415039]), + 'right_gaze_origin': array([-3.18846154, -3.08785868, 0.06838685]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.192352294921875, + 'right_pupil_posn': array([-0.12480086, -0.13743055]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5426862835884094, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.5048217661679, + 'timestamp_carla': 587506, + 'timestamp_device': 30751, + 'timestamp_stream': 587.5048217661679, + 'transform': [array([ 8.82405472e+00, -9.82489491e+00, -3.98674002e-03]), + array([-2.38373596e-02, -3.87411728e+01, 7.23876953e-02])]} +{'AngularVelocity': array([-2.56975851e-04, -2.54601091e-02, -9.11338866e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0458211749792099, + 'FR_Wheel_Angle': 0.0458526574075222, + 'Location': array([ -6.85682774, -21.35035324, 0.17675681]), + 'Rotation': array([-0.06976355, -1.08456433, -0.00231934]), + 'Velocity': array([-3.24773401e-01, 6.58622896e-03, 1.31626133e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.76851606, 10.98934555, 1.53638721]), + 'camera_rotation': array([ -7.3120451 , -17.7575798 , -0.98642814]), + 'current_gear_input': False, + 'focus_actor_dist': 1014.3140869140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 887.31378174, -1529.34509277, 15.7661438 ]), + 'frame': 18088, + 'frame_number': 18088, + 'framesequence': 69222, + 'gaze_dir': array([ 0.98973846, -0.13335419, 0.04536438]), + 'gaze_origin': array([-3.08695006, 0.06651536, 0.08010483]), + 'gaze_valid': True, + 'gaze_vergence': 130.68280029296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99307251, -0.1101532 , 0.04083252]), + 'left_gaze_origin': array([-2.97720504, 3.26002979, 0.07034913]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2890625, + 'left_pupil_posn': array([-0.06776565, -0.04545379]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98640442, -0.15655518, 0.04989624]), + 'right_gaze_origin': array([-3.19669509, -3.1269989 , 0.08986054]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.098968505859375, + 'right_pupil_posn': array([-0.07964027, -0.11597896]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.538987398147583, + 'throttle_input': 0.0634927898645401, + 'timestamp': 587.5386361666024, + 'timestamp_carla': 587539, + 'timestamp_device': 30784, + 'timestamp_stream': 587.5386361666024, + 'transform': [array([ 8.94955635e+00, -9.88731384e+00, -4.05139895e-03]), + array([-2.36529447e-02, -3.92798233e+01, 7.24792406e-02])]} +{'AngularVelocity': array([ 0.0083232 , -0.07231642, 0.57039964]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.045767851173877716, + 'FR_Wheel_Angle': 0.04580694064497948, + 'Location': array([ -6.94838285, -21.34817123, 0.17688312]), + 'Rotation': array([-0.07416219, -1.12261939, -0.00238037]), + 'Velocity': array([-3.84334326e-01, 1.02136666e-02, 1.86252597e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.72800493, 11.10166454, 1.51434004]), + 'camera_rotation': array([ -7.39904118, -17.17714882, -0.96191716]), + 'current_gear_input': False, + 'focus_actor_dist': 1426.4549560546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1250.52380371, -1317.54125977, 15.33278656]), + 'frame': 18089, + 'frame_number': 18089, + 'framesequence': 69227, + 'gaze_dir': array([ 0.99378967, -0.06938171, 0.08661652]), + 'gaze_origin': array([-3.08877516, 0.0247467 , 0.1123848 ]), + 'gaze_valid': True, + 'gaze_vergence': 401.1213684082031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99412537, -0.06202698, 0.08868408]), + 'left_gaze_origin': array([-2.99391961, 3.21154642, 0.10875702]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2174072265625, + 'left_pupil_posn': array([-0.00776917, -0.01042914]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99345398, -0.07673645, 0.08454895]), + 'right_gaze_origin': array([-3.18363047, -3.16205311, 0.11601258]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1012420654296875, + 'right_pupil_posn': array([-0.03874588, -0.07928336]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5351237654685974, + 'throttle_input': 0.07142747938632965, + 'timestamp': 587.5743722654879, + 'timestamp_carla': 587575, + 'timestamp_device': 30826, + 'timestamp_stream': 587.5743722654879, + 'transform': [array([ 9.08013058e+00, -9.95352364e+00, -4.13951883e-03]), + array([-2.36802641e-02, -3.98422852e+01, 7.25707933e-02])]} +{'AngularVelocity': array([ 0.0021482 , 0.00284736, -1.00699747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0457424558699131, + 'FR_Wheel_Angle': 0.04577232152223587, + 'Location': array([ -7.04877996, -21.34641838, 0.17700049]), + 'Rotation': array([-0.07455151, -1.11239624, -0.00192261]), + 'Velocity': array([-0.46108511, 0.00882758, 0.00062504]), + 'brake_input': 0.0, + 'camera_location': array([-4.68633747, 11.22088242, 1.49646199]), + 'camera_rotation': array([ -7.44427061, -16.58687973, -1.04946327]), + 'current_gear_input': False, + 'focus_actor_dist': 3050.938232421875, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.62743628e+03, -4.33108521e+02, 9.30786133e-04]), + 'frame': 18090, + 'frame_number': 18090, + 'framesequence': 69231, + 'gaze_dir': array([ 0.99358368, -0.07327271, 0.0852356 ]), + 'gaze_origin': array([-3.09890532, 0.02787018, 0.11758119]), + 'gaze_valid': True, + 'gaze_vergence': 279.6744689941406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99435425, -0.06195068, 0.08599854]), + 'left_gaze_origin': array([-3.02773309, 3.21840239, 0.12275239]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.277862548828125, + 'left_pupil_posn': array([-0.01522166, -0.00735497]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99281311, -0.08459473, 0.08447266]), + 'right_gaze_origin': array([-3.17007756, -3.16266203, 0.11240998]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.14373779296875, + 'right_pupil_posn': array([-0.0384686 , -0.08027768]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5305643081665039, + 'throttle_input': 0.08332952111959457, + 'timestamp': 587.6075456663966, + 'timestamp_carla': 587608, + 'timestamp_device': 30859, + 'timestamp_stream': 587.6075456663966, + 'transform': [array([ 9.19961452e+00, -1.00151405e+01, -4.17375565e-03]), + array([-2.36529447e-02, -4.03585014e+01, 7.25707933e-02])]} +{'AngularVelocity': array([-0.00459206, -0.19714934, -0.20053084]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.10684538, -21.3453064 , 0.17690067]), + 'Rotation': array([-0.04806404, -1.10995483, -0.00201416]), + 'Velocity': array([ 0.16925918, -0.00340479, -0.00032049]), + 'brake_input': 0.0, + 'camera_location': array([-4.6597147 , 11.32674694, 1.50784111]), + 'camera_rotation': array([ -7.39425325, -16.07392693, -1.1887449 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2900.24267578125, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.50491260e+03, -5.13722656e+02, 9.15527344e-04]), + 'frame': 18091, + 'frame_number': 18091, + 'framesequence': 69235, + 'gaze_dir': array([ 0.99385834, -0.07550049, 0.0798645 ]), + 'gaze_origin': array([-3.08987975, 0.02666092, 0.11828537]), + 'gaze_valid': True, + 'gaze_vergence': 240.88397216796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99424744, -0.06484985, 0.08512878]), + 'left_gaze_origin': array([-3.01908135, 3.21896362, 0.12124635]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2931671142578125, + 'left_pupil_posn': array([-0.01607621, -0.010162 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99346924, -0.08615112, 0.07460022]), + 'right_gaze_origin': array([-3.16067815, -3.16564178, 0.11532441]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1182098388671875, + 'right_pupil_posn': array([-0.03753418, -0.07684505]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5258767008781433, + 'throttle_input': 0.10316624492406845, + 'timestamp': 587.6407125666738, + 'timestamp_carla': 587641, + 'timestamp_device': 30892, + 'timestamp_stream': 587.6407125666738, + 'transform': [array([ 9.31775379e+00, -1.00771236e+01, -4.18828940e-03]), + array([-2.34616976e-02, -4.08707047e+01, 7.24792480e-02])]} +{'AngularVelocity': array([ 0.00182342, 0.09021131, -0.23496354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.04613785818219185, + 'Location': array([ -7.02676201, -21.34689713, 0.17684524]), + 'Rotation': array([-0.05413608, -1.11260974, -0.00207519]), + 'Velocity': array([ 0.39054632, -0.00783462, -0.00051812]), + 'brake_input': 0.0, + 'camera_location': array([-4.63042259, 11.40559959, 1.54141319]), + 'camera_rotation': array([ -7.28193045, -15.62714386, -1.10211658]), + 'current_gear_input': False, + 'focus_actor_dist': 2635.20068359375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.28004785e+03, -6.46680298e+02, 4.11987305e-04]), + 'frame': 18092, + 'frame_number': 18092, + 'framesequence': 69239, + 'gaze_dir': array([ 0.99394226, -0.07578278, 0.07839966]), + 'gaze_origin': array([-3.08568192, 0.02513657, 0.11295776]), + 'gaze_valid': True, + 'gaze_vergence': 222.10617065429688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99440002, -0.06404114, 0.08396912]), + 'left_gaze_origin': array([-3.01736307, 3.21861291, 0.11839753]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2076568603515625, + 'left_pupil_posn': array([-0.01633978, -0.01222074]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9934845 , -0.08752441, 0.0728302 ]), + 'right_gaze_origin': array([-3.154001 , -3.16833973, 0.10751801]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1246795654296875, + 'right_pupil_posn': array([-0.03555244, -0.08133626]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5203467011451721, + 'throttle_input': 0.1269855797290802, + 'timestamp': 587.6734535656869, + 'timestamp_carla': 587674, + 'timestamp_device': 30926, + 'timestamp_stream': 587.6734535656869, + 'transform': [array([ 9.43305302e+00, -1.01384468e+01, -4.17337427e-03]), + array([-2.32226420e-02, -4.13717232e+01, 7.22656250e-02])]} +{'AngularVelocity': array([-5.16577798e-04, -2.92781387e-02, 1.20154414e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612336680293083, + 'FR_Wheel_Angle': 0.04614397510886192, + 'Location': array([ -7.0228734 , -21.34693718, 0.17699154]), + 'Rotation': array([-0.07800075, -1.11843872, -0.00207519]), + 'Velocity': array([-1.75551413e-05, 9.15058445e-06, 2.52816913e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.5904808 , 11.48109627, 1.57380164]), + 'camera_rotation': array([ -7.14436388, -15.12735653, -1.06286633]), + 'current_gear_input': False, + 'focus_actor_dist': 2666.581787109375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.31268945e+03, -6.32066650e+02, 7.47680664e-04]), + 'frame': 18093, + 'frame_number': 18093, + 'framesequence': 69243, + 'gaze_dir': array([ 0.99383545, -0.07675171, 0.07911682]), + 'gaze_origin': array([-3.08427835, 0.02426682, 0.1109108 ]), + 'gaze_valid': True, + 'gaze_vergence': 250.6151580810547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99427795, -0.06614685, 0.08387756]), + 'left_gaze_origin': array([-3.01455545, 3.21795392, 0.1143036 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.224212646484375, + 'left_pupil_posn': array([-0.01583046, -0.0139569 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99339294, -0.08735657, 0.07435608]), + 'right_gaze_origin': array([-3.154001 , -3.16942 , 0.10751801]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.105804443359375, + 'right_pupil_posn': array([-0.03555244, -0.08136785]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5145787000656128, + 'throttle_input': 0.14682230353355408, + 'timestamp': 587.7077601663768, + 'timestamp_carla': 587708, + 'timestamp_device': 30959, + 'timestamp_stream': 587.7077601663768, + 'transform': [array([ 9.55233097e+00, -1.02026510e+01, -4.16210154e-03]), + array([-2.29835846e-02, -4.18909225e+01, 7.19909668e-02])]} +{'AngularVelocity': array([-2.32513630e-04, -9.40018892e-03, 1.12495024e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612337425351143, + 'FR_Wheel_Angle': 0.04614398255944252, + 'Location': array([ -7.02284241, -21.34693718, 0.17696323]), + 'Rotation': array([-0.07363626, -1.1184386 , -0.0020752 ]), + 'Velocity': array([-3.51191034e-06, 9.59707177e-06, 3.51373834e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.56534958, 11.56144142, 1.57262075]), + 'camera_rotation': array([ -7.12562847, -14.69162178, -1.02438474]), + 'current_gear_input': False, + 'focus_actor_dist': 2842.81298828125, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.47173511e+03, -5.46447388e+02, 9.00268555e-04]), + 'frame': 18094, + 'frame_number': 18094, + 'framesequence': 69247, + 'gaze_dir': array([ 0.99372101, -0.07881165, 0.07881927]), + 'gaze_origin': array([-3.09332371, 0.02244797, 0.11178589]), + 'gaze_valid': True, + 'gaze_vergence': 342.8451843261719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99411011, -0.07077026, 0.08201599]), + 'left_gaze_origin': array([-3.01428986, 3.21689463, 0.1139969 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2234954833984375, + 'left_pupil_posn': array([-0.014943 , -0.01367855]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99333191, -0.08685303, 0.07562256]), + 'right_gaze_origin': array([-3.17235732, -3.17199874, 0.1095749 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.116485595703125, + 'right_pupil_posn': array([-0.0351761 , -0.08399034]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5078951716423035, + 'throttle_input': 0.16269169747829437, + 'timestamp': 587.7400949671865, + 'timestamp_carla': 587741, + 'timestamp_device': 30992, + 'timestamp_stream': 587.7400949671865, + 'transform': [array([ 9.66388988e+00, -1.02633801e+01, -4.08355705e-03]), + array([-2.25259624e-02, -4.23773613e+01, 7.15331957e-02])]} +{'AngularVelocity': array([-3.57210811e-05, -2.82692700e-03, 3.28281260e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612337797880173, + 'FR_Wheel_Angle': 0.04614398628473282, + 'Location': array([ -7.0228343 , -21.34693718, 0.17695022]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([ 6.38887286e-07, 1.10002838e-05, -4.16598195e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.53986073, 11.67675972, 1.54818451]), + 'camera_rotation': array([ -7.13745832, -14.34494019, -1.45781088]), + 'current_gear_input': False, + 'focus_actor_dist': 1940.850830078125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([1690.78198242, -986.9286499 , 43.28662872]), + 'frame': 18095, + 'frame_number': 18095, + 'framesequence': 69251, + 'gaze_dir': array([ 0.99351501, -0.0785141 , 0.08141327]), + 'gaze_origin': array([-3.08910394, 0.02032547, 0.1169403 ]), + 'gaze_valid': True, + 'gaze_vergence': 276.4419250488281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99456787, -0.06747437, 0.07920837]), + 'left_gaze_origin': array([-3.00496078, 3.21394348, 0.12002107]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.27874755859375, + 'left_pupil_posn': array([-0.01378328, -0.00538421]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99246216, -0.08955383, 0.08361816]), + 'right_gaze_origin': array([-3.17324686, -3.17329288, 0.11385956]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1542816162109375, + 'right_pupil_posn': array([-0.0330953, -0.0823009]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.5020905137062073, + 'throttle_input': 0.17062638700008392, + 'timestamp': 587.7747155688703, + 'timestamp_carla': 587775, + 'timestamp_device': 31026, + 'timestamp_stream': 587.7747155688703, + 'transform': [array([ 9.78227043e+00, -1.03284893e+01, -4.02263645e-03]), + array([-2.20341887e-02, -4.28942108e+01, 7.10449070e-02])]} +{'AngularVelocity': array([ 2.46855689e-05, -8.26288306e-04, -1.32177929e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612337425351143, + 'FR_Wheel_Angle': 0.04614398255944252, + 'Location': array([ -7.02283287, -21.34693718, 0.17694934]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([ 1.72791067e-06, 3.74981880e-07, -6.64052277e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.5542922 , 11.79743099, 1.51766455]), + 'camera_rotation': array([ -7.42170382, -13.91730785, -1.47982538]), + 'current_gear_input': False, + 'focus_actor_dist': 2957.977294921875, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.58864526e+03, -5.02186523e+02, 9.30786133e-04]), + 'frame': 18096, + 'frame_number': 18096, + 'framesequence': 69255, + 'gaze_dir': array([ 0.99399567, -0.07833099, 0.075737 ]), + 'gaze_origin': array([-3.11656499, 0.0195076 , 0.12136841]), + 'gaze_valid': True, + 'gaze_vergence': 299.149658203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99432373, -0.06993103, 0.08010864]), + 'left_gaze_origin': array([-3.03314829, 3.21286631, 0.12370911]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2612152099609375, + 'left_pupil_posn': array([-0.01224047, -0.01212895]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9936676 , -0.08673096, 0.07136536]), + 'right_gaze_origin': array([-3.19998193, -3.17385125, 0.11902772]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.211181640625, + 'right_pupil_posn': array([-0.03318512, -0.08351445]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4957548975944519, + 'throttle_input': 0.17062638700008392, + 'timestamp': 587.8086890652776, + 'timestamp_carla': 587809, + 'timestamp_device': 31059, + 'timestamp_stream': 587.8086890652776, + 'transform': [array([ 9.89810181e+00, -1.03930511e+01, -3.92318703e-03]), + array([-2.12692078e-02, -4.34013329e+01, 7.04650804e-02])]} +{'AngularVelocity': array([-6.12257936e-05, -2.09377074e-04, -1.32069827e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17694855]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([ 2.06791788e-06, 4.12113735e-07, -1.59770061e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.51617908, 11.9124155 , 1.53857815]), + 'camera_rotation': array([ -7.32178497, -13.42429161, -1.10250497]), + 'current_gear_input': False, + 'focus_actor_dist': 2132.642578125, + 'focus_actor_name': 'Road_Sidewalk_Town05_214', + 'focus_actor_pt': array([1869.15893555, -898.17193604, 15.24004364]), + 'frame': 18097, + 'frame_number': 18097, + 'framesequence': 69259, + 'gaze_dir': array([ 0.99372101, -0.07660675, 0.08083344]), + 'gaze_origin': array([-3.10586262, 0.02024841, 0.11394119]), + 'gaze_valid': True, + 'gaze_vergence': 282.7198791503906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99407959, -0.06738281, 0.08520508]), + 'left_gaze_origin': array([-3.02138066, 3.2142427 , 0.1156128 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3850555419921875, + 'left_pupil_posn': array([-0.01276857, -0.01393354]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99336243, -0.08583069, 0.07646179]), + 'right_gaze_origin': array([-3.19034457, -3.17374587, 0.1122696 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.049835205078125, + 'right_pupil_posn': array([-0.03260589, -0.08423734]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4896206855773926, + 'throttle_input': 0.17856107652187347, + 'timestamp': 587.8417638652027, + 'timestamp_carla': 587842, + 'timestamp_device': 31092, + 'timestamp_stream': 587.8417638652027, + 'transform': [array([ 1.00107441e+01, -1.04565258e+01, -3.78437038e-03]), + array([-2.03471333e-02, -4.38953743e+01, 6.97631761e-02])]} +{'AngularVelocity': array([ 7.88401958e-05, -7.14401831e-05, -1.30348471e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17695396]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([2.53478061e-06, 3.50363536e-07, 1.36913892e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.5010767 , 12.03317547, 1.5330925 ]), + 'camera_rotation': array([ -7.31847239, -12.92865562, -1.10128844]), + 'current_gear_input': False, + 'focus_actor_dist': 1928.6959228515625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([1693.01000977, -989.65472412, 41.04859924]), + 'frame': 18098, + 'frame_number': 18098, + 'framesequence': 69263, + 'gaze_dir': array([ 0.99337769, -0.08194733, 0.07920074]), + 'gaze_origin': array([-3.10018778, 0.02206268, 0.1042717 ]), + 'gaze_valid': True, + 'gaze_vergence': 223.41944885253906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99438477, -0.06793213, 0.08103943]), + 'left_gaze_origin': array([-3.01480865, 3.21696329, 0.10574951]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3035888671875, + 'left_pupil_posn': array([-0.0181089 , -0.01891232]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99237061, -0.09596252, 0.07736206]), + 'right_gaze_origin': array([-3.1855669 , -3.17283797, 0.10279389]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1135101318359375, + 'right_pupil_posn': array([-0.03352499, -0.09136748]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.48302868008613586, + 'throttle_input': 0.1904631108045578, + 'timestamp': 587.8752956651151, + 'timestamp_carla': 587876, + 'timestamp_device': 31126, + 'timestamp_stream': 587.8752956651151, + 'transform': [array([ 1.01244059e+01, -1.05209742e+01, -3.65955336e-03]), + array([-1.94387175e-02, -4.43937073e+01, 6.90917894e-02])]} +{'AngularVelocity': array([ 7.63849239e-05, -4.64668519e-05, -1.30313256e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17694953]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([2.60830848e-06, 4.01229471e-07, 1.98626425e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.48058224, 12.14245224, 1.57580554]), + 'camera_rotation': array([ -7.18013334, -12.38290405, -1.06425333]), + 'current_gear_input': False, + 'focus_actor_dist': 2674.93701171875, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.35714722e+03, -6.42182007e+02, 8.39233398e-04]), + 'frame': 18099, + 'frame_number': 18099, + 'framesequence': 69267, + 'gaze_dir': array([ 0.99337006, -0.08275604, 0.07797241]), + 'gaze_origin': array([-3.08237791, 0.02177963, 0.09391328]), + 'gaze_valid': True, + 'gaze_vergence': 190.19024658203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99493408, -0.06652832, 0.07522583]), + 'left_gaze_origin': array([-2.99457717, 3.21708703, 0.09243317]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.164794921875, + 'left_pupil_posn': array([-0.01913565, -0.02302837]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99180603, -0.09898376, 0.08071899]), + 'right_gaze_origin': array([-3.17017841, -3.17352748, 0.09539337]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.147064208984375, + 'right_pupil_posn': array([-0.03281569, -0.09555292]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4761803150177002, + 'throttle_input': 0.20236514508724213, + 'timestamp': 587.908360067755, + 'timestamp_carla': 587909, + 'timestamp_device': 31159, + 'timestamp_stream': 587.908360067755, + 'transform': [array([ 1.02361717e+01, -1.05847254e+01, -3.52460844e-03]), + array([-1.85234714e-02, -4.48835983e+01, 6.83898702e-02])]} +{'AngularVelocity': array([-5.45780131e-05, -3.66945351e-05, -1.29562186e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17694625]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([2.56785188e-06, 5.01786701e-07, 1.69502178e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.47056437, 12.23741627, 1.63411069]), + 'camera_rotation': array([ -6.83999681, -11.93047047, -0.94963968]), + 'current_gear_input': False, + 'focus_actor_dist': 1939.34814453125, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([1714.66955566, -988.87243652, 39.81203461]), + 'frame': 18100, + 'frame_number': 18100, + 'framesequence': 69271, + 'gaze_dir': array([ 0.99359131, -0.08123779, 0.07746124]), + 'gaze_origin': array([-3.10189605, 0.02290039, 0.10057221]), + 'gaze_valid': True, + 'gaze_vergence': 249.83029174804688, + 'handbrake_input': False, + 'left_eye_openness': 0.9466891884803772, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99459839, -0.06851196, 0.07785034]), + 'left_gaze_origin': array([-3.01485157, 3.21838856, 0.10142517]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.16680908203125, + 'left_pupil_posn': array([-0.01842207, -0.02182841]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9970813393592834, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99258423, -0.09396362, 0.07707214]), + 'right_gaze_origin': array([-3.18894053, -3.17258763, 0.09971925]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1170196533203125, + 'right_pupil_posn': array([-0.03386229, -0.0952847 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4692220985889435, + 'throttle_input': 0.21031509339809418, + 'timestamp': 587.9417202658951, + 'timestamp_carla': 587942, + 'timestamp_device': 31192, + 'timestamp_stream': 587.9417202658951, + 'transform': [array([ 1.03486366e+01, -1.06491842e+01, -3.40200425e-03]), + array([-1.76423769e-02, -4.53761749e+01, 6.77184910e-02])]} +{'AngularVelocity': array([-4.77469075e-05, -9.58391320e-06, -1.30453309e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17694752]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([2.54512770e-06, 5.01809382e-07, 1.47206403e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.45532894, 12.34001923, 1.65039074]), + 'camera_rotation': array([ -6.74095249, -11.4779644 , -1.08765411]), + 'current_gear_input': False, + 'focus_actor_dist': 3091.093505859375, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.72963965e+03, -4.36441772e+02, 9.61303711e-04]), + 'frame': 18101, + 'frame_number': 18101, + 'framesequence': 69275, + 'gaze_dir': array([ 0.99246979, -0.09056854, 0.08113861]), + 'gaze_origin': array([-3.09538746, 0.02526703, 0.10975953]), + 'gaze_valid': True, + 'gaze_vergence': 213.89541625976562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99403381, -0.07670593, 0.07749939]), + 'left_gaze_origin': array([-2.99176359, 3.21980762, 0.10321351]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.134521484375, + 'left_pupil_posn': array([-0.02283013, -0.01381719]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99090576, -0.10443115, 0.08477783]), + 'right_gaze_origin': array([-3.19901156, -3.16927361, 0.11630554]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9889373779296875, + 'right_pupil_posn': array([-0.0388329 , -0.08558607]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4621906280517578, + 'throttle_input': 0.21031509339809418, + 'timestamp': 587.9760499671102, + 'timestamp_carla': 587977, + 'timestamp_device': 31226, + 'timestamp_stream': 587.9760499671102, + 'transform': [array([ 1.04642124e+01, -1.07158489e+01, -3.31001263e-03]), + array([-1.67544540e-02, -4.58823204e+01, 6.71386644e-02])]} +{'AngularVelocity': array([-2.87385301e-05, -1.02902413e-05, -1.32735086e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17694373]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([ 2.20546485e-06, 4.03733566e-07, -1.53503948e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.46670437, 12.44599152, 1.59885478]), + 'camera_rotation': array([ -7.00399637, -10.99420166, -1.01073945]), + 'current_gear_input': False, + 'focus_actor_dist': 3500.7041015625, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 3.11105200e+03, -2.70619873e+02, 1.11389160e-03]), + 'frame': 18102, + 'frame_number': 18102, + 'framesequence': 69279, + 'gaze_dir': array([ 0.99337769, -0.08396149, 0.07798767]), + 'gaze_origin': array([-3.07841277, 0.02531433, 0.10625915]), + 'gaze_valid': True, + 'gaze_vergence': 437.63641357421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99397278, -0.07669067, 0.07814026]), + 'left_gaze_origin': array([-2.98524809, 3.2211442 , 0.10310975]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0990142822265625, + 'left_pupil_posn': array([-0.01922119, -0.01469767]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99278259, -0.0912323 , 0.07783508]), + 'right_gaze_origin': array([-3.17157769, -3.17051554, 0.10940857]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0859527587890625, + 'right_pupil_posn': array([-0.03827989, -0.08523071]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.4548112452030182, + 'throttle_input': 0.21031509339809418, + 'timestamp': 588.0092085674405, + 'timestamp_carla': 588010, + 'timestamp_device': 31259, + 'timestamp_stream': 588.0092085674405, + 'transform': [array([ 1.05758858e+01, -1.07805805e+01, -3.19694518e-03]), + array([-1.58392079e-02, -4.63710175e+01, 6.65283054e-02])]} +{'AngularVelocity': array([-3.98254197e-05, 3.36979429e-05, -1.30634880e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17695007]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([ 2.42832107e-06, 4.82875635e-07, -1.04268165e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.44086266, 12.53188801, 1.58816695]), + 'camera_rotation': array([ -7.01878405, -10.64208126, -1.03860247]), + 'current_gear_input': False, + 'focus_actor_dist': 1936.5716552734375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([1726.98486328, -987.9251709 , 46.12036896]), + 'frame': 18103, + 'frame_number': 18103, + 'framesequence': 69283, + 'gaze_dir': array([ 0.99263763, -0.08989716, 0.07952118]), + 'gaze_origin': array([-3.0791688 , 0.02383728, 0.10781174]), + 'gaze_valid': True, + 'gaze_vergence': 206.72247314453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99397278, -0.07455444, 0.0802002 ]), + 'left_gaze_origin': array([-2.99063587, 3.21855807, 0.10728608]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1671600341796875, + 'left_pupil_posn': array([-0.02227736, -0.01276922]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99130249, -0.10523987, 0.07884216]), + 'right_gaze_origin': array([-3.16770196, -3.17088318, 0.1083374 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.117767333984375, + 'right_pupil_posn': array([-0.037314 , -0.08461523]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.44682762026786804, + 'throttle_input': 0.21031509339809418, + 'timestamp': 588.0404950678349, + 'timestamp_carla': 588041, + 'timestamp_device': 31292, + 'timestamp_stream': 588.0404950678349, + 'transform': [array([ 1.06812439e+01, -1.08416758e+01, -3.05814738e-03]), + array([-1.49581134e-02, -4.68308601e+01, 6.58569112e-02])]} +{'AngularVelocity': array([ 7.07189756e-05, -6.65277958e-06, -1.31906463e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.02283049, -21.34693718, 0.17694885]), + 'Rotation': array([-0.0726937, -1.1184386, -0.0020752]), + 'Velocity': array([2.44039097e-06, 3.09464525e-07, 3.30034454e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.44123936, 12.62242603, 1.5745945 ]), + 'camera_rotation': array([ -7.13478088, -10.30224228, -1.05859673]), + 'current_gear_input': False, + 'focus_actor_dist': 3008.845703125, + 'focus_actor_name': 'Road_Road_Town05_173', + 'focus_actor_pt': array([ 2.68685986e+03, -5.01290771e+02, 9.76562500e-04]), + 'frame': 18104, + 'frame_number': 18104, + 'framesequence': 69287, + 'gaze_dir': array([ 0.99291992, -0.09341431, 0.07264709]), + 'gaze_origin': array([-3.07119703, 0.02403641, 0.11162034]), + 'gaze_valid': True, + 'gaze_vergence': 323.8883972167969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9934845 , -0.08486938, 0.07598877]), + 'left_gaze_origin': array([-2.99613523, 3.22062564, 0.11359712]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1514892578125, + 'left_pupil_posn': array([-0.02255976, -0.01273465]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99235535, -0.10195923, 0.06930542]), + 'right_gaze_origin': array([-3.14625883, -3.17255259, 0.10964356]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.06689453125, + 'right_pupil_posn': array([-0.04001707, -0.0812006 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.43867915868759155, + 'throttle_input': 0.21031509339809418, + 'timestamp': 588.0736388675869, + 'timestamp_carla': 588074, + 'timestamp_device': 31326, + 'timestamp_stream': 588.0736388675869, + 'transform': [array([ 1.07926588e+01, -1.09063644e+01, -2.98122410e-03]), + array([-1.42204529e-02, -4.73161545e+01, 6.53381199e-02])]} diff --git a/PythonAPI/data/trials/trial12.txt b/PythonAPI/data/trials/trial12.txt new file mode 100644 index 0000000..bc23c14 --- /dev/null +++ b/PythonAPI/data/trials/trial12.txt @@ -0,0 +1,10528 @@ +{'AngularVelocity': array([ 1.70656058e-04, -4.81012103e-05, 9.96032668e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.46834612, -30.75714493, 0.17282623]), + 'Rotation': array([-1.76423769e-02, 8.77886658e+01, -6.28051758e-02]), + 'Velocity': array([ 5.48490289e-06, -2.14257597e-07, -4.85328819e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.00224209, 13.76874542, 1.6264931 ]), + 'camera_rotation': array([-7.44350576, -1.01585031, -1.15844154]), + 'current_gear_input': False, + 'focus_actor_dist': 1133.9786376953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -594.1796875 , -1974.96386719, 38.64935303]), + 'frame': 20759, + 'frame_number': 20759, + 'framesequence': 79336, + 'gaze_dir': array([0.95055389, 0.30927277, 0.02709961]), + 'gaze_origin': array([-3.09700036, -0.2477501 , 0.04952927]), + 'gaze_valid': True, + 'gaze_vergence': 485.6371154785156, + 'handbrake_input': False, + 'left_eye_openness': 0.9978703260421753, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94863892, 0.31515503, 0.02697754]), + 'left_gaze_origin': array([-3.0221498 , 2.93671274, 0.0542984 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.132537841796875, + 'left_pupil_posn': array([ 0.30996001, -0.07641232]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9063393473625183, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95246887, 0.3033905 , 0.02722168]), + 'right_gaze_origin': array([-3.17185068, -3.43221307, 0.04476013]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.069488525390625, + 'right_pupil_posn': array([ 0.27855134, -0.15420592]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004998932126909494, + 'throttle_input': 0.0, + 'timestamp': 671.803389467299, + 'timestamp_carla': 671804, + 'timestamp_device': 115049, + 'timestamp_stream': 671.803389467299, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.03095435e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([2.52863756e-05, 6.00434614e-05, 1.03469829e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.9945830702781677, + 'Location': array([ -3.46834612, -30.75714493, 0.17280731]), + 'Rotation': array([-1.76423769e-02, 8.77886658e+01, -6.28051758e-02]), + 'Velocity': array([ 5.12779661e-06, -1.09446660e-07, -3.40437837e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.98024368, 13.80632019, 1.64125979]), + 'camera_rotation': array([-7.40298223, -0.69354552, -1.11378562]), + 'current_gear_input': False, + 'focus_actor_dist': 1141.203857421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -607.01245117, -1971.24536133, 33.54994965]), + 'frame': 20760, + 'frame_number': 20760, + 'framesequence': 79340, + 'gaze_dir': array([0.95346832, 0.29994202, 0.02565765]), + 'gaze_origin': array([-3.09549952, -0.24586642, 0.0511261 ]), + 'gaze_valid': True, + 'gaze_vergence': 188.35946655273438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94865417, 0.31518555, 0.02622986]), + 'left_gaze_origin': array([-3.01971602, 2.94005442, 0.05697785]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.107696533203125, + 'left_pupil_posn': array([ 0.30099213, -0.07433391]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9230613112449646, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95828247, 0.28469849, 0.02508545]), + 'right_gaze_origin': array([-3.17128301, -3.43178725, 0.04527435]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0230560302734375, + 'right_pupil_posn': array([ 0.27828777, -0.15393412]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005072176456451416, + 'throttle_input': 0.0, + 'timestamp': 671.8378185667098, + 'timestamp_carla': 671838, + 'timestamp_device': 115083, + 'timestamp_stream': 671.8378185667098, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.02971839e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([0.00100484, 0.00012455, 0.00248534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.46823359, -30.75525475, 0.17281593]), + 'Rotation': array([-1.70618109e-02, 8.77905273e+01, -6.27746433e-02]), + 'Velocity': array([0.00081703, 0.01817062, 0.0009651 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.98146343, 13.85691261, 1.64259243]), + 'camera_rotation': array([-7.43425083, -0.42282668, -1.10083723]), + 'current_gear_input': False, + 'focus_actor_dist': 1298.3125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -641.95007324, -1818.80566406, 17.379776 ]), + 'frame': 20761, + 'frame_number': 20761, + 'framesequence': 79344, + 'gaze_dir': array([0.95329285, 0.30079651, 0.02323914]), + 'gaze_origin': array([-3.09524322, -0.24514467, 0.05218048]), + 'gaze_valid': True, + 'gaze_vergence': 210.8582000732422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94906616, 0.31430054, 0.02171326]), + 'left_gaze_origin': array([-3.0198884 , 2.94115615, 0.05726472]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.108123779296875, + 'left_pupil_posn': array([ 0.30115557, -0.07433391]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9018498659133911, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95751953, 0.28729248, 0.02476501]), + 'right_gaze_origin': array([-3.17059803, -3.43144536, 0.04709626]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0788726806640625, + 'right_pupil_posn': array([ 0.27761042, -0.15420592]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005200354382395744, + 'throttle_input': 0.0, + 'timestamp': 671.8713439665735, + 'timestamp_carla': 671872, + 'timestamp_device': 115116, + 'timestamp_stream': 671.8713439665735, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.02971839e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([-9.79834236e-04, -8.38920605e-05, -1.80157870e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7872866988182068, + 'FR_Wheel_Angle': 0.8202763199806213, + 'Location': array([ -3.46806693, -30.75129509, 0.17278957]), + 'Rotation': array([-1.73691697e-02, 8.77886047e+01, -6.27746433e-02]), + 'Velocity': array([9.47946042e-04, 2.09821966e-02, 6.05869282e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.97683811, 13.9079113 , 1.64534557]), + 'camera_rotation': array([-7.40731907, -0.21279526, -1.03187454]), + 'current_gear_input': False, + 'focus_actor_dist': 1257.9202880859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -638.73840332, -1859.90026855, 17.39099884]), + 'frame': 20762, + 'frame_number': 20762, + 'framesequence': 79349, + 'gaze_dir': array([0.9541626 , 0.29798889, 0.02368164]), + 'gaze_origin': array([-3.0949502 , -0.24470903, 0.05237046]), + 'gaze_valid': True, + 'gaze_vergence': 215.52195739746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95021057, 0.31086731, 0.02095032]), + 'left_gaze_origin': array([-3.01986861, 2.94203973, 0.05697785]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0794525146484375, + 'left_pupil_posn': array([ 0.2998203 , -0.07385468]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9219351410865784, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95811462, 0.28511047, 0.02641296]), + 'right_gaze_origin': array([-3.17003202, -3.43145776, 0.04776306]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0705413818359375, + 'right_pupil_posn': array([ 0.27635026, -0.15378857]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005713065154850483, + 'throttle_input': 0.0, + 'timestamp': 671.9042889662087, + 'timestamp_carla': 671905, + 'timestamp_device': 115158, + 'timestamp_stream': 671.9042889662087, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.03017613e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([0.04171168, 0.00360965, 0.57024914]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.4444977045059204, + 'FR_Wheel_Angle': 1.7162302732467651, + 'Location': array([ -3.46799088, -30.74698257, 0.17283081]), + 'Rotation': array([-1.75467543e-02, 8.77848206e+01, -6.28356859e-02]), + 'Velocity': array([5.90984942e-04, 4.06801403e-02, 1.09958646e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.98726654, 13.96297932, 1.62605584]), + 'camera_rotation': array([-7.45699501, -0.03742075, -0.97751355]), + 'current_gear_input': False, + 'focus_actor_dist': 1262.8099365234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -640.92541504, -1855.38305664, 17.3915863 ]), + 'frame': 20763, + 'frame_number': 20763, + 'framesequence': 79352, + 'gaze_dir': array([0.95541382, 0.2939682 , 0.02413177]), + 'gaze_origin': array([-3.093925 , -0.24351959, 0.05426102]), + 'gaze_valid': True, + 'gaze_vergence': 231.16851806640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95167542, 0.30627441, 0.02241516]), + 'left_gaze_origin': array([-3.01971602, 2.94287586, 0.05726472]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0786285400390625, + 'left_pupil_posn': array([ 0.29801881, -0.07373393]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9028224945068359, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95915222, 0.28166199, 0.02584839]), + 'right_gaze_origin': array([-3.16813374, -3.42991495, 0.05125733]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0491943359375, + 'right_pupil_posn': array([ 0.27357054, -0.15032792]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.006665242835879326, + 'throttle_input': 0.0, + 'timestamp': 671.9377551674843, + 'timestamp_carla': 671938, + 'timestamp_device': 115183, + 'timestamp_stream': 671.9377551674843, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.03006167e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([0.04913588, 0.01020311, 0.68766493]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.602431058883667, + 'FR_Wheel_Angle': 4.0089945793151855, + 'Location': array([ -3.46785522, -30.74053383, 0.17282158]), + 'Rotation': array([-1.67544540e-02, 8.77938156e+01, -6.29272386e-02]), + 'Velocity': array([-0.00010238, 0.06523959, 0.00013753]), + 'brake_input': 0.0, + 'camera_location': array([-5.99385071, 14.01980686, 1.60089087]), + 'camera_rotation': array([-7.56746006, 0.14240211, -0.84628707]), + 'current_gear_input': False, + 'focus_actor_dist': 1250.8785400390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -636.52349854, -1866.60510254, 17.39116669]), + 'frame': 20764, + 'frame_number': 20764, + 'framesequence': 79357, + 'gaze_dir': array([0.95562744, 0.29263306, 0.02919006]), + 'gaze_origin': array([-3.09326267, -0.24215852, 0.05518189]), + 'gaze_valid': True, + 'gaze_vergence': 171.414306640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95106506, 0.30804443, 0.02407837]), + 'left_gaze_origin': array([-3.01903105, 2.94472671, 0.05773316]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.079376220703125, + 'left_pupil_posn': array([ 0.29521179, -0.07024884]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9140193462371826, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96018982, 0.27722168, 0.03430176]), + 'right_gaze_origin': array([-3.1674943 , -3.42904377, 0.05263061]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0702972412109375, + 'right_pupil_posn': array([ 0.27357054, -0.14877737]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.008056886494159698, + 'throttle_input': 0.0, + 'timestamp': 671.9718492664397, + 'timestamp_carla': 671972, + 'timestamp_device': 115224, + 'timestamp_stream': 671.9718492664397, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.02952383e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([0.09495938, 0.0252342 , 0.33122167]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.81588888168335, + 'FR_Wheel_Angle': 6.560084342956543, + 'Location': array([ -3.46773767, -30.71630859, 0.1727629 ]), + 'Rotation': array([-9.37101897e-03, 8.78320847e+01, -6.42394945e-02]), + 'Velocity': array([-3.46077443e-03, 2.62967080e-01, -1.28240586e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.00621605, 14.06805992, 1.58948171]), + 'camera_rotation': array([-7.53488684, 0.31925535, -0.72929412]), + 'current_gear_input': False, + 'focus_actor_dist': 1283.9578857421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -647.18017578, -1835.04821777, 17.390625 ]), + 'frame': 20765, + 'frame_number': 20765, + 'framesequence': 79361, + 'gaze_dir': array([0.95552063, 0.29291534, 0.02940369]), + 'gaze_origin': array([-3.09255457, -0.24017258, 0.05662384]), + 'gaze_valid': True, + 'gaze_vergence': 160.35458374023438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95101929, 0.30828857, 0.02256775]), + 'left_gaze_origin': array([-3.01779962, 2.94801641, 0.05981751]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0593719482421875, + 'left_pupil_posn': array([ 0.29307997, -0.06790197]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9103845357894897, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96002197, 0.27754211, 0.03623962]), + 'right_gaze_origin': array([-3.16730952, -3.42836165, 0.05343018]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09722900390625, + 'right_pupil_posn': array([ 0.27314365, -0.14877737]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.010126041248440742, + 'throttle_input': 0.0, + 'timestamp': 672.0040974654257, + 'timestamp_carla': 672005, + 'timestamp_device': 115257, + 'timestamp_stream': 672.0040974654257, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.03057669e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([-0.02662806, 0.0084015 , 0.77583963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.8141865730285645, + 'FR_Wheel_Angle': 8.701835632324219, + 'Location': array([ -3.4693377 , -30.62749672, 0.17273544]), + 'Rotation': array([-3.48339626e-03, 8.80366058e+01, -6.67724609e-02]), + 'Velocity': array([-2.20499597e-02, 5.07731557e-01, -1.49602885e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.00064087, 14.1132946 , 1.61984456]), + 'camera_rotation': array([-7.44127226, 0.48283991, -0.55859536]), + 'current_gear_input': False, + 'focus_actor_dist': 1286.3089599609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -652.09991455, -1833.92675781, 17.39511108]), + 'frame': 20766, + 'frame_number': 20766, + 'framesequence': 79365, + 'gaze_dir': array([0.9562912 , 0.29061127, 0.02861786]), + 'gaze_origin': array([-3.09215641, -0.23841402, 0.05730668]), + 'gaze_valid': True, + 'gaze_vergence': 178.6410369873047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95281982, 0.30279541, 0.0211792 ]), + 'left_gaze_origin': array([-3.01732802, 2.9510088 , 0.06111145]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0928802490234375, + 'left_pupil_posn': array([ 0.29129398, -0.06707442]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9074655771255493, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95976257, 0.27842712, 0.03605652]), + 'right_gaze_origin': array([-3.1669848 , -3.42783666, 0.0535019 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.111053466796875, + 'right_pupil_posn': array([ 0.27074707, -0.14898729]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01228675339370966, + 'throttle_input': 0.01190203707665205, + 'timestamp': 672.0391392670572, + 'timestamp_carla': 672040, + 'timestamp_device': 115291, + 'timestamp_stream': 672.0391392670572, + 'transform': [array([-1.48869169e+00, -1.75996323e+01, 1.02906227e-02]), + array([-0.06280359, -2.21135259, 0.01763918])]} +{'AngularVelocity': array([0.07130259, 0.03373726, 3.0271523 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.227195739746094, + 'FR_Wheel_Angle': 10.26081371307373, + 'Location': array([ -3.47585106, -30.45783424, 0.17270984]), + 'Rotation': array([ 1.51630188e-03, 8.85345688e+01, -7.00378343e-02]), + 'Velocity': array([-6.15956597e-02, 9.34231997e-01, 2.50701909e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.00703716, 14.15216923, 1.6478914 ]), + 'camera_rotation': array([-7.37909031, 0.71482456, -0.51171744]), + 'current_gear_input': False, + 'focus_actor_dist': 1283.731201171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -652.1229248 , -1836.60058594, 17.39607239]), + 'frame': 20767, + 'frame_number': 20767, + 'framesequence': 79369, + 'gaze_dir': array([0.95771027, 0.28582764, 0.03050232]), + 'gaze_origin': array([-3.09098673, -0.23573914, 0.05720673]), + 'gaze_valid': True, + 'gaze_vergence': 230.79588317871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95498657, 0.29554749, 0.02490234]), + 'left_gaze_origin': array([-3.01721215, 2.95245075, 0.06111145]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.086700439453125, + 'left_pupil_posn': array([ 0.28949583, -0.0669837 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9220468401908875, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96043396, 0.27610779, 0.03610229]), + 'right_gaze_origin': array([-3.16476154, -3.42392874, 0.053302 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.14276123046875, + 'right_pupil_posn': array([ 0.26532209, -0.14718735]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.014209418557584286, + 'throttle_input': 0.043656062334775925, + 'timestamp': 672.0720163658261, + 'timestamp_carla': 672073, + 'timestamp_device': 115324, + 'timestamp_stream': 672.0720163658261, + 'transform': [array([-1.48907769e+00, -1.75995750e+01, 1.02929492e-02]), + array([-0.06277627, -2.20960045, 0.01766969])]} +{'AngularVelocity': array([0.04380797, 0.01637636, 4.33185244]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.048572540283203, + 'FR_Wheel_Angle': 9.636883735656738, + 'Location': array([ -3.4907124 , -30.2005024 , 0.17272457]), + 'Rotation': array([ 3.62683018e-03, 8.93828659e+01, -7.15331957e-02]), + 'Velocity': array([-1.08467482e-01, 1.29950285e+00, 2.22787858e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.015028 , 14.21865082, 1.65993595]), + 'camera_rotation': array([-7.27167845, 0.91325337, -0.61533976]), + 'current_gear_input': False, + 'focus_actor_dist': 1145.6929931640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -614.96282959, -1968.66064453, 33.00804901]), + 'frame': 20768, + 'frame_number': 20768, + 'framesequence': 79374, + 'gaze_dir': array([0.95838165, 0.28365326, 0.02825165]), + 'gaze_origin': array([-3.09080911, -0.23380204, 0.05631256]), + 'gaze_valid': True, + 'gaze_vergence': 196.28892517089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95448303, 0.29725647, 0.02388 ]), + 'left_gaze_origin': array([-3.01699686, 2.95426631, 0.06070252]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09820556640625, + 'left_pupil_posn': array([ 0.28607726, -0.0682683 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9142647385597229, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96228027, 0.27005005, 0.03262329]), + 'right_gaze_origin': array([-3.16462111, -3.42187071, 0.05192261]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1692962646484375, + 'right_pupil_posn': array([ 0.2644906 , -0.14853251]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015198218636214733, + 'throttle_input': 0.05555810034275055, + 'timestamp': 672.1185800656676, + 'timestamp_carla': 672119, + 'timestamp_device': 115366, + 'timestamp_stream': 672.1185800656676, + 'transform': [array([-1.48907101e+00, -1.75995293e+01, 1.02560613e-02]), + array([-0.06277627, -2.20960045, 0.01766969])]} +{'AngularVelocity': array([ 0.0237689 , -0.01575981, 3.56788039]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.957121849060059, + 'FR_Wheel_Angle': 5.582319259643555, + 'Location': array([ -3.51172352, -29.87363243, 0.1727737 ]), + 'Rotation': array([-5.53245307e-04, 9.03128510e+01, -6.59789816e-02]), + 'Velocity': array([-1.12750910e-01, 1.52472246e+00, -5.55133811e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.01301575, 14.34992981, 1.68680084]), + 'camera_rotation': array([-7.10557508, 1.23448455, -0.54100877]), + 'current_gear_input': False, + 'focus_actor_dist': 1146.1121826171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -616.43945312, -1968.62402344, 32.92718506]), + 'frame': 20769, + 'frame_number': 20769, + 'framesequence': 79378, + 'gaze_dir': array([0.95920563, 0.2809906 , 0.02567291]), + 'gaze_origin': array([-3.0902276 , -0.23252335, 0.0559845 ]), + 'gaze_valid': True, + 'gaze_vergence': 167.80857849121094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95466614, 0.29695129, 0.02059937]), + 'left_gaze_origin': array([-3.01588607, 2.95604563, 0.06035309]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1003570556640625, + 'left_pupil_posn': array([ 0.28302217, -0.06888151]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9200672507286072, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96374512, 0.26502991, 0.03074646]), + 'right_gaze_origin': array([-3.16456938, -3.42109251, 0.05161591]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.18304443359375, + 'right_pupil_posn': array([ 0.26379061, -0.14992702]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015546129085123539, + 'throttle_input': 0.0158693827688694, + 'timestamp': 672.1494693681598, + 'timestamp_carla': 672150, + 'timestamp_device': 115399, + 'timestamp_stream': 672.1494693681598, + 'transform': [array([-1.48901916e+00, -1.75994396e+01, 1.03109544e-02]), + array([-0.06277627, -2.20980167, 0.01757814])]} +{'AngularVelocity': array([ 0.03429235, -0.0156033 , 1.15589488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2362972497940063, + 'FR_Wheel_Angle': 0.5806741118431091, + 'Location': array([ -3.52816367, -29.50584984, 0.17282684]), + 'Rotation': array([-4.46011312e-03, 9.08374176e+01, -5.70678674e-02]), + 'Velocity': array([-5.85965030e-02, 1.67938423e+00, -8.43906382e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.01301575, 14.34992981, 1.68680084]), + 'camera_rotation': array([-7.10557508, 1.23448455, -0.54100877]), + 'current_gear_input': False, + 'focus_actor_dist': 1147.1336669921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -620.01330566, -1968.53552246, 32.52599335]), + 'frame': 20770, + 'frame_number': 20770, + 'framesequence': 79382, + 'gaze_dir': array([0.95970154, 0.27949524, 0.02480316]), + 'gaze_origin': array([-3.08963275, -0.23125687, 0.05609131]), + 'gaze_valid': True, + 'gaze_vergence': 190.52935791015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9559021 , 0.29299927, 0.01954651]), + 'left_gaze_origin': array([-3.01493382, 2.95795918, 0.06026001]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1380767822265625, + 'left_pupil_posn': array([ 0.28203273, -0.06904006]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9136219024658203, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96350098, 0.26599121, 0.03005981]), + 'right_gaze_origin': array([-3.1643312 , -3.42047286, 0.05192261]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.18572998046875, + 'right_pupil_posn': array([ 0.26191318, -0.14992702]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015509507618844509, + 'throttle_input': 0.0, + 'timestamp': 672.180498868227, + 'timestamp_carla': 672181, + 'timestamp_device': 115432, + 'timestamp_stream': 672.180498868227, + 'transform': [array([-1.48899901e+00, -1.75991573e+01, 1.03787612e-02]), + array([-0.06277627, -2.20982909, 0.01736452])]} +{'AngularVelocity': array([ 0.03778427, 0.02638147, -0.58928919]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.9677713513374329, + 'FR_Wheel_Angle': -0.9060486555099487, + 'Location': array([ -3.53387666, -29.0965023 , 0.17283286]), + 'Rotation': array([-6.62528304e-03, 9.08200607e+01, -5.49621582e-02]), + 'Velocity': array([-7.09349196e-03, 1.81208658e+00, 2.26516713e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.01942062, 14.41335869, 1.68077993]), + 'camera_rotation': array([-7.11015844, 1.36396325, -0.28670618]), + 'current_gear_input': False, + 'focus_actor_dist': 1300.8570556640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -658.72766113, -1820.51220703, 17.39697266]), + 'frame': 20771, + 'frame_number': 20771, + 'framesequence': 79386, + 'gaze_dir': array([0.95608521, 0.28955841, 0.04096985]), + 'gaze_origin': array([-3.09001851, -0.23842776, 0.06511383]), + 'gaze_valid': True, + 'gaze_vergence': 147.2397918701172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95135498, 0.30625916, 0.03338623]), + 'left_gaze_origin': array([-3.01556706, 2.94841623, 0.06899567]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09417724609375, + 'left_pupil_posn': array([ 0.29110432, -0.05701435]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9153618216514587, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96081543, 0.27285767, 0.04855347]), + 'right_gaze_origin': array([-3.1644702 , -3.42527175, 0.061232 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2671356201171875, + 'right_pupil_posn': array([ 0.27005279, -0.13927734]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015070040710270405, + 'throttle_input': 0.0, + 'timestamp': 672.2151540666819, + 'timestamp_carla': 672216, + 'timestamp_device': 115466, + 'timestamp_stream': 672.2151540666819, + 'transform': [array([-1.48895991e+00, -1.75986881e+01, 1.04118157e-02]), + array([-0.06277627, -2.20990062, 0.01715089])]} +{'AngularVelocity': array([-0.04052773, 0.01486477, -0.41314331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.613470196723938, + 'FR_Wheel_Angle': -0.6096490025520325, + 'Location': array([ -3.53638291, -28.6713829 , 0.17286941]), + 'Rotation': array([-7.47905672e-03, 9.07039566e+01, -6.03027381e-02]), + 'Velocity': array([-9.33183078e-03, 1.88944042e+00, 1.10378263e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.01959038, 14.46179581, 1.66617703]), + 'camera_rotation': array([-7.11509657, 1.43786466, -0.11990637]), + 'current_gear_input': False, + 'focus_actor_dist': 1148.085693359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -632.70562744, -1969.64599609, 48.87999725]), + 'frame': 20772, + 'frame_number': 20772, + 'framesequence': 79389, + 'gaze_dir': array([0.95498657, 0.29302216, 0.04372406]), + 'gaze_origin': array([-3.09015369, -0.24029084, 0.06798477]), + 'gaze_valid': True, + 'gaze_vergence': 201.39271545410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95124817, 0.30589294, 0.03897095]), + 'left_gaze_origin': array([-3.01591349, 2.94598866, 0.07151031]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.18890380859375, + 'left_pupil_posn': array([ 0.29533994, -0.05560243]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9316264986991882, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95872498, 0.28015137, 0.04847717]), + 'right_gaze_origin': array([-3.1643939 , -3.42657042, 0.06445923]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.233367919921875, + 'right_pupil_posn': array([ 0.27087891, -0.13506269]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0142277292907238, + 'throttle_input': 0.0, + 'timestamp': 672.2438419684768, + 'timestamp_carla': 672244, + 'timestamp_device': 115491, + 'timestamp_stream': 672.2438419684768, + 'transform': [array([-1.48902762e+00, -1.75982170e+01, 1.03987306e-02]), + array([-0.06277627, -2.20949769, 0.01705934])]} +{'AngularVelocity': array([-0.0399643 , 0.00325049, -0.3991977 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5874443054199219, + 'FR_Wheel_Angle': -0.5424627661705017, + 'Location': array([ -3.53940725, -28.14140892, 0.17289169]), + 'Rotation': array([-7.44490558e-03, 9.05962067e+01, -6.16455153e-02]), + 'Velocity': array([-7.74182472e-03, 2.02699375e+00, 6.25514949e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.0329237 , 14.49359131, 1.65749621]), + 'camera_rotation': array([-7.19821978e+00, 1.46445227e+00, 1.13780284e-03]), + 'current_gear_input': True, + 'focus_actor_dist': 1148.9532470703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -638.50415039, -1970.18811035, 51.06907654]), + 'frame': 20773, + 'frame_number': 20773, + 'framesequence': 79393, + 'gaze_dir': array([0.95474243, 0.29367065, 0.04423523]), + 'gaze_origin': array([-3.08980131, -0.24027023, 0.06855164]), + 'gaze_valid': True, + 'gaze_vergence': 191.888916015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9503479 , 0.30836487, 0.0415802 ]), + 'left_gaze_origin': array([-3.01528645, 2.94673634, 0.0719223 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.181427001953125, + 'left_pupil_posn': array([ 0.29429853, -0.05588078]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9383209347724915, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95913696, 0.27897644, 0.04689026]), + 'right_gaze_origin': array([-3.16431594, -3.42727685, 0.06518097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2568359375, + 'right_pupil_posn': array([ 0.27226436, -0.13373804]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.013275551609694958, + 'throttle_input': 0.0, + 'timestamp': 672.2741502672434, + 'timestamp_carla': 672275, + 'timestamp_device': 115524, + 'timestamp_stream': 672.2741502672434, + 'transform': [array([-1.48900390e+00, -1.75976772e+01, 1.04338648e-02]), + array([-0.06277627, -2.20949769, 0.01705934])]} +{'AngularVelocity': array([-0.06460305, 0.00469333, -0.18069619]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.54173112, -27.72459602, 0.17292289]), + 'Rotation': array([-9.30271670e-03, 9.05369949e+01, -6.27136156e-02]), + 'Velocity': array([-1.21852122e-02, 2.06974292e+00, 1.56440728e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.05514812, 14.51885414, 1.63602328]), + 'camera_rotation': array([-7.26134443, 1.4660157 , 0.00808843]), + 'current_gear_input': False, + 'focus_actor_dist': 1149.722900390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -640.13336182, -1969.95410156, 49.32919312]), + 'frame': 20774, + 'frame_number': 20774, + 'framesequence': 79396, + 'gaze_dir': array([0.95464325, 0.2942276 , 0.0418396 ]), + 'gaze_origin': array([-3.08956838, -0.24041063, 0.0690712 ]), + 'gaze_valid': True, + 'gaze_vergence': 166.35235595703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94975281, 0.3106842 , 0.03756714]), + 'left_gaze_origin': array([-3.01504087, 2.94693923, 0.07246247]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1661224365234375, + 'left_pupil_posn': array([ 0.29374516, -0.05568957]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9106053113937378, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95953369, 0.277771 , 0.04611206]), + 'right_gaze_origin': array([-3.16409612, -3.42776036, 0.06567994]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.260650634765625, + 'right_pupil_posn': array([ 0.27340579, -0.13483083]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.012176885269582272, + 'throttle_input': 0.0, + 'timestamp': 672.3041846677661, + 'timestamp_carla': 672305, + 'timestamp_device': 115549, + 'timestamp_stream': 672.3041846677661, + 'transform': [array([-1.48897851e+00, -1.75971107e+01, 1.04566002e-02]), + array([-0.06277627, -2.20949769, 0.01705934])]} +{'AngularVelocity': array([-0.32570133, 0.45561442, 0.00149805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.546206 , -27.18538475, 0.17570995]), + 'Rotation': array([-9.18660406e-03, 9.05352554e+01, -2.72521973e-01]), + 'Velocity': array([-0.009512 , 1.94459224, 0.01351906]), + 'brake_input': 0.0, + 'camera_location': array([-6.08314323, 14.54793739, 1.62826204]), + 'camera_rotation': array([-7.33092356, 1.52456129, 0.0371774 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1151.12744140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -641.25177002, -1969.1048584 , 45.2355957 ]), + 'frame': 20775, + 'frame_number': 20775, + 'framesequence': 79400, + 'gaze_dir': array([0.95470428, 0.2937851 , 0.0435791 ]), + 'gaze_origin': array([-3.08936548, -0.24034654, 0.06930999]), + 'gaze_valid': True, + 'gaze_vergence': 172.68971252441406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94984436, 0.31004333, 0.04042053]), + 'left_gaze_origin': array([-3.01468825, 2.94714832, 0.07286683]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.18609619140625, + 'left_pupil_posn': array([ 0.29348683, -0.05515456]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.923198938369751, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95956421, 0.27752686, 0.04673767]), + 'right_gaze_origin': array([-3.16404295, -3.42784142, 0.06575318]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2528076171875, + 'right_pupil_posn': array([ 0.27325785, -0.13373804]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011352885514497757, + 'throttle_input': 0.0, + 'timestamp': 672.337194468826, + 'timestamp_carla': 672338, + 'timestamp_device': 115582, + 'timestamp_stream': 672.337194468826, + 'transform': [array([-1.48894954e+00, -1.75964661e+01, 1.04500391e-02]), + array([-0.06277627, -2.20949769, 0.01705934])]} +{'AngularVelocity': array([0.01930549, 0.01313249, 0.0008865 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -3.55000019, -26.75016594, 0.17292678]), + 'Rotation': array([-2.09345277e-02, 9.05353241e+01, -5.59997521e-02]), + 'Velocity': array([-0.01510886, 1.76382315, -0.00203432]), + 'brake_input': 0.0, + 'camera_location': array([-6.12822723, 14.570261 , 1.62508094]), + 'camera_rotation': array([-7.396029 , 1.66507423, 0.15339045]), + 'current_gear_input': False, + 'focus_actor_dist': 1151.144287109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -641.91815186, -1969.20666504, 45.70957947]), + 'frame': 20776, + 'frame_number': 20776, + 'framesequence': 79405, + 'gaze_dir': array([0.95438385, 0.29463196, 0.04521179]), + 'gaze_origin': array([-3.08908319, -0.23984529, 0.07045288]), + 'gaze_valid': True, + 'gaze_vergence': 181.85836791992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94969177, 0.31021118, 0.04269409]), + 'left_gaze_origin': array([-3.0142839 , 2.94807005, 0.07399445]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.195465087890625, + 'left_pupil_posn': array([ 0.29338026, -0.05401778]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9243863821029663, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95907593, 0.27905273, 0.04772949]), + 'right_gaze_origin': array([-3.16388273, -3.42776036, 0.06691132]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2657318115234375, + 'right_pupil_posn': array([ 0.27325785, -0.13214326]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011096530593931675, + 'throttle_input': 0.0, + 'timestamp': 672.37542456761, + 'timestamp_carla': 672376, + 'timestamp_device': 115624, + 'timestamp_stream': 672.37542456761, + 'transform': [array([-1.48916984e+00, -1.75956726e+01, 1.03784371e-02]), + array([-0.06277627, -2.20836377, 0.01715089])]} +{'AngularVelocity': array([-5.01476636e-04, 1.41898086e-02, -9.36416030e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.7912001609802246, + 'FR_Wheel_Angle': -1.8575407266616821, + 'Location': array([ -3.5507524 , -26.35876465, 0.17296398]), + 'Rotation': array([-2.06613205e-02, 9.04300079e+01, -5.63964881e-02]), + 'Velocity': array([1.70875266e-02, 1.59883833e+00, 3.37409962e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.15432262, 14.58917618, 1.64240718]), + 'camera_rotation': array([-7.26547003, 1.83324015, 0.27658561]), + 'current_gear_input': False, + 'focus_actor_dist': 1152.3563232421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -646.05529785, -1969.15124512, 45.60411072]), + 'frame': 20777, + 'frame_number': 20777, + 'framesequence': 79409, + 'gaze_dir': array([0.95502472, 0.29258728, 0.04540253]), + 'gaze_origin': array([-3.08884668, -0.23895952, 0.07267228]), + 'gaze_valid': True, + 'gaze_vergence': 195.9058380126953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95080566, 0.30683899, 0.04234314]), + 'left_gaze_origin': array([-3.01414204, 2.94968128, 0.07597046]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.198394775390625, + 'left_pupil_posn': array([ 0.29201794, -0.0524075 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9264737963676453, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95924377, 0.27833557, 0.04846191]), + 'right_gaze_origin': array([-3.16355157, -3.42760015, 0.06937409]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.263031005859375, + 'right_pupil_posn': array([ 0.27191389, -0.13042247]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011114842258393764, + 'throttle_input': 0.0, + 'timestamp': 672.4049267657101, + 'timestamp_carla': 672406, + 'timestamp_device': 115657, + 'timestamp_stream': 672.4049267657101, + 'transform': [array([-1.48842919e+00, -1.75951595e+01, 1.03484532e-02]), + array([-0.06277627, -2.21155024, 0.01715089])]} +{'AngularVelocity': array([ 0.00198701, 0.01258969, -0.97069716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.0120766162872314, + 'FR_Wheel_Angle': -1.9743742942810059, + 'Location': array([ -3.54757071, -26.05661011, 0.17303883]), + 'Rotation': array([-2.03812830e-02, 9.02333221e+01, -5.93871959e-02]), + 'Velocity': array([2.42908001e-02, 1.47138977e+00, 4.46281425e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.15567589, 14.58998585, 1.68094957]), + 'camera_rotation': array([-7.00010347, 1.99890721, 0.31124893]), + 'current_gear_input': False, + 'focus_actor_dist': 1151.997802734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -646.95043945, -1969.58361816, 47.55290222]), + 'frame': 20778, + 'frame_number': 20778, + 'framesequence': 79412, + 'gaze_dir': array([0.95608521, 0.28847504, 0.04756927]), + 'gaze_origin': array([-3.08824563, -0.23664017, 0.06976318]), + 'gaze_valid': True, + 'gaze_vergence': 145.9813995361328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95074463, 0.30706787, 0.04216003]), + 'left_gaze_origin': array([-3.01297617, 2.95384073, 0.07015228]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1934051513671875, + 'left_pupil_posn': array([ 0.28621519, -0.0543263 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9254112243652344, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96142578, 0.2698822 , 0.05297852]), + 'right_gaze_origin': array([-3.16351509, -3.42712116, 0.06937409]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2586669921875, + 'right_pupil_posn': array([ 0.27166748, -0.13046658]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011188086122274399, + 'throttle_input': 0.0, + 'timestamp': 672.4376972652972, + 'timestamp_carla': 672438, + 'timestamp_device': 115682, + 'timestamp_stream': 672.4376972652972, + 'transform': [array([-1.48852968e+00, -1.75944805e+01, 1.03554530e-02]), + array([-0.06277627, -2.21098042, 0.01727296])]} +{'AngularVelocity': array([ 0.00185426, 0.00376224, -0.85912323]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.11348557472229, + 'FR_Wheel_Angle': -2.1966781616210938, + 'Location': array([ -3.54280114, -25.73024559, 0.1730677 ]), + 'Rotation': array([-1.99304912e-02, 9.00162354e+01, -6.10656776e-02]), + 'Velocity': array([2.74972245e-02, 1.33381188e+00, 2.49719626e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.13549328, 14.58955002, 1.71988344]), + 'camera_rotation': array([-6.85795355, 2.088938 , 0.29735205]), + 'current_gear_input': False, + 'focus_actor_dist': 1149.8555908203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -644.76843262, -1970.54528809, 54.95252991]), + 'frame': 20779, + 'frame_number': 20779, + 'framesequence': 79417, + 'gaze_dir': array([0.95684052, 0.28682709, 0.04455566]), + 'gaze_origin': array([-3.08812809, -0.23688737, 0.06491242]), + 'gaze_valid': True, + 'gaze_vergence': 210.5582733154297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95317078, 0.29966736, 0.04069519]), + 'left_gaze_origin': array([-3.01344776, 2.95433211, 0.06794129]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1674041748046875, + 'left_pupil_posn': array([ 0.28734493, -0.057531 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9292333722114563, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96051025, 0.27398682, 0.04841614]), + 'right_gaze_origin': array([-3.16280842, -3.42810678, 0.06188355]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2462921142578125, + 'right_pupil_posn': array([ 0.26964366, -0.13575125]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011188086122274399, + 'throttle_input': 0.0, + 'timestamp': 672.4730039685965, + 'timestamp_carla': 672474, + 'timestamp_device': 115724, + 'timestamp_stream': 672.4730039685965, + 'transform': [array([-1.48839653e+00, -1.75937843e+01, 1.03370668e-02]), + array([-0.06277627, -2.21142077, 0.01736451])]} +{'AngularVelocity': array([ 1.17809221e-03, -7.70080369e-03, -1.37040544e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.042256832122803, + 'FR_Wheel_Angle': -4.223811149597168, + 'Location': array([ -3.53573966, -25.43465042, 0.17307925]), + 'Rotation': array([-1.95616614e-02, 8.97519836e+01, -5.92040978e-02]), + 'Velocity': array([4.92163040e-02, 1.20844924e+00, 9.61399055e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.12850189, 14.59524727, 1.72450817]), + 'camera_rotation': array([-6.92298365, 2.0745759 , 0.06840255]), + 'current_gear_input': False, + 'focus_actor_dist': 1149.3780517578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -644.39794922, -1970.90319824, 54.29193115]), + 'frame': 20780, + 'frame_number': 20780, + 'framesequence': 79421, + 'gaze_dir': array([0.95719147, 0.28567505, 0.04384613]), + 'gaze_origin': array([-3.0872612 , -0.23698045, 0.06678239]), + 'gaze_valid': True, + 'gaze_vergence': 192.44747924804688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95317078, 0.29977417, 0.03970337]), + 'left_gaze_origin': array([-3.01207757, 2.9540894 , 0.07133331]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.186431884765625, + 'left_pupil_posn': array([ 0.28659058, -0.05512798]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9279123544692993, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96121216, 0.27157593, 0.04798889]), + 'right_gaze_origin': array([-3.16244507, -3.42805052, 0.06223145]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.235748291015625, + 'right_pupil_posn': array([ 0.26964366, -0.13575125]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011334575712680817, + 'throttle_input': 0.027771420776844025, + 'timestamp': 672.5071610659361, + 'timestamp_carla': 672508, + 'timestamp_device': 115757, + 'timestamp_stream': 672.5071610659361, + 'transform': [array([-1.48797417e+00, -1.75932617e+01, 1.03265569e-02]), + array([-0.06280359, -2.21320748, 0.01745606])]} +{'AngularVelocity': array([ 0.00285598, 0.00563884, -2.01804042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.167585372924805, + 'FR_Wheel_Angle': -5.974279880523682, + 'Location': array([ -3.52304864, -25.16700554, 0.17308185]), + 'Rotation': array([-1.91381890e-02, 8.93170319e+01, -5.78918383e-02]), + 'Velocity': array([7.69268423e-02, 1.09323239e+00, 4.59003422e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.14981461, 14.59756374, 1.6831913 ]), + 'camera_rotation': array([-7.08414888, 2.05988979, -0.00831105]), + 'current_gear_input': False, + 'focus_actor_dist': 1148.9910888671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -642.48974609, -1970.71765137, 53.52876282]), + 'frame': 20781, + 'frame_number': 20781, + 'framesequence': 79425, + 'gaze_dir': array([0.95685577, 0.28669739, 0.04436493]), + 'gaze_origin': array([-3.08703089, -0.23696749, 0.06774369]), + 'gaze_valid': True, + 'gaze_vergence': 193.8221435546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95254517, 0.30142212, 0.04206848]), + 'left_gaze_origin': array([-3.01189446, 2.95411706, 0.07178803]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1821746826171875, + 'left_pupil_posn': array([ 0.28671551, -0.05522251]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9234427809715271, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96116638, 0.27197266, 0.04666138]), + 'right_gaze_origin': array([-3.16216755, -3.42805195, 0.06369934]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2280426025390625, + 'right_pupil_posn': array([ 0.27024567, -0.13391864]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011719108559191227, + 'throttle_input': 0.0476234070956707, + 'timestamp': 672.5385207682848, + 'timestamp_carla': 672539, + 'timestamp_device': 115791, + 'timestamp_stream': 672.5385207682848, + 'transform': [array([-1.48776543e+00, -1.75927620e+01, 1.03375623e-02]), + array([-0.06283091, -2.21409202, 0.0175171 ])]} +{'AngularVelocity': array([ 0.01100068, 0.00799402, -0.92492658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.910547733306885, + 'FR_Wheel_Angle': -6.52933931350708, + 'Location': array([ -3.50783324, -24.94158554, 0.17311314]), + 'Rotation': array([-2.22800765e-02, 8.88516998e+01, -6.05773963e-02]), + 'Velocity': array([ 7.64525980e-02, 8.80094945e-01, -5.75828526e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.14856148, 14.59720612, 1.66836143]), + 'camera_rotation': array([-7.12536907, 2.01737714, 0.14004682]), + 'current_gear_input': False, + 'focus_actor_dist': 1149.6865234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -643.4864502 , -1970.40515137, 51.43299103]), + 'frame': 20782, + 'frame_number': 20782, + 'framesequence': 79428, + 'gaze_dir': array([0.95672607, 0.28746796, 0.04207611]), + 'gaze_origin': array([-3.08698893, -0.23705445, 0.06741104]), + 'gaze_valid': True, + 'gaze_vergence': 188.9226837158203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95251465, 0.30204773, 0.03831482]), + 'left_gaze_origin': array([-3.01184869, 2.95399809, 0.07129364]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.181640625, + 'left_pupil_posn': array([ 0.28711414, -0.0558511 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9214367270469666, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9609375 , 0.27288818, 0.0458374 ]), + 'right_gaze_origin': array([-3.16212916, -3.42810678, 0.06352845]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.226776123046875, + 'right_pupil_posn': array([ 0.27047992, -0.13536191]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.012158574536442757, + 'throttle_input': 0.059525445103645325, + 'timestamp': 672.5702906660736, + 'timestamp_carla': 672571, + 'timestamp_device': 115816, + 'timestamp_stream': 672.5702906660736, + 'transform': [array([-1.48760128e+00, -1.75922832e+01, 1.03356363e-02]), + array([-0.06283091, -2.21477485, 0.01757813])]} +{'AngularVelocity': array([ 2.64661349e-02, 3.49588590e-05, -8.46451521e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.897756576538086, + 'FR_Wheel_Angle': -6.392144203186035, + 'Location': array([ -3.49229383, -24.74502373, 0.17308055]), + 'Rotation': array([-1.78267919e-02, 8.84081268e+01, -6.14624061e-02]), + 'Velocity': array([ 7.88897946e-02, 8.22669029e-01, -3.24020366e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.12913322, 14.59579468, 1.65015864]), + 'camera_rotation': array([-7.14909029, 1.9161849 , 0.16333373]), + 'current_gear_input': False, + 'focus_actor_dist': 1150.9847412109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -644.04266357, -1969.50097656, 47.08930969]), + 'frame': 20783, + 'frame_number': 20783, + 'framesequence': 79433, + 'gaze_dir': array([0.97761536, 0.2020874 , 0.0556488 ]), + 'gaze_origin': array([-3.02884912, -0.16977921, 0.0627739 ]), + 'gaze_valid': True, + 'gaze_vergence': 160.94590759277344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97457886, 0.21861267, 0.04898071]), + 'left_gaze_origin': array([-2.90925288, 3.03123641, 0.05275879]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2137908935546875, + 'left_pupil_posn': array([ 0.20288193, -0.04191029]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9383232593536377, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98065186, 0.18556213, 0.06231689]), + 'right_gaze_origin': array([-3.14844513, -3.37079477, 0.07278901]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1365509033203125, + 'right_pupil_posn': array([ 0.20077527, -0.1200918 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01300088595598936, + 'throttle_input': 0.0634927898645401, + 'timestamp': 672.6064209677279, + 'timestamp_carla': 672607, + 'timestamp_device': 115857, + 'timestamp_stream': 672.6064209677279, + 'transform': [array([-1.48742700e+00, -1.75918102e+01, 1.02863116e-02]), + array([-0.06283091, -2.21551633, 0.01766969])]} +{'AngularVelocity': array([ 0.03470582, -0.00606378, -1.168167 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.351731300354004, + 'FR_Wheel_Angle': -6.012521266937256, + 'Location': array([ -3.47518158, -24.54188156, 0.17304592]), + 'Rotation': array([-9.64422617e-03, 8.79704742e+01, -6.10351600e-02]), + 'Velocity': array([ 9.22549739e-02, 9.44257081e-01, -1.24864571e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.12520123, 14.60296726, 1.62832212]), + 'camera_rotation': array([-7.21177769, 1.83356333, 0.16746792]), + 'current_gear_input': False, + 'focus_actor_dist': 1117.20947265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -537.1340332 , -1976.51574707, 61.40518188]), + 'frame': 20784, + 'frame_number': 20784, + 'framesequence': 79437, + 'gaze_dir': array([0.98957062, 0.12146759, 0.07645416]), + 'gaze_origin': array([-3.0663383 , -0.09857636, 0.0885994 ]), + 'gaze_valid': True, + 'gaze_vergence': 281.9903259277344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98820496, 0.13259888, 0.07644653]), + 'left_gaze_origin': array([-3.00940728, 3.09404612, 0.09709778]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.16595458984375, + 'left_pupil_posn': array([ 0.13564527, -0.0245198 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99093628, 0.1103363 , 0.07646179]), + 'right_gaze_origin': array([-3.1232698 , -3.29119897, 0.08010102]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0390167236328125, + 'right_pupil_posn': array([ 0.11564374, -0.09875488]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01424604095518589, + 'throttle_input': 0.07539482414722443, + 'timestamp': 672.639382366091, + 'timestamp_carla': 672640, + 'timestamp_device': 115891, + 'timestamp_stream': 672.639382366091, + 'transform': [array([-1.48741639e+00, -1.75912971e+01, 1.02955820e-02]), + array([-0.06283091, -2.21551633, 0.01766969])]} +{'AngularVelocity': array([ 0.0143368 , -0.01553172, -1.78435326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.144056797027588, + 'FR_Wheel_Angle': -6.835628032684326, + 'Location': array([ -3.45287251, -24.29705238, 0.17300716]), + 'Rotation': array([-3.94101907e-03, 8.74478683e+01, -5.88073730e-02]), + 'Velocity': array([ 1.27684101e-01, 1.14700413e+00, -3.64112842e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.10574341, 14.58633232, 1.61931324]), + 'camera_rotation': array([-7.24632502, 1.72114742, 0.25490025]), + 'current_gear_input': False, + 'focus_actor_dist': 2789.938720703125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-6.38077393e+02, -3.01160400e+02, 2.44140625e-04]), + 'frame': 20785, + 'frame_number': 20785, + 'framesequence': 79441, + 'gaze_dir': array([0.98976898, 0.12041473, 0.07492065]), + 'gaze_origin': array([-3.07781315, -0.10325012, 0.09147874]), + 'gaze_valid': True, + 'gaze_vergence': 146.17422485351562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98768616, 0.13087463, 0.08563232]), + 'left_gaze_origin': array([-3.0298326 , 3.08913732, 0.10231019]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0497589111328125, + 'left_pupil_posn': array([ 0.13899195, -0.02872801]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99185181, 0.10995483, 0.06420898]), + 'right_gaze_origin': array([-3.12579346, -3.29563761, 0.08064728]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.054779052734375, + 'right_pupil_posn': array([ 0.11817825, -0.09569871]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.016003906726837158, + 'throttle_input': 0.08332952111959457, + 'timestamp': 672.6725248657167, + 'timestamp_carla': 672673, + 'timestamp_device': 115924, + 'timestamp_stream': 672.6725248657167, + 'transform': [array([-1.48740566e+00, -1.75907707e+01, 1.02993203e-02]), + array([-0.06283091, -2.21551633, 0.01766969])]} +{'AngularVelocity': array([ 0.00915931, -0.00797904, -2.7704556 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.108046531677246, + 'FR_Wheel_Angle': -7.516139507293701, + 'Location': array([ -3.42025328, -24.00005722, 0.17299464]), + 'Rotation': array([-1.52996229e-03, 8.67171326e+01, -5.57861328e-02]), + 'Velocity': array([1.86442614e-01, 1.38182509e+00, 2.36892702e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.08694935, 14.54894638, 1.61955833]), + 'camera_rotation': array([-7.2456212 , 1.57184005, 0.30914211]), + 'current_gear_input': False, + 'focus_actor_dist': 2365.32958984375, + 'focus_actor_name': 'Road_Curb_Town05_210', + 'focus_actor_pt': array([-582.35314941, -721.87207031, 15.2399826 ]), + 'frame': 20786, + 'frame_number': 20786, + 'framesequence': 79444, + 'gaze_dir': array([0.99020386, 0.12016296, 0.07010651]), + 'gaze_origin': array([-3.07875824, -0.10551301, 0.09047166]), + 'gaze_valid': True, + 'gaze_vergence': 249.9062957763672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98864746, 0.1300354 , 0.07521057]), + 'left_gaze_origin': array([-3.01873493, 3.08884597, 0.09752198]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0824127197265625, + 'left_pupil_posn': array([ 0.13921535, -0.02970302]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99176025, 0.11029053, 0.06500244]), + 'right_gaze_origin': array([-3.13878179, -3.29987192, 0.08342133]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.006591796875, + 'right_pupil_posn': array([ 0.12106371, -0.09974468]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.018036440014839172, + 'throttle_input': 0.0952315554022789, + 'timestamp': 672.7049358673394, + 'timestamp_carla': 672706, + 'timestamp_device': 115949, + 'timestamp_stream': 672.7049358673394, + 'transform': [array([-1.48742068e+00, -1.75902100e+01, 1.03199389e-02]), + array([-0.06283091, -2.21539664, 0.01760865])]} +{'AngularVelocity': array([ 1.30007174e-02, 2.87220161e-03, -3.47922945e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.5045881271362305, + 'FR_Wheel_Angle': -6.759521007537842, + 'Location': array([ -3.37508607, -23.64643097, 0.17298782]), + 'Rotation': array([ 1.28407544e-03, 8.57927551e+01, -5.54504357e-02]), + 'Velocity': array([2.48215124e-01, 1.66848934e+00, 1.36837960e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.05423164, 14.52513695, 1.61062884]), + 'camera_rotation': array([-7.22745323, 1.39438081, 0.21209785]), + 'current_gear_input': False, + 'focus_actor_dist': 2162.5576171875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-553.51812744, -922.92773438, 14.95740509]), + 'frame': 20787, + 'frame_number': 20787, + 'framesequence': 79449, + 'gaze_dir': array([0.98963165, 0.12285614, 0.07315063]), + 'gaze_origin': array([-3.06423593, -0.10725937, 0.08643266]), + 'gaze_valid': True, + 'gaze_vergence': 199.55628967285156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98777771, 0.13345337, 0.08047485]), + 'left_gaze_origin': array([-3.00441599, 3.08837438, 0.09393159]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.089111328125, + 'left_pupil_posn': array([ 0.14011228, -0.0292418 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9914856 , 0.11225891, 0.06582642]), + 'right_gaze_origin': array([-3.12405562, -3.30289316, 0.07893372]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0229644775390625, + 'right_pupil_posn': array([ 0.12396085, -0.09833479]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.020929595455527306, + 'throttle_input': 0.1111009418964386, + 'timestamp': 672.7376953661442, + 'timestamp_carla': 672738, + 'timestamp_device': 115991, + 'timestamp_stream': 672.7376953661442, + 'transform': [array([-1.48745394e+00, -1.75896015e+01, 1.03344722e-02]), + array([-0.06283091, -2.21519876, 0.01754762])]} +{'AngularVelocity': array([ 0.00886231, 0.0242739 , -2.70935035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.566652297973633, + 'FR_Wheel_Angle': -3.8300201892852783, + 'Location': array([ -3.31834507, -23.22280693, 0.17298053]), + 'Rotation': array([ 2.58181128e-03, 8.48788300e+01, -5.99365272e-02]), + 'Velocity': array([2.77729213e-01, 1.95995736e+00, 2.29797355e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.04101181, 14.50066376, 1.59092128]), + 'camera_rotation': array([-7.3158083 , 1.22461009, 0.14133395]), + 'current_gear_input': False, + 'focus_actor_dist': 2305.204833984375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-567.99591064, -780.6862793 , 15.23073578]), + 'frame': 20788, + 'frame_number': 20788, + 'framesequence': 79452, + 'gaze_dir': array([0.98931885, 0.12392426, 0.07555389]), + 'gaze_origin': array([-3.05955219, -0.10847549, 0.08473893]), + 'gaze_valid': True, + 'gaze_vergence': 160.65785217285156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98748779, 0.13264465, 0.08525085]), + 'left_gaze_origin': array([-3.00568247, 3.08747578, 0.09438934]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0884552001953125, + 'left_pupil_posn': array([ 0.14174724, -0.02918625]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9911499 , 0.11520386, 0.06585693]), + 'right_gaze_origin': array([-3.11342192, -3.30442667, 0.07508851]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.084197998046875, + 'right_pupil_posn': array([ 0.12444484, -0.0974735 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02451857179403305, + 'throttle_input': 0.12300297617912292, + 'timestamp': 672.7709752656519, + 'timestamp_carla': 672772, + 'timestamp_device': 116016, + 'timestamp_stream': 672.7709752656519, + 'transform': [array([-1.48751402e+00, -1.75889359e+01, 1.03439903e-02]), + array([-0.06283091, -2.21486378, 0.01748658])]} +{'AngularVelocity': array([-0.01469926, -0.00337884, -0.51067871]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.569940209388733, + 'FR_Wheel_Angle': -1.4945013523101807, + 'Location': array([ -3.25139284, -22.66586685, 0.1730009 ]), + 'Rotation': array([-6.42037718e-04, 8.43271332e+01, -6.70471117e-02]), + 'Velocity': array([2.53162444e-01, 2.17777181e+00, 2.44150142e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.01719952, 14.46228409, 1.56604421]), + 'camera_rotation': array([-7.40043449, 1.10484958, 0.23463033]), + 'current_gear_input': False, + 'focus_actor_dist': 2351.375244140625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-568.41357422, -734.14916992, 15.23960114]), + 'frame': 20789, + 'frame_number': 20789, + 'framesequence': 79456, + 'gaze_dir': array([0.9888382 , 0.1271286 , 0.07661438]), + 'gaze_origin': array([-3.07061934, -0.1124756 , 0.08907013]), + 'gaze_valid': True, + 'gaze_vergence': 157.53549194335938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9871521 , 0.13444519, 0.08622742]), + 'left_gaze_origin': array([-3.03089762, 3.08061385, 0.10363923]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1448974609375, + 'left_pupil_posn': array([ 0.14813054, -0.02737582]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99052429, 0.11981201, 0.06700134]), + 'right_gaze_origin': array([-3.11034107, -3.30556512, 0.07450104]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.085479736328125, + 'right_pupil_posn': array([ 0.1257745 , -0.09700167]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.028858304023742676, + 'throttle_input': 0.1269855797290802, + 'timestamp': 672.8036956675351, + 'timestamp_carla': 672804, + 'timestamp_device': 116049, + 'timestamp_stream': 672.8036956675351, + 'transform': [array([-1.48763788e+00, -1.75881939e+01, 1.03658102e-02]), + array([-0.06283091, -2.21426988, 0.01739503])]} +{'AngularVelocity': array([-0.06133091, -0.04821637, -1.58456242]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.14107346534729, + 'FR_Wheel_Angle': -3.7390835285186768, + 'Location': array([ -3.19054198, -22.14805603, 0.1729652 ]), + 'Rotation': array([-8.54456611e-03, 8.39937744e+01, -5.59997447e-02]), + 'Velocity': array([ 3.01831096e-01, 2.25115561e+00, -6.59790006e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.99637604, 14.42084694, 1.53635085]), + 'camera_rotation': array([-7.56917429, 1.01425195, 0.24708095]), + 'current_gear_input': False, + 'focus_actor_dist': 2325.863525390625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-568.59735107, -759.7902832 , 15.23470306]), + 'frame': 20790, + 'frame_number': 20790, + 'framesequence': 79460, + 'gaze_dir': array([0.98875427, 0.12693787, 0.07804871]), + 'gaze_origin': array([-3.07191253, -0.11350175, 0.09005433]), + 'gaze_valid': True, + 'gaze_vergence': 190.81907653808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98704529, 0.13519287, 0.08625793]), + 'left_gaze_origin': array([-3.03506804, 3.0796206 , 0.1059723 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1143035888671875, + 'left_pupil_posn': array([ 0.14847064, -0.02554178]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99046326, 0.11868286, 0.06983948]), + 'right_gaze_origin': array([-3.10875726, -3.30662394, 0.07413635]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0554962158203125, + 'right_pupil_posn': array([ 0.12672853, -0.09691107]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.033637501299381256, + 'throttle_input': 0.13492026925086975, + 'timestamp': 672.8387609682977, + 'timestamp_carla': 672839, + 'timestamp_device': 116082, + 'timestamp_stream': 672.8387609682977, + 'transform': [array([-1.48776674e+00, -1.75873547e+01, 1.03604887e-02]), + array([-0.06286506, -2.2136445 , 0.017334 ])]} +{'AngularVelocity': array([-0.08033466, -0.02902302, -5.66646528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.200894355773926, + 'FR_Wheel_Angle': -9.117345809936523, + 'Location': array([ -3.12104082, -21.70153999, 0.17288856]), + 'Rotation': array([-2.20956616e-02, 8.31531296e+01, -4.08020020e-02]), + 'Velocity': array([ 4.26794589e-01, 2.14185309e+00, -9.79223172e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.97729015, 14.40547276, 1.52096093]), + 'camera_rotation': array([-7.70228767, 0.9007777 , 0.19709021]), + 'current_gear_input': False, + 'focus_actor_dist': 2260.430908203125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-557.57116699, -824.41748047, 15.20536804]), + 'frame': 20791, + 'frame_number': 20791, + 'framesequence': 79465, + 'gaze_dir': array([0.98880768, 0.12949371, 0.07350922]), + 'gaze_origin': array([-3.09151459, -0.11755677, 0.10132752]), + 'gaze_valid': True, + 'gaze_vergence': 258.9936218261719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98748779, 0.13616943, 0.07949829]), + 'left_gaze_origin': array([-3.03419805, 3.07638097, 0.10873566]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0723724365234375, + 'left_pupil_posn': array([ 0.15210438, -0.02430248]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99012756, 0.12281799, 0.06752014]), + 'right_gaze_origin': array([-3.14883137, -3.31149483, 0.09391937]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.049835205078125, + 'right_pupil_posn': array([ 0.1314621 , -0.09319341]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03878292441368103, + 'throttle_input': 0.13888761401176453, + 'timestamp': 672.8716731667519, + 'timestamp_carla': 672872, + 'timestamp_device': 116124, + 'timestamp_stream': 672.8716731667519, + 'transform': [array([-1.48800659e+00, -1.75864334e+01, 1.03946496e-02]), + array([-0.06286506, -2.21249986, 0.01721192])]} +{'AngularVelocity': array([-0.0338657 , 0.04511918, -7.31535053]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.998790740966797, + 'FR_Wheel_Angle': -10.882120132446289, + 'Location': array([ -3.01826739, -21.22755241, 0.1727877 ]), + 'Rotation': array([-3.56809050e-02, 8.15077209e+01, -4.04663086e-02]), + 'Velocity': array([ 5.09376407e-01, 1.91850400e+00, -9.23633575e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.95540905, 14.39061737, 1.50764501]), + 'camera_rotation': array([-7.81358576, 0.82043815, 0.1753771 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1978.4561767578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -528.5645752, -1105.1697998, 17.0530014]), + 'frame': 20792, + 'frame_number': 20792, + 'framesequence': 79469, + 'gaze_dir': array([0.98873901, 0.12928772, 0.07492828]), + 'gaze_origin': array([-3.09759164, -0.12024003, 0.10772554]), + 'gaze_valid': True, + 'gaze_vergence': 392.6358642578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9876709 , 0.13568115, 0.07806396]), + 'left_gaze_origin': array([-3.030617 , 3.07377338, 0.11282197]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.079132080078125, + 'left_pupil_posn': array([ 0.15388155, -0.01945937]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98980713, 0.12289429, 0.0717926 ]), + 'right_gaze_origin': array([-3.16456628, -3.31425333, 0.1026291 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9683380126953125, + 'right_pupil_posn': array([ 0.13362682, -0.09052968]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.043964967131614685, + 'throttle_input': 0.1428549587726593, + 'timestamp': 672.9053622670472, + 'timestamp_carla': 672906, + 'timestamp_device': 116157, + 'timestamp_stream': 672.9053622670472, + 'transform': [array([-1.48829651e+00, -1.75853882e+01, 1.04195401e-02]), + array([-0.06289238, -2.21115756, 0.01708985])]} +{'AngularVelocity': array([-0.02381043, 0.01090094, -7.82178783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.854833602905273, + 'FR_Wheel_Angle': -12.536288261413574, + 'Location': array([ -2.89283347, -20.75780296, 0.17264447]), + 'Rotation': array([-4.36107554e-02, 7.95502396e+01, -4.55932580e-02]), + 'Velocity': array([ 5.45859873e-01, 1.69362831e+00, -7.49130209e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.93415833, 14.39347267, 1.49211979]), + 'camera_rotation': array([-7.87890959, 0.73447424, 0.14111346]), + 'current_gear_input': False, + 'focus_actor_dist': 1963.59375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -523.81018066, -1119.53149414, 17.05185699]), + 'frame': 20793, + 'frame_number': 20793, + 'framesequence': 79473, + 'gaze_dir': array([0.9715271 , 0.22649384, 0.06770325]), + 'gaze_origin': array([-3.08215666, -0.19150086, 0.0858284 ]), + 'gaze_valid': True, + 'gaze_vergence': 207.01165771484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96809387, 0.2409668 , 0.06855774]), + 'left_gaze_origin': array([-3.02851129, 2.9959352 , 0.09493104]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.07550048828125, + 'left_pupil_posn': array([ 0.23763287, -0.03425503]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9894275665283203, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97496033, 0.21202087, 0.06684875]), + 'right_gaze_origin': array([-3.13580179, -3.37893701, 0.07672577]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0050048828125, + 'right_pupil_posn': array([ 0.21415305, -0.10857129]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04887234419584274, + 'throttle_input': 0.14682230353355408, + 'timestamp': 672.9380469657481, + 'timestamp_carla': 672939, + 'timestamp_device': 116191, + 'timestamp_stream': 672.9380469657481, + 'transform': [array([-1.48872042e+00, -1.75842133e+01, 1.04530333e-02]), + array([-0.06289238, -2.2092073 , 0.01696778])]} +{'AngularVelocity': array([-0.01411056, 0.0241746 , -7.52386379]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.646076202392578, + 'FR_Wheel_Angle': -12.876443862915039, + 'Location': array([ -2.77325273, -20.38179398, 0.17250644]), + 'Rotation': array([-4.87129055e-02, 7.77445145e+01, -4.92858812e-02]), + 'Velocity': array([ 5.55316687e-01, 1.51448822e+00, -8.47225194e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.89582539, 14.40732956, 1.47235322]), + 'camera_rotation': array([-7.87044716, 0.66714019, 0.2294386 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1117.367919921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -541.88659668, -1976.51501465, 61.71761322]), + 'frame': 20794, + 'frame_number': 20794, + 'framesequence': 79476, + 'gaze_dir': array([0.96618652, 0.24948883, 0.06291962]), + 'gaze_origin': array([-3.08521271, -0.20412752, 0.08457718]), + 'gaze_valid': True, + 'gaze_vergence': 182.64158630371094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96199036, 0.26478577, 0.06668091]), + 'left_gaze_origin': array([-3.03199768, 2.98129129, 0.09407043]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.071319580078125, + 'left_pupil_posn': array([ 0.25540185, -0.0385716 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9733208417892456, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97038269, 0.23419189, 0.05915833]), + 'right_gaze_origin': array([-3.13842773, -3.38954639, 0.07508393]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0009613037109375, + 'right_pupil_posn': array([ 0.23002958, -0.11147892]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05334025248885155, + 'throttle_input': 0.15475699305534363, + 'timestamp': 672.9703985676169, + 'timestamp_carla': 672971, + 'timestamp_device': 116216, + 'timestamp_stream': 672.9703985676169, + 'transform': [array([-1.48938107e+00, -1.75828419e+01, 1.05060386e-02]), + array([-0.06292653, -2.20620131, 0.01675416])]} +{'AngularVelocity': array([-0.0162591 , 0.00738433, -7.0158782 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.304412841796875, + 'FR_Wheel_Angle': -13.416519165039062, + 'Location': array([ -2.65957475, -20.06108284, 0.1724239 ]), + 'Rotation': array([-5.27905300e-02, 7.61495895e+01, -5.12390025e-02]), + 'Velocity': array([ 5.51562965e-01, 1.36232781e+00, -3.86986736e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.8501873 , 14.44141293, 1.45401752]), + 'camera_rotation': array([-7.89935255, 0.6485709 , 0.33898014]), + 'current_gear_input': False, + 'focus_actor_dist': 1122.233642578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -567.70166016, -1977.37207031, 56.57540894]), + 'frame': 20795, + 'frame_number': 20795, + 'framesequence': 79480, + 'gaze_dir': array([0.96650696, 0.24835205, 0.06298065]), + 'gaze_origin': array([-3.08500147, -0.20466919, 0.08494721]), + 'gaze_valid': True, + 'gaze_vergence': 211.7352752685547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96287537, 0.26179504, 0.06573486]), + 'left_gaze_origin': array([-3.03179026, 2.98164368, 0.09443665]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0602569580078125, + 'left_pupil_posn': array([ 0.25542212, -0.03790808]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9747039079666138, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97013855, 0.23490906, 0.06022644]), + 'right_gaze_origin': array([-3.13821292, -3.39098239, 0.07545777]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0182037353515625, + 'right_pupil_posn': array([ 0.22991383, -0.11147892]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05729545280337334, + 'throttle_input': 0.16269169747829437, + 'timestamp': 673.0035978667438, + 'timestamp_carla': 673004, + 'timestamp_device': 116249, + 'timestamp_stream': 673.0035978667438, + 'transform': [array([-1.48986781e+00, -1.75812626e+01, 1.05440896e-02]), + array([-0.06292653, -2.20396376, 0.01657106])]} +{'AngularVelocity': array([-1.09566404e-02, 1.22931949e-03, -6.61407375e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.632591247558594, + 'FR_Wheel_Angle': -13.618529319763184, + 'Location': array([ -2.5577178 , -19.79940414, 0.17229396]), + 'Rotation': array([-5.59392460e-02, 7.47821808e+01, -5.20019457e-02]), + 'Velocity': array([ 5.41844726e-01, 1.23834693e+00, -6.84475875e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.79700756, 14.49043655, 1.43585503]), + 'camera_rotation': array([-7.98068619, 0.7027359 , 0.43389302]), + 'current_gear_input': False, + 'focus_actor_dist': 1121.472900390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -566.1104126 , -1977.6796875 , 55.56786346]), + 'frame': 20796, + 'frame_number': 20796, + 'framesequence': 79484, + 'gaze_dir': array([0.96673584, 0.24744415, 0.06330109]), + 'gaze_origin': array([-3.08490849, -0.20459671, 0.08532563]), + 'gaze_valid': True, + 'gaze_vergence': 233.4661865234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96342468, 0.25996399, 0.06488037]), + 'left_gaze_origin': array([-3.03169274, 2.98225737, 0.0948761 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0659637451171875, + 'left_pupil_posn': array([ 0.25501263, -0.03709722]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.96323561668396, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.970047 , 0.23492432, 0.0617218 ]), + 'right_gaze_origin': array([-3.13812423, -3.39145064, 0.07577515]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0106964111328125, + 'right_pupil_posn': array([ 0.22958326, -0.11147892]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06161687523126602, + 'throttle_input': 0.1904631108045578, + 'timestamp': 673.0370816662908, + 'timestamp_carla': 673038, + 'timestamp_device': 116282, + 'timestamp_stream': 673.0370816662908, + 'transform': [array([-1.49047029e+00, -1.75795155e+01, 1.05726812e-02]), + array([-0.062988 , -2.201231 , 0.01641847])]} +{'AngularVelocity': array([-8.53989366e-03, -4.62023309e-03, -6.10349417e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.687108039855957, + 'FR_Wheel_Angle': -13.672285079956055, + 'Location': array([ -2.4577179 , -19.56007957, 0.17211917]), + 'Rotation': array([-5.74350581e-02, 7.35058060e+01, -5.09033166e-02]), + 'Velocity': array([ 0.52440369, 1.12732673, -0.00134668]), + 'brake_input': 0.0, + 'camera_location': array([-5.74444771, 14.53365898, 1.40538144]), + 'camera_rotation': array([-8.02278042, 0.83502561, 0.59830087]), + 'current_gear_input': False, + 'focus_actor_dist': 1121.3433837890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -566.28973389, -1977.76135254, 53.90133667]), + 'frame': 20797, + 'frame_number': 20797, + 'framesequence': 79488, + 'gaze_dir': array([0.96729279, 0.24436951, 0.06603241]), + 'gaze_origin': array([-3.08424473, -0.20315172, 0.08641434]), + 'gaze_valid': True, + 'gaze_vergence': 193.06317138671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96359253, 0.25959778, 0.06385803]), + 'left_gaze_origin': array([-3.03051758, 2.98514724, 0.0962021 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0767059326171875, + 'left_pupil_posn': array([ 0.25101483, -0.03365767]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9698855876922607, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97099304, 0.22914124, 0.06820679]), + 'right_gaze_origin': array([-3.1379714 , -3.39145064, 0.07662659]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.996337890625, + 'right_pupil_posn': array([ 0.22944975, -0.11119831]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06606647372245789, + 'throttle_input': 0.21428243815898895, + 'timestamp': 673.0713425688446, + 'timestamp_carla': 673072, + 'timestamp_device': 116316, + 'timestamp_stream': 673.0713425688446, + 'transform': [array([-1.48996818e+00, -1.75767231e+01, 1.08341593e-02]), + array([-0.06317241, -2.20344758, 0.01519777])]} +{'AngularVelocity': array([-0.01108222, -0.01077697, -5.83081627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.313983917236328, + 'FR_Wheel_Angle': -14.25330924987793, + 'Location': array([ -2.36172938, -19.34461784, 0.17198017]), + 'Rotation': array([-5.88420779e-02, 7.23267441e+01, -4.87060510e-02]), + 'Velocity': array([ 5.09694517e-01, 1.02460027e+00, -8.77885788e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.68729973, 14.57120323, 1.37175488]), + 'camera_rotation': array([-8.07869911, 1.01525021, 0.64496452]), + 'current_gear_input': False, + 'focus_actor_dist': 1120.8299560546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -565.54681396, -1977.78271484, 55.30570984]), + 'frame': 20798, + 'frame_number': 20798, + 'framesequence': 79492, + 'gaze_dir': array([0.96879578, 0.23779297, 0.06755829]), + 'gaze_origin': array([-3.08378291, -0.20244448, 0.08410721]), + 'gaze_valid': True, + 'gaze_vergence': 171.96527099609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96478271, 0.25489807, 0.06489563]), + 'left_gaze_origin': array([-3.02966022, 2.98645639, 0.09138947]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9576263427734375, + 'left_pupil_posn': array([ 0.24726903, -0.0356549 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9755918979644775, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97280884, 0.22068787, 0.07022095]), + 'right_gaze_origin': array([-3.13790584, -3.39134526, 0.07682496]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.99334716796875, + 'right_pupil_posn': array([ 0.22770429, -0.11055779]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07108371704816818, + 'throttle_input': 0.23015183210372925, + 'timestamp': 673.1043251678348, + 'timestamp_carla': 673105, + 'timestamp_device': 116349, + 'timestamp_stream': 673.1043251678348, + 'transform': [array([-1.49402833e+00, -1.75717506e+01, 1.12499809e-02]), + array([-0.06347294, -2.18539095, 0.0133362 ])]} +{'AngularVelocity': array([-2.31278478e-03, -1.24384870e-03, -5.78920794e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.660131454467773, + 'FR_Wheel_Angle': -15.22789192199707, + 'Location': array([ -2.2775631 , -19.16862679, 0.17183876]), + 'Rotation': array([-5.96002266e-02, 7.12900848e+01, -4.69970740e-02]), + 'Velocity': array([ 0.50050366, 0.93686634, -0.00102575]), + 'brake_input': 0.0, + 'camera_location': array([-5.63571835, 14.57217693, 1.35307407]), + 'camera_rotation': array([-8.27879715, 1.20712399, 0.97776341]), + 'current_gear_input': False, + 'focus_actor_dist': 1120.8310546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -561.63476562, -1976.52661133, 55.54779816]), + 'frame': 20799, + 'frame_number': 20799, + 'framesequence': 79496, + 'gaze_dir': array([0.96278381, 0.26007843, 0.07099152]), + 'gaze_origin': array([-3.08727503, -0.21742478, 0.08935089]), + 'gaze_valid': True, + 'gaze_vergence': 162.51463317871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95797729, 0.27822876, 0.06967163]), + 'left_gaze_origin': array([-3.03305221, 2.96997237, 0.0969864 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.009979248046875, + 'left_pupil_posn': array([ 0.26597703, -0.03234923]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9614868760108948, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96759033, 0.2419281 , 0.0723114 ]), + 'right_gaze_origin': array([-3.14149785, -3.40482187, 0.0817154 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.10333251953125, + 'right_pupil_posn': array([ 0.24541533, -0.10712314]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07591784745454788, + 'throttle_input': 0.2380865216255188, + 'timestamp': 673.1375776678324, + 'timestamp_carla': 673138, + 'timestamp_device': 116382, + 'timestamp_stream': 673.1375776678324, + 'transform': [array([-1.49594390e+00, -1.75651569e+01, 1.17869945e-02]), + array([-0.06399887, -2.17709637, 0.01089479])]} +{'AngularVelocity': array([-1.68405229e-03, 7.51086161e-04, -5.64949989e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.710399627685547, + 'FR_Wheel_Angle': -15.976619720458984, + 'Location': array([ -2.18557882, -18.98918533, 0.17168766]), + 'Rotation': array([-5.98734356e-02, 7.01487045e+01, -4.67529334e-02]), + 'Velocity': array([ 4.86341119e-01, 8.47944796e-01, -1.81512834e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.61716843, 14.59204674, 1.30314529]), + 'camera_rotation': array([-8.5680275 , 1.3262825 , 0.84168154]), + 'current_gear_input': False, + 'focus_actor_dist': 1129.6622314453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -593.33972168, -1974.62976074, 54.00102234]), + 'frame': 20800, + 'frame_number': 20800, + 'framesequence': 79501, + 'gaze_dir': array([0.95989227, 0.27049255, 0.07327271]), + 'gaze_origin': array([-3.08978677, -0.23095475, 0.09380112]), + 'gaze_valid': True, + 'gaze_vergence': 351.53656005859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95770264, 0.27742004, 0.0763855 ]), + 'left_gaze_origin': array([-3.03677082, 2.9537828 , 0.10208742]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1072998046875, + 'left_pupil_posn': array([ 0.28462672, -0.03102648]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9405487179756165, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96208191, 0.26356506, 0.07015991]), + 'right_gaze_origin': array([-3.14280248, -3.41569233, 0.08551484]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9818572998046875, + 'right_pupil_posn': array([ 0.25284517, -0.10225201]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08192389458417892, + 'throttle_input': 0.2380865216255188, + 'timestamp': 673.1716738678515, + 'timestamp_carla': 673172, + 'timestamp_device': 116424, + 'timestamp_stream': 673.1716738678515, + 'transform': [array([-1.49805629e+00, -1.75572758e+01, 1.21182250e-02]), + array([-0.06423792, -2.16793084, 0.00936891])]} +{'AngularVelocity': array([-2.47985893e-03, -7.35272712e-04, -5.47424984e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.66011619567871, + 'FR_Wheel_Angle': -16.723493576049805, + 'Location': array([ -2.09580994, -18.8252182 , 0.17153133]), + 'Rotation': array([-6.02422655e-02, 6.90340576e+01, -4.65393066e-02]), + 'Velocity': array([ 4.69770044e-01, 7.66707003e-01, -6.95238123e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.58612728, 14.62305355, 1.2808795 ]), + 'camera_rotation': array([-8.62888527, 1.42868376, 0.72279006]), + 'current_gear_input': False, + 'focus_actor_dist': 1137.0628662109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -609.30273438, -1970.64868164, 51.56681824]), + 'frame': 20801, + 'frame_number': 20801, + 'framesequence': 79504, + 'gaze_dir': array([0.95964813, 0.27089691, 0.07472229]), + 'gaze_origin': array([-3.08991885, -0.23083344, 0.09305115]), + 'gaze_valid': True, + 'gaze_vergence': 304.7176208496094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95729065, 0.279953 , 0.07214355]), + 'left_gaze_origin': array([-3.03701329, 2.95425582, 0.10077821]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1527252197265625, + 'left_pupil_posn': array([ 0.28369522, -0.0295403 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9532979130744934, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96200562, 0.26184082, 0.07730103]), + 'right_gaze_origin': array([-3.14282393, -3.41592288, 0.0853241 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1390838623046875, + 'right_pupil_posn': array([ 0.25372648, -0.10422063]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0884975790977478, + 'throttle_input': 0.2380865216255188, + 'timestamp': 673.2037500664592, + 'timestamp_carla': 673204, + 'timestamp_device': 116449, + 'timestamp_stream': 673.2037500664592, + 'transform': [array([-1.50293303e+00, -1.75483303e+01, 1.23301884e-02]), + array([-0.0647297 , -2.1468761 , 0.00842286])]} +{'AngularVelocity': array([ 0.02016781, -0.04723578, -5.13435316]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.041791915893555, + 'FR_Wheel_Angle': -17.65765380859375, + 'Location': array([ -2.02255607, -18.69947433, 0.17143604]), + 'Rotation': array([-6.39032498e-02, 6.81149979e+01, -4.83703613e-02]), + 'Velocity': array([ 4.23931807e-01, 6.52240872e-01, -4.33878886e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.54057789, 14.65532112, 1.27477479]), + 'camera_rotation': array([-8.63122749, 1.53499258, 0.77981198]), + 'current_gear_input': False, + 'focus_actor_dist': 1137.68798828125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -611.94445801, -1969.8248291 , 52.67086792]), + 'frame': 20802, + 'frame_number': 20802, + 'framesequence': 79508, + 'gaze_dir': array([0.96002197, 0.26924896, 0.07580566]), + 'gaze_origin': array([-3.0895822 , -0.22989884, 0.09359208]), + 'gaze_valid': True, + 'gaze_vergence': 334.9079284667969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95770264, 0.27789307, 0.07447815]), + 'left_gaze_origin': array([-3.03624892, 2.95641637, 0.10208587]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.16412353515625, + 'left_pupil_posn': array([ 0.28175235, -0.02857387]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9490671157836914, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96234131, 0.26060486, 0.07713318]), + 'right_gaze_origin': array([-3.14291573, -3.41621423, 0.08509827]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1295928955078125, + 'right_pupil_posn': array([ 0.25322115, -0.10351217]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09421064704656601, + 'throttle_input': 0.24998855590820312, + 'timestamp': 673.2378191687167, + 'timestamp_carla': 673239, + 'timestamp_device': 116482, + 'timestamp_stream': 673.2378191687167, + 'transform': [array([-1.50820065e+00, -1.75375843e+01, 1.25258444e-02]), + array([-0.0650917 , -2.1244452 , 0.00747681])]} +{'AngularVelocity': array([-0.02631709, 0.01798067, -4.10505009]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.25017547607422, + 'FR_Wheel_Angle': -17.76853370666504, + 'Location': array([ -1.94321346, -18.57017517, 0.17124279]), + 'Rotation': array([-6.14853613e-02, 6.71119308e+01, -4.73938026e-02]), + 'Velocity': array([ 0.38537014, 0.56066835, -0.00145228]), + 'brake_input': 0.0, + 'camera_location': array([-5.52129364, 14.69465828, 1.25948691]), + 'camera_rotation': array([-8.73642635, 1.58969736, 0.77564669]), + 'current_gear_input': False, + 'focus_actor_dist': 1136.7916259765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -612.39489746, -1969.9206543 , 53.58248138]), + 'frame': 20803, + 'frame_number': 20803, + 'framesequence': 79513, + 'gaze_dir': array([0.95924377, 0.27185059, 0.076828 ]), + 'gaze_origin': array([-3.0895195 , -0.22946091, 0.09399185]), + 'gaze_valid': True, + 'gaze_vergence': 537.8599853515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95779419, 0.27720642, 0.07594299]), + 'left_gaze_origin': array([-3.03626418, 2.95715046, 0.10265962]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1654815673828125, + 'left_pupil_posn': array([ 0.28333592, -0.02811825]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9481208920478821, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96069336, 0.26649475, 0.07771301]), + 'right_gaze_origin': array([-3.1427753 , -3.41607213, 0.0853241 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1063690185546875, + 'right_pupil_posn': array([ 0.25290358, -0.10276258]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09975890070199966, + 'throttle_input': 0.269825279712677, + 'timestamp': 673.2714308686554, + 'timestamp_carla': 673272, + 'timestamp_device': 116524, + 'timestamp_stream': 673.2714308686554, + 'transform': [array([-1.51342773e+00, -1.75254288e+01, 1.27561754e-02]), + array([-0.06546053, -2.1025908 , 0.0064087 ])]} +{'AngularVelocity': array([-0.01048653, 0.05025511, -4.9035449 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.376564025878906, + 'FR_Wheel_Angle': -17.821683883666992, + 'Location': array([ -1.86480558, -18.44772148, 0.17107712]), + 'Rotation': array([-5.73735870e-02, 6.61764679e+01, -4.48608398e-02]), + 'Velocity': array([4.15246308e-01, 5.90971231e-01, 4.45070269e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.4810915 , 14.73326969, 1.24857676]), + 'camera_rotation': array([-8.79205799, 1.62711096, 0.90743649]), + 'current_gear_input': False, + 'focus_actor_dist': 1136.975830078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -616.93188477, -1969.9765625 , 52.8479538 ]), + 'frame': 20804, + 'frame_number': 20804, + 'framesequence': 79517, + 'gaze_dir': array([0.95952606, 0.27038574, 0.07831573]), + 'gaze_origin': array([-3.08939528, -0.22923127, 0.09385605]), + 'gaze_valid': True, + 'gaze_vergence': 458.3963317871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95768738, 0.27670288, 0.07897949]), + 'left_gaze_origin': array([-3.03626418, 2.957515 , 0.10263824]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.16656494140625, + 'left_pupil_posn': array([ 0.28222513, -0.02811825]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9505391716957092, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96136475, 0.2640686 , 0.07765198]), + 'right_gaze_origin': array([-3.14252639, -3.41597748, 0.08507386]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1325225830078125, + 'right_pupil_posn': array([ 0.2526499 , -0.10187042]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10468459129333496, + 'throttle_input': 0.28172731399536133, + 'timestamp': 673.3040418662131, + 'timestamp_carla': 673305, + 'timestamp_device': 116557, + 'timestamp_stream': 673.3040418662131, + 'transform': [array([-1.51864588e+00, -1.75126495e+01, 1.28365895e-02]), + array([-0.06555615, -2.08080912, 0.006073 ])]} +{'AngularVelocity': array([ 0.01648812, -0.04522265, -5.94896698]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.330678939819336, + 'FR_Wheel_Angle': -17.78734016418457, + 'Location': array([ -1.75835085, -18.28727341, 0.17093089]), + 'Rotation': array([-5.27632087e-02, 6.48876877e+01, -4.00695764e-02]), + 'Velocity': array([ 0.53828579, 0.7299543 , -0.00073927]), + 'brake_input': 0.0, + 'camera_location': array([-5.43156719, 14.77731705, 1.24597669]), + 'camera_rotation': array([-8.81748676, 1.60837722, 0.97511894]), + 'current_gear_input': False, + 'focus_actor_dist': 1135.671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -616.32958984, -1969.95959473, 52.83984375]), + 'frame': 20805, + 'frame_number': 20805, + 'framesequence': 79521, + 'gaze_dir': array([0.95974731, 0.26950836, 0.07865143]), + 'gaze_origin': array([-3.08930373, -0.22917406, 0.09380876]), + 'gaze_valid': True, + 'gaze_vergence': 472.92156982421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95799255, 0.27532959, 0.08009338]), + 'left_gaze_origin': array([-3.03626418, 2.95761108, 0.10253907]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1663665771484375, + 'left_pupil_posn': array([ 0.28202486, -0.02831149]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9483683705329895, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96150208, 0.26368713, 0.07720947]), + 'right_gaze_origin': array([-3.14234352, -3.41595936, 0.08507843]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1331787109375, + 'right_pupil_posn': array([ 0.25214291, -0.10139751]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10939054936170578, + 'throttle_input': 0.2896620035171509, + 'timestamp': 673.3378867655993, + 'timestamp_carla': 673339, + 'timestamp_device': 116591, + 'timestamp_stream': 673.3378867655993, + 'transform': [array([-1.52400172e+00, -1.74974918e+01, 1.31289959e-02]), + array([-0.06600694, -2.05892396, 0.00469971])]} +{'AngularVelocity': array([-0.02694089, 0.02903648, -6.07738686]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.320629119873047, + 'FR_Wheel_Angle': -17.79071617126465, + 'Location': array([ -1.63585806, -18.1125164 , 0.17079525]), + 'Rotation': array([-5.65812849e-02, 6.34742775e+01, -4.01000939e-02]), + 'Velocity': array([5.67831099e-01, 7.28892744e-01, 5.49077959e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.39072514, 14.82047272, 1.23379648]), + 'camera_rotation': array([-8.84686375, 1.61928654, 1.07137024]), + 'current_gear_input': False, + 'focus_actor_dist': 1134.225341796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -615.18212891, -1969.89379883, 52.46281433]), + 'frame': 20806, + 'frame_number': 20806, + 'framesequence': 79524, + 'gaze_dir': array([0.95932007, 0.27076721, 0.07938385]), + 'gaze_origin': array([-3.0890038 , -0.22754289, 0.09355622]), + 'gaze_valid': True, + 'gaze_vergence': 391.41925048828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9571991 , 0.27774048, 0.08122253]), + 'left_gaze_origin': array([-3.03627181, 2.9582231 , 0.10240632]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2068939208984375, + 'left_pupil_posn': array([ 0.28160405, -0.02837205]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9562909603118896, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96144104, 0.26379395, 0.07754517]), + 'right_gaze_origin': array([-3.14173579, -3.41330886, 0.08470612]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1482391357421875, + 'right_pupil_posn': array([ 0.25115764, -0.10123932]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11371196806430817, + 'throttle_input': 0.29364460706710815, + 'timestamp': 673.3703634664416, + 'timestamp_carla': 673371, + 'timestamp_device': 116616, + 'timestamp_stream': 673.3703634664416, + 'transform': [array([-1.53537965e+00, -1.74803753e+01, 1.33812046e-02]), + array([-0.06664898, -2.01067758, 0.00354005])]} +{'AngularVelocity': array([-0.01276181, 0.01500368, -5.60250521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.346290588378906, + 'FR_Wheel_Angle': -17.809419631958008, + 'Location': array([ -1.52987373, -17.96855545, 0.17062958]), + 'Rotation': array([-6.21888675e-02, 6.22893257e+01, -4.20837365e-02]), + 'Velocity': array([ 0.54003048, 0.66410816, -0.00073638]), + 'brake_input': 0.0, + 'camera_location': array([-5.34813118, 14.84476566, 1.2090255 ]), + 'camera_rotation': array([-8.92421532, 1.65195549, 1.25457346]), + 'current_gear_input': False, + 'focus_actor_dist': 1133.2718505859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -617.22302246, -1969.93908691, 52.35168457]), + 'frame': 20807, + 'frame_number': 20807, + 'framesequence': 79529, + 'gaze_dir': array([0.95928192, 0.27000427, 0.08228302]), + 'gaze_origin': array([-3.08891153, -0.22694398, 0.09192963]), + 'gaze_valid': True, + 'gaze_vergence': 315.5174560546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9568634 , 0.27748108, 0.08595276]), + 'left_gaze_origin': array([-3.03625345, 2.95913696, 0.10123749]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2164306640625, + 'left_pupil_posn': array([ 0.2805289 , -0.02876592]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9426762461662292, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96170044, 0.26252747, 0.07861328]), + 'right_gaze_origin': array([-3.14156961, -3.4130249 , 0.08262177]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.189239501953125, + 'right_pupil_posn': array([ 0.25085819, -0.10106516]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11752068251371384, + 'throttle_input': 0.29761195182800293, + 'timestamp': 673.4043664671481, + 'timestamp_carla': 673405, + 'timestamp_device': 116657, + 'timestamp_stream': 673.4043664671481, + 'transform': [array([-1.54664731e+00, -1.74615002e+01, 1.33851720e-02]), + array([-0.06677192, -1.96340561, 0.00347901])]} +{'AngularVelocity': array([-8.90415162e-03, -2.99619930e-03, -5.26811934e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.37620735168457, + 'FR_Wheel_Angle': -17.830068588256836, + 'Location': array([ -1.42926466, -17.83753967, 0.17048535]), + 'Rotation': array([-6.45111352e-02, 6.11919289e+01, -4.25414927e-02]), + 'Velocity': array([ 0.51059914, 0.60206056, -0.00086337]), + 'brake_input': 0.0, + 'camera_location': array([-5.31898785, 14.86951256, 1.18420744]), + 'camera_rotation': array([-9.06230831, 1.64194357, 1.3622483 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1131.706787109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -617.87731934, -1970.04333496, 53.2971344 ]), + 'frame': 20808, + 'frame_number': 20808, + 'framesequence': 79532, + 'gaze_dir': array([0.95977783, 0.26792908, 0.08351135]), + 'gaze_origin': array([-3.08869863, -0.22673188, 0.09175568]), + 'gaze_valid': True, + 'gaze_vergence': 337.1582336425781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95780945, 0.27368164, 0.08766174]), + 'left_gaze_origin': array([-3.03610539, 2.95944524, 0.10088959]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.245025634765625, + 'left_pupil_posn': array([ 0.28016222, -0.02876592]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9439203143119812, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96174622, 0.26217651, 0.07936096]), + 'right_gaze_origin': array([-3.14129186, -3.41290903, 0.08262177]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2058258056640625, + 'right_pupil_posn': array([ 0.24940157, -0.10035396]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12200690060853958, + 'throttle_input': 0.3055466413497925, + 'timestamp': 673.4366622678936, + 'timestamp_carla': 673437, + 'timestamp_device': 116682, + 'timestamp_stream': 673.4366622678936, + 'transform': [array([-1.55844450e+00, -1.74410954e+01, 1.37028499e-02]), + array([-0.06759155, -1.91454136, 0.00201416])]} +{'AngularVelocity': array([-3.73388245e-03, -1.05124898e-03, -4.75010967e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.403383255004883, + 'FR_Wheel_Angle': -17.84892463684082, + 'Location': array([ -1.32035017, -17.70142365, 0.17035164]), + 'Rotation': array([-6.55561537e-02, 6.00328255e+01, -4.23583947e-02]), + 'Velocity': array([ 4.74696904e-01, 5.37735879e-01, -1.02224345e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.29780102, 14.88361359, 1.14459336]), + 'camera_rotation': array([-9.20446491, 1.68557978, 1.35710847]), + 'current_gear_input': False, + 'focus_actor_dist': 1129.7994384765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -615.99102783, -1969.83447266, 51.57368469]), + 'frame': 20809, + 'frame_number': 20809, + 'framesequence': 79536, + 'gaze_dir': array([0.96005249, 0.26618958, 0.08581543]), + 'gaze_origin': array([-3.08821821, -0.22661744, 0.09189225]), + 'gaze_valid': True, + 'gaze_vergence': 361.8216552734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95785522, 0.27323914, 0.08851624]), + 'left_gaze_origin': array([-3.03573012, 2.95970321, 0.10088959]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.26287841796875, + 'left_pupil_posn': array([ 0.27891266, -0.02737498]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9459478855133057, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96224976, 0.25914001, 0.08311462]), + 'right_gaze_origin': array([-3.1407063 , -3.41293812, 0.08289491]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.208221435546875, + 'right_pupil_posn': array([ 0.24924624, -0.0997417 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12566912174224854, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.4703992679715, + 'timestamp_carla': 673471, + 'timestamp_device': 116716, + 'timestamp_stream': 673.4703992679715, + 'transform': [array([-1.57239866e+00, -1.74184666e+01, 1.37940785e-02]), + array([-6.78715855e-02, -1.85662329e+00, 1.55640242e-03])]} +{'AngularVelocity': array([ 0.03398502, -0.10154164, 0.00026733]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.674823760986328, + 'FR_Wheel_Angle': -18.03742027282715, + 'Location': array([ -1.26779449, -17.63770866, 0.17043652]), + 'Rotation': array([-0.09378532, 59.48060989, -0.06060791]), + 'Velocity': array([-4.28483982e-05, -4.23391721e-05, 6.28202048e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.28730202, 14.87880135, 1.11919498]), + 'camera_rotation': array([-9.35235882, 1.75458717, 1.50724936]), + 'current_gear_input': False, + 'focus_actor_dist': 1127.7728271484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -615.37042236, -1969.82250977, 51.6251297 ]), + 'frame': 20810, + 'frame_number': 20810, + 'framesequence': 79540, + 'gaze_dir': array([0.97541046, 0.19944 , 0.0927887 ]), + 'gaze_origin': array([-3.04140782, -0.17386857, 0.0897461 ]), + 'gaze_valid': True, + 'gaze_vergence': 237.49818420410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97323608, 0.21157837, 0.08956909]), + 'left_gaze_origin': array([-2.95310068, 3.01930404, 0.084935 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3901214599609375, + 'left_pupil_posn': array([ 0.21206057, -0.01745343]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9637182950973511, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97758484, 0.18730164, 0.0960083 ]), + 'right_gaze_origin': array([-3.1297152 , -3.36704111, 0.0945572 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.22027587890625, + 'right_pupil_posn': array([ 0.1953994 , -0.08777678]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12962432205677032, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.5044648684561, + 'timestamp_carla': 673505, + 'timestamp_device': 116749, + 'timestamp_stream': 673.5044648684561, + 'transform': [array([-1.58762574e+00, -1.73939457e+01, 1.38449185e-02]), + array([-6.81106448e-02, -1.79371262e+00, 1.28174538e-03])]} +{'AngularVelocity': array([ 0.036637 , -0.05964548, -0.0965374 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.66883659362793, + 'FR_Wheel_Angle': -18.032930374145508, + 'Location': array([ -1.26709855, -17.63697624, 0.1702954 ]), + 'Rotation': array([-7.07949102e-02, 5.94748268e+01, -4.72717322e-02]), + 'Velocity': array([0.00958997, 0.01057965, 0.0004154 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.27931023, 14.86264706, 1.10788488]), + 'camera_rotation': array([-9.46163559, 1.78307939, 1.54694688]), + 'current_gear_input': False, + 'focus_actor_dist': 1100.6900634765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -537.62701416, -1976.52429199, 56.78166199]), + 'frame': 20811, + 'frame_number': 20811, + 'framesequence': 79544, + 'gaze_dir': array([0.97667694, 0.18952179, 0.10057068]), + 'gaze_origin': array([-3.0405283 , -0.1570427 , 0.09409333]), + 'gaze_valid': True, + 'gaze_vergence': 293.3070373535156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97640991, 0.19374084, 0.09527588]), + 'left_gaze_origin': array([-2.94649816, 3.03251505, 0.08739167]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3643646240234375, + 'left_pupil_posn': array([ 0.20242429, -0.01116228]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97694397, 0.18530273, 0.10586548]), + 'right_gaze_origin': array([-3.13455844, -3.34660029, 0.10079499]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2268829345703125, + 'right_pupil_posn': array([ 0.17531812, -0.08201361]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13312174379825592, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.5367307662964, + 'timestamp_carla': 673537, + 'timestamp_device': 116782, + 'timestamp_stream': 673.5367307662964, + 'transform': [array([-1.60408080e+00, -1.73686638e+01, 1.39824962e-02]), + array([-6.85409456e-02, -1.72587025e+00, 6.71393354e-04])]} +{'AngularVelocity': array([ 0.00532388, -0.01027856, -0.13911101]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.66718864440918, + 'FR_Wheel_Angle': -18.03213119506836, + 'Location': array([ -1.26380825, -17.63308525, 0.17025334]), + 'Rotation': array([-6.34729415e-02, 5.94407234e+01, -4.33044396e-02]), + 'Velocity': array([ 1.37649532e-02, 1.51665024e-02, -5.35391300e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.26912403, 14.83981991, 1.10549259]), + 'camera_rotation': array([-9.47928429, 1.73046792, 1.46416926]), + 'current_gear_input': False, + 'focus_actor_dist': 1096.0855712890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -527.90435791, -1976.51184082, 63.38846588]), + 'frame': 20812, + 'frame_number': 20812, + 'framesequence': 79548, + 'gaze_dir': array([0.97669983, 0.18849182, 0.10232544]), + 'gaze_origin': array([-3.04266906, -0.15881883, 0.09487458]), + 'gaze_valid': True, + 'gaze_vergence': 421.97052001953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97633362, 0.19241333, 0.09857178]), + 'left_gaze_origin': array([-2.9554491 , 3.03215814, 0.09007111]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.357330322265625, + 'left_pupil_posn': array([ 0.20252097, -0.01089239]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9898273944854736, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97706604, 0.18457031, 0.1060791 ]), + 'right_gaze_origin': array([-3.12988901, -3.34979558, 0.09967805]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2611083984375, + 'right_pupil_posn': array([ 0.17689621, -0.08085048]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.136747345328331, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.5700954683125, + 'timestamp_carla': 673571, + 'timestamp_device': 116815, + 'timestamp_stream': 673.5700954683125, + 'transform': [array([-1.62250388e+00, -1.73403625e+01, 1.41757680e-02]), + array([-6.90941885e-02, -1.65032303e+00, -2.52712169e-04])]} +{'AngularVelocity': array([ 0.00101405, -0.00307591, -0.14087456]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.667219161987305, + 'FR_Wheel_Angle': -18.032060623168945, + 'Location': array([ -1.26076984, -17.6294632 , 0.1702399 ]), + 'Rotation': array([-6.23801127e-02, 5.94094124e+01, -4.25720252e-02]), + 'Velocity': array([1.37293274e-02, 1.51289469e-02, 6.89650333e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.25192356, 14.79402924, 1.10188937]), + 'camera_rotation': array([-9.43053055, 1.64418674, 1.55150235]), + 'current_gear_input': False, + 'focus_actor_dist': 1093.3741455078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -526.50836182, -1976.50793457, 65.46472168]), + 'frame': 20813, + 'frame_number': 20813, + 'framesequence': 79553, + 'gaze_dir': array([0.97689056, 0.18824768, 0.10099792]), + 'gaze_origin': array([-3.04416752, -0.16017228, 0.09375611]), + 'gaze_valid': True, + 'gaze_vergence': 257.3440856933594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97691345, 0.19084167, 0.09594727]), + 'left_gaze_origin': array([-2.95847487, 3.03168964, 0.08949891]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.35125732421875, + 'left_pupil_posn': array([ 0.20325446, -0.01184916]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.977625846862793, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97686768, 0.18565369, 0.10604858]), + 'right_gaze_origin': array([-3.12985992, -3.35203409, 0.0980133 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2603607177734375, + 'right_pupil_posn': array([ 0.17784774, -0.08285761]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1404278725385666, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.6056121662259, + 'timestamp_carla': 673606, + 'timestamp_device': 116857, + 'timestamp_stream': 673.6056121662259, + 'transform': [array([-1.64444029e+00, -1.73081493e+01, 1.42765995e-02]), + array([-6.95518106e-02, -1.56048334e+00, -8.26449657e-04])]} +{'AngularVelocity': array([-0.00099709, -0.00172249, -0.12757786]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.66836929321289, + 'FR_Wheel_Angle': -18.033084869384766, + 'Location': array([ -1.25831771, -17.62642479, 0.17023769]), + 'Rotation': array([-6.21273965e-02, 5.93805695e+01, -4.23584022e-02]), + 'Velocity': array([0.01328788, 0.01461828, 0.00011707]), + 'brake_input': 0.0, + 'camera_location': array([-5.22024632, 14.72460651, 1.10192287]), + 'camera_rotation': array([-9.48865509, 1.52512479, 1.47412992]), + 'current_gear_input': False, + 'focus_actor_dist': 1090.6705322265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -525.71795654, -1976.50915527, 64.78967285]), + 'frame': 20814, + 'frame_number': 20814, + 'framesequence': 79557, + 'gaze_dir': array([0.97698975, 0.18721771, 0.10198212]), + 'gaze_origin': array([-3.05616164, -0.16239166, 0.0994774 ]), + 'gaze_valid': True, + 'gaze_vergence': 1041.73193359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97639465, 0.19004822, 0.10249329]), + 'left_gaze_origin': array([-2.98282337, 3.02836943, 0.10136414]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4064483642578125, + 'left_pupil_posn': array([ 0.20528448, -0.00996292]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.993249237537384, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97758484, 0.18438721, 0.10147095]), + 'right_gaze_origin': array([-3.12950015, -3.35315275, 0.09759065]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.269378662109375, + 'right_pupil_posn': array([ 0.17836332, -0.08085048]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14405347406864166, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.6389696672559, + 'timestamp_carla': 673640, + 'timestamp_device': 116890, + 'timestamp_stream': 673.6389696672559, + 'transform': [array([-1.66766751e+00, -1.72756100e+01, 1.44287106e-02]), + array([-0.07002993, -1.46543229, -0.0015163 ])]} +{'AngularVelocity': array([-5.91232616e-04, -7.23933568e-03, 1.07074285e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.66697120666504, + 'FR_Wheel_Angle': -18.031152725219727, + 'Location': array([ -1.25584877, -17.62338448, 0.17022152]), + 'Rotation': array([-6.20386042e-02, 5.93501930e+01, -4.22058105e-02]), + 'Velocity': array([ 0.01336971, 0.01399108, -0.00022959]), + 'brake_input': 0.0, + 'camera_location': array([-5.24769878, 14.68065357, 1.08737302]), + 'camera_rotation': array([-9.61945343, 1.40156877, 1.28903139]), + 'current_gear_input': False, + 'focus_actor_dist': 1085.8465576171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -523.09375 , -1977.87463379, 65.38314819]), + 'frame': 20815, + 'frame_number': 20815, + 'framesequence': 79561, + 'gaze_dir': array([0.97647095, 0.19007874, 0.10163116]), + 'gaze_origin': array([-3.0553019 , -0.16304246, 0.10007401]), + 'gaze_valid': True, + 'gaze_vergence': 798.9609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97569275, 0.19342041, 0.10284424]), + 'left_gaze_origin': array([-2.98177052, 3.02771616, 0.10192109]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4116363525390625, + 'left_pupil_posn': array([ 0.20651603, -0.0098139 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9817816615104675, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97724915, 0.18673706, 0.10041809]), + 'right_gaze_origin': array([-3.12883329, -3.35380101, 0.09822693]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.278900146484375, + 'right_pupil_posn': array([ 0.17997468, -0.08025682]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14707480370998383, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.6712398678064, + 'timestamp_carla': 673672, + 'timestamp_device': 116924, + 'timestamp_stream': 673.6712398678064, + 'transform': [array([-1.69216454e+00, -1.72418499e+01, 1.46288583e-02]), + array([-0.07059 , -1.36552918, -0.00240422])]} +{'AngularVelocity': array([ 0.05965866, -0.02122355, -1.91454542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.607370376586914, + 'FR_Wheel_Angle': -17.97833251953125, + 'Location': array([ -1.24437523, -17.60930824, 0.17013083]), + 'Rotation': array([-5.57206795e-02, 5.92133713e+01, -3.81469764e-02]), + 'Velocity': array([ 0.12403892, 0.14843284, -0.0001719 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.2296648 , 14.64953423, 1.11545789]), + 'camera_rotation': array([-9.48030186, 1.3213259 , 1.25989223]), + 'current_gear_input': False, + 'focus_actor_dist': 1084.7890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -525.2310791 , -1976.51184082, 63.33882141]), + 'frame': 20816, + 'frame_number': 20816, + 'framesequence': 79564, + 'gaze_dir': array([0.97611237, 0.19220734, 0.10110474]), + 'gaze_origin': array([-3.05367303, -0.16367264, 0.09883957]), + 'gaze_valid': True, + 'gaze_vergence': 534.9012451171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97503662, 0.19633484, 0.10360718]), + 'left_gaze_origin': array([-2.97947097, 3.02741408, 0.09986268]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4113922119140625, + 'left_pupil_posn': array([ 0.20714903, -0.01139724]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9832718372344971, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97718811, 0.18807983, 0.09860229]), + 'right_gaze_origin': array([-3.12787485, -3.35475945, 0.09781647]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.298583984375, + 'right_pupil_posn': array([ 0.18161762, -0.08019245]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14921720325946808, + 'throttle_input': 0.30951398611068726, + 'timestamp': 673.7035878673196, + 'timestamp_carla': 673704, + 'timestamp_device': 116949, + 'timestamp_stream': 673.7035878673196, + 'transform': [array([-1.71808839e+00, -1.72061653e+01, 1.47599028e-02]), + array([-0.07104763, -1.26032352, -0.00299845])]} +{'AngularVelocity': array([-0.01141407, 0.11051067, -0.97300363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.553050994873047, + 'FR_Wheel_Angle': -17.93854331970215, + 'Location': array([ -1.20299602, -17.5607338 , 0.17013767]), + 'Rotation': array([-5.69706038e-02, 5.87925453e+01, -3.80859412e-02]), + 'Velocity': array([ 1.73532575e-01, 1.90757632e-01, -1.21870042e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21397877, 14.61478615, 1.15800941]), + 'camera_rotation': array([-9.3038578 , 1.23425305, 1.11990273]), + 'current_gear_input': False, + 'focus_actor_dist': 1081.9713134765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -527.42364502, -1976.50756836, 65.69616699]), + 'frame': 20817, + 'frame_number': 20817, + 'framesequence': 79568, + 'gaze_dir': array([0.97579193, 0.19378662, 0.10100555]), + 'gaze_origin': array([-3.05221272, -0.16436921, 0.09776917]), + 'gaze_valid': True, + 'gaze_vergence': 414.1417236328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97428894, 0.19999695, 0.10360718]), + 'left_gaze_origin': array([-2.97686934, 3.02708912, 0.09772186]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.429229736328125, + 'left_pupil_posn': array([ 0.20714903, -0.01245761]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9794524908065796, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97729492, 0.18757629, 0.09840393]), + 'right_gaze_origin': array([-3.12755585, -3.35582757, 0.09781647]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.322265625, + 'right_pupil_posn': array([ 0.18361294, -0.08025682]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15026092529296875, + 'throttle_input': 0.2856946587562561, + 'timestamp': 673.7374898679554, + 'timestamp_carla': 673738, + 'timestamp_device': 116982, + 'timestamp_stream': 673.7374898679554, + 'transform': [array([-1.74718475e+00, -1.71667557e+01, 1.48421954e-02]), + array([-0.07140962, -1.14259481, -0.00342875])]} +{'AngularVelocity': array([-0.00810236, 0.0157805 , -2.7299335 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.686941146850586, + 'FR_Wheel_Angle': -17.1502628326416, + 'Location': array([ -1.15100372, -17.50028038, 0.17004791]), + 'Rotation': array([-5.66427559e-02, 5.82724380e+01, -3.75061035e-02]), + 'Velocity': array([ 0.27221647, 0.29368719, -0.00039067]), + 'brake_input': 0.0, + 'camera_location': array([-5.19168186, 14.58563614, 1.17704844]), + 'camera_rotation': array([-9.28219891, 1.11189115, 1.0096339 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1077.474609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -528.48101807, -1977.71447754, 69.70194244]), + 'frame': 20818, + 'frame_number': 20818, + 'framesequence': 79572, + 'gaze_dir': array([0.99263763, 0.08490753, 0.08481598]), + 'gaze_origin': array([-3.08088398, -0.07704239, 0.10060579]), + 'gaze_valid': True, + 'gaze_vergence': 195.87342834472656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99101257, 0.10003662, 0.08866882]), + 'left_gaze_origin': array([-3.01583266, 3.11957884, 0.10227051]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.44970703125, + 'left_pupil_posn': array([ 0.1043973 , -0.02085865]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9942627 , 0.06977844, 0.08096313]), + 'right_gaze_origin': array([-3.1459353 , -3.27366376, 0.09894104]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.34173583984375, + 'right_pupil_posn': array([ 0.09291971, -0.08601689]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15031588077545166, + 'throttle_input': 0.27775996923446655, + 'timestamp': 673.7709211669862, + 'timestamp_carla': 673772, + 'timestamp_device': 117015, + 'timestamp_stream': 673.7709211669862, + 'transform': [array([-1.77773225e+00, -1.71259842e+01, 1.48893641e-02]), + array([-0.07155989, -1.01922238, -0.00364732])]} +{'AngularVelocity': array([-0.0100947 , 0.0172979 , -2.20777988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.932981491088867, + 'FR_Wheel_Angle': -14.84011173248291, + 'Location': array([ -1.09151149, -17.43055344, 0.16998558]), + 'Rotation': array([-6.17722273e-02, 5.77182846e+01, -4.08630371e-02]), + 'Velocity': array([ 0.25703755, 0.28546828, -0.00030232]), + 'brake_input': 0.0, + 'camera_location': array([-5.18249226, 14.55627823, 1.17347968]), + 'camera_rotation': array([-9.33699131, 0.94731635, 0.95521021]), + 'current_gear_input': False, + 'focus_actor_dist': 1530.355224609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -449.81774902, -1508.66638184, 17.08117676]), + 'frame': 20819, + 'frame_number': 20819, + 'framesequence': 79576, + 'gaze_dir': array([ 0.9954834 , -0.02133179, 0.09178925]), + 'gaze_origin': array([-3.14834595, 0.00751724, 0.11307221]), + 'gaze_valid': True, + 'gaze_vergence': 272.6169738769531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99533081, -0.01127625, 0.09584045]), + 'left_gaze_origin': array([-3.07126474, 3.19543791, 0.11340334]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3195953369140625, + 'left_pupil_posn': array([ 0.01839292, -0.02041459]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99563599, -0.03138733, 0.08773804]), + 'right_gaze_origin': array([-3.22542739, -3.18040323, 0.11274109]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3245391845703125, + 'right_pupil_posn': array([-0.0079596 , -0.08731925]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.150279238820076, + 'throttle_input': 0.269825279712677, + 'timestamp': 673.8031880669296, + 'timestamp_carla': 673804, + 'timestamp_device': 117049, + 'timestamp_stream': 673.8031880669296, + 'transform': [array([-1.80863154e+00, -1.70848465e+01, 1.49370665e-02]), + array([-0.07168283, -0.89482653, -0.0038249 ])]} +{'AngularVelocity': array([-0.00360602, 0.00433193, -1.35160637]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.515268325805664, + 'FR_Wheel_Angle': -9.440540313720703, + 'Location': array([ -1.03752387, -17.36384773, 0.16992114]), + 'Rotation': array([-6.41559660e-02, 5.73210068e+01, -4.34570275e-02]), + 'Velocity': array([ 0.22204542, 0.2736693 , -0.00043728]), + 'brake_input': 0.0, + 'camera_location': array([-5.17516994, 14.51247978, 1.16900241]), + 'camera_rotation': array([-9.34765339, 0.65079093, 0.92131454]), + 'current_gear_input': False, + 'focus_actor_dist': 1689.2908935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -283.13970947, -1340.28588867, 16.8647995 ]), + 'frame': 20820, + 'frame_number': 20820, + 'framesequence': 79581, + 'gaze_dir': array([ 0.99552155, -0.01692963, 0.09202576]), + 'gaze_origin': array([-3.10807967e+00, 2.35595717e-03, 1.00691989e-01]), + 'gaze_valid': True, + 'gaze_vergence': 221.28111267089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99519348, -0.00534058, 0.09776306]), + 'left_gaze_origin': array([-3.06466389, 3.19344187, 0.11148377]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.375244140625, + 'left_pupil_posn': array([ 0.02075863, -0.02113342]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99584961, -0.02851868, 0.08628845]), + 'right_gaze_origin': array([-3.15149546, -3.18873 , 0.08990021]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3630218505859375, + 'right_pupil_posn': array([-0.00139242, -0.08879054]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1497848480939865, + 'throttle_input': 0.2658579349517822, + 'timestamp': 673.8380974680185, + 'timestamp_carla': 673839, + 'timestamp_device': 117090, + 'timestamp_stream': 673.8380974680185, + 'transform': [array([-1.84346497e+00, -1.70386639e+01, 1.49011416e-02]), + array([-0.07165551, -0.75497478, -0.00371562])]} +{'AngularVelocity': array([-0.00472413, -0.00471645, -0.39676061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.3272814750671387, + 'FR_Wheel_Angle': -2.379359722137451, + 'Location': array([ -0.99153227, -17.30043221, 0.16986099]), + 'Rotation': array([-6.47911727e-02, 5.71462593e+01, -4.46472168e-02]), + 'Velocity': array([ 0.18363893, 0.26435643, -0.00031443]), + 'brake_input': 0.0, + 'camera_location': array([-5.15747261, 14.44434166, 1.18583846]), + 'camera_rotation': array([-9.26187229, 0.12666826, 0.79612595]), + 'current_gear_input': False, + 'focus_actor_dist': 1688.017822265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -285.66012573, -1337.65856934, 16.86662292]), + 'frame': 20821, + 'frame_number': 20821, + 'framesequence': 79585, + 'gaze_dir': array([ 0.99524689, -0.0135498 , 0.09600067]), + 'gaze_origin': array([-3.07672668, -0.00324783, 0.08871079]), + 'gaze_valid': True, + 'gaze_vergence': 393.3414001464844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99542236, -0.00549316, 0.09532166]), + 'left_gaze_origin': array([-2.9968462 , 3.18839431, 0.0882431 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.476043701171875, + 'left_pupil_posn': array([ 0.02669978, -0.02104688]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99507141, -0.02160645, 0.09667969]), + 'right_gaze_origin': array([-3.15660715, -3.19488978, 0.08917847]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3773345947265625, + 'right_pupil_posn': array([ 0.00281382, -0.0911417 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14797204732894897, + 'throttle_input': 0.2539559006690979, + 'timestamp': 673.8713719658554, + 'timestamp_carla': 673872, + 'timestamp_device': 117124, + 'timestamp_stream': 673.8713719658554, + 'transform': [array([-1.87789512e+00, -1.69929466e+01, 1.48921870e-02]), + array([-0.07152574, -0.61713225, -0.00362683])]} +{'AngularVelocity': array([ 3.80967855e-02, -4.16658558e-02, -2.85314709e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.35510873794555664, + 'FR_Wheel_Angle': 0.24610112607479095, + 'Location': array([ -0.98350537, -17.28842163, 0.16989818]), + 'Rotation': array([-7.59858489e-02, 5.71240501e+01, -4.31213342e-02]), + 'Velocity': array([-1.66444752e-05, -3.21669759e-05, 1.77513808e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.15278912, 14.37048817, 1.20054066]), + 'camera_rotation': array([-9.16081333, -0.45109481, 0.73716897]), + 'current_gear_input': False, + 'focus_actor_dist': 1827.7669677734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -276.81774902, -1193.42028809, 16.82081604]), + 'frame': 20822, + 'frame_number': 20822, + 'framesequence': 79588, + 'gaze_dir': array([ 0.99608612, -0.01161194, 0.08728027]), + 'gaze_origin': array([-3.07861876, -0.0079483 , 0.08808289]), + 'gaze_valid': True, + 'gaze_vergence': 475.3908996582031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99615479, -0.00489807, 0.08738708]), + 'left_gaze_origin': array([-2.99773574, 3.18427753, 0.0879654 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4865264892578125, + 'left_pupil_posn': array([ 0.03058457, -0.02465177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99601746, -0.01832581, 0.08717346]), + 'right_gaze_origin': array([-3.15950179, -3.20017409, 0.08820038]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.403533935546875, + 'right_pupil_posn': array([ 0.00663638, -0.09514141]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1448957920074463, + 'throttle_input': 0.23411917686462402, + 'timestamp': 673.9033097662032, + 'timestamp_carla': 673904, + 'timestamp_device': 117149, + 'timestamp_stream': 673.9033097662032, + 'transform': [array([-1.91161561e+00, -1.69476318e+01, 1.48847867e-02]), + array([-0.07129351, -0.48256245, -0.00349705])]} +{'AngularVelocity': array([ 1.28014535e-02, -1.25763007e-02, -1.26155874e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.15614040195941925, + 'FR_Wheel_Angle': 0.15637680888175964, + 'Location': array([ -0.98345792, -17.28837204, 0.16986522]), + 'Rotation': array([-6.62255138e-02, 5.71237068e+01, -4.11071740e-02]), + 'Velocity': array([-2.60599882e-06, -1.04494266e-05, 3.51446070e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.13054085, 14.30023956, 1.22908807]), + 'camera_rotation': array([-8.94730854, -0.94607311, 0.72504139]), + 'current_gear_input': False, + 'focus_actor_dist': 1649.4700927734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -271.41131592, -1368.09106445, 16.85995483]), + 'frame': 20823, + 'frame_number': 20823, + 'framesequence': 79592, + 'gaze_dir': array([ 0.99623108, -0.00530243, 0.08602905]), + 'gaze_origin': array([-3.08382726, -0.01446152, 0.08339234]), + 'gaze_valid': True, + 'gaze_vergence': 349.2770080566406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99601746, 0.00273132, 0.08900452]), + 'left_gaze_origin': array([-3.01618814, 3.1784718 , 0.08678742]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4718475341796875, + 'left_pupil_posn': array([ 0.03616667, -0.03016996]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9964447 , -0.01333618, 0.08305359]), + 'right_gaze_origin': array([-3.15146661, -3.2073946 , 0.07999726]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.373016357421875, + 'right_pupil_posn': array([ 0.01402712, -0.09869373]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14101383090019226, + 'throttle_input': 0.21031509339809418, + 'timestamp': 673.9370287656784, + 'timestamp_carla': 673938, + 'timestamp_device': 117182, + 'timestamp_stream': 673.9370287656784, + 'transform': [array([-1.94724083e+00, -1.68985863e+01, 1.48055069e-02]), + array([-0.07082906, -0.34095141, -0.0031009 ])]} +{'AngularVelocity': array([ 3.06785596e-03, -3.15816654e-03, -6.13645034e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16252955794334412, + 'FR_Wheel_Angle': 0.20764794945716858, + 'Location': array([ -0.98344678, -17.2883606 , 0.16983299]), + 'Rotation': array([-6.40944913e-02, 5.71235161e+01, -4.06494103e-02]), + 'Velocity': array([ 2.17273828e-06, -2.78564153e-06, -1.79159921e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.10833168, 14.22319794, 1.26394415]), + 'camera_rotation': array([-8.75884247, -1.48342347, 0.8017633 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1705.91845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -270.00015259, -1307.28540039, 16.84306335]), + 'frame': 20824, + 'frame_number': 20824, + 'framesequence': 79596, + 'gaze_dir': array([9.96826172e-01, 5.11169434e-04, 7.86209106e-02]), + 'gaze_origin': array([-3.08844543, -0.02063522, 0.08505402]), + 'gaze_valid': True, + 'gaze_vergence': 151.14910888671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99604797, 0.00724792, 0.08848572]), + 'left_gaze_origin': array([-3.06122303, 3.17267323, 0.1022522 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.475189208984375, + 'left_pupil_posn': array([ 0.04246938, -0.03291702]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99760437, -0.00622559, 0.0687561 ]), + 'right_gaze_origin': array([-3.11566806, -3.21394348, 0.06785583]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3040008544921875, + 'right_pupil_posn': array([ 0.01939738, -0.1004281 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1357768476009369, + 'throttle_input': 0.19839780032634735, + 'timestamp': 673.9700822681189, + 'timestamp_carla': 673971, + 'timestamp_device': 117215, + 'timestamp_stream': 673.9700822681189, + 'transform': [array([-1.98197198e+00, -1.68494186e+01, 1.47077655e-02]), + array([-0.07019385, -0.20339134, -0.00256815])]} +{'AngularVelocity': array([ 6.27156754e-04, -9.12968826e-04, -4.12507097e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.0856695175170898, + 'FR_Wheel_Angle': 1.348429799079895, + 'Location': array([ -0.98344398, -17.28835869, 0.16983543]), + 'Rotation': array([-6.39647171e-02, 5.71234741e+01, -4.06188890e-02]), + 'Velocity': array([ 3.51423387e-06, -7.19937930e-07, -4.04497041e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.10807514, 14.15434837, 1.28475475]), + 'camera_rotation': array([-8.75951195, -1.97220778, 0.77382457]), + 'current_gear_input': False, + 'focus_actor_dist': 1608.8033447265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -271.38842773, -1400.05383301, 16.8680954 ]), + 'frame': 20825, + 'frame_number': 20825, + 'framesequence': 79600, + 'gaze_dir': array([0.99677277, 0.00393677, 0.07926941]), + 'gaze_origin': array([-3.08943439, -0.0235054 , 0.08507004]), + 'gaze_valid': True, + 'gaze_vergence': 200.73753356933594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99610901, 0.01226807, 0.08720398]), + 'left_gaze_origin': array([-3.04283166, 3.169559 , 0.09705963]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4569549560546875, + 'left_pupil_posn': array([ 0.04522014, -0.0321511 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99743652, -0.00439453, 0.07133484]), + 'right_gaze_origin': array([-3.13603687, -3.21656942, 0.07308044]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.282440185546875, + 'right_pupil_posn': array([ 0.02326918, -0.10106981]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.130027174949646, + 'throttle_input': 0.19839780032634735, + 'timestamp': 674.0034828670323, + 'timestamp_carla': 674004, + 'timestamp_device': 117249, + 'timestamp_stream': 674.0034828670323, + 'transform': [array([-2.01657152e+00, -1.67988091e+01, 1.45752048e-02]), + array([-0.06939472, -0.06682544, -0.00187829])]} +{'AngularVelocity': array([ 2.07048608e-04, -1.34592716e-04, -2.62035223e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.81225323677063, + 'FR_Wheel_Angle': 4.541336536407471, + 'Location': array([ -0.98343593, -17.28834534, 0.16985424]), + 'Rotation': array([-6.39647171e-02, 5.71234741e+01, -4.06188890e-02]), + 'Velocity': array([ 3.75891091e-06, -4.33241951e-07, -3.74159979e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.0947752 , 14.10451508, 1.30290866]), + 'camera_rotation': array([-8.67459202, -2.40885448, 0.71362752]), + 'current_gear_input': False, + 'focus_actor_dist': 1621.8660888671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -266.86035156, -1382.48120117, 16.85905457]), + 'frame': 20826, + 'frame_number': 20826, + 'framesequence': 79604, + 'gaze_dir': array([0.9967041 , 0.01155853, 0.07893372]), + 'gaze_origin': array([-3.10592127, -0.02641983, 0.08672791]), + 'gaze_valid': True, + 'gaze_vergence': 188.10292053222656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99594116, 0.02296448, 0.08686829]), + 'left_gaze_origin': array([-3.04467487, 3.1665802 , 0.09367371]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3330535888671875, + 'left_pupil_posn': array([ 0.04878962, -0.03474712]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([9.97467041e-01, 1.52587891e-04, 7.09991455e-02]), + 'right_gaze_origin': array([-3.16716766, -3.21942019, 0.07978211]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3746337890625, + 'right_pupil_posn': array([ 0.02946615, -0.1024431 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12246467918157578, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.0361992679536, + 'timestamp_carla': 674037, + 'timestamp_device': 117282, + 'timestamp_stream': 674.0361992679536, + 'transform': [array([-2.04954743e+00, -1.67484207e+01, 1.44486427e-02]), + array([-0.068418 , 0.06288284, -0.00116796])]} +{'AngularVelocity': array([ 6.61251834e-05, -5.98169645e-05, -9.31678244e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.412242889404297, + 'FR_Wheel_Angle': 8.35077953338623, + 'Location': array([ -0.98343575, -17.28834534, 0.16982448]), + 'Rotation': array([-6.39647171e-02, 5.71234741e+01, -4.06188890e-02]), + 'Velocity': array([ 4.28584417e-06, -7.45058060e-08, 5.74555015e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.08367157, 14.05521488, 1.29922307]), + 'camera_rotation': array([-8.51010799, -2.79320717, 0.77848971]), + 'current_gear_input': False, + 'focus_actor_dist': 1645.7713623046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -270.17141724, -1353.6328125 , 16.85501099]), + 'frame': 20827, + 'frame_number': 20827, + 'framesequence': 79608, + 'gaze_dir': array([0.99726868, 0.01499939, 0.07117462]), + 'gaze_origin': array([-3.09538579, -0.02955399, 0.0854805 ]), + 'gaze_valid': True, + 'gaze_vergence': 150.98350524902344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99645996, 0.0219574 , 0.08108521]), + 'left_gaze_origin': array([-3.03594232, 3.16301584, 0.09305268]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3242340087890625, + 'left_pupil_posn': array([ 0.05389845, -0.03677356]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99807739, 0.00804138, 0.06126404]), + 'right_gaze_origin': array([-3.1548295 , -3.22212386, 0.07790833]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.25006103515625, + 'right_pupil_posn': array([ 0.03072023, -0.10338354]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11451765894889832, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.069918166846, + 'timestamp_carla': 674071, + 'timestamp_device': 117315, + 'timestamp_stream': 674.069918166846, + 'transform': [array([-2.08217072e+00, -1.66958218e+01, 1.42921917e-02]), + array([-0.06729102, 0.19071968, -0.00034833])]} +{'AngularVelocity': array([0.02247826, 0.02367695, 0.18460411]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.95590591430664, + 'FR_Wheel_Angle': 11.293059349060059, + 'Location': array([ -0.98329884, -17.28811836, 0.16984577]), + 'Rotation': array([-6.38690963e-02, 5.71235466e+01, -4.07409631e-02]), + 'Velocity': array([-0.00041289, 0.00663066, 0.00084227]), + 'brake_input': 0.0, + 'camera_location': array([-5.08784771, 14.02873611, 1.29170692]), + 'camera_rotation': array([-8.52802372, -3.10685086, 0.73956662]), + 'current_gear_input': False, + 'focus_actor_dist': 1539.5782470703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -272.18017578, -1455.32385254, 16.88684082]), + 'frame': 20828, + 'frame_number': 20828, + 'framesequence': 79613, + 'gaze_dir': array([0.99717712, 0.01604462, 0.07247162]), + 'gaze_origin': array([-3.09174681, -0.03050079, 0.08454285]), + 'gaze_valid': True, + 'gaze_vergence': 172.68231201171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9964447 , 0.02215576, 0.08114624]), + 'left_gaze_origin': array([-3.03262186, 3.16204381, 0.09225465]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.37591552734375, + 'left_pupil_posn': array([ 0.05520523, -0.03593814]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99790955, 0.00993347, 0.063797 ]), + 'right_gaze_origin': array([-3.15087128, -3.22304559, 0.07683106]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2508544921875, + 'right_pupil_posn': array([ 0.03134418, -0.10338354]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10444654524326324, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.1042813658714, + 'timestamp_carla': 674105, + 'timestamp_device': 117357, + 'timestamp_stream': 674.1042813658714, + 'transform': [array([-2.11346793e+00, -1.66416531e+01, 1.41199781e-02]), + array([-0.06597962, 0.3128466 , 0.00054932])]} +{'AngularVelocity': array([-0.03089485, -0.03247458, -0.23204497]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.227280616760254, + 'FR_Wheel_Angle': 12.69675350189209, + 'Location': array([ -0.9832288 , -17.28814125, 0.16983753]), + 'Rotation': array([-6.39988706e-02, 5.71214333e+01, -4.03137133e-02]), + 'Velocity': array([ 0.00179463, -0.00699843, -0.00021969]), + 'brake_input': 0.0, + 'camera_location': array([-5.09381485, 14.00084114, 1.30058658]), + 'camera_rotation': array([-8.44983864, -3.31418729, 0.89331514]), + 'current_gear_input': False, + 'focus_actor_dist': 1559.0660400390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -268.41934204, -1430.89440918, 16.87458801]), + 'frame': 20829, + 'frame_number': 20829, + 'framesequence': 79616, + 'gaze_dir': array([0.99707794, 0.01712036, 0.07341003]), + 'gaze_origin': array([-3.09013534, -0.03150025, 0.08270417]), + 'gaze_valid': True, + 'gaze_vergence': 124.17058563232422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99621582, 0.02256775, 0.08389282]), + 'left_gaze_origin': array([-3.03029203, 3.16102767, 0.09068146]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.354766845703125, + 'left_pupil_posn': array([ 0.05648386, -0.03683484]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99794006, 0.01167297, 0.06292725]), + 'right_gaze_origin': array([-3.14997888, -3.22402835, 0.07472687]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2375946044921875, + 'right_pupil_posn': array([ 0.0321393 , -0.10366404]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09278237819671631, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.1373690664768, + 'timestamp_carla': 674138, + 'timestamp_device': 117382, + 'timestamp_stream': 674.1373690664768, + 'transform': [array([-2.14122605e+00, -1.65889454e+01, 1.40014077e-02]), + array([-0.06454528, 0.42062718, 0.00128175])]} +{'AngularVelocity': array([-0.02966277, -0.02737467, -0.25824624]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.336081504821777, + 'FR_Wheel_Angle': 12.710538864135742, + 'Location': array([ -0.98368061, -17.28904152, 0.16985695]), + 'Rotation': array([-6.43267184e-02, 5.71167450e+01, -4.01611254e-02]), + 'Velocity': array([-0.00292971, -0.0154064 , 0.0004473 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.0973711 , 13.9637022 , 1.29348266]), + 'camera_rotation': array([-8.39499187, -3.38871193, 1.13058317]), + 'current_gear_input': False, + 'focus_actor_dist': 1606.0234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -266.8112793 , -1378.66577148, 16.85799408]), + 'frame': 20830, + 'frame_number': 20830, + 'framesequence': 79621, + 'gaze_dir': array([0.99701691, 0.01851654, 0.07375336]), + 'gaze_origin': array([-3.08715153, -0.03256531, 0.08155823]), + 'gaze_valid': True, + 'gaze_vergence': 150.99713134765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99613953, 0.02580261, 0.08377075]), + 'left_gaze_origin': array([-3.02664042, 3.16052389, 0.08905335]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30255126953125, + 'left_pupil_posn': array([ 0.05667865, -0.03686261]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99789429, 0.01123047, 0.06373596]), + 'right_gaze_origin': array([-3.1476624 , -3.22565484, 0.07406311]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2223968505859375, + 'right_pupil_posn': array([ 0.03432465, -0.10373533]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08197882771492004, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.1722122654319, + 'timestamp_carla': 674173, + 'timestamp_device': 117424, + 'timestamp_stream': 674.1722122654319, + 'transform': [array([-2.16769743e+00, -1.65330067e+01, 1.38550466e-02]), + array([-0.06304947, 0.5228585 , 0.0020752 ])]} +{'AngularVelocity': array([-0.02838376, -0.03053834, -0.31675538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.326557159423828, + 'FR_Wheel_Angle': 12.665609359741211, + 'Location': array([ -0.98556221, -17.29270744, 0.16984768]), + 'Rotation': array([-6.46340773e-02, 5.70996971e+01, -4.00390588e-02]), + 'Velocity': array([-0.00843302, -0.02750152, 0.00014745]), + 'brake_input': 0.0, + 'camera_location': array([-5.11170864, 13.95352936, 1.28763783]), + 'camera_rotation': array([-8.41752434, -3.39160228, 1.07137215]), + 'current_gear_input': False, + 'focus_actor_dist': 1632.0814208984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -269.91369629, -1347.36254883, 16.8532486 ]), + 'frame': 20831, + 'frame_number': 20831, + 'framesequence': 79624, + 'gaze_dir': array([0.99028015, 0.11579895, 0.07570648]), + 'gaze_origin': array([-3.1387043 , -0.10773392, 0.10530625]), + 'gaze_valid': True, + 'gaze_vergence': 218.0837860107422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9884491 , 0.12849426, 0.08021545]), + 'left_gaze_origin': array([-3.04008651, 3.0842135 , 0.09912263]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.339324951171875, + 'left_pupil_posn': array([ 0.13991058, -0.03086078]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99211121, 0.10310364, 0.07119751]), + 'right_gaze_origin': array([-3.23732162, -3.29968119, 0.11148987]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9853973388671875, + 'right_pupil_posn': array([ 0.12301302, -0.09697413]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07049775868654251, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.2031266652048, + 'timestamp_carla': 674204, + 'timestamp_device': 117449, + 'timestamp_stream': 674.2031266652048, + 'transform': [array([-2.18874288e+00, -1.64828091e+01, 1.38112260e-02]), + array([-0.06173808, 0.60361946, 0.00253296])]} +{'AngularVelocity': array([-0.02508915, -0.02877415, -0.30582908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.495160102844238, + 'FR_Wheel_Angle': 11.371294021606445, + 'Location': array([ -0.98832715, -17.2980957 , 0.16985717]), + 'Rotation': array([-6.42652437e-02, 5.70756721e+01, -4.01916467e-02]), + 'Velocity': array([-1.00098522e-02, -2.97684725e-02, 1.64222711e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.10049629, 13.94647789, 1.29387558]), + 'camera_rotation': array([-8.44227695, -3.29191232, 1.08656228]), + 'current_gear_input': False, + 'focus_actor_dist': 1649.2515869140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -433.15301514, -1327.75720215, 17.01327515]), + 'frame': 20832, + 'frame_number': 20832, + 'framesequence': 79628, + 'gaze_dir': array([0.97195435, 0.2153244 , 0.09392548]), + 'gaze_origin': array([-3.10846424, -0.18422395, 0.09677277]), + 'gaze_valid': True, + 'gaze_vergence': 302.0967102050781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96965027, 0.22496033, 0.09562683]), + 'left_gaze_origin': array([-3.04872608, 2.9969697 , 0.10326234]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2752227783203125, + 'left_pupil_posn': array([ 0.2349757 , -0.02392089]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9738056659698486, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97425842, 0.20568848, 0.09222412]), + 'right_gaze_origin': array([-3.16820216, -3.36541748, 0.09028321]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.056732177734375, + 'right_pupil_posn': array([ 0.20039332, -0.09564817]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06015198677778244, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.2358651682734, + 'timestamp_carla': 674237, + 'timestamp_device': 117482, + 'timestamp_stream': 674.2358651682734, + 'transform': [array([-2.20830369e+00, -1.64292107e+01, 1.37460036e-02]), + array([-0.06042668, 0.67812413, 0.00299072])]} +{'AngularVelocity': array([-0.02517687, -0.02166052, -0.26286003]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.113921165466309, + 'FR_Wheel_Angle': 8.172158241271973, + 'Location': array([ -0.99128163, -17.30368042, 0.16984996]), + 'Rotation': array([-6.41559660e-02, 5.70534363e+01, -4.03442346e-02]), + 'Velocity': array([-1.28100561e-02, -3.18198092e-02, -5.58280917e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.11752319, 13.93287468, 1.28514969]), + 'camera_rotation': array([-8.46140862, -3.22201276, 1.10187614]), + 'current_gear_input': False, + 'focus_actor_dist': 1014.5032958984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -495.54776001, -1965.97290039, 81.60168457]), + 'frame': 20833, + 'frame_number': 20833, + 'framesequence': 79633, + 'gaze_dir': array([0.97306061, 0.21096039, 0.0923233 ]), + 'gaze_origin': array([-3.10822082, -0.188192 , 0.09774857]), + 'gaze_valid': True, + 'gaze_vergence': 286.27508544921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97109985, 0.22106934, 0.08990479]), + 'left_gaze_origin': array([-3.04874897, 2.99469781, 0.10422516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2617950439453125, + 'left_pupil_posn': array([ 0.23484516, -0.02233303]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9731295704841614, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97502136, 0.20085144, 0.09474182]), + 'right_gaze_origin': array([-3.16769266, -3.37108183, 0.09127197]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0608367919921875, + 'right_pupil_posn': array([ 0.20285094, -0.09679508]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04938505217432976, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.2715576663613, + 'timestamp_carla': 674272, + 'timestamp_device': 117524, + 'timestamp_stream': 674.2715576663613, + 'transform': [array([-2.22645259e+00, -1.63704472e+01, 1.36075784e-02]), + array([-0.05913578, 0.74656367, 0.00366212])]} +{'AngularVelocity': array([-0.10798122, 0.08196916, 0.26544622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.8986167907714844, + 'FR_Wheel_Angle': 3.3430075645446777, + 'Location': array([ -1.00424051, -17.32584953, 0.16995677]), + 'Rotation': array([-7.85540044e-02, 5.70001373e+01, -3.78417931e-02]), + 'Velocity': array([-1.98745862e-01, -3.38142693e-01, 2.31037135e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.14053822, 13.95066166, 1.28178048]), + 'camera_rotation': array([-8.47228909, -3.10482764, 0.88179821]), + 'current_gear_input': False, + 'focus_actor_dist': 1011.1343383789062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -493.25305176, -1963.85498047, 79.69244385]), + 'frame': 20834, + 'frame_number': 20834, + 'framesequence': 79636, + 'gaze_dir': array([0.97333527, 0.20998383, 0.09174347]), + 'gaze_origin': array([-3.10792708, -0.18764801, 0.09887925]), + 'gaze_valid': True, + 'gaze_vergence': 334.0714111328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97138977, 0.21905518, 0.09165955]), + 'left_gaze_origin': array([-3.04829431, 2.99622512, 0.10552674]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2652130126953125, + 'left_pupil_posn': array([ 0.2337991 , -0.02237332]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9894461035728455, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97528076, 0.20091248, 0.09182739]), + 'right_gaze_origin': array([-3.16755986, -3.371521 , 0.09223176]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.051971435546875, + 'right_pupil_posn': array([ 0.20245242, -0.09541368]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03891110420227051, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.3028956651688, + 'timestamp_carla': 674304, + 'timestamp_device': 117549, + 'timestamp_stream': 674.3028956651688, + 'transform': [array([-2.23973632e+00, -1.63183441e+01, 1.35738747e-02]), + array([-0.05810441, 0.79600149, 0.00402832])]} +{'AngularVelocity': array([ 0.06968836, -0.02219738, -0.03311757]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.189231738448143, + 'FR_Wheel_Angle': -0.13820962607860565, + 'Location': array([ -1.09290576, -17.46696663, 0.17012347]), + 'Rotation': array([-8.43255073e-02, 5.68790703e+01, -4.18395959e-02]), + 'Velocity': array([-0.44176674, -0.6811108 , 0.00079637]), + 'brake_input': 0.0, + 'camera_location': array([-5.14626884, 13.95966911, 1.27204192]), + 'camera_rotation': array([-8.50110531, -2.75172019, 0.96583331]), + 'current_gear_input': False, + 'focus_actor_dist': 1008.1124267578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -494.86114502, -1961.41479492, 79.86659241]), + 'frame': 20835, + 'frame_number': 20835, + 'framesequence': 79641, + 'gaze_dir': array([0.97348785, 0.21018219, 0.08966064]), + 'gaze_origin': array([-3.10747004, -0.1867798 , 0.10008698]), + 'gaze_valid': True, + 'gaze_vergence': 319.8733825683594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97174072, 0.21920776, 0.08743286]), + 'left_gaze_origin': array([-3.04825449, 2.99807143, 0.10552674]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2613525390625, + 'left_pupil_posn': array([ 0.23263371, -0.02233303]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9868136644363403, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97523499, 0.20115662, 0.09188843]), + 'right_gaze_origin': array([-3.16668558, -3.37163091, 0.09464722]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0509796142578125, + 'right_pupil_posn': array([ 0.20253134, -0.09509146]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.028968172147870064, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.33677636832, + 'timestamp_carla': 674338, + 'timestamp_device': 117590, + 'timestamp_stream': 674.33677636832, + 'transform': [array([-2.25108719e+00, -1.62616310e+01, 1.35002322e-02]), + array([-0.05706623, 0.83741379, 0.00445557])]} +{'AngularVelocity': array([-0.00483975, -0.00201656, 0.00494116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.013791704550385475, + 'FR_Wheel_Angle': -0.013775041326880455, + 'Location': array([ -1.22457182, -17.66842842, 0.17031834]), + 'Rotation': array([-8.18803012e-02, 5.68800125e+01, -4.10766564e-02]), + 'Velocity': array([-0.64647973, -0.98966193, 0.00101599]), + 'brake_input': 0.0, + 'camera_location': array([-5.16164303, 13.99260235, 1.26965892]), + 'camera_rotation': array([-8.47575855, -2.4624567 , 0.89376307]), + 'current_gear_input': False, + 'focus_actor_dist': 995.3077392578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -500.03167725, -1970.33203125, 77.70492554]), + 'frame': 20836, + 'frame_number': 20836, + 'framesequence': 79644, + 'gaze_dir': array([0.97557068, 0.20046234, 0.08912659]), + 'gaze_origin': array([-3.10500741, -0.18655473, 0.10200882]), + 'gaze_valid': True, + 'gaze_vergence': 256.6466369628906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97419739, 0.20953369, 0.08383179]), + 'left_gaze_origin': array([-3.04455113, 3.00170135, 0.10787201]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.212799072265625, + 'left_pupil_posn': array([ 0.22674704, -0.01894724]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97694397, 0.19139099, 0.09442139]), + 'right_gaze_origin': array([-3.16546345, -3.37481093, 0.09614563]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0142822265625, + 'right_pupil_posn': array([ 0.20123935, -0.09483552]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.018420973792672157, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.3701015673578, + 'timestamp_carla': 674371, + 'timestamp_device': 117615, + 'timestamp_stream': 674.3701015673578, + 'transform': [array([-2.25916529e+00, -1.62054443e+01, 1.34455962e-02]), + array([-0.05609634, 0.865852 , 0.00482178])]} +{'AngularVelocity': array([ 0.04180913, -0.02900699, 0.00698896]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.028701666742563248, + 'FR_Wheel_Angle': 0.14229938387870789, + 'Location': array([ -1.39734054, -17.93292618, 0.17055106]), + 'Rotation': array([-7.94965699e-02, 5.68812141e+01, -4.04663086e-02]), + 'Velocity': array([-7.89577723e-01, -1.20872903e+00, 9.63706931e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.1904707 , 14.05216217, 1.28732061]), + 'camera_rotation': array([-8.49188519, -2.13203669, 0.75923377]), + 'current_gear_input': False, + 'focus_actor_dist': 992.1763916015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -495.48632812, -1967.06787109, 77.87989807]), + 'frame': 20837, + 'frame_number': 20837, + 'framesequence': 79649, + 'gaze_dir': array([0.93934631, 0.33640289, 0.06652069]), + 'gaze_origin': array([-3.13212538, -0.27787858, 0.08524857]), + 'gaze_valid': True, + 'gaze_vergence': 706.014892578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93797302, 0.34033203, 0.06600952]), + 'left_gaze_origin': array([-3.07251763, 2.90051889, 0.09453583]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.186981201171875, + 'left_pupil_posn': array([ 0.34658885, -0.04581022]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9125746488571167, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9407196 , 0.33247375, 0.06703186]), + 'right_gaze_origin': array([-3.19173288, -3.45627618, 0.07596131]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.166534423828125, + 'right_pupil_posn': array([ 0.30555654, -0.12396801]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.008551286533474922, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.4045671671629, + 'timestamp_carla': 674405, + 'timestamp_device': 117657, + 'timestamp_stream': 674.4045671671629, + 'transform': [array([-2.26427794e+00, -1.61469841e+01, 1.33732026e-02]), + array([-0.05517427, 0.88241202, 0.00521851])]} +{'AngularVelocity': array([ 0.01115203, -0.03438497, -1.35415161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.397623300552368, + 'FR_Wheel_Angle': 4.324418544769287, + 'Location': array([ -1.58084345, -18.21845818, 0.17079036]), + 'Rotation': array([-7.10134730e-02, 5.67660713e+01, -3.52477916e-02]), + 'Velocity': array([-7.84116030e-01, -1.26884043e+00, 1.08890526e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.23305988, 14.13269997, 1.31207073]), + 'camera_rotation': array([-8.49606514, -1.56959867, 0.90133154]), + 'current_gear_input': False, + 'focus_actor_dist': 1022.4727172851562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -646.49621582, -1970.1550293 , 57.23639679]), + 'frame': 20838, + 'frame_number': 20838, + 'framesequence': 79653, + 'gaze_dir': array([0.93906403, 0.33704376, 0.06723785]), + 'gaze_origin': array([-3.13237309, -0.27831116, 0.08535615]), + 'gaze_valid': True, + 'gaze_vergence': 692.2112426757812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94033813, 0.33381653, 0.06558228]), + 'left_gaze_origin': array([-3.07308817, 2.90294814, 0.09361573]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2722015380859375, + 'left_pupil_posn': array([ 0.34766698, -0.04626024]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9041936993598938, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93778992, 0.340271 , 0.06889343]), + 'right_gaze_origin': array([-3.19165802, -3.45957065, 0.07709656]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1577606201171875, + 'right_pupil_posn': array([ 0.30546749, -0.12311554]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0022705772425979376, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.4378292672336, + 'timestamp_carla': 674439, + 'timestamp_device': 117690, + 'timestamp_stream': 674.4378292672336, + 'transform': [array([-2.26589203e+00, -1.60901699e+01, 1.33341216e-02]), + array([-0.05425902, 0.88525689, 0.00552369])]} +{'AngularVelocity': array([ 0.04897235, -0.03757035, -2.92908835]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.857693672180176, + 'FR_Wheel_Angle': 10.241422653198242, + 'Location': array([ -1.7283442 , -18.46477318, 0.17087337]), + 'Rotation': array([-4.62335497e-02, 5.62327881e+01, -3.43627892e-02]), + 'Velocity': array([-4.61941361e-01, -8.45375955e-01, 5.77583327e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.273283 , 14.23456383, 1.34077871]), + 'camera_rotation': array([-8.41744995, -0.84812051, 1.08351469]), + 'current_gear_input': False, + 'focus_actor_dist': 1020.2494506835938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -656.52990723, -1970.09082031, 57.2742691 ]), + 'frame': 20839, + 'frame_number': 20839, + 'framesequence': 79656, + 'gaze_dir': array([0.94288635, 0.32701111, 0.06324768]), + 'gaze_origin': array([-3.12968898, -0.27298966, 0.08559266]), + 'gaze_valid': True, + 'gaze_vergence': 762.3692016601562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94226074, 0.32917786, 0.0612793 ]), + 'left_gaze_origin': array([-3.06973886, 2.91005421, 0.09335785]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1878662109375, + 'left_pupil_posn': array([ 0.33717036, -0.04648232]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9259999990463257, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94351196, 0.32484436, 0.06521606]), + 'right_gaze_origin': array([-3.18963933, -3.45603347, 0.07782745]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0710601806640625, + 'right_pupil_posn': array([ 0.30126154, -0.12340534]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.010986663401126862, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.4711234681308, + 'timestamp_carla': 674472, + 'timestamp_device': 117715, + 'timestamp_stream': 674.4711234681308, + 'transform': [array([-2.26441741e+00, -1.60329132e+01, 1.32953636e-02]), + array([-0.05349404, 0.87597084, 0.00579835])]} +{'AngularVelocity': array([ 0.00470002, 0.02191762, -3.05534101]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.866508483886719, + 'FR_Wheel_Angle': 13.972845077514648, + 'Location': array([ -1.82529628, -18.63801384, 0.17106518]), + 'Rotation': array([-5.04750945e-02, 5.55300102e+01, -3.77502441e-02]), + 'Velocity': array([-0.34768301, -0.6693244 , 0.00068352]), + 'brake_input': 0.0, + 'camera_location': array([-5.31567955, 14.35892296, 1.34305036]), + 'camera_rotation': array([-8.33546638, -0.04025037, 1.13000822]), + 'current_gear_input': False, + 'focus_actor_dist': 1014.557861328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -656.83721924, -1970.85913086, 53.57789612]), + 'frame': 20840, + 'frame_number': 20840, + 'framesequence': 79660, + 'gaze_dir': array([0.94577026, 0.31921387, 0.05949402]), + 'gaze_origin': array([-3.1267159 , -0.26542056, 0.08543167]), + 'gaze_valid': True, + 'gaze_vergence': 364.5811462402344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94364929, 0.32601929, 0.05662537]), + 'left_gaze_origin': array([-3.06654215, 2.91822219, 0.09293366]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.138031005859375, + 'left_pupil_posn': array([ 0.32702363, -0.04670978]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9285291433334351, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94789124, 0.31240845, 0.06236267]), + 'right_gaze_origin': array([-3.18688965, -3.4490633 , 0.07792969]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0945587158203125, + 'right_pupil_posn': array([ 0.2950629 , -0.12437081]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0142277292907238, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.5035675652325, + 'timestamp_carla': 674504, + 'timestamp_device': 117749, + 'timestamp_stream': 674.5035675652325, + 'transform': [array([-2.26122952e+00, -1.59766045e+01, 1.32657243e-02]), + array([-0.05337109, 0.86012423, 0.00598145])]} +{'AngularVelocity': array([-0.00613005, 0.01366949, -2.81798077]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.024984359741211, + 'FR_Wheel_Angle': 17.92660903930664, + 'Location': array([ -1.89523554, -18.76833725, 0.17115505]), + 'Rotation': array([-5.21826409e-02, 5.48289833e+01, -4.01306078e-02]), + 'Velocity': array([-2.26265639e-01, -4.65822965e-01, 1.61762233e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.36920738, 14.47225189, 1.34357834]), + 'camera_rotation': array([-8.28009415, 0.81273401, 1.23724401]), + 'current_gear_input': False, + 'focus_actor_dist': 1011.5221557617188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -661.36010742, -1970.1628418 , 50.88776398]), + 'frame': 20841, + 'frame_number': 20841, + 'framesequence': 79665, + 'gaze_dir': array([0.95018005, 0.30516052, 0.06296539]), + 'gaze_origin': array([-3.1242435 , -0.2585274 , 0.08486024]), + 'gaze_valid': True, + 'gaze_vergence': 390.3537292480469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94821167, 0.31063843, 0.06620789]), + 'left_gaze_origin': array([-3.06399083, 2.92629099, 0.09093018]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.263275146484375, + 'left_pupil_posn': array([ 0.31674016, -0.04828382]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9318843483924866, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95214844, 0.29968262, 0.0597229 ]), + 'right_gaze_origin': array([-3.18449593, -3.44334579, 0.07879028]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1431427001953125, + 'right_pupil_posn': array([ 0.28538096, -0.1195538 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014502395875751972, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.5402187667787, + 'timestamp_carla': 674541, + 'timestamp_device': 117790, + 'timestamp_stream': 674.5402187667787, + 'transform': [array([-2.25693297e+00, -1.59125147e+01, 1.31298350e-02]), + array([-0.05404728, 0.83961582, 0.00637818])]} +{'AngularVelocity': array([-0.01060233, 0.01128287, -2.15358233]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.60642433166504, + 'FR_Wheel_Angle': 19.956615447998047, + 'Location': array([ -1.94023025, -18.85515404, 0.17127387]), + 'Rotation': array([-5.54816239e-02, 5.42640533e+01, -4.12902832e-02]), + 'Velocity': array([-0.15180503, -0.32182387, 0.00056833]), + 'brake_input': 0.0, + 'camera_location': array([-5.39831543, 14.58757973, 1.36344695]), + 'camera_rotation': array([-8.22883415, 1.70986962, 1.33099771]), + 'current_gear_input': False, + 'focus_actor_dist': 1004.4993286132812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -659.07983398, -1970.82495117, 54.9085083 ]), + 'frame': 20842, + 'frame_number': 20842, + 'framesequence': 79669, + 'gaze_dir': array([0.95372009, 0.2950058 , 0.05653381]), + 'gaze_origin': array([-3.1214869 , -0.25141984, 0.08308029]), + 'gaze_valid': True, + 'gaze_vergence': 227.02210998535156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94978333, 0.30729675, 0.05874634]), + 'left_gaze_origin': array([-3.06064939, 2.93429589, 0.08690643]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2655029296875, + 'left_pupil_posn': array([ 0.3051095 , -0.05175138]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9348590970039368, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95765686, 0.28271484, 0.05432129]), + 'right_gaze_origin': array([-3.18232441, -3.43713546, 0.07925415]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1624603271484375, + 'right_pupil_posn': array([ 0.27966273, -0.12135708]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014502395875751972, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.5740680657327, + 'timestamp_carla': 674575, + 'timestamp_device': 117824, + 'timestamp_stream': 674.5740680657327, + 'transform': [array([-2.25278163e+00, -1.58526783e+01, 1.30602075e-02]), + array([-0.05496253, 0.82005 , 0.00662232])]} +{'AngularVelocity': array([-0.01193061, 0.00446522, -1.61988986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.040340423583984, + 'FR_Wheel_Angle': 22.024641036987305, + 'Location': array([ -1.97133613, -18.91605377, 0.17133842]), + 'Rotation': array([-5.87464534e-02, 5.38279648e+01, -4.08020020e-02]), + 'Velocity': array([-1.01281628e-01, -2.20690429e-01, 8.02516952e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.43658924, 14.6829319 , 1.40562117]), + 'camera_rotation': array([-8.23080063, 2.53799367, 1.31218565]), + 'current_gear_input': False, + 'focus_actor_dist': 1001.1339111328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -662.34655762, -1969.66088867, 48.89750671]), + 'frame': 20843, + 'frame_number': 20843, + 'framesequence': 79673, + 'gaze_dir': array([0.9552002, 0.2912674, 0.0507431]), + 'gaze_origin': array([-3.11933684, -0.24524613, 0.08392487]), + 'gaze_valid': True, + 'gaze_vergence': 233.57098388671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95141602, 0.30331421, 0.05273438]), + 'left_gaze_origin': array([-3.05835581, 2.94124603, 0.08685303]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.193939208984375, + 'left_pupil_posn': array([ 0.29899967, -0.05321622]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9547764658927917, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95898438, 0.27922058, 0.04875183]), + 'right_gaze_origin': array([-3.18031788, -3.43173862, 0.08099671]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.19879150390625, + 'right_pupil_posn': array([ 0.2743125 , -0.12179935]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014282663352787495, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.6077050678432, + 'timestamp_carla': 674608, + 'timestamp_device': 117857, + 'timestamp_stream': 674.6077050678432, + 'transform': [array([-2.24861956e+00, -1.57925653e+01, 1.30094625e-02]), + array([-0.0559051 , 0.80052882, 0.00677491])]} +{'AngularVelocity': array([-0.0092953 , 0.00216426, -1.27258909]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.979137420654297, + 'FR_Wheel_Angle': 26.96198081970215, + 'Location': array([ -1.99189794, -18.95747757, 0.1713924 ]), + 'Rotation': array([-6.10960387e-02, 5.34984169e+01, -3.95812988e-02]), + 'Velocity': array([-6.52018860e-02, -1.52342975e-01, 1.40298005e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.51803112, 14.8025198 , 1.41166198]), + 'camera_rotation': array([-8.29270935, 3.18192267, 0.9820292 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1000.5706176757812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -671.60229492, -1968.19299316, 43.2039566 ]), + 'frame': 20844, + 'frame_number': 20844, + 'framesequence': 79677, + 'gaze_dir': array([0.9586792 , 0.2795639 , 0.05170441]), + 'gaze_origin': array([-3.11791086, -0.24140626, 0.08328324]), + 'gaze_valid': True, + 'gaze_vergence': 306.6700439453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95588684, 0.28890991, 0.05291748]), + 'left_gaze_origin': array([-3.05685735, 2.94597197, 0.08789521]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2041168212890625, + 'left_pupil_posn': array([ 0.29265201, -0.05122113]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9538507461547852, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96147156, 0.2702179 , 0.05049133]), + 'right_gaze_origin': array([-3.17896461, -3.42878437, 0.07867127]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.118682861328125, + 'right_pupil_posn': array([ 0.2669704 , -0.12268245]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01349528506398201, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.6407397687435, + 'timestamp_carla': 674641, + 'timestamp_device': 117890, + 'timestamp_stream': 674.6407397687435, + 'transform': [array([-2.24466252e+00, -1.57328558e+01, 1.29821301e-02]), + array([-0.05682717, 0.78191262, 0.00683594])]} +{'AngularVelocity': array([-0.00528033, 0.00410081, -1.05128372]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.331499099731445, + 'FR_Wheel_Angle': 31.6705265045166, + 'Location': array([ -2.00487685, -18.98603249, 0.17142951]), + 'Rotation': array([-6.28309101e-02, 5.32244415e+01, -3.86352502e-02]), + 'Velocity': array([-3.96504551e-02, -1.05778947e-01, -6.90133311e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.58415222, 14.92401314, 1.41954625]), + 'camera_rotation': array([-8.20629406, 3.60332417, 0.5491128 ]), + 'current_gear_input': False, + 'focus_actor_dist': 992.8729248046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -667.53271484, -1968.71789551, 45.20879364]), + 'frame': 20845, + 'frame_number': 20845, + 'framesequence': 79680, + 'gaze_dir': array([0.95741272, 0.28486633, 0.04605865]), + 'gaze_origin': array([-3.1180985 , -0.23981936, 0.08099976]), + 'gaze_valid': True, + 'gaze_vergence': 357.45477294921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95527649, 0.29241943, 0.04374695]), + 'left_gaze_origin': array([-3.05749226, 2.94809437, 0.08710328]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.225494384765625, + 'left_pupil_posn': array([ 0.29358029, -0.05299103]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9452372789382935, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95954895, 0.27731323, 0.04837036]), + 'right_gaze_origin': array([-3.17870498, -3.42773318, 0.07489625]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2627410888671875, + 'right_pupil_posn': array([ 0.26739693, -0.12856841]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01268959604203701, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.669770065695, + 'timestamp_carla': 674671, + 'timestamp_device': 117915, + 'timestamp_stream': 674.669770065695, + 'transform': [array([-2.24137926e+00, -1.56803560e+01, 1.27480887e-02]), + array([-0.05761947, 0.76641744, 0.0076294 ])]} +{'AngularVelocity': array([-0.06738512, -0.0764835 , -1.06348443]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.50022315979004, + 'FR_Wheel_Angle': 34.87724304199219, + 'Location': array([ -2.01204109, -19.0033989 , 0.17143616]), + 'Rotation': array([-6.30767941e-02, 5.30356293e+01, -3.88793908e-02]), + 'Velocity': array([-0.00724779, -0.05630238, 0.00018997]), + 'brake_input': 0.0, + 'camera_location': array([-5.58581257, 15.0471611 , 1.41991639]), + 'camera_rotation': array([-8.00395679, 3.88734174, 0.49749896]), + 'current_gear_input': False, + 'focus_actor_dist': 991.7178955078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -678.47106934, -1968.28137207, 43.42695618]), + 'frame': 20846, + 'frame_number': 20846, + 'framesequence': 79684, + 'gaze_dir': array([0.95864868, 0.28130341, 0.04109192]), + 'gaze_origin': array([-3.11653137, -0.23750763, 0.07867432]), + 'gaze_valid': True, + 'gaze_vergence': 241.48484802246094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95513916, 0.29293823, 0.04335022]), + 'left_gaze_origin': array([-3.05484486, 2.95112181, 0.08390046]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.266815185546875, + 'left_pupil_posn': array([ 0.28865635, -0.057814 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9534230828285217, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9621582 , 0.26966858, 0.03883362]), + 'right_gaze_origin': array([-3.17821836, -3.42613673, 0.07344818]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.29168701171875, + 'right_pupil_posn': array([ 0.26642394, -0.12965298]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.011938841082155704, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.7033607661724, + 'timestamp_carla': 674704, + 'timestamp_device': 117949, + 'timestamp_stream': 674.7033607661724, + 'transform': [array([-2.23779130e+00, -1.56186914e+01, 1.27330013e-02]), + array([-0.05843909, 0.74931079, 0.00769044])]} +{'AngularVelocity': array([-0.07243846, -0.08348227, -0.93747151]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.221342086791992, + 'FR_Wheel_Angle': 37.7830810546875, + 'Location': array([ -2.015589 , -19.01271629, 0.17146099]), + 'Rotation': array([-6.50302246e-02, 5.29274254e+01, -3.75366174e-02]), + 'Velocity': array([ 9.37704346e-04, -3.75953056e-02, 4.61196905e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.59605312, 15.14690113, 1.40192127]), + 'camera_rotation': array([-8.04126358, 4.10534 , 0.8057456 ]), + 'current_gear_input': False, + 'focus_actor_dist': 986.8004150390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -677.64672852, -1968.0255127 , 42.44205475]), + 'frame': 20847, + 'frame_number': 20847, + 'framesequence': 79688, + 'gaze_dir': array([0.97618103, 0.2009201 , 0.080513 ]), + 'gaze_origin': array([-3.07354522, -0.18269502, 0.08863373]), + 'gaze_valid': True, + 'gaze_vergence': 217.48680114746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.973526 , 0.21466064, 0.07835388]), + 'left_gaze_origin': array([-2.98335886, 3.0083313 , 0.08305054]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3834075927734375, + 'left_pupil_posn': array([ 0.21977317, -0.02871168]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9647775292396545, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97883606, 0.18717957, 0.08267212]), + 'right_gaze_origin': array([-3.16373158, -3.3737216 , 0.09421692]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1175994873046875, + 'right_pupil_posn': array([ 0.20213962, -0.0980351 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.011096530593931675, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.7368063665926, + 'timestamp_carla': 674738, + 'timestamp_device': 117982, + 'timestamp_stream': 674.7368063665926, + 'transform': [array([-2.23446012e+00, -1.55565987e+01, 1.27421953e-02]), + array([-0.05916993, 0.73327667, 0.0076294 ])]} +{'AngularVelocity': array([-0.07271363, -0.08557672, -1.02016926]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.065940856933594, + 'FR_Wheel_Angle': 38.85964584350586, + 'Location': array([ -2.01798606, -19.01929474, 0.17146698]), + 'Rotation': array([-6.62596598e-02, 5.28439484e+01, -3.64379883e-02]), + 'Velocity': array([ 0.00034756, -0.04070196, 0.00014007]), + 'brake_input': 0.0, + 'camera_location': array([-5.61601162, 15.21431351, 1.4000591 ]), + 'camera_rotation': array([-8.23929119, 4.16966057, 1.16309988]), + 'current_gear_input': False, + 'focus_actor_dist': 945.8207397460938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -592.97558594, -1973.20373535, 79.90208435]), + 'frame': 20848, + 'frame_number': 20848, + 'framesequence': 79692, + 'gaze_dir': array([0.98921967, 0.11687469, 0.0869751 ]), + 'gaze_origin': array([-3.09026575, -0.10415497, 0.10947266]), + 'gaze_valid': True, + 'gaze_vergence': 214.14198303222656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98728943, 0.13044739, 0.0907135 ]), + 'left_gaze_origin': array([-3.06272888, 3.08256388, 0.12206574]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4864959716796875, + 'left_pupil_posn': array([ 0.1412313 , -0.01578689]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9911499 , 0.103302 , 0.08323669]), + 'right_gaze_origin': array([-3.11780262, -3.29087377, 0.09687958]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.26715087890625, + 'right_pupil_posn': array([ 0.11459076, -0.08192408]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.010382398031651974, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.7700855657458, + 'timestamp_carla': 674771, + 'timestamp_device': 118015, + 'timestamp_stream': 674.7700855657458, + 'transform': [array([-2.23136401e+00, -1.54941435e+01, 1.27580445e-02]), + array([-0.05978464, 0.71822602, 0.00753784])]} +{'AngularVelocity': array([-0.25563398, -0.07771715, -2.71375322]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.192079544067383, + 'FR_Wheel_Angle': 39.04051208496094, + 'Location': array([ -2.02233672, -19.03043175, 0.17149593]), + 'Rotation': array([-6.95791319e-02, 5.26858978e+01, -3.24706957e-02]), + 'Velocity': array([-0.05755447, -0.17523679, 0.00044669]), + 'brake_input': 0.0, + 'camera_location': array([-5.61727142, 15.25602722, 1.42320836]), + 'camera_rotation': array([-8.20556355, 3.96284318, 1.31217992]), + 'current_gear_input': False, + 'focus_actor_dist': 918.91259765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -510.94100952, -1973.89501953, 82.91893005]), + 'frame': 20849, + 'frame_number': 20849, + 'framesequence': 79696, + 'gaze_dir': array([0.98902893, 0.11702728, 0.08974457]), + 'gaze_origin': array([-3.08110142, -0.10669174, 0.10184556]), + 'gaze_valid': True, + 'gaze_vergence': 401.88922119140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98800659, 0.1244812 , 0.09129333]), + 'left_gaze_origin': array([-3.0230577 , 3.08313155, 0.1058487 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.35809326171875, + 'left_pupil_posn': array([ 0.14280093, -0.01757002]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99005127, 0.10957336, 0.0881958 ]), + 'right_gaze_origin': array([-3.1391449 , -3.29651499, 0.09784241]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2627410888671875, + 'right_pupil_posn': array([ 0.11689186, -0.08488941]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009576709009706974, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.803823467344, + 'timestamp_carla': 674805, + 'timestamp_device': 118049, + 'timestamp_stream': 674.803823467344, + 'transform': [array([-2.22846556e+00, -1.54301844e+01, 1.27624702e-02]), + array([-0.06030374, 0.70393693, 0.00747681])]} +{'AngularVelocity': array([ 0.03931688, 0.03762523, -5.34697151]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.674222946166992, + 'FR_Wheel_Angle': 39.86139678955078, + 'Location': array([ -2.05033231, -19.10440445, 0.17159767]), + 'Rotation': array([-8.01659226e-02, 5.17232361e+01, -2.10876502e-02]), + 'Velocity': array([-0.14591423, -0.45527241, 0.0009817 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.61489868, 15.28039265, 1.4308939 ]), + 'camera_rotation': array([-7.95472479, 3.67312098, 1.33660495]), + 'current_gear_input': False, + 'focus_actor_dist': 914.781982421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -507.12036133, -1970.86315918, 85.9588623 ]), + 'frame': 20850, + 'frame_number': 20850, + 'framesequence': 79700, + 'gaze_dir': array([0.98900604, 0.1184845 , 0.0883255 ]), + 'gaze_origin': array([-3.06662154, -0.10977631, 0.09417573]), + 'gaze_valid': True, + 'gaze_vergence': 712.420166015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98843384, 0.12275696, 0.08903503]), + 'left_gaze_origin': array([-2.99772358, 3.08261132, 0.09545746]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4137420654296875, + 'left_pupil_posn': array([ 0.14453459, -0.02026749]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98957825, 0.11421204, 0.08761597]), + 'right_gaze_origin': array([-3.1355195 , -3.30216408, 0.09289399]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2399139404296875, + 'right_pupil_posn': array([ 0.12002587, -0.0883373 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00908230897039175, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.8370854668319, + 'timestamp_carla': 674838, + 'timestamp_device': 118082, + 'timestamp_stream': 674.8370854668319, + 'transform': [array([-2.22578979e+00, -1.53665028e+01, 1.27721978e-02]), + array([-0.06072721, 0.69059736, 0.00741578])]} +{'AngularVelocity': array([ 0.13628022, 0.09018598, -8.62209606]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.749874114990234, + 'FR_Wheel_Angle': 39.93038558959961, + 'Location': array([ -2.10477805, -19.24096298, 0.17172728]), + 'Rotation': array([-8.17573592e-02, 4.98754921e+01, -2.01721173e-02]), + 'Velocity': array([-0.24356847, -0.70251244, 0.00087883]), + 'brake_input': 0.0, + 'camera_location': array([-5.59159946, 15.27912521, 1.44946706]), + 'camera_rotation': array([-7.88224268, 3.36999655, 1.43544996]), + 'current_gear_input': False, + 'focus_actor_dist': 912.4083251953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -503.30499268, -1965.92041016, 88.67938995]), + 'frame': 20851, + 'frame_number': 20851, + 'framesequence': 79704, + 'gaze_dir': array([0.9886322 , 0.12706757, 0.07946014]), + 'gaze_origin': array([-3.07223368, -0.11420136, 0.09558411]), + 'gaze_valid': True, + 'gaze_vergence': 273.2386779785156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98748779, 0.13781738, 0.07655334]), + 'left_gaze_origin': array([-3.01675415, 3.07925129, 0.10055237]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3948516845703125, + 'left_pupil_posn': array([ 0.14766192, -0.02211571]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98977661, 0.11631775, 0.08236694]), + 'right_gaze_origin': array([-3.1277132 , -3.3076539 , 0.09061585]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3423309326171875, + 'right_pupil_posn': array([ 0.12871099, -0.0931778 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00908230897039175, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.8699502684176, + 'timestamp_carla': 674871, + 'timestamp_device': 118115, + 'timestamp_stream': 674.8699502684176, + 'transform': [array([-2.22317624e+00, -1.53029804e+01, 1.27867507e-02]), + array([-0.06100725, 0.67755145, 0.00735474])]} +{'AngularVelocity': array([ 0.11762292, 0.0781256 , -7.66264725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.852128982543945, + 'FR_Wheel_Angle': 40.20250701904297, + 'Location': array([ -2.17872381, -19.41293144, 0.17176498]), + 'Rotation': array([-6.97635487e-02, 4.75331116e+01, -3.57971154e-02]), + 'Velocity': array([-0.24065809, -0.61836416, 0.00069226]), + 'brake_input': 0.0, + 'camera_location': array([-5.57051849, 15.26934052, 1.45885801]), + 'camera_rotation': array([-7.85112429, 2.97091246, 1.6305995 ]), + 'current_gear_input': False, + 'focus_actor_dist': 901.8836059570312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -503.98040771, -1970.76855469, 82.12928772]), + 'frame': 20852, + 'frame_number': 20852, + 'framesequence': 79709, + 'gaze_dir': array([0.98793793, 0.13207245, 0.07949829]), + 'gaze_origin': array([-3.06242156, -0.11839753, 0.08958512]), + 'gaze_valid': True, + 'gaze_vergence': 220.91436767578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98597717, 0.14616394, 0.08041382]), + 'left_gaze_origin': array([-3.01307988, 3.07489944, 0.09626008]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.328948974609375, + 'left_pupil_posn': array([ 0.15117204, -0.02549267]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98989868, 0.11798096, 0.07858276]), + 'right_gaze_origin': array([-3.111763 , -3.31169438, 0.08291016]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.422698974609375, + 'right_pupil_posn': array([ 0.13391042, -0.09447265]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00908230897039175, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.9042503684759, + 'timestamp_carla': 674905, + 'timestamp_device': 118157, + 'timestamp_stream': 674.9042503684759, + 'transform': [array([-2.22041869e+00, -1.52361107e+01, 1.27696609e-02]), + array([-0.06119166, 0.66385323, 0.00738526])]} +{'AngularVelocity': array([ 0.08723717, 0.06976636, -6.11367846]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.729135513305664, + 'FR_Wheel_Angle': 41.65314483642578, + 'Location': array([ -2.22737122, -19.51844406, 0.17179699]), + 'Rotation': array([-6.42652437e-02, 4.60548668e+01, -4.12597619e-02]), + 'Velocity': array([-2.00652003e-01, -4.86965507e-01, 2.70719524e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.56778526, 15.24983025, 1.44913828]), + 'camera_rotation': array([-7.87580872, 2.58274889, 1.72689557]), + 'current_gear_input': False, + 'focus_actor_dist': 896.9908447265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -501.41333008, -1968.81469727, 82.50604248]), + 'frame': 20853, + 'frame_number': 20853, + 'framesequence': 79712, + 'gaze_dir': array([0.98770142, 0.13423157, 0.07952881]), + 'gaze_origin': array([-3.0807116 , -0.12512742, 0.0960373 ]), + 'gaze_valid': True, + 'gaze_vergence': 259.8777160644531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98724365, 0.14118958, 0.07345581]), + 'left_gaze_origin': array([-2.99352431, 3.06951165, 0.09095307]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3936004638671875, + 'left_pupil_posn': array([ 0.15783799, -0.02333879]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98815918, 0.12727356, 0.08560181]), + 'right_gaze_origin': array([-3.16789865, -3.31976628, 0.10112153]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3795318603515625, + 'right_pupil_posn': array([ 0.13920307, -0.09470296]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00908230897039175, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.9372086673975, + 'timestamp_carla': 674938, + 'timestamp_device': 118182, + 'timestamp_stream': 674.9372086673975, + 'transform': [array([-2.21773839e+00, -1.51712914e+01, 1.27744675e-02]), + array([-0.06130777, 0.6506024 , 0.00738526])]} +{'AngularVelocity': array([ 0.0521431 , 0.06786338, -4.58686304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.829666137695312, + 'FR_Wheel_Angle': 41.74467086791992, + 'Location': array([ -2.27780128, -19.62348747, 0.17186341]), + 'Rotation': array([-6.30767941e-02, 4.45224113e+01, -4.16564867e-02]), + 'Velocity': array([-1.52197048e-01, -3.41392219e-01, 2.70767196e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.563344 , 15.2186203 , 1.40524018]), + 'camera_rotation': array([-7.99077463, 2.20465755, 1.79726493]), + 'current_gear_input': False, + 'focus_actor_dist': 891.3099975585938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -496.21508789, -1966.89562988, 82.26486206]), + 'frame': 20854, + 'frame_number': 20854, + 'framesequence': 79716, + 'gaze_dir': array([0.99069977, 0.09753418, 0.09449005]), + 'gaze_origin': array([-3.05292678, -0.0840271 , 0.09372788]), + 'gaze_valid': True, + 'gaze_vergence': 380.09722900390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98973083, 0.10473633, 0.097229 ]), + 'left_gaze_origin': array([-2.98041391, 3.11040068, 0.09358368]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4257965087890625, + 'left_pupil_posn': array([ 0.11750138, -0.01674151]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9916687 , 0.09033203, 0.0917511 ]), + 'right_gaze_origin': array([-3.12543964, -3.27845478, 0.09387208]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4035491943359375, + 'right_pupil_posn': array([ 0.09735954, -0.08298993]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00908230897039175, + 'throttle_input': 0.1904631108045578, + 'timestamp': 674.9696385674179, + 'timestamp_carla': 674970, + 'timestamp_device': 118215, + 'timestamp_stream': 674.9696385674179, + 'transform': [array([-2.21506476e+00, -1.51069345e+01, 1.27879716e-02]), + array([-0.06139657, 0.63746428, 0.00735474])]} +{'AngularVelocity': array([ 0.06809257, 0.07679532, -3.30436397]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.86989974975586, + 'FR_Wheel_Angle': 41.81364059448242, + 'Location': array([ -2.30678034, -19.68086052, 0.17189808]), + 'Rotation': array([-6.42379224e-02, 4.36720772e+01, -3.99169847e-02]), + 'Velocity': array([-1.25047311e-01, -2.58234501e-01, -1.59053801e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.54740143, 15.18630409, 1.4052707 ]), + 'camera_rotation': array([-8.06697178, 1.86941457, 1.98965645]), + 'current_gear_input': False, + 'focus_actor_dist': 993.2941284179688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -473.65814209, -1852.39575195, 89.29370117]), + 'frame': 20855, + 'frame_number': 20855, + 'framesequence': 79720, + 'gaze_dir': array([0.99063873, 0.09959412, 0.09277344]), + 'gaze_origin': array([-3.0652566 , -0.09141999, 0.09556962]), + 'gaze_valid': True, + 'gaze_vergence': 312.70123291015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98944092, 0.1084137 , 0.09603882]), + 'left_gaze_origin': array([-3.00914931, 3.10165262, 0.10017395]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4192047119140625, + 'left_pupil_posn': array([ 0.12370503, -0.01831174]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99183655, 0.09077454, 0.08950806]), + 'right_gaze_origin': array([-3.12136388, -3.28449273, 0.09096527]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3609619140625, + 'right_pupil_posn': array([ 0.10264528, -0.08463824]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00908230897039175, + 'throttle_input': 0.1904631108045578, + 'timestamp': 675.0032117664814, + 'timestamp_carla': 675004, + 'timestamp_device': 118249, + 'timestamp_stream': 675.0032117664814, + 'transform': [array([-2.21226001e+00, -1.50397558e+01, 1.27836037e-02]), + array([-0.06148536, 0.62374568, 0.00735474])]} +{'AngularVelocity': array([-0.02062458, 0.04788273, -3.00429964]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.90728759765625, + 'FR_Wheel_Angle': 41.87686538696289, + 'Location': array([ -2.33539033, -19.73426628, 0.17194946]), + 'Rotation': array([-6.53375834e-02, 4.28424416e+01, -3.68347131e-02]), + 'Velocity': array([-9.68744904e-02, -1.88063309e-01, 9.86480663e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.52437496, 15.16723728, 1.41126657]), + 'camera_rotation': array([-8.03327179, 1.64904475, 2.13213277]), + 'current_gear_input': False, + 'focus_actor_dist': 1011.7261962890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -472.67315674, -1827.33691406, 84.97121429]), + 'frame': 20856, + 'frame_number': 20856, + 'framesequence': 79725, + 'gaze_dir': array([0.9903717 , 0.09931183, 0.09568787]), + 'gaze_origin': array([-3.05647969, -0.09555435, 0.09186936]), + 'gaze_valid': True, + 'gaze_vergence': 220.78343200683594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98880005, 0.10842896, 0.10250854]), + 'left_gaze_origin': array([-3.02937031, 3.09838438, 0.10678711]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.43890380859375, + 'left_pupil_posn': array([ 0.12582386, -0.01782346]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99194336, 0.0901947 , 0.08886719]), + 'right_gaze_origin': array([-3.08358932, -3.28949285, 0.07695161]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3475341796875, + 'right_pupil_posn': array([ 0.10516131, -0.08499467]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00906399730592966, + 'throttle_input': 0.1904631108045578, + 'timestamp': 675.037249468267, + 'timestamp_carla': 675038, + 'timestamp_device': 118290, + 'timestamp_stream': 675.037249468267, + 'transform': [array([-2.20938540e+00, -1.49711151e+01, 1.27644343e-02]), + array([-0.06155366, 0.6097607 , 0.00741578])]} +{'AngularVelocity': array([ 0.029607 , 0.06897651, -2.25983119]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.899715423583984, + 'FR_Wheel_Angle': 41.85396194458008, + 'Location': array([ -2.35327315, -19.7671032 , 0.17200299]), + 'Rotation': array([-6.85682669e-02, 4.23400688e+01, -3.14636230e-02]), + 'Velocity': array([-0.0954412 , -0.18776613, 0.00045577]), + 'brake_input': 0.0, + 'camera_location': array([-5.50918484, 15.15139389, 1.39893436]), + 'camera_rotation': array([-8.01045227, 1.49975741, 2.02206898]), + 'current_gear_input': False, + 'focus_actor_dist': 2875.18896484375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-7.33616821e+02, 2.26049805e+01, 1.52587891e-05]), + 'frame': 20857, + 'frame_number': 20857, + 'framesequence': 79728, + 'gaze_dir': array([0.99025726, 0.10124969, 0.09494019]), + 'gaze_origin': array([-3.05834603, -0.096698 , 0.0923996 ]), + 'gaze_valid': True, + 'gaze_vergence': 225.39317321777344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98878479, 0.10916138, 0.10183716]), + 'left_gaze_origin': array([-3.02809763, 3.0973711 , 0.10622102]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.439056396484375, + 'left_pupil_posn': array([ 0.12758029, -0.01827407]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99172974, 0.09333801, 0.08804321]), + 'right_gaze_origin': array([-3.0885942 , -3.29076719, 0.07857819]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.31732177734375, + 'right_pupil_posn': array([ 0.10641158, -0.08499467]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.008716086857020855, + 'throttle_input': 0.1904631108045578, + 'timestamp': 675.0709102675319, + 'timestamp_carla': 675072, + 'timestamp_device': 118315, + 'timestamp_stream': 675.0709102675319, + 'transform': [array([-2.20659471e+00, -1.49026909e+01, 1.27573200e-02]), + array([-0.06164929, 0.59617525, 0.0074463 ])]} +{'AngularVelocity': array([ 1.05783651e-02, -5.38566906e-04, -2.85398912e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.868894577026367, + 'FR_Wheel_Angle': 41.81498336791992, + 'Location': array([ -2.37997413, -19.81477547, 0.17205749]), + 'Rotation': array([-7.32127950e-02, 4.16130333e+01, -2.56347694e-02]), + 'Velocity': array([-1.21197768e-01, -2.56868064e-01, -5.86700444e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.50516987, 15.15375042, 1.3845315 ]), + 'camera_rotation': array([-8.03051949, 1.48978889, 1.93323672]), + 'current_gear_input': False, + 'focus_actor_dist': 2862.717041015625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-7.28738159e+02, 1.75969238e+01, -1.52587891e-05]), + 'frame': 20858, + 'frame_number': 20858, + 'framesequence': 79733, + 'gaze_dir': array([0.99002838, 0.10398102, 0.09423828]), + 'gaze_origin': array([-3.06219196, -0.09733277, 0.0939026 ]), + 'gaze_valid': True, + 'gaze_vergence': 227.38595581054688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98841858, 0.11357117, 0.10058594]), + 'left_gaze_origin': array([-3.02958989, 3.09700322, 0.10703278]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.425384521484375, + 'left_pupil_posn': array([ 0.12820125, -0.01803768]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99163818, 0.09439087, 0.08789062]), + 'right_gaze_origin': array([-3.0947938 , -3.29166865, 0.0807724 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3342437744140625, + 'right_pupil_posn': array([ 0.10869694, -0.08516896]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.008093508891761303, + 'throttle_input': 0.17856107652187347, + 'timestamp': 675.1041337661445, + 'timestamp_carla': 675105, + 'timestamp_device': 118357, + 'timestamp_stream': 675.1041337661445, + 'transform': [array([-2.20399404e+00, -1.48346043e+01, 1.27529902e-02]), + array([-0.06177223, 0.58343333, 0.00747681])]} +{'AngularVelocity': array([ 4.01876085e-02, 1.89952448e-03, -1.99214649e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.880481719970703, + 'FR_Wheel_Angle': 41.83344650268555, + 'Location': array([ -2.40993071, -19.86610031, 0.17208698]), + 'Rotation': array([-6.98591694e-02, 4.08302689e+01, -3.03039495e-02]), + 'Velocity': array([-0.10669308, -0.21429779, 0.00042962]), + 'brake_input': 0.0, + 'camera_location': array([-5.49216175, 15.15434361, 1.38315463]), + 'camera_rotation': array([-8.04102421, 1.48871136, 1.88190889]), + 'current_gear_input': False, + 'focus_actor_dist': 2807.007080078125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-726.93908691, -31.61938477, 0. ]), + 'frame': 20859, + 'frame_number': 20859, + 'framesequence': 79736, + 'gaze_dir': array([0.98995209, 0.10575104, 0.09313965]), + 'gaze_origin': array([-3.06346226, -0.09758454, 0.09429321]), + 'gaze_valid': True, + 'gaze_vergence': 246.59693908691406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9884491 , 0.11463928, 0.09896851]), + 'left_gaze_origin': array([-3.03081226, 3.09673619, 0.10744172]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.425384521484375, + 'left_pupil_posn': array([ 0.12924099, -0.01819026]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99145508, 0.09686279, 0.08731079]), + 'right_gaze_origin': array([-3.09611225, -3.2919054 , 0.08114471]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3331756591796875, + 'right_pupil_posn': array([ 0.10924792, -0.08572948]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.007397687062621117, + 'throttle_input': 0.16665904223918915, + 'timestamp': 675.1361217685044, + 'timestamp_carla': 675137, + 'timestamp_device': 118382, + 'timestamp_stream': 675.1361217685044, + 'transform': [array([-2.20169187e+00, -1.47685289e+01, 1.27618974e-02]), + array([-0.06192249, 0.57198238, 0.00747681])]} +{'AngularVelocity': array([ 0.01597733, -0.02732844, -2.74424052]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.868013381958008, + 'FR_Wheel_Angle': 41.81386184692383, + 'Location': array([ -2.44053268, -19.91690445, 0.17214981]), + 'Rotation': array([-7.06173256e-02, 4.00332909e+01, -2.86560003e-02]), + 'Velocity': array([-1.03194438e-01, -2.13119924e-01, 1.77412032e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.48831844, 15.15684891, 1.38848305]), + 'camera_rotation': array([-8.05674744, 1.51412952, 1.88713276]), + 'current_gear_input': False, + 'focus_actor_dist': 2738.18603515625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.20960815e+02, -9.35307617e+01, -1.52587891e-05]), + 'frame': 20860, + 'frame_number': 20860, + 'framesequence': 79740, + 'gaze_dir': array([0.98979187, 0.10694885, 0.09367371]), + 'gaze_origin': array([-3.06939483, -0.09865189, 0.09562683]), + 'gaze_valid': True, + 'gaze_vergence': 267.04351806640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98857117, 0.1131134 , 0.09953308]), + 'left_gaze_origin': array([-3.03042316, 3.09588623, 0.10703278]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3971099853515625, + 'left_pupil_posn': array([ 0.13116992, -0.01821184]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99101257, 0.1007843 , 0.08781433]), + 'right_gaze_origin': array([-3.10836649, -3.29319024, 0.08422089]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3300933837890625, + 'right_pupil_posn': array([ 0.10989976, -0.08566451]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.006591998506337404, + 'throttle_input': 0.1428549587726593, + 'timestamp': 675.170722566545, + 'timestamp_carla': 675171, + 'timestamp_device': 118415, + 'timestamp_stream': 675.170722566545, + 'transform': [array([-2.19949436e+00, -1.46966228e+01, 1.27052497e-02]), + array([-0.06210008, 0.56080788, 0.00765992])]} +{'AngularVelocity': array([ 0.05815759, -0.03682781, -2.27431107]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.89494514465332, + 'FR_Wheel_Angle': 41.83584213256836, + 'Location': array([ -2.46716404, -19.95944023, 0.17214577]), + 'Rotation': array([-6.88209832e-02, 3.93777542e+01, -3.10363714e-02]), + 'Velocity': array([-8.51958841e-02, -1.76662922e-01, 5.96237187e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.47576141, 15.16959667, 1.37848675]), + 'camera_rotation': array([-8.08225155, 1.50693941, 1.86685812]), + 'current_gear_input': False, + 'focus_actor_dist': 2751.232666015625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.26887207e+02, -7.45681152e+01, -1.52587891e-05]), + 'frame': 20861, + 'frame_number': 20861, + 'framesequence': 79744, + 'gaze_dir': array([0.98978424, 0.10696411, 0.09384155]), + 'gaze_origin': array([-3.07165241, -0.09922104, 0.09609528]), + 'gaze_valid': True, + 'gaze_vergence': 352.6178894042969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9887085 , 0.1134491 , 0.09777832]), + 'left_gaze_origin': array([-3.02963281, 3.09519982, 0.1059784 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3798370361328125, + 'left_pupil_posn': array([ 0.13154364, -0.01803768]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99085999, 0.10047913, 0.08990479]), + 'right_gaze_origin': array([-3.11367202, -3.29364157, 0.08621217]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.329620361328125, + 'right_pupil_posn': array([ 0.11044896, -0.0858835 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.005603198427706957, + 'throttle_input': 0.09919890016317368, + 'timestamp': 675.2039764672518, + 'timestamp_carla': 675205, + 'timestamp_device': 118448, + 'timestamp_stream': 675.2039764672518, + 'transform': [array([-2.19771719e+00, -1.46272087e+01, 1.26367761e-02]), + array([-0.06231181, 0.55141956, 0.0079651 ])]} +{'AngularVelocity': array([ 0.02263507, -0.00566517, -2.37715483]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.894145965576172, + 'FR_Wheel_Angle': 41.87767028808594, + 'Location': array([ -2.49397564, -20.00186157, 0.17218384]), + 'Rotation': array([-6.82062656e-02, 3.87172585e+01, -3.12499981e-02]), + 'Velocity': array([-0.08844171, -0.16454145, 0.00027939]), + 'brake_input': 0.0, + 'camera_location': array([-5.48596764, 15.17868042, 1.36342084]), + 'camera_rotation': array([-8.11786366, 1.46193147, 1.8082577 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2737.84326171875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-7.24079102e+02, -8.04753418e+01, -1.52587891e-05]), + 'frame': 20862, + 'frame_number': 20862, + 'framesequence': 79749, + 'gaze_dir': array([0.98956299, 0.10899353, 0.09385681]), + 'gaze_origin': array([-3.07061028, -0.09980545, 0.09648133]), + 'gaze_valid': True, + 'gaze_vergence': 422.9281921386719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98861694, 0.11552429, 0.09625244]), + 'left_gaze_origin': array([-3.02358413, 3.09470677, 0.10453339]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.37249755859375, + 'left_pupil_posn': array([ 0.13253033, -0.01738799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99050903, 0.10246277, 0.09146118]), + 'right_gaze_origin': array([-3.1176362 , -3.29431772, 0.08842926]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3281707763671875, + 'right_pupil_posn': array([ 0.11172473, -0.08566451]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004651021212339401, + 'throttle_input': 0.0634927898645401, + 'timestamp': 675.2376941666007, + 'timestamp_carla': 675238, + 'timestamp_device': 118490, + 'timestamp_stream': 675.2376941666007, + 'transform': [array([-2.19628596e+00, -1.45566988e+01, 1.25090405e-02]), + array([-0.06253038, 0.54339713, 0.00851441])]} +{'AngularVelocity': array([-0.0013631 , 0.01429801, -1.35817504]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.910104751586914, + 'FR_Wheel_Angle': 41.871490478515625, + 'Location': array([ -2.51401687, -20.0330925 , 0.17224583]), + 'Rotation': array([-6.82062656e-02, 3.82327080e+01, -3.09753399e-02]), + 'Velocity': array([-0.08381282, -0.1433832 , -0.00027487]), + 'brake_input': 0.0, + 'camera_location': array([-5.48973465, 15.18624878, 1.34708273]), + 'camera_rotation': array([-8.16498566, 1.35394657, 1.76339686]), + 'current_gear_input': False, + 'focus_actor_dist': 2708.93505859375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-722.59301758, -102.55712891, 0. ]), + 'frame': 20863, + 'frame_number': 20863, + 'framesequence': 79752, + 'gaze_dir': array([ 0.99640656, -0.00796509, 0.08180237]), + 'gaze_origin': array([-3.08824182, -0.0162529 , 0.08789521]), + 'gaze_valid': True, + 'gaze_vergence': 134.67279052734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9956665 , 0.00914001, 0.09248352]), + 'left_gaze_origin': array([-3.05304742, 3.18346739, 0.1019577 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.311065673828125, + 'left_pupil_posn': array([ 0.02869642, -0.03044879]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99714661, -0.02507019, 0.07112122]), + 'right_gaze_origin': array([-3.12343621, -3.21597314, 0.07383271]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3263092041015625, + 'right_pupil_posn': array([ 0.02160847, -0.09650469]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.003680532332509756, + 'throttle_input': 0.043656062334775925, + 'timestamp': 675.2709369659424, + 'timestamp_carla': 675272, + 'timestamp_device': 118515, + 'timestamp_stream': 675.2709369659424, + 'transform': [array([-2.19524312e+00, -1.44872713e+01, 1.23314662e-02]), + array([-0.06272162, 0.53698635, 0.00930787])]} +{'AngularVelocity': array([-0.00951694, 0.02008621, -1.09778869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.936342239379883, + 'FR_Wheel_Angle': 41.90468978881836, + 'Location': array([ -2.5298934 , -20.05735397, 0.17226261]), + 'Rotation': array([-6.82677403e-02, 3.78506927e+01, -3.02734338e-02]), + 'Velocity': array([-0.07362811, -0.12242583, -0.00029315]), + 'brake_input': 0.0, + 'camera_location': array([-5.48637581, 15.18023872, 1.34101439]), + 'camera_rotation': array([-8.22330189, 1.20397902, 1.86204267]), + 'current_gear_input': False, + 'focus_actor_dist': 1780.8460693359375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-374.4513855 , -994.75500488, 28.43108368]), + 'frame': 20864, + 'frame_number': 20864, + 'framesequence': 79757, + 'gaze_dir': array([ 0.98745728, -0.13963318, 0.07019043]), + 'gaze_origin': array([-3.13992882, 0.09552994, 0.08109742]), + 'gaze_valid': True, + 'gaze_vergence': 130.0792694091797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98959351, -0.11978149, 0.07965088]), + 'left_gaze_origin': array([-3.06947041, 3.28644896, 0.08286133]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1753997802734375, + 'left_pupil_posn': array([-0.08776671, -0.05009043]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98532104, -0.15948486, 0.06072998]), + 'right_gaze_origin': array([-3.21038675, -3.09538889, 0.0793335 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3167724609375, + 'right_pupil_posn': array([-0.10444313, -0.11250186]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0028382213786244392, + 'throttle_input': 0.019836727529764175, + 'timestamp': 675.3040316663682, + 'timestamp_carla': 675305, + 'timestamp_device': 118557, + 'timestamp_stream': 675.3040316663682, + 'transform': [array([-2.19534326e+00, -1.44180450e+01, 1.21933362e-02]), + array([-0.06323389, 0.53510773, 0.00988771])]} +{'AngularVelocity': array([-0.02849896, 0.0144209 , -0.48810521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.946130752563477, + 'FR_Wheel_Angle': 41.95991516113281, + 'Location': array([ -2.5389514 , -20.07139397, 0.17226554]), + 'Rotation': array([-6.73798099e-02, 3.76443787e+01, -3.13720666e-02]), + 'Velocity': array([-0.04870266, -0.07769213, -0.00020936]), + 'brake_input': 0.0, + 'camera_location': array([-5.48216248, 15.1629715 , 1.34374034]), + 'camera_rotation': array([-8.21791935, 0.96222591, 1.90883505]), + 'current_gear_input': False, + 'focus_actor_dist': 1767.1090087890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -135.97673035, -1011.88708496, 16.63434601]), + 'frame': 20865, + 'frame_number': 20865, + 'framesequence': 79760, + 'gaze_dir': array([ 0.98245239, -0.17906189, 0.04917145]), + 'gaze_origin': array([-3.10885954, 0.12558441, 0.06388245]), + 'gaze_valid': True, + 'gaze_vergence': 144.9098663330078, + 'handbrake_input': False, + 'left_eye_openness': 0.9570118188858032, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98428345, -0.16607666, 0.05990601]), + 'left_gaze_origin': array([-3.06657577, 3.31643534, 0.07419129]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2342987060546875, + 'left_pupil_posn': array([-0.11939925, -0.06343365]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98062134, -0.19204712, 0.03843689]), + 'right_gaze_origin': array([-3.15114307, -3.06526661, 0.05357361]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3702545166015625, + 'right_pupil_posn': array([-0.14163435, -0.12611151]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0022705772425979376, + 'throttle_input': 0.0, + 'timestamp': 675.3370794653893, + 'timestamp_carla': 675338, + 'timestamp_device': 118582, + 'timestamp_stream': 675.3370794653893, + 'transform': [array([-2.19586992e+00, -1.43491583e+01, 1.20059010e-02]), + array([-0.06350709, 0.53491592, 0.01071168])]} +{'AngularVelocity': array([ 0.01089197, -0.01378597, -1.19403267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.950471878051758, + 'FR_Wheel_Angle': 41.9672737121582, + 'Location': array([ -2.54608369, -20.08230591, 0.17228484]), + 'Rotation': array([-6.85409456e-02, 3.74743500e+01, -2.96020415e-02]), + 'Velocity': array([-0.02173902, -0.04667536, 0.00040414]), + 'brake_input': 0.0, + 'camera_location': array([-5.46247673, 15.10871696, 1.3372134 ]), + 'camera_rotation': array([-8.14525318, 0.52596927, 1.89436817]), + 'current_gear_input': False, + 'focus_actor_dist': 1384.340576171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.56942749, -1394.66882324, 16.71071625]), + 'frame': 20866, + 'frame_number': 20866, + 'framesequence': 79764, + 'gaze_dir': array([ 0.9826355 , -0.18001556, 0.04372406]), + 'gaze_origin': array([-3.11087823, 0.12241212, 0.06310349]), + 'gaze_valid': True, + 'gaze_vergence': 231.64857482910156, + 'handbrake_input': False, + 'left_eye_openness': 0.9570111036300659, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98361206, -0.17301941, 0.05058289]), + 'left_gaze_origin': array([-3.06771088, 3.31712675, 0.07257233]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.254486083984375, + 'left_pupil_posn': array([-0.11812609, -0.06523407]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98165894, -0.18701172, 0.03686523]), + 'right_gaze_origin': array([-3.15404534, -3.07230234, 0.05363465]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3330230712890625, + 'right_pupil_posn': array([-0.13927537, -0.12988925]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0021240883506834507, + 'throttle_input': 0.0, + 'timestamp': 675.3698387667537, + 'timestamp_carla': 675371, + 'timestamp_device': 118615, + 'timestamp_stream': 675.3698387667537, + 'transform': [array([-2.19644213e+00, -1.42813425e+01, 1.17786024e-02]), + array([-0.06350709, 0.53488123, 0.01174928])]} +{'AngularVelocity': array([-9.59686527e-04, -3.57001461e-02, -2.01954174e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.89012908935547, + 'FR_Wheel_Angle': 41.867286682128906, + 'Location': array([ -2.56193757, -20.10497284, 0.1722974 ]), + 'Rotation': array([-7.48315454e-02, 3.71096725e+01, -2.14538556e-02]), + 'Velocity': array([-0.09084822, -0.16933696, 0.00080011]), + 'brake_input': 0.0, + 'camera_location': array([-5.43542671, 15.02785301, 1.32744408]), + 'camera_rotation': array([-8.15373611, -0.2230285 , 1.93820167]), + 'current_gear_input': False, + 'focus_actor_dist': 1319.7159423828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.99610901, -1453.69714355, 16.72984314]), + 'frame': 20867, + 'frame_number': 20867, + 'framesequence': 79768, + 'gaze_dir': array([ 0.98435974, -0.16940308, 0.04592896]), + 'gaze_origin': array([-3.11979079, 0.11911164, 0.06442872]), + 'gaze_valid': True, + 'gaze_vergence': 185.59075927734375, + 'handbrake_input': False, + 'left_eye_openness': 0.9808542728424072, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98609924, -0.1572113 , 0.05360413]), + 'left_gaze_origin': array([-3.06928706, 3.31361556, 0.07135315]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2256927490234375, + 'left_pupil_posn': array([-0.11386508, -0.06584239]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98262024, -0.18159485, 0.03825378]), + 'right_gaze_origin': array([-3.17029428, -3.07539225, 0.05750427]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3044891357421875, + 'right_pupil_posn': array([-0.1315828 , -0.12908947]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0021240883506834507, + 'throttle_input': 0.0, + 'timestamp': 675.4024797677994, + 'timestamp_carla': 675403, + 'timestamp_device': 118648, + 'timestamp_stream': 675.4024797677994, + 'transform': [array([-2.19700599e+00, -1.42143965e+01, 1.15256496e-02]), + array([-0.06341831, 0.53487372, 0.01290894])]} +{'AngularVelocity': array([-9.01991792e-04, -1.25494944e-02, -3.34369016e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.861736297607422, + 'FR_Wheel_Angle': 41.79249572753906, + 'Location': array([ -2.59183383, -20.14842796, 0.1723164 ]), + 'Rotation': array([-7.55350590e-02, 3.64113960e+01, -2.05383282e-02]), + 'Velocity': array([-0.15458415, -0.26044556, 0.00172517]), + 'brake_input': 0.0, + 'camera_location': array([-5.41776085, 14.90995026, 1.33693779]), + 'camera_rotation': array([-8.16428185, -1.11616528, 2.02712631]), + 'current_gear_input': False, + 'focus_actor_dist': 1342.794921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -107.46955872, -1424.48474121, 16.71316528]), + 'frame': 20868, + 'frame_number': 20868, + 'framesequence': 79772, + 'gaze_dir': array([ 0.98642731, -0.15765381, 0.04354095]), + 'gaze_origin': array([-3.15429091, 0.11586685, 0.07475509]), + 'gaze_valid': True, + 'gaze_vergence': 196.31997680664062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98808289, -0.145401 , 0.05039978]), + 'left_gaze_origin': array([-3.07915974, 3.30943155, 0.07463226]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.279296875, + 'left_pupil_posn': array([-0.10709155, -0.06584835]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98477173, -0.16990662, 0.03668213]), + 'right_gaze_origin': array([-3.22942209, -3.07769799, 0.07487793]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.28167724609375, + 'right_pupil_posn': array([-0.1255281, -0.1293385]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0021240883506834507, + 'throttle_input': 0.0, + 'timestamp': 675.4358377680182, + 'timestamp_carla': 675437, + 'timestamp_device': 118682, + 'timestamp_stream': 675.4358377680182, + 'transform': [array([ -2.1980691 , -14.1464386 , 0.01644223]), + array([-0.13409026, 0.53525627, -0.01409755])]} +{'AngularVelocity': array([-0.05872846, -0.07888848, -4.45842838]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8577880859375, + 'FR_Wheel_Angle': 41.77069854736328, + 'Location': array([ -2.62424469, -20.19382858, 0.17237365]), + 'Rotation': array([-7.26049095e-02, 3.56723328e+01, -2.35290527e-02]), + 'Velocity': array([-0.14758468, -0.26808125, -0.00072674]), + 'brake_input': 0.0, + 'camera_location': array([-5.38139248, 14.75389862, 1.34298825]), + 'camera_rotation': array([-8.09944916, -2.17673635, 2.09806252]), + 'current_gear_input': False, + 'focus_actor_dist': 1298.892333984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -109.94047546, -1462.07885742, 16.72875214]), + 'frame': 20869, + 'frame_number': 20869, + 'framesequence': 79776, + 'gaze_dir': array([ 0.97929382, -0.19579315, 0.04828644]), + 'gaze_origin': array([-3.1269691 , 0.142379 , 0.06082993]), + 'gaze_valid': True, + 'gaze_vergence': 176.25062561035156, + 'handbrake_input': False, + 'left_eye_openness': 0.9809592366218567, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98219299, -0.17996216, 0.05368042]), + 'left_gaze_origin': array([-3.07945561, 3.34000874, 0.0667389 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1942291259765625, + 'left_pupil_posn': array([-0.14257997, -0.06946158]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97639465, -0.21162415, 0.04289246]), + 'right_gaze_origin': array([-3.17448306, -3.05525064, 0.05492096]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.322509765625, + 'right_pupil_posn': array([-0.15331846, -0.13172233]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0021240883506834507, + 'throttle_input': 0.0, + 'timestamp': 675.4693764671683, + 'timestamp_carla': 675470, + 'timestamp_device': 118715, + 'timestamp_stream': 675.4693764671683, + 'transform': [array([ -2.1986351 , -14.07902813, 0.02022253]), + array([-0.1712943 , 0.53544581, -0.03260062])]} +{'AngularVelocity': array([ 0.07909285, 0.02163117, -5.17060089]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79265022277832, + 'FR_Wheel_Angle': 41.68719482421875, + 'Location': array([ -2.67566609, -20.26291847, 0.17246982]), + 'Rotation': array([-7.53779635e-02, 3.45418396e+01, -2.02941895e-02]), + 'Velocity': array([-2.33112156e-01, -3.53011310e-01, 1.70841216e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.3468132 , 14.56266499, 1.35007513]), + 'camera_rotation': array([-7.98616409, -3.38886189, 2.21166348]), + 'current_gear_input': False, + 'focus_actor_dist': 1432.9044189453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -7.68151855, -1338.45617676, 16.58563232]), + 'frame': 20870, + 'frame_number': 20870, + 'framesequence': 79780, + 'gaze_dir': array([ 0.9577713 , -0.28179932, 0.05272675]), + 'gaze_origin': array([-3.14200521, 0.208239 , 0.05457611]), + 'gaze_valid': True, + 'gaze_vergence': 133.10931396484375, + 'handbrake_input': False, + 'left_eye_openness': 0.900230884552002, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96308899, -0.26226807, 0.0605011 ]), + 'left_gaze_origin': array([-3.09548807, 3.39803028, 0.06193085]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.29510498046875, + 'left_pupil_posn': array([-0.21405685, -0.07692826]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95245361, -0.30133057, 0.04495239]), + 'right_gaze_origin': array([-3.18852258, -2.98155236, 0.04722138]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2997894287109375, + 'right_pupil_posn': array([-0.2330541, -0.1378094]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0021240883506834507, + 'throttle_input': 0.0, + 'timestamp': 675.5020611658692, + 'timestamp_carla': 675503, + 'timestamp_device': 118748, + 'timestamp_stream': 675.5020611658692, + 'transform': [array([-2.19940972e+00, -1.40145788e+01, 1.30936047e-02]), + array([-0.24679521, 0.53521788, -0.00525925])]} +{'AngularVelocity': array([-0.08738205, -0.04056042, -5.09907913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.829143524169922, + 'FR_Wheel_Angle': 41.745574951171875, + 'Location': array([ -2.73493147, -20.33992195, 0.17250519]), + 'Rotation': array([-7.06514716e-02, 3.32781906e+01, -2.52685547e-02]), + 'Velocity': array([-2.29379117e-01, -3.49534452e-01, -1.04141236e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.30817032, 14.33277321, 1.3722806 ]), + 'camera_rotation': array([-7.79194069, -4.68768883, 2.20901227]), + 'current_gear_input': False, + 'focus_actor_dist': 1697.441650390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 229.41781616, -1124.07263184, 16.291008 ]), + 'frame': 20871, + 'frame_number': 20871, + 'framesequence': 79784, + 'gaze_dir': array([ 0.96051025, -0.27375031, 0.04692078]), + 'gaze_origin': array([-3.14111328, 0.20318833, 0.04682083]), + 'gaze_valid': True, + 'gaze_vergence': 181.1259307861328, + 'handbrake_input': False, + 'left_eye_openness': 0.8954948782920837, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96444702, -0.2590332 , 0.05224609]), + 'left_gaze_origin': array([-3.0946002 , 3.39385676, 0.05471802]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.250244140625, + 'left_pupil_posn': array([-0.206783 , -0.08233929]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95657349, -0.28846741, 0.04159546]), + 'right_gaze_origin': array([-3.18762708, -2.9874804 , 0.03892365]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.282440185546875, + 'right_pupil_posn': array([-0.22789651, -0.14622223]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0021240883506834507, + 'throttle_input': 0.0, + 'timestamp': 675.5361436679959, + 'timestamp_carla': 675537, + 'timestamp_device': 118782, + 'timestamp_stream': 675.5361436679959, + 'transform': [array([-2.19990468e+00, -1.39481068e+01, 9.76304989e-03]), + array([-0.27252454, 0.53519863, 0.0091859 ])]} +{'AngularVelocity': array([-0.08443028, -0.03094804, -4.19984055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.842998504638672, + 'FR_Wheel_Angle': 41.71420669555664, + 'Location': array([ -2.78663445, -20.40455055, 0.17256522]), + 'Rotation': array([-6.81447908e-02, 3.21971817e+01, -2.79235840e-02]), + 'Velocity': array([-1.98515043e-01, -2.89629430e-01, 5.67340830e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.23717213, 14.07868481, 1.41054523]), + 'camera_rotation': array([-7.48405647, -6.19755173, 2.15516949]), + 'current_gear_input': False, + 'focus_actor_dist': 1604.060791015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 220.8132019 , -1213.71594238, 16.32261658]), + 'frame': 20872, + 'frame_number': 20872, + 'framesequence': 79789, + 'gaze_dir': array([ 0.96633911, -0.25265503, 0.04456329]), + 'gaze_origin': array([-3.13686252, 0.18493195, 0.0427948 ]), + 'gaze_valid': True, + 'gaze_vergence': 156.17752075195312, + 'handbrake_input': False, + 'left_eye_openness': 0.9108557105064392, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97053528, -0.23548889, 0.05090332]), + 'left_gaze_origin': array([-3.09007287, 3.37765074, 0.05174714]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2685394287109375, + 'left_pupil_posn': array([-0.18896103, -0.08432567]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96214294, -0.26982117, 0.03822327]), + 'right_gaze_origin': array([-3.18365169, -3.00778675, 0.03384247]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0178680419921875, + 'right_pupil_posn': array([-0.20596969, -0.14865077]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0022339550778269768, + 'throttle_input': 0.0, + 'timestamp': 675.5714732669294, + 'timestamp_carla': 675572, + 'timestamp_device': 118823, + 'timestamp_stream': 675.5714732669294, + 'transform': [array([-2.20010972e+00, -1.38804150e+01, 1.51638023e-03]), + array([-0.19350608, 0.53545558, 0.05242951])]} +{'AngularVelocity': array([ 0.05421544, 0.01442943, -4.93208981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81936264038086, + 'FR_Wheel_Angle': 41.73472213745117, + 'Location': array([ -2.85372663, -20.48390007, 0.17267193]), + 'Rotation': array([-7.07675889e-02, 3.08505516e+01, -2.36816369e-02]), + 'Velocity': array([-0.23596695, -0.31473944, 0.00035565]), + 'brake_input': 0.0, + 'camera_location': array([-5.17791939, 13.81452656, 1.44888806]), + 'camera_rotation': array([-7.33735752, -7.67249727, 2.15894866]), + 'current_gear_input': False, + 'focus_actor_dist': 1618.313720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 232.81063843, -1196.04919434, 16.30596924]), + 'frame': 20873, + 'frame_number': 20873, + 'framesequence': 79793, + 'gaze_dir': array([ 0.97242737, -0.22813416, 0.04519653]), + 'gaze_origin': array([-3.13459921, 0.17467271, 0.0388916 ]), + 'gaze_valid': True, + 'gaze_vergence': 120.16094207763672, + 'handbrake_input': False, + 'left_eye_openness': 0.9164703488349915, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97422791, -0.21792603, 0.05805969]), + 'left_gaze_origin': array([-3.08751845, 3.3698349 , 0.04646454]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1668243408203125, + 'left_pupil_posn': array([-0.17259628, -0.08866942]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97062683, -0.23834229, 0.03233337]), + 'right_gaze_origin': array([-3.1816802 , -3.02048969, 0.03131867]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1771240234375, + 'right_pupil_posn': array([-0.19088501, -0.14760661]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.002636799355968833, + 'throttle_input': 0.0, + 'timestamp': 675.605069167912, + 'timestamp_carla': 675606, + 'timestamp_device': 118857, + 'timestamp_stream': 675.605069167912, + 'transform': [array([-2.20049334e+00, -1.38166046e+01, 5.78250852e-04]), + array([-0.14382328, 0.53535932, 0.05996723])]} +{'AngularVelocity': array([ 0.10588543, 0.01889466, -3.02003241]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.842226028442383, + 'FR_Wheel_Angle': 41.77085876464844, + 'Location': array([ -2.90006518, -20.53688622, 0.1727071 ]), + 'Rotation': array([-6.77213222e-02, 2.99334526e+01, -2.73132306e-02]), + 'Velocity': array([-0.1906985 , -0.24109165, 0.00039779]), + 'brake_input': 0.0, + 'camera_location': array([-5.13801384, 13.55947304, 1.44395745]), + 'camera_rotation': array([-7.22038364, -8.88434029, 2.15568161]), + 'current_gear_input': False, + 'focus_actor_dist': 1645.780029296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 243.07003784, -1163.5402832 , 16.28728485]), + 'frame': 20874, + 'frame_number': 20874, + 'framesequence': 79797, + 'gaze_dir': array([ 0.97583008, -0.21430969, 0.039711 ]), + 'gaze_origin': array([-3.13190031, 0.15978546, 0.03787308]), + 'gaze_valid': True, + 'gaze_vergence': 150.75221252441406, + 'handbrake_input': False, + 'left_eye_openness': 0.91522216796875, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97781372, -0.20332336, 0.0501709 ]), + 'left_gaze_origin': array([-3.08485413, 3.35578918, 0.04597473]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.24932861328125, + 'left_pupil_posn': array([-0.15827727, -0.08949876]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97384644, -0.22529602, 0.0292511 ]), + 'right_gaze_origin': array([-3.17894602, -3.0362184 , 0.02977142]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0984649658203125, + 'right_pupil_posn': array([-0.17505723, -0.15066123]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0039185769855976105, + 'throttle_input': 0.0, + 'timestamp': 675.6379553675652, + 'timestamp_carla': 675639, + 'timestamp_device': 118890, + 'timestamp_stream': 675.6379553675652, + 'transform': [array([-2.20090199e+00, -1.37547359e+01, 5.95987309e-03]), + array([-0.08554129, 0.53528529, 0.03930668])]} +{'AngularVelocity': array([-0.07677298, -0.0146869 , -3.55701709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.880290985107422, + 'FR_Wheel_Angle': 41.83433532714844, + 'Location': array([ -2.94502521, -20.58706284, 0.17277195]), + 'Rotation': array([-6.78374320e-02, 2.90430355e+01, -2.52380371e-02]), + 'Velocity': array([-0.17787163, -0.23208648, 0.0006066 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.12230015, 13.30322456, 1.42496037]), + 'camera_rotation': array([ -7.22187948, -10.10267258, 2.00436807]), + 'current_gear_input': False, + 'focus_actor_dist': 1554.3563232421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 221.98635864, -1247.04980469, 16.32991791]), + 'frame': 20875, + 'frame_number': 20875, + 'framesequence': 79801, + 'gaze_dir': array([ 0.97803497, -0.20414734, 0.0389328 ]), + 'gaze_origin': array([-3.12932277, 0.14647295, 0.0410286 ]), + 'gaze_valid': True, + 'gaze_vergence': 144.74578857421875, + 'handbrake_input': False, + 'left_eye_openness': 0.9745334982872009, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97993469, -0.19294739, 0.04986572]), + 'left_gaze_origin': array([-3.08412957, 3.34215569, 0.05094452]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.184356689453125, + 'left_pupil_posn': array([-0.14549726, -0.08620632]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97613525, -0.21534729, 0.02799988]), + 'right_gaze_origin': array([-3.17451668, -3.04920959, 0.03111267]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.098175048828125, + 'right_pupil_posn': array([-0.16248977, -0.14896011]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.005841243080794811, + 'throttle_input': 0.0, + 'timestamp': 675.6713894680142, + 'timestamp_carla': 675672, + 'timestamp_device': 118923, + 'timestamp_stream': 675.6713894680142, + 'transform': [array([-2.20150137e+00, -1.36927996e+01, 8.32469948e-03]), + array([-0.06463408, 0.53528118, 0.02902223])]} +{'AngularVelocity': array([ 0.01683943, 0.01118673, -2.67566872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.900461196899414, + 'FR_Wheel_Angle': 41.867862701416016, + 'Location': array([ -2.98174787, -20.62697411, 0.17281009]), + 'Rotation': array([-6.72910213e-02, 2.83338852e+01, -2.58789062e-02]), + 'Velocity': array([-0.13464811, -0.16204509, 0.00028573]), + 'brake_input': 0.0, + 'camera_location': array([-5.12754536, 13.07847404, 1.40417385]), + 'camera_rotation': array([ -7.2722044 , -11.1567421 , 1.77870345]), + 'current_gear_input': False, + 'focus_actor_dist': 1527.806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 228.40652466, -1271.84570312, 16.32976532]), + 'frame': 20876, + 'frame_number': 20876, + 'framesequence': 79805, + 'gaze_dir': array([ 0.98087311, -0.18930054, 0.04330444]), + 'gaze_origin': array([-3.13973379, 0.13572769, 0.0454155 ]), + 'gaze_valid': True, + 'gaze_vergence': 147.65000915527344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9818573 , -0.18183899, 0.05358887]), + 'left_gaze_origin': array([-3.08879256, 3.33189106, 0.05422516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.079315185546875, + 'left_pupil_posn': array([-0.13215888, -0.08268726]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97988892, -0.19676208, 0.03302002]), + 'right_gaze_origin': array([-3.19067526, -3.06043577, 0.03660584]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.236083984375, + 'right_pupil_posn': array([-0.15068251, -0.14718664]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00834986474364996, + 'throttle_input': 0.0, + 'timestamp': 675.7041188664734, + 'timestamp_carla': 675705, + 'timestamp_device': 118957, + 'timestamp_stream': 675.7041188664734, + 'transform': [array([-2.20205522e+00, -1.36330528e+01, 9.30585805e-03]), + array([-0.05773558, 0.53529561, 0.02420046])]} +{'AngularVelocity': array([-0.00365346, -0.01063141, -0.91215163]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.921083450317383, + 'FR_Wheel_Angle': 41.89698028564453, + 'Location': array([ -3.01055837, -20.65756035, 0.17284873]), + 'Rotation': array([-6.73798099e-02, 2.77842445e+01, -2.51159668e-02]), + 'Velocity': array([-9.74332765e-02, -1.20418519e-01, 6.84356710e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.11341381, 12.90488434, 1.39728141]), + 'camera_rotation': array([ -7.21825266, -12.03643322, 1.52973652]), + 'current_gear_input': False, + 'focus_actor_dist': 1570.9810791015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 248.94113159, -1227.18505859, 16.29761505]), + 'frame': 20877, + 'frame_number': 20877, + 'framesequence': 79808, + 'gaze_dir': array([ 0.98314667, -0.17869568, 0.03778076]), + 'gaze_origin': array([-3.1547401 , 0.12591019, 0.05311508]), + 'gaze_valid': True, + 'gaze_vergence': 323.3382263183594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9836731 , -0.17478943, 0.0426178 ]), + 'left_gaze_origin': array([-3.11997223, 3.3247118 , 0.06584778]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.08355712890625, + 'left_pupil_posn': array([-0.12272352, -0.08055556]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98262024, -0.18260193, 0.03294373]), + 'right_gaze_origin': array([-3.1895082 , -3.07289147, 0.04038239]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.095489501953125, + 'right_pupil_posn': array([-0.13977647, -0.14794147]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.010803552344441414, + 'throttle_input': 0.0, + 'timestamp': 675.7374391667545, + 'timestamp_carla': 675738, + 'timestamp_device': 118982, + 'timestamp_stream': 675.7374391667545, + 'transform': [array([-2.20258760e+00, -1.35730982e+01, 9.70005058e-03]), + array([-0.0559051 , 0.5353142 , 0.02191163])]} +{'AngularVelocity': array([ 0.02265574, 0.01074682, -1.49291539]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.930505752563477, + 'FR_Wheel_Angle': 41.91575241088867, + 'Location': array([ -3.03340721, -20.68130112, 0.17288558]), + 'Rotation': array([-6.82677403e-02, 2.73381042e+01, -2.34375000e-02]), + 'Velocity': array([-0.08495648, -0.09626283, 0.00012499]), + 'brake_input': 0.0, + 'camera_location': array([-5.12224579, 12.737216 , 1.39421296]), + 'camera_rotation': array([ -7.15868664, -12.66315269, 1.55501032]), + 'current_gear_input': False, + 'focus_actor_dist': 1458.7349853515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 214.50946045, -1328.65246582, 16.36122131]), + 'frame': 20878, + 'frame_number': 20878, + 'framesequence': 79812, + 'gaze_dir': array([ 0.99181366, -0.12099457, 0.03842926]), + 'gaze_origin': array([-3.22931075, 0.08866883, 0.08144455]), + 'gaze_valid': True, + 'gaze_vergence': 47.8389778137207, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99160767, -0.11851501, 0.0514679 ]), + 'left_gaze_origin': array([-3.26641083, 3.28663516, 0.11938477]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9870452880859375, + 'left_pupil_posn': array([-0.077573 , -0.0737747]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99201965, -0.12347412, 0.02539062]), + 'right_gaze_origin': array([-3.19221067, -3.10929728, 0.04350433]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1635589599609375, + 'right_pupil_posn': array([-0.09506041, -0.14312816]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.012945952825248241, + 'throttle_input': 0.0, + 'timestamp': 675.7713693678379, + 'timestamp_carla': 675772, + 'timestamp_device': 119015, + 'timestamp_stream': 675.7713693678379, + 'transform': [array([-2.20310688e+00, -1.35129108e+01, 9.82406549e-03]), + array([-0.05600072, 0.53529751, 0.02093507])]} +{'AngularVelocity': array([-0.05408528, 0.01288417, -1.06493306]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.912044525146484, + 'FR_Wheel_Angle': 41.84965133666992, + 'Location': array([ -3.05203295, -20.70046043, 0.17290673]), + 'Rotation': array([-6.90600425e-02, 2.69865570e+01, -2.16979980e-02]), + 'Velocity': array([-0.08630691, -0.09817728, 0.00022132]), + 'brake_input': 0.0, + 'camera_location': array([-5.11279964, 12.59634972, 1.39767122]), + 'camera_rotation': array([ -7.13817549, -13.11780643, 1.53816092]), + 'current_gear_input': False, + 'focus_actor_dist': 1443.8572998046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 144.85372925, -1312.71643066, 16.42473602]), + 'frame': 20879, + 'frame_number': 20879, + 'framesequence': 79817, + 'gaze_dir': array([ 0.99200439, -0.12198639, 0.03134155]), + 'gaze_origin': array([-3.13678241, 0.07513123, 0.05627823]), + 'gaze_valid': True, + 'gaze_vergence': 442.6246337890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99285889, -0.11489868, 0.03187561]), + 'left_gaze_origin': array([-3.09136367, 3.27047586, 0.06510315]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0811309814453125, + 'left_pupil_posn': array([-0.06669909, -0.07597983]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9911499, -0.1290741, 0.0308075]), + 'right_gaze_origin': array([-3.18220067, -3.12021327, 0.04745331]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0958709716796875, + 'right_pupil_posn': array([-0.08643371, -0.14530015]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01499679684638977, + 'throttle_input': 0.0, + 'timestamp': 675.8051682673395, + 'timestamp_carla': 675806, + 'timestamp_device': 119057, + 'timestamp_stream': 675.8051682673395, + 'transform': [array([-2.20361590e+00, -1.34538069e+01, 9.84920468e-03]), + array([-0.05670423, 0.53529757, 0.02056886])]} +{'AngularVelocity': array([-0.08951409, -0.02427288, -4.01430988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.89691162109375, + 'FR_Wheel_Angle': 41.821929931640625, + 'Location': array([ -3.08516836, -20.73333168, 0.17297062]), + 'Rotation': array([-7.26663768e-02, 2.63671303e+01, -1.63879413e-02]), + 'Velocity': array([-1.52547464e-01, -1.82850197e-01, 1.03797909e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.09306431, 12.48653412, 1.4027617 ]), + 'camera_rotation': array([ -7.05958748, -13.39093494, 1.43128371]), + 'current_gear_input': False, + 'focus_actor_dist': 1334.8367919921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 120.80841064, -1414.078125 , 16.48374939]), + 'frame': 20880, + 'frame_number': 20880, + 'framesequence': 79821, + 'gaze_dir': array([ 0.99220276, -0.11692047, 0.04220581]), + 'gaze_origin': array([-3.14502788, 0.07387619, 0.05569611]), + 'gaze_valid': True, + 'gaze_vergence': 321.6072692871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99258423, -0.11187744, 0.04718018]), + 'left_gaze_origin': array([-3.08838367, 3.26944137, 0.06363983]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1088104248046875, + 'left_pupil_posn': array([-0.06349212, -0.07416773]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99182129, -0.1219635 , 0.03723145]), + 'right_gaze_origin': array([-3.20167255, -3.12168884, 0.04775238]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.117218017578125, + 'right_pupil_posn': array([-0.08419538, -0.14346647]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.016772974282503128, + 'throttle_input': 0.0, + 'timestamp': 675.8399718664587, + 'timestamp_carla': 675841, + 'timestamp_device': 119090, + 'timestamp_stream': 675.8399718664587, + 'transform': [array([-2.20412993e+00, -1.33938208e+01, 9.83163808e-03]), + array([-0.057558 , 0.53529751, 0.02047731])]} +{'AngularVelocity': array([ 0.05397784, 0.03648655, -3.54628778]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.860824584960938, + 'FR_Wheel_Angle': 41.80087661743164, + 'Location': array([ -3.1286087 , -20.77519798, 0.17301601]), + 'Rotation': array([-7.33630583e-02, 2.55951328e+01, -1.61743145e-02]), + 'Velocity': array([-2.10712716e-01, -2.14127570e-01, -8.97312129e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.09578609, 12.4046154 , 1.41288841]), + 'camera_rotation': array([ -7.04229355, -13.5105772 , 1.33670962]), + 'current_gear_input': False, + 'focus_actor_dist': 1538.107421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 188.18338013, -1215.61047363, 16.35614014]), + 'frame': 20881, + 'frame_number': 20881, + 'framesequence': 79825, + 'gaze_dir': array([ 0.99230957, -0.11556244, 0.04364777]), + 'gaze_origin': array([-3.13737273, 0.07276382, 0.05381623]), + 'gaze_valid': True, + 'gaze_vergence': 284.5867004394531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99255371, -0.1114502 , 0.04907227]), + 'left_gaze_origin': array([-3.08487558, 3.26862669, 0.06234131]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.090423583984375, + 'left_pupil_posn': array([-0.06212598, -0.07400775]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99206543, -0.11967468, 0.03822327]), + 'right_gaze_origin': array([-3.18986988, -3.12309909, 0.04529114]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.120697021484375, + 'right_pupil_posn': array([-0.08317792, -0.14226222]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.018585773184895515, + 'throttle_input': 0.0, + 'timestamp': 675.872616365552, + 'timestamp_carla': 675873, + 'timestamp_device': 119123, + 'timestamp_stream': 675.872616365552, + 'transform': [array([-2.20460391e+00, -1.33383322e+01, 9.83243901e-03]), + array([-0.05832298, 0.53529739, 0.02047731])]} +{'AngularVelocity': array([-0.03699736, -0.00479472, -4.73671675]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79895782470703, + 'FR_Wheel_Angle': 41.68058776855469, + 'Location': array([ -3.18479872, -20.82866096, 0.17310272]), + 'Rotation': array([-7.57741109e-02, 2.45720387e+01, -1.19323721e-02]), + 'Velocity': array([-2.78245509e-01, -3.05527776e-01, 6.24847380e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.0972414 , 12.35259438, 1.39364111]), + 'camera_rotation': array([ -7.10334873, -13.54856777, 1.12298071]), + 'current_gear_input': False, + 'focus_actor_dist': 1568.4793701171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 199.48880005, -1181.28552246, 16.33589935]), + 'frame': 20882, + 'frame_number': 20882, + 'framesequence': 79829, + 'gaze_dir': array([ 0.99238586, -0.11356354, 0.04704285]), + 'gaze_origin': array([-3.1276803 , 0.07167816, 0.05153351]), + 'gaze_valid': True, + 'gaze_vergence': 320.6069030761719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99272156, -0.10858154, 0.05203247]), + 'left_gaze_origin': array([-3.06766844, 3.26725769, 0.05779114]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.085205078125, + 'left_pupil_posn': array([-0.06065512, -0.07250905]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99205017, -0.11854553, 0.04205322]), + 'right_gaze_origin': array([-3.18769264, -3.12390161, 0.04527588]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1221923828125, + 'right_pupil_posn': array([-0.08164179, -0.14083588]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02058168314397335, + 'throttle_input': 0.0, + 'timestamp': 675.9045006670058, + 'timestamp_carla': 675905, + 'timestamp_device': 119157, + 'timestamp_stream': 675.9045006670058, + 'transform': [array([-2.20043969e+00, -1.32853041e+01, 9.88374650e-03]), + array([-0.05685449, 0.51700616, 0.02053834])]} +{'AngularVelocity': array([ 0.10152457, 0.02382805, -6.03589773]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76848030090332, + 'FR_Wheel_Angle': 41.6163215637207, + 'Location': array([ -3.28061771, -20.91510201, 0.17320888]), + 'Rotation': array([-7.58014321e-02, 2.28822460e+01, -1.45263625e-02]), + 'Velocity': array([-3.74704033e-01, -3.72470319e-01, 2.02589028e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.09873772, 12.32369137, 1.3696419 ]), + 'camera_rotation': array([ -7.15259409, -13.49677658, 0.97271889]), + 'current_gear_input': False, + 'focus_actor_dist': 1607.198974609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 210.59231567, -1138.46337891, 16.31374359]), + 'frame': 20883, + 'frame_number': 20883, + 'framesequence': 79833, + 'gaze_dir': array([ 0.99240875, -0.11281586, 0.04799652]), + 'gaze_origin': array([-3.11900806, 0.07119752, 0.05010834]), + 'gaze_valid': True, + 'gaze_vergence': 248.2559356689453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99273682, -0.10723877, 0.05438232]), + 'left_gaze_origin': array([-3.05342889, 3.26652527, 0.05493775]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0712890625, + 'left_pupil_posn': array([-0.05997926, -0.07189322]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99208069, -0.11839294, 0.04161072]), + 'right_gaze_origin': array([-3.18458724, -3.12413025, 0.04527893]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.122772216796875, + 'right_pupil_posn': array([-0.08103544, -0.13942647]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.022394483909010887, + 'throttle_input': 0.0, + 'timestamp': 675.9375689662993, + 'timestamp_carla': 675938, + 'timestamp_device': 119190, + 'timestamp_stream': 675.9375689662993, + 'transform': [array([-2.19415879e+00, -1.32312489e+01, 9.90789384e-03]), + array([-0.05606219, 0.49053904, 0.02059938])]} +{'AngularVelocity': array([ 0.09488744, 0.02505101, -6.32643938]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76321792602539, + 'FR_Wheel_Angle': 41.62752914428711, + 'Location': array([ -3.36293197, -20.98574638, 0.17327285]), + 'Rotation': array([-7.31513202e-02, 2.15005760e+01, -1.89819317e-02]), + 'Velocity': array([-0.39479479, -0.37364954, 0.00057046]), + 'brake_input': 0.0, + 'camera_location': array([-5.08397007, 12.31587029, 1.3784107 ]), + 'camera_rotation': array([ -7.19964075, -13.36890793, 0.92821264]), + 'current_gear_input': False, + 'focus_actor_dist': 1602.4560546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 207.19415283, -1136.95288086, 16.31682587]), + 'frame': 20884, + 'frame_number': 20884, + 'framesequence': 79836, + 'gaze_dir': array([ 0.99163818, -0.11649323, 0.05418396]), + 'gaze_origin': array([-3.0998826 , 0.06870575, 0.04708023]), + 'gaze_valid': True, + 'gaze_vergence': 252.6141815185547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99253845, -0.10647583, 0.05926514]), + 'left_gaze_origin': array([-3.01517797, 3.26242852, 0.04886932]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.13055419921875, + 'left_pupil_posn': array([-0.05962557, -0.06645799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99073792, -0.12651062, 0.04910278]), + 'right_gaze_origin': array([-3.18458724, -3.12501669, 0.04529114]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1246185302734375, + 'right_pupil_posn': array([-0.0801506 , -0.13771844]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.024353770539164543, + 'throttle_input': 0.0, + 'timestamp': 675.9706172682345, + 'timestamp_carla': 675971, + 'timestamp_device': 119215, + 'timestamp_stream': 675.9706172682345, + 'transform': [array([-2.18723512e+00, -1.31780434e+01, 9.91964340e-03]), + array([-0.05606219, 0.46174276, 0.02062989])]} +{'AngularVelocity': array([-3.87932383e-03, 2.28784103e-02, -8.52891827e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.696807861328125, + 'FR_Wheel_Angle': 41.524635314941406, + 'Location': array([ -3.4687984 , -21.07192039, 0.17339157]), + 'Rotation': array([-7.83969089e-02, 1.97303314e+01, -1.42517071e-02]), + 'Velocity': array([-0.51599395, -0.46085092, 0.00112627]), + 'brake_input': 0.0, + 'camera_location': array([-5.08039093, 12.34349632, 1.36504614]), + 'camera_rotation': array([ -7.30861616, -13.15460587, 0.93160063]), + 'current_gear_input': False, + 'focus_actor_dist': 1728.3602294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 252.20733643, -1013.48632812, 16.23974609]), + 'frame': 20885, + 'frame_number': 20885, + 'framesequence': 79841, + 'gaze_dir': array([0.9957428 , 0.07142639, 0.05514526]), + 'gaze_origin': array([-3.07962823, -0.06897049, 0.05578537]), + 'gaze_valid': True, + 'gaze_vergence': 158.684814453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99412537, 0.08851624, 0.06214905]), + 'left_gaze_origin': array([-3.01851511, 3.12574959, 0.06356507]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1616973876953125, + 'left_pupil_posn': array([ 0.09491777, -0.05778348]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99736023, 0.05433655, 0.04814148]), + 'right_gaze_origin': array([-3.14074111, -3.26369023, 0.04800568]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0802459716796875, + 'right_pupil_posn': array([ 0.08166039, -0.12809658]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.026349682360887527, + 'throttle_input': 0.0, + 'timestamp': 676.0047012679279, + 'timestamp_carla': 676005, + 'timestamp_device': 119257, + 'timestamp_stream': 676.0047012679279, + 'transform': [array([-2.17952943e+00, -1.31240063e+01, 9.91445500e-03]), + array([-0.05639687, 0.42996839, 0.02066042])]} +{'AngularVelocity': array([ 0.04647649, -0.02101874, -6.61885977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.764020919799805, + 'FR_Wheel_Angle': 41.64791488647461, + 'Location': array([ -3.59402204, -21.16631126, 0.17348258]), + 'Rotation': array([-0.06888245, 17.70023537, -0.02737427]), + 'Velocity': array([-0.40039402, -0.33750397, 0.00047865]), + 'brake_input': 0.0, + 'camera_location': array([-5.06696892, 12.40497017, 1.34691 ]), + 'camera_rotation': array([ -7.48028612, -12.70038509, 0.95202851]), + 'current_gear_input': False, + 'focus_actor_dist': 1622.3125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -84.04580688, -1033.11730957, 16.58493042]), + 'frame': 20886, + 'frame_number': 20886, + 'framesequence': 79844, + 'gaze_dir': array([0.96116638, 0.26881409, 0.06112671]), + 'gaze_origin': array([-3.1473062 , -0.22501986, 0.07445984]), + 'gaze_valid': True, + 'gaze_vergence': 256.85845947265625, + 'handbrake_input': False, + 'left_eye_openness': 0.9671290516853333, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95794678, 0.28004456, 0.06240845]), + 'left_gaze_origin': array([-3.08481598, 2.95143294, 0.08109894]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2582550048828125, + 'left_pupil_posn': array([ 0.28488266, -0.05774701]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8974842429161072, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96438599, 0.25758362, 0.05984497]), + 'right_gaze_origin': array([-3.20979619, -3.40147281, 0.06782074]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.06158447265625, + 'right_pupil_posn': array([ 0.24618852, -0.13185954]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02781457081437111, + 'throttle_input': 0.0, + 'timestamp': 676.0366902686656, + 'timestamp_carla': 676037, + 'timestamp_device': 119282, + 'timestamp_stream': 676.0366902686656, + 'transform': [array([-2.17191124e+00, -1.30740366e+01, 9.92979016e-03]), + array([-0.05682717, 0.39878145, 0.02066041])]} +{'AngularVelocity': array([-3.48479417e-03, -1.79384986e-03, -4.57966280e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.832080841064453, + 'FR_Wheel_Angle': 41.75800704956055, + 'Location': array([ -3.67470169, -21.22367859, 0.17354645]), + 'Rotation': array([-0.0655903 , 16.41313553, -0.0302124 ]), + 'Velocity': array([-2.81288356e-01, -2.26550728e-01, 2.49414443e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.04677677, 12.51846027, 1.31553853]), + 'camera_rotation': array([ -7.54357481, -11.97937679, 0.99528122]), + 'current_gear_input': False, + 'focus_actor_dist': 1747.576171875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-428.04537964, -887.48583984, 15.03639984]), + 'frame': 20887, + 'frame_number': 20887, + 'framesequence': 79848, + 'gaze_dir': array([0.94720459, 0.31472015, 0.06011963]), + 'gaze_origin': array([-3.15691018, -0.25261766, 0.07785416]), + 'gaze_valid': True, + 'gaze_vergence': 180.11920166015625, + 'handbrake_input': False, + 'left_eye_openness': 0.9890754818916321, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9453125 , 0.32202148, 0.05169678]), + 'left_gaze_origin': array([-3.09559941, 2.92451501, 0.08425903]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.26812744140625, + 'left_pupil_posn': array([ 0.32149386, -0.05591595]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8970090746879578, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94909668, 0.30741882, 0.06854248]), + 'right_gaze_origin': array([-3.21822047, -3.42975044, 0.07144928]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.139862060546875, + 'right_pupil_posn': array([ 0.28131104, -0.13629603]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029004791751503944, + 'throttle_input': 0.0, + 'timestamp': 676.0699578672647, + 'timestamp_carla': 676071, + 'timestamp_device': 119315, + 'timestamp_stream': 676.0699578672647, + 'transform': [array([-2.16368318e+00, -1.30228243e+01, 9.93558858e-03]), + array([-0.05731212, 0.36528251, 0.02062989])]} +{'AngularVelocity': array([-0.01305276, 0.00334745, -3.29038072]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.880905151367188, + 'FR_Wheel_Angle': 41.835811614990234, + 'Location': array([ -3.72529721, -21.25831032, 0.17354584]), + 'Rotation': array([-0.06643724, 15.61441994, -0.02832031]), + 'Velocity': array([-0.20396045, -0.15970108, -0.00073524]), + 'brake_input': 0.0, + 'camera_location': array([-5.03609562, 12.65723991, 1.30289412]), + 'camera_rotation': array([ -7.64476395, -11.09928703, 0.88408959]), + 'current_gear_input': False, + 'focus_actor_dist': 1719.6456298828125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-529.2623291 , -919.65710449, 14.96369171]), + 'frame': 20888, + 'frame_number': 20888, + 'framesequence': 79852, + 'gaze_dir': array([0.95131683, 0.30254364, 0.05683136]), + 'gaze_origin': array([-3.15336037, -0.24819259, 0.08090897]), + 'gaze_valid': True, + 'gaze_vergence': 204.00433349609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94685364, 0.31660461, 0.05673218]), + 'left_gaze_origin': array([-3.09059763, 2.92992711, 0.08616029]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0797576904296875, + 'left_pupil_posn': array([ 0.31072474, -0.05728793]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9073594212532043, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95578003, 0.28848267, 0.05693054]), + 'right_gaze_origin': array([-3.21612239, -3.42631221, 0.07565766]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2869873046875, + 'right_pupil_posn': array([ 0.27673006, -0.13130331]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029517503455281258, + 'throttle_input': 0.0, + 'timestamp': 676.1023612655699, + 'timestamp_carla': 676103, + 'timestamp_device': 119348, + 'timestamp_stream': 676.1023612655699, + 'transform': [array([-2.15555286e+00, -1.29736481e+01, 9.95243061e-03]), + array([-0.05783121, 0.33232659, 0.02056886])]} +{'AngularVelocity': array([-0.01172835, 0.00420406, -2.2483232 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.91306495666504, + 'FR_Wheel_Angle': 41.88713836669922, + 'Location': array([ -3.7659843 , -21.285429 , 0.17366134]), + 'Rotation': array([-0.06814479, 14.97708988, -0.02563477]), + 'Velocity': array([-1.41106084e-01, -1.07697144e-01, 1.19297511e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.03167915, 12.81868744, 1.30405784]), + 'camera_rotation': array([ -7.78685236, -10.2611866 , 0.77975106]), + 'current_gear_input': False, + 'focus_actor_dist': 1584.915283203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -516.12670898, -1048.79260254, 17.02603912]), + 'frame': 20889, + 'frame_number': 20889, + 'framesequence': 79856, + 'gaze_dir': array([0.95368195, 0.29524994, 0.05540466]), + 'gaze_origin': array([-3.15044713, -0.24062349, 0.08448181]), + 'gaze_valid': True, + 'gaze_vergence': 192.46456909179688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94975281, 0.30883789, 0.05059814]), + 'left_gaze_origin': array([-3.0879519 , 2.94004679, 0.08744355]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22314453125, + 'left_pupil_posn': array([ 0.30127347, -0.05460668]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9034220576286316, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95761108, 0.28166199, 0.06021118]), + 'right_gaze_origin': array([-3.2129426 , -3.42129397, 0.08152009]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.286651611328125, + 'right_pupil_posn': array([ 0.27027845, -0.12849712]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029517503455281258, + 'throttle_input': 0.0, + 'timestamp': 676.1353019662201, + 'timestamp_carla': 676136, + 'timestamp_device': 119382, + 'timestamp_stream': 676.1353019662201, + 'transform': [array([-2.14733219e+00, -1.29243441e+01, 9.96013638e-03]), + array([-0.05840494, 0.29913515, 0.02050783])]} +{'AngularVelocity': array([-0.00908056, 0.00318614, -1.54048264]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.935260772705078, + 'FR_Wheel_Angle': 41.915775299072266, + 'Location': array([ -3.79400325, -21.30369759, 0.17368728]), + 'Rotation': array([-0.06957913, 14.54244328, -0.0234375 ]), + 'Velocity': array([-0.09715537, -0.07301349, 0.00011804]), + 'brake_input': 0.0, + 'camera_location': array([-5.02832413, 12.96221352, 1.30256772]), + 'camera_rotation': array([-7.78868294, -9.49763489, 0.72521782]), + 'current_gear_input': False, + 'focus_actor_dist': 1515.5438232421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -517.2510376 , -1114.06616211, 17.0438385 ]), + 'frame': 20890, + 'frame_number': 20890, + 'framesequence': 79860, + 'gaze_dir': array([0.95900726, 0.27820587, 0.05338287]), + 'gaze_origin': array([-3.14630079, -0.22916642, 0.0844986 ]), + 'gaze_valid': True, + 'gaze_vergence': 447.6900634765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95724487, 0.28451538, 0.05207825]), + 'left_gaze_origin': array([-3.08364725, 2.95408177, 0.08722382]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2160797119140625, + 'left_pupil_posn': array([ 0.28813028, -0.05541003]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9359778761863708, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96076965, 0.27189636, 0.0546875 ]), + 'right_gaze_origin': array([-3.20895386, -3.41241479, 0.08177339]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.123809814453125, + 'right_pupil_posn': array([ 0.25525439, -0.12605822]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029517503455281258, + 'throttle_input': 0.0, + 'timestamp': 676.1697107665241, + 'timestamp_carla': 676170, + 'timestamp_device': 119415, + 'timestamp_stream': 676.1697107665241, + 'transform': [array([-2.13883543e+00, -1.28735809e+01, 9.95676033e-03]), + array([-0.05896502, 0.26496691, 0.02044679])]} +{'AngularVelocity': array([-0.01565128, -0.00589098, 0.16938622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.957489013671875, + 'FR_Wheel_Angle': 41.96010971069336, + 'Location': array([ -3.81253266, -21.31558609, 0.17371085]), + 'Rotation': array([-0.06996845, 14.25812817, -0.02258301]), + 'Velocity': array([-5.19573912e-02, -4.23144661e-02, 6.49166104e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.00191402, 13.10813713, 1.29202366]), + 'camera_rotation': array([-7.71922684, -8.95709801, 0.64794445]), + 'current_gear_input': False, + 'focus_actor_dist': 1473.2325439453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -504.3576355 , -1150.21643066, 17.04003143]), + 'frame': 20891, + 'frame_number': 20891, + 'framesequence': 79864, + 'gaze_dir': array([0.95897675, 0.27771759, 0.0561142 ]), + 'gaze_origin': array([-3.14460182, -0.22303848, 0.08423005]), + 'gaze_valid': True, + 'gaze_vergence': 368.96820068359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9569397 , 0.28517151, 0.05406189]), + 'left_gaze_origin': array([-3.08210158, 2.96058059, 0.08738098]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.225616455078125, + 'left_pupil_posn': array([ 0.28304672, -0.05381465]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9435522556304932, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96101379, 0.27026367, 0.0581665 ]), + 'right_gaze_origin': array([-3.20710158, -3.4066577 , 0.0810791 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0751190185546875, + 'right_pupil_posn': array([ 0.25145948, -0.1254288 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029517503455281258, + 'throttle_input': 0.0, + 'timestamp': 676.2019801661372, + 'timestamp_carla': 676203, + 'timestamp_device': 119448, + 'timestamp_stream': 676.2019801661372, + 'transform': [array([-2.13093376e+00, -1.28266363e+01, 9.97594837e-03]), + array([-0.05938849, 0.23329182, 0.02038576])]} +{'AngularVelocity': array([-0.02207229, -0.00119578, 0.40637746]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.96756362915039, + 'FR_Wheel_Angle': 41.97434997558594, + 'Location': array([ -3.82194042, -21.32172394, 0.17373347]), + 'Rotation': array([-0.07107495, 14.11123848, -0.02114868]), + 'Velocity': array([-0.02980358, -0.02515172, 0.00076328]), + 'brake_input': 0.0, + 'camera_location': array([-4.99676037, 13.21174622, 1.29358041]), + 'camera_rotation': array([-7.74697065, -8.69073582, 0.748864 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1554.984619140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -527.0826416 , -1065.27416992, 17.04131317]), + 'frame': 20892, + 'frame_number': 20892, + 'framesequence': 79868, + 'gaze_dir': array([0.95845032, 0.2795105 , 0.0562439 ]), + 'gaze_origin': array([-3.14437199, -0.22032091, 0.08272706]), + 'gaze_valid': True, + 'gaze_vergence': 394.45086669921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95628357, 0.28689575, 0.05645752]), + 'left_gaze_origin': array([-3.08185744, 2.96429443, 0.08535156]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2532196044921875, + 'left_pupil_posn': array([ 0.28112185, -0.05595624]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9625005722045898, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96061707, 0.27212524, 0.05603027]), + 'right_gaze_origin': array([-3.20688629, -3.40493631, 0.08010254]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0707244873046875, + 'right_pupil_posn': array([ 0.25092006, -0.12519598]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029517503455281258, + 'throttle_input': 0.0, + 'timestamp': 676.2355084680021, + 'timestamp_carla': 676236, + 'timestamp_device': 119482, + 'timestamp_stream': 676.2355084680021, + 'transform': [array([-2.12281513e+00, -1.27785425e+01, 9.98302456e-03]), + array([-0.05975732, 0.20087221, 0.02032472])]} +{'AngularVelocity': array([-0.0182439 , -0.00379473, 0.639754 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.97137451171875, + 'FR_Wheel_Angle': 41.97969055175781, + 'Location': array([ -3.82837629, -21.32588387, 0.17372844]), + 'Rotation': array([-0.07214729, 14.00909615, -0.01980591]), + 'Velocity': array([-0.02198972, -0.01929017, 0.00020519]), + 'brake_input': 0.0, + 'camera_location': array([-4.98765373, 13.27197552, 1.29125977]), + 'camera_rotation': array([-7.86734629, -8.64972591, 0.97228718]), + 'current_gear_input': False, + 'focus_actor_dist': 1539.528076171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -534.33856201, -1077.13427734, 17.05170441]), + 'frame': 20893, + 'frame_number': 20893, + 'framesequence': 79872, + 'gaze_dir': array([0.95923615, 0.2762146 , 0.05883026]), + 'gaze_origin': array([-3.14415836, -0.21910097, 0.08324509]), + 'gaze_valid': True, + 'gaze_vergence': 324.44073486328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95680237, 0.28500366, 0.05722046]), + 'left_gaze_origin': array([-3.08171868, 2.96522236, 0.08605195]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2538604736328125, + 'left_pupil_posn': array([ 0.27885103, -0.05380964]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.963333785533905, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96166992, 0.26742554, 0.06044006]), + 'right_gaze_origin': array([-3.20659804, -3.40342402, 0.08043824]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0699462890625, + 'right_pupil_posn': array([ 0.24919021, -0.12458897]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029517503455281258, + 'throttle_input': 0.0, + 'timestamp': 676.2692047655582, + 'timestamp_carla': 676270, + 'timestamp_device': 119515, + 'timestamp_stream': 676.2692047655582, + 'transform': [array([-2.11475086e+00, -1.27308846e+01, 9.99111123e-03]), + array([-0.06005785, 0.16876686, 0.02026369])]} +{'AngularVelocity': array([-0.01502015, -0.00451506, 0.64924276]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.9730167388916, + 'FR_Wheel_Angle': 41.98272705078125, + 'Location': array([ -3.83346128, -21.32916641, 0.17375098]), + 'Rotation': array([-0.07263223, 13.92847061, -0.01916504]), + 'Velocity': array([-0.0185067 , -0.01651986, 0.00034524]), + 'brake_input': 0.0, + 'camera_location': array([-4.97520161, 13.30433273, 1.27741659]), + 'camera_rotation': array([-8.04218483, -8.80785751, 1.23617899]), + 'current_gear_input': False, + 'focus_actor_dist': 1528.1011962890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -528.20611572, -1082.98291016, 17.0470047 ]), + 'frame': 20894, + 'frame_number': 20894, + 'framesequence': 79876, + 'gaze_dir': array([0.98253632, 0.17178345, 0.06951141]), + 'gaze_origin': array([-3.06097817, -0.13474961, 0.06709748]), + 'gaze_valid': True, + 'gaze_vergence': 185.95639038085938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98010254, 0.18739319, 0.06529236]), + 'left_gaze_origin': array([-2.95135832, 3.06468368, 0.05417023]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2351531982421875, + 'left_pupil_posn': array([ 0.1707294 , -0.04431808]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9631414413452148, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98497009, 0.15617371, 0.07373047]), + 'right_gaze_origin': array([-3.17059803, -3.33418298, 0.08002473]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17938232421875, + 'right_pupil_posn': array([ 0.1653595 , -0.11286175]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029517503455281258, + 'throttle_input': 0.0, + 'timestamp': 676.3036812655628, + 'timestamp_carla': 676304, + 'timestamp_device': 119548, + 'timestamp_stream': 676.3036812655628, + 'transform': [array([-2.10660982e+00, -1.26828222e+01, 1.00021167e-02]), + array([-0.06033789, 0.13648733, 0.02017212])]} +{'AngularVelocity': array([ 0.02928624, -0.00638695, -3.28894019]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.87198829650879, + 'FR_Wheel_Angle': 41.81157302856445, + 'Location': array([ -3.86420918, -21.34810066, 0.17383693]), + 'Rotation': array([-8.22696239e-02, 1.34547176e+01, -7.20214797e-03]), + 'Velocity': array([-0.21902999, -0.15822791, 0.00044 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.96587467, 13.28992271, 1.27460217]), + 'camera_rotation': array([-7.98005772, -9.09358788, 1.43486166]), + 'current_gear_input': False, + 'focus_actor_dist': 1666.8560791015625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-363.89974976, -925.79919434, 14.93490601]), + 'frame': 20895, + 'frame_number': 20895, + 'framesequence': 79880, + 'gaze_dir': array([0.99811554, 0.01077271, 0.05841827]), + 'gaze_origin': array([-3.14697957, -0.00609894, 0.08759537]), + 'gaze_valid': True, + 'gaze_vergence': 184.55551147460938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99754333, 0.02412415, 0.0657196 ]), + 'left_gaze_origin': array([-3.13910699, 3.190413 , 0.10581819]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09075927734375, + 'left_pupil_posn': array([ 0.03150189, -0.05008173]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99868774, -0.00257874, 0.05111694]), + 'right_gaze_origin': array([-3.15485263, -3.20261073, 0.06937256]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2033233642578125, + 'right_pupil_posn': array([ 0.01804006, -0.11414373]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029590748250484467, + 'throttle_input': 0.0, + 'timestamp': 676.3358842656016, + 'timestamp_carla': 676337, + 'timestamp_device': 119582, + 'timestamp_stream': 676.3358842656016, + 'transform': [array([-2.09902453e+00, -1.26385584e+01, 1.00272363e-02]), + array([-0.06054279, 0.10648229, 0.02011109])]} +{'AngularVelocity': array([ 0.03895268, -0.02006172, -2.70993161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.894071578979492, + 'FR_Wheel_Angle': 41.856258392333984, + 'Location': array([ -3.91046476, -21.37639046, 0.17383324]), + 'Rotation': array([-0.07433978, 12.74868393, -0.01779175]), + 'Velocity': array([-1.74474061e-01, -1.23304620e-01, 1.48162842e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.95782948, 13.21717644, 1.28225183]), + 'camera_rotation': array([-7.7988801 , -9.68867207, 1.59419942]), + 'current_gear_input': False, + 'focus_actor_dist': 1465.1654052734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.70936584, -1137.77502441, 16.64260864]), + 'frame': 20896, + 'frame_number': 20896, + 'framesequence': 79884, + 'gaze_dir': array([ 0.98645782, -0.15842438, 0.03747559]), + 'gaze_origin': array([-3.14221191, 0.11770554, 0.06557846]), + 'gaze_valid': True, + 'gaze_vergence': 158.0001220703125, + 'handbrake_input': False, + 'left_eye_openness': 0.9684930443763733, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98965454, -0.139328 , 0.03413391]), + 'left_gaze_origin': array([-3.08340621, 3.30311441, 0.06676789]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.016815185546875, + 'left_pupil_posn': array([-0.10561842, -0.07047117]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98326111, -0.17752075, 0.04081726]), + 'right_gaze_origin': array([-3.20101786, -3.06770325, 0.06438904]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3070831298828125, + 'right_pupil_posn': array([-0.13055044, -0.13659573]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029627369716763496, + 'throttle_input': 0.0, + 'timestamp': 676.3683406673372, + 'timestamp_carla': 676369, + 'timestamp_device': 119615, + 'timestamp_stream': 676.3683406673372, + 'transform': [array([-2.09145164e+00, -1.25945559e+01, 1.00450320e-02]), + array([-0.06075453, 0.07663093, 0.02005006])]} +{'AngularVelocity': array([-0.01072655, -0.01358497, -0.54755694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.9390926361084, + 'FR_Wheel_Angle': 41.93239974975586, + 'Location': array([ -3.93762851, -21.39269638, 0.17383899]), + 'Rotation': array([-0.06961329, 12.34038067, -0.02325439]), + 'Velocity': array([-9.23002064e-02, -6.85287789e-02, -9.62257400e-06]), + 'brake_input': 0.0, + 'camera_location': array([-4.94459629, 13.10697365, 1.29282737]), + 'camera_rotation': array([ -7.73376799, -10.48873329, 1.62148571]), + 'current_gear_input': False, + 'focus_actor_dist': 1284.4580078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 85.14916992, -1366.8494873 , 16.50252533]), + 'frame': 20897, + 'frame_number': 20897, + 'framesequence': 79888, + 'gaze_dir': array([ 0.98252106, -0.18173218, 0.03723907]), + 'gaze_origin': array([-3.14439344, 0.13923569, 0.0576561 ]), + 'gaze_valid': True, + 'gaze_vergence': 191.21849060058594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98472595, -0.16847229, 0.04364014]), + 'left_gaze_origin': array([-3.08701801, 3.32598567, 0.05987092]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.048828125, + 'left_pupil_posn': array([-0.1274752 , -0.07922506]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98031616, -0.19499207, 0.03083801]), + 'right_gaze_origin': array([-3.20176864, -3.04751444, 0.05544129]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.287750244140625, + 'right_pupil_posn': array([-0.1546253 , -0.13973188]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029682302847504616, + 'throttle_input': 0.0, + 'timestamp': 676.4026179686189, + 'timestamp_carla': 676403, + 'timestamp_device': 119648, + 'timestamp_stream': 676.4026179686189, + 'transform': [array([-2.08356929e+00, -1.25487375e+01, 1.00473594e-02]), + array([-0.06094578, 0.04565943, 0.01998902])]} +{'AngularVelocity': array([-0.11509629, 0.01010198, -1.06278968]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.963943481445312, + 'FR_Wheel_Angle': 41.97111892700195, + 'Location': array([ -3.95544791, -21.40343285, 0.17386691]), + 'Rotation': array([-0.07082906, 12.05666733, -0.02142334]), + 'Velocity': array([-0.07450269, -0.05873444, 0.00032913]), + 'brake_input': 0.0, + 'camera_location': array([-4.93052864, 12.9964838 , 1.30574584]), + 'camera_rotation': array([ -7.61734056, -11.21891308, 1.63149834]), + 'current_gear_input': False, + 'focus_actor_dist': 1315.0068359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 142.12902832, -1350.21008301, 16.44031525]), + 'frame': 20898, + 'frame_number': 20898, + 'framesequence': 79892, + 'gaze_dir': array([ 0.98361206, -0.17621613, 0.03567505]), + 'gaze_origin': array([-3.14497995, 0.13172837, 0.05350876]), + 'gaze_valid': True, + 'gaze_vergence': 225.52464294433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98539734, -0.16513062, 0.04125977]), + 'left_gaze_origin': array([-3.08701038, 3.32174087, 0.05588837]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.08447265625, + 'left_pupil_posn': array([-0.12189484, -0.08211946]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98182678, -0.18730164, 0.03009033]), + 'right_gaze_origin': array([-3.20294976, -3.05828404, 0.05112915]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2953033447265625, + 'right_pupil_posn': array([-0.14605379, -0.14387584]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029938658699393272, + 'throttle_input': 0.0, + 'timestamp': 676.4352524653077, + 'timestamp_carla': 676436, + 'timestamp_device': 119682, + 'timestamp_stream': 676.4352524653077, + 'transform': [array([-2.07605076e+00, -1.25057335e+01, 1.00673866e-02]), + array([-0.06106872, 0.01620084, 0.01992799])]} +{'AngularVelocity': array([-0.12233225, 0.01029428, -0.59855068]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.935697555541992, + 'FR_Wheel_Angle': 41.881996154785156, + 'Location': array([ -3.96588063, -21.409729 , 0.17387946]), + 'Rotation': array([-0.07158721, 11.89952183, -0.02047729]), + 'Velocity': array([-4.68100905e-02, -3.96481492e-02, 8.75663754e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.92918301, 12.88646793, 1.3076874 ]), + 'camera_rotation': array([ -7.50125504, -11.89720058, 1.57427883]), + 'current_gear_input': False, + 'focus_actor_dist': 1317.5849609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 152.6192627 , -1346.7557373 , 16.42874908]), + 'frame': 20899, + 'frame_number': 20899, + 'framesequence': 79896, + 'gaze_dir': array([ 0.98497772, -0.16766357, 0.03879547]), + 'gaze_origin': array([-3.14702988, 0.12871552, 0.05229798]), + 'gaze_valid': True, + 'gaze_vergence': 215.4337158203125, + 'handbrake_input': False, + 'left_eye_openness': 0.9700098037719727, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98686218, -0.15534973, 0.04406738]), + 'left_gaze_origin': array([-3.08909917, 3.32003951, 0.05529328]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0518951416015625, + 'left_pupil_posn': array([-0.11823976, -0.08156812]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98309326, -0.17997742, 0.03352356]), + 'right_gaze_origin': array([-3.20496082, -3.06260848, 0.04930267]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.335235595703125, + 'right_pupil_posn': array([-0.13972062, -0.14439046]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03092745877802372, + 'throttle_input': 0.0, + 'timestamp': 676.4685710668564, + 'timestamp_carla': 676469, + 'timestamp_device': 119715, + 'timestamp_stream': 676.4685710668564, + 'transform': [array([-2.06826496e+00, -1.24624596e+01, 1.00819971e-02]), + array([-0.06109604, -0.01421739, 0.01986696])]} +{'AngularVelocity': array([ 0.03805045, -0.0195438 , -2.6682353 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.899290084838867, + 'FR_Wheel_Angle': 41.86476135253906, + 'Location': array([ -4.00306797, -21.43096924, 0.17395321]), + 'Rotation': array([-0.07775487, 11.34222984, -0.01330566]), + 'Velocity': array([-0.17376667, -0.11678553, 0.00035963]), + 'brake_input': 0.0, + 'camera_location': array([-4.94527531, 12.78948402, 1.30537271]), + 'camera_rotation': array([ -7.53774834, -12.47233582, 1.44702291]), + 'current_gear_input': False, + 'focus_actor_dist': 1386.6983642578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 182.5133667 , -1279.5255127 , 16.37815094]), + 'frame': 20900, + 'frame_number': 20900, + 'framesequence': 79900, + 'gaze_dir': array([ 0.98647308, -0.16035461, 0.03149414]), + 'gaze_origin': array([-3.15865946, 0.12199632, 0.05750504]), + 'gaze_valid': True, + 'gaze_vergence': 261.2156066894531, + 'handbrake_input': False, + 'left_eye_openness': 0.9804239273071289, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98835754, -0.14851379, 0.03269958]), + 'left_gaze_origin': array([-3.09309554, 3.31545424, 0.05850678]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1915435791015625, + 'left_pupil_posn': array([-0.11230928, -0.0814805 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98458862, -0.17219543, 0.0302887 ]), + 'right_gaze_origin': array([-3.22422338, -3.07146168, 0.0565033 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3018035888671875, + 'right_pupil_posn': array([-0.13117051, -0.14701557]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.032831814140081406, + 'throttle_input': 0.0, + 'timestamp': 676.5022215656936, + 'timestamp_carla': 676503, + 'timestamp_device': 119748, + 'timestamp_stream': 676.5022215656936, + 'transform': [array([-2.06006646e+00, -1.24194164e+01, 1.00974841e-02]), + array([-0.06100725, -0.04615872, 0.01980592])]} +{'AngularVelocity': array([ 0.01540906, -0.00853672, -1.77205765]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.96204948425293, + 'FR_Wheel_Angle': 37.957027435302734, + 'Location': array([ -4.03972292, -21.45131493, 0.17395012]), + 'Rotation': array([-0.07254343, 10.80824661, -0.0201416 ]), + 'Velocity': array([-0.12664621, -0.07855193, -0.00022602]), + 'brake_input': 0.0, + 'camera_location': array([-4.96696758, 12.68301582, 1.30805254]), + 'camera_rotation': array([ -7.47334003, -13.08174992, 1.45236754]), + 'current_gear_input': False, + 'focus_actor_dist': 1260.1484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 140.22064209, -1395.01245117, 16.45788574]), + 'frame': 20901, + 'frame_number': 20901, + 'framesequence': 79904, + 'gaze_dir': array([ 0.98756409, -0.1523819 , 0.036026 ]), + 'gaze_origin': array([-3.16241693, 0.11469194, 0.05611954]), + 'gaze_valid': True, + 'gaze_vergence': 200.85562133789062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98904419, -0.14108276, 0.04312134]), + 'left_gaze_origin': array([-3.11706877, 3.30727243, 0.0646347 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1354217529296875, + 'left_pupil_posn': array([-0.10405016, -0.08226764]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98608398, -0.16368103, 0.02893066]), + 'right_gaze_origin': array([-3.20776558, -3.07788873, 0.04760437]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2549896240234375, + 'right_pupil_posn': array([-0.12424642, -0.14644206]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03563341125845909, + 'throttle_input': 0.0, + 'timestamp': 676.5355359651148, + 'timestamp_carla': 676536, + 'timestamp_device': 119782, + 'timestamp_stream': 676.5355359651148, + 'transform': [array([-2.05139089e+00, -1.23774652e+01, 1.01196477e-02]), + array([-0.06078868, -0.07990663, 0.01974489])]} +{'AngularVelocity': array([-1.88182504e-03, -9.25184810e-04, -1.07889938e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.15777015686035, + 'FR_Wheel_Angle': 33.32027816772461, + 'Location': array([ -4.06485415, -21.4639473 , 0.1739756 ]), + 'Rotation': array([-0.07149842, 10.48756313, -0.02127075]), + 'Velocity': array([-8.97083580e-02, -4.96164225e-02, -6.29043570e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.96944332, 12.59834099, 1.31635749]), + 'camera_rotation': array([ -7.41279697, -13.62701893, 1.31754112]), + 'current_gear_input': False, + 'focus_actor_dist': 1334.81689453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 171.69580078, -1322.4251709 , 16.4013443 ]), + 'frame': 20902, + 'frame_number': 20902, + 'framesequence': 79908, + 'gaze_dir': array([ 0.9896698 , -0.14086914, 0.0230484 ]), + 'gaze_origin': array([-3.259974 , 0.11232301, 0.08657075]), + 'gaze_valid': True, + 'gaze_vergence': 92.62654876708984, + 'handbrake_input': False, + 'left_eye_openness': 0.9806186556816101, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99002075, -0.13650513, 0.03468323]), + 'left_gaze_origin': array([-3.29089689, 3.30771351, 0.11946412]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1036834716796875, + 'left_pupil_posn': array([-0.10005629, -0.08365047]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98931885, -0.14523315, 0.01141357]), + 'right_gaze_origin': array([-3.22905135, -3.08306742, 0.05367737]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.27783203125, + 'right_pupil_posn': array([-0.11899489, -0.14916551]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0394604317843914, + 'throttle_input': 0.0, + 'timestamp': 676.5688324682415, + 'timestamp_carla': 676570, + 'timestamp_device': 119815, + 'timestamp_stream': 676.5688324682415, + 'transform': [array([-2.04193759e+00, -1.23362188e+01, 1.01447292e-02]), + array([-0.060454 , -0.11663589, 0.01968386])]} +{'AngularVelocity': array([-0.02047992, 0.00403306, -0.0001795 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.121288299560547, + 'FR_Wheel_Angle': 28.528514862060547, + 'Location': array([ -4.07662344, -21.46932602, 0.17396976]), + 'Rotation': array([-0.06856827, 10.35692883, -0.02340698]), + 'Velocity': array([-3.08855419e-06, 3.63552499e-05, -8.94686964e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.96980762, 12.53039265, 1.30500305]), + 'camera_rotation': array([ -7.4226737 , -14.03792953, 1.30514455]), + 'current_gear_input': False, + 'focus_actor_dist': 1168.400634765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 108.45626831, -1472.95483398, 16.5165863 ]), + 'frame': 20903, + 'frame_number': 20903, + 'framesequence': 79912, + 'gaze_dir': array([ 0.98995209, -0.1398468 , 0.01928711]), + 'gaze_origin': array([-3.24684453, 0.10836106, 0.08644104]), + 'gaze_valid': True, + 'gaze_vergence': 217.08157348632812, + 'handbrake_input': False, + 'left_eye_openness': 0.9826353192329407, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99031067, -0.13642883, 0.02555847]), + 'left_gaze_origin': array([-3.28227544, 3.30434299, 0.11666413]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1384124755859375, + 'left_pupil_posn': array([-0.09689665, -0.08342004]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98959351, -0.14326477, 0.01301575]), + 'right_gaze_origin': array([-3.21141362, -3.08762074, 0.05621796]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2620849609375, + 'right_pupil_posn': array([-0.11590272, -0.14731038]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.043891724199056625, + 'throttle_input': 0.0, + 'timestamp': 676.6018512658775, + 'timestamp_carla': 676603, + 'timestamp_device': 119848, + 'timestamp_stream': 676.6018512658775, + 'transform': [array([-2.03164673e+00, -1.22959995e+01, 1.01728626e-02]), + array([-0.06005785, -0.15654463, 0.01962282])]} +{'AngularVelocity': array([-1.05263414e-02, 7.46884570e-03, 4.84633565e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.055545806884766, + 'FR_Wheel_Angle': 23.925655364990234, + 'Location': array([ -4.07664251, -21.46935654, 0.17396797]), + 'Rotation': array([-0.07199019, 10.35715199, -0.01959228]), + 'Velocity': array([ 9.40985046e-06, 2.62362823e-06, -2.99352629e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.99253178, 12.4703331 , 1.27866113]), + 'camera_rotation': array([ -7.39086533, -14.3478651 , 1.42826259]), + 'current_gear_input': False, + 'focus_actor_dist': 1124.2877197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 99.30233765, -1512.81103516, 16.53957367]), + 'frame': 20904, + 'frame_number': 20904, + 'framesequence': 79916, + 'gaze_dir': array([ 0.99002075, -0.13921356, 0.02030182]), + 'gaze_origin': array([-3.19169712, 0.10216675, 0.06829758]), + 'gaze_valid': True, + 'gaze_vergence': 428.7464294433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99102783, -0.13227844, 0.01872253]), + 'left_gaze_origin': array([-3.18533468, 3.29761362, 0.08572388]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1721649169921875, + 'left_pupil_posn': array([-0.09218335, -0.0829736 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98901367, -0.14614868, 0.0218811 ]), + 'right_gaze_origin': array([-3.19805932, -3.09328008, 0.05087128]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2696685791015625, + 'right_pupil_posn': array([-0.11072659, -0.15078294]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04845118895173073, + 'throttle_input': 0.0, + 'timestamp': 676.6353696659207, + 'timestamp_carla': 676636, + 'timestamp_device': 119882, + 'timestamp_stream': 676.6353696659207, + 'transform': [array([-2.02027607e+00, -1.22558556e+01, 1.01897428e-02]), + array([-0.05963438, -0.20057882, 0.0195923 ])]} +{'AngularVelocity': array([-2.51928717e-03, 1.59027311e-03, 8.76500167e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.053150177001953, + 'FR_Wheel_Angle': 19.65733528137207, + 'Location': array([ -4.07664919, -21.46936798, 0.174015 ]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([4.73341879e-06, 9.21508772e-08, 2.12931758e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.98956013, 12.43815041, 1.28138518]), + 'camera_rotation': array([ -7.40343952, -14.5872736 , 1.30728948]), + 'current_gear_input': False, + 'focus_actor_dist': 1143.603515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 112.46105957, -1493.00927734, 16.51966095]), + 'frame': 20905, + 'frame_number': 20905, + 'framesequence': 79920, + 'gaze_dir': array([ 0.98991394, -0.14011383, 0.01898193]), + 'gaze_origin': array([-3.17566395, 0.10007324, 0.06490631]), + 'gaze_valid': True, + 'gaze_vergence': 423.0980224609375, + 'handbrake_input': False, + 'left_eye_openness': 0.982917845249176, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9909668 , -0.13272095, 0.01876831]), + 'left_gaze_origin': array([-3.16213417, 3.29515076, 0.08118134]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.173492431640625, + 'left_pupil_posn': array([-0.09063721, -0.08276784]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98886108, -0.14750671, 0.01919556]), + 'right_gaze_origin': array([-3.18919373, -3.09500432, 0.04863129]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.257720947265625, + 'right_pupil_posn': array([-0.10975939, -0.15064466]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05381634086370468, + 'throttle_input': 0.0, + 'timestamp': 676.6683583669364, + 'timestamp_carla': 676669, + 'timestamp_device': 119915, + 'timestamp_stream': 676.6683583669364, + 'transform': [array([-2.00800896e+00, -1.22170420e+01, 1.02112573e-02]), + array([-0.05919725, -0.24804182, 0.01956178])]} +{'AngularVelocity': array([-7.28968414e-04, 3.59340454e-04, -7.44571435e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.770185470581055, + 'FR_Wheel_Angle': 15.24930477142334, + 'Location': array([ -4.07665014, -21.46936989, 0.17400821]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 3.27671864e-06, -3.92050111e-07, 2.79972573e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.95416069, 12.42276001, 1.28587258]), + 'camera_rotation': array([ -7.38977242, -14.70296192, 1.20792472]), + 'current_gear_input': False, + 'focus_actor_dist': 1124.3448486328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 111.35507202, -1509.34472656, 16.52645874]), + 'frame': 20906, + 'frame_number': 20906, + 'framesequence': 79924, + 'gaze_dir': array([ 0.9899826 , -0.13928986, 0.02133179]), + 'gaze_origin': array([-3.18267989, 0.09964295, 0.06525269]), + 'gaze_valid': True, + 'gaze_vergence': 387.274658203125, + 'handbrake_input': False, + 'left_eye_openness': 0.983704686164856, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99099731, -0.13175964, 0.02345276]), + 'left_gaze_origin': array([-3.1673007 , 3.2942903 , 0.08187409]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.171966552734375, + 'left_pupil_posn': array([-0.08988845, -0.08321369]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9889679 , -0.14682007, 0.01921082]), + 'right_gaze_origin': array([-3.19805932, -3.09500432, 0.04863129]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.24102783203125, + 'right_pupil_posn': array([-0.10938501, -0.15064466]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.059016697108745575, + 'throttle_input': 0.0, + 'timestamp': 676.702152967453, + 'timestamp_carla': 676703, + 'timestamp_device': 119948, + 'timestamp_stream': 676.702152967453, + 'transform': [array([-1.99441648e+00, -1.21779709e+01, 1.02248760e-02]), + array([-0.05880792, -0.30056265, 0.01953126])]} +{'AngularVelocity': array([-1.47279672e-04, 1.22801561e-04, -9.80385721e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.388550758361816, + 'FR_Wheel_Angle': 10.998930931091309, + 'Location': array([ -4.07665062, -21.46936989, 0.174005 ]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 2.72234888e-06, -5.04350169e-07, -1.38817952e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.93468285, 12.39977741, 1.2820394 ]), + 'camera_rotation': array([ -7.36458969, -14.70975208, 1.21766376]), + 'current_gear_input': False, + 'focus_actor_dist': 1149.4808349609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 123.38928223, -1482.91955566, 16.50531769]), + 'frame': 20907, + 'frame_number': 20907, + 'framesequence': 79928, + 'gaze_dir': array([ 0.98994446, -0.13899231, 0.0242157 ]), + 'gaze_origin': array([-3.1895504 , 0.09923629, 0.06567078]), + 'gaze_valid': True, + 'gaze_vergence': 266.9512634277344, + 'handbrake_input': False, + 'left_eye_openness': 0.9787276983261108, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99076843, -0.13206482, 0.03010559]), + 'left_gaze_origin': array([-3.17302275, 3.29385996, 0.08356934]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.20245361328125, + 'left_pupil_posn': array([-0.0893085 , -0.08354056]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98912048, -0.1459198 , 0.01832581]), + 'right_gaze_origin': array([-3.20607758, -3.09538746, 0.04777222]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.23138427734375, + 'right_pupil_posn': array([-0.10918379, -0.15042591]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06427198648452759, + 'throttle_input': 0.0, + 'timestamp': 676.7347167655826, + 'timestamp_carla': 676735, + 'timestamp_device': 119981, + 'timestamp_stream': 676.7347167655826, + 'transform': [array([-1.98027742e+00, -1.21409922e+01, 1.02473833e-02]), + array([-0.05846642, -0.35515648, 0.01950075])]} +{'AngularVelocity': array([-1.15844661e-04, -1.90549690e-05, -1.11575964e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.669863700866699, + 'FR_Wheel_Angle': 6.713949203491211, + 'Location': array([ -4.07665062, -21.46936989, 0.17404564]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 2.91328411e-06, -3.04272390e-07, 1.11973961e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.92126751, 12.38446426, 1.23986804]), + 'camera_rotation': array([ -7.56697512, -14.73756981, 1.18718135]), + 'current_gear_input': False, + 'focus_actor_dist': 1187.5985107421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 139.19519043, -1443.89685059, 16.4760437 ]), + 'frame': 20908, + 'frame_number': 20908, + 'framesequence': 79932, + 'gaze_dir': array([ 0.99015045, -0.13726807, 0.02592468]), + 'gaze_origin': array([-3.19533873, 0.09887239, 0.06681519]), + 'gaze_valid': True, + 'gaze_vergence': 299.7972412109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99098206, -0.13034058, 0.03097534]), + 'left_gaze_origin': array([-3.18208027, 3.293648 , 0.085141 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1999664306640625, + 'left_pupil_posn': array([-0.08867735, -0.0832504 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98931885, -0.14419556, 0.02087402]), + 'right_gaze_origin': array([-3.20859694, -3.09590316, 0.04848938]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2178802490234375, + 'right_pupil_posn': array([-0.10822386, -0.15006304]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06993011385202408, + 'throttle_input': 0.0, + 'timestamp': 676.7677125670016, + 'timestamp_carla': 676769, + 'timestamp_device': 120015, + 'timestamp_stream': 676.7677125670016, + 'transform': [array([-1.96493924e+00, -1.21041889e+01, 1.02642244e-02]), + array([-0.05813857, -0.41428912, 0.01947023])]} +{'AngularVelocity': array([ 3.14149293e-06, 2.77810050e-05, -1.24053877e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.208102226257324, + 'FR_Wheel_Angle': 2.8775901794433594, + 'Location': array([ -4.07665062, -21.46936989, 0.17403542]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 2.75731077e-06, -2.46489634e-07, -2.59775220e-07]), + 'brake_input': 0.0, + 'camera_location': array([-4.89951801, 12.4020443 , 1.17265666]), + 'camera_rotation': array([ -7.76414871, -14.69072723, 1.10470986]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9873046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 130.16171265, -1460.84973145, 16.49089813]), + 'frame': 20909, + 'frame_number': 20909, + 'framesequence': 79936, + 'gaze_dir': array([ 0.99253082, -0.11952209, 0.02172089]), + 'gaze_origin': array([-3.23269963, 0.08562241, 0.08244858]), + 'gaze_valid': True, + 'gaze_vergence': 211.02760314941406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99325562, -0.11209106, 0.02932739]), + 'left_gaze_origin': array([-3.2456913 , 3.28321528, 0.11159821]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21441650390625, + 'left_pupil_posn': array([-0.07611412, -0.07948625]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99180603, -0.12695312, 0.01411438]), + 'right_gaze_origin': array([-3.21970844, -3.11197066, 0.05329895]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1585693359375, + 'right_pupil_posn': array([-0.09075499, -0.14937317]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07459944486618042, + 'throttle_input': 0.0, + 'timestamp': 676.800985366106, + 'timestamp_carla': 676802, + 'timestamp_device': 120048, + 'timestamp_stream': 676.800985366106, + 'transform': [array([-1.94861841e+00, -1.20677252e+01, 1.02829169e-02]), + array([-0.05792683, -0.47713745, 0.01940919])]} +{'AngularVelocity': array([-1.80991374e-05, -1.15663815e-05, -1.41109422e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5345011353492737, + 'FR_Wheel_Angle': -0.5558473467826843, + 'Location': array([ -4.07665062, -21.46936989, 0.17402118]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 2.60562160e-06, -1.01818003e-07, 8.64088543e-06]), + 'brake_input': 0.0, + 'camera_location': array([-4.88714886, 12.44649124, 1.13531387]), + 'camera_rotation': array([ -8.09453201, -14.48455048, 1.10607564]), + 'current_gear_input': False, + 'focus_actor_dist': 1075.86083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 77.99514771, -1532.390625 , 16.56754303]), + 'frame': 20910, + 'frame_number': 20910, + 'framesequence': 79940, + 'gaze_dir': array([0.99443054, 0.09514618, 0.04199982]), + 'gaze_origin': array([-3.10238576, -0.08151856, 0.05239029]), + 'gaze_valid': True, + 'gaze_vergence': 190.4418487548828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99302673, 0.11117554, 0.03898621]), + 'left_gaze_origin': array([-3.08018804, 3.10817742, 0.06829071]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2709503173828125, + 'left_pupil_posn': array([ 0.11557102, -0.06748438]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.983465850353241, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99583435, 0.07911682, 0.04501343]), + 'right_gaze_origin': array([-3.12458348, -3.27121425, 0.03648987]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.206207275390625, + 'right_pupil_posn': array([ 0.09416044, -0.14125586]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0791955292224884, + 'throttle_input': 0.0, + 'timestamp': 676.8345354683697, + 'timestamp_carla': 676835, + 'timestamp_device': 120081, + 'timestamp_stream': 676.8345354683697, + 'transform': [array([-1.93137085e+00, -1.20316095e+01, 1.03045274e-02]), + array([-0.05783121, -0.5434593 , 0.01931764])]} +{'AngularVelocity': array([ 1.30991639e-05, -1.54810950e-05, -1.46522298e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -4.07665062, -21.46936989, 0.17394832]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 3.13151622e-06, -6.05161787e-08, 7.08455802e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.89471531, 12.51910782, 1.10470235]), + 'camera_rotation': array([ -8.40770245, -14.09228516, 1.21659422]), + 'current_gear_input': False, + 'focus_actor_dist': 1182.7373046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -129.23193359, -1359.1619873 , 16.71379089]), + 'frame': 20911, + 'frame_number': 20911, + 'framesequence': 79944, + 'gaze_dir': array([0.95368195, 0.29502106, 0.05416107]), + 'gaze_origin': array([-3.21293211, -0.23845141, 0.08696671]), + 'gaze_valid': True, + 'gaze_vergence': 135.3173370361328, + 'handbrake_input': False, + 'left_eye_openness': 0.980285108089447, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94703674, 0.3163147 , 0.05517578]), + 'left_gaze_origin': array([-3.19129634, 2.93695378, 0.1067627 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.367156982421875, + 'left_pupil_posn': array([ 0.30272067, -0.06307507]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.88944011926651, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96032715, 0.27372742, 0.05314636]), + 'right_gaze_origin': array([-3.2345674 , -3.41385674, 0.06717072]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1643524169921875, + 'right_pupil_posn': array([ 0.26867664, -0.14104366]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08309580385684967, + 'throttle_input': 0.0, + 'timestamp': 676.868026766926, + 'timestamp_carla': 676869, + 'timestamp_device': 120115, + 'timestamp_stream': 676.868026766926, + 'transform': [array([-1.91348016e+00, -1.19961824e+01, 1.03256609e-02]), + array([-0.05783121, -0.61217523, 0.01922608])]} +{'AngularVelocity': array([-3.30714211e-05, -5.87894306e-07, -1.44359337e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -4.07665062, -21.46936989, 0.17401507]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 3.06845641e-06, -1.98156336e-08, 5.23017312e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.89363289, 12.63068771, 1.0761708 ]), + 'camera_rotation': array([ -8.57742596, -13.51748657, 1.20337462]), + 'current_gear_input': False, + 'focus_actor_dist': 1288.2352294921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -381.43157959, -1235.06335449, 16.93732452]), + 'frame': 20912, + 'frame_number': 20912, + 'framesequence': 79948, + 'gaze_dir': array([0.92606354, 0.37270355, 0.05735779]), + 'gaze_origin': array([-3.23674202, -0.29805374, 0.08874893]), + 'gaze_valid': True, + 'gaze_vergence': 207.01939392089844, + 'handbrake_input': False, + 'left_eye_openness': 0.9909246563911438, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92092896, 0.38496399, 0.06066895]), + 'left_gaze_origin': array([-3.21606469, 2.87490392, 0.10679016]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3232879638671875, + 'left_pupil_posn': array([ 0.37854338, -0.06992376]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8615518808364868, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93119812, 0.36044312, 0.05404663]), + 'right_gaze_origin': array([-3.25741887, -3.47101164, 0.0707077 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1872711181640625, + 'right_pupil_posn': array([ 0.33531368, -0.14376736]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08684957027435303, + 'throttle_input': 0.0, + 'timestamp': 676.901508666575, + 'timestamp_carla': 676902, + 'timestamp_device': 120148, + 'timestamp_stream': 676.901508666575, + 'transform': [array([-1.89501894e+00, -1.19613752e+01, 1.03461454e-02]), + array([-0.05789268, -0.68299508, 0.01913453])]} +{'AngularVelocity': array([-3.46842389e-05, -4.33582718e-05, -1.25259121e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.133489608764648, + 'FR_Wheel_Angle': 5.041229724884033, + 'Location': array([ -4.07665062, -21.46936989, 0.1740073 ]), + 'Rotation': array([-0.07287128, 10.35730648, -0.01867676]), + 'Velocity': array([ 2.32726325e-06, -2.66082935e-07, -1.82009841e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.89068317, 12.7688446 , 1.0447613 ]), + 'camera_rotation': array([ -8.64606285, -12.734828 , 1.21174717]), + 'current_gear_input': False, + 'focus_actor_dist': 1330.5106201171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -504.05325317, -1200.19262695, 17.05247498]), + 'frame': 20913, + 'frame_number': 20913, + 'framesequence': 79952, + 'gaze_dir': array([0.92882538, 0.36697388, 0.04957581]), + 'gaze_origin': array([-3.23058176, -0.28819048, 0.09378204]), + 'gaze_valid': True, + 'gaze_vergence': 255.79307556152344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92486572, 0.37730408, 0.04722595]), + 'left_gaze_origin': array([-3.20845199, 2.89098382, 0.1104065 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.39776611328125, + 'left_pupil_posn': array([ 0.36539149, -0.06681943]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8907554745674133, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93278503, 0.35664368, 0.05192566]), + 'right_gaze_origin': array([-3.25271153, -3.46736455, 0.07715759]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2415313720703125, + 'right_pupil_posn': array([ 0.32952285, -0.14282823]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08981598168611526, + 'throttle_input': 0.01190203707665205, + 'timestamp': 676.9360067658126, + 'timestamp_carla': 676937, + 'timestamp_device': 120181, + 'timestamp_stream': 676.9360067658126, + 'transform': [array([-1.87712669e+00, -1.19266815e+01, 1.01651186e-02]), + array([-0.05828883, -0.75086504, 0.01986695])]} +{'AngularVelocity': array([ 0.00242869, -0.02498263, 0.52361691]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.409070014953613, + 'FR_Wheel_Angle': 9.727462768554688, + 'Location': array([ -4.07647991, -21.46934128, 0.17399761]), + 'Rotation': array([-0.07263223, 10.35965157, -0.01870727]), + 'Velocity': array([ 1.59644466e-02, 2.94261170e-03, -5.95664969e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.90386963, 12.91300583, 1.02956653]), + 'camera_rotation': array([ -8.80427742, -11.97571182, 1.24935806]), + 'current_gear_input': False, + 'focus_actor_dist': 1206.6346435546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -494.39154053, -1320.85888672, 17.07345581]), + 'frame': 20914, + 'frame_number': 20914, + 'framesequence': 79956, + 'gaze_dir': array([0.92912292, 0.36598206, 0.05052185]), + 'gaze_origin': array([-3.22870564, -0.28543398, 0.09734803]), + 'gaze_valid': True, + 'gaze_vergence': 146.35479736328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92466736, 0.37593079, 0.06040955]), + 'left_gaze_origin': array([-3.20496225, 2.89579177, 0.11362915]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2995452880859375, + 'left_pupil_posn': array([ 0.36163974, -0.06780207]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8989099264144897, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93357849, 0.35603333, 0.04063416]), + 'right_gaze_origin': array([-3.25244927, -3.46665978, 0.0810669 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2149200439453125, + 'right_pupil_posn': array([ 0.32857084, -0.13541508]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09225135296583176, + 'throttle_input': 0.0238040741533041, + 'timestamp': 676.9684061668813, + 'timestamp_carla': 676969, + 'timestamp_device': 120215, + 'timestamp_stream': 676.9684061668813, + 'transform': [array([-1.86000335e+00, -1.18955307e+01, 9.93295666e-03]), + array([-0.05874645, -0.81603062, 0.02090456])]} +{'AngularVelocity': array([ 0.00061321, 0.00310625, -0.09444814]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.443331718444824, + 'FR_Wheel_Angle': 13.307056427001953, + 'Location': array([ -4.07384491, -21.46865273, 0.17398891]), + 'Rotation': array([-0.07275517, 10.36867428, -0.01870727]), + 'Velocity': array([ 0.00802239, 0.00273055, -0.00015173]), + 'brake_input': 0.0, + 'camera_location': array([-4.91021633, 13.05834007, 1.01834369]), + 'camera_rotation': array([ -8.93358612, -11.28680897, 1.26273131]), + 'current_gear_input': False, + 'focus_actor_dist': 1183.8028564453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -503.92419434, -1341.91101074, 17.08851624]), + 'frame': 20915, + 'frame_number': 20915, + 'framesequence': 79960, + 'gaze_dir': array([0.93094635, 0.36078644, 0.05478668]), + 'gaze_origin': array([-3.2268908 , -0.28075412, 0.09994049]), + 'gaze_valid': True, + 'gaze_vergence': 122.72541809082031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92791748, 0.36697388, 0.06546021]), + 'left_gaze_origin': array([-3.20283365, 2.90199304, 0.1171402 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3379364013671875, + 'left_pupil_posn': array([ 0.35665715, -0.06379902]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9082567095756531, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93397522, 0.354599 , 0.04411316]), + 'right_gaze_origin': array([-3.25094748, -3.46350121, 0.08274078]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1778411865234375, + 'right_pupil_posn': array([ 0.32303715, -0.13174284]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0940641537308693, + 'throttle_input': 0.0317387655377388, + 'timestamp': 677.0017525665462, + 'timestamp_carla': 677003, + 'timestamp_device': 120248, + 'timestamp_stream': 677.0017525665462, + 'transform': [array([-1.84226072e+00, -1.18646727e+01, 9.72362515e-03]), + array([-0.05919725, -0.88366562, 0.02178957])]} +{'AngularVelocity': array([ 0.00188641, 0.00172572, -0.10380397]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.527664184570312, + 'FR_Wheel_Angle': 15.769427299499512, + 'Location': array([ -4.0727582 , -21.46832466, 0.17399006]), + 'Rotation': array([-0.07311717, 10.37244606, -0.01852417]), + 'Velocity': array([0.00102689, 0.00074451, 0.00025174]), + 'brake_input': 0.0, + 'camera_location': array([-4.90433502, 13.22227097, 1.02420664]), + 'camera_rotation': array([ -8.93557358, -10.56413841, 1.22030282]), + 'current_gear_input': False, + 'focus_actor_dist': 1206.1766357421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -513.58685303, -1317.43640137, 17.09204102]), + 'frame': 20916, + 'frame_number': 20916, + 'framesequence': 79964, + 'gaze_dir': array([0.93721771, 0.34411621, 0.05619812]), + 'gaze_origin': array([-3.22340798, -0.27544174, 0.10190201]), + 'gaze_valid': True, + 'gaze_vergence': 490.981689453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93539429, 0.34872437, 0.0585022 ]), + 'left_gaze_origin': array([-3.19968414, 2.90954161, 0.1175766 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.323272705078125, + 'left_pupil_posn': array([ 0.345891 , -0.05887079]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9120956659317017, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93904114, 0.33950806, 0.05389404]), + 'right_gaze_origin': array([-3.24713135, -3.46042514, 0.08622742]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1040496826171875, + 'right_pupil_posn': array([ 0.31396115, -0.13018334]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09560228139162064, + 'throttle_input': 0.035706110298633575, + 'timestamp': 677.0354011654854, + 'timestamp_carla': 677036, + 'timestamp_device': 120281, + 'timestamp_stream': 677.0354011654854, + 'transform': [array([-1.82451141e+00, -1.18345385e+01, 9.58827976e-03]), + array([-0.05963438, -0.95124263, 0.02233888])]} +{'AngularVelocity': array([ 0.00356687, 0.00138728, -0.15958838]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.726590156555176, + 'FR_Wheel_Angle': 17.32865333557129, + 'Location': array([ -4.07393551, -21.46869659, 0.17399018]), + 'Rotation': array([-0.07330158, 10.36557865, -0.01834106]), + 'Velocity': array([-0.00994073, -0.00301937, -0.0003807 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.88800812, 13.3822813 , 1.01314354]), + 'camera_rotation': array([-8.91224861, -9.81702042, 1.29167068]), + 'current_gear_input': False, + 'focus_actor_dist': 1218.600830078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -507.64501953, -1300.60998535, 17.08174896]), + 'frame': 20917, + 'frame_number': 20917, + 'framesequence': 79969, + 'gaze_dir': array([0.94042969, 0.33460236, 0.05966187]), + 'gaze_origin': array([-3.22138453, -0.26915896, 0.10151062]), + 'gaze_valid': True, + 'gaze_vergence': 407.0756530761719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93835449, 0.33988953, 0.06268311]), + 'left_gaze_origin': array([-3.19716191, 2.91708398, 0.11756898]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3194732666015625, + 'left_pupil_posn': array([ 0.33684373, -0.05712712]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9205353260040283, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94250488, 0.32931519, 0.05664062]), + 'right_gaze_origin': array([-3.2456069 , -3.4554019 , 0.08545227]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.030181884765625, + 'right_pupil_posn': array([ 0.30720353, -0.128492 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09690237790346146, + 'throttle_input': 0.03967345505952835, + 'timestamp': 677.0693767666817, + 'timestamp_carla': 677070, + 'timestamp_device': 120323, + 'timestamp_stream': 677.0693767666817, + 'transform': [array([-1.80675590e+00, -1.18049946e+01, 9.52779781e-03]), + array([-0.0600237 , -1.01875818, 0.0225525 ])]} +{'AngularVelocity': array([ 0.00358021, 0.00156173, -0.21888925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.01090431213379, + 'FR_Wheel_Angle': 19.098125457763672, + 'Location': array([ -4.0775609 , -21.46988678, 0.17402358]), + 'Rotation': array([-0.07336306, 10.3438549 , -0.01818848]), + 'Velocity': array([-2.16315649e-02, -7.46416301e-03, -3.87144064e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.85962963, 13.5440731 , 1.00982249]), + 'camera_rotation': array([-8.94006824, -9.21400166, 1.2639184 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1258.2945556640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -515.8248291 , -1258.34863281, 17.07926178]), + 'frame': 20918, + 'frame_number': 20918, + 'framesequence': 79972, + 'gaze_dir': array([0.94244385, 0.32788086, 0.06471252]), + 'gaze_origin': array([-3.21992445, -0.26640627, 0.10445786]), + 'gaze_valid': True, + 'gaze_vergence': 330.41864013671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93943787, 0.33638 , 0.06539917]), + 'left_gaze_origin': array([-3.19590306, 2.91855025, 0.12088318]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.157867431640625, + 'left_pupil_posn': array([ 0.33239925, -0.05146456]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9188928604125977, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94544983, 0.31938171, 0.06402588]), + 'right_gaze_origin': array([-3.2439456 , -3.45136261, 0.08803254]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1959075927734375, + 'right_pupil_posn': array([ 0.30283964, -0.12559354]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09833064675331116, + 'throttle_input': 0.03967345505952835, + 'timestamp': 677.1018171682954, + 'timestamp_carla': 677103, + 'timestamp_device': 120348, + 'timestamp_stream': 677.1018171682954, + 'transform': [array([-1.78997004e+00, -1.17775097e+01, 9.53712407e-03]), + array([-0.06033789, -1.08247983, 0.02252199])]} +{'AngularVelocity': array([ 0.00478979, 0.00128651, -0.27646837]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.03936767578125, + 'FR_Wheel_Angle': 20.369380950927734, + 'Location': array([ -4.08270264, -21.47163773, 0.17401035]), + 'Rotation': array([-0.07330158, 10.31061935, -0.01818848]), + 'Velocity': array([-2.95374691e-02, -1.06950682e-02, 6.97040523e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.83458424, 13.69086075, 0.99460894]), + 'camera_rotation': array([-9.13279533, -8.66126251, 1.45461702]), + 'current_gear_input': False, + 'focus_actor_dist': 1321.7139892578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -528.40930176, -1192.72509766, 17.07512665]), + 'frame': 20919, + 'frame_number': 20919, + 'framesequence': 79976, + 'gaze_dir': array([0.94490051, 0.32110596, 0.06241608]), + 'gaze_origin': array([-3.21746922, -0.26248705, 0.10767365]), + 'gaze_valid': True, + 'gaze_vergence': 239.5054168701172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94180298, 0.33114624, 0.05767822]), + 'left_gaze_origin': array([-3.19411945, 2.92210245, 0.12444459]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2877197265625, + 'left_pupil_posn': array([ 0.32671344, -0.04759073]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9321702122688293, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94799805, 0.31106567, 0.06715393]), + 'right_gaze_origin': array([-3.24081898, -3.4470768 , 0.09090271]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.15570068359375, + 'right_pupil_posn': array([ 0.29774547, -0.1254915 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0993194431066513, + 'throttle_input': 0.043656062334775925, + 'timestamp': 677.1354961656034, + 'timestamp_carla': 677136, + 'timestamp_device': 120381, + 'timestamp_stream': 677.1354961656034, + 'transform': [array([-1.77261591e+00, -1.17496214e+01, 9.58301499e-03]), + array([-0.06057011, -1.14833283, 0.02227785])]} +{'AngularVelocity': array([ 0.00507121, 0.00188528, -0.36662227]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.717266082763672, + 'FR_Wheel_Angle': 21.3830509185791, + 'Location': array([ -4.09101057, -21.47452164, 0.17401566]), + 'Rotation': array([-0.07336306, 10.25408173, -0.01812744]), + 'Velocity': array([-4.15629223e-02, -1.55854197e-02, 7.10487366e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.82547379, 13.82360077, 0.95315927]), + 'camera_rotation': array([-9.3219986 , -8.07062149, 1.71869493]), + 'current_gear_input': False, + 'focus_actor_dist': 1229.57958984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -515.77752686, -1281.49865723, 17.08507538]), + 'frame': 20920, + 'frame_number': 20920, + 'framesequence': 79980, + 'gaze_dir': array([0.94664764, 0.31636047, 0.05998993]), + 'gaze_origin': array([-3.21581817, -0.26009369, 0.11015245]), + 'gaze_valid': True, + 'gaze_vergence': 242.6594696044922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9427948 , 0.32809448, 0.05899048]), + 'left_gaze_origin': array([-3.1920259 , 2.92462158, 0.1256485 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2981414794921875, + 'left_pupil_posn': array([ 0.32253528, -0.04833305]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9333137273788452, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95050049, 0.30462646, 0.06098938]), + 'right_gaze_origin': array([-3.23961043, -3.4448092 , 0.09465638]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2042236328125, + 'right_pupil_posn': array([ 0.29493535, -0.12219989]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10028992593288422, + 'throttle_input': 0.05555810034275055, + 'timestamp': 677.1686301678419, + 'timestamp_carla': 677170, + 'timestamp_device': 120415, + 'timestamp_stream': 677.1686301678419, + 'transform': [array([-1.75567436e+00, -1.17227516e+01, 9.66283772e-03]), + array([-0.06078868, -1.21251261, 0.02191164])]} +{'AngularVelocity': array([ 7.98305776e-03, -2.78293301e-04, -5.05475581e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.82146453857422, + 'FR_Wheel_Angle': 23.04973030090332, + 'Location': array([ -4.10328484, -21.47887611, 0.17402755]), + 'Rotation': array([-0.07360212, 10.16566372, -0.01785278]), + 'Velocity': array([-0.05928958, -0.0233216 , -0.00018756]), + 'brake_input': 0.0, + 'camera_location': array([-4.80713558, 13.94027328, 0.92522025]), + 'camera_rotation': array([-9.47990608, -7.47862625, 1.85257649]), + 'current_gear_input': False, + 'focus_actor_dist': 1145.0030517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -507.2276001 , -1363.2857666 , 17.09732056]), + 'frame': 20921, + 'frame_number': 20921, + 'framesequence': 79984, + 'gaze_dir': array([0.94998169, 0.3059845 , 0.06057739]), + 'gaze_origin': array([-3.21304941, -0.25817034, 0.11313325]), + 'gaze_valid': True, + 'gaze_vergence': 208.9568328857422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94552612, 0.31973267, 0.06097412]), + 'left_gaze_origin': array([-3.18947172, 2.92642069, 0.12855531]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.298126220703125, + 'left_pupil_posn': array([ 0.31672144, -0.04582477]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9356149435043335, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95443726, 0.29223633, 0.06018066]), + 'right_gaze_origin': array([-3.2366271 , -3.44276142, 0.09771118]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.442626953125, + 'right_pupil_posn': array([ 0.2903192, -0.1185689]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10109561681747437, + 'throttle_input': 0.059525445103645325, + 'timestamp': 677.2014964669943, + 'timestamp_carla': 677202, + 'timestamp_device': 120448, + 'timestamp_stream': 677.2014964669943, + 'transform': [array([-1.73896027e+00, -1.16965685e+01, 9.77247208e-03]), + array([-0.06094578, -1.27574635, 0.02142335])]} +{'AngularVelocity': array([ 0.0422494 , -0.04905159, -3.32875204]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.17070770263672, + 'FR_Wheel_Angle': 25.008697509765625, + 'Location': array([ -4.17177343, -21.50372696, 0.17417996]), + 'Rotation': array([-8.71873572e-02, 9.64871788e+00, -8.69750883e-03]), + 'Velocity': array([-0.41436964, -0.17267714, 0.00042541]), + 'brake_input': 0.0, + 'camera_location': array([-4.76992226, 14.06326103, 0.89097327]), + 'camera_rotation': array([-9.57882023, -6.854599 , 1.90281868]), + 'current_gear_input': False, + 'focus_actor_dist': 1113.0146484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -500.16195679, -1391.87145996, 17.09750366]), + 'frame': 20922, + 'frame_number': 20922, + 'framesequence': 79988, + 'gaze_dir': array([0.95027161, 0.30425262, 0.06373596]), + 'gaze_origin': array([-3.21147394, -0.25191957, 0.11539383]), + 'gaze_valid': True, + 'gaze_vergence': 164.19154357910156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9446106 , 0.32145691, 0.06596375]), + 'left_gaze_origin': array([-3.18719196, 2.93264627, 0.13025361]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2526092529296875, + 'left_pupil_posn': array([ 0.31044018, -0.0436902 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9368353486061096, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95593262, 0.28704834, 0.06150818]), + 'right_gaze_origin': array([-3.23575616, -3.43648529, 0.10053406]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.406036376953125, + 'right_pupil_posn': array([ 0.28643858, -0.11496043]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10133366286754608, + 'throttle_input': 0.07142747938632965, + 'timestamp': 677.2339293658733, + 'timestamp_carla': 677235, + 'timestamp_device': 120481, + 'timestamp_stream': 677.2339293658733, + 'transform': [array([-1.72256804e+00, -1.16710920e+01, 9.90432687e-03]), + array([-0.06109604, -1.33766592, 0.02084352])]} +{'AngularVelocity': array([ 0.04564265, -0.04870746, -3.39382553]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.34977912902832, + 'FR_Wheel_Angle': 26.707199096679688, + 'Location': array([ -4.28791666, -21.54657364, 0.174262 ]), + 'Rotation': array([-0.08010446, 8.69339371, -0.01296997]), + 'Velocity': array([-0.50419247, -0.21317041, 0.00087782]), + 'brake_input': 0.0, + 'camera_location': array([-4.73883343, 14.18920517, 0.87319142]), + 'camera_rotation': array([-9.63506031, -6.19498873, 1.94452846]), + 'current_gear_input': False, + 'focus_actor_dist': 1125.7437744140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -511.04162598, -1377.92468262, 17.10498047]), + 'frame': 20923, + 'frame_number': 20923, + 'framesequence': 79992, + 'gaze_dir': array([0.95353699, 0.29397583, 0.06493378]), + 'gaze_origin': array([-3.20894933, -0.24674989, 0.1171753 ]), + 'gaze_valid': True, + 'gaze_vergence': 298.5103454589844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95056152, 0.30369568, 0.06465149]), + 'left_gaze_origin': array([-3.18510461, 2.93776703, 0.13200989]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2651824951171875, + 'left_pupil_posn': array([ 0.30589581, -0.04064047]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9414666295051575, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95651245, 0.28425598, 0.06521606]), + 'right_gaze_origin': array([-3.23279428, -3.43126702, 0.1023407 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.149871826171875, + 'right_pupil_posn': array([ 0.27626324, -0.11286962]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10133366286754608, + 'throttle_input': 0.0793621763586998, + 'timestamp': 677.2681627683342, + 'timestamp_carla': 677269, + 'timestamp_device': 120515, + 'timestamp_stream': 677.2681627683342, + 'transform': [array([-1.70541167e+00, -1.16445322e+01, 1.00411791e-02]), + array([-0.06125313, -1.40239668, 0.02017214])]} +{'AngularVelocity': array([ 0.03800839, -0.02942323, -5.53938627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.829975128173828, + 'FR_Wheel_Angle': 27.28838348388672, + 'Location': array([ -4.42608547, -21.5958271 , 0.17439505]), + 'Rotation': array([-0.07946925, 7.4756093 , -0.01364136]), + 'Velocity': array([-6.26158595e-01, -2.54043549e-01, 4.60672367e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.71326923, 14.29123688, 0.86152768]), + 'camera_rotation': array([-9.76203346, -5.52570868, 2.13507295]), + 'current_gear_input': False, + 'focus_actor_dist': 1124.053955078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -510.23602295, -1376.78942871, 17.1038208 ]), + 'frame': 20924, + 'frame_number': 20924, + 'framesequence': 79996, + 'gaze_dir': array([0.95659637, 0.28224945, 0.07025909]), + 'gaze_origin': array([-3.20676684, -0.24035569, 0.12072526]), + 'gaze_valid': True, + 'gaze_vergence': 170.00315856933594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95161438, 0.29797363, 0.07496643]), + 'left_gaze_origin': array([-3.18148661, 2.94543171, 0.13352357]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.263397216796875, + 'left_pupil_posn': array([ 0.29412675, -0.03839993]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9454803466796875, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96157837, 0.26652527, 0.06555176]), + 'right_gaze_origin': array([-3.2320466 , -3.42614317, 0.10792694]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.33929443359375, + 'right_pupil_posn': array([ 0.27057683, -0.10526347]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10133366286754608, + 'throttle_input': 0.09919890016317368, + 'timestamp': 677.3021393679082, + 'timestamp_carla': 677303, + 'timestamp_device': 120548, + 'timestamp_stream': 677.3021393679082, + 'transform': [array([-1.68847620e+00, -1.16184511e+01, 1.01862717e-02]), + array([-0.06133509, -1.46617448, 0.01950075])]} +{'AngularVelocity': array([-0.10653422, 0.10658854, -6.00361538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.677288055419922, + 'FR_Wheel_Angle': 26.754318237304688, + 'Location': array([ -4.56428003, -21.64278984, 0.1745023 ]), + 'Rotation': array([-0.07192872, 6.23533058, -0.02038574]), + 'Velocity': array([-0.55497164, -0.21148847, 0.00115067]), + 'brake_input': 0.0, + 'camera_location': array([-4.68616962, 14.39037132, 0.871656 ]), + 'camera_rotation': array([-9.77001095, -4.90073061, 2.29291987]), + 'current_gear_input': False, + 'focus_actor_dist': 1146.7064208984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -512.36077881, -1351.21838379, 17.09945679]), + 'frame': 20925, + 'frame_number': 20925, + 'framesequence': 80000, + 'gaze_dir': array([0.95970917, 0.27244568, 0.06834412]), + 'gaze_origin': array([-3.20471525, -0.23413697, 0.11916351]), + 'gaze_valid': True, + 'gaze_vergence': 485.4716796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95797729, 0.27824402, 0.06951904]), + 'left_gaze_origin': array([-3.1805408 , 2.95180821, 0.13232881]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.281341552734375, + 'left_pupil_posn': array([ 0.28964877, -0.03863382]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9526745676994324, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96144104, 0.26664734, 0.06716919]), + 'right_gaze_origin': array([-3.2288897 , -3.42008209, 0.10599823]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.174713134765625, + 'right_pupil_posn': array([ 0.25911355, -0.10714126]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10109561681747437, + 'throttle_input': 0.1111009418964386, + 'timestamp': 677.3345035687089, + 'timestamp_carla': 677335, + 'timestamp_device': 120581, + 'timestamp_stream': 677.3345035687089, + 'transform': [array([-1.67238796e+00, -1.15936975e+01, 1.03733633e-02]), + array([-0.06139657, -1.52665389, 0.01870728])]} +{'AngularVelocity': array([ 0.05694792, -0.06656512, -5.759305 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.685039520263672, + 'FR_Wheel_Angle': 25.494783401489258, + 'Location': array([ -4.7626133 , -21.70228386, 0.17471954]), + 'Rotation': array([-0.07516623, 4.55746746, -0.02001953]), + 'Velocity': array([-6.98884487e-01, -2.30682939e-01, 5.85441594e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.65368652, 14.48512459, 0.85855311]), + 'camera_rotation': array([-9.74306583, -4.44451332, 2.04814315]), + 'current_gear_input': False, + 'focus_actor_dist': 1115.449951171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -506.53930664, -1379.33374023, 17.1007843 ]), + 'frame': 20926, + 'frame_number': 20926, + 'framesequence': 80004, + 'gaze_dir': array([0.96025848, 0.2706604 , 0.06749725]), + 'gaze_origin': array([-3.2032907 , -0.22958452, 0.12072526]), + 'gaze_valid': True, + 'gaze_vergence': 362.440673828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95800781, 0.27807617, 0.06974792]), + 'left_gaze_origin': array([-3.17886806, 2.95590067, 0.13380432]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3717041015625, + 'left_pupil_posn': array([ 0.28552675, -0.03792894]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.967739462852478, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96250916, 0.26324463, 0.06524658]), + 'right_gaze_origin': array([-3.22771335, -3.41506982, 0.10764619]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2884521484375, + 'right_pupil_posn': array([ 0.25548017, -0.10577655]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10074771195650101, + 'throttle_input': 0.1269855797290802, + 'timestamp': 677.3696008659899, + 'timestamp_carla': 677370, + 'timestamp_device': 120615, + 'timestamp_stream': 677.3696008659899, + 'transform': [array([-1.65500271e+00, -1.15668745e+01, 1.05560683e-02]), + array([-0.06145804, -1.59190857, 0.01782228])]} +{'AngularVelocity': array([ 0.00667855, -0.02373583, -4.28203583]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.087635040283203, + 'FR_Wheel_Angle': 26.51901626586914, + 'Location': array([ -4.88286257, -21.73486328, 0.17479041]), + 'Rotation': array([-0.06555615, 3.57176185, -0.0249939 ]), + 'Velocity': array([-5.16527712e-01, -1.61750391e-01, 4.30946355e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.65110397, 14.54970932, 0.85603863]), + 'camera_rotation': array([-9.87824917, -4.1932106 , 2.00772524]), + 'current_gear_input': False, + 'focus_actor_dist': 1123.3155517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -512.92492676, -1369.76721191, 17.10479736]), + 'frame': 20927, + 'frame_number': 20927, + 'framesequence': 80008, + 'gaze_dir': array([0.96041107, 0.2699585 , 0.06816864]), + 'gaze_origin': array([-3.2025497 , -0.22685471, 0.12229767]), + 'gaze_valid': True, + 'gaze_vergence': 396.97283935546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95829773, 0.27719116, 0.0692749 ]), + 'left_gaze_origin': array([-3.17758512, 2.96086454, 0.13597107]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3970184326171875, + 'left_pupil_posn': array([ 0.28190076, -0.03554869]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.945511519908905, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96252441, 0.26272583, 0.06706238]), + 'right_gaze_origin': array([-3.22751474, -3.41457391, 0.10862427]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2440032958984375, + 'right_pupil_posn': array([ 0.25482607, -0.10514629]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10003357380628586, + 'throttle_input': 0.15078964829444885, + 'timestamp': 677.4017443656921, + 'timestamp_carla': 677403, + 'timestamp_device': 120648, + 'timestamp_stream': 677.4017443656921, + 'transform': [array([-1.63900816e+00, -1.15421934e+01, 1.07840914e-02]), + array([-0.06142389, -1.65180779, 0.01687624])]} +{'AngularVelocity': array([-0.00560664, 0.00624635, -2.9968586 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.27995491027832, + 'FR_Wheel_Angle': 27.895273208618164, + 'Location': array([ -4.99401903, -21.76433945, 0.17489974]), + 'Rotation': array([-0.06436087, 2.6052351 , -0.02334594]), + 'Velocity': array([-0.33445129, -0.10550275, 0.00050319]), + 'brake_input': 0.0, + 'camera_location': array([-4.63859844, 14.56704044, 0.83186209]), + 'camera_rotation': array([-9.97157669, -4.12368488, 2.0936377 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1108.7708740234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -512.95727539, -1381.80065918, 17.10780334]), + 'frame': 20928, + 'frame_number': 20928, + 'framesequence': 80012, + 'gaze_dir': array([0.96018982, 0.27068329, 0.06861877]), + 'gaze_origin': array([-3.20219874, -0.22584613, 0.12220918]), + 'gaze_valid': True, + 'gaze_vergence': 475.8535461425781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95848083, 0.27633667, 0.07032776]), + 'left_gaze_origin': array([-3.17748737, 2.96224523, 0.13539124]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.461029052734375, + 'left_pupil_posn': array([ 0.28168857, -0.03618121]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9469463229179382, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9618988 , 0.26502991, 0.06690979]), + 'right_gaze_origin': array([-3.22691059, -3.41393757, 0.1090271 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3099822998046875, + 'right_pupil_posn': array([ 0.25402951, -0.1044414 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09880673140287399, + 'throttle_input': 0.16269169747829437, + 'timestamp': 677.4350733682513, + 'timestamp_carla': 677436, + 'timestamp_device': 120681, + 'timestamp_stream': 677.4350733682513, + 'transform': [array([-1.62237084e+00, -1.15162554e+01, 1.10460473e-02]), + array([-0.06139657, -1.71399939, 0.01571657])]} +{'AngularVelocity': array([-0.0656293 , 0.05706497, -0.00064283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.085317611694336, + 'FR_Wheel_Angle': 27.672277450561523, + 'Location': array([ -5.02871418, -21.77327538, 0.17487545]), + 'Rotation': array([-0.05615098, 2.30619907, -0.02954101]), + 'Velocity': array([ 1.65738256e-05, 1.51371802e-04, -2.32396807e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.64570713, 14.53314972, 0.82246131]), + 'camera_rotation': array([-10.10189724, -4.29617262, 2.19744158]), + 'current_gear_input': False, + 'focus_actor_dist': 1093.425537109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -511.18670654, -1394.55859375, 17.10938263]), + 'frame': 20929, + 'frame_number': 20929, + 'framesequence': 80016, + 'gaze_dir': array([0.95983124, 0.27170563, 0.06954956]), + 'gaze_origin': array([-3.20210052, -0.2257271 , 0.12206269]), + 'gaze_valid': True, + 'gaze_vergence': 440.5562744140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95791626, 0.27832031, 0.07011414]), + 'left_gaze_origin': array([-3.17742157, 2.96224523, 0.13476411]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.47857666015625, + 'left_pupil_posn': array([ 0.2816937 , -0.03591061]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9458968639373779, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96174622, 0.26509094, 0.06898499]), + 'right_gaze_origin': array([-3.22677946, -3.41369963, 0.10936128]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3478240966796875, + 'right_pupil_posn': array([ 0.254547 , -0.10436559]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09730521589517593, + 'throttle_input': 0.1745937317609787, + 'timestamp': 677.4678472653031, + 'timestamp_carla': 677469, + 'timestamp_device': 120715, + 'timestamp_stream': 677.4678472653031, + 'transform': [array([-1.60592103e+00, -1.14903278e+01, 1.13189500e-02]), + array([-0.06136242, -1.77534091, 0.01452638])]} +{'AngularVelocity': array([-0.02347456, 0.02812411, 0.00017185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.442216873168945, + 'FR_Wheel_Angle': 28.24010467529297, + 'Location': array([ -5.02878904, -21.77334404, 0.17494804]), + 'Rotation': array([-0.06817211, 2.30622816, -0.01974487]), + 'Velocity': array([ 2.39183846e-05, 6.81953725e-06, -3.32402095e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.64379215, 14.46930122, 0.82905841]), + 'camera_rotation': array([-10.16330051, -4.68582153, 2.25830555]), + 'current_gear_input': False, + 'focus_actor_dist': 1076.533203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -504.94729614, -1408.00268555, 17.10640717]), + 'frame': 20930, + 'frame_number': 20930, + 'framesequence': 80020, + 'gaze_dir': array([0.98513031, 0.14905548, 0.0816803 ]), + 'gaze_origin': array([-3.05136728, -0.11758119, 0.08511505]), + 'gaze_valid': True, + 'gaze_vergence': 127.52345275878906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98136902, 0.17347717, 0.08253479]), + 'left_gaze_origin': array([-3.02303481, 3.0794878 , 0.09572297]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.51971435546875, + 'left_pupil_posn': array([ 0.1504035 , -0.02708364]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9888916 , 0.12463379, 0.08082581]), + 'right_gaze_origin': array([-3.07969999, -3.31465006, 0.07450715]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3425140380859375, + 'right_pupil_posn': array([ 0.1445173 , -0.09417415]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09560228139162064, + 'throttle_input': 0.18649576604366302, + 'timestamp': 677.5019539669156, + 'timestamp_carla': 677503, + 'timestamp_device': 120748, + 'timestamp_stream': 677.5019539669156, + 'transform': [array([ -1.58870912, -11.46277714, 0.01160053]), + array([-0.06133509, -1.83935046, 0.01324464])]} +{'AngularVelocity': array([-0.01881645, 0.01761753, -0.08837661]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.489267349243164, + 'FR_Wheel_Angle': 28.24956703186035, + 'Location': array([ -5.02898455, -21.7734108 , 0.17497203]), + 'Rotation': array([-0.07192872, 2.30470872, -0.01660156]), + 'Velocity': array([-0.00978811, -0.00303116, 0.00017746]), + 'brake_input': 0.0, + 'camera_location': array([-4.62825871, 14.39804459, 0.8360095 ]), + 'camera_rotation': array([-10.01036549, -5.23630428, 2.16281033]), + 'current_gear_input': False, + 'focus_actor_dist': 1194.1629638671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -367.35821533, -1271.5279541 , 16.93242645]), + 'frame': 20931, + 'frame_number': 20931, + 'framesequence': 80024, + 'gaze_dir': array([ 0.99658203, -0.04753876, 0.06465149]), + 'gaze_origin': array([-3.15895939, 0.02106934, 0.10388566]), + 'gaze_valid': True, + 'gaze_vergence': 162.1582794189453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99719238, -0.02883911, 0.06890869]), + 'left_gaze_origin': array([-3.121979 , 3.21053648, 0.11381532]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3555145263671875, + 'left_pupil_posn': array([-0.0040772 , -0.03896582]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99597168, -0.0662384 , 0.06039429]), + 'right_gaze_origin': array([-3.19594002, -3.16839767, 0.093956 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4210052490234375, + 'right_pupil_posn': array([-0.02286756, -0.10402262]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09393598139286041, + 'throttle_input': 0.1904631108045578, + 'timestamp': 677.5345721654594, + 'timestamp_carla': 677535, + 'timestamp_device': 120781, + 'timestamp_stream': 677.5345721654594, + 'transform': [array([ -1.57215726, -11.43582344, 0.01187685]), + array([-0.06127362, -1.90072036, 0.01205446])]} +{'AngularVelocity': array([ 0.00260522, -0.0032535 , -0.20271713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.483715057373047, + 'FR_Wheel_Angle': 28.246456146240234, + 'Location': array([ -5.03401947, -21.77471352, 0.17499492]), + 'Rotation': array([-0.07321279, 2.2595284 , -0.01550293]), + 'Velocity': array([-0.02287908, -0.00709006, 0.00022028]), + 'brake_input': 0.0, + 'camera_location': array([-4.59381294, 14.30432701, 0.84094346]), + 'camera_rotation': array([-9.83314991, -5.88532877, 2.03364182]), + 'current_gear_input': False, + 'focus_actor_dist': 1099.76318359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -135.01216125, -1378.14001465, 16.72455597]), + 'frame': 20932, + 'frame_number': 20932, + 'framesequence': 80028, + 'gaze_dir': array([ 0.98484039, -0.16174316, 0.06071472]), + 'gaze_origin': array([-3.18420196, 0.11961365, 0.09479065]), + 'gaze_valid': True, + 'gaze_vergence': 199.155517578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98678589, -0.14793396, 0.06590271]), + 'left_gaze_origin': array([-3.15716863, 3.30435967, 0.10777131]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.45526123046875, + 'left_pupil_posn': array([-0.10641432, -0.05193758]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9828949 , -0.17555237, 0.05552673]), + 'right_gaze_origin': array([-3.21123528, -3.06513238, 0.08181 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.47314453125, + 'right_pupil_posn': array([-0.13497114, -0.11583424]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09272743761539459, + 'throttle_input': 0.20236514508724213, + 'timestamp': 677.5677743665874, + 'timestamp_carla': 677569, + 'timestamp_device': 120815, + 'timestamp_stream': 677.5677743665874, + 'transform': [array([ -1.55510521, -11.40768433, 0.01215395]), + array([-0.06119166, -1.9637717 , 0.01083375])]} +{'AngularVelocity': array([ 0.00348707, -0.00658932, 0.00190734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.492446899414062, + 'FR_Wheel_Angle': 28.29907989501953, + 'Location': array([ -5.03769827, -21.77564812, 0.17499107]), + 'Rotation': array([-0.07202434, 2.22624898, -0.01644898]), + 'Velocity': array([ 1.15847770e-05, 2.10204344e-05, -7.07833897e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.55126762, 14.21726894, 0.82593685]), + 'camera_rotation': array([-9.75290203, -6.63788891, 1.9487282 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1154.3917236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 17.45117188, -1355.02453613, 16.56529999]), + 'frame': 20933, + 'frame_number': 20933, + 'framesequence': 80032, + 'gaze_dir': array([ 0.98628235, -0.15319824, 0.06012726]), + 'gaze_origin': array([-3.18371511, 0.11460343, 0.09180374]), + 'gaze_valid': True, + 'gaze_vergence': 164.14585876464844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98681641, -0.14607239, 0.06951904]), + 'left_gaze_origin': array([-3.15687728, 3.30334949, 0.10525513]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4557342529296875, + 'left_pupil_posn': array([-0.10045868, -0.05493498]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98574829, -0.1603241 , 0.05073547]), + 'right_gaze_origin': array([-3.21055317, -3.07414246, 0.07835236]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.344512939453125, + 'right_pupil_posn': array([-0.12807065, -0.11710978]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09232459962368011, + 'throttle_input': 0.21031509339809418, + 'timestamp': 677.601741168648, + 'timestamp_carla': 677603, + 'timestamp_device': 120848, + 'timestamp_stream': 677.601741168648, + 'transform': [array([ -1.53728116, -11.37812805, 0.0124201 ]), + array([-0.06103457, -2.02954507, 0.00964357])]} +{'AngularVelocity': array([-0.00212279, 0.00261362, 0.0027491 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.156923294067383, + 'FR_Wheel_Angle': 29.53727149963379, + 'Location': array([ -5.03769779, -21.77565193, 0.17498882]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([2.20965867e-05, 3.00320226e-05, 1.39972599e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.53375244, 14.12656975, 0.79613954]), + 'camera_rotation': array([-9.82449532, -7.48621893, 2.01171374]), + 'current_gear_input': False, + 'focus_actor_dist': 1154.8421630859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 24.1078186 , -1353.47302246, 16.55817413]), + 'frame': 20934, + 'frame_number': 20934, + 'framesequence': 80036, + 'gaze_dir': array([ 0.98707581, -0.14597321, 0.06439972]), + 'gaze_origin': array([-3.18303847, 0.10699845, 0.09488678]), + 'gaze_valid': True, + 'gaze_vergence': 156.6894989013672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98788452, -0.13597107, 0.07460022]), + 'left_gaze_origin': array([-3.15756083, 3.29803038, 0.10973969]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3975677490234375, + 'left_pupil_posn': array([-0.09529477, -0.05077219]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98626709, -0.15597534, 0.05419922]), + 'right_gaze_origin': array([-3.20851612, -3.08403325, 0.08003388]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.340240478515625, + 'right_pupil_posn': array([-0.11779422, -0.11369932]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09234290570020676, + 'throttle_input': 0.2222171425819397, + 'timestamp': 677.6349580660462, + 'timestamp_carla': 677636, + 'timestamp_device': 120881, + 'timestamp_stream': 677.6349580660462, + 'transform': [array([ -1.51950467, -11.34846973, 0.01265427]), + array([-0.06085015, -2.09494448, 0.00863648])]} +{'AngularVelocity': array([-0.00060013, 0.00060709, -0.00078611]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.35869789123535, + 'FR_Wheel_Angle': 31.358680725097656, + 'Location': array([ -5.03769684, -21.77565384, 0.17500728]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 3.31350589e-06, -7.78835238e-06, 6.43578474e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.51161289, 14.03752708, 0.80449522]), + 'camera_rotation': array([-9.90406704, -8.17147636, 2.27153301]), + 'current_gear_input': False, + 'focus_actor_dist': 1186.712158203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 43.38775635, -1322.70507812, 16.52991486]), + 'frame': 20935, + 'frame_number': 20935, + 'framesequence': 80040, + 'gaze_dir': array([ 0.98950958, -0.13405609, 0.05243683]), + 'gaze_origin': array([-3.17772293, 0.10166015, 0.09469453]), + 'gaze_valid': True, + 'gaze_vergence': 256.9783630371094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99067688, -0.12367249, 0.05691528]), + 'left_gaze_origin': array([-3.16876984, 3.29349828, 0.11038056]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3999481201171875, + 'left_pupil_posn': array([-0.08825076, -0.05461168]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98834229, -0.1444397 , 0.04795837]), + 'right_gaze_origin': array([-3.18667626, -3.09017801, 0.07900849]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3856964111328125, + 'right_pupil_posn': array([-0.10950011, -0.11628425]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09283731132745743, + 'throttle_input': 0.23411917686462402, + 'timestamp': 677.6685096658766, + 'timestamp_carla': 677669, + 'timestamp_device': 120915, + 'timestamp_stream': 677.6685096658766, + 'transform': [array([ -1.5010016 , -11.31772041, 0.01287277]), + array([-0.06060427, -2.16289854, 0.00769043])]} +{'AngularVelocity': array([-2.43444709e-04, 2.10712227e-04, -7.77822970e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.387632369995117, + 'FR_Wheel_Angle': 32.97372055053711, + 'Location': array([ -5.03769732, -21.77565384, 0.17503619]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 3.68661699e-06, -2.21912629e-07, 2.32965438e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.47176933, 13.97285652, 0.83783013]), + 'camera_rotation': array([-9.71580696, -8.7951231 , 2.40216041]), + 'current_gear_input': False, + 'focus_actor_dist': 1046.6793212890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ 1.99127197, -1454.03466797, 16.61523438]), + 'frame': 20936, + 'frame_number': 20936, + 'framesequence': 80044, + 'gaze_dir': array([ 0.99061584, -0.12241364, 0.05883789]), + 'gaze_origin': array([-3.22563934, 0.09760132, 0.10028076]), + 'gaze_valid': True, + 'gaze_vergence': 162.86985778808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99134827, -0.11175537, 0.06861877]), + 'left_gaze_origin': array([-3.20208883, 3.28927159, 0.11510468]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5141448974609375, + 'left_pupil_posn': array([-0.08177185, -0.05719519]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98988342, -0.1330719 , 0.04905701]), + 'right_gaze_origin': array([-3.24919009, -3.094069 , 0.08545685]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.380157470703125, + 'right_pupil_posn': array([-0.10226631, -0.11943889]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0937894880771637, + 'throttle_input': 0.2380865216255188, + 'timestamp': 677.7007667683065, + 'timestamp_carla': 677702, + 'timestamp_device': 120948, + 'timestamp_stream': 677.7007667683065, + 'transform': [array([ -1.48226285, -11.28740311, 0.01308112]), + array([-0.06033789, -2.23187876, 0.00683595])]} +{'AngularVelocity': array([-5.72921672e-05, 4.08247906e-05, -8.46525381e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.359439849853516, + 'FR_Wheel_Angle': 34.5092887878418, + 'Location': array([ -5.03769779, -21.77565384, 0.17501885]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 3.28692590e-06, -2.69537566e-07, -2.67921314e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.46531773, 13.90355682, 0.83748823]), + 'camera_rotation': array([-9.52395344, -9.43340302, 2.45061135]), + 'current_gear_input': False, + 'focus_actor_dist': 1139.484619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 30.72280884, -1361.84301758, 16.55456543]), + 'frame': 20937, + 'frame_number': 20937, + 'framesequence': 80048, + 'gaze_dir': array([ 0.99169922, -0.11807251, 0.05041504]), + 'gaze_origin': array([-3.19994211, 0.08984986, 0.09570008]), + 'gaze_valid': True, + 'gaze_vergence': 507.70196533203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99220276, -0.11286926, 0.05276489]), + 'left_gaze_origin': array([-3.22621942, 3.28537154, 0.1212494 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.415313720703125, + 'left_pupil_posn': array([-0.07594436, -0.0577544 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99119568, -0.12327576, 0.04806519]), + 'right_gaze_origin': array([-3.17366505, -3.10567188, 0.07015076]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2852630615234375, + 'right_pupil_posn': array([-0.09529662, -0.12141263]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09510789066553116, + 'throttle_input': 0.2380865216255188, + 'timestamp': 677.7339107654989, + 'timestamp_carla': 677735, + 'timestamp_device': 120981, + 'timestamp_stream': 677.7339107654989, + 'transform': [array([ -1.46218777, -11.25527763, 0.01330932]), + array([-0.05996223, -2.30565882, 0.00585938])]} +{'AngularVelocity': array([ 7.29540261e-06, -2.04166486e-06, -9.14017983e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.884065628051758, + 'FR_Wheel_Angle': 35.23990249633789, + 'Location': array([ -5.03769779, -21.77565384, 0.17500626]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 3.85621570e-06, -1.89589329e-07, 5.18954708e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.47415924, 13.84309959, 0.82383007]), + 'camera_rotation': array([-9.44813156, -9.99660301, 2.44648051]), + 'current_gear_input': False, + 'focus_actor_dist': 1084.74755859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 22.69067383, -1413.75744629, 16.58068848]), + 'frame': 20938, + 'frame_number': 20938, + 'framesequence': 80052, + 'gaze_dir': array([ 0.99239349, -0.10905457, 0.05524445]), + 'gaze_origin': array([-3.20349145, 0.08680268, 0.09140473]), + 'gaze_valid': True, + 'gaze_vergence': 79.38349914550781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99217224, -0.10461426, 0.06803894]), + 'left_gaze_origin': array([-3.22788095, 3.28149128, 0.12056427]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.32208251953125, + 'left_pupil_posn': array([-0.06988752, -0.0604043 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99261475, -0.11349487, 0.04244995]), + 'right_gaze_origin': array([-3.17910171, -3.10788584, 0.06224518]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.24603271484375, + 'right_pupil_posn': array([-0.09100866, -0.12226391]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09670095145702362, + 'throttle_input': 0.2380865216255188, + 'timestamp': 677.7679190672934, + 'timestamp_carla': 677769, + 'timestamp_device': 121015, + 'timestamp_stream': 677.7679190672934, + 'transform': [array([ -1.4407202 , -11.22136974, 0.0135038 ]), + array([-0.05960023, -2.38445044, 0.00500489])]} +{'AngularVelocity': array([ 9.49102541e-05, 1.42573517e-05, -6.96630377e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.951093673706055, + 'FR_Wheel_Angle': 35.306549072265625, + 'Location': array([ -5.03769779, -21.77565384, 0.17495452]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 2.56507656e-06, -4.20008433e-07, -6.53627561e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.4733839 , 13.78406048, 0.82821238]), + 'camera_rotation': array([ -9.36014557, -10.56206226, 2.422961 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1142.9156494140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 43.33969116, -1355.43591309, 16.53986359]), + 'frame': 20939, + 'frame_number': 20939, + 'framesequence': 80056, + 'gaze_dir': array([ 0.99315643, -0.09828949, 0.06157684]), + 'gaze_origin': array([-3.23698068, 0.08364258, 0.09944077]), + 'gaze_valid': True, + 'gaze_vergence': 77.29524230957031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99278259, -0.09417725, 0.07415771]), + 'left_gaze_origin': array([-3.2683351 , 3.27874017, 0.13147278]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.31353759765625, + 'left_pupil_posn': array([-0.06459242, -0.05785513]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99353027, -0.10240173, 0.04899597]), + 'right_gaze_origin': array([-3.20562601, -3.11145496, 0.06740876]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.274383544921875, + 'right_pupil_posn': array([-0.0846839 , -0.12158954]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09897153079509735, + 'throttle_input': 0.24205386638641357, + 'timestamp': 677.8003820665181, + 'timestamp_carla': 677801, + 'timestamp_device': 121048, + 'timestamp_stream': 677.8003820665181, + 'transform': [array([ -1.41941893, -11.18818855, 0.01365801]), + array([-0.0592314 , -2.46246195, 0.00439453])]} +{'AngularVelocity': array([-1.51937420e-04, 2.41965008e-05, -8.53228448e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.951093673706055, + 'FR_Wheel_Angle': 35.306549072265625, + 'Location': array([ -5.03769779, -21.77565384, 0.17499943]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 3.43062902e-06, -1.13599818e-07, 1.29698048e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.47426319, 13.70898056, 0.82352757]), + 'camera_rotation': array([ -9.32730579, -11.10826969, 2.47559094]), + 'current_gear_input': False, + 'focus_actor_dist': 1227.8798828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 70.80892944, -1270.8605957 , 16.48892975]), + 'frame': 20940, + 'frame_number': 20940, + 'framesequence': 80060, + 'gaze_dir': array([ 0.99377441, -0.09902191, 0.05021667]), + 'gaze_origin': array([-3.13919449, 0.0753952 , 0.07520295]), + 'gaze_valid': True, + 'gaze_vergence': 379.0093078613281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99465942, -0.09126282, 0.04811096]), + 'left_gaze_origin': array([-3.09793401, 3.26925516, 0.08075409]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.267547607421875, + 'left_pupil_posn': array([-0.05806357, -0.05939472]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9928894 , -0.10678101, 0.05232239]), + 'right_gaze_origin': array([-3.18045497, -3.11846471, 0.0696518 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1867218017578125, + 'right_pupil_posn': array([-0.07914984, -0.12422419]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1014801487326622, + 'throttle_input': 0.26189059019088745, + 'timestamp': 677.8355206660926, + 'timestamp_carla': 677836, + 'timestamp_device': 121081, + 'timestamp_stream': 677.8355206660926, + 'transform': [array([ -1.39497828, -11.15150833, 0.01375566]), + array([-0.05880792, -2.55214262, 0.00393678])]} +{'AngularVelocity': array([-7.16935119e-06, 1.60911095e-05, -8.52812263e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.007831573486328, + 'FR_Wheel_Angle': 35.42191696166992, + 'Location': array([ -5.03769779, -21.77565384, 0.17499508]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 3.49451784e-06, -2.45231206e-07, 1.89726910e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.49858952, 13.61858177, 0.82166624]), + 'camera_rotation': array([ -9.28779984, -11.69075298, 2.5677278 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1105.9725341796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 45.10244751, -1387.7644043 , 16.54942322]), + 'frame': 20941, + 'frame_number': 20941, + 'framesequence': 80064, + 'gaze_dir': array([ 0.99357605, -0.09488678, 0.06082916]), + 'gaze_origin': array([-3.11150455, 0.06961212, 0.06052857]), + 'gaze_valid': True, + 'gaze_vergence': 300.781005859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99398804, -0.08747864, 0.06570435]), + 'left_gaze_origin': array([-3.05214572, 3.26289678, 0.0643097 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2683258056640625, + 'left_pupil_posn': array([-0.05179763, -0.06079447]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99316406, -0.10229492, 0.05595398]), + 'right_gaze_origin': array([-3.17086363, -3.12367272, 0.05674744]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.127685546875, + 'right_pupil_posn': array([-0.07445979, -0.12502325]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10426343977451324, + 'throttle_input': 0.269825279712677, + 'timestamp': 677.8670577667654, + 'timestamp_carla': 677868, + 'timestamp_device': 121115, + 'timestamp_stream': 677.8670577667654, + 'transform': [array([ -1.37202358, -11.11770153, 0.01388944]), + array([-0.05828883, -2.63610029, 0.00347901])]} +{'AngularVelocity': array([ 1.41168505e-06, 1.12567159e-05, -7.58975193e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.109392166137695, + 'FR_Wheel_Angle': 35.56419372558594, + 'Location': array([ -5.03769779, -21.77565384, 0.17497951]), + 'Rotation': array([-0.07222924, 2.22625303, -0.01626587]), + 'Velocity': array([ 2.82417045e-06, -3.00862013e-07, -4.26343438e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.5073719 , 13.51815605, 0.83657557]), + 'camera_rotation': array([ -9.1332674 , -12.32366848, 2.69504142]), + 'current_gear_input': False, + 'focus_actor_dist': 1234.3509521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 95.89431763, -1264.72424316, 16.46201324]), + 'frame': 20942, + 'frame_number': 20942, + 'framesequence': 80068, + 'gaze_dir': array([ 0.99397278, -0.09919739, 0.04544067]), + 'gaze_origin': array([-3.19790888, 0.08370514, 0.08930054]), + 'gaze_valid': True, + 'gaze_vergence': 217.33868408203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99430847, -0.09240723, 0.05282593]), + 'left_gaze_origin': array([-3.23628569, 3.27918124, 0.1186142 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17242431640625, + 'left_pupil_posn': array([-0.06588721, -0.0643028 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99363708, -0.10598755, 0.03805542]), + 'right_gaze_origin': array([-3.15953231, -3.11177063, 0.05998688]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1077423095703125, + 'right_pupil_posn': array([-0.08442873, -0.12496197]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10686361789703369, + 'throttle_input': 0.2737926244735718, + 'timestamp': 677.9005403667688, + 'timestamp_carla': 677902, + 'timestamp_device': 121148, + 'timestamp_stream': 677.9005403667688, + 'transform': [array([ -1.34638572, -11.08089828, 0.01401529]), + array([-0.05779706, -2.72981238, 0.00296021])]} +{'AngularVelocity': array([-0.09606614, 0.02537359, 0.03476731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.10823631286621, + 'FR_Wheel_Angle': 35.560367584228516, + 'Location': array([ -5.0380969 , -21.77586555, 0.17499085]), + 'Rotation': array([-0.07222924, 2.2237761 , -0.01599121]), + 'Velocity': array([-1.51424473e-02, -1.17711276e-02, -3.98349766e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.51812172, 13.41123199, 0.85601914]), + 'camera_rotation': array([ -8.9380188 , -12.89091873, 2.77616811]), + 'current_gear_input': False, + 'focus_actor_dist': 1096.013916015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 67.74639893, -1398.77563477, 16.53086853]), + 'frame': 20943, + 'frame_number': 20943, + 'framesequence': 80072, + 'gaze_dir': array([ 0.9842453 , -0.17012024, 0.04703522]), + 'gaze_origin': array([-3.19719505, 0.13097458, 0.08018494]), + 'gaze_valid': True, + 'gaze_vergence': 220.18089294433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98497009, -0.16397095, 0.05419922]), + 'left_gaze_origin': array([-3.18379068, 3.32132292, 0.09660339]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.232574462890625, + 'left_pupil_posn': array([-0.11889452, -0.06945956]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98352051, -0.17626953, 0.03987122]), + 'right_gaze_origin': array([-3.21059895, -3.05937362, 0.06376648]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2404327392578125, + 'right_pupil_posn': array([-0.14482808, -0.13196194]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11010468751192093, + 'throttle_input': 0.2737926244735718, + 'timestamp': 677.934551667422, + 'timestamp_carla': 677936, + 'timestamp_device': 121181, + 'timestamp_stream': 677.934551667422, + 'transform': [array([ -1.31886375, -11.04252434, 0.01414613]), + array([-5.72847947e-02, -2.83034086e+00, 2.41089216e-03])]} +{'AngularVelocity': array([-0.10258182, 0.0312719 , 0.08963369]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.12498664855957, + 'FR_Wheel_Angle': 35.592472076416016, + 'Location': array([ -5.03638887, -21.77539062, 0.17499012]), + 'Rotation': array([-0.07205166, 2.24411678, -0.01617432]), + 'Velocity': array([-9.98948608e-03, -9.52011999e-03, -1.73664084e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.5165081 , 13.28065681, 0.86539352]), + 'camera_rotation': array([ -8.79085636, -13.4899416 , 2.80567026]), + 'current_gear_input': False, + 'focus_actor_dist': 1207.6082763671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 199.56768799, -1328.67578125, 16.37596893]), + 'frame': 20944, + 'frame_number': 20944, + 'framesequence': 80076, + 'gaze_dir': array([ 0.98810577, -0.14311218, 0.05337524]), + 'gaze_origin': array([-3.20989084, 0.13128969, 0.08229218]), + 'gaze_valid': True, + 'gaze_vergence': 146.0800018310547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98945618, -0.12979126, 0.06402588]), + 'left_gaze_origin': array([-3.24820423, 3.31864953, 0.1159195 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.239166259765625, + 'left_pupil_posn': array([-0.1109339 , -0.06726277]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98675537, -0.15643311, 0.04272461]), + 'right_gaze_origin': array([-3.17157769, -3.05607009, 0.04866486]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2573699951171875, + 'right_pupil_posn': array([-0.13546735, -0.13105667]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11286965757608414, + 'throttle_input': 0.27775996923446655, + 'timestamp': 677.9671839661896, + 'timestamp_carla': 677968, + 'timestamp_device': 121215, + 'timestamp_stream': 677.9671839661896, + 'transform': [array([ -1.29094696, -11.00481415, 0.01425509]), + array([-5.67656979e-02, -2.93229318e+00, 2.01416551e-03])]} +{'AngularVelocity': array([-0.10160895, 0.03108281, 0.00239282]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.134197235107422, + 'FR_Wheel_Angle': 35.609580993652344, + 'Location': array([ -5.03517103, -21.77501869, 0.1749942 ]), + 'Rotation': array([-0.07260491, 2.25867772, -0.01565552]), + 'Velocity': array([-1.72738545e-02, -1.21802902e-02, 5.96046448e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.53213501, 13.14530087, 0.86348128]), + 'camera_rotation': array([ -8.74822235, -14.01120186, 2.83889341]), + 'current_gear_input': False, + 'focus_actor_dist': 1300.0579833984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 221.44854736, -1232.06176758, 16.32666016]), + 'frame': 20945, + 'frame_number': 20945, + 'framesequence': 80080, + 'gaze_dir': array([ 0.98834991, -0.14627075, 0.0411377 ]), + 'gaze_origin': array([-3.24838638, 0.11849824, 0.09717255]), + 'gaze_valid': True, + 'gaze_vergence': 122.70523834228516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9875946 , -0.1491394 , 0.04910278]), + 'left_gaze_origin': array([-3.29291868, 3.3130877 , 0.13110657]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2176666259765625, + 'left_pupil_posn': array([-0.1030336 , -0.06857264]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98910522, -0.1434021 , 0.03317261]), + 'right_gaze_origin': array([-3.20385432, -3.07609129, 0.06323852]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1194305419921875, + 'right_pupil_posn': array([-0.12836623, -0.13243723]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11512192338705063, + 'throttle_input': 0.27775996923446655, + 'timestamp': 678.0012773685157, + 'timestamp_carla': 678002, + 'timestamp_device': 121248, + 'timestamp_stream': 678.0012773685157, + 'transform': [array([ -1.26024592, -10.96469688, 0.01428524]), + array([-5.63695468e-02, -3.04446220e+00, 1.89209240e-03])]} +{'AngularVelocity': array([-0.09781519, 0.02993699, -0.12647541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.14274024963379, + 'FR_Wheel_Angle': 35.61927032470703, + 'Location': array([ -5.03617573, -21.77535629, 0.17500076]), + 'Rotation': array([-0.07278932, 2.24783516, -0.01535034]), + 'Velocity': array([-0.0277969 , -0.01597469, 0.00031929]), + 'brake_input': 0.0, + 'camera_location': array([-4.52775574, 13.0300312 , 0.87039417]), + 'camera_rotation': array([ -8.66361618, -14.45893955, 2.71625304]), + 'current_gear_input': False, + 'focus_actor_dist': 1158.77001953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 178.81109619, -1364.43615723, 16.40904236]), + 'frame': 20946, + 'frame_number': 20946, + 'framesequence': 80084, + 'gaze_dir': array([ 0.98944855, -0.1403656 , 0.03555298]), + 'gaze_origin': array([-3.22558069, 0.11276017, 0.09387665]), + 'gaze_valid': True, + 'gaze_vergence': 494.2722473144531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98953247, -0.13916016, 0.0381012 ]), + 'left_gaze_origin': array([-3.26312113, 3.30749822, 0.12360078]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1990814208984375, + 'left_pupil_posn': array([-0.09817338, -0.0680846 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98936462, -0.14157104, 0.03300476]), + 'right_gaze_origin': array([-3.18804049, -3.08197784, 0.06415253]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0393524169921875, + 'right_pupil_posn': array([-0.12091947, -0.13262594]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11682485789060593, + 'throttle_input': 0.28172731399536133, + 'timestamp': 678.0356430672109, + 'timestamp_carla': 678037, + 'timestamp_device': 121281, + 'timestamp_stream': 678.0356430672109, + 'transform': [array([ -1.22795749, -10.92338562, 0.01431412]), + array([-5.60621880e-02, -3.16229248e+00, 1.77002524e-03])]} +{'AngularVelocity': array([-0.10517649, 0.03080595, -0.22961542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.143203735351562, + 'FR_Wheel_Angle': 35.61921310424805, + 'Location': array([ -5.03950167, -21.77643776, 0.17499359]), + 'Rotation': array([-0.07284396, 2.2108891 , -0.01519775]), + 'Velocity': array([-0.03842937, -0.02067791, -0.00017692]), + 'brake_input': 0.0, + 'camera_location': array([-4.54532433, 12.90707302, 0.90417761]), + 'camera_rotation': array([ -8.65721607, -14.78948498, 2.69298649]), + 'current_gear_input': False, + 'focus_actor_dist': 1106.7764892578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 161.30789185, -1409.30688477, 16.44207764]), + 'frame': 20947, + 'frame_number': 20947, + 'framesequence': 80088, + 'gaze_dir': array([ 0.98949432, -0.1367569 , 0.04547882]), + 'gaze_origin': array([-3.20826125, 0.1057808 , 0.08473664]), + 'gaze_valid': True, + 'gaze_vergence': 98.87740325927734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98951721, -0.13314819, 0.05578613]), + 'left_gaze_origin': array([-3.22008848, 3.29999852, 0.11059876]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1647186279296875, + 'left_pupil_posn': array([-0.0920977 , -0.06799412]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98947144, -0.1403656 , 0.03517151]), + 'right_gaze_origin': array([-3.19643426, -3.08843708, 0.05887452]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.990020751953125, + 'right_pupil_posn': array([-0.11441666, -0.13154638]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11819818615913391, + 'throttle_input': 0.28172731399536133, + 'timestamp': 678.0694106668234, + 'timestamp_carla': 678070, + 'timestamp_device': 121315, + 'timestamp_stream': 678.0694106668234, + 'transform': [array([ -1.1948688 , -10.88182068, 0.01437713]), + array([-5.57821505e-02, -3.28286910e+00, 1.52588170e-03])]} +{'AngularVelocity': array([-0.08341515, 0.12675646, -2.0506072 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.06453514099121, + 'FR_Wheel_Angle': 35.46613311767578, + 'Location': array([ -5.05339241, -21.7800312 , 0.17505656]), + 'Rotation': array([-0.07851985, 2.07258034, -0.01092529]), + 'Velocity': array([-0.21378165, -0.0583959 , 0.00044641]), + 'brake_input': 0.0, + 'camera_location': array([-4.56592369, 12.79186058, 0.92123139]), + 'camera_rotation': array([ -8.62251186, -15.04520035, 2.6803329 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1217.1005859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 213.64309692, -1306.58276367, 16.35430908]), + 'frame': 20948, + 'frame_number': 20948, + 'framesequence': 80092, + 'gaze_dir': array([ 0.98899841, -0.13828278, 0.05001068]), + 'gaze_origin': array([-3.19924402, 0.10185701, 0.0823494 ]), + 'gaze_valid': True, + 'gaze_vergence': 83.73811340332031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98913574, -0.13217163, 0.06414795]), + 'left_gaze_origin': array([-3.20603657, 3.29478598, 0.10778503]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.25128173828125, + 'left_pupil_posn': array([-0.08976614, -0.06707394]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98886108, -0.14439392, 0.03587341]), + 'right_gaze_origin': array([-3.19245148, -3.09107232, 0.05691376]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.062774658203125, + 'right_pupil_posn': array([-0.11223572, -0.12937653]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11887570470571518, + 'throttle_input': 0.28172731399536133, + 'timestamp': 678.100260168314, + 'timestamp_carla': 678101, + 'timestamp_device': 121348, + 'timestamp_stream': 678.100260168314, + 'transform': [array([ -1.16334343, -10.84275723, 0.01452705]), + array([-5.55430949e-02, -3.39756870e+00, 9.76562442e-04])]} +{'AngularVelocity': array([-0.10574314, 0.10984689, -4.56474686]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.977436065673828, + 'FR_Wheel_Angle': 35.303924560546875, + 'Location': array([ -5.1026907 , -21.79487801, 0.17510898]), + 'Rotation': array([-0.08078064, 1.49241185, -0.00717163]), + 'Velocity': array([-0.36627471, -0.12546018, 0.00095112]), + 'brake_input': 0.0, + 'camera_location': array([-4.57176304, 12.69306564, 0.9231801 ]), + 'camera_rotation': array([ -8.55798721, -15.2161274 , 2.55971384]), + 'current_gear_input': False, + 'focus_actor_dist': 1285.7496337890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 253.27212524, -1244.31103516, 16.29760742]), + 'frame': 20949, + 'frame_number': 20949, + 'framesequence': 80096, + 'gaze_dir': array([ 0.99000549, -0.13245392, 0.04606628]), + 'gaze_origin': array([-3.20342493, 0.10088044, 0.08405305]), + 'gaze_valid': True, + 'gaze_vergence': 62.90459060668945, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98988342, -0.12867737, 0.05958557]), + 'left_gaze_origin': array([-3.20831919, 3.29349375, 0.10895081]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.188690185546875, + 'left_pupil_posn': array([-0.08602524, -0.06782269]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99012756, -0.13623047, 0.032547 ]), + 'right_gaze_origin': array([-3.19853091, -3.09173298, 0.05915527]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0550537109375, + 'right_pupil_posn': array([-0.11053067, -0.13052189]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11887570470571518, + 'throttle_input': 0.28172731399536133, + 'timestamp': 678.1334036663175, + 'timestamp_carla': 678134, + 'timestamp_device': 121381, + 'timestamp_stream': 678.1334036663175, + 'transform': [array([ -1.12844789, -10.7996912 , 0.01464291]), + array([-5.54201528e-02, -3.52417946e+00, 4.57771879e-04])]} +{'AngularVelocity': array([-0.0489003 , -0.02611353, -6.84096146]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.82992935180664, + 'FR_Wheel_Angle': 34.8534049987793, + 'Location': array([ -5.21705914, -21.82840729, 0.17522819]), + 'Rotation': array([-0.08121094, 0.1744951 , -0.00576782]), + 'Velocity': array([-0.5250023 , -0.19546737, 0.00066394]), + 'brake_input': 0.0, + 'camera_location': array([-4.57100677, 12.60481358, 0.92643142]), + 'camera_rotation': array([ -8.5590601 , -15.28933525, 2.48552608]), + 'current_gear_input': False, + 'focus_actor_dist': 1239.2720947265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 232.67453003, -1281.6184082 , 16.32794952]), + 'frame': 20950, + 'frame_number': 20950, + 'framesequence': 80100, + 'gaze_dir': array([ 0.99000549, -0.1316452 , 0.04891968]), + 'gaze_origin': array([-3.20122027, 0.10051499, 0.08344346]), + 'gaze_valid': True, + 'gaze_vergence': 84.0324478149414, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98994446, -0.12774658, 0.06060791]), + 'left_gaze_origin': array([-3.20998836, 3.29333496, 0.109906 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.14581298828125, + 'left_pupil_posn': array([-0.08571607, -0.06577754]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99006653, -0.13554382, 0.03723145]), + 'right_gaze_origin': array([-3.19245148, -3.09230518, 0.0569809 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0173187255859375, + 'right_pupil_posn': array([-0.1098581 , -0.13052189]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11887570470571518, + 'throttle_input': 0.28172731399536133, + 'timestamp': 678.1673557683825, + 'timestamp_carla': 678168, + 'timestamp_device': 121415, + 'timestamp_stream': 678.1673557683825, + 'transform': [array([ -1.09164488, -10.75447369, 0.01471763]), + array([-5.53586818e-02, -3.65733767e+00, 9.15594501e-05])]} +{'AngularVelocity': array([ 0.08245312, -0.07324882, -7.68780947]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.407907485961914, + 'FR_Wheel_Angle': 30.26704978942871, + 'Location': array([ -5.38288784, -21.86964607, 0.17537761]), + 'Rotation': array([-0.08328049, -1.59176648, -0.00802612]), + 'Velocity': array([-0.75433236, -0.21168764, 0.00105885]), + 'brake_input': 0.0, + 'camera_location': array([-4.59192371, 12.52085876, 0.94782597]), + 'camera_rotation': array([ -8.59627056, -15.33796406, 2.47145176]), + 'current_gear_input': False, + 'focus_actor_dist': 1274.1024169921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 251.70733643, -1246.9152832 , 16.29983521]), + 'frame': 20951, + 'frame_number': 20951, + 'framesequence': 80104, + 'gaze_dir': array([ 0.99124146, -0.12567902, 0.03991699]), + 'gaze_origin': array([-3.18395376, 0.09768525, 0.0851883 ]), + 'gaze_valid': True, + 'gaze_vergence': 365.9082336425781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99160767, -0.1214447 , 0.04429626]), + 'left_gaze_origin': array([-3.21000695, 3.29303932, 0.11012574]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.12457275390625, + 'left_pupil_posn': array([-0.08354586, -0.06615889]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99087524, -0.12991333, 0.03553772]), + 'right_gaze_origin': array([-3.15790105, -3.09766865, 0.06025086]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0698089599609375, + 'right_pupil_posn': array([-0.10416257, -0.12751627]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11876583099365234, + 'throttle_input': 0.28172731399536133, + 'timestamp': 678.2006657682359, + 'timestamp_carla': 678202, + 'timestamp_device': 121448, + 'timestamp_stream': 678.2006657682359, + 'transform': [array([ -1.05446744, -10.70897579, 0.01480071]), + array([-5.52972071e-02, -3.79148269e+00, -2.73202459e-04])]} +{'AngularVelocity': array([ 0.01171199, -0.04015137, -4.43230295]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.165863037109375, + 'FR_Wheel_Angle': 24.032316207885742, + 'Location': array([ -5.53340244, -21.89664459, 0.17546752]), + 'Rotation': array([-0.06808332, -2.94506884, -0.02374267]), + 'Velocity': array([-0.55720901, -0.10568139, 0.0011247 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.6160078 , 12.44990158, 0.95762646]), + 'camera_rotation': array([ -8.589324 , -15.42420006, 2.25751209]), + 'current_gear_input': False, + 'focus_actor_dist': 1150.7738037109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 195.16912842, -1351.87451172, 16.38845062]), + 'frame': 20952, + 'frame_number': 20952, + 'framesequence': 80108, + 'gaze_dir': array([ 0.99133301, -0.12496948, 0.03995514]), + 'gaze_origin': array([-3.18769479, 0.09741212, 0.08632278]), + 'gaze_valid': True, + 'gaze_vergence': 474.21124267578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99171448, -0.12086487, 0.04324341]), + 'left_gaze_origin': array([-3.21518564, 3.29263759, 0.11167756]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1185760498046875, + 'left_pupil_posn': array([-0.08303994, -0.06564367]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99095154, -0.1290741 , 0.03666687]), + 'right_gaze_origin': array([-3.1602037 , -3.09781361, 0.06096802]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.070648193359375, + 'right_pupil_posn': array([-0.10383964, -0.12784147]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11828974634408951, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.2344274669886, + 'timestamp_carla': 678235, + 'timestamp_device': 121481, + 'timestamp_stream': 678.2344274669886, + 'transform': [array([ -1.01580596, -10.66170406, 0.01486848]), + array([-5.52630574e-02, -3.93051100e+00, -5.87391900e-04])]} +{'AngularVelocity': array([-1.92048773e-02, 5.53440419e-04, -2.31204295e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.971508979797363, + 'FR_Wheel_Angle': 16.03795623779297, + 'Location': array([ -5.64224243, -21.90891838, 0.1755342 ]), + 'Rotation': array([-0.06448381, -3.70904613, -0.02282714]), + 'Velocity': array([-3.86333764e-01, -4.41020131e-02, 4.36210612e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.63502026, 12.36152649, 0.99567717]), + 'camera_rotation': array([ -8.48700142, -15.48574924, 2.26237011]), + 'current_gear_input': False, + 'focus_actor_dist': 1147.1953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 197.69094849, -1351.78076172, 16.38593292]), + 'frame': 20953, + 'frame_number': 20953, + 'framesequence': 80112, + 'gaze_dir': array([ 0.99172974, -0.12213898, 0.03894043]), + 'gaze_origin': array([-3.1924274 , 0.09705277, 0.08813019]), + 'gaze_valid': True, + 'gaze_vergence': 302.2568359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99182129, -0.12008667, 0.04316711]), + 'left_gaze_origin': array([-3.22462034, 3.29207468, 0.11523286]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0800933837890625, + 'left_pupil_posn': array([-0.08103544, -0.06564367]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99163818, -0.12419128, 0.03471375]), + 'right_gaze_origin': array([-3.16023421, -3.09796929, 0.06102753]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0355377197265625, + 'right_pupil_posn': array([-0.10345811, -0.12784147]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11673329770565033, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.2677183672786, + 'timestamp_carla': 678269, + 'timestamp_device': 121514, + 'timestamp_stream': 678.2677183672786, + 'transform': [array([ -0.97690457, -10.61388683, 0.01494275]), + array([-5.52972071e-02, -4.06986427e+00, -9.15237353e-04])]} +{'AngularVelocity': array([-4.37875688e-02, 7.38977268e-02, -3.31016527e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.703704357147217, + 'FR_Wheel_Angle': 0.693440854549408, + 'Location': array([ -5.65848017, -21.9100647 , 0.17552719]), + 'Rotation': array([-0.05987344, -3.78579855, -0.01907349]), + 'Velocity': array([6.92573740e-05, 3.40017490e-04, 4.28591993e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.6617136 , 12.26190662, 1.0192312 ]), + 'camera_rotation': array([ -8.43779659, -15.63151169, 2.21720028]), + 'current_gear_input': False, + 'focus_actor_dist': 1154.3560791015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 202.35195923, -1340.47717285, 16.37732697]), + 'frame': 20954, + 'frame_number': 20954, + 'framesequence': 80116, + 'gaze_dir': array([ 0.99424744, -0.07273865, 0.07765961]), + 'gaze_origin': array([-3.12733936, 0.05047989, 0.08690491]), + 'gaze_valid': True, + 'gaze_vergence': 229.5909423828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99446106, -0.06297302, 0.08401489]), + 'left_gaze_origin': array([-3.0688324 , 3.24037027, 0.09077149]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.129364013671875, + 'left_pupil_posn': array([-0.02979505, -0.04054844]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99403381, -0.08250427, 0.07130432]), + 'right_gaze_origin': array([-3.18584633, -3.1394105 , 0.08303833]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1306610107421875, + 'right_pupil_posn': array([-0.05475366, -0.10379195]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11405988037586212, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.3003003671765, + 'timestamp_carla': 678301, + 'timestamp_device': 121548, + 'timestamp_stream': 678.3003003671765, + 'transform': [array([ -0.93835628, -10.5657959 , 0.01502747]), + array([-5.54543026e-02, -4.20724630e+00, -1.28407194e-03])]} +{'AngularVelocity': array([-1.23080779e-02, 2.05453411e-02, -1.72945438e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.8444770574569702, + 'FR_Wheel_Angle': -1.665923833847046, + 'Location': array([ -5.65854549, -21.91008759, 0.17558499]), + 'Rotation': array([-0.06927177, -3.78579831, -0.01272583]), + 'Velocity': array([ 1.62636479e-05, -9.48924537e-07, 1.59252566e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.67990494, 12.16518116, 1.03690076]), + 'camera_rotation': array([ -8.38843536, -15.8782692 , 2.06401753]), + 'current_gear_input': False, + 'focus_actor_dist': 2037.66064453125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 510.55709839, -502.24523926, 0. ]), + 'frame': 20955, + 'frame_number': 20955, + 'framesequence': 80120, + 'gaze_dir': array([ 0.99504852, -0.06435394, 0.07473755]), + 'gaze_origin': array([-3.15054655, 0.04214402, 0.09892502]), + 'gaze_valid': True, + 'gaze_vergence': 283.8066101074219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99568176, -0.05325317, 0.07583618]), + 'left_gaze_origin': array([-3.08172631, 3.2306838 , 0.09936982]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.23486328125, + 'left_pupil_posn': array([-0.02082092, -0.03646564]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99441528, -0.07545471, 0.07363892]), + 'right_gaze_origin': array([-3.21936655, -3.14639616, 0.09848022]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17938232421875, + 'right_pupil_posn': array([-0.04616165, -0.10227978]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11061739921569824, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.3340575657785, + 'timestamp_carla': 678335, + 'timestamp_device': 121581, + 'timestamp_stream': 678.3340575657785, + 'transform': [array([ -0.89829648, -10.51465034, 0.01507316]), + array([-5.57821505e-02, -4.34915829e+00, -1.55045092e-03])]} +{'AngularVelocity': array([-3.40520637e-03, 5.07918792e-03, -2.10164108e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.1213412284851074, + 'FR_Wheel_Angle': -2.0651259422302246, + 'Location': array([ -5.65856361, -21.91009712, 0.17559174]), + 'Rotation': array([-0.07165551, -3.78579831, -0.01092529]), + 'Velocity': array([ 5.60777244e-06, -3.90524491e-07, -1.58651470e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.67586708, 12.05556393, 1.07621872]), + 'camera_rotation': array([ -8.1865139 , -16.08533287, 1.93662274]), + 'current_gear_input': False, + 'focus_actor_dist': 1741.093994140625, + 'focus_actor_name': 'Road_Sidewalk_Town05_207', + 'focus_actor_pt': array([ 390.09683228, -767.24230957, 15.23375702]), + 'frame': 20956, + 'frame_number': 20956, + 'framesequence': 80124, + 'gaze_dir': array([ 0.99505615, -0.06427765, 0.07447815]), + 'gaze_origin': array([-3.1222229 , 0.03459549, 0.08641129]), + 'gaze_valid': True, + 'gaze_vergence': 206.5380859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99523926, -0.05325317, 0.08148193]), + 'left_gaze_origin': array([-3.08145618, 3.22462964, 0.09606934]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15692138671875, + 'left_pupil_posn': array([-0.01666033, -0.04075611]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99487305, -0.07530212, 0.06747437]), + 'right_gaze_origin': array([-3.16299009, -3.15543818, 0.07675324]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.196502685546875, + 'right_pupil_posn': array([-0.0407486 , -0.10467958]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10666219145059586, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.3666912652552, + 'timestamp_carla': 678368, + 'timestamp_device': 121614, + 'timestamp_stream': 678.3666912652552, + 'transform': [array([ -0.85960507, -10.46383667, 0.01513225]), + array([-5.61851338e-02, -4.48527813e+00, -1.83731958e-03])]} +{'AngularVelocity': array([-0.00084424, 0.0025281 , 0.00961944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.019561767578125, + 'FR_Wheel_Angle': -1.9808262586593628, + 'Location': array([ -5.65985203, -21.90999413, 0.17561489]), + 'Rotation': array([-0.07287128, -3.78494358, -0.01046753]), + 'Velocity': array([-0.01442708, 0.00125475, 0.00026077]), + 'brake_input': 0.0, + 'camera_location': array([-4.65939331, 11.9878006 , 1.09444356]), + 'camera_rotation': array([ -8.05383778, -16.30853081, 1.60308301]), + 'current_gear_input': False, + 'focus_actor_dist': 2053.331298828125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.27583069e+02, -4.80912354e+02, -1.52587891e-05]), + 'frame': 20957, + 'frame_number': 20957, + 'framesequence': 80128, + 'gaze_dir': array([ 0.9956131 , -0.05697632, 0.07293701]), + 'gaze_origin': array([-3.12365961, 0.03236313, 0.0863678 ]), + 'gaze_valid': True, + 'gaze_vergence': 212.81121826171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99580383, -0.04553223, 0.07933044]), + 'left_gaze_origin': array([-3.07409215, 3.2228868 , 0.09482117]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22589111328125, + 'left_pupil_posn': array([-0.01307923, -0.04043913]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99542236, -0.06842041, 0.06654358]), + 'right_gaze_origin': array([-3.17322731, -3.15816069, 0.07791443]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2121124267578125, + 'right_pupil_posn': array([-0.03608596, -0.10661077]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10257881879806519, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.3999951668084, + 'timestamp_carla': 678401, + 'timestamp_device': 121648, + 'timestamp_stream': 678.3999951668084, + 'transform': [array([ -0.82036954, -10.41059208, 0.01516497]), + array([-5.66700771e-02, -4.62225676e+00, -2.04905123e-03])]} +{'AngularVelocity': array([-1.43868427e-04, 1.24820636e-03, -2.35959706e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.418927550315857, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -5.66109324, -21.90990257, 0.17560634]), + 'Rotation': array([-0.07202434, -3.78408885, -0.01028442]), + 'Velocity': array([ 3.33627668e-06, -1.56265443e-07, -1.69953601e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.64691639, 11.94071865, 1.10185111]), + 'camera_rotation': array([ -8.10636902, -16.37082481, 1.45188999]), + 'current_gear_input': False, + 'focus_actor_dist': 2058.135498046875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.29313110e+02, -4.70432983e+02, -3.05175781e-05]), + 'frame': 20958, + 'frame_number': 20958, + 'framesequence': 80132, + 'gaze_dir': array([ 0.99567413, -0.05567932, 0.07328796]), + 'gaze_origin': array([-3.12780857, 0.03197327, 0.08781967]), + 'gaze_valid': True, + 'gaze_vergence': 236.39100646972656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99589539, -0.04478455, 0.07862854]), + 'left_gaze_origin': array([-3.0761826 , 3.22255421, 0.09559937]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.225799560546875, + 'left_pupil_posn': array([-0.01222348, -0.03983068]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99545288, -0.0665741 , 0.06794739]), + 'right_gaze_origin': array([-3.1794343 , -3.15860772, 0.08003998]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.18682861328125, + 'right_pupil_posn': array([-0.0354259 , -0.10661077]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09715873748064041, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.4348587654531, + 'timestamp_carla': 678436, + 'timestamp_device': 121681, + 'timestamp_stream': 678.4348587654531, + 'transform': [array([ -0.77997863, -10.35339832, 0.0151415 ]), + array([-5.73462658e-02, -4.76193190e+00, -2.08320282e-03])]} +{'AngularVelocity': array([0.00409984, 0.00501998, 0.02346582]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1137025356292725, + 'FR_Wheel_Angle': -1.0892895460128784, + 'Location': array([ -5.66301632, -21.90975571, 0.17561008]), + 'Rotation': array([-0.0726937 , -3.78354049, -0.01031494]), + 'Velocity': array([-1.67114250e-02, 1.73590239e-03, 5.57231906e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.65226555, 11.88552952, 1.13095939]), + 'camera_rotation': array([ -8.14351082, -16.34239388, 1.53780353]), + 'current_gear_input': False, + 'focus_actor_dist': 2035.20166015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.25231079e+02, -4.87539062e+02, 1.52587891e-05]), + 'frame': 20959, + 'frame_number': 20959, + 'framesequence': 80136, + 'gaze_dir': array([ 0.99580383, -0.05283356, 0.0740509 ]), + 'gaze_origin': array([-3.1314187 , 0.03146668, 0.0889145 ]), + 'gaze_valid': True, + 'gaze_vergence': 274.14056396484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99575806, -0.04568481, 0.07972717]), + 'left_gaze_origin': array([-3.07729793, 3.22247338, 0.09559937]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2255401611328125, + 'left_pupil_posn': array([-0.00990003, -0.0398854 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99584961, -0.0599823 , 0.06837463]), + 'right_gaze_origin': array([-3.18553925, -3.1595397 , 0.08222962]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.176422119140625, + 'right_pupil_posn': array([-0.03502226, -0.10582781]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09031037241220474, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.4674026668072, + 'timestamp_carla': 678468, + 'timestamp_device': 121714, + 'timestamp_stream': 678.4674026668072, + 'transform': [array([ -0.7432785 , -10.29844189, 0.01517018]), + array([-5.81044145e-02, -4.88732576e+00, -2.25395733e-03])]} +{'AngularVelocity': array([0.00436439, 0.00766358, 0.02200379]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0470951795578003, + 'FR_Wheel_Angle': -1.0189836025238037, + 'Location': array([ -5.66517448, -21.90959167, 0.17561221]), + 'Rotation': array([-0.07248196, -3.78335643, -0.01031494]), + 'Velocity': array([-1.49896638e-02, 1.56255008e-03, -1.77288057e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.65409565, 11.85067749, 1.14447653]), + 'camera_rotation': array([ -8.10899162, -16.30081749, 1.28328109]), + 'current_gear_input': False, + 'focus_actor_dist': 2038.62548828125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 525.60864258, -477.28979492, 0. ]), + 'frame': 20960, + 'frame_number': 20960, + 'framesequence': 80140, + 'gaze_dir': array([ 0.99581146, -0.05382538, 0.07325745]), + 'gaze_origin': array([-3.13214874, 0.03071213, 0.08923493]), + 'gaze_valid': True, + 'gaze_vergence': 285.4046325683594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99580383, -0.04673767, 0.07865906]), + 'left_gaze_origin': array([-3.07883477, 3.22196221, 0.09649506]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2260284423828125, + 'left_pupil_posn': array([-0.00988233, -0.03976071]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99581909, -0.06091309, 0.06785583]), + 'right_gaze_origin': array([-3.18546295, -3.16053772, 0.0819748 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1793975830078125, + 'right_pupil_posn': array([-0.03470671, -0.10637915]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0839381068944931, + 'throttle_input': 0.2856946587562561, + 'timestamp': 678.5009490661323, + 'timestamp_carla': 678502, + 'timestamp_device': 121748, + 'timestamp_stream': 678.5009490661323, + 'transform': [array([ -0.70675993, -10.24018288, 0.01517677]), + array([-5.89923412e-02, -5.01035690e+00, -2.39055627e-03])]} +{'AngularVelocity': array([0.00444923, 0.01232489, 0.02469231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.9879323840141296, + 'FR_Wheel_Angle': -0.9609110951423645, + 'Location': array([ -5.66909981, -21.90928841, 0.17562412]), + 'Rotation': array([-0.07284396, -3.7824719 , -0.01031494]), + 'Velocity': array([-0.027903 , 0.0024751 , 0.00032083]), + 'brake_input': 0.0, + 'camera_location': array([-4.65288258, 11.81914043, 1.16911733]), + 'camera_rotation': array([ -8.06145287, -16.21557999, 1.11820829]), + 'current_gear_input': False, + 'focus_actor_dist': 2026.960693359375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 526.90356445, -484.30822754, 0. ]), + 'frame': 20961, + 'frame_number': 20961, + 'framesequence': 80144, + 'gaze_dir': array([ 0.9958725, -0.0539856, 0.0723877]), + 'gaze_origin': array([-3.13986754, 0.02881317, 0.08989182]), + 'gaze_valid': True, + 'gaze_vergence': 346.74444580078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99603271, -0.04641724, 0.07591248]), + 'left_gaze_origin': array([-3.09313369, 3.21982574, 0.09701691]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2677001953125, + 'left_pupil_posn': array([-0.00872618, -0.04174471]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99571228, -0.06155396, 0.06886292]), + 'right_gaze_origin': array([-3.1866014 , -3.16219974, 0.08276673]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17535400390625, + 'right_pupil_posn': array([-0.03345001, -0.10700703]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07630237936973572, + 'throttle_input': 0.2539559006690979, + 'timestamp': 678.5331005677581, + 'timestamp_carla': 678534, + 'timestamp_device': 121781, + 'timestamp_stream': 678.5331005677581, + 'transform': [array([ -0.67329621, -10.1826973 , 0.01520458]), + array([-5.99280782e-02, -5.12117672e+00, -2.58180825e-03])]} +{'AngularVelocity': array([0.01514197, 0.15499566, 0.02743135]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8011618852615356, + 'FR_Wheel_Angle': -0.7909584045410156, + 'Location': array([ -5.67785501, -21.90864182, 0.17563972]), + 'Rotation': array([-0.07568532, -3.78015208, -0.01037597]), + 'Velocity': array([-0.16372368, 0.01226775, 0.00024626]), + 'brake_input': 0.0, + 'camera_location': array([-4.65811157, 11.77769947, 1.19251037]), + 'camera_rotation': array([ -7.95171261, -16.10234642, 0.99919343]), + 'current_gear_input': False, + 'focus_actor_dist': 2021.56298828125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.27520752e+02, -4.83809692e+02, -1.52587891e-05]), + 'frame': 20962, + 'frame_number': 20962, + 'framesequence': 80148, + 'gaze_dir': array([ 0.99573517, -0.05156708, 0.07596588]), + 'gaze_origin': array([-3.1080513 , 0.02305679, 0.07842179]), + 'gaze_valid': True, + 'gaze_vergence': 342.71728515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99569702, -0.04571533, 0.08047485]), + 'left_gaze_origin': array([-3.05833769, 3.21504545, 0.0865799 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2349700927734375, + 'left_pupil_posn': array([-0.00387251, -0.04164052]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99577332, -0.05741882, 0.07145691]), + 'right_gaze_origin': array([-3.15776539, -3.16893148, 0.07026367]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.178253173828125, + 'right_pupil_posn': array([-0.02901369, -0.10870695]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06767784804105759, + 'throttle_input': 0.2380865216255188, + 'timestamp': 678.5669416673481, + 'timestamp_carla': 678568, + 'timestamp_device': 121814, + 'timestamp_stream': 678.5669416673481, + 'transform': [array([ -0.64030486, -10.12052441, 0.01516024]), + array([-6.11575097e-02, -5.22799683e+00, -2.55448604e-03])]} +{'AngularVelocity': array([-0.0086997 , -0.06988819, -0.10348502]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7927810549736023, + 'FR_Wheel_Angle': -0.7866095900535583, + 'Location': array([ -5.7881217 , -21.90061951, 0.17584544]), + 'Rotation': array([-0.09182506, -3.75677586, -0.01068115]), + 'Velocity': array([-6.16922259e-01, 4.56912667e-02, 3.61919403e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.65789986, 11.78406715, 1.18669617]), + 'camera_rotation': array([ -7.91375065, -16.05661392, 0.4289687 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2195.334716796875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 595.1373291 , -316.67590332, 0. ]), + 'frame': 20963, + 'frame_number': 20963, + 'framesequence': 80152, + 'gaze_dir': array([ 0.99397278, -0.0332489 , 0.10399628]), + 'gaze_origin': array([-3.07161045, 0.00912399, 0.08071442]), + 'gaze_valid': True, + 'gaze_vergence': 281.1054992675781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99478149, -0.02577209, 0.09864807]), + 'left_gaze_origin': array([-2.98434305, 3.20018005, 0.07828064]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3064422607421875, + 'left_pupil_posn': array([ 0.01220286, -0.02068543]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99316406, -0.04072571, 0.10934448]), + 'right_gaze_origin': array([-3.15887785, -3.18193221, 0.0831482 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.11981201171875, + 'right_pupil_posn': array([-0.01311278, -0.09375429]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058980073779821396, + 'throttle_input': 0.22618448734283447, + 'timestamp': 678.6010939665139, + 'timestamp_carla': 678602, + 'timestamp_device': 121848, + 'timestamp_stream': 678.6010939665139, + 'transform': [array([ -0.60957426, -10.05615616, 0.01506356]), + array([-6.24689050e-02, -5.32467842e+00, -2.30176747e-03])]} +{'AngularVelocity': array([-0.00139676, -0.01533867, 0.15868981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7905295491218567, + 'FR_Wheel_Angle': -0.782890260219574, + 'Location': array([ -5.97642279, -21.88694763, 0.17604133]), + 'Rotation': array([-0.09075955, -3.71057224, -0.01049805]), + 'Velocity': array([-0.97229695, 0.07177794, 0.00113176]), + 'brake_input': 0.0, + 'camera_location': array([-4.66443539, 11.81449509, 1.16758931]), + 'camera_rotation': array([ -8.01892185, -15.87639332, 0.25337166]), + 'current_gear_input': False, + 'focus_actor_dist': 3565.963134765625, + 'focus_actor_name': 'Road_Sidewalk_Town05_159', + 'focus_actor_pt': array([1101.96362305, 967.03344727, 15.10187531]), + 'frame': 20964, + 'frame_number': 20964, + 'framesequence': 80156, + 'gaze_dir': array([ 0.99214172, -0.02318573, 0.12262726]), + 'gaze_origin': array([-3.06998372e+00, 2.00500479e-03, 8.99299681e-02]), + 'gaze_valid': True, + 'gaze_vergence': 306.245849609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99163818, -0.01742554, 0.12776184]), + 'left_gaze_origin': array([-2.98939991, 3.19102955, 0.08816071]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2232666015625, + 'left_pupil_posn': array([ 0.02241838, -0.01225543]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99264526, -0.02894592, 0.11749268]), + 'right_gaze_origin': array([-3.15056777, -3.18701935, 0.09169923]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1329345703125, + 'right_pupil_posn': array([-0.0066883 , -0.07654667]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04964141175150871, + 'throttle_input': 0.21428243815898895, + 'timestamp': 678.633265465498, + 'timestamp_carla': 678634, + 'timestamp_device': 121881, + 'timestamp_stream': 678.633265465498, + 'transform': [array([-0.58330232, -9.99392223, 0.01498898]), + array([-6.37803003e-02, -5.40426493e+00, -2.06954032e-03])]} +{'AngularVelocity': array([ 0.00730238, -0.03738033, 0.49461144]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.5508736371994019, + 'FR_Wheel_Angle': -2.029254913330078, + 'Location': array([ -6.2403903 , -21.86790085, 0.17628704]), + 'Rotation': array([-0.08612185, -3.64157152, -0.01062012]), + 'Velocity': array([-1.21645641, 0.09288667, 0.00148397]), + 'brake_input': 0.0, + 'camera_location': array([-4.66855717, 11.83887863, 1.180426 ]), + 'camera_rotation': array([ -7.93499899, -15.76829815, 0.265439 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3679.68359375, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([1109.85180664, 1095.92163086, 72.80638123]), + 'frame': 20965, + 'frame_number': 20965, + 'framesequence': 80160, + 'gaze_dir': array([ 0.99205017, -0.02674866, 0.12258911]), + 'gaze_origin': array([-3.06922245e+00, 1.49383547e-03, 8.70613158e-02]), + 'gaze_valid': True, + 'gaze_vergence': 368.97808837890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99195862, -0.01887512, 0.12504578]), + 'left_gaze_origin': array([-2.98897576, 3.19163537, 0.08622437]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.238555908203125, + 'left_pupil_posn': array([ 0.02005708, -0.01253319]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99214172, -0.03462219, 0.12013245]), + 'right_gaze_origin': array([-3.14946914, -3.18864775, 0.08789826]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1669769287109375, + 'right_pupil_posn': array([-0.00613588, -0.07985198]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04231696575880051, + 'throttle_input': 0.21031509339809418, + 'timestamp': 678.6662802658975, + 'timestamp_carla': 678667, + 'timestamp_device': 121914, + 'timestamp_stream': 678.6662802658975, + 'transform': [array([-0.55894285, -9.92859745, 0.01487282]), + array([-6.50029033e-02, -5.47488403e+00, -1.68705278e-03])]} +{'AngularVelocity': array([ 0.01646398, -0.03953933, 1.98424673]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.7552103996276855, + 'FR_Wheel_Angle': -6.107234477996826, + 'Location': array([ -6.52172518, -21.84368324, 0.17649245]), + 'Rotation': array([-0.0740051 , -3.35781956, -0.01477051]), + 'Velocity': array([-1.16368639, 0.12803434, 0.00117333]), + 'brake_input': 0.0, + 'camera_location': array([-4.6981926 , 11.88770962, 1.17840958]), + 'camera_rotation': array([ -8.02779388, -15.6854744 , 0.07893999]), + 'current_gear_input': False, + 'focus_actor_dist': 3677.135009765625, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([1120.04602051, 1095.90258789, 78.17908478]), + 'frame': 20966, + 'frame_number': 20966, + 'framesequence': 80164, + 'gaze_dir': array([ 0.99215698, -0.02635956, 0.1217804 ]), + 'gaze_origin': array([-3.06336522e+00, 2.55966210e-03, 9.10209715e-02]), + 'gaze_valid': True, + 'gaze_vergence': 344.25567626953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99200439, -0.01821899, 0.12480164]), + 'left_gaze_origin': array([-2.98275018, 3.19340086, 0.09027405]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.257080078125, + 'left_pupil_posn': array([ 0.01894128, -0.00916946]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99230957, -0.03450012, 0.11875916]), + 'right_gaze_origin': array([-3.14398074, -3.18828154, 0.09176788]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.099853515625, + 'right_pupil_posn': array([-0.00619918, -0.07640612]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03464461490511894, + 'throttle_input': 0.21031509339809418, + 'timestamp': 678.7008268684149, + 'timestamp_carla': 678702, + 'timestamp_device': 121948, + 'timestamp_stream': 678.7008268684149, + 'transform': [array([-0.53620118, -9.85888481, 0.01469114]), + array([-6.61025643e-02, -5.53718233e+00, -1.05184561e-03])]} +{'AngularVelocity': array([-3.42506357e-02, -6.67867134e-04, 3.37480664e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.042081832885742, + 'FR_Wheel_Angle': -9.475043296813965, + 'Location': array([ -6.80995464, -21.81066895, 0.17676601]), + 'Rotation': array([-0.06949034, -2.62728906, -0.01574707]), + 'Velocity': array([-1.09316087e+00, 1.55331314e-01, 1.04130746e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.7422924 , 11.95868397, 1.19088113]), + 'camera_rotation': array([ -8.07774353, -15.56930923, 0.29229653]), + 'current_gear_input': False, + 'focus_actor_dist': 4568.48193359375, + 'focus_actor_name': 'BP_RepSpline77', + 'focus_actor_pt': array([1463.44042969, 1925.25610352, 52.6147995 ]), + 'frame': 20967, + 'frame_number': 20967, + 'framesequence': 80168, + 'gaze_dir': array([ 0.99220276, -0.02492523, 0.12171173]), + 'gaze_origin': array([-3.06392622, 0.0057869 , 0.09038162]), + 'gaze_valid': True, + 'gaze_vergence': 358.69354248046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99221802, -0.01634216, 0.12335205]), + 'left_gaze_origin': array([-2.99259353, 3.19812632, 0.0910553 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2234649658203125, + 'left_pupil_posn': array([ 0.01605678, -0.00984561]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9921875 , -0.0335083 , 0.12007141]), + 'right_gaze_origin': array([-3.13525867, -3.18655252, 0.08970796]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1870880126953125, + 'right_pupil_posn': array([-0.00686246, -0.07669806]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029499193653464317, + 'throttle_input': 0.2063324898481369, + 'timestamp': 678.7330053672194, + 'timestamp_carla': 678734, + 'timestamp_device': 121981, + 'timestamp_stream': 678.7330053672194, + 'transform': [array([-0.51701629, -9.79274368, 0.01457185]), + array([-6.67992458e-02, -5.58668184e+00, -5.46410272e-04])]} +{'AngularVelocity': array([-0.05323643, -0.00584203, 4.00832939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.67664623260498, + 'FR_Wheel_Angle': -10.512984275817871, + 'Location': array([ -7.0707922 , -21.77775383, 0.17702103]), + 'Rotation': array([-0.07199019, -1.69848645, -0.01245117]), + 'Velocity': array([-1.11697721e+00, 1.58949137e-01, 8.08248529e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.77270508, 12.00438118, 1.23411214]), + 'camera_rotation': array([ -7.81280041, -15.56060791, 0.46475962]), + 'current_gear_input': False, + 'focus_actor_dist': 4986.14501953125, + 'focus_actor_name': 'BP_RepSpline77', + 'focus_actor_pt': array([1612.06054688, 2323.15283203, 40.67462158]), + 'frame': 20968, + 'frame_number': 20968, + 'framesequence': 80172, + 'gaze_dir': array([ 0.99240112, -0.02607727, 0.11987305]), + 'gaze_origin': array([-3.060251 , 0.00566788, 0.08667832]), + 'gaze_valid': True, + 'gaze_vergence': 314.522216796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99205017, -0.01873779, 0.12438965]), + 'left_gaze_origin': array([-2.98503733, 3.19788837, 0.08487854]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1613311767578125, + 'left_pupil_posn': array([ 0.01624823, -0.01410055]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99275208, -0.03341675, 0.11535645]), + 'right_gaze_origin': array([-3.13546467, -3.18655252, 0.0884781 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.18756103515625, + 'right_pupil_posn': array([-0.00769621, -0.07719088]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02623981423676014, + 'throttle_input': 0.2063324898481369, + 'timestamp': 678.7675059661269, + 'timestamp_carla': 678768, + 'timestamp_device': 122014, + 'timestamp_stream': 678.7675059661269, + 'transform': [array([-0.49794462, -9.72084045, 0.01440512]), + array([-6.70792833e-02, -5.63331699e+00, 1.22074067e-04])]} +{'AngularVelocity': array([-0.06179852, -0.02980083, 3.57324672]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.841632843017578, + 'FR_Wheel_Angle': -8.379894256591797, + 'Location': array([ -7.29168463, -21.75272179, 0.17724189]), + 'Rotation': array([-0.07025532, -0.89016724, -0.00720215]), + 'Velocity': array([-1.07731056e+00, 1.27758399e-01, 7.72352214e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.77784824, 12.03061485, 1.26465368]), + 'camera_rotation': array([ -7.57620239, -15.74218845, 0.46295217]), + 'current_gear_input': False, + 'focus_actor_dist': 3652.328369140625, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([1107.69238281, 1095.92529297, 76.57374573]), + 'frame': 20969, + 'frame_number': 20969, + 'framesequence': 80176, + 'gaze_dir': array([ 0.99249268, -0.02383423, 0.11943817]), + 'gaze_origin': array([-3.06655598, 0.00344849, 0.08463135]), + 'gaze_valid': True, + 'gaze_vergence': 302.4159240722656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99256897, -0.01347351, 0.12086487]), + 'left_gaze_origin': array([-2.98219013, 3.1961627 , 0.08290253]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1715850830078125, + 'left_pupil_posn': array([ 0.01715803, -0.01412153]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99241638, -0.03419495, 0.11801147]), + 'right_gaze_origin': array([-3.15092158, -3.18926573, 0.08636017]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.14459228515625, + 'right_pupil_posn': array([-0.00385988, -0.0824821 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.023346660658717155, + 'throttle_input': 0.2063324898481369, + 'timestamp': 678.8001787662506, + 'timestamp_carla': 678801, + 'timestamp_device': 122048, + 'timestamp_stream': 678.8001787662506, + 'transform': [array([-0.48092774, -9.65183735, 0.01429864]), + array([-6.7051962e-02, -5.6728673e+00, 6.4087467e-04])]} +{'AngularVelocity': array([-0.01396235, -0.02092342, 1.72646368]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.561133861541748, + 'FR_Wheel_Angle': -3.793205976486206, + 'Location': array([ -7.55085516, -21.73457909, 0.17755695]), + 'Rotation': array([-0.07528234, -0.2618103 , -0.00115967]), + 'Velocity': array([-1.14765990e+00, 5.93250021e-02, 5.69038384e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.79182148, 12.05465984, 1.29091001]), + 'camera_rotation': array([ -7.45454979, -16.00103188, 0.42684168]), + 'current_gear_input': False, + 'focus_actor_dist': 4545.6845703125, + 'focus_actor_name': 'BP_RepSpline77', + 'focus_actor_pt': array([1458.99316406, 1925.2043457 , 78.65576172]), + 'frame': 20970, + 'frame_number': 20970, + 'framesequence': 80180, + 'gaze_dir': array([ 0.99346161, -0.02200317, 0.11144257]), + 'gaze_origin': array([-3.08027434e+00, -3.89099150e-05, 8.87634307e-02]), + 'gaze_valid': True, + 'gaze_vergence': 285.5603332519531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99336243, -0.01165771, 0.11436462]), + 'left_gaze_origin': array([-3.00966048, 3.19076109, 0.09093781]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2149200439453125, + 'left_pupil_posn': array([ 0.02135181, -0.01678264]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99356079, -0.03234863, 0.10852051]), + 'right_gaze_origin': array([-3.1508882 , -3.19083881, 0.08658905]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1446533203125, + 'right_pupil_posn': array([-0.00216126, -0.08471072]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.022559283301234245, + 'throttle_input': 0.19839780032634735, + 'timestamp': 678.8331980668008, + 'timestamp_carla': 678834, + 'timestamp_device': 122081, + 'timestamp_stream': 678.8331980668008, + 'transform': [array([-0.46421537, -9.58134651, 0.01416781]), + array([-6.62596598e-02, -5.71048689e+00, 1.31226645e-03])]} +{'AngularVelocity': array([ 0.03073859, -0.30568814, 0.00057819]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.71514702, -21.7308712 , 0.17757778]), + 'Rotation': array([-0.04910223, -0.13766479, 0.001348 ]), + 'Velocity': array([-4.91579533e-01, 1.42258732e-03, 2.46591575e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.83308506, 12.07327175, 1.31165874]), + 'camera_rotation': array([ -7.41108274, -16.12992668, 0.69956124]), + 'current_gear_input': False, + 'focus_actor_dist': 4545.34765625, + 'focus_actor_name': 'BP_RepSpline77', + 'focus_actor_pt': array([1474.15905762, 1925.38012695, 51.54651642]), + 'frame': 20971, + 'frame_number': 20971, + 'framesequence': 80184, + 'gaze_dir': array([ 0.99346924, -0.01822662, 0.11181641]), + 'gaze_origin': array([-3.09321165e+00, -1.21078501e-03, 8.83911178e-02]), + 'gaze_valid': True, + 'gaze_vergence': 242.41395568847656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9934845 , -0.00535583, 0.11376953]), + 'left_gaze_origin': array([-3.03031492, 3.1899631 , 0.09284973]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2259063720703125, + 'left_pupil_posn': array([ 0.02226281, -0.01881027]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99345398, -0.03109741, 0.10986328]), + 'right_gaze_origin': array([-3.15610838, -3.19238448, 0.0839325 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.183319091796875, + 'right_pupil_posn': array([ 0.00113964, -0.08782744]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.022559283301234245, + 'throttle_input': 0.1904631108045578, + 'timestamp': 678.8671320676804, + 'timestamp_carla': 678868, + 'timestamp_device': 122114, + 'timestamp_stream': 678.8671320676804, + 'transform': [array([-0.44707856, -9.50832462, 0.0139917 ]), + array([-6.48867935e-02, -5.74861050e+00, 2.19727214e-03])]} +{'AngularVelocity': array([ 2.59262118e-02, 9.94524285e-02, -3.14891222e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.05639415234327316, + 'FR_Wheel_Angle': -0.015379025600850582, + 'Location': array([ -7.75615072, -21.73074722, 0.17749473]), + 'Rotation': array([-0.04141143, -0.13766481, -0.00588989]), + 'Velocity': array([-0.09349243, 0.00010286, -0.00150018]), + 'brake_input': 0.0, + 'camera_location': array([-4.85880566, 12.10907555, 1.3454622 ]), + 'camera_rotation': array([ -7.20335627, -16.19573975, 0.67085338]), + 'current_gear_input': False, + 'focus_actor_dist': 3634.837890625, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([1116.22583008, 1095.90991211, 72.76763916]), + 'frame': 20972, + 'frame_number': 20972, + 'framesequence': 80188, + 'gaze_dir': array([ 0.99410248, -0.01559448, 0.10655975]), + 'gaze_origin': array([-3.09330010e+00, -1.25961308e-03, 8.67294371e-02]), + 'gaze_valid': True, + 'gaze_vergence': 264.27508544921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99452209, -0.00395203, 0.1043396 ]), + 'left_gaze_origin': array([-3.03445768, 3.19024062, 0.09282685]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2258758544921875, + 'left_pupil_posn': array([ 0.02340257, -0.02016902]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99368286, -0.02723694, 0.10877991]), + 'right_gaze_origin': array([-3.15214252, -3.19275975, 0.08063202]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.198974609375, + 'right_pupil_posn': array([ 0.00177586, -0.0926199 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.023621326312422752, + 'throttle_input': 0.17856107652187347, + 'timestamp': 678.9001194685698, + 'timestamp_carla': 678901, + 'timestamp_device': 122148, + 'timestamp_stream': 678.9001194685698, + 'transform': [array([-0.43003753, -9.43687439, 0.01383677]), + array([-6.32338896e-02, -5.78682947e+00, 3.05176014e-03])]} +{'AngularVelocity': array([ 8.03107768e-03, 7.36534968e-02, -8.94999084e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006408483721315861, + 'FR_Wheel_Angle': 0.006408882327377796, + 'Location': array([ -7.7574029 , -21.73073387, 0.17757568]), + 'Rotation': array([-0.05938849, -0.13754271, -0.00909424]), + 'Velocity': array([ 5.35454783e-05, -4.81162024e-05, -1.74881963e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.90243626, 12.13197708, 1.34758723]), + 'camera_rotation': array([ -7.15782595, -16.20825195, 0.84021842]), + 'current_gear_input': False, + 'focus_actor_dist': 4525.3271484375, + 'focus_actor_name': 'BP_RepSpline77', + 'focus_actor_pt': array([1459.15551758, 1925.20654297, 49.51847076]), + 'frame': 20973, + 'frame_number': 20973, + 'framesequence': 80192, + 'gaze_dir': array([ 0.99415588, -0.09351349, 0.0503006 ]), + 'gaze_origin': array([-3.2221489 , 0.06919785, 0.09164811]), + 'gaze_valid': True, + 'gaze_vergence': 107.86831665039062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99452209, -0.08172607, 0.06494141]), + 'left_gaze_origin': array([-3.26722908, 3.26215219, 0.12633668]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.115631103515625, + 'left_pupil_posn': array([-0.05417067, -0.06580365]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99378967, -0.1053009 , 0.03565979]), + 'right_gaze_origin': array([-3.17706919, -3.12375641, 0.05695954]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1320648193359375, + 'right_pupil_posn': array([-0.07234788, -0.12630987]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.026587726548314095, + 'throttle_input': 0.16665904223918915, + 'timestamp': 678.9338113665581, + 'timestamp_carla': 678935, + 'timestamp_device': 122181, + 'timestamp_stream': 678.9338113665581, + 'transform': [array([-0.41161254, -9.36365318, 0.01364256]), + array([-6.13965653e-02, -5.82962561e+00, 4.05884208e-03])]} +{'AngularVelocity': array([ 1.80049322e-03, 1.60274971e-02, -1.88495471e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0064084879122674465, + 'FR_Wheel_Angle': 0.006408885587006807, + 'Location': array([ -7.75746822, -21.73072433, 0.17772193]), + 'Rotation': array([-0.06918298, -0.13754271, -0.01010132]), + 'Velocity': array([ 1.33927533e-05, -4.27778059e-06, -2.47662363e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.91746521, 12.17689228, 1.3412478 ]), + 'camera_rotation': array([ -6.96233225, -16.20981979, 0.70113456]), + 'current_gear_input': False, + 'focus_actor_dist': 1653.999267578125, + 'focus_actor_name': 'Road_Sidewalk_Town05_207', + 'focus_actor_pt': array([ 466.37060547, -774.17944336, 15.2324295 ]), + 'frame': 20974, + 'frame_number': 20974, + 'framesequence': 80196, + 'gaze_dir': array([ 0.969841 , -0.24241638, -0.01734924]), + 'gaze_origin': array([-3.12347436, 0.16711883, 0.01166458]), + 'gaze_valid': True, + 'gaze_vergence': 170.37301635742188, + 'handbrake_input': False, + 'left_eye_openness': 0.8711663484573364, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97399902, -0.22550964, -0.02104187]), + 'left_gaze_origin': array([-3.06570911, 3.34700799, 0.01754608]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2770843505859375, + 'left_pupil_posn': array([-0.16392303, -0.12075913]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9375941157341003, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96568298, -0.25932312, -0.01365662]), + 'right_gaze_origin': array([-3.1812396 , -3.01277018, 0.00578308]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2342987060546875, + 'right_pupil_posn': array([-0.19911063, -0.1930747 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.031202124431729317, + 'throttle_input': 0.1428549587726593, + 'timestamp': 678.9668088667095, + 'timestamp_carla': 678968, + 'timestamp_device': 122214, + 'timestamp_stream': 678.9668088667095, + 'transform': [array([-0.39189941, -9.2919054 , 0.01338863]), + array([-5.98187931e-02, -5.87788248e+00, 5.31006465e-03])]} +{'AngularVelocity': array([ 7.42404780e-04, 4.76599857e-03, -1.47327701e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006408488377928734, + 'FR_Wheel_Angle': 0.006408886518329382, + 'Location': array([ -7.7574811 , -21.73072433, 0.17770344]), + 'Rotation': array([-0.07098615, -0.13754271, -0.01034546]), + 'Velocity': array([ 5.40127985e-06, 2.78978831e-07, -2.71786674e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.94585705, 12.23655891, 1.34281647]), + 'camera_rotation': array([ -6.95166349, -16.33512306, 0.34056726]), + 'current_gear_input': False, + 'focus_actor_dist': 902.8865966796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 238.40188599, -1509.8704834 , 16.40102386]), + 'frame': 20975, + 'frame_number': 20975, + 'framesequence': 80200, + 'gaze_dir': array([ 0.9665451 , -0.25493622, -0.02355194]), + 'gaze_origin': array([-3.12521601, 0.17778093, 0.01489639]), + 'gaze_valid': True, + 'gaze_vergence': 205.57945251464844, + 'handbrake_input': False, + 'left_eye_openness': 0.8847876787185669, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97038269, -0.24047852, -0.02256775]), + 'left_gaze_origin': array([-3.06669474, 3.35779262, 0.02094422]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.240936279296875, + 'left_pupil_posn': array([-0.17478728, -0.1226753 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9546614289283752, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96270752, -0.26939392, -0.02453613]), + 'right_gaze_origin': array([-3.18373728, -3.00223112, 0.00884857]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1872711181640625, + 'right_pupil_posn': array([-0.2117222 , -0.19202745]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.038361769169569016, + 'throttle_input': 0.09919890016317368, + 'timestamp': 678.9994807653129, + 'timestamp_carla': 679000, + 'timestamp_device': 122248, + 'timestamp_stream': 678.9994807653129, + 'transform': [array([-0.36984161, -9.22113037, 0.01308906]), + array([-0.05804294, -5.93551064, 0.00677491])]} +{'AngularVelocity': array([ 1.58449911e-04, 1.12204661e-03, -1.37475772e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006408488377928734, + 'FR_Wheel_Angle': 0.006408886518329382, + 'Location': array([ -7.75748539, -21.73072433, 0.17771114]), + 'Rotation': array([-0.07125936, -0.13754271, -0.0104065 ]), + 'Velocity': array([ 3.09308052e-06, 4.58333517e-07, -5.78027939e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.96002197, 12.27745342, 1.36318183]), + 'camera_rotation': array([ -6.90494537, -16.51676941, 0.41810474]), + 'current_gear_input': False, + 'focus_actor_dist': 857.2061157226562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 223.04101562, -1547.94641113, 16.42956543]), + 'frame': 20976, + 'frame_number': 20976, + 'framesequence': 80204, + 'gaze_dir': array([ 0.96676636, -0.25397491, -0.02641296]), + 'gaze_origin': array([-3.12583566, 0.17513582, 0.01041946]), + 'gaze_valid': True, + 'gaze_vergence': 250.61500549316406, + 'handbrake_input': False, + 'left_eye_openness': 0.8764930963516235, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96987915, -0.24232483, -0.02458191]), + 'left_gaze_origin': array([-3.06824827, 3.35962701, 0.01569824]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.261138916015625, + 'left_pupil_posn': array([-0.17479002, -0.12771559]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9595895409584045, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96365356, -0.265625 , -0.02824402]), + 'right_gaze_origin': array([-3.18342304, -3.00935531, 0.00514069]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.15435791015625, + 'right_pupil_posn': array([-0.20754468, -0.19527555]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04678487405180931, + 'throttle_input': 0.051590751856565475, + 'timestamp': 679.032428868115, + 'timestamp_carla': 679033, + 'timestamp_device': 122281, + 'timestamp_stream': 679.032428868115, + 'transform': [array([-0.34437743, -9.15039158, 0.01272217]), + array([-0.05600072, -6.0062418 , 0.00854493])]} +{'AngularVelocity': array([ 7.29479871e-05, 2.61736044e-04, -1.27467274e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006408488377928734, + 'FR_Wheel_Angle': 0.006408886518329382, + 'Location': array([ -7.75748587, -21.73072243, 0.17771313]), + 'Rotation': array([-0.07125936, -0.13754271, -0.0104065 ]), + 'Velocity': array([3.69605596e-06, 5.86516080e-07, 9.81702469e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.94952583, 12.35607719, 1.41060209]), + 'camera_rotation': array([ -6.621984 , -16.77316284, 0.13578968]), + 'current_gear_input': False, + 'focus_actor_dist': 846.6326293945312, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 219.63531494, -1550.80114746, 16.43391418]), + 'frame': 20977, + 'frame_number': 20977, + 'framesequence': 80208, + 'gaze_dir': array([ 0.9667511 , -0.25370026, -0.02994537]), + 'gaze_origin': array([-3.12602639, 0.17661363, 0.00921173]), + 'gaze_valid': True, + 'gaze_vergence': 202.07244873046875, + 'handbrake_input': False, + 'left_eye_openness': 0.8825806379318237, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96887207, -0.24653625, -0.02232361]), + 'left_gaze_origin': array([-3.06804657, 3.36430526, 0.01607208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2661895751953125, + 'left_pupil_posn': array([-0.17640609, -0.13045037]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9625579714775085, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96463013, -0.26086426, -0.03756714]), + 'right_gaze_origin': array([-3.18400598e+00, -3.01107812e+00, 2.35137949e-03]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.27264404296875, + 'right_pupil_posn': array([-0.20774782, -0.19674075]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05778985098004341, + 'throttle_input': 0.0, + 'timestamp': 679.0668468661606, + 'timestamp_carla': 679068, + 'timestamp_device': 122314, + 'timestamp_stream': 679.0668468661606, + 'transform': [array([-0.31290925, -9.07728004, 0.01237942]), + array([-0.0532823 , -6.09914732, 0.01022339])]} +{'AngularVelocity': array([ 2.54493079e-05, 3.29068789e-05, -1.34762267e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.75748634, -21.73072243, 0.17773005]), + 'Rotation': array([-0.07125936, -0.13754271, -0.0104065 ]), + 'Velocity': array([ 2.22466883e-06, 4.05950118e-07, -1.99244052e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.96612167, 12.45789909, 1.43694615]), + 'camera_rotation': array([ -6.61852121, -16.92393494, 0.06189734]), + 'current_gear_input': False, + 'focus_actor_dist': 846.7002563476562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 224.05422974, -1546.04296875, 16.42789459]), + 'frame': 20978, + 'frame_number': 20978, + 'framesequence': 80212, + 'gaze_dir': array([ 0.96746826, -0.25032806, -0.03476715]), + 'gaze_origin': array([-3.12677097, 0.18082353, 0.00638733]), + 'gaze_valid': True, + 'gaze_vergence': 249.41726684570312, + 'handbrake_input': False, + 'left_eye_openness': 0.8606371879577637, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97001648, -0.24121094, -0.0295105 ]), + 'left_gaze_origin': array([-3.06927347, 3.36906624, 0.01279755]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.293975830078125, + 'left_pupil_posn': array([-0.17907739, -0.13388264]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9412366151809692, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96492004, -0.25944519, -0.0400238 ]), + 'right_gaze_origin': array([-3.18426824e+00, -3.00741911e+00, -2.28881836e-05]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.20037841796875, + 'right_pupil_posn': array([-0.20850569, -0.2007848 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06991180032491684, + 'throttle_input': 0.0, + 'timestamp': 679.0997770652175, + 'timestamp_carla': 679101, + 'timestamp_device': 122348, + 'timestamp_stream': 679.0997770652175, + 'transform': [array([-0.27797607, -9.00850487, 0.01201382]), + array([-0.05050242, -6.2068615 , 0.01208497])]} +{'AngularVelocity': array([ 1.10232431e-05, -1.27502726e-05, -1.30918779e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.75748634, -21.73072243, 0.17773171]), + 'Rotation': array([-0.07125936, -0.13754271, -0.0104065 ]), + 'Velocity': array([2.61614105e-06, 5.30045952e-07, 1.46720864e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.96788597, 12.51992798, 1.50146616]), + 'camera_rotation': array([ -6.44642782, -17.07037926, 0.45672938]), + 'current_gear_input': False, + 'focus_actor_dist': 816.9605102539062, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 207.20812988, -1562.56103516, 16.45035553]), + 'frame': 20979, + 'frame_number': 20979, + 'framesequence': 80216, + 'gaze_dir': array([ 0.96829224, -0.24803925, -0.02829742]), + 'gaze_origin': array([-3.1296525 , 0.18395844, -0.00332718]), + 'gaze_valid': True, + 'gaze_vergence': 321.2077941894531, + 'handbrake_input': False, + 'left_eye_openness': 0.8691996932029724, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96975708, -0.24179077, -0.03288269]), + 'left_gaze_origin': array([-3.07238626e+00, 3.37281370e+00, 2.61688232e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2435760498046875, + 'left_pupil_posn': array([-0.18001831, -0.13549733]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9391222596168518, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96682739, -0.25428772, -0.02371216]), + 'right_gaze_origin': array([-3.18691874, -3.00489664, -0.00927124]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3107757568359375, + 'right_pupil_posn': array([-0.21051133, -0.20892859]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08337046951055527, + 'throttle_input': 0.0, + 'timestamp': 679.1327553652227, + 'timestamp_carla': 679134, + 'timestamp_device': 122381, + 'timestamp_stream': 679.1327553652227, + 'transform': [array([-0.23787291, -8.94122887, 0.0115637 ]), + array([-0.04769521, -6.33480597, 0.01431275])]} +{'AngularVelocity': array([-1.75646564e-05, 8.61902762e-08, -1.33060448e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.75748634, -21.73072243, 0.17769904]), + 'Rotation': array([-0.07125936, -0.13754271, -0.0104065 ]), + 'Velocity': array([2.74370427e-06, 4.87078182e-07, 3.38723126e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.00564671, 12.56340408, 1.53292298]), + 'camera_rotation': array([ -6.50154066, -17.23633003, 0.83144522]), + 'current_gear_input': False, + 'focus_actor_dist': 883.5325317382812, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 250.55136108, -1502.96765137, 16.38658905]), + 'frame': 20980, + 'frame_number': 20980, + 'framesequence': 80220, + 'gaze_dir': array([ 0.96800232, -0.24928284, -0.0276413 ]), + 'gaze_origin': array([-3.13011932e+00, 1.86895758e-01, -2.69927992e-03]), + 'gaze_valid': True, + 'gaze_vergence': 177.24156188964844, + 'handbrake_input': False, + 'left_eye_openness': 0.864165186882019, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96836853, -0.2472229 , -0.03335571]), + 'left_gaze_origin': array([-3.07293248e+00, 3.37476349e+00, 1.82037370e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21380615234375, + 'left_pupil_posn': array([-0.18036181, -0.13541317]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9416660666465759, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96763611, -0.25134277, -0.02192688]), + 'right_gaze_origin': array([-3.18730617, -3.00097203, -0.00721893]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.230377197265625, + 'right_pupil_posn': array([-0.21501732, -0.20793056]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09642628580331802, + 'throttle_input': 0.0, + 'timestamp': 679.1676583662629, + 'timestamp_carla': 679169, + 'timestamp_device': 122414, + 'timestamp_stream': 679.1676583662629, + 'transform': [array([-0.19014221, -8.87197495, 0.01100174]), + array([-0.04507925, -6.49091911, 0.01693726])]} +{'AngularVelocity': array([-5.98887927e-05, -8.90030606e-06, -1.33949934e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.75748634, -21.73072243, 0.17771819]), + 'Rotation': array([-0.07125936, -0.13754271, -0.0104065 ]), + 'Velocity': array([ 2.27586361e-06, 4.66908659e-07, -1.08739856e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.08593178, 12.57391644, 1.51680338]), + 'camera_rotation': array([ -6.72741508, -17.36395454, 1.20603383]), + 'current_gear_input': False, + 'focus_actor_dist': 893.0307006835938, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 262.0451355 , -1491.67700195, 16.37128448]), + 'frame': 20981, + 'frame_number': 20981, + 'framesequence': 80224, + 'gaze_dir': array([ 0.9677124 , -0.25055695, -0.02709198]), + 'gaze_origin': array([-3.13131094, 0.19141084, -0.00525665]), + 'gaze_valid': True, + 'gaze_vergence': 1126.8121337890625, + 'handbrake_input': False, + 'left_eye_openness': 0.8547091484069824, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96839905, -0.24789429, -0.02708435]), + 'left_gaze_origin': array([-3.07414103e+00, 3.38102126e+00, -1.99890137e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1604766845703125, + 'left_pupil_posn': array([-0.18541765, -0.13997805]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9432045817375183, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96702576, -0.2532196 , -0.02709961]), + 'right_gaze_origin': array([-3.18848109, -2.9981997 , -0.00851441]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.298004150390625, + 'right_pupil_posn': array([-0.21720886, -0.2067914 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11083712428808212, + 'throttle_input': 0.0, + 'timestamp': 679.1993776671588, + 'timestamp_carla': 679200, + 'timestamp_device': 122448, + 'timestamp_stream': 679.1993776671588, + 'transform': [array([-0.14180847, -8.81099319, 0.01049488]), + array([-0.04287992, -6.6524291 , 0.01940919])]} +{'AngularVelocity': array([ 3.69328809e-05, -6.06441608e-06, -1.32770383e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.75748634, -21.73072243, 0.17771846]), + 'Rotation': array([-0.07125936, -0.13754271, -0.0104065 ]), + 'Velocity': array([2.59987064e-06, 4.81549648e-07, 1.68099694e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.19511795, 12.55705643, 1.51980364]), + 'camera_rotation': array([ -6.76294565, -17.5345192 , 1.3211875 ]), + 'current_gear_input': False, + 'focus_actor_dist': 882.6425170898438, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 261.23071289, -1495.86279297, 16.3735199 ]), + 'frame': 20982, + 'frame_number': 20982, + 'framesequence': 80228, + 'gaze_dir': array([ 0.96647644, -0.25457764, -0.03237152]), + 'gaze_origin': array([-3.13095641e+00, 1.93519592e-01, -7.33184861e-04]), + 'gaze_valid': True, + 'gaze_vergence': 279.79046630859375, + 'handbrake_input': False, + 'left_eye_openness': 0.8587886691093445, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96502686, -0.25938416, -0.0378418 ]), + 'left_gaze_origin': array([-3.07376099e+00, 3.38394642e+00, 1.03607180e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.210235595703125, + 'left_pupil_posn': array([-0.18615478, -0.1377244 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.955963671207428, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96792603, -0.24977112, -0.02690125]), + 'right_gaze_origin': array([-3.18815184e+00, -2.99690723e+00, -2.50244164e-03]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.28045654296875, + 'right_pupil_posn': array([-0.222148 , -0.20657802]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.12402112036943436, + 'throttle_input': 0.0, + 'timestamp': 679.2337606661022, + 'timestamp_carla': 679235, + 'timestamp_device': 122481, + 'timestamp_stream': 679.2337606661022, + 'transform': [array([-0.08445038, -8.74707508, 0.00990826]), + array([-0.04080355, -6.84688425, 0.02209473])]} diff --git a/PythonAPI/data/trials/trial2.txt b/PythonAPI/data/trials/trial2.txt new file mode 100644 index 0000000..90c4234 --- /dev/null +++ b/PythonAPI/data/trials/trial2.txt @@ -0,0 +1,8037 @@ +{'AngularVelocity': array([-2.45562314e-05, -3.78214318e-05, -4.73319778e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02947246842086315, + 'FR_Wheel_Angle': 0.02948087826371193, + 'Location': array([ -2.0546906 , -15.14080429, 0.17017019]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([5.81010681e-06, 9.36996628e-07, 4.49974963e-04]), + 'brake_input': 0.03967345505952835, + 'camera_location': array([-6.04360962, 16.85380554, 0.29320785]), + 'camera_rotation': array([-5.43158484, 2.95317197, 0.10941092]), + 'current_gear_input': False, + 'focus_actor_dist': 1395.6822509765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 102.82923889, -2869.09423828, 16.64776611]), + 'frame': 21267, + 'frame_number': 21267, + 'framesequence': 81385, + 'gaze_dir': array([0.97491455, 0.22200775, 0.01251221]), + 'gaze_origin': array([-3.86600614, -0.15234375, -0.25252685]), + 'gaze_valid': True, + 'gaze_vergence': 220.4185028076172, + 'handbrake_input': False, + 'left_eye_openness': 0.7141970992088318, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97351074, 0.22782898, 0.01855469]), + 'left_gaze_origin': array([-3.79419112, 2.63832712, -0.28445131]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3060302734375, + 'left_pupil_posn': array([ 0.53241634, -0.4959805 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97631836, 0.21618652, 0.00646973]), + 'right_gaze_origin': array([-3.93782067, -2.94301462, -0.22060242]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.807037353515625, + 'right_pupil_posn': array([-0.08548141, -0.50441098]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.553339779377, + 'timestamp_carla': 687555, + 'timestamp_device': 3840988, + 'timestamp_stream': 687.553339779377, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90805800e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-1.25405131e-05, -6.05957248e-05, -4.97191604e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02947246842086315, + 'FR_Wheel_Angle': 0.02948087826371193, + 'Location': array([ -2.0546906 , -15.14080429, 0.17016099]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([5.39320490e-06, 8.04092224e-07, 1.40955293e-04]), + 'brake_input': 0.03967345505952835, + 'camera_location': array([-6.07413292, 16.82419968, 0.3138549 ]), + 'camera_rotation': array([-5.40987825, 2.8745997 , 0.11190577]), + 'current_gear_input': False, + 'focus_actor_dist': 1465.25634765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 119.07762146, -2936.95947266, 16.6306839 ]), + 'frame': 21268, + 'frame_number': 21268, + 'framesequence': 81389, + 'gaze_dir': array([0.97301483, 0.22980499, 0.01386261]), + 'gaze_origin': array([-3.86670089, -0.15353929, -0.25375977]), + 'gaze_valid': True, + 'gaze_vergence': 92.11799621582031, + 'handbrake_input': False, + 'left_eye_openness': 0.7321537733078003, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97106934, 0.23725891, 0.02653503]), + 'left_gaze_origin': array([-3.79419112, 2.63827991, -0.28609315]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2982940673828125, + 'left_pupil_posn': array([ 0.53530395, -0.4997133 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97496033, 0.22235107, 0.00119019]), + 'right_gaze_origin': array([-3.93921065, -2.94535851, -0.22142641]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8757781982421875, + 'right_pupil_posn': array([-0.08013046, -0.50270474]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.5876727774739, + 'timestamp_carla': 687589, + 'timestamp_device': 3841021, + 'timestamp_stream': 687.5876727774739, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89531704e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-1.54717327e-05, -7.73527499e-05, -4.86947238e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17015168]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([5.74470505e-06, 8.75154512e-07, 3.74157040e-04]), + 'brake_input': 0.03967345505952835, + 'camera_location': array([-6.09427071, 16.80174255, 0.31332922]), + 'camera_rotation': array([-5.3340497 , 2.77642322, 0.02572175]), + 'current_gear_input': False, + 'focus_actor_dist': 1500.323974609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 137.15238953, -2968.64892578, 16.61190033]), + 'frame': 21269, + 'frame_number': 21269, + 'framesequence': 81393, + 'gaze_dir': array([0.96395111, 0.26499176, 0.02181244]), + 'gaze_origin': array([-3.8756988 , -0.19012757, -0.26304933]), + 'gaze_valid': True, + 'gaze_vergence': 252.55213928222656, + 'handbrake_input': False, + 'left_eye_openness': 0.66147780418396, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96194458, 0.2726593 , 0.01713562]), + 'left_gaze_origin': array([-3.80590868, 2.59288049, -0.3032288 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.291229248046875, + 'left_pupil_posn': array([ 0.59009397, -0.51026094]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96595764, 0.25732422, 0.02648926]), + 'right_gaze_origin': array([-3.94548965, -2.97313547, -0.22286989]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.887908935546875, + 'right_pupil_posn': array([-0.04594821, -0.51035154]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.6195622757077, + 'timestamp_carla': 687621, + 'timestamp_device': 3841055, + 'timestamp_stream': 687.6195622757077, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90592178e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 1.51326631e-05, 9.04177723e-05, -5.42996304e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17013955]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([ 4.87366697e-06, 5.32311390e-07, -4.71695908e-04]), + 'brake_input': 0.0476234070956707, + 'camera_location': array([-6.11142349, 16.79975128, 0.31384838]), + 'camera_rotation': array([-5.24099493, 2.67779803, -0.01720068]), + 'current_gear_input': False, + 'focus_actor_dist': 1729.1845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 251.14457703, -3175.30566406, 16.49347687]), + 'frame': 21270, + 'frame_number': 21270, + 'framesequence': 81397, + 'gaze_dir': array([0.9630661 , 0.26829529, 0.02207947]), + 'gaze_origin': array([-3.87552118, -0.19090652, -0.26308596]), + 'gaze_valid': True, + 'gaze_vergence': 616.5711669921875, + 'handbrake_input': False, + 'left_eye_openness': 0.6611501574516296, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96200562, 0.27200317, 0.02336121]), + 'left_gaze_origin': array([-3.80514216, 2.59402943, -0.30318758]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3199462890625, + 'left_pupil_posn': array([ 0.59257948, -0.51291239]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96412659, 0.2645874 , 0.02079773]), + 'right_gaze_origin': array([-3.9459002 , -2.97584248, -0.22298433]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.913055419921875, + 'right_pupil_posn': array([-0.04415244, -0.50814331]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.6539214774966, + 'timestamp_carla': 687656, + 'timestamp_device': 3841088, + 'timestamp_stream': 687.6539214774966, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89367675e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 1.03416223e-05, 7.92855717e-05, -5.27641077e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17015669]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([ 5.06005244e-06, 5.96132566e-07, -3.45681008e-04]), + 'brake_input': 0.05555810034275055, + 'camera_location': array([-6.14416981, 16.80742073, 0.315983 ]), + 'camera_rotation': array([-5.25416374, 2.63417602, -0.04595777]), + 'current_gear_input': False, + 'focus_actor_dist': 1784.531982421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.50964355, -3227.71289062, 16.47428131]), + 'frame': 21271, + 'frame_number': 21271, + 'framesequence': 81400, + 'gaze_dir': array([0.96329498, 0.26757812, 0.02001953]), + 'gaze_origin': array([-3.87547159, -0.1913971 , -0.26267779]), + 'gaze_valid': True, + 'gaze_vergence': 410.73406982421875, + 'handbrake_input': False, + 'left_eye_openness': 0.6465604305267334, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96162415, 0.27368164, 0.01895142]), + 'left_gaze_origin': array([-3.80493188, 2.59410572, -0.30287781]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.325653076171875, + 'left_pupil_posn': array([ 0.59107113, -0.5123086 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96496582, 0.26147461, 0.02108765]), + 'right_gaze_origin': array([-3.94601154, -2.97689986, -0.22247773]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.84307861328125, + 'right_pupil_posn': array([-0.0426535, -0.5094043]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.685960277915, + 'timestamp_carla': 687688, + 'timestamp_device': 3841113, + 'timestamp_stream': 687.685960277915, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90386193e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 5.81697077e-06, -1.42500567e-05, -5.08818221e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17015359]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([5.30998204e-06, 7.48836896e-07, 5.50790392e-05]), + 'brake_input': 0.059525445103645325, + 'camera_location': array([-6.15785408, 16.82219696, 0.3046644 ]), + 'camera_rotation': array([-5.30202961, 2.64212632, 0.04691473]), + 'current_gear_input': False, + 'focus_actor_dist': 1727.853271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 251.07867432, -3173.88964844, 16.49355316]), + 'frame': 21272, + 'frame_number': 21272, + 'framesequence': 81405, + 'gaze_dir': array([0.96378326, 0.26609039, 0.01661682]), + 'gaze_origin': array([-3.8750689 , -0.19179688, -0.26217958]), + 'gaze_valid': True, + 'gaze_vergence': 467.880615234375, + 'handbrake_input': False, + 'left_eye_openness': 0.6445721983909607, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96258545, 0.27055359, 0.014328 ]), + 'left_gaze_origin': array([-3.80445576, 2.5942018 , -0.30232546]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3247222900390625, + 'left_pupil_posn': array([ 0.59105074, -0.51266205]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96498108, 0.2616272 , 0.01890564]), + 'right_gaze_origin': array([-3.94568181, -2.9777956 , -0.22203371]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.807830810546875, + 'right_pupil_posn': array([-0.04319167, -0.51061618]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.7202341780066, + 'timestamp_carla': 687722, + 'timestamp_device': 3841155, + 'timestamp_stream': 687.7202341780066, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89321900e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 8.47585306e-06, 8.73923054e-05, -4.86591080e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17017137]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([5.76733146e-06, 8.47987792e-07, 2.86449649e-04]), + 'brake_input': 0.059525445103645325, + 'camera_location': array([-6.17526627, 16.84630013, 0.32109737]), + 'camera_rotation': array([-5.23836565, 2.69675493, 0.11085071]), + 'current_gear_input': False, + 'focus_actor_dist': 1616.7767333984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 217.87744141, -3067.57299805, 16.52832031]), + 'frame': 21273, + 'frame_number': 21273, + 'framesequence': 81408, + 'gaze_dir': array([0.9811554 , 0.18959045, 0.02912903]), + 'gaze_origin': array([-3.87640643, -0.1391449 , -0.250029 ]), + 'gaze_valid': True, + 'gaze_vergence': 91.4666748046875, + 'handbrake_input': False, + 'left_eye_openness': 0.6736202836036682, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97833252, 0.20651245, 0.01409912]), + 'left_gaze_origin': array([-3.82204604, 2.65748286, -0.27844697]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2429962158203125, + 'left_pupil_posn': array([ 0.49885941, -0.48032045]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98397827, 0.17266846, 0.04415894]), + 'right_gaze_origin': array([-3.93076658, -2.93577266, -0.22161102]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8789215087890625, + 'right_pupil_posn': array([-0.09921622, -0.50482082]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.7529583759606, + 'timestamp_carla': 687755, + 'timestamp_device': 3841180, + 'timestamp_stream': 687.7529583759606, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89886468e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 1.73931812e-06, -1.39014388e-04, -5.08876974e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17015828]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([ 5.09017127e-06, 7.08044979e-07, -7.39812967e-05]), + 'brake_input': 0.059525445103645325, + 'camera_location': array([-6.19722557, 16.88593674, 0.34943503]), + 'camera_rotation': array([-5.14065266, 2.79149008, 0.18324694]), + 'current_gear_input': False, + 'focus_actor_dist': 1929.7017822265625, + 'focus_actor_name': 'Plane22', + 'focus_actor_pt': array([ 159.88490295, -3404.94726562, 16.62550354]), + 'frame': 21274, + 'frame_number': 21274, + 'framesequence': 81413, + 'gaze_dir': array([0.99627686, 0.0790863 , 0.02882385]), + 'gaze_origin': array([-3.86885118, -0.04604874, -0.23713228]), + 'gaze_valid': True, + 'gaze_vergence': 148.26075744628906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99476624, 0.09651184, 0.03337097]), + 'left_gaze_origin': array([-3.76184535, 2.75223708, -0.27371827]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2341156005859375, + 'left_pupil_posn': array([ 0.37786961, -0.46400845]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99778748, 0.06166077, 0.02427673]), + 'right_gaze_origin': array([-3.9758563 , -2.8443346 , -0.20054628]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.986968994140625, + 'right_pupil_posn': array([-0.20881653, -0.49012029]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.7881125770509, + 'timestamp_carla': 687790, + 'timestamp_device': 3841221, + 'timestamp_stream': 687.7881125770509, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88337702e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 8.66899154e-06, 7.44200443e-05, -4.90371349e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17016359]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([5.72880708e-06, 8.54223003e-07, 3.17802711e-04]), + 'brake_input': 0.059525445103645325, + 'camera_location': array([-6.20796967, 16.92610168, 0.35804203]), + 'camera_rotation': array([-5.09717846, 2.915308 , 0.2601352 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1935.49951171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -49.09353638, -3442.37231445, 16.80047607]), + 'frame': 21275, + 'frame_number': 21275, + 'framesequence': 81417, + 'gaze_dir': array([0.99849701, 0.03899384, 0.03525543]), + 'gaze_origin': array([-3.87330723, -0.02424316, -0.23847735]), + 'gaze_valid': True, + 'gaze_vergence': 140.51280212402344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99841309, 0.05018616, 0.02516174]), + 'left_gaze_origin': array([-3.68835473, 2.77364039, -0.30019227]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2599029541015625, + 'left_pupil_posn': array([ 0.34661531, -0.45717335]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99858093, 0.02780151, 0.04534912]), + 'right_gaze_origin': array([-4.05825996, -2.82212687, -0.17676239]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8236083984375, + 'right_pupil_posn': array([-0.24336714, -0.49420989]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.8216180764139, + 'timestamp_carla': 687823, + 'timestamp_device': 3841255, + 'timestamp_stream': 687.8216180764139, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88822176e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-3.25770889e-05, -2.90052176e-05, -5.32265540e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17015016]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([ 4.70226632e-06, 5.84123200e-07, -4.64153767e-04]), + 'brake_input': 0.059525445103645325, + 'camera_location': array([-6.23682976, 16.96020317, 0.36234194]), + 'camera_rotation': array([-5.09998608, 2.99815106, 0.28177062]), + 'current_gear_input': False, + 'focus_actor_dist': 2189.75048828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -107.85405731, -3702.17773438, 16.85930634]), + 'frame': 21276, + 'frame_number': 21276, + 'framesequence': 81421, + 'gaze_dir': array([0.99847412, 0.03912354, 0.03549957]), + 'gaze_origin': array([-3.87479401, -0.02410126, -0.23724823]), + 'gaze_valid': True, + 'gaze_vergence': 165.1629180908203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99816895, 0.052948 , 0.02879333]), + 'left_gaze_origin': array([-3.7112751 , 2.77508879, -0.29147798]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.217926025390625, + 'left_pupil_posn': array([ 0.34510744, -0.45717335]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9987793 , 0.02529907, 0.04220581]), + 'right_gaze_origin': array([-4.03831339, -2.82329106, -0.18301851]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.893310546875, + 'right_pupil_posn': array([-0.24137777, -0.49295533]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.8543449789286, + 'timestamp_carla': 687856, + 'timestamp_device': 3841288, + 'timestamp_stream': 687.8543449789286, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89688096e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 7.23895118e-06, -9.38035828e-06, -4.81751658e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0546906 , -15.14080429, 0.17017053]), + 'Rotation': array([ 8.74947198e-03, -9.19093018e+01, 6.43839315e-02]), + 'Velocity': array([5.72659974e-06, 8.55920348e-07, 3.09599913e-04]), + 'brake_input': 0.027771420776844025, + 'camera_location': array([-6.25598145, 16.9924202 , 0.35032663]), + 'camera_rotation': array([-5.08030796, 3.03015113, 0.34205115]), + 'current_gear_input': False, + 'focus_actor_dist': 2197.2509765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -103.91539001, -3709.44677734, 16.85520935]), + 'frame': 21277, + 'frame_number': 21277, + 'framesequence': 81425, + 'gaze_dir': array([0.99858093, 0.03760529, 0.03512573]), + 'gaze_origin': array([-3.89505553, -0.02498551, -0.22738266]), + 'gaze_valid': True, + 'gaze_vergence': 201.2353515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99835205, 0.04890442, 0.02955627]), + 'left_gaze_origin': array([-3.72253132, 2.77636576, -0.28688049]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21490478515625, + 'left_pupil_posn': array([ 0.34480441, -0.45700252]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99880981, 0.02630615, 0.04069519]), + 'right_gaze_origin': array([-4.06758022, -2.82633686, -0.16788483]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.980621337890625, + 'right_pupil_posn': array([-0.24063993, -0.48837376]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.8868466764688, + 'timestamp_carla': 687889, + 'timestamp_device': 3841321, + 'timestamp_stream': 687.8868466764688, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90351850e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.07382978, 0.00238952, -0.00065038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.023050624877214432, + 'FR_Wheel_Angle': 0.02177567221224308, + 'Location': array([ -2.05465126, -15.14056873, 0.17015637]), + 'Rotation': array([ 8.89290590e-03, -9.19092484e+01, 6.43649548e-02]), + 'Velocity': array([-1.13905675e-03, -4.02081087e-02, 1.79004674e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.27531433, 17.02274895, 0.35265246]), + 'camera_rotation': array([-5.08990431, 3.09108973, 0.40258265]), + 'current_gear_input': False, + 'focus_actor_dist': 2194.375732421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -106.08734894, -3706.65283203, 16.85743713]), + 'frame': 21278, + 'frame_number': 21278, + 'framesequence': 81429, + 'gaze_dir': array([0.99848938, 0.03769684, 0.0373764 ]), + 'gaze_origin': array([-3.862252 , -0.02349167, -0.23898698]), + 'gaze_valid': True, + 'gaze_vergence': 203.55711364746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99798584, 0.05140686, 0.03697205]), + 'left_gaze_origin': array([-3.71724558, 2.77751946, -0.28714448]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.220245361328125, + 'left_pupil_posn': array([ 0.34292638, -0.45700252]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99899292, 0.02398682, 0.03778076]), + 'right_gaze_origin': array([-4.00725842, -2.82450271, -0.19082947]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9616851806640625, + 'right_pupil_posn': array([-0.24087924, -0.48837376]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.920294675976, + 'timestamp_carla': 687922, + 'timestamp_device': 3841355, + 'timestamp_stream': 687.920294675976, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90027610e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.07939147, 0.00333532, -0.66876745]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021716995164752007, + 'FR_Wheel_Angle': 0.021719790995121002, + 'Location': array([ -2.05508161, -15.15501213, 0.17012057]), + 'Rotation': array([ 1.58596989e-02, -9.19094543e+01, 6.43186569e-02]), + 'Velocity': array([-0.00615793, -0.19574624, -0.00048022]), + 'brake_input': 0.0, + 'camera_location': array([-6.29181862, 17.03797722, 0.37389711]), + 'camera_rotation': array([-5.02514076, 3.13647413, 0.46268281]), + 'current_gear_input': False, + 'focus_actor_dist': 2281.16845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -98.32962036, -3793.27685547, 16.84897614]), + 'frame': 21279, + 'frame_number': 21279, + 'framesequence': 81433, + 'gaze_dir': array([0.99867249, 0.03826141, 0.02919769]), + 'gaze_origin': array([-3.86241078, -0.02268448, -0.24033661]), + 'gaze_valid': True, + 'gaze_vergence': 110.27812194824219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99856567, 0.05099487, 0.01628113]), + 'left_gaze_origin': array([-3.7149415 , 2.77899337, -0.2891266 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2524871826171875, + 'left_pupil_posn': array([ 0.34233749, -0.45628154]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9987793 , 0.02552795, 0.04211426]), + 'right_gaze_origin': array([-4.00988007, -2.82436228, -0.19154663]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.972991943359375, + 'right_pupil_posn': array([-0.2414034 , -0.49758053]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.9565981775522, + 'timestamp_carla': 687958, + 'timestamp_device': 3841388, + 'timestamp_stream': 687.9565981775522, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.87467940e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.06182019, -0.00091804, -0.28356522]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021640703082084656, + 'FR_Wheel_Angle': 0.021632445976138115, + 'Location': array([ -2.05717468, -15.22113705, 0.17012483]), + 'Rotation': array([ 1.77789815e-02, -9.19234924e+01, 6.41879365e-02]), + 'Velocity': array([-1.05622122e-02, -3.29339921e-01, -2.15225213e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.30174828, 17.0464859 , 0.39896315]), + 'camera_rotation': array([-4.88066149, 3.15208507, 0.49835214]), + 'current_gear_input': False, + 'focus_actor_dist': 2005.6241455078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -111.79656219, -3517.61328125, 16.86448669]), + 'frame': 21280, + 'frame_number': 21280, + 'framesequence': 81437, + 'gaze_dir': array([0.99877167, 0.03702545, 0.02550507]), + 'gaze_origin': array([-3.85929203, -0.02236328, -0.24276811]), + 'gaze_valid': True, + 'gaze_vergence': 89.36994171142578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.998703 , 0.04969788, 0.00984192]), + 'left_gaze_origin': array([-3.70358157, 2.77935195, -0.29337618]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2630157470703125, + 'left_pupil_posn': array([ 0.34139407, -0.4571681 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99884033, 0.02435303, 0.04116821]), + 'right_gaze_origin': array([-4.01500273, -2.82407856, -0.19216004]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.965667724609375, + 'right_pupil_posn': array([-0.24230218, -0.50200689]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 687.9893288761377, + 'timestamp_carla': 687991, + 'timestamp_device': 3841421, + 'timestamp_stream': 687.9893288761377, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88955681e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-3.64908166e-02, -7.29109306e-05, -3.79568338e-02]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021643513813614845, + 'FR_Wheel_Angle': 0.021654509007930756, + 'Location': array([ -2.05973411, -15.29810238, 0.1701494 ]), + 'Rotation': array([ 1.42341135e-02, -9.19229431e+01, 6.41382560e-02]), + 'Velocity': array([-0.0143847 , -0.43762875, -0.00057042]), + 'brake_input': 0.0, + 'camera_location': array([-6.30145645, 17.05241013, 0.39504823]), + 'camera_rotation': array([-4.78190374, 3.16300464, 0.47065294]), + 'current_gear_input': False, + 'focus_actor_dist': 1965.9141845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.08690643, -3478.01171875, 16.86911774]), + 'frame': 21281, + 'frame_number': 21281, + 'framesequence': 81441, + 'gaze_dir': array([0.99900818, 0.03522491, 0.01832581]), + 'gaze_origin': array([-3.84491539, -0.0226532 , -0.24904558]), + 'gaze_valid': True, + 'gaze_vergence': 92.10375213623047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99885559, 0.04750061, 0.00309753]), + 'left_gaze_origin': array([-3.6738255 , 2.77935195, -0.30670169]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2698822021484375, + 'left_pupil_posn': array([ 0.34032047, -0.46295595]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99916077, 0.02294922, 0.03355408]), + 'right_gaze_origin': array([-4.01600504, -2.82465839, -0.19138947]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0355682373046875, + 'right_pupil_posn': array([-0.24284792, -0.50456238]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.0213596783578, + 'timestamp_carla': 688023, + 'timestamp_device': 3841454, + 'timestamp_stream': 688.0213596783578, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90317531e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.05597134, 0.00124193, -0.05064921]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021664410829544067, + 'FR_Wheel_Angle': 0.02167288027703762, + 'Location': array([ -2.06282282, -15.38474369, 0.17025499]), + 'Rotation': array([ 8.57188739e-03, -9.18883591e+01, 6.39671162e-02]), + 'Velocity': array([-1.25870463e-02, -3.90125453e-01, -1.08690263e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.31227112, 17.05060005, 0.36776513]), + 'camera_rotation': array([-4.84050703, 3.13945031, 0.45285955]), + 'current_gear_input': False, + 'focus_actor_dist': 1802.1988525390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -128.76318359, -3314.45214844, 16.88316345]), + 'frame': 21282, + 'frame_number': 21282, + 'framesequence': 81445, + 'gaze_dir': array([0.99378967, 0.07798767, 0.07822418]), + 'gaze_origin': array([-3.88231468, -0.04944916, -0.19116822]), + 'gaze_valid': True, + 'gaze_vergence': 218.30360412597656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99287415, 0.09060669, 0.07725525]), + 'left_gaze_origin': array([-3.69683838, 2.74493265, -0.25471193]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3436431884765625, + 'left_pupil_posn': array([ 0.38153744, -0.41348267]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9947052 , 0.06536865, 0.07919312]), + 'right_gaze_origin': array([-4.06779051, -2.84383082, -0.12762453]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9940643310546875, + 'right_pupil_posn': array([-0.21010834, -0.43928218]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.0543998777866, + 'timestamp_carla': 688056, + 'timestamp_device': 3841488, + 'timestamp_stream': 688.0543998777866, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90317531e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.06587129, 0.00152487, -0.03886177]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021684791892766953, + 'FR_Wheel_Angle': 0.02041536755859852, + 'Location': array([ -2.06524062, -15.46209908, 0.17027563]), + 'Rotation': array([ 6.84384909e-03, -9.18965454e+01, 6.38833195e-02]), + 'Velocity': array([-0.01057989, -0.33584327, 0.00071159]), + 'brake_input': 0.0, + 'camera_location': array([-6.31770325, 17.03759766, 0.33708113]), + 'camera_rotation': array([-4.93475008, 3.07718563, 0.4612866 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3831.771728515625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 151.39678955, -5331.49023438, 109.53569031]), + 'frame': 21283, + 'frame_number': 21283, + 'framesequence': 81448, + 'gaze_dir': array([0.99373627, 0.0802536 , 0.07697296]), + 'gaze_origin': array([-3.89323616, -0.05268784, -0.18816453]), + 'gaze_valid': True, + 'gaze_vergence': 256.2540283203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99319458, 0.09011841, 0.07373047]), + 'left_gaze_origin': array([-3.70096159, 2.74488997, -0.25489503]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.325225830078125, + 'left_pupil_posn': array([ 0.38361835, -0.41422582]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99427795, 0.07038879, 0.08021545]), + 'right_gaze_origin': array([-4.08551073, -2.8502655 , -0.12143402]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0007171630859375, + 'right_pupil_posn': array([-0.20549583, -0.440184 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.0858842767775, + 'timestamp_carla': 688088, + 'timestamp_device': 3841513, + 'timestamp_stream': 688.0858842767775, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.91381823e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.04902629, 0.00131146, 0.7903372 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020364239811897278, + 'FR_Wheel_Angle': 0.020358387380838394, + 'Location': array([ -2.06762576, -15.53284264, 0.170286 ]), + 'Rotation': array([ 1.02452831e-02, -9.18931274e+01, 6.39676452e-02]), + 'Velocity': array([-1.24087455e-02, -3.55449826e-01, 3.54289987e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.31239891, 17.02867889, 0.3189581 ]), + 'camera_rotation': array([-4.94545269, 3.01500583, 0.45482749]), + 'current_gear_input': False, + 'focus_actor_dist': 3832.336181640625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 155.94801331, -5331.49023438, 98.35017395]), + 'frame': 21284, + 'frame_number': 21284, + 'framesequence': 81453, + 'gaze_dir': array([0.99406433, 0.07925415, 0.07357025]), + 'gaze_origin': array([-3.89663506, -0.05352249, -0.18633653]), + 'gaze_valid': True, + 'gaze_vergence': 230.121337890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99362183, 0.08921814, 0.06880188]), + 'left_gaze_origin': array([-3.70096159, 2.74492359, -0.25489503]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3071746826171875, + 'left_pupil_posn': array([ 0.38317001, -0.41487062]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99450684, 0.06929016, 0.07833862]), + 'right_gaze_origin': array([-4.09230804, -2.85196853, -0.11777802]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0175018310546875, + 'right_pupil_posn': array([-0.20459825, -0.44097662]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.1212101764977, + 'timestamp_carla': 688123, + 'timestamp_device': 3841554, + 'timestamp_stream': 688.1212101764977, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89031980e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.03033418, -0.00282833, -0.01585821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02028648369014263, + 'FR_Wheel_Angle': 0.02028064988553524, + 'Location': array([ -2.07088017, -15.63269997, 0.17029734]), + 'Rotation': array([ 1.67681128e-02, -9.18848495e+01, 6.36932403e-02]), + 'Velocity': array([-1.63460057e-02, -5.10828912e-01, 3.06920992e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.3130064 , 17.01749039, 0.31372714]), + 'camera_rotation': array([-4.98133183, 2.99993348, 0.46311179]), + 'current_gear_input': False, + 'focus_actor_dist': 3500.83544921875, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ 114.99577332, -5002.31054688, 88.91348267]), + 'frame': 21285, + 'frame_number': 21285, + 'framesequence': 81457, + 'gaze_dir': array([0.99421692, 0.07901001, 0.07169342]), + 'gaze_origin': array([-3.91188216, -0.05379715, -0.18110429]), + 'gaze_valid': True, + 'gaze_vergence': 237.35098266601562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99363708, 0.08959961, 0.06809998]), + 'left_gaze_origin': array([-3.73204207, 2.74564838, -0.24390717]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3046417236328125, + 'left_pupil_posn': array([ 0.38317001, -0.41513979]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99479675, 0.06842041, 0.07528687]), + 'right_gaze_origin': array([-4.09172201, -2.85324264, -0.1183014 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0069427490234375, + 'right_pupil_posn': array([-0.20350122, -0.44147944]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.1534970775247, + 'timestamp_carla': 688155, + 'timestamp_device': 3841588, + 'timestamp_stream': 688.1534970775247, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90054316e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.04317296, -0.00061256, -0.00237528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020213356241583824, + 'FR_Wheel_Angle': 0.020203623920679092, + 'Location': array([ -2.07588029, -15.78714466, 0.1703217 ]), + 'Rotation': array([ 1.85303017e-02, -9.18920822e+01, 6.37383759e-02]), + 'Velocity': array([-2.32242644e-02, -7.06457436e-01, 1.87177648e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.3057127 , 17.02226639, 0.31406707]), + 'camera_rotation': array([-4.99715757, 3.02691698, 0.4428868 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3831.628662109375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 145.78193665, -5331.48974609, 74.96562958]), + 'frame': 21286, + 'frame_number': 21286, + 'framesequence': 81461, + 'gaze_dir': array([0.9942627 , 0.07850647, 0.07170868]), + 'gaze_origin': array([-3.9101913 , -0.05405045, -0.18168642]), + 'gaze_valid': True, + 'gaze_vergence': 239.1818389892578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99369812, 0.08894348, 0.06803894]), + 'left_gaze_origin': array([-3.73086715, 2.74577951, -0.24437715]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.29742431640625, + 'left_pupil_posn': array([ 0.38289428, -0.41513979]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99482727, 0.06806946, 0.07537842]), + 'right_gaze_origin': array([-4.08951616, -2.85388041, -0.11899567]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.001373291015625, + 'right_pupil_posn': array([-0.2032702 , -0.44147944]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.186790779233, + 'timestamp_carla': 688189, + 'timestamp_device': 3841621, + 'timestamp_stream': 688.186790779233, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89920811e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.02964275, -0.00102985, 0.00788833]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020099475979804993, + 'FR_Wheel_Angle': 0.020087437704205513, + 'Location': array([ -2.08262992, -15.99152756, 0.17039938]), + 'Rotation': array([ 2.32021511e-02, -9.18912888e+01, 6.37187809e-02]), + 'Velocity': array([-3.31652537e-02, -1.00799525e+00, 5.52053447e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.29939842, 17.01601028, 0.32269555]), + 'camera_rotation': array([-5.04910755, 3.08713937, 0.58323497]), + 'current_gear_input': False, + 'focus_actor_dist': 3831.6103515625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 145.55262756, -5331.49023438, 74.07778931]), + 'frame': 21287, + 'frame_number': 21287, + 'framesequence': 81465, + 'gaze_dir': array([0.99417114, 0.0790863 , 0.07234192]), + 'gaze_origin': array([-3.90860319, -0.05363388, -0.18246002]), + 'gaze_valid': True, + 'gaze_vergence': 245.75489807128906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99362183, 0.08927917, 0.06881714]), + 'left_gaze_origin': array([-3.7286303 , 2.7469759 , -0.24577028]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.29742431640625, + 'left_pupil_posn': array([ 0.38225615, -0.41545177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99472046, 0.06889343, 0.0758667 ]), + 'right_gaze_origin': array([-4.08857584, -2.85424376, -0.11914979]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9867095947265625, + 'right_pupil_posn': array([-0.20284289, -0.44102919]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.2226597778499, + 'timestamp_carla': 688225, + 'timestamp_device': 3841654, + 'timestamp_stream': 688.2226597778499, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.87742610e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.08222916, -0.00270036, 0.00753753]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.0917573 , -16.26856041, 0.17049363]), + 'Rotation': array([ 2.20000390e-02, -9.18894196e+01, 6.37259185e-02]), + 'Velocity': array([-4.06073667e-02, -1.23407137e+00, 6.87465654e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.29549217, 17.01245117, 0.31814384]), + 'camera_rotation': array([-5.09585381, 3.14727044, 0.5223645 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3832.32568359375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 152.52482605, -5331.49023438, 72.29298401]), + 'frame': 21288, + 'frame_number': 21288, + 'framesequence': 81469, + 'gaze_dir': array([0.99422455, 0.07835388, 0.07236481]), + 'gaze_origin': array([-3.90722966, -0.05365372, -0.18288881]), + 'gaze_valid': True, + 'gaze_vergence': 252.0001678466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99357605, 0.08886719, 0.06990051]), + 'left_gaze_origin': array([-3.72764778, 2.74711466, -0.24584047]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.275787353515625, + 'left_pupil_posn': array([ 0.38169956, -0.41559076]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99487305, 0.06784058, 0.0748291 ]), + 'right_gaze_origin': array([-4.08681202, -2.85442209, -0.11993714]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9689483642578125, + 'right_pupil_posn': array([-0.20284289, -0.44072008]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.2537494786084, + 'timestamp_carla': 688256, + 'timestamp_device': 3841688, + 'timestamp_stream': 688.2537494786084, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90092453e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 5.28436601e-02, -1.91485160e-03, -2.99058120e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.10188532, -16.57406044, 0.17066683]), + 'Rotation': array([ 1.38516231e-02, -9.18893814e+01, 6.37278110e-02]), + 'Velocity': array([-4.29159589e-02, -1.29417753e+00, 5.22489543e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.27870941, 17.02190781, 0.29395145]), + 'camera_rotation': array([-5.16469526, 3.17454171, 0.36935613]), + 'current_gear_input': False, + 'focus_actor_dist': 3832.457275390625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 153.4370575 , -5331.49023438, 69.58688354]), + 'frame': 21289, + 'frame_number': 21289, + 'framesequence': 81473, + 'gaze_dir': array([0.99398041, 0.07875061, 0.07513428]), + 'gaze_origin': array([-3.90109563, -0.05365372, -0.18551484]), + 'gaze_valid': True, + 'gaze_vergence': 202.45962524414062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99365234, 0.08885193, 0.06886292]), + 'left_gaze_origin': array([-3.71706414, 2.74711466, -0.25108033]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2547149658203125, + 'left_pupil_posn': array([ 0.38167667, -0.41444981]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99430847, 0.06864929, 0.08140564]), + 'right_gaze_origin': array([-4.08512783, -2.85442209, -0.11994934]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.956756591796875, + 'right_pupil_posn': array([-0.20284289, -0.44071352]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.2863866761327, + 'timestamp_carla': 688288, + 'timestamp_device': 3841721, + 'timestamp_stream': 688.2863866761327, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90462491e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 1.86616331e-02, -5.39247063e-04, 1.24266435e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.11139011, -16.86070442, 0.17083246]), + 'Rotation': array([ 5.89445280e-03, -9.18892593e+01, 6.37127906e-02]), + 'Velocity': array([-3.91802639e-02, -1.18172932e+00, 6.72912574e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.26823807, 17.01177406, 0.27620775]), + 'camera_rotation': array([-5.16791868, 3.17839766, 0.35840157]), + 'current_gear_input': False, + 'focus_actor_dist': 3832.594970703125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 156.13815308, -5331.48974609, 76.42077637]), + 'frame': 21290, + 'frame_number': 21290, + 'framesequence': 81477, + 'gaze_dir': array([0.99278259, 0.0820694 , 0.08562469]), + 'gaze_origin': array([-3.83665562, -0.0537262 , -0.21091539]), + 'gaze_valid': True, + 'gaze_vergence': 62.25907897949219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99368286, 0.08808899, 0.06948853]), + 'left_gaze_origin': array([-3.59209633, 2.74669361, -0.30064699]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2461090087890625, + 'left_pupil_posn': array([ 0.38136256, -0.41421056]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99188232, 0.0760498 , 0.10176086]), + 'right_gaze_origin': array([-4.0812149 , -2.85414577, -0.12118378]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9451751708984375, + 'right_pupil_posn': array([-0.20332998, -0.44043911]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.320214278996, + 'timestamp_carla': 688322, + 'timestamp_device': 3841754, + 'timestamp_stream': 688.320214278996, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89764395e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.03147586, -0.00190454, 0.00370257]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0138419009745121, + 'FR_Wheel_Angle': 0.013852326199412346, + 'Location': array([ -2.12009883, -17.12358665, 0.17094427]), + 'Rotation': array([ 3.01211327e-03, -9.18891220e+01, 6.36875778e-02]), + 'Velocity': array([-3.42548378e-02, -1.03995752e+00, 3.14331061e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.247612 , 17.00118256, 0.25663093]), + 'camera_rotation': array([-5.17565775, 3.12168884, 0.3569285 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3833.497802734375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 169.45089722, -5331.49072266, 116.57516479]), + 'frame': 21291, + 'frame_number': 21291, + 'framesequence': 81481, + 'gaze_dir': array([0.99279022, 0.08239746, 0.08530426]), + 'gaze_origin': array([-3.83407927, -0.05384674, -0.21123964]), + 'gaze_valid': True, + 'gaze_vergence': 61.795440673828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99368286, 0.08804321, 0.06950378]), + 'left_gaze_origin': array([-3.58868122, 2.74645233, -0.30129549]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.211395263671875, + 'left_pupil_posn': array([ 0.38167667, -0.41403019]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99189758, 0.07675171, 0.10110474]), + 'right_gaze_origin': array([-4.07947731, -2.85414577, -0.12118378]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.939056396484375, + 'right_pupil_posn': array([-0.20332998, -0.44000506]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.3553905785084, + 'timestamp_carla': 688357, + 'timestamp_device': 3841788, + 'timestamp_stream': 688.3553905785084, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88276677e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-2.27641743e-02, 7.15962145e-04, 3.29843024e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.12762427, -17.35155678, 0.17100771]), + 'Rotation': array([ 4.31667920e-03, -9.18887329e+01, 6.37224913e-02]), + 'Velocity': array([-3.16472314e-02, -9.55513835e-01, -3.36933117e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.22101116, 16.98352432, 0.24052423]), + 'camera_rotation': array([-5.24657536, 3.0129149 , 0.40111718]), + 'current_gear_input': False, + 'focus_actor_dist': 3833.21484375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 166.8745575 , -5331.49023438, 114.81638336]), + 'frame': 21292, + 'frame_number': 21292, + 'framesequence': 81485, + 'gaze_dir': array([0.99272919, 0.0839386 , 0.0846405 ]), + 'gaze_origin': array([-3.83220458, -0.05402603, -0.21126938]), + 'gaze_valid': True, + 'gaze_vergence': 58.34178924560547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99362183, 0.08865356, 0.06945801]), + 'left_gaze_origin': array([-3.58500528, 2.74645233, -0.30129549]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1992645263671875, + 'left_pupil_posn': array([ 0.38249481, -0.41365266]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99183655, 0.07922363, 0.099823 ]), + 'right_gaze_origin': array([-4.07940388, -2.85450459, -0.12124328]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9218292236328125, + 'right_pupil_posn': array([-0.20281386, -0.44000506]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.3871699757874, + 'timestamp_carla': 688389, + 'timestamp_device': 3841821, + 'timestamp_stream': 688.3871699757874, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89981836e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 2.28292705e-03, -1.12631860e-04, 1.61090775e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.13534117, -17.5845356 , 0.1711175 ]), + 'Rotation': array([ 5.24558499e-03, -9.18887329e+01, 6.37159124e-02]), + 'Velocity': array([-2.88204346e-02, -8.70222151e-01, 2.45752337e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.19811916, 16.95990944, 0.22395366]), + 'camera_rotation': array([-5.37168407, 2.9258709 , 0.4266744 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3833.11572265625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 165.73175049, -5331.48974609, 107.27947998]), + 'frame': 21293, + 'frame_number': 21293, + 'framesequence': 81489, + 'gaze_dir': array([0.99121857, 0.09040833, 0.09340668]), + 'gaze_origin': array([-3.77453351, -0.05626908, -0.23185883]), + 'gaze_valid': True, + 'gaze_vergence': 2.914837598800659, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99362183, 0.08862305, 0.06967163]), + 'left_gaze_origin': array([-3.47219253, 2.74251103, -0.34154361]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2188873291015625, + 'left_pupil_posn': array([ 0.3871733 , -0.41082978]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98881531, 0.0921936 , 0.11714172]), + 'right_gaze_origin': array([-4.07687378, -2.85504937, -0.12217408]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9104156494140625, + 'right_pupil_posn': array([-0.20240968, -0.43999147]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.4209782779217, + 'timestamp_carla': 688423, + 'timestamp_device': 3841854, + 'timestamp_stream': 688.4209782779217, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89539341e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-6.72161696e-05, -2.61010136e-05, 7.64990691e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.14173269, -17.77755928, 0.17117925]), + 'Rotation': array([ 5.24558499e-03, -9.18887329e+01, 6.37159124e-02]), + 'Velocity': array([-2.61094403e-02, -7.88677752e-01, 9.90295375e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.1864357 , 16.92819214, 0.21076316]), + 'camera_rotation': array([-5.44760132, 2.79571223, 0.3905482 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3835.03076171875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 185.36401367, -5331.49023438, 132.55718994]), + 'frame': 21294, + 'frame_number': 21294, + 'framesequence': 81492, + 'gaze_dir': array([0.99061584, 0.09075165, 0.09938049]), + 'gaze_origin': array([-3.73168039, -0.05796738, -0.24526902]), + 'gaze_valid': True, + 'gaze_vergence': 15.942584991455078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99278259, 0.09255981, 0.07614136]), + 'left_gaze_origin': array([-3.38635588, 2.74239206, -0.37126926]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.20428466796875, + 'left_pupil_posn': array([ 0.38365293, -0.41054761]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9884491 , 0.08894348, 0.12261963]), + 'right_gaze_origin': array([-4.07700491, -2.85832667, -0.1192688 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8310546875, + 'right_pupil_posn': array([-0.19824266, -0.43512392]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.4524023756385, + 'timestamp_carla': 688454, + 'timestamp_device': 3841879, + 'timestamp_stream': 688.4524023756385, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90943147e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.01698272, 0.00066007, 0.0223657 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04555356130003929, + 'FR_Wheel_Angle': 0.06202349066734314, + 'Location': array([ -2.1467073 , -17.92924118, 0.17124796]), + 'Rotation': array([ 3.41509446e-03, -9.18875046e+01, 6.36692867e-02]), + 'Velocity': array([-2.18991488e-02, -6.73438430e-01, -4.54807268e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.17042923, 16.89881325, 0.2535744 ]), + 'camera_rotation': array([-5.47111797, 2.67758703, 0.26433265]), + 'current_gear_input': False, + 'focus_actor_dist': 3834.20654296875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 177.85269165, -5331.49023438, 150.71722412]), + 'frame': 21295, + 'frame_number': 21295, + 'framesequence': 81497, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 25.6355037689209, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.99623108, 0.07295227, 0.04676819]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.35965919, -2.85547948, -0.02426911]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([-0.20801759, -0.44061887]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.4869392774999, + 'timestamp_carla': 688489, + 'timestamp_device': 3841921, + 'timestamp_stream': 688.4869392774999, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89455405e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.00114899, -0.00491934, 0.61414176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1863308697938919, + 'FR_Wheel_Angle': 0.19305706024169922, + 'Location': array([ -2.15310669, -18.12986755, 0.17120194]), + 'Rotation': array([ 1.59348305e-02, -9.18782349e+01, 6.34995550e-02]), + 'Velocity': array([-0.02648667, -0.86733997, -0.00093734]), + 'brake_input': 0.0, + 'camera_location': array([-6.15758133, 16.87268066, 0.30417177]), + 'camera_rotation': array([-5.4718008 , 2.53846025, 0.16744551]), + 'current_gear_input': False, + 'focus_actor_dist': 1231.8306884765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -215.44168091, -2749.14355469, 16.97634125]), + 'frame': 21296, + 'frame_number': 21296, + 'framesequence': 81501, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5845073461532593, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.13518095, -2.83766508, -0.07636414]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.5199509784579, + 'timestamp_carla': 688522, + 'timestamp_device': 3841954, + 'timestamp_stream': 688.5199509784579, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89783464e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.01320225, -0.00082603, 0.11124574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3300734758377075, + 'FR_Wheel_Angle': 0.3408624529838562, + 'Location': array([ -2.15950036, -18.33579254, 0.17131186]), + 'Rotation': array([ 2.13580001e-02, -9.18538437e+01, 6.33953214e-02]), + 'Velocity': array([-3.25109214e-02, -1.10094559e+00, 7.52258289e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.14806366, 16.84021378, 0.39083433]), + 'camera_rotation': array([-5.49852037, 2.36678672, 0.05619364]), + 'current_gear_input': False, + 'focus_actor_dist': 1232.199462890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -218.44161987, -2749.55761719, 16.97940063]), + 'frame': 21297, + 'frame_number': 21297, + 'framesequence': 81505, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 15.252135276794434, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.99736023, 0.02987671, 0.0660553 ]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5671015381813049, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.11043072, -2.80497289, -0.111055 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.718902587890625, + 'right_pupil_posn': array([-0.26273447, -0.43971157]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.5527284778655, + 'timestamp_carla': 688555, + 'timestamp_device': 3841988, + 'timestamp_stream': 688.5527284778655, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90130614e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.04827598, 0.00030377, 0.18837111]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.401732861995697, + 'FR_Wheel_Angle': 0.45411375164985657, + 'Location': array([ -2.16848731, -18.64099121, 0.1713841 ]), + 'Rotation': array([ 2.56883409e-02, -9.18181152e+01, 6.32898584e-02]), + 'Velocity': array([-0.04143462, -1.47167003, 0.00195546]), + 'brake_input': 0.0, + 'camera_location': array([-6.10933113, 16.80734253, 0.53274405]), + 'camera_rotation': array([-5.49660826, 2.1876893 , -0.054511 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1227.12890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -222.19004822, -2744.49853516, 16.98355103]), + 'frame': 21298, + 'frame_number': 21298, + 'framesequence': 81509, + 'gaze_dir': array([ 0.99325562, 0.03633118, -0.05928802]), + 'gaze_origin': array([-3.92093444, -0.02193832, -0.26469803]), + 'gaze_valid': True, + 'gaze_vergence': 14.175853729248047, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99969482, -0.00375366, 0.02403259]), + 'left_gaze_origin': array([-3.63177347, 2.74471903, -0.42392427]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.8671417236328125, + 'left_pupil_posn': array([ 0.38171172, -0.60521603]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.6783854365348816, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98681641, 0.07641602, -0.14260864]), + 'right_gaze_origin': array([-4.21009541, -2.78859568, -0.1054718 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.84033203125, + 'right_pupil_posn': array([-0.29008502, -0.47648668]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 688.5857574790716, + 'timestamp_carla': 688588, + 'timestamp_device': 3842021, + 'timestamp_stream': 688.5857574790716, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90130614e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.00419325, -0.00108721, 0.31217808]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.17848849, -19.00485992, 0.17158613]), + 'Rotation': array([ 1.85781140e-02, -9.17570419e+01, 6.30065873e-02]), + 'Velocity': array([-3.95353176e-02, -1.57847011e+00, 1.15436548e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.0599575 , 16.78493118, 0.66584438]), + 'camera_rotation': array([-5.35656881, 2.00865626, -0.17636158]), + 'current_gear_input': False, + 'focus_actor_dist': 760.6474609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -200.57145691, -2269.98632812, 17.00232697]), + 'frame': 21299, + 'frame_number': 21299, + 'framesequence': 81513, + 'gaze_dir': array([ 0.99890137, -0.0262146 , 0.03591919]), + 'gaze_origin': array([-3.96995473, 0.03015824, -0.20313875]), + 'gaze_valid': True, + 'gaze_vergence': 189.02638244628906, + 'handbrake_input': False, + 'left_eye_openness': 0.3326159715652466, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99942017, -0.01335144, 0.03088379]), + 'left_gaze_origin': array([-3.92156243, 2.83561254, -0.20624085]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8256988525390625, + 'left_pupil_posn': array([ 0.2789973 , -0.44166112]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9115853905677795, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99838257, -0.03907776, 0.04095459]), + 'right_gaze_origin': array([-4.01834726, -2.77529621, -0.20003663]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.98773193359375, + 'right_pupil_posn': array([-0.30342013, -0.50062394]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00043946655932813883, + 'throttle_input': 0.0, + 'timestamp': 688.6208100765944, + 'timestamp_carla': 688623, + 'timestamp_device': 3842054, + 'timestamp_stream': 688.6208100765944, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88528437e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.04496467, 0.01361228, -0.00024113]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.18906069, -19.35101891, 0.17170236]), + 'Rotation': array([ 9.33686830e-03, -9.17543335e+01, 6.55776188e-02]), + 'Velocity': array([-4.63841520e-02, -1.50876951e+00, -6.68354041e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.00771141, 16.77500916, 0.73191112]), + 'camera_rotation': array([-5.15662861, 1.86570787, -0.23491079]), + 'current_gear_input': False, + 'focus_actor_dist': 2051.818115234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -282.44650269, -3566.96240234, 17.0395813 ]), + 'frame': 21300, + 'frame_number': 21300, + 'framesequence': 81517, + 'gaze_dir': array([ 0.99921417, -0.02865601, 0.02404022]), + 'gaze_origin': array([-3.89566827, 0.02610092, -0.234964 ]), + 'gaze_valid': True, + 'gaze_vergence': 210.53773498535156, + 'handbrake_input': False, + 'left_eye_openness': 0.4475460648536682, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9994812, -0.0163269, 0.0275116]), + 'left_gaze_origin': array([-3.81231093, 2.83159494, -0.25083926]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9783935546875, + 'left_pupil_posn': array([ 0.2796756 , -0.45734715]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99894714, -0.04098511, 0.02056885]), + 'right_gaze_origin': array([-3.97902536, -2.7793932 , -0.21908875]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.939483642578125, + 'right_pupil_posn': array([-0.30133802, -0.50684178]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004577776708174497, + 'throttle_input': 0.0, + 'timestamp': 688.6527795791626, + 'timestamp_carla': 688655, + 'timestamp_device': 3842088, + 'timestamp_stream': 688.6527795791626, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89955130e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.02577262, -0.00172272, 0.0001572 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.20042682, -19.71998405, 0.17184496]), + 'Rotation': array([-7.03509431e-04, -9.17543335e+01, 6.54944554e-02]), + 'Velocity': array([-4.18237075e-02, -1.35713387e+00, 7.35545123e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.96209335, 16.76948738, 0.72228491]), + 'camera_rotation': array([-5.14422512, 1.74337232, -0.25670722]), + 'current_gear_input': False, + 'focus_actor_dist': 1789.95556640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -284.81460571, -3304.56518555, 17.04360962]), + 'frame': 21301, + 'frame_number': 21301, + 'framesequence': 81521, + 'gaze_dir': array([ 0.99917603, -0.02351379, 0.02957153]), + 'gaze_origin': array([-3.87745094, 0.02426147, -0.24591905]), + 'gaze_valid': True, + 'gaze_vergence': 185.7954559326172, + 'handbrake_input': False, + 'left_eye_openness': 0.6536827683448792, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99940491, -0.00930786, 0.0330658 ]), + 'left_gaze_origin': array([-3.77922249, 2.8289597 , -0.27026519]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09228515625, + 'left_pupil_posn': array([ 0.28245151, -0.46221602]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99894714, -0.03771973, 0.02607727]), + 'right_gaze_origin': array([-3.9756794 , -2.78043699, -0.22157289]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9785919189453125, + 'right_pupil_posn': array([-0.29781169, -0.50584614]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.68726817891, + 'timestamp_carla': 688689, + 'timestamp_device': 3842121, + 'timestamp_stream': 688.68726817891, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88932794e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([0.08269571, 0.0079605 , 0.51386076]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.390899896621704, + 'FR_Wheel_Angle': 1.4418543577194214, + 'Location': array([ -2.20684814, -19.98819351, 0.17184763]), + 'Rotation': array([-8.66751000e-03, -9.16744766e+01, 6.32474199e-02]), + 'Velocity': array([-1.74898915e-02, -1.11843181e+00, 4.13455942e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.93320274, 16.75980949, 0.61524439]), + 'camera_rotation': array([-5.36087179, 1.59873354, -0.31442732]), + 'current_gear_input': False, + 'focus_actor_dist': 1960.4437255859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -284.01028442, -3475.5456543 , 17.04176331]), + 'frame': 21302, + 'frame_number': 21302, + 'framesequence': 81525, + 'gaze_dir': array([ 0.9989624 , -0.02187347, 0.03410339]), + 'gaze_origin': array([-3.90663338, 0.02535858, -0.23301621]), + 'gaze_valid': True, + 'gaze_vergence': 101.58982849121094, + 'handbrake_input': False, + 'left_eye_openness': 0.7707498669624329, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99884033, -0.00642395, 0.04766846]), + 'left_gaze_origin': array([-3.77902532, 2.8301363 , -0.25980225]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.06805419921875, + 'left_pupil_posn': array([ 0.28157711, -0.45633519]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99908447, -0.037323 , 0.02053833]), + 'right_gaze_origin': array([-4.03424072, -2.77941918, -0.20623018]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9820098876953125, + 'right_pupil_posn': array([-0.29780245, -0.50258482]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.7207666784525, + 'timestamp_carla': 688723, + 'timestamp_device': 3842154, + 'timestamp_stream': 688.7207666784525, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89146416e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([0.02545124, 0.00483736, 0.68441403]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.7688370943069458, + 'FR_Wheel_Angle': 1.8571579456329346, + 'Location': array([ -2.21097565, -20.24982452, 0.17188932]), + 'Rotation': array([-6.65260386e-03, -9.15332947e+01, 6.39992058e-02]), + 'Velocity': array([-1.02091394e-02, -1.06729901e+00, 2.16970438e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.89999485, 16.72673035, 0.46856508]), + 'camera_rotation': array([-5.69879532, 1.50953293, -0.11750928]), + 'current_gear_input': False, + 'focus_actor_dist': 1983.51708984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -286.47817993, -3498.60791016, 17.04414368]), + 'frame': 21303, + 'frame_number': 21303, + 'framesequence': 81529, + 'gaze_dir': array([ 0.9982605 , -0.02577972, 0.0491333 ]), + 'gaze_origin': array([-3.85177255, 0.02687759, -0.24716797]), + 'gaze_valid': True, + 'gaze_vergence': 85.70484161376953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99778748, -0.01411438, 0.06477356]), + 'left_gaze_origin': array([-3.79626346, 2.83159661, -0.24970704]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0709228515625, + 'left_pupil_posn': array([ 0.28058553, -0.44789672]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99873352, -0.03744507, 0.03349304]), + 'right_gaze_origin': array([-3.90728164, -2.77784133, -0.24462892]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.03277587890625, + 'right_pupil_posn': array([-0.30072516, -0.49459469]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.753407176584, + 'timestamp_carla': 688755, + 'timestamp_device': 3842188, + 'timestamp_stream': 688.753407176584, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89905537e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([0.03411721, 0.0024742 , 0.81063658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.183133602142334, + 'FR_Wheel_Angle': 2.3121588230133057, + 'Location': array([ -2.21331453, -20.47719955, 0.17186543]), + 'Rotation': array([-2.41105654e-03, -9.13807373e+01, 6.37857094e-02]), + 'Velocity': array([-3.92417656e-03, -1.14848709e+00, 1.51815417e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.86341476, 16.64748764, 0.3366802 ]), + 'camera_rotation': array([-5.9336853 , 1.36924565, 0.27706298]), + 'current_gear_input': False, + 'focus_actor_dist': 2344.8583984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -309.04153442, -3860.06542969, 17.06513214]), + 'frame': 21304, + 'frame_number': 21304, + 'framesequence': 81533, + 'gaze_dir': array([ 0.99759674, -0.01489258, 0.06279755]), + 'gaze_origin': array([-3.85928822, 0.01518097, -0.22883987]), + 'gaze_valid': True, + 'gaze_vergence': 85.81056213378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99891663, 0.00360107, 0.04629517]), + 'left_gaze_origin': array([-3.69806695, 2.81853962, -0.27898407]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1526641845703125, + 'left_pupil_posn': array([ 0.28952122, -0.42924154]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99627686, -0.03338623, 0.07929993]), + 'right_gaze_origin': array([-4.02050972, -2.78817773, -0.17869569]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9546356201171875, + 'right_pupil_posn': array([-0.28636384, -0.47844732]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.7863176763058, + 'timestamp_carla': 688788, + 'timestamp_device': 3842221, + 'timestamp_stream': 688.7863176763058, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90145865e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 5.00834584e-02, -1.21877012e-04, 1.25245988e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.019118070602417, + 'FR_Wheel_Angle': 3.2447245121002197, + 'Location': array([ -2.21411037, -20.76613426, 0.17186242]), + 'Rotation': array([-4.57622635e-04, -9.11406860e+01, 6.26055673e-02]), + 'Velocity': array([ 1.04473578e-02, -1.30705380e+00, -6.71195958e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.77941704, 16.53473282, 0.26709789]), + 'camera_rotation': array([-5.91768217, 1.06838536, 0.37667707]), + 'current_gear_input': False, + 'focus_actor_dist': 2903.5634765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -301.80822754, -4419.80175781, 17.05434418]), + 'frame': 21305, + 'frame_number': 21305, + 'framesequence': 81537, + 'gaze_dir': array([0.99301147, 0.03865051, 0.11109161]), + 'gaze_origin': array([-3.81492043, -0.01986923, -0.2073288 ]), + 'gaze_valid': True, + 'gaze_vergence': 301.652099609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9924469 , 0.0473175 , 0.11314392]), + 'left_gaze_origin': array([-3.64125061, 2.77538323, -0.25984803]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2628021240234375, + 'left_pupil_posn': array([ 0.34331071, -0.39192522]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99357605, 0.02998352, 0.10903931]), + 'right_gaze_origin': array([-3.98858976, -2.81512165, -0.15480958]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.068145751953125, + 'right_pupil_posn': array([-0.24773198, -0.42722487]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.82031307742, + 'timestamp_carla': 688822, + 'timestamp_device': 3842254, + 'timestamp_stream': 688.82031307742, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89447769e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([0.07784846, 0.00769195, 1.87996674]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.7882447242736816, + 'FR_Wheel_Angle': 4.013747215270996, + 'Location': array([ -2.21034074, -21.13272095, 0.17183565]), + 'Rotation': array([-3.11456621e-03, -9.07186966e+01, 6.12631924e-02]), + 'Velocity': array([ 3.63170654e-02, -1.47666705e+00, -1.20339391e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.6516304 , 16.42017937, 0.24244402]), + 'camera_rotation': array([-5.78150892, 0.78278148, 0.34958184]), + 'current_gear_input': False, + 'focus_actor_dist': 3813.19287109375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -137.8218689 , -5331.49072266, 164.82745361]), + 'frame': 21306, + 'frame_number': 21306, + 'framesequence': 81541, + 'gaze_dir': array([0.99267578, 0.0412674 , 0.11260223]), + 'gaze_origin': array([-3.80482268, -0.02825852, -0.22084734]), + 'gaze_valid': True, + 'gaze_vergence': 172.35569763183594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99302673, 0.05311584, 0.10513306]), + 'left_gaze_origin': array([-3.55964088, 2.77005935, -0.30013734]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2772979736328125, + 'left_pupil_posn': array([ 0.3452177 , -0.39866328]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99232483, 0.02941895, 0.12007141]), + 'right_gaze_origin': array([-4.05000496, -2.82657623, -0.14155732]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0136871337890625, + 'right_pupil_posn': array([-0.23726952, -0.43456316]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.8547633774579, + 'timestamp_carla': 688857, + 'timestamp_device': 3842288, + 'timestamp_stream': 688.8547633774579, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88703921e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.02542031, -0.00447242, 2.63554358]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.3766703605651855, + 'FR_Wheel_Angle': 4.760380744934082, + 'Location': array([ -2.20221806, -21.47664833, 0.17186289]), + 'Rotation': array([-1.28407544e-03, -9.02429886e+01, 5.96456043e-02]), + 'Velocity': array([ 6.83710352e-02, -1.77349651e+00, 2.49519333e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.47499847, 16.32428551, 0.26498386]), + 'camera_rotation': array([-5.58466959, 0.35943142, 0.11428834]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.991943359375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -147.08770752, -5331.48925781, 179.71661377]), + 'frame': 21307, + 'frame_number': 21307, + 'framesequence': 81545, + 'gaze_dir': array([0.99233246, 0.04238129, 0.11475372]), + 'gaze_origin': array([-3.85942459, -0.03540573, -0.21325685]), + 'gaze_valid': True, + 'gaze_vergence': 133.3830108642578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99295044, 0.05593872, 0.10444641]), + 'left_gaze_origin': array([-3.65950322, 2.76467156, -0.277475 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.209625244140625, + 'left_pupil_posn': array([ 0.35151899, -0.4031328 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99171448, 0.02882385, 0.12506104]), + 'right_gaze_origin': array([-4.0593462 , -2.83548284, -0.1490387 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9262847900390625, + 'right_pupil_posn': array([-0.2296555 , -0.44248414]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.8872123770416, + 'timestamp_carla': 688889, + 'timestamp_device': 3842321, + 'timestamp_stream': 688.8872123770416, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89787282e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.00500236, -0.01670162, 4.22101688]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.586887359619141, + 'FR_Wheel_Angle': 6.07818603515625, + 'Location': array([ -2.18574262, -21.88385201, 0.17188174]), + 'Rotation': array([ 2.81403773e-03, -8.95543747e+01, 5.49762845e-02]), + 'Velocity': array([ 1.34777233e-01, -2.21981549e+00, 4.68535407e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.34919548, 16.25812149, 0.17432933]), + 'camera_rotation': array([-5.92387056, -0.04561687, -0.05997226]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.712646484375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -172.79116821, -5331.49023438, 201.78678894]), + 'frame': 21308, + 'frame_number': 21308, + 'framesequence': 81549, + 'gaze_dir': array([0.99169922, 0.04615784, 0.11643219]), + 'gaze_origin': array([-3.88973808, -0.0422493 , -0.19448319]), + 'gaze_valid': True, + 'gaze_vergence': 45.0310173034668, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9941864 , 0.05839539, 0.09043884]), + 'left_gaze_origin': array([-3.60881495, 2.75645304, -0.29137728]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.34197998046875, + 'left_pupil_posn': array([ 0.35821104, -0.39575684]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98921204, 0.03392029, 0.14242554]), + 'right_gaze_origin': array([-4.1706605 , -2.84095168, -0.09758911]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9990692138671875, + 'right_pupil_posn': array([-0.22465014, -0.43528199]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.9188912771642, + 'timestamp_carla': 688921, + 'timestamp_device': 3842354, + 'timestamp_stream': 688.9188912771642, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90924055e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 3.89645086e-03, -2.12350097e-02, 6.67613745e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.731600761413574, + 'FR_Wheel_Angle': 7.404697418212891, + 'Location': array([ -2.14060593, -22.55150986, 0.17183721]), + 'Rotation': array([ 1.88513217e-03, -8.81333923e+01, 4.84721437e-02]), + 'Velocity': array([ 2.73843169e-01, -2.78829694e+00, -5.42125665e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.30457306, 16.20104408, -0.04162311]), + 'camera_rotation': array([-6.84430695, -0.34581321, 0.22754875]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.183837890625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -186.69734192, -5331.49023438, 186.33529663]), + 'frame': 21309, + 'frame_number': 21309, + 'framesequence': 81552, + 'gaze_dir': array([0.99099731, 0.05434418, 0.12006378]), + 'gaze_origin': array([-3.85584569, -0.044664 , -0.19118883]), + 'gaze_valid': True, + 'gaze_vergence': 75.71139526367188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99249268, 0.06799316, 0.10150146]), + 'left_gaze_origin': array([-3.57759714, 2.7541275 , -0.28575745]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30169677734375, + 'left_pupil_posn': array([ 0.36139894, -0.38581848]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98950195, 0.04069519, 0.1386261 ]), + 'right_gaze_origin': array([-4.13409424, -2.84345555, -0.09662018]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8346099853515625, + 'right_pupil_posn': array([-0.21852952, -0.42113841]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.9529874771833, + 'timestamp_carla': 688955, + 'timestamp_device': 3842379, + 'timestamp_stream': 688.9529874771833, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89794919e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 8.16030800e-02, -7.75084924e-03, 9.05145741e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.303041458129883, + 'FR_Wheel_Angle': 9.280062675476074, + 'Location': array([ -2.06680202, -23.24059105, 0.17171873]), + 'Rotation': array([-7.54052866e-03, -8.63196335e+01, 4.13538814e-02]), + 'Velocity': array([ 4.39247161e-01, -3.00002289e+00, -7.14235299e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.27994156, 16.16861916, -0.24930505]), + 'camera_rotation': array([-7.703722 , -0.60543197, 0.27652708]), + 'current_gear_input': False, + 'focus_actor_dist': 3811.935791015625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -173.27003479, -5331.48925781, 138.05838013]), + 'frame': 21310, + 'frame_number': 21310, + 'framesequence': 81557, + 'gaze_dir': array([0.99012756, 0.05635834, 0.12503052]), + 'gaze_origin': array([-3.91921997, -0.05060044, -0.16254045]), + 'gaze_valid': True, + 'gaze_vergence': 56.04970932006836, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99229431, 0.07182312, 0.10089111]), + 'left_gaze_origin': array([-3.6328752 , 2.74751902, -0.26426086]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3144989013671875, + 'left_pupil_posn': array([ 0.36768734, -0.37898374]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98796082, 0.04089355, 0.14916992]), + 'right_gaze_origin': array([-4.20556498, -2.84872007, -0.06082001]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7751922607421875, + 'right_pupil_posn': array([-0.21282804, -0.4106915 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 688.9868391789496, + 'timestamp_carla': 688989, + 'timestamp_device': 3842421, + 'timestamp_stream': 688.9868391789496, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89337151e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 7.20823705e-02, -4.87406412e-03, 1.10731773e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.53309154510498, + 'FR_Wheel_Angle': 12.129700660705566, + 'Location': array([ -1.95938087, -23.92106628, 0.17160848]), + 'Rotation': array([-2.66445670e-02, -8.40616989e+01, 3.72508317e-02]), + 'Velocity': array([ 5.91778219e-01, -2.80920506e+00, -7.74931919e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.24525166, 16.15715218, -0.37368241]), + 'camera_rotation': array([-8.24394894, -0.76421744, 0.19515607]), + 'current_gear_input': False, + 'focus_actor_dist': 3811.989013671875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -182.39059448, -5331.48925781, 99.85514832]), + 'frame': 21311, + 'frame_number': 21311, + 'framesequence': 81561, + 'gaze_dir': array([0.99110413, 0.05229187, 0.12071228]), + 'gaze_origin': array([-4.03911686, -0.05056687, -0.11490326]), + 'gaze_valid': True, + 'gaze_vergence': 94.88618469238281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99226379, 0.06497192, 0.10568237]), + 'left_gaze_origin': array([-3.83707929, 2.74964619, -0.18708344]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2173309326171875, + 'left_pupil_posn': array([ 0.37086856, -0.37375271]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98994446, 0.03961182, 0.13574219]), + 'right_gaze_origin': array([-4.24115467, -2.85078001, -0.04272309]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.86126708984375, + 'right_pupil_posn': array([-0.21383429, -0.40352976]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 689.0205702781677, + 'timestamp_carla': 689022, + 'timestamp_device': 3842454, + 'timestamp_stream': 689.0205702781677, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89180758e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.02683008, 0.0217526 , 11.97648525]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.713730812072754, + 'FR_Wheel_Angle': 14.782852172851562, + 'Location': array([ -1.81814635, -24.54713249, 0.1714332 ]), + 'Rotation': array([-3.72928306e-02, -8.13917084e+01, 3.54722962e-02]), + 'Velocity': array([ 7.29415178e-01, -2.52449250e+00, -1.22685428e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.23239899, 16.1559906 , -0.45298567]), + 'camera_rotation': array([-8.70359325, -0.72399074, 0.3683666 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.63427734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -209.27355957, -5331.48974609, 47.51177979]), + 'frame': 21312, + 'frame_number': 21312, + 'framesequence': 81565, + 'gaze_dir': array([0.99111176, 0.0579071 , 0.11925507]), + 'gaze_origin': array([-4.04889011, -0.04848786, -0.10264283]), + 'gaze_valid': True, + 'gaze_vergence': 240.2661590576172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99102783, 0.06793213, 0.11508179]), + 'left_gaze_origin': array([-3.87143564, 2.75327778, -0.16473085]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.184967041015625, + 'left_pupil_posn': array([ 0.37211335, -0.36966205]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99119568, 0.04788208, 0.12342834]), + 'right_gaze_origin': array([-4.22634459, -2.85025358, -0.04055481]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9209442138671875, + 'right_pupil_posn': array([-0.21290499, -0.39494991]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 689.0532289780676, + 'timestamp_carla': 689055, + 'timestamp_device': 3842488, + 'timestamp_stream': 689.0532289780676, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89890287e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([7.66231865e-03, 2.35682409e-02, 1.22273951e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.211544036865234, + 'FR_Wheel_Angle': 16.67021942138672, + 'Location': array([ -1.65180647, -25.10860825, 0.17122419]), + 'Rotation': array([-4.16231714e-02, -7.85423889e+01, 3.92444320e-02]), + 'Velocity': array([ 8.14499140e-01, -2.23575568e+00, -1.09416002e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.26054192, 16.18312073, -0.47194812]), + 'camera_rotation': array([-8.96503258, -0.44957364, 0.53479367]), + 'current_gear_input': False, + 'focus_actor_dist': 3618.230224609375, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -186.30160522, -5135.95947266, 16.99240875]), + 'frame': 21313, + 'frame_number': 21313, + 'framesequence': 81569, + 'gaze_dir': array([0.98960876, 0.05364227, 0.13264465]), + 'gaze_origin': array([-3.9991107 , -0.04716874, -0.12144013]), + 'gaze_valid': True, + 'gaze_vergence': 206.97361755371094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98873901, 0.06695557, 0.1337738 ]), + 'left_gaze_origin': array([-3.85729074, 2.75346994, -0.16931458]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.118682861328125, + 'left_pupil_posn': array([ 0.36854923, -0.36644626]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99047852, 0.04032898, 0.1315155 ]), + 'right_gaze_origin': array([-4.14093018, -2.84780741, -0.07356568]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9384307861328125, + 'right_pupil_posn': array([-0.215029 , -0.39311099]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005310220876708627, + 'throttle_input': 0.0, + 'timestamp': 689.0878230780363, + 'timestamp_carla': 689090, + 'timestamp_device': 3842521, + 'timestamp_stream': 689.0878230780363, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88825971e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([1.01030068e-02, 3.19580920e-02, 1.26572104e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.34473991394043, + 'FR_Wheel_Angle': 18.062652587890625, + 'Location': array([ -1.47235298, -25.59956741, 0.17100541]), + 'Rotation': array([-4.51680385e-02, -7.57012177e+01, 4.44919951e-02]), + 'Velocity': array([ 8.47719908e-01, -1.94335854e+00, -1.18612288e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.25227928, 16.2102375 , -0.41996267]), + 'camera_rotation': array([-8.8462553 , -0.07485345, 0.53293139]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.9716796875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -180.04786682, -5331.49023438, 44.1265564 ]), + 'frame': 21314, + 'frame_number': 21314, + 'framesequence': 81573, + 'gaze_dir': array([0.99010468, 0.05068207, 0.1292038 ]), + 'gaze_origin': array([-3.93681264, -0.04710007, -0.14880677]), + 'gaze_valid': True, + 'gaze_vergence': 47.047786712646484, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99230957, 0.05677795, 0.10993958]), + 'left_gaze_origin': array([-3.67440057, 2.75341964, -0.24179994]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1692657470703125, + 'left_pupil_posn': array([ 0.3655057 , -0.37172592]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98789978, 0.04458618, 0.14846802]), + 'right_gaze_origin': array([-4.19922495, -2.84761977, -0.0558136 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.78619384765625, + 'right_pupil_posn': array([-0.21929789, -0.40176558]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005127110052853823, + 'throttle_input': 0.0, + 'timestamp': 689.120154876262, + 'timestamp_carla': 689122, + 'timestamp_device': 3842554, + 'timestamp_stream': 689.120154876262, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89924606e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-1.56500712e-02, -5.58899716e-03, 1.13366537e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.943735122680664, + 'FR_Wheel_Angle': 18.873239517211914, + 'Location': array([ -1.28834271, -26.02659416, 0.17078531]), + 'Rotation': array([-4.50792462e-02, -7.30140533e+01, 4.69821692e-02]), + 'Velocity': array([ 8.75547767e-01, -1.73192382e+00, -5.11646271e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.24065208, 16.25372505, -0.33907446]), + 'camera_rotation': array([-8.52514839, 0.33124089, 0.42307574]), + 'current_gear_input': False, + 'focus_actor_dist': 3813.243896484375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -166.53665161, -5331.48925781, 38.84506226]), + 'frame': 21315, + 'frame_number': 21315, + 'framesequence': 81577, + 'gaze_dir': array([0.9882431 , 0.0493927 , 0.14276123]), + 'gaze_origin': array([-3.85108972, -0.04304581, -0.19008179]), + 'gaze_valid': True, + 'gaze_vergence': 58.82687759399414, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9907074 , 0.0597229 , 0.12211609]), + 'left_gaze_origin': array([-3.56329679, 2.75677657, -0.29103547]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22174072265625, + 'left_pupil_posn': array([ 0.35823095, -0.37692475]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98577881, 0.0390625 , 0.16340637]), + 'right_gaze_origin': array([-4.13888264, -2.84286809, -0.08912811]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8454132080078125, + 'right_pupil_posn': array([-0.22185057, -0.40850985]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004577776708174497, + 'throttle_input': 0.0, + 'timestamp': 689.1537932790816, + 'timestamp_carla': 689156, + 'timestamp_device': 3842588, + 'timestamp_stream': 689.1537932790816, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89615616e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([3.27762240e-03, 1.39840357e-02, 1.07976398e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.387937545776367, + 'FR_Wheel_Angle': 19.402904510498047, + 'Location': array([ -1.1265856 , -26.35581207, 0.17057589]), + 'Rotation': array([-4.49221507e-02, -7.08315125e+01, 4.89541329e-02]), + 'Velocity': array([ 8.84978771e-01, -1.57500291e+00, 1.56955721e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.23948669, 16.29590988, -0.29239637]), + 'camera_rotation': array([-8.35611439, 0.70751154, 0.36375466]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.458740234375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -144.94415283, -5331.48925781, 112.76593018]), + 'frame': 21316, + 'frame_number': 21316, + 'framesequence': 81581, + 'gaze_dir': array([0.98994446, 0.04375458, 0.13265991]), + 'gaze_origin': array([-3.979671 , -0.03388825, -0.15044938]), + 'gaze_valid': True, + 'gaze_vergence': 62.3816032409668, + 'handbrake_input': False, + 'left_eye_openness': 0.7715327739715576, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98695374, 0.05444336, 0.15144348]), + 'left_gaze_origin': array([-3.92737269, 2.77219391, -0.15765686]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09332275390625, + 'left_pupil_posn': array([ 0.35369539, -0.38037217]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99293518, 0.0330658 , 0.11387634]), + 'right_gaze_origin': array([-4.03196907, -2.83997059, -0.1432419 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9442596435546875, + 'right_pupil_posn': array([-0.22604144, -0.4136281 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00043946655932813883, + 'throttle_input': 0.0, + 'timestamp': 689.1864609792829, + 'timestamp_carla': 689188, + 'timestamp_device': 3842621, + 'timestamp_stream': 689.1864609792829, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90142046e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([2.56387284e-03, 1.00042326e-02, 9.97332478e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.771259307861328, + 'FR_Wheel_Angle': 19.966482162475586, + 'Location': array([ -0.93294019, -26.70919609, 0.17035708]), + 'Rotation': array([-4.67184931e-02, -6.83759308e+01, 5.15819937e-02]), + 'Velocity': array([ 8.70015383e-01, -1.38846457e+00, -5.48400858e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.20853233, 16.33463478, -0.27577126]), + 'camera_rotation': array([-8.31431389, 1.0129379 , 0.26650521]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.894775390625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -142.2306366 , -5331.48974609, 85.36216736]), + 'frame': 21317, + 'frame_number': 21317, + 'framesequence': 81585, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.7386146783828735, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-8.92190075, -2.85972452, 1.42772067]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00043946655932813883, + 'throttle_input': 0.0, + 'timestamp': 689.2198733761907, + 'timestamp_carla': 689222, + 'timestamp_device': 3842654, + 'timestamp_stream': 689.2198733761907, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89890287e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([9.13815515e-04, 6.72863470e-03, 9.27534389e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.89145851135254, + 'FR_Wheel_Angle': 20.077051162719727, + 'Location': array([ -0.74801373, -27.01377106, 0.17015204]), + 'Rotation': array([-4.77566794e-02, -6.61537018e+01, 5.32986596e-02]), + 'Velocity': array([ 8.42961311e-01, -1.22902834e+00, 3.41334322e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.25177956, 16.37154961, -0.28162831]), + 'camera_rotation': array([-8.40150833, 1.36431241, 0.13456868]), + 'current_gear_input': False, + 'focus_actor_dist': 808.000732421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -244.98683167, -2323.38793945, 17.03890991]), + 'frame': 21318, + 'frame_number': 21318, + 'framesequence': 81589, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00043946655932813883, + 'throttle_input': 0.0, + 'timestamp': 689.2523491792381, + 'timestamp_carla': 689254, + 'timestamp_device': 3842688, + 'timestamp_stream': 689.2523491792381, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90405261e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([1.90899405e-03, 2.74650869e-03, 8.11484337e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.936185836791992, + 'FR_Wheel_Angle': 20.130422592163086, + 'Location': array([ -0.56629521, -27.28862 , 0.1699169 ]), + 'Rotation': array([-4.84260395e-02, -6.40896149e+01, 5.43473735e-02]), + 'Velocity': array([ 8.07258964e-01, -1.08825886e+00, -6.74667361e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.23778629, 16.39860916, -0.33294591]), + 'camera_rotation': array([-8.3363142 , 1.56292987, -0.16030194]), + 'current_gear_input': False, + 'focus_actor_dist': 799.6105346679688, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -239.96488953, -2314.92919922, 17.03520203]), + 'frame': 21319, + 'frame_number': 21319, + 'framesequence': 81593, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5484694242477417, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.19681263, -2.83524776, -0.04841461]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 689.2861409783363, + 'timestamp_carla': 689288, + 'timestamp_device': 3842721, + 'timestamp_stream': 689.2861409783363, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89710984e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([1.67421519e-03, 2.51233368e-03, 7.83118391e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.964611053466797, + 'FR_Wheel_Angle': 20.15408706665039, + 'Location': array([ -0.39428943, -27.52998734, 0.16977857]), + 'Rotation': array([-4.92251702e-02, -6.22245216e+01, 5.48732318e-02]), + 'Velocity': array([ 0.76582366, -0.96359992, -0.00119414]), + 'brake_input': 0.0, + 'camera_location': array([-5.32238388, 16.41194344, -0.32051259]), + 'camera_rotation': array([-8.31578922, 1.89467812, -0.45079961]), + 'current_gear_input': False, + 'focus_actor_dist': 805.4793701171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -237.23239136, -2320.90454102, 17.03141785]), + 'frame': 21320, + 'frame_number': 21320, + 'framesequence': 81597, + 'gaze_dir': array([0.99279785, 0.03131866, 0.1112442 ]), + 'gaze_origin': array([-4.0849452 , -0.01626282, -0.08524018]), + 'gaze_valid': True, + 'gaze_vergence': 0.3730371594429016, + 'handbrake_input': False, + 'left_eye_openness': 0.2909027934074402, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98930359, 0.03182983, 0.14227295]), + 'left_gaze_origin': array([-3.99229598, 2.79218316, -0.10935059]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5938262939453125, + 'left_pupil_posn': array([ 0.33869612, -0.37039471]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.7893120646476746, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99629211, 0.0308075 , 0.08021545]), + 'right_gaze_origin': array([-4.17759418, -2.8247087 , -0.06112976]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9699859619140625, + 'right_pupil_posn': array([-0.24605089, -0.38857305]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 689.3196732774377, + 'timestamp_carla': 689322, + 'timestamp_device': 3842754, + 'timestamp_stream': 689.3196732774377, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89512635e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-1.26823795e-03, 1.28626423e-02, 6.76085806e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.772029876708984, + 'FR_Wheel_Angle': 19.726831436157227, + 'Location': array([ -0.23114036, -27.74452972, 0.16958094]), + 'Rotation': array([-4.96281534e-02, -6.05360985e+01, 5.52308708e-02]), + 'Velocity': array([ 0.72037405, -0.85686034, -0.00091146]), + 'brake_input': 0.0, + 'camera_location': array([-5.38782883, 16.4846077 , -0.32628036]), + 'camera_rotation': array([-8.17055893, 2.270468 , -0.60164857]), + 'current_gear_input': False, + 'focus_actor_dist': 3532.523681640625, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -125.72143555, -5048.765625 , 16.92476654]), + 'frame': 21321, + 'frame_number': 21321, + 'framesequence': 81601, + 'gaze_dir': array([0.99427795, 0.03109741, 0.10160828]), + 'gaze_origin': array([-4.03880262, -0.01889343, -0.10046463]), + 'gaze_valid': True, + 'gaze_vergence': 212.71524047851562, + 'handbrake_input': False, + 'left_eye_openness': 0.4398343861103058, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99382019, 0.02374268, 0.10835266]), + 'left_gaze_origin': array([-3.81529856, 2.78948665, -0.17023164]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.717864990234375, + 'left_pupil_posn': array([ 0.33940995, -0.36948538]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99473572, 0.03845215, 0.09486389]), + 'right_gaze_origin': array([-4.26230669, -2.82727361, -0.03069763]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.897857666015625, + 'right_pupil_posn': array([-0.2477603 , -0.39796758]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 689.3538776785135, + 'timestamp_carla': 689356, + 'timestamp_device': 3842788, + 'timestamp_stream': 689.3538776785135, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88890838e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.08951636, -0.17350706, -0.00044134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.476165771484375, + 'FR_Wheel_Angle': 17.793590545654297, + 'Location': array([ -0.16884401, -27.82379341, 0.16979329]), + 'Rotation': array([ -0.09146306, -59.91854095, 0.08137181]), + 'Velocity': array([-7.89059850e-05, 9.21173196e-05, 4.65140271e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.45202255, 16.54573059, -0.24269044]), + 'camera_rotation': array([-7.84890461, 2.65217566, -0.82616842]), + 'current_gear_input': False, + 'focus_actor_dist': 2908.22216796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -126.72433472, -4423.71679688, 16.87431335]), + 'frame': 21322, + 'frame_number': 21322, + 'framesequence': 81605, + 'gaze_dir': array([0.99134827, 0.01073456, 0.12979126]), + 'gaze_origin': array([-3.8788662 , -0.01476669, -0.17092821]), + 'gaze_valid': True, + 'gaze_vergence': 135.22003173828125, + 'handbrake_input': False, + 'left_eye_openness': 0.5567710399627686, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99258423, 0.02264404, 0.11940002]), + 'left_gaze_origin': array([-3.73403168, 2.79027581, -0.20967102]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2618255615234375, + 'left_pupil_posn': array([ 0.32215428, -0.36436808]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9901123 , -0.00117493, 0.1401825 ]), + 'right_gaze_origin': array([-4.02370024, -2.8198092 , -0.13218537]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.036407470703125, + 'right_pupil_posn': array([-0.25346678, -0.41569638]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 689.3858847767115, + 'timestamp_carla': 689388, + 'timestamp_device': 3842821, + 'timestamp_stream': 689.3858847767115, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90145865e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.06400333, -0.09029329, -0.00024212]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.075956344604492, + 'FR_Wheel_Angle': 14.4263916015625, + 'Location': array([ -0.16864869, -27.82393265, 0.16958211]), + 'Rotation': array([ -0.06015347, -59.91848755, 0.06589795]), + 'Velocity': array([-4.23565725e-05, 5.78639228e-05, -1.42586388e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.50205612, 16.64731216, -0.14384422]), + 'camera_rotation': array([-7.34729576, 3.02995729, -1.11807942]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.6171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -149.00195312, -5331.48925781, 109.09636688]), + 'frame': 21323, + 'frame_number': 21323, + 'framesequence': 81609, + 'gaze_dir': array([0.99189758, 0.00634003, 0.1260376 ]), + 'gaze_origin': array([-3.87648273, -0.01171799, -0.18193513]), + 'gaze_valid': True, + 'gaze_vergence': 150.92745971679688, + 'handbrake_input': False, + 'left_eye_openness': 0.6467927098274231, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99067688, 0.01663208, 0.13511658]), + 'left_gaze_origin': array([-3.79353642, 2.79445529, -0.19526674]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1089019775390625, + 'left_pupil_posn': array([ 0.31935847, -0.37532604]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99311829, -0.00395203, 0.11695862]), + 'right_gaze_origin': array([-3.95942855, -2.81789088, -0.16860352]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.12506103515625, + 'right_pupil_posn': array([-0.25716901, -0.42262435]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.4200570769608, + 'timestamp_carla': 689422, + 'timestamp_device': 3842854, + 'timestamp_stream': 689.4200570769608, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89287558e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-1.52917802e-02, -2.37375293e-02, -5.45365328e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.935162544250488, + 'FR_Wheel_Angle': 10.301642417907715, + 'Location': array([ -0.16857122, -27.82398796, 0.16950144]), + 'Rotation': array([-4.76610586e-02, -5.99184341e+01, 5.99343516e-02]), + 'Velocity': array([-7.11058237e-06, 1.58247585e-05, -1.58785770e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.53330231, 16.76423454, -0.04199292]), + 'camera_rotation': array([-6.84703207, 3.31102657, -1.22561753]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.728271484375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -142.75762939, -5331.48974609, 127.90081024]), + 'frame': 21324, + 'frame_number': 21324, + 'framesequence': 81612, + 'gaze_dir': array([0.99369812, 0.00405121, 0.11143494]), + 'gaze_origin': array([-3.94549322, -0.00919113, -0.1685936 ]), + 'gaze_valid': True, + 'gaze_vergence': 255.86317443847656, + 'handbrake_input': False, + 'left_eye_openness': 0.7417186498641968, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99334717, 0.01420593, 0.114151 ]), + 'left_gaze_origin': array([-3.78526926, 2.79637766, -0.21271974]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.122039794921875, + 'left_pupil_posn': array([ 0.3172729 , -0.38968205]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99404907, -0.00610352, 0.10871887]), + 'right_gaze_origin': array([-4.10571766, -2.81475997, -0.12446748]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.075653076171875, + 'right_pupil_posn': array([-0.26129586, -0.43118811]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.452443677932, + 'timestamp_carla': 689454, + 'timestamp_device': 3842879, + 'timestamp_stream': 689.452443677932, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90119159e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-3.45760351e-03, -6.25559455e-03, -1.83239226e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.552348613739014, + 'FR_Wheel_Angle': 5.151462554931641, + 'Location': array([ -0.16855021, -27.82400131, 0.16949476]), + 'Rotation': array([-4.45806421e-02, -5.99184456e+01, 5.82741313e-02]), + 'Velocity': array([2.13871704e-06, 4.84392285e-06, 3.16806952e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.58043861, 16.87059593, 0.05920809]), + 'camera_rotation': array([-6.52808952, 3.63136673, -1.10516787]), + 'current_gear_input': False, + 'focus_actor_dist': 3813.185302734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -132.41143799, -5331.48925781, 105.01455688]), + 'frame': 21325, + 'frame_number': 21325, + 'framesequence': 81617, + 'gaze_dir': array([ 0.9944458 , -0.00302887, 0.10452271]), + 'gaze_origin': array([-3.92986751, -0.00804367, -0.17681275]), + 'gaze_valid': True, + 'gaze_vergence': 238.5365753173828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9941864 , 0.00799561, 0.10725403]), + 'left_gaze_origin': array([-3.79804564, 2.79667377, -0.21294405]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2431488037109375, + 'left_pupil_posn': array([ 0.31456232, -0.39582121]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9947052 , -0.01405334, 0.10179138]), + 'right_gaze_origin': array([-4.06168985, -2.81276107, -0.14068146]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1673583984375, + 'right_pupil_posn': array([-0.26517087, -0.43611085]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.4868026785553, + 'timestamp_carla': 689489, + 'timestamp_device': 3842921, + 'timestamp_stream': 689.4868026785553, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89123529e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-7.65814446e-04, -1.63723098e-03, -1.41305545e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.9424014687538147, + 'FR_Wheel_Angle': 0.5063021183013916, + 'Location': array([ -0.16854464, -27.82400513, 0.16948594]), + 'Rotation': array([-4.41298485e-02, -5.99184456e+01, 5.79997674e-02]), + 'Velocity': array([4.23579468e-06, 2.13165231e-06, 1.78964576e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.64960575, 16.98171234, 0.08398648]), + 'camera_rotation': array([-6.4352808 , 3.95000577, -0.86917615]), + 'current_gear_input': False, + 'focus_actor_dist': 3813.155517578125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -136.60678101, -5331.48974609, 99.27864838]), + 'frame': 21326, + 'frame_number': 21326, + 'framesequence': 81620, + 'gaze_dir': array([ 0.99305725, -0.01050568, 0.11673737]), + 'gaze_origin': array([-3.8707819 , -0.00607758, -0.19850694]), + 'gaze_valid': True, + 'gaze_vergence': 306.5451965332031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9932251 , -0.00138855, 0.11608887]), + 'left_gaze_origin': array([-3.72282553, 2.79810643, -0.24324341]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.328155517578125, + 'left_pupil_posn': array([ 0.30979598, -0.39512646]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9928894 , -0.0196228 , 0.11738586]), + 'right_gaze_origin': array([-4.01873827, -2.81026149, -0.15377045]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1279296875, + 'right_pupil_posn': array([-0.27031952, -0.43239582]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.519020177424, + 'timestamp_carla': 689521, + 'timestamp_device': 3842946, + 'timestamp_stream': 689.519020177424, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90145865e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-1.43986719e-04, -4.27604158e-04, -1.44274727e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.36915189027786255, + 'FR_Wheel_Angle': -0.3067130148410797, + 'Location': array([ -0.16854215, -27.82400513, 0.16948545]), + 'Rotation': array([-4.41298485e-02, -5.99184456e+01, 5.79997674e-02]), + 'Velocity': array([4.58211616e-06, 1.42115277e-06, 3.52661336e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.71966934, 17.09765244, 0.08240321]), + 'camera_rotation': array([-6.4800868 , 4.37556601, -0.69525146]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.890380859375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -142.82060242, -5331.48925781, 151.9691925 ]), + 'frame': 21327, + 'frame_number': 21327, + 'framesequence': 81625, + 'gaze_dir': array([ 0.99437714, -0.01633453, 0.10360718]), + 'gaze_origin': array([-3.88919306e+00, -4.28772008e-04, -1.91923529e-01]), + 'gaze_valid': True, + 'gaze_vergence': 158.47174072265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99546814, -0.00593567, 0.09475708]), + 'left_gaze_origin': array([-3.7342515 , 2.80397344, -0.23827364]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3104095458984375, + 'left_pupil_posn': array([ 0.30301428, -0.39578736]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99328613, -0.0267334 , 0.11245728]), + 'right_gaze_origin': array([-4.04413462, -2.80483103, -0.14557344]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09490966796875, + 'right_pupil_posn': array([-0.27650696, -0.44027174]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.5534455776215, + 'timestamp_carla': 689555, + 'timestamp_device': 3842987, + 'timestamp_stream': 689.5534455776215, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89085391e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 3.54703880e-05, -2.17787980e-04, -1.49896568e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.019223080947995186, + 'FR_Wheel_Angle': 0.01922665908932686, + 'Location': array([ -0.16854076, -27.82400513, 0.16947743]), + 'Rotation': array([-4.41298485e-02, -5.99184456e+01, 5.79997674e-02]), + 'Velocity': array([ 4.36236132e-06, 1.25929182e-06, -1.61855496e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.77970982, 17.20969391, 0.08674971]), + 'camera_rotation': array([-6.35652208, 4.76017761, -0.61319315]), + 'current_gear_input': False, + 'focus_actor_dist': 3813.296142578125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -134.73902893, -5331.49023438, 98.54423523]), + 'frame': 21328, + 'frame_number': 21328, + 'framesequence': 81628, + 'gaze_dir': array([ 0.99705505, -0.01914215, 0.07260895]), + 'gaze_origin': array([-3.97302508e+00, 2.44369521e-03, -1.66136175e-01]), + 'gaze_valid': True, + 'gaze_vergence': 115.90341186523438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99810791, -0.00996399, 0.06056213]), + 'left_gaze_origin': array([-3.76133728, 2.80925751, -0.22685243]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.319549560546875, + 'left_pupil_posn': array([ 0.29926264, -0.40407777]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9960022 , -0.02832031, 0.08465576]), + 'right_gaze_origin': array([-4.18471241, -2.80437016, -0.10541993]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1100616455078125, + 'right_pupil_posn': array([-0.27975088, -0.45651186]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.584487978369, + 'timestamp_carla': 689586, + 'timestamp_device': 3843012, + 'timestamp_stream': 689.584487978369, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90870667e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 3.67001740e-05, -8.81505621e-05, -1.46523216e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.019223080947995186, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.1685396 , -27.82400513, 0.16947789]), + 'Rotation': array([-4.41298485e-02, -5.99184456e+01, 5.79997674e-02]), + 'Velocity': array([4.69475981e-06, 1.20083257e-06, 1.07803215e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.81708622, 17.29046059, 0.13030323]), + 'camera_rotation': array([-6.08183908, 5.0470295 , -0.67813528]), + 'current_gear_input': False, + 'focus_actor_dist': 3063.807861328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -140.49630737, -4579.65576172, 16.8875351 ]), + 'frame': 21329, + 'frame_number': 21329, + 'framesequence': 81633, + 'gaze_dir': array([ 0.99659729, -0.02354431, 0.0776825 ]), + 'gaze_origin': array([-3.99806166, 0.00417023, -0.16084825]), + 'gaze_valid': True, + 'gaze_vergence': 150.9137725830078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99757385, -0.01341248, 0.06819153]), + 'left_gaze_origin': array([-3.78705597, 2.81008005, -0.22394256]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.217926025390625, + 'left_pupil_posn': array([ 0.29710543, -0.40663981]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99562073, -0.03367615, 0.08717346]), + 'right_gaze_origin': array([-4.20906687, -2.80173969, -0.09775391]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.174285888671875, + 'right_pupil_posn': array([-0.28320712, -0.45364416]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.6197111792862, + 'timestamp_carla': 689622, + 'timestamp_device': 3843054, + 'timestamp_stream': 689.6197111792862, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88803084e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 1.37424904e-05, -4.23938400e-05, -1.44693495e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.1685387 , -27.82400513, 0.16948274]), + 'Rotation': array([-4.41298485e-02, -5.99184456e+01, 5.79997674e-02]), + 'Velocity': array([4.83719623e-06, 1.22042354e-06, 1.80290692e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.86973 , 17.34202957, 0.17472655]), + 'camera_rotation': array([-5.88263655, 5.19679594, -0.59791911]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.76806640625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ -110.97386169, -5504.71875 , 20.57085419]), + 'frame': 21330, + 'frame_number': 21330, + 'framesequence': 81636, + 'gaze_dir': array([0.99375153, 0.00919342, 0.11032104]), + 'gaze_origin': array([-3.89955759, -0.01823273, -0.19206925]), + 'gaze_valid': True, + 'gaze_vergence': 111.25005340576172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99497986, 0.01622009, 0.09872437]), + 'left_gaze_origin': array([-3.70070386, 2.78355718, -0.25158691]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.36285400390625, + 'left_pupil_posn': array([ 0.32834291, -0.39485347]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99252319, 0.00216675, 0.12191772]), + 'right_gaze_origin': array([-4.09841156, -2.82002282, -0.13255158]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2179107666015625, + 'right_pupil_posn': array([-0.25688303, -0.44211614]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.6527416780591, + 'timestamp_carla': 689655, + 'timestamp_device': 3843079, + 'timestamp_stream': 689.6527416780591, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89382925e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 2.54166230e-06, -9.58509918e-06, -1.44842534e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.16853781, -27.82400513, 0.16948853]), + 'Rotation': array([-4.41298485e-02, -5.99184456e+01, 5.79997674e-02]), + 'Velocity': array([4.74771468e-06, 1.21048561e-06, 1.02489750e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.94426918, 17.36870766, 0.18604416]), + 'camera_rotation': array([-5.89459658, 5.48468924, -0.46666956]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.341552734375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 18.21847534, -5331.48974609, 165.07142639]), + 'frame': 21331, + 'frame_number': 21331, + 'framesequence': 81641, + 'gaze_dir': array([0.99562073, 0.00131226, 0.08861542]), + 'gaze_origin': array([-3.90113401, -0.00950089, -0.19465256]), + 'gaze_valid': True, + 'gaze_vergence': 41.03073501586914, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9980011 , 0.01345825, 0.0617218 ]), + 'left_gaze_origin': array([-3.71582222, 2.79315352, -0.25025484]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.391448974609375, + 'left_pupil_posn': array([ 0.31678712, -0.39968908]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99324036, -0.01083374, 0.11550903]), + 'right_gaze_origin': array([-4.08644581, -2.81215525, -0.1390503 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.147674560546875, + 'right_pupil_posn': array([-0.26429504, -0.45845091]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.6864543780684, + 'timestamp_carla': 689688, + 'timestamp_device': 3843121, + 'timestamp_stream': 689.6864543780684, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89234146e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 1.22638376e-05, -2.74058511e-05, -1.43343905e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0487043671309948, + 'Location': array([ -0.16853675, -27.82400513, 0.16948934]), + 'Rotation': array([-4.41298485e-02, -5.99184456e+01, 5.79997674e-02]), + 'Velocity': array([4.87989746e-06, 1.20566210e-06, 2.12561776e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.98740959, 17.41363525, 0.22855121]), + 'camera_rotation': array([-5.6905241 , 5.80605793, -0.45709455]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.068603515625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 8.85462952, -5331.48974609, 80.74168396]), + 'frame': 21332, + 'frame_number': 21332, + 'framesequence': 81645, + 'gaze_dir': array([ 0.99533844, -0.0030365 , 0.09144592]), + 'gaze_origin': array([-3.88476801, -0.00867081, -0.20493852]), + 'gaze_valid': True, + 'gaze_vergence': 26.384424209594727, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99803162, 0.00456238, 0.06234741]), + 'left_gaze_origin': array([-3.65363479, 2.79401875, -0.27868959]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.363983154296875, + 'left_pupil_posn': array([ 0.31490779, -0.40420842]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99264526, -0.01063538, 0.12054443]), + 'right_gaze_origin': array([-4.11590147, -2.81136036, -0.13118745]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.121734619140625, + 'right_pupil_posn': array([-0.26848084, -0.45914853]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.7194840759039, + 'timestamp_carla': 689721, + 'timestamp_device': 3843154, + 'timestamp_stream': 689.7194840759039, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89665209e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.03176764, 0.01980242, -0.58531731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04867014288902283, + 'FR_Wheel_Angle': 0.048694759607315063, + 'Location': array([ -0.16964628, -27.8218956 , 0.16947828]), + 'Rotation': array([-4.43415865e-02, -5.99244308e+01, 5.79618141e-02]), + 'Velocity': array([-0.01446969, 0.02558385, -0.0001932 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.0072403 , 17.44810867, 0.27723801]), + 'camera_rotation': array([-5.37344599, 5.96042299, -0.61654389]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.13623046875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 13.69610596, -5331.49023438, 105.09539032]), + 'frame': 21333, + 'frame_number': 21333, + 'framesequence': 81649, + 'gaze_dir': array([ 0.99588013, -0.0038681 , 0.08761597]), + 'gaze_origin': array([-3.87537408, -0.00745316, -0.20711517]), + 'gaze_valid': True, + 'gaze_vergence': 44.97739028930664, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99777222, 0.00372314, 0.06640625]), + 'left_gaze_origin': array([-3.67222476, 2.79507923, -0.26992798]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.33612060546875, + 'left_pupil_posn': array([ 0.31424665, -0.40633976]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99398804, -0.01145935, 0.10882568]), + 'right_gaze_origin': array([-4.07852364, -2.80998564, -0.14430238]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.169219970703125, + 'right_pupil_posn': array([-0.26966685, -0.45879698]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.7528688758612, + 'timestamp_carla': 689755, + 'timestamp_device': 3843187, + 'timestamp_stream': 689.7528688758612, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89665209e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.03411822, 0.02113193, -0.56400722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04866870492696762, + 'FR_Wheel_Angle': 0.048698876053094864, + 'Location': array([ -0.17027554, -27.82056999, 0.16948408]), + 'Rotation': array([-4.42186408e-02, -5.99276543e+01, 5.79875708e-02]), + 'Velocity': array([-1.43162888e-02, 2.54628509e-02, 7.15541828e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.01508522, 17.44525146, 0.27650359]), + 'camera_rotation': array([-5.29106045, 6.04257965, -0.60749644]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.513671875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 20.04595947, -5331.48974609, 111.41313934]), + 'frame': 21334, + 'frame_number': 21334, + 'framesequence': 81653, + 'gaze_dir': array([ 0.99668884, -0.00183105, 0.07948303]), + 'gaze_origin': array([-3.88410354, -0.0087326 , -0.19709398]), + 'gaze_valid': True, + 'gaze_vergence': 68.47062683105469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99790955, 0.00436401, 0.0642395 ]), + 'left_gaze_origin': array([-3.66371465, 2.79431772, -0.26324159]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3769989013671875, + 'left_pupil_posn': array([ 0.31592107, -0.40487123]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99546814, -0.00802612, 0.09472656]), + 'right_gaze_origin': array([-4.10449266, -2.81178308, -0.13094635]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1731414794921875, + 'right_pupil_posn': array([-0.26810104, -0.45563936]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.7865381762385, + 'timestamp_carla': 689788, + 'timestamp_device': 3843221, + 'timestamp_stream': 689.7865381762385, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89447769e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.03406365, 0.02059085, -0.52988666]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0486798956990242, + 'FR_Wheel_Angle': 0.048702631145715714, + 'Location': array([ -0.17144519, -27.81829071, 0.16949575]), + 'Rotation': array([-4.45191711e-02, -5.99305611e+01, 5.79945408e-02]), + 'Velocity': array([-0.01853305, 0.03289239, 0.00038264]), + 'brake_input': 0.0, + 'camera_location': array([-6.02462769, 17.4529953 , 0.26299447]), + 'camera_rotation': array([-5.36934137, 6.05732632, -0.54982638]), + 'current_gear_input': False, + 'focus_actor_dist': 3821.69287109375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 33.68702698, -5331.48974609, 85.7411499 ]), + 'frame': 21335, + 'frame_number': 21335, + 'framesequence': 81656, + 'gaze_dir': array([ 0.99549103, -0.00491333, 0.09226227]), + 'gaze_origin': array([-3.84241557, -0.01150971, -0.21564713]), + 'gaze_valid': True, + 'gaze_vergence': 88.11915588378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99703979, 0.00878906, 0.07623291]), + 'left_gaze_origin': array([-3.67986298, 2.78961182, -0.26389009]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3801727294921875, + 'left_pupil_posn': array([ 0.31576467, -0.4040482 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99394226, -0.01861572, 0.10829163]), + 'right_gaze_origin': array([-4.00496817, -2.81263137, -0.16740419]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1277618408203125, + 'right_pupil_posn': array([-0.26521349, -0.45492983]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.8187202773988, + 'timestamp_carla': 689821, + 'timestamp_device': 3843246, + 'timestamp_stream': 689.8187202773988, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90386193e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.03506298, 0.02142609, -0.55110383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.048672161996364594, + 'FR_Wheel_Angle': 0.04868762940168381, + 'Location': array([ -0.17418613, -27.81332016, 0.16949041]), + 'Rotation': array([-4.49836217e-02, -5.99331017e+01, 5.80081940e-02]), + 'Velocity': array([-0.02757913, 0.04834785, 0.00029402]), + 'brake_input': 0.0, + 'camera_location': array([-6.00395584, 17.45944977, 0.255537 ]), + 'camera_rotation': array([-5.45429516, 5.99408722, -0.46430412]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.61181640625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 22.7565918 , -5331.49023438, 129.45591736]), + 'frame': 21336, + 'frame_number': 21336, + 'framesequence': 81660, + 'gaze_dir': array([ 0.99573517, -0.00153351, 0.09069824]), + 'gaze_origin': array([-3.90424728, -0.01132507, -0.18841478]), + 'gaze_valid': True, + 'gaze_vergence': 142.3764190673828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99662781, 0.01133728, 0.08110046]), + 'left_gaze_origin': array([-3.71049047, 2.79114389, -0.24836275]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.332061767578125, + 'left_pupil_posn': array([ 0.31682038, -0.40255451]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99484253, -0.0144043 , 0.10029602]), + 'right_gaze_origin': array([-4.09800434, -2.81379414, -0.1284668 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.131591796875, + 'right_pupil_posn': array([-0.26353353, -0.44544363]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.8526675775647, + 'timestamp_carla': 689855, + 'timestamp_device': 3843279, + 'timestamp_stream': 689.8526675775647, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.89623253e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([ 0.08599389, 0.04930761, -0.09442829]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04845393821597099, + 'FR_Wheel_Angle': 0.048491351306438446, + 'Location': array([ -0.18572579, -27.79315567, 0.16954 ]), + 'Rotation': array([-5.07824533e-02, -5.99464912e+01, 5.80673441e-02]), + 'Velocity': array([-1.19767837e-01, 2.07187891e-01, 9.43088526e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.98137665, 17.44883156, 0.23940833]), + 'camera_rotation': array([-5.53051329, 5.95422029, -0.45614147]), + 'current_gear_input': False, + 'focus_actor_dist': 3821.311279296875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 32.04794312, -5331.48974609, 117.91125488]), + 'frame': 21337, + 'frame_number': 21337, + 'framesequence': 81664, + 'gaze_dir': array([ 0.99576569, -0.00322723, 0.08990479]), + 'gaze_origin': array([-3.8797884, -0.013517 , -0.1972046]), + 'gaze_valid': True, + 'gaze_vergence': 69.52287292480469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99729919, 0.00486755, 0.07325745]), + 'left_gaze_origin': array([-3.68523741, 2.78900623, -0.25782016]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.320465087890625, + 'left_pupil_posn': array([ 0.3189584, -0.4013027]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99423218, -0.01132202, 0.10655212]), + 'right_gaze_origin': array([-4.07433939, -2.81604028, -0.13658907]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.14178466796875, + 'right_pupil_posn': array([-0.26432198, -0.4491266 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.8842691779137, + 'timestamp_carla': 689886, + 'timestamp_device': 3843312, + 'timestamp_stream': 689.8842691779137, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.90840142e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.05079447, -0.03298494, -0.46242231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03807252272963524, + 'FR_Wheel_Angle': 0.0025385464541614056, + 'Location': array([ -0.24092855, -27.69736481, 0.16965975]), + 'Rotation': array([-5.69091327e-02, -5.99635811e+01, 5.62078580e-02]), + 'Velocity': array([-0.26442513, 0.45790389, 0.00059872]), + 'brake_input': 0.0, + 'camera_location': array([-5.95391655, 17.43855286, 0.23998769]), + 'camera_rotation': array([-5.55663872, 5.87274599, -0.44400463]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.693359375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 22.94801331, -5331.49023438, 109.73825836]), + 'frame': 21338, + 'frame_number': 21338, + 'framesequence': 81669, + 'gaze_dir': array([ 0.99486542, -0.00260925, 0.10012054]), + 'gaze_origin': array([-3.85514307, -0.01727219, -0.20612259]), + 'gaze_valid': True, + 'gaze_vergence': 102.58828735351562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99609375, 0.00395203, 0.08810425]), + 'left_gaze_origin': array([-3.65769815, 2.78557444, -0.26890108]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3367156982421875, + 'left_pupil_posn': array([ 0.32169104, -0.40109015]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99363708, -0.00917053, 0.11213684]), + 'right_gaze_origin': array([-4.05258799, -2.8201189 , -0.14334412]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.03277587890625, + 'right_pupil_posn': array([-0.26126587, -0.4429816 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 689.9198952764273, + 'timestamp_carla': 689922, + 'timestamp_device': 3843354, + 'timestamp_stream': 689.9198952764273, + 'transform': [array([4.29734564e+00, 1.31820984e+01, 2.88436888e-03]), + array([ -0.06188834, -11.90938377, 0.01979676])]} +{'AngularVelocity': array([-0.02629643, -0.0130133 , 0.16626827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.4353219270706177, + 'FR_Wheel_Angle': -1.769903540611267, + 'Location': array([ -0.29784146, -27.59820175, 0.16968083]), + 'Rotation': array([-5.07483035e-02, -5.99475899e+01, 5.66471778e-02]), + 'Velocity': array([-2.89896816e-01, 5.13438702e-01, 3.82103899e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.91711998, 17.43380737, 0.21743949]), + 'camera_rotation': array([-5.60522842, 5.83191586, -0.4245936 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.36767578125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 19.67153931, -5331.48974609, 147.19856262]), + 'frame': 21339, + 'frame_number': 21339, + 'framesequence': 81672, + 'gaze_dir': array([ 0.99486542, -0.00324249, 0.10069275]), + 'gaze_origin': array([-3.88200545, -0.01555328, -0.19361192]), + 'gaze_valid': True, + 'gaze_vergence': 229.1426239013672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99551392, 0.00309753, 0.0944519 ]), + 'left_gaze_origin': array([-3.70005965, 2.78704548, -0.24949494]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3188018798828125, + 'left_pupil_posn': array([ 0.32133865, -0.3984834 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99421692, -0.00958252, 0.10693359]), + 'right_gaze_origin': array([-4.06395102, -2.81815195, -0.13772888]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.133758544921875, + 'right_pupil_posn': array([-0.26307344, -0.4392488 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.03967345505952835, + 'timestamp': 689.9516300782561, + 'timestamp_carla': 689954, + 'timestamp_device': 3843379, + 'timestamp_stream': 689.9516300782561, + 'transform': [array([4.29732275e+00, 1.31821156e+01, 2.83002853e-03]), + array([ -0.06184053, -11.90932083, 0.01993471])]} +{'AngularVelocity': array([-0.01828643, -0.00131769, 0.66141838]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6685523986816406, + 'FR_Wheel_Angle': -3.7097930908203125, + 'Location': array([ -0.36990097, -27.46805763, 0.1697336 ]), + 'Rotation': array([-4.86787558e-02, -5.98294907e+01, 5.59520759e-02]), + 'Velocity': array([-3.10663790e-01, 5.78267276e-01, 5.21364214e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.88645554, 17.43404388, 0.18714006]), + 'camera_rotation': array([-5.70911598, 5.85609007, -0.5057326 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.025146484375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 14.62857056, -5331.48974609, 146.11842346]), + 'frame': 21340, + 'frame_number': 21340, + 'framesequence': 81677, + 'gaze_dir': array([ 0.99486542, -0.00458527, 0.1006012 ]), + 'gaze_origin': array([-3.89348078, -0.01560211, -0.18854904]), + 'gaze_valid': True, + 'gaze_vergence': 279.6813659667969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99533081, 0.00328064, 0.09637451]), + 'left_gaze_origin': array([-3.71360326, 2.78660893, -0.24365541]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2976531982421875, + 'left_pupil_posn': array([ 0.32085764, -0.39803803]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99440002, -0.01245117, 0.10482788]), + 'right_gaze_origin': array([-4.07335854, -2.8178134 , -0.1334427 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1184234619140625, + 'right_pupil_posn': array([-0.26324099, -0.43741322]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.07142747938632965, + 'timestamp': 689.9861944764853, + 'timestamp_carla': 689988, + 'timestamp_device': 3843421, + 'timestamp_stream': 689.9861944764853, + 'transform': [array([4.29733276e+00, 1.31822176e+01, 2.81858444e-03]), + array([ -0.06184053, -11.90932083, 0.01993471])]} +{'AngularVelocity': array([-0.01275541, 0.01180384, 0.77779585]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.349093914031982, + 'FR_Wheel_Angle': -4.173986911773682, + 'Location': array([ -0.44254839, -27.33338165, 0.16978635]), + 'Rotation': array([-4.56529818e-02, -5.96261826e+01, 5.67990765e-02]), + 'Velocity': array([-3.04195613e-01, 5.74180067e-01, 3.27568036e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.85834026, 17.42955017, 0.17164296]), + 'camera_rotation': array([-5.78896761, 5.86999655, -0.52914393]), + 'current_gear_input': False, + 'focus_actor_dist': 3819.7314453125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 10.55278015, -5331.49023438, 138.77549744]), + 'frame': 21341, + 'frame_number': 21341, + 'framesequence': 81681, + 'gaze_dir': array([ 0.9947052 , -0.0019455 , 0.10224915]), + 'gaze_origin': array([-3.87512994, -0.01578751, -0.19488527]), + 'gaze_valid': True, + 'gaze_vergence': 264.8404541015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99519348, 0.00608826, 0.09759521]), + 'left_gaze_origin': array([-3.67766738, 2.7862916 , -0.25593719]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3097076416015625, + 'left_pupil_posn': array([ 0.3212235 , -0.39803803]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99421692, -0.00997925, 0.10690308]), + 'right_gaze_origin': array([-4.07259226, -2.81786656, -0.13383332]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1194915771484375, + 'right_pupil_posn': array([-0.26210767, -0.43705928]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.1111009418964386, + 'timestamp': 690.0191475786269, + 'timestamp_carla': 690021, + 'timestamp_device': 3843454, + 'timestamp_stream': 690.0191475786269, + 'transform': [array([4.29734135e+00, 1.31822691e+01, 2.82445899e-03]), + array([ -0.06184053, -11.90932083, 0.01993471])]} +{'AngularVelocity': array([-0.00844571, 0.01251407, 0.62767595]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.711778163909912, + 'FR_Wheel_Angle': -3.3286588191986084, + 'Location': array([ -0.51375568, -27.20179939, 0.16984285]), + 'Rotation': array([-4.40069064e-02, -5.94153938e+01, 5.82046807e-02]), + 'Velocity': array([-2.92274326e-01, 5.42354763e-01, 3.62300867e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.82770538, 17.43389511, 0.17538148]), + 'camera_rotation': array([-5.74656582, 5.88793707, -0.5997287 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.397705078125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 21.36636353, -5331.49023438, 139.8291626 ]), + 'frame': 21342, + 'frame_number': 21342, + 'framesequence': 81684, + 'gaze_dir': array([ 0.99458313, -0.00382233, 0.103508 ]), + 'gaze_origin': array([-3.87262583, -0.01710892, -0.19582215]), + 'gaze_valid': True, + 'gaze_vergence': 302.80828857421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9949646 , 0.0040741 , 0.10012817]), + 'left_gaze_origin': array([-3.69810343, 2.7862916 , -0.24894106]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30462646484375, + 'left_pupil_posn': array([ 0.3210156 , -0.39760602]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99420166, -0.01171875, 0.10688782]), + 'right_gaze_origin': array([-4.04714823, -2.82050943, -0.14270325]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0707244873046875, + 'right_pupil_posn': array([-0.26073867, -0.43666339]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.1587243527173996, + 'timestamp': 690.0525088757277, + 'timestamp_carla': 690054, + 'timestamp_device': 3843479, + 'timestamp_stream': 690.0525088757277, + 'transform': [array([4.29734993e+00, 1.31823187e+01, 2.82480242e-03]), + array([ -0.06184053, -11.90932083, 0.01993471])]} +{'AngularVelocity': array([-4.26149089e-03, 2.53088831e-04, 9.01197493e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.1506590843200684, + 'FR_Wheel_Angle': -3.291166067123413, + 'Location': array([ -0.58098745, -27.08081436, 0.16990709]), + 'Rotation': array([-4.32419255e-02, -5.92668648e+01, 5.88188395e-02]), + 'Velocity': array([-2.75957793e-01, 4.98401135e-01, -1.13782880e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.78425026, 17.43462753, 0.15888081]), + 'camera_rotation': array([-5.81268883, 5.85098314, -0.54470211]), + 'current_gear_input': False, + 'focus_actor_dist': 3819.96240234375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 14.8560791 , -5331.49023438, 147.40713501]), + 'frame': 21343, + 'frame_number': 21343, + 'framesequence': 81688, + 'gaze_dir': array([9.94216919e-01, 1.60217285e-04, 1.06620789e-01]), + 'gaze_origin': array([-3.86952305, -0.01792297, -0.19743654]), + 'gaze_valid': True, + 'gaze_vergence': 232.27963256835938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99447632, 0.01177979, 0.10418701]), + 'left_gaze_origin': array([-3.690732 , 2.78582931, -0.25232697]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30657958984375, + 'left_pupil_posn': array([ 0.32128537, -0.39758396]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99395752, -0.01145935, 0.10905457]), + 'right_gaze_origin': array([-4.04831409, -2.8216753 , -0.14254609]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.125701904296875, + 'right_pupil_posn': array([-0.25690192, -0.43546569]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.1904631108045578, + 'timestamp': 690.0859016776085, + 'timestamp_carla': 690088, + 'timestamp_device': 3843512, + 'timestamp_stream': 690.0859016776085, + 'transform': [array([4.29735756e+00, 1.31823387e+01, 2.82464968e-03]), + array([ -0.06184053, -11.90932083, 0.01993471])]} +{'AngularVelocity': array([0.00851771, 0.00827135, 1.24617708]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.148166179656982, + 'FR_Wheel_Angle': -6.219901084899902, + 'Location': array([ -0.6375491 , -26.97817802, 0.1699619 ]), + 'Rotation': array([-4.05918136e-02, -5.91086235e+01, 5.70382141e-02]), + 'Velocity': array([-2.14307785e-01, 4.06372964e-01, 1.33810041e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.74671078, 17.4222908 , 0.14718814]), + 'camera_rotation': array([-5.92609024, 5.66556025, -0.42577446]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.8193359375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 27.91020203, -5331.49023438, 155.1078949 ]), + 'frame': 21344, + 'frame_number': 21344, + 'framesequence': 81693, + 'gaze_dir': array([ 9.94171143e-01, -7.93457031e-04, 1.07368469e-01]), + 'gaze_origin': array([-3.85823321, -0.01932831, -0.20149767]), + 'gaze_valid': True, + 'gaze_vergence': 306.6159973144531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99407959, 0.00823975, 0.10826111]), + 'left_gaze_origin': array([-3.68075109, 2.78410649, -0.25466004]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.300384521484375, + 'left_pupil_posn': array([ 0.32295406, -0.39795613]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9942627 , -0.00982666, 0.10647583]), + 'right_gaze_origin': array([-4.0357151 , -2.8227632 , -0.14833528]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0317840576171875, + 'right_pupil_posn': array([-0.25733024, -0.43499792]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.21824978291988373, + 'timestamp': 690.1193096786737, + 'timestamp_carla': 690121, + 'timestamp_device': 3843554, + 'timestamp_stream': 690.1193096786737, + 'transform': [array([4.29736328e+00, 1.31823034e+01, 2.82415375e-03]), + array([ -0.06184053, -11.90932083, 0.01993471])]} +{'AngularVelocity': array([0.00967543, 0.01334102, 0.00583213]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.760032653808594, + 'FR_Wheel_Angle': -8.3400239944458, + 'Location': array([ -0.68033111, -26.89605904, 0.17001256]), + 'Rotation': array([-4.01000381e-02, -5.89051743e+01, 5.66221774e-02]), + 'Velocity': array([-1.55042738e-01, 3.16911131e-01, 1.77183145e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.71526527, 17.41320992, 0.12542927]), + 'camera_rotation': array([-6.03566027, 5.48351812, -0.47787026]), + 'current_gear_input': False, + 'focus_actor_dist': 3819.747314453125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 12.68487549, -5331.48974609, 150.38739014]), + 'frame': 21345, + 'frame_number': 21345, + 'framesequence': 81697, + 'gaze_dir': array([0.99414062, 0.00405884, 0.10746765]), + 'gaze_origin': array([-3.87040567, -0.02067566, -0.1985756 ]), + 'gaze_valid': True, + 'gaze_vergence': 276.14154052734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99412537, 0.01420593, 0.10719299]), + 'left_gaze_origin': array([-3.6792345 , 2.78224826, -0.25571138]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.299713134765625, + 'left_pupil_posn': array([ 0.32569838, -0.39794612]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99415588, -0.00608826, 0.10774231]), + 'right_gaze_origin': array([-4.06157732, -2.82359934, -0.14143983]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9328765869140625, + 'right_pupil_posn': array([-0.25449693, -0.4359448 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.24205386638641357, + 'timestamp': 690.1531449779868, + 'timestamp_carla': 690155, + 'timestamp_device': 3843587, + 'timestamp_stream': 690.1531449779868, + 'transform': [array([4.29739380e+00, 1.31821852e+01, 2.76151649e-03]), + array([ -0.0618337 , -11.90938377, 0.02005082])]} +{'AngularVelocity': array([0.08903749, 0.02119366, 0.01548788]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.956668853759766, + 'FR_Wheel_Angle': -10.180702209472656, + 'Location': array([ -0.71109539, -26.83502579, 0.17005159]), + 'Rotation': array([-4.25725654e-02, -5.86923714e+01, 5.72610013e-02]), + 'Velocity': array([-1.40844956e-01, 2.90921569e-01, 1.03340150e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.67570496, 17.40200806, 0.10816742]), + 'camera_rotation': array([-6.0992837 , 5.35689497, -0.50098902]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.093017578125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 18.71150208, -5331.49023438, 143.60218811]), + 'frame': 21346, + 'frame_number': 21346, + 'framesequence': 81700, + 'gaze_dir': array([0.99343109, 0.09304047, 0.06246948]), + 'gaze_origin': array([-3.82906055, -0.09016419, -0.24879305]), + 'gaze_valid': True, + 'gaze_vergence': 71.94413757324219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99339294, 0.10592651, 0.04380798]), + 'left_gaze_origin': array([-3.66391921, 2.70304275, -0.3036209 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3639373779296875, + 'left_pupil_posn': array([ 0.41901386, -0.44266546]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99346924, 0.08015442, 0.08113098]), + 'right_gaze_origin': array([-3.9942019 , -2.88337111, -0.19396515]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0100555419921875, + 'right_pupil_posn': array([-0.17588335, -0.48568785]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.24998855590820312, + 'timestamp': 690.1861047782004, + 'timestamp_carla': 690188, + 'timestamp_device': 3843612, + 'timestamp_stream': 690.1861047782004, + 'transform': [array([4.29740572e+00, 1.31819019e+01, 2.66607269e-03]), + array([ -0.06180638, -11.90941334, 0.02024656])]} +{'AngularVelocity': array([-0.0073256 , -0.01893939, 0.05359276]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.713887214660645, + 'FR_Wheel_Angle': -11.510750770568848, + 'Location': array([ -0.74046582, -26.77679443, 0.17009069]), + 'Rotation': array([-4.32760753e-02, -5.84236183e+01, 5.70681617e-02]), + 'Velocity': array([-9.73669216e-02, 2.15948269e-01, 4.00924691e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.60832787, 17.38469505, 0.10640317]), + 'camera_rotation': array([-6.02387142, 5.12244034, -0.56115925]), + 'current_gear_input': False, + 'focus_actor_dist': 2756.488037109375, + 'focus_actor_name': 'Plane19', + 'focus_actor_pt': array([ 187.74633789, -4241.56542969, 16.62149811]), + 'frame': 21347, + 'frame_number': 21347, + 'framesequence': 81704, + 'gaze_dir': array([0.98799133, 0.15156555, 0.01277924]), + 'gaze_origin': array([-3.8457737 , -0.13838425, -0.27433777]), + 'gaze_valid': True, + 'gaze_vergence': 43.74892044067383, + 'handbrake_input': False, + 'left_eye_openness': 0.7264230251312256, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98664856, 0.16239929, -0.01165771]), + 'left_gaze_origin': array([-3.6756382 , 2.64201379, -0.33405304]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.36810302734375, + 'left_pupil_posn': array([ 0.49303615, -0.4891808 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98933411, 0.14073181, 0.03721619]), + 'right_gaze_origin': array([-4.01590919, -2.91878223, -0.21462251]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0873260498046875, + 'right_pupil_posn': array([-0.12886274, -0.53007388]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.24998855590820312, + 'timestamp': 690.2120807766914, + 'timestamp_carla': 690214, + 'timestamp_device': 3843646, + 'timestamp_stream': 690.2120807766914, + 'transform': [array([4.29742527e+00, 1.31819048e+01, 2.86407466e-03]), + array([ -0.06187468, -11.90944386, 0.01984359])]} +{'AngularVelocity': array([4.57030945e-02, 3.30935640e-04, 1.24940062e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.174501419067383, + 'FR_Wheel_Angle': -12.519753456115723, + 'Location': array([ -0.77456462, -26.70633888, 0.17018205]), + 'Rotation': array([-5.10010198e-02, -5.80773697e+01, 5.38893119e-02]), + 'Velocity': array([-0.1567592 , 0.35286269, 0.00051648]), + 'brake_input': 0.0, + 'camera_location': array([-5.60832787, 17.38469505, 0.10640317]), + 'camera_rotation': array([-6.02387142, 5.12244034, -0.56115925]), + 'current_gear_input': False, + 'focus_actor_dist': 1311.4962158203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 38.96351624, -2797.65820312, 16.71389008]), + 'frame': 21348, + 'frame_number': 21348, + 'framesequence': 81708, + 'gaze_dir': array([0.98606873, 0.1635437 , 0.01792908]), + 'gaze_origin': array([-3.84245777, -0.14202042, -0.26996234]), + 'gaze_valid': True, + 'gaze_vergence': 10.58992862701416, + 'handbrake_input': False, + 'left_eye_openness': 0.7082554697990417, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98696899, 0.16073608, -0.00604248]), + 'left_gaze_origin': array([-3.67156672, 2.64221215, -0.33182985]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5050811767578125, + 'left_pupil_posn': array([ 0.50315571, -0.48590779]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98516846, 0.16635132, 0.04190063]), + 'right_gaze_origin': array([-4.01334858, -2.92625308, -0.20809479]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1590576171875, + 'right_pupil_posn': array([-0.12376577, -0.52221799]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.24998855590820312, + 'timestamp': 690.2465498782694, + 'timestamp_carla': 690248, + 'timestamp_device': 3843679, + 'timestamp_stream': 690.2465498782694, + 'transform': [array([4.29741907e+00, 1.31805468e+01, 2.31954572e-03]), + array([ -0.06168343, -11.90950203, 0.02089951])]} +{'AngularVelocity': array([0.01366324, 0.00673679, 2.38880134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.163091659545898, + 'FR_Wheel_Angle': -12.490044593811035, + 'Location': array([ -0.82079375, -26.61149788, 0.17024469]), + 'Rotation': array([-5.49010560e-02, -5.75826797e+01, 5.31178750e-02]), + 'Velocity': array([-2.26864815e-01, 4.93159562e-01, 1.85632700e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.5785284 , 17.35824585, 0.09297577]), + 'camera_rotation': array([-6.12853718, 4.95152044, -0.46064422]), + 'current_gear_input': False, + 'focus_actor_dist': 1396.4686279296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 73.00888062, -2877.53222656, 16.67839813]), + 'frame': 21349, + 'frame_number': 21349, + 'framesequence': 81712, + 'gaze_dir': array([0.98619843, 0.16273499, 0.02471924]), + 'gaze_origin': array([-3.84118152, -0.14508057, -0.26905367]), + 'gaze_valid': True, + 'gaze_vergence': 4.498884677886963, + 'handbrake_input': False, + 'left_eye_openness': 0.7157749533653259, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98678589, 0.16181946, 0.0072937 ]), + 'left_gaze_origin': array([-3.67068648, 2.64145684, -0.33098453]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.462982177734375, + 'left_pupil_posn': array([ 0.50250304, -0.48474729]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98561096, 0.16365051, 0.04214478]), + 'right_gaze_origin': array([-4.01167631, -2.93161798, -0.20712282]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.129150390625, + 'right_pupil_posn': array([-0.11919594, -0.51581478]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.24998855590820312, + 'timestamp': 690.2775061763823, + 'timestamp_carla': 690279, + 'timestamp_device': 3843712, + 'timestamp_stream': 690.2775061763823, + 'transform': [array([4.29799747e+00, 1.31773996e+01, 1.09048840e-03]), + array([ -0.06125996, -11.91084671, 0.02334785])]} +{'AngularVelocity': array([-0.03234898, -0.0038887 , 1.88045168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.23952579498291, + 'FR_Wheel_Angle': -12.55563735961914, + 'Location': array([ -0.87255538, -26.50678635, 0.17026284]), + 'Rotation': array([-4.74493206e-02, -5.70583916e+01, 5.62717989e-02]), + 'Velocity': array([-1.94836497e-01, 4.18191403e-01, 1.67875289e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.54321861, 17.34564972, 0.08613111]), + 'camera_rotation': array([-6.14032602, 4.83845234, -0.36841083]), + 'current_gear_input': False, + 'focus_actor_dist': 1478.8297119140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 85.45127869, -2959.57910156, 16.66507721]), + 'frame': 21350, + 'frame_number': 21350, + 'framesequence': 81715, + 'gaze_dir': array([0.98529053, 0.16882324, 0.01970673]), + 'gaze_origin': array([-3.84706068, -0.15019761, -0.27169725]), + 'gaze_valid': True, + 'gaze_vergence': 2.773467540740967, + 'handbrake_input': False, + 'left_eye_openness': 0.7314097285270691, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98565674, 0.16871643, 0.00257874]), + 'left_gaze_origin': array([-3.66857958, 2.63846445, -0.33300325]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.426666259765625, + 'left_pupil_posn': array([ 0.50713193, -0.48811519]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98492432, 0.16893005, 0.03683472]), + 'right_gaze_origin': array([-4.02554178, -2.9388597 , -0.21039124]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1178436279296875, + 'right_pupil_posn': array([-0.11123353, -0.52397466]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.21824978291988373, + 'timestamp': 690.3081975765526, + 'timestamp_carla': 690310, + 'timestamp_device': 3843737, + 'timestamp_stream': 690.3081975765526, + 'transform': [array([4.29524565e+00, 1.31742506e+01, 3.44619737e-04]), + array([ -0.06100725, -11.9056015 , 0.02483661])]} +{'AngularVelocity': array([ 0.0591883 , -0.0293987 , 2.11003661]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.627365112304688, + 'FR_Wheel_Angle': -12.87578010559082, + 'Location': array([ -0.91710836, -26.41828346, 0.17029832]), + 'Rotation': array([-4.61993963e-02, -5.66065750e+01, 5.64509518e-02]), + 'Velocity': array([-1.81739479e-01, 3.91678452e-01, 3.29942704e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.52807045, 17.35361099, 0.10526825]), + 'camera_rotation': array([-6.0547576 , 4.81586456, -0.35455188]), + 'current_gear_input': False, + 'focus_actor_dist': 1386.6131591796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 71.38061523, -2868.23681641, 16.68011475]), + 'frame': 21351, + 'frame_number': 21351, + 'framesequence': 81719, + 'gaze_dir': array([0.98606873, 0.16403198, 0.02136993]), + 'gaze_origin': array([-3.85097313, -0.16123506, -0.28120348]), + 'gaze_valid': True, + 'gaze_vergence': 22.212352752685547, + 'handbrake_input': False, + 'left_eye_openness': 0.7455432415008545, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9868927 , 0.1612854 , 0.00447083]), + 'left_gaze_origin': array([-3.67538786, 2.62724161, -0.33961794]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.43280029296875, + 'left_pupil_posn': array([ 0.51595616, -0.49475336]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98524475, 0.16677856, 0.03826904]), + 'right_gaze_origin': array([-4.0265584, -2.9497118, -0.222789 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.190643310546875, + 'right_pupil_posn': array([-0.10606873, -0.53296542]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2063324898481369, + 'timestamp': 690.3432167768478, + 'timestamp_carla': 690345, + 'timestamp_device': 3843771, + 'timestamp_stream': 690.3432167768478, + 'transform': [array([ 4.29702997e+00, 1.31678581e+01, -6.74514740e-04]), + array([ -0.06059061, -11.9095335 , 0.02678763])]} +{'AngularVelocity': array([ 0.00294274, -0.04342595, 2.17958832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.703377723693848, + 'FR_Wheel_Angle': -12.918542861938477, + 'Location': array([ -0.95942485, -26.33528519, 0.1703539 ]), + 'Rotation': array([-4.86172847e-02, -5.61623611e+01, 5.52356392e-02]), + 'Velocity': array([-1.87537000e-01, 4.04500633e-01, -6.27708432e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.49675179, 17.37846565, 0.11989187]), + 'camera_rotation': array([-5.96859455, 4.88293123, -0.3889046 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1437.5880126953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 75.27545166, -2920.14819336, 16.67579651]), + 'frame': 21352, + 'frame_number': 21352, + 'framesequence': 81723, + 'gaze_dir': array([0.98731232, 0.15738678, 0.01498413]), + 'gaze_origin': array([-3.85252523, -0.16224442, -0.27950519]), + 'gaze_valid': True, + 'gaze_vergence': 5.8170857429504395, + 'handbrake_input': False, + 'left_eye_openness': 0.7040615081787109, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([9.87503052e-01, 1.57516479e-01, 7.62939453e-04]), + 'left_gaze_origin': array([-3.68416166, 2.62702799, -0.33438417]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.43975830078125, + 'left_pupil_posn': array([ 0.51266754, -0.49626338]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98712158, 0.15725708, 0.02920532]), + 'right_gaze_origin': array([-4.02088928, -2.95151687, -0.22462618]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1277008056640625, + 'right_pupil_posn': array([-0.10614347, -0.53411317]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1904631108045578, + 'timestamp': 690.3753064759076, + 'timestamp_carla': 690377, + 'timestamp_device': 3843804, + 'timestamp_stream': 690.3753064759076, + 'transform': [array([ 4.29893875e+00, 1.31609507e+01, -1.30329130e-03]), + array([ -0.06039936, -11.91378403, 0.02803782])]} +{'AngularVelocity': array([0.0289423 , 0.00611232, 2.85063839]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.06259822845459, + 'FR_Wheel_Angle': -13.198663711547852, + 'Location': array([ -1.02093041, -26.2174778 , 0.17045651]), + 'Rotation': array([-5.39243408e-02, -5.55464325e+01, 5.26895262e-02]), + 'Velocity': array([-2.65761733e-01, 5.39660275e-01, 4.51860426e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.50197983, 17.4192276 , 0.11750712]), + 'camera_rotation': array([-6.01323652, 5.09126902, -0.34080827]), + 'current_gear_input': False, + 'focus_actor_dist': 1356.0347900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 50.38757324, -2842.41870117, 16.70185852]), + 'frame': 21353, + 'frame_number': 21353, + 'framesequence': 81727, + 'gaze_dir': array([0.98727417, 0.15742493, 0.01351929]), + 'gaze_origin': array([-3.84278035, -0.1612854 , -0.28428346]), + 'gaze_valid': True, + 'gaze_vergence': 9.14273452758789, + 'handbrake_input': False, + 'left_eye_openness': 0.736906886100769, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9874115 , 0.15808105, -0.00402832]), + 'left_gaze_origin': array([-3.67619944, 2.62845469, -0.33941194]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4538421630859375, + 'left_pupil_posn': array([ 0.51104701, -0.49730027]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98713684, 0.1567688 , 0.03106689]), + 'right_gaze_origin': array([-4.00936174, -2.95102549, -0.22915497]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.144683837890625, + 'right_pupil_posn': array([-0.10641706, -0.53655207]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 690.408663276583, + 'timestamp_carla': 690411, + 'timestamp_device': 3843837, + 'timestamp_stream': 690.408663276583, + 'transform': [array([ 4.29961586e+00, 1.31531954e+01, -1.55858987e-03]), + array([ -0.06034472, -11.91564274, 0.02853369])]} +{'AngularVelocity': array([-0.03495884, -0.0059529 , 2.38342428]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.091727256774902, + 'FR_Wheel_Angle': -13.249035835266113, + 'Location': array([ -1.09663224, -26.07584572, 0.17054933]), + 'Rotation': array([-5.52630574e-02, -5.47908783e+01, 5.25380708e-02]), + 'Velocity': array([-3.21508169e-01, 6.34419918e-01, 4.96110879e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.50001526, 17.46022797, 0.10997952]), + 'camera_rotation': array([-6.08905888, 5.33787346, -0.32659274]), + 'current_gear_input': False, + 'focus_actor_dist': 1320.3404541015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 47.62164307, -2807.00732422, 16.70491028]), + 'frame': 21354, + 'frame_number': 21354, + 'framesequence': 81731, + 'gaze_dir': array([0.98738098, 0.15647888, 0.02148438]), + 'gaze_origin': array([-3.86661839, -0.16409989, -0.2859543 ]), + 'gaze_valid': True, + 'gaze_vergence': 126.2419204711914, + 'handbrake_input': False, + 'left_eye_openness': 0.7142248749732971, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98838806, 0.15138245, 0.01246643]), + 'left_gaze_origin': array([-3.71722579, 2.62756515, -0.33117831]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5632171630859375, + 'left_pupil_posn': array([ 0.51601267, -0.5023433 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9863739 , 0.16157532, 0.03050232]), + 'right_gaze_origin': array([-4.01601124, -2.95576501, -0.24073032]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.010955810546875, + 'right_pupil_posn': array([-0.10531962, -0.54033208]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.13888761401176453, + 'timestamp': 690.4420228786767, + 'timestamp_carla': 690444, + 'timestamp_device': 3843871, + 'timestamp_stream': 690.4420228786767, + 'transform': [array([ 4.30015326e+00, 1.31441851e+01, -1.94509502e-03]), + array([ -0.06018762, -11.91732216, 0.0292909 ])]} +{'AngularVelocity': array([-0.03277547, -0.01069832, 2.1264987 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.509632110595703, + 'FR_Wheel_Angle': -14.425954818725586, + 'Location': array([ -1.16259325, -25.95495224, 0.17057858]), + 'Rotation': array([-4.96281534e-02, -5.41138535e+01, 5.43142706e-02]), + 'Velocity': array([-2.92401463e-01, 5.74046910e-01, 5.47542586e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.49248409, 17.49377251, 0.13388757]), + 'camera_rotation': array([-5.99612045, 5.52880192, -0.38063717]), + 'current_gear_input': False, + 'focus_actor_dist': 1425.9564208984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 74.53045654, -2910.36401367, 16.67662811]), + 'frame': 21355, + 'frame_number': 21355, + 'framesequence': 81736, + 'gaze_dir': array([0.98911285, 0.14524841, 0.02292633]), + 'gaze_origin': array([-3.88257766, -0.16371919, -0.2816368 ]), + 'gaze_valid': True, + 'gaze_vergence': 426.69537353515625, + 'handbrake_input': False, + 'left_eye_openness': 0.7221620082855225, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98869324, 0.14860535, 0.01965332]), + 'left_gaze_origin': array([-3.76060987, 2.62943578, -0.3151108 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4799652099609375, + 'left_pupil_posn': array([ 0.50793219, -0.50149572]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98953247, 0.14189148, 0.02619934]), + 'right_gaze_origin': array([-4.00454569, -2.95687437, -0.24816285]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.98760986328125, + 'right_pupil_posn': array([-0.1056093 , -0.54024839]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1269855797290802, + 'timestamp': 690.477177478373, + 'timestamp_carla': 690479, + 'timestamp_device': 3843912, + 'timestamp_stream': 690.477177478373, + 'transform': [array([ 4.30198479e+00, 1.31332874e+01, -2.23165518e-03]), + array([ -0.060092 , -11.92168617, 0.02982786])]} +{'AngularVelocity': array([-5.05217677e-03, -1.61747576e-03, 1.66164851e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.128143310546875, + 'FR_Wheel_Angle': -14.771668434143066, + 'Location': array([ -1.23539078, -25.82220078, 0.1706291 ]), + 'Rotation': array([-4.53729443e-02, -5.33233414e+01, 5.60910851e-02]), + 'Velocity': array([-2.30069607e-01, 4.46011275e-01, -8.99887091e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.49481201, 17.53388786, 0.13319029]), + 'camera_rotation': array([-5.9704318 , 5.74479389, -0.35462019]), + 'current_gear_input': False, + 'focus_actor_dist': 1479.1175537109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 74.24371338, -2965.8659668 , 16.67655945]), + 'frame': 21356, + 'frame_number': 21356, + 'framesequence': 81739, + 'gaze_dir': array([0.98926544, 0.14361572, 0.02478027]), + 'gaze_origin': array([-3.85805511, -0.16250612, -0.29013443]), + 'gaze_valid': True, + 'gaze_vergence': 154.46829223632812, + 'handbrake_input': False, + 'left_eye_openness': 0.7093057036399841, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98867798, 0.14910889, 0.01635742]), + 'left_gaze_origin': array([-3.69423079, 2.6301806 , -0.34122774]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4151611328125, + 'left_pupil_posn': array([ 0.50299907, -0.50166082]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98985291, 0.13812256, 0.03320312]), + 'right_gaze_origin': array([-4.02187967, -2.9551928 , -0.23904115]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0330657958984375, + 'right_pupil_posn': array([-0.10653442, -0.53889883]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.12300297617912292, + 'timestamp': 690.5075503773987, + 'timestamp_carla': 690510, + 'timestamp_device': 3843937, + 'timestamp_stream': 690.5075503773987, + 'transform': [array([ 4.30247927e+00, 1.31232977e+01, -2.25816714e-03]), + array([ -0.05996223, -11.9233036 , 0.02993667])]} +{'AngularVelocity': array([ 0.00457459, -0.00253076, 1.22075772]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.07755470275879, + 'FR_Wheel_Angle': -15.650310516357422, + 'Location': array([ -1.28737581, -25.72903824, 0.17070439]), + 'Rotation': array([-4.64179628e-02, -5.27462845e+01, 5.51472083e-02]), + 'Velocity': array([-0.19368747, 0.37463054, 0.00046036]), + 'brake_input': 0.0, + 'camera_location': array([-5.51219177, 17.58543587, 0.12535931]), + 'camera_rotation': array([-6.01983452, 6.0444808 , -0.39090154]), + 'current_gear_input': False, + 'focus_actor_dist': 1521.1373291015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 85.98208618, -3007.52197266, 16.66426849]), + 'frame': 21357, + 'frame_number': 21357, + 'framesequence': 81743, + 'gaze_dir': array([0.99126434, 0.11494446, 0.05596161]), + 'gaze_origin': array([-3.61919665, -0.13107148, -0.3753731 ]), + 'gaze_valid': True, + 'gaze_vergence': 13.34366226196289, + 'handbrake_input': False, + 'left_eye_openness': 0.7241266965866089, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99267578, 0.11824036, 0.02416992]), + 'left_gaze_origin': array([-3.24233723, 2.66088724, -0.4990128 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5182342529296875, + 'left_pupil_posn': array([ 0.4514755 , -0.48655152]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98985291, 0.11164856, 0.0877533 ]), + 'right_gaze_origin': array([-3.99605584, -2.92303014, -0.25173342]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.04388427734375, + 'right_pupil_posn': array([-0.14269942, -0.53868771]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1111009418964386, + 'timestamp': 690.540801178664, + 'timestamp_carla': 690543, + 'timestamp_device': 3843971, + 'timestamp_stream': 690.540801178664, + 'transform': [array([ 4.30347395e+00, 1.31118746e+01, -2.02960963e-03]), + array([ -0.06001687, -11.92601204, 0.02948926])]} +{'AngularVelocity': array([ 0.07184623, -0.00373322, 2.40990782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.009063720703125, + 'FR_Wheel_Angle': -17.029512405395508, + 'Location': array([ -1.32923889, -25.65407181, 0.17078626]), + 'Rotation': array([-5.24353608e-02, -5.22359428e+01, 5.08482456e-02]), + 'Velocity': array([-2.23960951e-01, 4.41113412e-01, 4.12611960e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.51391029, 17.63711548, 0.13749903]), + 'camera_rotation': array([-5.9960041 , 6.30764055, -0.49495 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2478.647216796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 228.33963013, -3958.52392578, 16.51219177]), + 'frame': 21358, + 'frame_number': 21358, + 'framesequence': 81747, + 'gaze_dir': array([0.99211884, 0.10570526, 0.05767822]), + 'gaze_origin': array([-3.6116693 , -0.12383042, -0.37599185]), + 'gaze_valid': True, + 'gaze_vergence': 11.878023147583008, + 'handbrake_input': False, + 'left_eye_openness': 0.7526867985725403, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9937439 , 0.10919189, 0.02340698]), + 'left_gaze_origin': array([-3.27477741, 2.66605234, -0.48870546]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5159454345703125, + 'left_pupil_posn': array([ 0.44502294, -0.48489201]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99049377, 0.10221863, 0.09194946]), + 'right_gaze_origin': array([-3.94856119, -2.91371322, -0.26327822]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1039886474609375, + 'right_pupil_posn': array([-0.15336776, -0.53612697]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.08729686588048935, + 'timestamp': 690.575590878725, + 'timestamp_carla': 690578, + 'timestamp_device': 3844004, + 'timestamp_stream': 690.575590878725, + 'transform': [array([ 4.30187798e+00, 1.31001654e+01, -1.61321636e-03]), + array([ -0.06011932, -11.92358494, 0.02865505])]} +{'AngularVelocity': array([-0.01914029, 0.00489717, 3.95845127]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.860797882080078, + 'FR_Wheel_Angle': -17.45311737060547, + 'Location': array([ -1.38125503, -25.56132698, 0.17082776]), + 'Rotation': array([-5.13015464e-02, -5.15462761e+01, 5.20205908e-02]), + 'Velocity': array([-1.99068442e-01, 3.86852801e-01, 1.03340150e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.52716446, 17.67603683, 0.14218399]), + 'camera_rotation': array([-5.93285227, 6.43869495, -0.45655084]), + 'current_gear_input': False, + 'focus_actor_dist': 2596.884033203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 237.88438416, -4078.27050781, 16.5016098 ]), + 'frame': 21359, + 'frame_number': 21359, + 'framesequence': 81751, + 'gaze_dir': array([9.9559021e-01, 9.3421936e-02, 7.4005127e-04]), + 'gaze_origin': array([-3.9525547 , -0.11610643, -0.2314972 ]), + 'gaze_valid': True, + 'gaze_vergence': 76.00507354736328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99543762, 0.09510803, -0.00730896]), + 'left_gaze_origin': array([-3.74536133, 2.68247843, -0.28804475]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.518646240234375, + 'left_pupil_posn': array([ 0.44301951, -0.47991025]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9957428 , 0.09173584, 0.00878906]), + 'right_gaze_origin': array([-4.1597476 , -2.91469145, -0.17494966]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0631561279296875, + 'right_pupil_posn': array([-0.15693361, -0.53212667]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0634927898645401, + 'timestamp': 690.60732607916, + 'timestamp_carla': 690609, + 'timestamp_device': 3844037, + 'timestamp_stream': 690.60732607916, + 'transform': [array([ 4.30501890e+00, 1.30875607e+01, -1.49250031e-03]), + array([ -0.06017396, -11.93063068, 0.02845529])]} +{'AngularVelocity': array([ 0.20428912, -0.00787538, 5.02360678]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.72262954711914, + 'FR_Wheel_Angle': -17.36772346496582, + 'Location': array([ -1.44296038, -25.45378113, 0.17097448]), + 'Rotation': array([-6.26874715e-02, -5.07472649e+01, 4.53490801e-02]), + 'Velocity': array([-0.35599822, 0.66864079, 0.00082232]), + 'brake_input': 0.0, + 'camera_location': array([-5.54301167, 17.70746994, 0.1075857 ]), + 'camera_rotation': array([-6.07685995, 6.64790773, -0.35084695]), + 'current_gear_input': False, + 'focus_actor_dist': 1159.8902587890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -33.34936523, -2664.51074219, 16.79599762]), + 'frame': 21360, + 'frame_number': 21360, + 'framesequence': 81755, + 'gaze_dir': array([0.99472809, 0.09856415, 0.02745819]), + 'gaze_origin': array([-3.81731725, -0.10910874, -0.26131594]), + 'gaze_valid': True, + 'gaze_vergence': 328.606201171875, + 'handbrake_input': False, + 'left_eye_openness': 0.7722742557525635, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9944458 , 0.10256958, 0.02311707]), + 'left_gaze_origin': array([-3.56313801, 2.68729115, -0.34456331]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.421142578125, + 'left_pupil_posn': array([ 0.43454349, -0.46913111]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99501038, 0.09455872, 0.03179932]), + 'right_gaze_origin': array([-4.07149696, -2.90550852, -0.17806855]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0438385009765625, + 'right_pupil_posn': array([-0.16070467, -0.50065374]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.05555810034275055, + 'timestamp': 690.6415214762092, + 'timestamp_carla': 690644, + 'timestamp_device': 3844071, + 'timestamp_stream': 690.6415214762092, + 'transform': [array([ 4.30131197e+00, 1.30750217e+01, -1.31837837e-03]), + array([ -0.06027642, -11.92409706, 0.0281052 ])]} +{'AngularVelocity': array([-0.07667414, 0.03323169, 4.64186287]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.741558074951172, + 'FR_Wheel_Angle': -17.38395881652832, + 'Location': array([ -1.5359863 , -25.29628372, 0.17103471]), + 'Rotation': array([-5.89308701e-02, -4.95627785e+01, 4.90466468e-02]), + 'Velocity': array([-3.73990089e-01, 6.64111495e-01, 2.51970283e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.55638313, 17.74740028, 0.03015719]), + 'camera_rotation': array([-6.3285594 , 6.772017 , -0.06758155]), + 'current_gear_input': False, + 'focus_actor_dist': 1520.339111328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 41.33451843, -3020.05883789, 16.71009827]), + 'frame': 21361, + 'frame_number': 21361, + 'framesequence': 81759, + 'gaze_dir': array([0.99292755, 0.09696198, 0.06109619]), + 'gaze_origin': array([-3.70413995, -0.09945679, -0.29922792]), + 'gaze_valid': True, + 'gaze_vergence': 18.824508666992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99430847, 0.10189819, 0.03076172]), + 'left_gaze_origin': array([-3.36539626, 2.69632721, -0.41641238]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4727630615234375, + 'left_pupil_posn': array([ 0.41993856, -0.45242369]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99154663, 0.09202576, 0.09143066]), + 'right_gaze_origin': array([-4.0428834 , -2.89524078, -0.18204346]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0320587158203125, + 'right_pupil_posn': array([-0.16861665, -0.49363291]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 690.6746387779713, + 'timestamp_carla': 690677, + 'timestamp_device': 3844104, + 'timestamp_stream': 690.6746387779713, + 'transform': [array([ 4.29928827e+00, 1.30621967e+01, -9.51576221e-04]), + array([ -0.06041302, -11.92095757, 0.02740243])]} +{'AngularVelocity': array([-0.05293749, 0.03495126, 4.19839048]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.77812385559082, + 'FR_Wheel_Angle': -17.407032012939453, + 'Location': array([ -1.62376201, -25.1536541 , 0.17110628]), + 'Rotation': array([ -0.05307057, -48.46836472, 0.05243183]), + 'Velocity': array([-3.46561372e-01, 5.89278579e-01, 5.52549376e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.54408169e+00, 1.78504658e+01, 1.49166230e-02]), + 'camera_rotation': array([-6.52917576, 7.06912279, -0.10284133]), + 'current_gear_input': False, + 'focus_actor_dist': 2421.67919921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 205.56140137, -3909.46264648, 16.53586578]), + 'frame': 21362, + 'frame_number': 21362, + 'framesequence': 81763, + 'gaze_dir': array([0.99396515, 0.08886719, 0.0559082 ]), + 'gaze_origin': array([-3.77080488, -0.09576951, -0.2809639 ]), + 'gaze_valid': True, + 'gaze_vergence': 9.229963302612305, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99560547, 0.09037781, 0.02438354]), + 'left_gaze_origin': array([-3.36863256, 2.70142841, -0.41861421]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4701080322265625, + 'left_pupil_posn': array([ 0.41451597, -0.45586121]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99232483, 0.08735657, 0.08743286]), + 'right_gaze_origin': array([-4.17297697, -2.89296722, -0.1433136 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0870361328125, + 'right_pupil_posn': array([-0.17440909, -0.49784863]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.043656062334775925, + 'timestamp': 690.7073066793382, + 'timestamp_carla': 690709, + 'timestamp_device': 3844137, + 'timestamp_stream': 690.7073066793382, + 'transform': [array([ 4.29909945e+00, 1.30489540e+01, -5.47847711e-04]), + array([ -0.06049498, -11.92143822, 0.02663273])]} +{'AngularVelocity': array([-0.04541305, 0.03902423, 3.57566023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.822675704956055, + 'FR_Wheel_Angle': -17.439544677734375, + 'Location': array([ -1.70189154, -25.03133583, 0.17117514]), + 'Rotation': array([ -0.05053657, -47.5177002 , 0.05344343]), + 'Velocity': array([-2.96206683e-01, 4.82660085e-01, 2.43606555e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.52253342, 17.91734886, 0.02885553]), + 'camera_rotation': array([-6.56031418e+00, 7.31579876e+00, -8.87922244e-04]), + 'current_gear_input': False, + 'focus_actor_dist': 2052.210205078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 132.87670898, -3547.9152832 , 16.61280823]), + 'frame': 21363, + 'frame_number': 21363, + 'framesequence': 81767, + 'gaze_dir': array([0.99395752, 0.0870285 , 0.05804443]), + 'gaze_origin': array([-3.72807264, -0.08912583, -0.29632264]), + 'gaze_valid': True, + 'gaze_vergence': 18.336082458496094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99536133, 0.09262085, 0.02560425]), + 'left_gaze_origin': array([-3.38914514, 2.70758224, -0.41346592]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.53436279296875, + 'left_pupil_posn': array([ 0.40833592, -0.45563364]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99255371, 0.08143616, 0.09048462]), + 'right_gaze_origin': array([-4.06699991, -2.88583398, -0.17917939]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1066741943359375, + 'right_pupil_posn': array([-0.17933655, -0.49930036]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.7419559769332, + 'timestamp_carla': 690744, + 'timestamp_device': 3844171, + 'timestamp_stream': 690.7419559769332, + 'transform': [array([4.29882908e+00, 1.30349293e+01, 1.23214722e-05]), + array([ -0.06065891, -11.92182922, 0.02552351])]} +{'AngularVelocity': array([-0.02701791, 0.04482672, 2.87338424]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.86252784729004, + 'FR_Wheel_Angle': -17.471715927124023, + 'Location': array([ -1.76606917, -24.93409348, 0.17124921]), + 'Rotation': array([ -0.05044094, -46.75172043, 0.05264561]), + 'Velocity': array([-0.24637625, 0.38683236, 0.00039827]), + 'brake_input': 0.0, + 'camera_location': array([-5.50029278, 17.98249435, 0.03744039]), + 'camera_rotation': array([-6.47710228, 7.50411844, 0.07356686]), + 'current_gear_input': False, + 'focus_actor_dist': 2104.1396484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 147.40879822, -3599.52636719, 16.59753418]), + 'frame': 21364, + 'frame_number': 21364, + 'framesequence': 81771, + 'gaze_dir': array([0.99252319, 0.01861572, 0.12001038]), + 'gaze_origin': array([-3.83089137, -0.04297257, -0.21256563]), + 'gaze_valid': True, + 'gaze_vergence': 211.06219482421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9929657 , 0.02940369, 0.1146698 ]), + 'left_gaze_origin': array([-3.57482767, 2.74882531, -0.28551027]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.400604248046875, + 'left_pupil_posn': array([ 0.35305572, -0.39002562]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99208069, 0.00782776, 0.12535095]), + 'right_gaze_origin': array([-4.08695555, -2.8347702 , -0.13962097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0808563232421875, + 'right_pupil_posn': array([-0.24043673, -0.43824005]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.7699499763548, + 'timestamp_carla': 690772, + 'timestamp_device': 3844204, + 'timestamp_stream': 690.7699499763548, + 'transform': [array([4.29904747e+00, 1.30232735e+01, 1.80473318e-04]), + array([ -0.06069306, -11.92302036, 0.02515541])]} +{'AngularVelocity': array([-0.01518515, -0.03049354, 2.06991768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.89351463317871, + 'FR_Wheel_Angle': -17.488990783691406, + 'Location': array([ -1.81867456, -24.85664177, 0.17130037]), + 'Rotation': array([ -0.05120593, -46.13156128, 0.05190528]), + 'Velocity': array([-1.78075403e-01, 2.83530444e-01, 2.41088856e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.48036575, 18.04356003, 0.04121324]), + 'camera_rotation': array([-6.36158323, 7.66062641, 0.19805476]), + 'current_gear_input': False, + 'focus_actor_dist': 4816.39404296875, + 'focus_actor_name': 'SM_Shop_52', + 'focus_actor_pt': array([ 326.87310791, -6318.25683594, 169.67272949]), + 'frame': 21365, + 'frame_number': 21365, + 'framesequence': 81774, + 'gaze_dir': array([0.99198914, 0.0182724 , 0.12400055]), + 'gaze_origin': array([-3.84994531, -0.04129181, -0.2135689 ]), + 'gaze_valid': True, + 'gaze_vergence': 141.10264587402344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99304199, 0.02963257, 0.11393738]), + 'left_gaze_origin': array([-3.62701273, 2.7542665 , -0.27989656]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3975677490234375, + 'left_pupil_posn': array([ 0.35010862, -0.39463603]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99093628, 0.00691223, 0.13406372]), + 'right_gaze_origin': array([-4.07287788, -2.83685017, -0.14724122]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.067626953125, + 'right_pupil_posn': array([-0.23880416, -0.44095135]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.8016779758036, + 'timestamp_carla': 690804, + 'timestamp_device': 3844229, + 'timestamp_stream': 690.8016779758036, + 'transform': [array([4.29706049e+00, 1.30110283e+01, 7.30590778e-04]), + array([ -0.06085698, -11.91987419, 0.0241387 ])]} +{'AngularVelocity': array([-0.04851591, 0.04030813, 2.03369141]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.904403686523438, + 'FR_Wheel_Angle': -17.48284912109375, + 'Location': array([ -1.86623764, -24.78859329, 0.17138331]), + 'Rotation': array([ -0.05554309, -45.59217453, 0.04819194]), + 'Velocity': array([-1.97276205e-01, 2.93109626e-01, 2.21137991e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.45804405, 18.11073112, 0.05357291]), + 'camera_rotation': array([-6.28165627, 7.86224461, 0.13162932]), + 'current_gear_input': False, + 'focus_actor_dist': 4817.03466796875, + 'focus_actor_name': 'SM_Shop_52', + 'focus_actor_pt': array([ 339.60321045, -6318.25683594, 198.5406189 ]), + 'frame': 21366, + 'frame_number': 21366, + 'framesequence': 81779, + 'gaze_dir': array([0.99324036, 0.0120163 , 0.11456299]), + 'gaze_origin': array([-3.84057164, -0.03974686, -0.21483307]), + 'gaze_valid': True, + 'gaze_vergence': 157.71798706054688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99415588, 0.0223999 , 0.1055603 ]), + 'left_gaze_origin': array([-3.59337044, 2.75729394, -0.28688201]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.37823486328125, + 'left_pupil_posn': array([ 0.3450501 , -0.39573824]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99232483, 0.00163269, 0.12356567]), + 'right_gaze_origin': array([-4.08777332, -2.83678746, -0.14278412]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.060577392578125, + 'right_pupil_posn': array([-0.24176335, -0.44428778]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.8369119763374, + 'timestamp_carla': 690839, + 'timestamp_device': 3844271, + 'timestamp_stream': 690.8369119763374, + 'transform': [array([4.29258204e+00, 1.29982624e+01, 1.32289878e-03]), + array([ -0.0611097 , -11.9118576 , 0.02296939])]} +{'AngularVelocity': array([0.0737856 , 0.01331121, 2.50084829]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.87423324584961, + 'FR_Wheel_Angle': -17.47484588623047, + 'Location': array([ -1.91303575, -24.72237778, 0.17143972]), + 'Rotation': array([ -0.05630808, -45.05472946, 0.04705301]), + 'Velocity': array([-2.04764023e-01, 3.07924956e-01, 4.03404229e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.45920563, 18.18177605, 0.02228782]), + 'camera_rotation': array([-6.44370937, 8.09029198, 0.08857201]), + 'current_gear_input': False, + 'focus_actor_dist': 4813.74072265625, + 'focus_actor_name': 'SM_Shop_52', + 'focus_actor_pt': array([ 325.59405518, -6318.25732422, 159.49787903]), + 'frame': 21367, + 'frame_number': 21367, + 'framesequence': 81783, + 'gaze_dir': array([0.99343109, 0.00359344, 0.11300659]), + 'gaze_origin': array([-3.85421777, -0.03749314, -0.20929185]), + 'gaze_valid': True, + 'gaze_vergence': 125.99417877197266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99467468, 0.01631165, 0.10166931]), + 'left_gaze_origin': array([-3.59156346, 2.759166 , -0.28681949]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.355926513671875, + 'left_pupil_posn': array([ 0.33953583, -0.39481664]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9921875 , -0.00912476, 0.12434387]), + 'right_gaze_origin': array([-4.11687183, -2.83415246, -0.13176423]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9989776611328125, + 'right_pupil_posn': array([-0.24616045, -0.44405246]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.8701726794243, + 'timestamp_carla': 690872, + 'timestamp_device': 3844304, + 'timestamp_stream': 690.8701726794243, + 'transform': [array([4.28977919e+00, 1.29861403e+01, 1.83347694e-03]), + array([ -0.06128728, -11.90712357, 0.02199979])]} +{'AngularVelocity': array([0.02993056, 0.02012636, 2.95180273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.825374603271484, + 'FR_Wheel_Angle': -17.417097091674805, + 'Location': array([ -1.98525238, -24.62460136, 0.17156903]), + 'Rotation': array([-6.43608719e-02, -4.42518387e+01, 4.19996642e-02]), + 'Velocity': array([-3.15840572e-01, 4.56680208e-01, 2.39543908e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.45080948e+00, 1.82355881e+01, 7.11422320e-03]), + 'camera_rotation': array([-6.54482365, 8.29995537, 0.11054802]), + 'current_gear_input': False, + 'focus_actor_dist': 3816.942138671875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 193.56080627, -5331.48974609, 137.51374817]), + 'frame': 21368, + 'frame_number': 21368, + 'framesequence': 81788, + 'gaze_dir': array([0.99394226, 0.0013504 , 0.10429382]), + 'gaze_origin': array([-3.89223647, -0.03814698, -0.20682527]), + 'gaze_valid': True, + 'gaze_vergence': 34.42381286621094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9972229 , 0.01473999, 0.07287598]), + 'left_gaze_origin': array([-3.64590168, 2.75942707, -0.27935031]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3231353759765625, + 'left_pupil_posn': array([ 0.33958852, -0.39755774]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99066162, -0.01203918, 0.13571167]), + 'right_gaze_origin': array([-4.13857126, -2.83572102, -0.13430025]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0222015380859375, + 'right_pupil_posn': array([-0.24617302, -0.46256423]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.9132754765451, + 'timestamp_carla': 690915, + 'timestamp_device': 3844346, + 'timestamp_stream': 690.9132754765451, + 'transform': [array([4.28431129e+00, 1.29715796e+01, 2.68285745e-03]), + array([ -0.06155366, -11.89726543, 0.02034271])]} +{'AngularVelocity': array([-0.02487607, -0.00939306, 4.94723701]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.742116928100586, + 'FR_Wheel_Angle': -17.37405014038086, + 'Location': array([ -2.08445024, -24.49403191, 0.171699 ]), + 'Rotation': array([-6.78715855e-02, -4.31684952e+01, 4.04601358e-02]), + 'Velocity': array([-4.41159159e-01, 6.18685961e-01, 4.98275738e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.44124794, 18.2602272 , 0.025546 ]), + 'camera_rotation': array([-6.45861959, 8.36405945, 0.0589317 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3816.51904296875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 199.22541809, -5331.49023438, 97.4375 ]), + 'frame': 21369, + 'frame_number': 21369, + 'framesequence': 81791, + 'gaze_dir': array([9.94369507e-01, 4.42504883e-04, 9.96017456e-02]), + 'gaze_origin': array([-3.94265318, -0.03816986, -0.19035035]), + 'gaze_valid': True, + 'gaze_vergence': 29.5557861328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9977417 , 0.01278687, 0.06593323]), + 'left_gaze_origin': array([-3.66107631, 2.76063561, -0.2756348 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3356781005859375, + 'left_pupil_posn': array([ 0.33916676, -0.39928925]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99099731, -0.01190186, 0.13327026]), + 'right_gaze_origin': array([-4.22422981, -2.83697534, -0.10506592]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0081024169921875, + 'right_pupil_posn': array([-0.24627286, -0.46340227]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.9364787787199, + 'timestamp_carla': 690938, + 'timestamp_device': 3844371, + 'timestamp_stream': 690.9364787787199, + 'transform': [array([4.28267145e+00, 1.29632874e+01, 2.79806135e-03]), + array([ -0.06154683, -11.89457321, 0.02016011])]} +{'AngularVelocity': array([5.14826225e-03, 9.21448972e-03, 6.73588848e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.626232147216797, + 'FR_Wheel_Angle': -17.287399291992188, + 'Location': array([ -2.21673632, -24.32744789, 0.17187425]), + 'Rotation': array([-7.44627193e-02, -4.18119011e+01, 3.69928740e-02]), + 'Velocity': array([-6.45626664e-01, 8.56756449e-01, 7.78017042e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.42277241, 18.25222778, 0.0516414 ]), + 'camera_rotation': array([-6.30305529, 8.28239155, 0.0160742 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3815.2333984375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 200.08125305, -5331.48974609, 85.13882446]), + 'frame': 21370, + 'frame_number': 21370, + 'framesequence': 81794, + 'gaze_dir': array([9.94003296e-01, 1.22070312e-04, 1.04576111e-01]), + 'gaze_origin': array([-3.92793226, -0.03666458, -0.19725114]), + 'gaze_valid': True, + 'gaze_vergence': 33.79253387451172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99711609, 0.01113892, 0.07498169]), + 'left_gaze_origin': array([-3.65707088, 2.76146245, -0.2774567 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.317901611328125, + 'left_pupil_posn': array([ 0.33881474, -0.39928925]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9908905 , -0.01089478, 0.13417053]), + 'right_gaze_origin': array([-4.19879341, -2.83479166, -0.1170456 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9880828857421875, + 'right_pupil_posn': array([-0.2484678 , -0.46284974]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 690.9680859781802, + 'timestamp_carla': 690970, + 'timestamp_device': 3844396, + 'timestamp_stream': 690.9680859781802, + 'transform': [array([4.27894449e+00, 1.29525232e+01, 2.92467116e-03]), + array([ -0.06142389, -11.88783169, 0.01994411])]} +{'AngularVelocity': array([-0.06246363, -0.02701505, 6.6208992 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.63262367248535, + 'FR_Wheel_Angle': -17.30805206298828, + 'Location': array([ -2.37791753, -24.13448715, 0.17200097]), + 'Rotation': array([ -0.06488679, -40.20378113, 0.04365496]), + 'Velocity': array([-6.49157405e-01, 8.18171680e-01, 7.94143649e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.43764877, 18.22473145, 0.05165099]), + 'camera_rotation': array([-6.28072071, 8.22042847, -0.02769724]), + 'current_gear_input': False, + 'focus_actor_dist': 3813.310791015625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 193.18087769, -5331.48925781, 114.54589844]), + 'frame': 21371, + 'frame_number': 21371, + 'framesequence': 81798, + 'gaze_dir': array([9.94300842e-01, 5.26428223e-04, 1.00479126e-01]), + 'gaze_origin': array([-3.91458225, -0.03737488, -0.19967271]), + 'gaze_valid': True, + 'gaze_vergence': 23.218647003173828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99772644, 0.00947571, 0.06655884]), + 'left_gaze_origin': array([-3.63517022, 2.7613678 , -0.28404391]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2690582275390625, + 'left_pupil_posn': array([ 0.33922684, -0.39881849]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99087524, -0.00842285, 0.13439941]), + 'right_gaze_origin': array([-4.19399452, -2.83611774, -0.11530152]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.94305419921875, + 'right_pupil_posn': array([-0.24808645, -0.46352887]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.03967345505952835, + 'timestamp': 691.0019066780806, + 'timestamp_carla': 691004, + 'timestamp_device': 3844429, + 'timestamp_stream': 691.0019066780806, + 'transform': [array([4.27886629e+00, 1.29404802e+01, 3.12055578e-03]), + array([ -0.06150585, -11.88844395, 0.01954949])]} +{'AngularVelocity': array([-0.01888619, -0.01766101, 5.53561735]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.710845947265625, + 'FR_Wheel_Angle': -17.36338233947754, + 'Location': array([ -2.50268006, -23.9918232 , 0.17207707]), + 'Rotation': array([ -0.05575483, -38.98929977, 0.04809069]), + 'Velocity': array([-0.54965669, 0.66498929, 0.00071239]), + 'brake_input': 0.0, + 'camera_location': array([-5.4483757 , 18.19594765, 0.04865663]), + 'camera_rotation': array([-6.24195242, 8.14784145, -0.09496081]), + 'current_gear_input': False, + 'focus_actor_dist': 3811.9794921875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 190.53163147, -5331.49023438, 100.36802673]), + 'frame': 21372, + 'frame_number': 21372, + 'framesequence': 81803, + 'gaze_dir': array([0.99289703, 0.00521088, 0.11647034]), + 'gaze_origin': array([-3.86246371, -0.04038391, -0.21788864]), + 'gaze_valid': True, + 'gaze_vergence': 52.614498138427734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99534607, 0.0146637 , 0.09515381]), + 'left_gaze_origin': array([-3.57947731, 2.7578342 , -0.30180818]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.238037109375, + 'left_pupil_posn': array([ 0.34200931, -0.39766347]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.990448 , -0.00424194, 0.13778687]), + 'right_gaze_origin': array([-4.14545012, -2.83860183, -0.13396913]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.783355712890625, + 'right_pupil_posn': array([-0.24369383, -0.45442212]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.0352176763117, + 'timestamp_carla': 691037, + 'timestamp_device': 3844471, + 'timestamp_stream': 691.0352176763117, + 'transform': [array([4.27852392e+00, 1.29289036e+01, 3.30595020e-03]), + array([ -0.06155366, -11.88849735, 0.01919081])]} +{'AngularVelocity': array([ 0.01808277, -0.00505742, 4.27455568]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.77644157409668, + 'FR_Wheel_Angle': -17.40848731994629, + 'Location': array([ -2.63628078, -23.84553719, 0.172217 ]), + 'Rotation': array([ -0.05399264, -37.7075882 , 0.04726566]), + 'Velocity': array([-4.30868179e-01, 4.98672664e-01, 4.57839953e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.46453857, 18.15948486, 0.03531996]), + 'camera_rotation': array([-6.2799964 , 8.07555676, -0.05789964]), + 'current_gear_input': False, + 'focus_actor_dist': 3812.1162109375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 202.92547607, -5331.48974609, 164.11665344]), + 'frame': 21373, + 'frame_number': 21373, + 'framesequence': 81806, + 'gaze_dir': array([0.99297333, 0.00540161, 0.11564636]), + 'gaze_origin': array([-3.8554008 , -0.04194336, -0.22166215]), + 'gaze_valid': True, + 'gaze_vergence': 58.508113861083984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99536133, 0.01649475, 0.09461975]), + 'left_gaze_origin': array([-3.57779551, 2.75689864, -0.30251467]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2455291748046875, + 'left_pupil_posn': array([ 0.34213161, -0.39824343]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99058533, -0.00569153, 0.13667297]), + 'right_gaze_origin': array([-4.13300657, -2.84078526, -0.14080964]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.83331298828125, + 'right_pupil_posn': array([-0.24138713, -0.45709062]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.0692541785538, + 'timestamp_carla': 691071, + 'timestamp_device': 3844495, + 'timestamp_stream': 691.0692541785538, + 'transform': [array([4.27695894e+00, 1.29176331e+01, 3.47909913e-03]), + array([ -0.06164929, -11.88611794, 0.01884609])]} +{'AngularVelocity': array([ 2.35891584e-02, -3.22520686e-03, 3.59308195e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.823549270629883, + 'FR_Wheel_Angle': -17.437175750732422, + 'Location': array([ -2.73104668, -23.74564171, 0.17233023]), + 'Rotation': array([ -0.05636955, -36.81346512, 0.04454308]), + 'Velocity': array([-3.56918007e-01, 4.00178403e-01, 2.31752390e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.44857025e+00, 1.81501007e+01, 9.19805840e-04]), + 'camera_rotation': array([-6.2261405 , 7.97677279, -0.04285639]), + 'current_gear_input': False, + 'focus_actor_dist': 3810.48779296875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 198.89959717, -5331.49023438, 158.3740387 ]), + 'frame': 21374, + 'frame_number': 21374, + 'framesequence': 81810, + 'gaze_dir': array([0.99210358, 0.01494598, 0.12107086]), + 'gaze_origin': array([-3.81756234, -0.0469574 , -0.23268357]), + 'gaze_valid': True, + 'gaze_vergence': 31.447338104248047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99536133, 0.02305603, 0.09336853]), + 'left_gaze_origin': array([-3.48860025, 2.75119185, -0.33308262]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3497467041015625, + 'left_pupil_posn': array([ 0.34890044, -0.39612401]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98884583, 0.00683594, 0.14877319]), + 'right_gaze_origin': array([-4.14652395, -2.8451066 , -0.13228455]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8014068603515625, + 'right_pupil_posn': array([-0.23550636, -0.4541986 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.1019350774586, + 'timestamp_carla': 691104, + 'timestamp_device': 3844529, + 'timestamp_stream': 691.1019350774586, + 'transform': [array([4.27801323e+00, 1.29064035e+01, 3.59811774e-03]), + array([ -0.06165611, -11.88892269, 0.01863292])]} +{'AngularVelocity': array([ 2.21691616e-02, -3.07410234e-03, 3.19362426e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.850927352905273, + 'FR_Wheel_Angle': -17.459491729736328, + 'Location': array([ -2.79913425, -23.67582893, 0.17242582]), + 'Rotation': array([ -0.05871913, -36.17638397, 0.04228762]), + 'Velocity': array([-3.17192405e-01, 3.47688407e-01, 2.44445808e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.40858269e+00, 1.80842342e+01, -1.04486579e-02]), + 'camera_rotation': array([-6.20398331e+00, 7.78762007e+00, -5.09337382e-03]), + 'current_gear_input': False, + 'focus_actor_dist': 4807.189453125, + 'focus_actor_name': 'SM_Shop_52', + 'focus_actor_pt': array([ 349.20648193, -6318.25683594, 195.48699951]), + 'frame': 21375, + 'frame_number': 21375, + 'framesequence': 81815, + 'gaze_dir': array([0.9934845 , 0.01211548, 0.11254883]), + 'gaze_origin': array([-3.83668232, -0.0588707 , -0.22682342]), + 'gaze_valid': True, + 'gaze_vergence': 189.74586486816406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99415588, 0.02232361, 0.10548401]), + 'left_gaze_origin': array([-3.54981565, 2.73880625, -0.30862734]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2125396728515625, + 'left_pupil_posn': array([ 0.3577106 , -0.40277708]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99281311, 0.00190735, 0.11961365]), + 'right_gaze_origin': array([-4.12354898, -2.85654783, -0.14501953]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7548370361328125, + 'right_pupil_posn': array([-0.22703707, -0.45358205]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.1361240781844, + 'timestamp_carla': 691138, + 'timestamp_device': 3844570, + 'timestamp_stream': 691.1361240781844, + 'transform': [array([4.27869415e+00, 1.28950863e+01, 3.73857492e-03]), + array([ -0.06166977, -11.89099026, 0.01835067])]} +{'AngularVelocity': array([0.07123113, 0.03750997, 3.25336289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.850622177124023, + 'FR_Wheel_Angle': -17.4436092376709, + 'Location': array([ -2.881253 , -23.59372711, 0.17252836]), + 'Rotation': array([ -0.06320657, -35.41705322, 0.03858034]), + 'Velocity': array([-3.36723536e-01, 3.53594840e-01, 3.40061175e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.36917686, 18.01034546, 0.0379639 ]), + 'camera_rotation': array([-6.09421539, 7.50019884, 0.03273971]), + 'current_gear_input': False, + 'focus_actor_dist': 3808.89697265625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 205.33406067, -5331.48925781, 151.35270691]), + 'frame': 21376, + 'frame_number': 21376, + 'framesequence': 81819, + 'gaze_dir': array([0.9961319 , 0.07226562, 0.03850555]), + 'gaze_origin': array([-3.73646307, -0.10525208, -0.30730745]), + 'gaze_valid': True, + 'gaze_vergence': 9.946269035339355, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99717712, 0.07473755, 0.00682068]), + 'left_gaze_origin': array([-3.44360352, 2.67855239, -0.39803925]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.302276611328125, + 'left_pupil_posn': array([ 0.42733312, -0.46440732]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99508667, 0.0697937 , 0.07019043]), + 'right_gaze_origin': array([-4.0293231 , -2.88905644, -0.21657564]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9616546630859375, + 'right_pupil_posn': array([-0.18435019, -0.5256151 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.1755201779306, + 'timestamp_carla': 691178, + 'timestamp_device': 3844604, + 'timestamp_stream': 691.1755201779306, + 'transform': [array([4.27803755e+00, 1.28830414e+01, 3.93342972e-03]), + array([ -0.0617654 , -11.89045238, 0.01787434])]} +{'AngularVelocity': array([-0.0871876 , 0.02433785, 3.69617939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.724164962768555, + 'FR_Wheel_Angle': -17.319400787353516, + 'Location': array([ -2.96275544, -23.5144577 , 0.17264138]), + 'Rotation': array([-7.06787929e-02, -3.46592484e+01, 3.40388045e-02]), + 'Velocity': array([-4.24677968e-01, 4.31780756e-01, 2.70357123e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.36618042, 17.93587685, 0.05184485]), + 'camera_rotation': array([-5.95815802, 7.32483864, -0.05805238]), + 'current_gear_input': False, + 'focus_actor_dist': 1737.1103515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 61.76902771, -3257.09326172, 16.68764496]), + 'frame': 21377, + 'frame_number': 21377, + 'framesequence': 81823, + 'gaze_dir': array([0.99701691, 0.07559204, 0.01383209]), + 'gaze_origin': array([-3.86284971, -0.11229859, -0.26098177]), + 'gaze_valid': True, + 'gaze_vergence': 477.5412292480469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99665833, 0.0806427 , 0.01187134]), + 'left_gaze_origin': array([-3.7630434 , 2.67534494, -0.2772339 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2360382080078125, + 'left_pupil_posn': array([ 0.44082975, -0.47237611]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99737549, 0.07054138, 0.01579285]), + 'right_gaze_origin': array([-3.96265578, -2.89994216, -0.24472962]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.87261962890625, + 'right_pupil_posn': array([-0.17415464, -0.5288502 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.2093672789633, + 'timestamp_carla': 691211, + 'timestamp_device': 3844637, + 'timestamp_stream': 691.2093672789633, + 'transform': [array([4.27934313e+00, 1.28723488e+01, 3.99362575e-03]), + array([ -0.06174491, -11.89371014, 0.01781022])]} +{'AngularVelocity': array([-0.02961728, -0.01200491, 3.76625395]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.219072341918945, + 'FR_Wheel_Angle': -16.988712310791016, + 'Location': array([ -3.06403494, -23.41904259, 0.17282221]), + 'Rotation': array([-7.36635849e-02, -3.37708549e+01, 3.23723517e-02]), + 'Velocity': array([-0.53224522, 0.52935767, 0.00056668]), + 'brake_input': 0.0, + 'camera_location': array([-5.35045528, 17.88713455, 0.05260037]), + 'camera_rotation': array([-5.8240881 , 7.15624094, -0.0932032 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1308.689697265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -10.79058838, -2834.60791016, 16.76476288]), + 'frame': 21378, + 'frame_number': 21378, + 'framesequence': 81827, + 'gaze_dir': array([0.99684906, 0.07766724, 0.01325989]), + 'gaze_origin': array([-3.86282063, -0.1154068 , -0.26015168]), + 'gaze_valid': True, + 'gaze_vergence': 320.4789123535156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99635315, 0.08465576, 0.00982666]), + 'left_gaze_origin': array([-3.7417438 , 2.67348504, -0.28518832]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2421112060546875, + 'left_pupil_posn': array([ 0.44163847, -0.47289264]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99734497, 0.07067871, 0.01669312]), + 'right_gaze_origin': array([-3.98389769, -2.90429854, -0.23511507]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.860626220703125, + 'right_pupil_posn': array([-0.1692751 , -0.52757752]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.2419287785888, + 'timestamp_carla': 691244, + 'timestamp_device': 3844670, + 'timestamp_stream': 691.2419287785888, + 'transform': [array([4.28048897e+00, 1.28622265e+01, 4.00924683e-03]), + array([ -0.06171758, -11.89661789, 0.01783315])]} +{'AngularVelocity': array([0.03052913, 0.01823252, 6.5974865 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.072511672973633, + 'FR_Wheel_Angle': -16.894935607910156, + 'Location': array([ -3.18772483, -23.30760765, 0.17299204]), + 'Rotation': array([-7.57741109e-02, -3.27171173e+01, 3.07578500e-02]), + 'Velocity': array([-6.72684908e-01, 6.38476729e-01, 5.43317758e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.35246468, 17.81691551, 0.06664736]), + 'camera_rotation': array([-5.74447584, 6.96154165, -0.12691 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1335.754150390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -7.4619751 , -2862.63842773, 16.76118469]), + 'frame': 21379, + 'frame_number': 21379, + 'framesequence': 81831, + 'gaze_dir': array([0.99195099, 0.09020996, 0.06793976]), + 'gaze_origin': array([-3.55221248, -0.12851182, -0.38736725]), + 'gaze_valid': True, + 'gaze_vergence': 1.1839557886123657, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99627686, 0.08529663, 0.01123047]), + 'left_gaze_origin': array([-3.14615488, 2.65224314, -0.52914739]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.472808837890625, + 'left_pupil_posn': array([ 0.44787693, -0.47199464]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98762512, 0.09512329, 0.12464905]), + 'right_gaze_origin': array([-3.95827031, -2.90926671, -0.24558719]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9394989013671875, + 'right_pupil_posn': array([-0.16550368, -0.52903962]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 691.2745387777686, + 'timestamp_carla': 691277, + 'timestamp_device': 3844704, + 'timestamp_stream': 691.2745387777686, + 'transform': [array([4.28073025e+00, 1.28524847e+01, 4.01826855e-03]), + array([ -0.06173125, -11.8977108 , 0.01784839])]} +{'AngularVelocity': array([-0.06064975, -0.02983881, 7.05833054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.085264205932617, + 'FR_Wheel_Angle': -16.977806091308594, + 'Location': array([ -3.32049727, -23.19234276, 0.17312039]), + 'Rotation': array([-7.45515078e-02, -3.16093559e+01, 3.13324854e-02]), + 'Velocity': array([-7.29226887e-01, 6.70136094e-01, 5.56383107e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.36255741, 17.78315544, 0.08614666]), + 'camera_rotation': array([-5.63367653, 6.78521395, -0.21200788]), + 'current_gear_input': False, + 'focus_actor_dist': 3505.24169921875, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ 390.52868652, -5000.12890625, 23.122612 ]), + 'frame': 21380, + 'frame_number': 21380, + 'framesequence': 81835, + 'gaze_dir': array([0.99198151, 0.09420776, 0.06611633]), + 'gaze_origin': array([-3.53542352, -0.13107681, -0.39607775]), + 'gaze_valid': True, + 'gaze_vergence': 2.8980207443237305, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99549866, 0.09368896, 0.01417542]), + 'left_gaze_origin': array([-3.10664845, 2.65015578, -0.54632723]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2934417724609375, + 'left_pupil_posn': array([ 0.4465878 , -0.47668421]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98846436, 0.09472656, 0.11805725]), + 'right_gaze_origin': array([-3.96419835, -2.91230941, -0.24582826]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.95086669921875, + 'right_pupil_posn': array([-0.16001773, -0.5296253 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.08729686588048935, + 'timestamp': 691.3073311783373, + 'timestamp_carla': 691309, + 'timestamp_device': 3844737, + 'timestamp_stream': 691.3073311783373, + 'transform': [array([4.28034210e+00, 1.28430157e+01, 4.01403429e-03]), + array([ -0.06173125, -11.89753056, 0.01787559])]} +{'AngularVelocity': array([-0.00491837, 0.01933065, 4.69236565]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.86443328857422, + 'FR_Wheel_Angle': -17.473142623901367, + 'Location': array([ -3.48880005, -23.05060959, 0.17459621]), + 'Rotation': array([ -0.11111351, -30.22913742, 0.11488114]), + 'Velocity': array([-0.54334098, 0.48664328, 0.00300951]), + 'brake_input': 0.0, + 'camera_location': array([-5.38021278, 17.76854706, 0.10798617]), + 'camera_rotation': array([-5.64962482, 6.81135941, -0.19280264]), + 'current_gear_input': False, + 'focus_actor_dist': 3504.72802734375, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ 393.16516113, -5000.11425781, 24.05569458]), + 'frame': 21381, + 'frame_number': 21381, + 'framesequence': 81839, + 'gaze_dir': array([0.99674225, 0.01134491, 0.07489014]), + 'gaze_origin': array([-3.8840766 , -0.06731644, -0.24190752]), + 'gaze_valid': True, + 'gaze_vergence': 58.00016403198242, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99830627, 0.02609253, 0.05183411]), + 'left_gaze_origin': array([-3.60183716, 2.72875381, -0.3255356 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2244415283203125, + 'left_pupil_posn': array([ 0.36547327, -0.43583202]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99517822, -0.00340271, 0.09794617]), + 'right_gaze_origin': array([-4.16631603, -2.86338663, -0.15827942]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.959014892578125, + 'right_pupil_posn': array([-0.22157407, -0.49558806]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.11903563141822815, + 'timestamp': 691.3403894789517, + 'timestamp_carla': 691342, + 'timestamp_device': 3844770, + 'timestamp_stream': 691.3403894789517, + 'transform': [array([4.27912760e+00, 1.28335667e+01, 3.84805677e-03]), + array([ -0.06168343, -11.89573288, 0.01820871])]} +{'AngularVelocity': array([ 0.01996254, -0.02764445, 3.4905839 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.012887954711914, + 'FR_Wheel_Angle': -17.62401580810547, + 'Location': array([ -3.60055137, -22.95980835, 0.17467704]), + 'Rotation': array([ -0.1054991 , -29.2902813 , 0.10917091]), + 'Velocity': array([-0.40203661, 0.34750855, 0.00040346]), + 'brake_input': 0.0, + 'camera_location': array([-5.37073708, 17.79446411, 0.10623581]), + 'camera_rotation': array([-5.80335855, 6.88148546, -0.29118499]), + 'current_gear_input': False, + 'focus_actor_dist': 3796.30712890625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 134.52748108, -5331.48974609, 44.73661804]), + 'frame': 21382, + 'frame_number': 21382, + 'framesequence': 81843, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 10.24850082397461, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.99778748, -0.01504517, 0.0645752 ]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.8832265734672546, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.23005056, -2.83068871, -0.10479736]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.87384033203125, + 'right_pupil_posn': array([-0.26201659, -0.46506 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.15078964829444885, + 'timestamp': 691.3739735782146, + 'timestamp_carla': 691376, + 'timestamp_device': 3844804, + 'timestamp_stream': 691.3739735782146, + 'transform': [array([4.28134203e+00, 1.28231764e+01, 3.65777966e-03]), + array([ -0.06166977, -11.9008255 , 0.01857941])]} +{'AngularVelocity': array([ 0.02540995, -0.00880182, 2.87845731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.040298461914062, + 'FR_Wheel_Angle': -18.420780181884766, + 'Location': array([ -3.67379999, -22.90167236, 0.17467846]), + 'Rotation': array([ -0.10522589, -28.66738129, 0.10364918]), + 'Velocity': array([-0.31937674, 0.2738584 , 0.00036113]), + 'brake_input': 0.0, + 'camera_location': array([-5.41012573, 17.79228401, 0.08303213]), + 'camera_rotation': array([-5.83492088, 7.03929424, -0.42141977]), + 'current_gear_input': False, + 'focus_actor_dist': 1159.7025146484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -131.88787842, -2708.26855469, 16.8937149 ]), + 'frame': 21383, + 'frame_number': 21383, + 'framesequence': 81847, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.6333006620407104, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.24356079, -2.81196904, -0.08883058]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.17856107652187347, + 'timestamp': 691.4073160775006, + 'timestamp_carla': 691409, + 'timestamp_device': 3844837, + 'timestamp_stream': 691.4073160775006, + 'transform': [array([4.27866316e+00, 1.28138304e+01, 3.52115626e-03]), + array([ -0.06156049, -11.89609718, 0.01885232])]} +{'AngularVelocity': array([-9.88688134e-03, -2.22249865e-03, 2.73778582e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.47233009338379, + 'FR_Wheel_Angle': -19.449169158935547, + 'Location': array([ -3.75131369, -22.84046173, 0.17474331]), + 'Rotation': array([ -0.10711785, -27.97151566, 0.09835608]), + 'Velocity': array([-0.24898238, 0.2132529 , 0.00031942]), + 'brake_input': 0.0, + 'camera_location': array([-5.41929245, 17.80404472, 0.08148477]), + 'camera_rotation': array([-5.72205877, 7.14536572, -0.44488856]), + 'current_gear_input': False, + 'focus_actor_dist': 1153.274658203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -129.43521118, -2702.50488281, 16.89159393]), + 'frame': 21384, + 'frame_number': 21384, + 'framesequence': 81851, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.8085114359855652, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.09087372, -2.82428145, -0.13684998]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.4414716772735, + 'timestamp_carla': 691443, + 'timestamp_device': 3844870, + 'timestamp_stream': 691.4414716772735, + 'transform': [array([4.27938080e+00, 1.28030291e+01, 3.13039776e-03]), + array([ -0.0616083 , -11.89832497, 0.01960823])]} +{'AngularVelocity': array([0.07824003, 0.0263075 , 2.64304233]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.22096061706543, + 'FR_Wheel_Angle': -19.783203125, + 'Location': array([ -3.81560421, -22.79008293, 0.17481102]), + 'Rotation': array([ -0.11053295, -27.37430954, 0.09359497]), + 'Velocity': array([-0.29388997, 0.24870947, 0.00103396]), + 'brake_input': 0.0, + 'camera_location': array([-5.43462181, 17.80698776, 0.060632 ]), + 'camera_rotation': array([-5.74346495, 7.23386002, -0.41122046]), + 'current_gear_input': False, + 'focus_actor_dist': 1176.026611328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -125.15499115, -2726.05517578, 16.88569641]), + 'frame': 21385, + 'frame_number': 21385, + 'framesequence': 81855, + 'gaze_dir': array([ 0., -0., 0.]), + 'gaze_origin': array([-4.01395369, -0.01458435, -0.14341584]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.3984026610851288, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([-3.88184524, 2.79384923, -0.16170046]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-4.1460619 , -2.82301807, -0.12513123]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9129180908203125, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.4756146781147, + 'timestamp_carla': 691478, + 'timestamp_device': 3844904, + 'timestamp_stream': 691.4756146781147, + 'transform': [array([4.27642202e+00, 1.27918491e+01, 2.31861114e-03]), + array([ -0.06121898, -11.89321136, 0.02119756])]} +{'AngularVelocity': array([ 0.11074506, -0.32390061, 2.91152239]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.206459045410156, + 'FR_Wheel_Angle': -19.794252395629883, + 'Location': array([ -3.88114214, -22.73948479, 0.17381534]), + 'Rotation': array([-7.19901919e-02, -2.67612457e+01, 2.58363299e-02]), + 'Velocity': array([-0.30224052, 0.2452845 , -0.00577569]), + 'brake_input': 0.0, + 'camera_location': array([-5.44586563, 17.81506157, 0.06534276]), + 'camera_rotation': array([-5.8269639 , 7.32031965, -0.37453911]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ -232.50289917, -1557.83178711, 134.37872314]), + 'frame': 21386, + 'frame_number': 21386, + 'framesequence': 81859, + 'gaze_dir': array([ 0.99642944, -0.02630615, 0.0797348 ]), + 'gaze_origin': array([-3.93667006, -0.01608887, -0.17098084]), + 'gaze_valid': True, + 'gaze_vergence': 210.22267150878906, + 'handbrake_input': False, + 'left_eye_openness': 0.4558875858783722, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99702454, -0.0223999 , 0.07357788]), + 'left_gaze_origin': array([-3.78288436, 2.79010034, -0.20401308]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0957794189453125, + 'left_pupil_posn': array([ 0.31275237, -0.39113843]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99583435, -0.0302124 , 0.08589172]), + 'right_gaze_origin': array([-4.09045601, -2.82227778, -0.13794862]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.944061279296875, + 'right_pupil_posn': array([-0.27026099, -0.45344579]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.5066166780889, + 'timestamp_carla': 691509, + 'timestamp_device': 3844937, + 'timestamp_stream': 691.5066166780889, + 'transform': [array([4.28096342e+00, 1.27794991e+01, 1.80877687e-03]), + array([ -0.06077502, -11.90297508, 0.02224272])]} +{'AngularVelocity': array([5.52953593e-02, 2.86481054e-06, 3.93998551e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.817657470703125, + 'FR_Wheel_Angle': -20.304956436157227, + 'Location': array([ -3.97037649, -22.67234612, 0.1737085 ]), + 'Rotation': array([-7.07334355e-02, -2.59191971e+01, 2.00792886e-02]), + 'Velocity': array([-0.36359951, 0.30606028, 0.00096484]), + 'brake_input': 0.0, + 'camera_location': array([-5.40838528, 17.85947418, 0.08320194]), + 'camera_rotation': array([-5.957407 , 7.36007404, -0.31674027]), + 'current_gear_input': False, + 'focus_actor_dist': 3782.0341796875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 23.85223389, -5331.48974609, 51.34745026]), + 'frame': 21387, + 'frame_number': 21387, + 'framesequence': 81863, + 'gaze_dir': array([ 0.99459839, -0.02796173, 0.09941101]), + 'gaze_origin': array([-3.90613413, -0.01263199, -0.18101807]), + 'gaze_valid': True, + 'gaze_vergence': 287.9092712402344, + 'handbrake_input': False, + 'left_eye_openness': 0.6366598606109619, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99499512, -0.01835632, 0.09820557]), + 'left_gaze_origin': array([-3.77215004, 2.79237533, -0.2113144 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1200408935546875, + 'left_pupil_posn': array([ 0.30801725, -0.3885715 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99420166, -0.03756714, 0.10061646]), + 'right_gaze_origin': array([-4.04011869, -2.81763935, -0.15072176]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9860992431640625, + 'right_pupil_posn': array([-0.27160203, -0.44157028]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.536403875798, + 'timestamp_carla': 691538, + 'timestamp_device': 3844970, + 'timestamp_stream': 691.536403875798, + 'transform': [array([4.27754307e+00, 1.27686567e+01, 1.33710855e-03]), + array([ -0.06066574, -11.89686775, 0.02307048])]} +{'AngularVelocity': array([0.0150835 , 0.06436843, 4.67472124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.83720588684082, + 'FR_Wheel_Angle': -21.023189544677734, + 'Location': array([ -4.06243229, -22.60417938, 0.17389812]), + 'Rotation': array([-7.52208680e-02, -2.50044022e+01, 1.94971897e-02]), + 'Velocity': array([-0.47422755, 0.37196952, 0.00055187]), + 'brake_input': 0.0, + 'camera_location': array([-5.34759521, 17.88511848, 0.03915006]), + 'camera_rotation': array([-6.04477167, 7.46817303, -0.21376643]), + 'current_gear_input': False, + 'focus_actor_dist': 3779.67919921875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 19.48512268, -5331.48974609, 117.6490097 ]), + 'frame': 21388, + 'frame_number': 21388, + 'framesequence': 81866, + 'gaze_dir': array([ 0.99477386, -0.03159332, 0.09580231]), + 'gaze_origin': array([-3.91343021, -0.00961685, -0.17926636]), + 'gaze_valid': True, + 'gaze_vergence': 173.9340057373047, + 'handbrake_input': False, + 'left_eye_openness': 0.7392418384552002, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99571228, -0.0171051 , 0.09082031]), + 'left_gaze_origin': array([-3.7478168 , 2.79463506, -0.22097626]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.235260009765625, + 'left_pupil_posn': array([ 0.30275393, -0.39032316]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99383545, -0.04608154, 0.1007843 ]), + 'right_gaze_origin': array([-4.07904387, -2.81386876, -0.13755646]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9218292236328125, + 'right_pupil_posn': array([-0.27426195, -0.44377661]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.5669770762324, + 'timestamp_carla': 691569, + 'timestamp_device': 3844995, + 'timestamp_stream': 691.5669770762324, + 'transform': [array([4.27571201e+00, 1.27567406e+01, 1.04953768e-03]), + array([ -0.06056328, -11.89400005, 0.02371106])]} +{'AngularVelocity': array([ 0.03628886, -0.03870489, 5.56336021]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.12652587890625, + 'FR_Wheel_Angle': -21.838090896606445, + 'Location': array([ -4.1731205 , -22.5228672 , 0.17402346]), + 'Rotation': array([-7.32742622e-02, -2.38647270e+01, 2.03765351e-02]), + 'Velocity': array([-4.73457545e-01, 3.90608907e-01, 3.60698701e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.29139709e+00, 1.79082031e+01, 1.40037397e-02]), + 'camera_rotation': array([-6.11135244, 7.54521227, -0.26966128]), + 'current_gear_input': False, + 'focus_actor_dist': 3778.238525390625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 13.86418152, -5331.48974609, 98.4261322 ]), + 'frame': 21389, + 'frame_number': 21389, + 'framesequence': 81870, + 'gaze_dir': array([ 0.99436951, -0.02958679, 0.10126495]), + 'gaze_origin': array([-3.88179636e+00, -3.72924795e-03, -1.83564007e-01]), + 'gaze_valid': True, + 'gaze_vergence': 289.5934143066406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99493408, -0.02090454, 0.0982666 ]), + 'left_gaze_origin': array([-3.7515049 , 2.80197001, -0.21206057]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.134521484375, + 'left_pupil_posn': array([ 0.30010509, -0.3828963 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99380493, -0.03826904, 0.10426331]), + 'right_gaze_origin': array([-4.0120883 , -2.80942869, -0.15506746]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.99969482421875, + 'right_pupil_posn': array([-0.27851218, -0.43826723]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.6016619764268, + 'timestamp_carla': 691604, + 'timestamp_device': 3845029, + 'timestamp_stream': 691.6016619764268, + 'transform': [array([4.27202034e+00, 1.27420177e+01, 3.18889623e-04]), + array([ -0.06024227, -11.8876152 , 0.02513783])]} +{'AngularVelocity': array([-0.01535167, -0.01414533, 6.57823515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.98292350769043, + 'FR_Wheel_Angle': -22.37963104248047, + 'Location': array([ -4.27757311, -22.44846535, 0.17409396]), + 'Rotation': array([-7.23248720e-02, -2.27583447e+01, 2.14424301e-02]), + 'Velocity': array([-5.01137078e-01, 3.90786797e-01, -9.69791363e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.2287674 , 17.95830345, -0.09570738]), + 'camera_rotation': array([-6.24684286, 7.5801096 , -0.21424437]), + 'current_gear_input': False, + 'focus_actor_dist': 3777.637939453125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 26.22389221, -5331.48925781, 114.65100861]), + 'frame': 21390, + 'frame_number': 21390, + 'framesequence': 81874, + 'gaze_dir': array([ 0.99341583, -0.03311157, 0.10881042]), + 'gaze_origin': array([-3.89458942e+00, -1.37481699e-03, -1.75180063e-01]), + 'gaze_valid': True, + 'gaze_vergence': 218.7924041748047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9937439 , -0.02035522, 0.10971069]), + 'left_gaze_origin': array([-3.75295877, 2.80416727, -0.20885621]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.238372802734375, + 'left_pupil_posn': array([ 0.29569864, -0.37981319]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99308777, -0.04586792, 0.10791016]), + 'right_gaze_origin': array([-4.03622007, -2.80691695, -0.14150392]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.093170166015625, + 'right_pupil_posn': array([-0.28012604, -0.42952108]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.6357006765902, + 'timestamp_carla': 691638, + 'timestamp_device': 3845062, + 'timestamp_stream': 691.6357006765902, + 'transform': [array([ 4.27041054e+00, 1.27264357e+01, -8.95881603e-05]), + array([ -0.06011932, -11.88542843, 0.02595 ])]} +{'AngularVelocity': array([ 0.05881799, -0.01971039, 6.45364285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.065109252929688, + 'FR_Wheel_Angle': -22.364065170288086, + 'Location': array([ -4.39880323, -22.36495972, 0.17429042]), + 'Rotation': array([-7.36021176e-02, -2.14759121e+01, 1.92430746e-02]), + 'Velocity': array([-0.55834073, 0.42722315, 0.00096303]), + 'brake_input': 0.0, + 'camera_location': array([-5.22414398, 17.94638062, -0.09955957]), + 'camera_rotation': array([-6.38624001, 7.66564226, -0.1415996 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3775.2939453125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 15.77049255, -5331.48974609, 134.52633667]), + 'frame': 21391, + 'frame_number': 21391, + 'framesequence': 81878, + 'gaze_dir': array([ 0.99339294, -0.03379822, 0.10877991]), + 'gaze_origin': array([-3.89584446e+00, -1.18865969e-03, -1.75046548e-01]), + 'gaze_valid': True, + 'gaze_vergence': 208.05433654785156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99406433, -0.02058411, 0.10681152]), + 'left_gaze_origin': array([-3.7490356 , 2.80394602, -0.21059725]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.338348388671875, + 'left_pupil_posn': array([ 0.29544401, -0.37944591]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99272156, -0.04701233, 0.11074829]), + 'right_gaze_origin': array([-4.04265308, -2.80632329, -0.13949586]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.089691162109375, + 'right_pupil_posn': array([-0.28072745, -0.43061936]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.6683030761778, + 'timestamp_carla': 691670, + 'timestamp_device': 3845095, + 'timestamp_stream': 691.6683030761778, + 'transform': [array([ 4.26968050e+00, 1.27102537e+01, -5.09433739e-04]), + array([ -0.05998272, -11.88503361, 0.02680518])]} +{'AngularVelocity': array([ 0.05610022, -0.02190286, 7.17912102]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.015663146972656, + 'FR_Wheel_Angle': -22.32894515991211, + 'Location': array([ -4.52176428, -22.28445053, 0.17443824]), + 'Rotation': array([-7.57467970e-02, -2.01912479e+01, 1.74250547e-02]), + 'Velocity': array([-0.64057875, 0.4651219 , 0.00079831]), + 'brake_input': 0.0, + 'camera_location': array([-5.19862556, 17.9579525 , -0.08554177]), + 'camera_rotation': array([-6.41093826, 7.71554613, -0.15795366]), + 'current_gear_input': False, + 'focus_actor_dist': 3773.960205078125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 19.29879761, -5331.48974609, 125.45440674]), + 'frame': 21392, + 'frame_number': 21392, + 'framesequence': 81882, + 'gaze_dir': array([ 0.99285126, -0.03105927, 0.11417389]), + 'gaze_origin': array([-3.86657500e+00, 1.70059211e-03, -1.83213055e-01]), + 'gaze_valid': True, + 'gaze_vergence': 179.17721557617188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99279785, -0.01678467, 0.11849976]), + 'left_gaze_origin': array([-3.72129083, 2.80609012, -0.21777956]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.37066650390625, + 'left_pupil_posn': array([ 0.2939502 , -0.37876403]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99290466, -0.04533386, 0.10984802]), + 'right_gaze_origin': array([-4.01185942, -2.80268884, -0.14864656]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.142120361328125, + 'right_pupil_posn': array([-0.28170669, -0.42600405]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.18252842128276825, + 'timestamp': 691.701112177223, + 'timestamp_carla': 691703, + 'timestamp_device': 3845129, + 'timestamp_stream': 691.701112177223, + 'transform': [array([ 4.26906872e+00, 1.26928854e+01, -8.90884374e-04]), + array([ -0.05981196, -11.88493443, 0.02757363])]} +{'AngularVelocity': array([ 0.07151151, -0.01292957, 8.13005543]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.95582389831543, + 'FR_Wheel_Angle': -22.285070419311523, + 'Location': array([ -4.68500948, -22.18363571, 0.1746072 ]), + 'Rotation': array([-7.67781511e-02, -1.85227699e+01, 1.62486844e-02]), + 'Velocity': array([-7.48619378e-01, 5.07383704e-01, 7.29074469e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.17807579, 17.96162033, -0.09088323]), + 'camera_rotation': array([-6.43640089, 7.74126673, -0.18785499]), + 'current_gear_input': False, + 'focus_actor_dist': 3773.212158203125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 32.67549133, -5331.48925781, 144.32426453]), + 'frame': 21393, + 'frame_number': 21393, + 'framesequence': 81887, + 'gaze_dir': array([ 0.99330902, -0.0305481 , 0.11064148]), + 'gaze_origin': array([-3.86437106e+00, 2.17742939e-03, -1.83245853e-01]), + 'gaze_valid': True, + 'gaze_vergence': 220.21986389160156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99331665, -0.01873779, 0.11387634]), + 'left_gaze_origin': array([-3.73740077, 2.80642414, -0.21198732]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.41644287109375, + 'left_pupil_posn': array([ 0.29520583, -0.37926757]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99330139, -0.0423584 , 0.10740662]), + 'right_gaze_origin': array([-3.99134088, -2.80206919, -0.1545044 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1461181640625, + 'right_pupil_posn': array([-0.28283042, -0.42741513]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1904631108045578, + 'timestamp': 691.7350305765867, + 'timestamp_carla': 691737, + 'timestamp_device': 3845170, + 'timestamp_stream': 691.7350305765867, + 'transform': [array([ 4.26916218e+00, 1.26738024e+01, -1.18423463e-03]), + array([ -0.05970268, -11.88634586, 0.02814986])]} +{'AngularVelocity': array([ 0.0478007 , -0.01621706, 9.61185265]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.862266540527344, + 'FR_Wheel_Angle': -22.224416732788086, + 'Location': array([ -4.88553476, -22.06884003, 0.17484367]), + 'Rotation': array([-8.03844929e-02, -1.65298347e+01, 1.31962486e-02]), + 'Velocity': array([-0.93385839, 0.58271921, 0.00118098]), + 'brake_input': 0.0, + 'camera_location': array([-5.16184235, 17.94844437, -0.08319384]), + 'camera_rotation': array([-6.42983055, 7.70075274, -0.32717422]), + 'current_gear_input': False, + 'focus_actor_dist': 3771.682373046875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 35.94104004, -5331.49023438, 129.20098877]), + 'frame': 21394, + 'frame_number': 21394, + 'framesequence': 81891, + 'gaze_dir': array([ 0.99253845, -0.03222656, 0.11679077]), + 'gaze_origin': array([-3.84717131e+00, 1.29089353e-03, -1.91361248e-01]), + 'gaze_valid': True, + 'gaze_vergence': 215.4740447998047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99317932, -0.01947021, 0.11488342]), + 'left_gaze_origin': array([-3.69510055, 2.80489516, -0.23062593]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.412872314453125, + 'left_pupil_posn': array([ 0.29446518, -0.37904894]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99189758, -0.04498291, 0.11869812]), + 'right_gaze_origin': array([-3.99924183, -2.80231333, -0.15209655]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.164459228515625, + 'right_pupil_posn': array([-0.2829783 , -0.42711115]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.19839780032634735, + 'timestamp': 691.7685441784561, + 'timestamp_carla': 691771, + 'timestamp_device': 3845204, + 'timestamp_stream': 691.7685441784561, + 'transform': [array([ 4.26906681e+00, 1.26541376e+01, -1.33045192e-03]), + array([ -0.05966853, -11.88741207, 0.0284492 ])]} +{'AngularVelocity': array([-0.04528613, -0.02063313, 11.66205311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.727807998657227, + 'FR_Wheel_Angle': -22.142738342285156, + 'Location': array([ -5.12104654, -21.94606972, 0.17515892]), + 'Rotation': array([-8.53841901e-02, -1.42599058e+01, 1.03233289e-02]), + 'Velocity': array([-1.20601976e+00, 6.75672352e-01, 9.13572265e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.16060543, 17.92283058, -0.08433395]), + 'camera_rotation': array([-6.4877367 , 7.59392357, -0.52218014]), + 'current_gear_input': False, + 'focus_actor_dist': 3769.082275390625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 25.49815369, -5331.49023438, 152.72241211]), + 'frame': 21395, + 'frame_number': 21395, + 'framesequence': 81894, + 'gaze_dir': array([ 0.99295807, -0.02973938, 0.11423492]), + 'gaze_origin': array([-3.86565471e+00, 9.33837960e-04, -1.83592230e-01]), + 'gaze_valid': True, + 'gaze_vergence': 294.0293884277344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99327087, -0.02020264, 0.11402893]), + 'left_gaze_origin': array([-3.72133803, 2.80478072, -0.2188324 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3793487548828125, + 'left_pupil_posn': array([ 0.29717374, -0.37789392]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99264526, -0.03927612, 0.11444092]), + 'right_gaze_origin': array([-4.00997162, -2.80291319, -0.14835206]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1605072021484375, + 'right_pupil_posn': array([-0.28287536, -0.42711115]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.20236514508724213, + 'timestamp': 691.8017277792096, + 'timestamp_carla': 691804, + 'timestamp_device': 3845229, + 'timestamp_stream': 691.8017277792096, + 'transform': [array([ 4.26876211e+00, 1.26337500e+01, -1.49316783e-03]), + array([ -0.05964121, -11.88814259, 0.02878611])]} +{'AngularVelocity': array([-0.04040305, -0.02243381, 12.5090847 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.551050186157227, + 'FR_Wheel_Angle': -21.95387840270996, + 'Location': array([ -5.34974432, -21.83755493, 0.17536651]), + 'Rotation': array([ -0.08114947, -12.09990311, 0.01431532]), + 'Velocity': array([-1.32348752e+00, 6.77478194e-01, 1.29475119e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.16387939, 17.87784767, -0.11764959]), + 'camera_rotation': array([-6.64032316, 7.43459749, -0.63887924]), + 'current_gear_input': False, + 'focus_actor_dist': 3767.158447265625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 26.14833069, -5331.48974609, 138.85795593]), + 'frame': 21396, + 'frame_number': 21396, + 'framesequence': 81899, + 'gaze_dir': array([ 0.9925766 , -0.02767944, 0.11763 ]), + 'gaze_origin': array([-3.86755919e+00, 1.02996833e-04, -1.80889145e-01]), + 'gaze_valid': True, + 'gaze_vergence': 205.20223999023438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99241638, -0.01554871, 0.12185669]), + 'left_gaze_origin': array([-3.73563242, 2.80430317, -0.21109925]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.338714599609375, + 'left_pupil_posn': array([ 0.29755247, -0.37575376]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99273682, -0.03981018, 0.11340332]), + 'right_gaze_origin': array([-3.99948573, -2.80409718, -0.15067902]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1580352783203125, + 'right_pupil_posn': array([-0.28002489, -0.42337561]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.21031509339809418, + 'timestamp': 691.8389921784401, + 'timestamp_carla': 691841, + 'timestamp_device': 3845270, + 'timestamp_stream': 691.8389921784401, + 'transform': [array([ 4.26853132e+00, 1.26097603e+01, -1.61170959e-03]), + array([ -0.05963438, -11.88924217, 0.02896986])]} +{'AngularVelocity': array([-0.10935361, -0.07654762, 11.37811852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.720245361328125, + 'FR_Wheel_Angle': -19.822019577026367, + 'Location': array([ -5.62713289, -21.72208214, 0.17562027]), + 'Rotation': array([-0.07501596, -9.62730122, 0.02371971]), + 'Velocity': array([-1.35229433e+00, 5.85070431e-01, 1.27550121e-03]), + 'brake_input': 0.0, + 'camera_location': array([-5.16180229, 17.82623482, -0.15232469]), + 'camera_rotation': array([-6.7919054 , 7.20184088, -0.70957142]), + 'current_gear_input': False, + 'focus_actor_dist': 3764.876220703125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 22.12405396, -5331.48925781, 141.55258179]), + 'frame': 21397, + 'frame_number': 21397, + 'framesequence': 81903, + 'gaze_dir': array([ 0.9930191 , -0.02457428, 0.11433411]), + 'gaze_origin': array([-3.88961816e+00, 9.72747861e-04, -1.71297461e-01]), + 'gaze_valid': True, + 'gaze_vergence': 152.30616760253906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99230957, -0.01275635, 0.12304688]), + 'left_gaze_origin': array([-3.78647923, 2.80604267, -0.1900879 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.337066650390625, + 'left_pupil_posn': array([ 0.29859376, -0.37486541]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99372864, -0.03639221, 0.10562134]), + 'right_gaze_origin': array([-3.99275684, -2.80409718, -0.15250702]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1512908935546875, + 'right_pupil_posn': array([-0.27889878, -0.42277002]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2222171425819397, + 'timestamp': 691.8750427775085, + 'timestamp_carla': 691877, + 'timestamp_device': 3845304, + 'timestamp_stream': 691.8750427775085, + 'transform': [array([ 4.26688576e+00, 1.25860834e+01, -1.53205870e-03]), + array([ -0.05964121, -11.8875103 , 0.0288203 ])]} +{'AngularVelocity': array([-8.17589113e-04, -5.40485643e-02, 7.23758650e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.641008377075195, + 'FR_Wheel_Angle': -17.830129623413086, + 'Location': array([ -5.88005733, -21.63528252, 0.17572479]), + 'Rotation': array([-0.05649249, -7.69770145, 0.03516884]), + 'Velocity': array([-1.02130580e+00, 3.61654460e-01, 2.30436315e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.16584969, 17.73568153, -0.15807103]), + 'camera_rotation': array([-6.82698536, 6.87905645, -0.77801204]), + 'current_gear_input': False, + 'focus_actor_dist': 3762.253662109375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 17.74992371, -5331.48974609, 119.09933472]), + 'frame': 21398, + 'frame_number': 21398, + 'framesequence': 81907, + 'gaze_dir': array([ 0.99201202, -0.01631165, 0.12392426]), + 'gaze_origin': array([-3.86837649e+00, -1.20544434e-03, -1.81089029e-01]), + 'gaze_valid': True, + 'gaze_vergence': 162.01397705078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 9.91653442e-01, -5.95092773e-04, 1.28799438e-01]), + 'left_gaze_origin': array([-3.73443317, 2.80426025, -0.21141511]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.366485595703125, + 'left_pupil_posn': array([ 0.30044246, -0.37364531]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99237061, -0.0320282 , 0.11904907]), + 'right_gaze_origin': array([-4.00231981, -2.80667138, -0.15076295]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1576995849609375, + 'right_pupil_posn': array([-0.27232933, -0.42143512]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.23411917686462402, + 'timestamp': 691.9078053757548, + 'timestamp_carla': 691910, + 'timestamp_device': 3845337, + 'timestamp_stream': 691.9078053757548, + 'transform': [array([ 4.26614857e+00, 1.25636177e+01, -1.49963377e-03]), + array([ -0.05964121, -11.8875103 , 0.0288203 ])]} +{'AngularVelocity': array([ 3.81734967e-02, -4.93123708e-03, 5.13824940e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.666601181030273, + 'FR_Wheel_Angle': -17.312091827392578, + 'Location': array([ -6.04405308, -21.58708 , 0.1758641 ]), + 'Rotation': array([-0.05236706, -6.58234119, 0.02994318]), + 'Velocity': array([-7.65483856e-01, 2.45579004e-01, 1.45177837e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.16937351, 17.63140869, -0.15412709]), + 'camera_rotation': array([-6.89731598, 6.46762276, -0.74512827]), + 'current_gear_input': False, + 'focus_actor_dist': 3760.482666015625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 26.50448608, -5331.48974609, 153.33096313]), + 'frame': 21399, + 'frame_number': 21399, + 'framesequence': 81911, + 'gaze_dir': array([ 0.99082947, -0.00279999, 0.13407135]), + 'gaze_origin': array([-3.79371643e+00, 1.90353405e-03, -2.09310159e-01]), + 'gaze_valid': True, + 'gaze_vergence': 153.1095428466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98985291, 0.01135254, 0.1415863 ]), + 'left_gaze_origin': array([-3.69808531, 2.80638289, -0.22707826]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.33709716796875, + 'left_pupil_posn': array([ 0.30376124, -0.37400424]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99180603, -0.01695251, 0.1265564 ]), + 'right_gaze_origin': array([-3.88934803, -2.80257583, -0.19154206]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1690216064453125, + 'right_pupil_posn': array([-0.27021623, -0.4211446 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.24602121114730835, + 'timestamp': 691.9429282769561, + 'timestamp_carla': 691945, + 'timestamp_device': 3845370, + 'timestamp_stream': 691.9429282769561, + 'transform': [array([ 4.26765013e+00, 1.25376406e+01, -1.74789422e-03]), + array([ -0.05954559, -11.89217472, 0.02931689])]} +{'AngularVelocity': array([0.03001451, 0.01343346, 3.66320276]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.71488380432129, + 'FR_Wheel_Angle': -17.365245819091797, + 'Location': array([ -6.17995882, -21.55017281, 0.17606613]), + 'Rotation': array([-0.05462785, -5.67563248, 0.02272435]), + 'Velocity': array([-0.54717851, 0.16595517, 0.00083053]), + 'brake_input': 0.0, + 'camera_location': array([-5.1536684 , 17.46333885, -0.15227671]), + 'camera_rotation': array([-6.98502922, 5.82516432, -0.83044875]), + 'current_gear_input': False, + 'focus_actor_dist': 3760.212646484375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 49.87960815, -5331.48974609, 187.77392578]), + 'frame': 21400, + 'frame_number': 21400, + 'framesequence': 81915, + 'gaze_dir': array([9.91928101e-01, 8.62121582e-04, 1.25968933e-01]), + 'gaze_origin': array([-3.86621094e+00, -1.43280043e-03, -1.85463727e-01]), + 'gaze_valid': True, + 'gaze_vergence': 199.4728240966797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9921875 , 0.01463318, 0.12384033]), + 'left_gaze_origin': array([-3.72770739, 2.80415511, -0.22279969]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.326568603515625, + 'left_pupil_posn': array([ 0.30766082, -0.37729251]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9916687 , -0.01290894, 0.12809753]), + 'right_gaze_origin': array([-4.00471497, -2.80702066, -0.14812775]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1273345947265625, + 'right_pupil_posn': array([-0.26625389, -0.42192566]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2658579349517822, + 'timestamp': 691.9742434769869, + 'timestamp_carla': 691976, + 'timestamp_device': 3845404, + 'timestamp_stream': 691.9742434769869, + 'transform': [array([ 4.26785231e+00, 1.25137329e+01, -1.90694805e-03]), + array([ -0.05948411, -11.89412498, 0.02969451])]} +{'AngularVelocity': array([0.01969285, 0.01504452, 2.60442376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.90015411376953, + 'FR_Wheel_Angle': -17.49580192565918, + 'Location': array([ -6.27891207, -21.52467728, 0.17615962]), + 'Rotation': array([-0.0583503 , -5.01404095, 0.01774793]), + 'Velocity': array([-0.38683701, 0.1130548 , 0.00059942]), + 'brake_input': 0.0, + 'camera_location': array([-5.10873604, 17.24231339, -0.16183978]), + 'camera_rotation': array([-6.99059582, 4.78123713, -0.95835626]), + 'current_gear_input': False, + 'focus_actor_dist': 3755.30224609375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 20.3853302 , -5331.49023438, 151.52983093]), + 'frame': 21401, + 'frame_number': 21401, + 'framesequence': 81919, + 'gaze_dir': array([0.99239349, 0.01084137, 0.12135315]), + 'gaze_origin': array([-3.83543038, -0.01422501, -0.19821396]), + 'gaze_valid': True, + 'gaze_vergence': 139.07192993164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99118042, 0.02580261, 0.12994385]), + 'left_gaze_origin': array([-3.72619176, 2.7914536 , -0.22602235]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.260650634765625, + 'left_pupil_posn': array([ 0.32043362, -0.38500178]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99360657, -0.00411987, 0.11276245]), + 'right_gaze_origin': array([-3.94466901, -2.81990385, -0.17040558]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1106109619140625, + 'right_pupil_posn': array([-0.25208563, -0.42238307]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2737926244735718, + 'timestamp': 692.0080464780331, + 'timestamp_carla': 692010, + 'timestamp_device': 3845437, + 'timestamp_stream': 692.0080464780331, + 'transform': [array([ 4.26696825e+00, 1.24869947e+01, -2.11645127e-03]), + array([ -0.05942264, -11.89412498, 0.0301186 ])]} +{'AngularVelocity': array([0.01260085, 0.01220207, 1.82702124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.976625442504883, + 'FR_Wheel_Angle': -17.599130630493164, + 'Location': array([ -6.35049915, -21.50693512, 0.17624679]), + 'Rotation': array([-0.06161513, -4.53363276, 0.0145448 ]), + 'Velocity': array([-0.27048737, 0.07675982, 0.00040939]), + 'brake_input': 0.0, + 'camera_location': array([-5.04436779, 16.95769882, -0.17916803]), + 'camera_rotation': array([-6.94089937, 3.35499334, -0.96563405]), + 'current_gear_input': False, + 'focus_actor_dist': 3750.80322265625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ -11.91293335, -5331.49023438, 134.39785767]), + 'frame': 21402, + 'frame_number': 21402, + 'framesequence': 81923, + 'gaze_dir': array([0.9953537 , 0.05564117, 0.07562256]), + 'gaze_origin': array([-3.82038999, -0.04281159, -0.23096925]), + 'gaze_valid': True, + 'gaze_vergence': 81.81224060058594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99595642, 0.06777954, 0.05871582]), + 'left_gaze_origin': array([-3.57756066, 2.75692749, -0.31066591]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.49481201171875, + 'left_pupil_posn': array([ 0.36133575, -0.42158628]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99475098, 0.04350281, 0.0925293 ]), + 'right_gaze_origin': array([-4.06321907, -2.84255075, -0.15127259]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0785675048828125, + 'right_pupil_posn': array([-0.22048402, -0.46340632]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.27775996923446655, + 'timestamp': 692.0397624783218, + 'timestamp_carla': 692042, + 'timestamp_device': 3845470, + 'timestamp_stream': 692.0397624783218, + 'transform': [array([ 4.26576328e+00, 1.24605141e+01, -2.57896422e-03]), + array([ -0.05925189, -11.89345932, 0.03106738])]} +{'AngularVelocity': array([0.00976257, 0.00959678, 1.34360838]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.19297218322754, + 'FR_Wheel_Angle': -18.491640090942383, + 'Location': array([ -6.40066004, -21.49467659, 0.17626193]), + 'Rotation': array([-0.06412181, -4.18847752, 0.01222657]), + 'Velocity': array([-0.18830977, 0.05439066, -0.00108559]), + 'brake_input': 0.0, + 'camera_location': array([-4.98019314, 16.65169144, -0.18086493]), + 'camera_rotation': array([-6.99679089, 1.66697192, -1.24994278]), + 'current_gear_input': False, + 'focus_actor_dist': 2661.314453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -21.94332886, -4240.23632812, 16.76773071]), + 'frame': 21403, + 'frame_number': 21403, + 'framesequence': 81927, + 'gaze_dir': array([0.98171997, 0.18010712, 0.0537796 ]), + 'gaze_origin': array([-3.85451698, -0.14780122, -0.24765092]), + 'gaze_valid': True, + 'gaze_vergence': 23.816692352294922, + 'handbrake_input': False, + 'left_eye_openness': 0.7280896902084351, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98202515, 0.18699646, 0.02511597]), + 'left_gaze_origin': array([-3.7154634 , 2.63602161, -0.29953462]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.616180419921875, + 'left_pupil_posn': array([ 0.51128829, -0.45693827]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98141479, 0.17321777, 0.08244324]), + 'right_gaze_origin': array([-3.99357009, -2.93162394, -0.19576722]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.050750732421875, + 'right_pupil_posn': array([-0.10921204, -0.49596465]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.27775996923446655, + 'timestamp': 692.0755016766489, + 'timestamp_carla': 692078, + 'timestamp_device': 3845504, + 'timestamp_stream': 692.0755016766489, + 'transform': [array([ 4.26384306e+00, 1.24291725e+01, -3.05110915e-03]), + array([ -0.05915627, -11.89174747, 0.03196582])]} +{'AngularVelocity': array([0.07897481, 0.00872673, 1.14174974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.86968231201172, + 'FR_Wheel_Angle': -19.716703414916992, + 'Location': array([ -6.42782021, -21.4877491 , 0.17633785]), + 'Rotation': array([-0.06438819, -3.9906013 , 0.01151428]), + 'Velocity': array([-0.10211691, 0.03914202, 0.00026513]), + 'brake_input': 0.0, + 'camera_location': array([-4.9244976 , 16.32648087, -0.1862634 ]), + 'camera_rotation': array([-7.01547146, -0.09627065, -1.30352581]), + 'current_gear_input': False, + 'focus_actor_dist': 1887.3665771484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 95.79272461, -3447.18041992, 16.65150452]), + 'frame': 21404, + 'frame_number': 21404, + 'framesequence': 81931, + 'gaze_dir': array([0.97910309, 0.19941711, 0.03794861]), + 'gaze_origin': array([-3.85701251, -0.1724312 , -0.24416354]), + 'gaze_valid': True, + 'gaze_vergence': 103.07857513427734, + 'handbrake_input': False, + 'left_eye_openness': 0.6531839966773987, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9785614 , 0.20405579, 0.02758789]), + 'left_gaze_origin': array([-3.71636081, 2.61343551, -0.28952026]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.536346435546875, + 'left_pupil_posn': array([ 0.53839171, -0.46368146]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97964478, 0.19477844, 0.04830933]), + 'right_gaze_origin': array([-3.99766421, -2.95829797, -0.19880678]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9504241943359375, + 'right_pupil_posn': array([-0.08265424, -0.49864018]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.27775996923446655, + 'timestamp': 692.1082540787756, + 'timestamp_carla': 692110, + 'timestamp_device': 3845537, + 'timestamp_stream': 692.1082540787756, + 'transform': [array([ 4.26295900e+00, 1.23988752e+01, -3.33410245e-03]), + array([ -0.05899917, -11.89196682, 0.03256141])]} +{'AngularVelocity': array([-0.07242762, 0.00558492, 0.1790645 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.47229766845703, + 'FR_Wheel_Angle': -19.989303588867188, + 'Location': array([ -6.44982672, -21.48195457, 0.17638652]), + 'Rotation': array([-0.06811064, -3.82373047, 0.00975247]), + 'Velocity': array([-0.07272817, 0.01432897, 0.00024336]), + 'brake_input': 0.0, + 'camera_location': array([-4.86727905, 16.06789207, -0.15455371]), + 'camera_rotation': array([-6.88621664, -1.46777785, -1.20232928]), + 'current_gear_input': False, + 'focus_actor_dist': 1518.5455322265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 14.80316162, -3089.12719727, 16.73693848]), + 'frame': 21405, + 'frame_number': 21405, + 'framesequence': 81935, + 'gaze_dir': array([0.97329712, 0.22718048, 0.03038025]), + 'gaze_origin': array([-3.86376333, -0.19697878, -0.25101548]), + 'gaze_valid': True, + 'gaze_vergence': 122.92724609375, + 'handbrake_input': False, + 'left_eye_openness': 0.6407020092010498, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97521973, 0.22027588, 0.02041626]), + 'left_gaze_origin': array([-3.72481728, 2.58869338, -0.29605561]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.574920654296875, + 'left_pupil_posn': array([ 0.57724142, -0.4777019 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97137451, 0.23408508, 0.04034424]), + 'right_gaze_origin': array([-4.00270987, -2.982651 , -0.20597535]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0566558837890625, + 'right_pupil_posn': array([-0.05844629, -0.50898969]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.27775996923446655, + 'timestamp': 692.1417676769197, + 'timestamp_carla': 692144, + 'timestamp_device': 3845570, + 'timestamp_stream': 692.1417676769197, + 'transform': [array([ 4.26180983e+00, 1.23663483e+01, -3.67727270e-03]), + array([ -0.05884891, -11.89180946, 0.03325661])]} +{'AngularVelocity': array([-0.07156168, 0.00307143, 0.03285438]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.549367904663086, + 'FR_Wheel_Angle': -20.02490997314453, + 'Location': array([ -6.46454954, -21.47807884, 0.17640266]), + 'Rotation': array([-0.06872536, -3.70935082, 0.00946228]), + 'Velocity': array([-5.32401949e-02, 8.05781316e-03, 8.56304177e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.82236481, 15.95222855, -0.11584356]), + 'camera_rotation': array([-6.71324921, -1.9687891 , -1.29009545]), + 'current_gear_input': False, + 'focus_actor_dist': 1437.288818359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 7.95379639, -3010.62451172, 16.74447632]), + 'frame': 21406, + 'frame_number': 21406, + 'framesequence': 81939, + 'gaze_dir': array([0.97451782, 0.22223663, 0.02948761]), + 'gaze_origin': array([-3.86498356, -0.20306396, -0.25952607]), + 'gaze_valid': True, + 'gaze_vergence': 205.9442138671875, + 'handbrake_input': False, + 'left_eye_openness': 0.6315039396286011, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97415161, 0.22453308, 0.02432251]), + 'left_gaze_origin': array([-3.72516513, 2.58326435, -0.30889893]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4839324951171875, + 'left_pupil_posn': array([ 0.57647753, -0.48950291]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97488403, 0.21994019, 0.03465271]), + 'right_gaze_origin': array([-4.00480223, -2.98939228, -0.21015322]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.137176513671875, + 'right_pupil_posn': array([-0.0517177 , -0.51124942]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.27775996923446655, + 'timestamp': 692.1742488779128, + 'timestamp_carla': 692176, + 'timestamp_device': 3845604, + 'timestamp_stream': 692.1742488779128, + 'transform': [array([ 4.26050472e+00, 1.23333273e+01, -3.99377802e-03]), + array([ -0.05871913, -11.89138603, 0.03391436])]} +{'AngularVelocity': array([0.0749156 , 0.00235457, 0.78011942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.5554141998291, + 'FR_Wheel_Angle': -20.02593994140625, + 'Location': array([ -6.47435999, -21.47546768, 0.17641136]), + 'Rotation': array([-0.06929909, -3.62875462, 0.00850017]), + 'Velocity': array([-0.0496544 , 0.0234621 , 0.00024025]), + 'brake_input': 0.0, + 'camera_location': array([-4.76325989, 15.91920471, -0.11461422]), + 'camera_rotation': array([-6.6553154 , -2.03257251, -1.40977621]), + 'current_gear_input': False, + 'focus_actor_dist': 1476.55029296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -5.76423645, -3056.06884766, 16.75827789]), + 'frame': 21407, + 'frame_number': 21407, + 'framesequence': 81943, + 'gaze_dir': array([0.9728775 , 0.22947693, 0.02287292]), + 'gaze_origin': array([-3.86480045, -0.20508575, -0.26642534]), + 'gaze_valid': True, + 'gaze_vergence': 94.82452392578125, + 'handbrake_input': False, + 'left_eye_openness': 0.6278784275054932, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97085571, 0.23944092, 0.00894165]), + 'left_gaze_origin': array([-3.72490835, 2.58108521, -0.31899261]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5735626220703125, + 'left_pupil_posn': array([ 0.57878697, -0.49676883]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97489929, 0.21951294, 0.0368042 ]), + 'right_gaze_origin': array([-4.00469208, -2.99125695, -0.21385804]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1946563720703125, + 'right_pupil_posn': array([-0.04502213, -0.52111995]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.24602121114730835, + 'timestamp': 692.2077635787427, + 'timestamp_carla': 692210, + 'timestamp_device': 3845637, + 'timestamp_stream': 692.2077635787427, + 'transform': [array([ 4.25919914e+00, 1.22977295e+01, -4.25901404e-03]), + array([ -0.05862351, -11.89110565, 0.03445208])]} +{'AngularVelocity': array([-0.06577323, 0.00305709, -0.0095112 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.553600311279297, + 'FR_Wheel_Angle': -20.02530860900879, + 'Location': array([ -6.48700857, -21.47229767, 0.17642742]), + 'Rotation': array([-0.06985917, -3.53210545, 0.00866877]), + 'Velocity': array([-0.04506513, 0.00554847, 0.00059584]), + 'brake_input': 0.0, + 'camera_location': array([-4.73178864, 15.95204544, -0.13711372]), + 'camera_rotation': array([-6.71180773, -1.71369421, -1.43187046]), + 'current_gear_input': False, + 'focus_actor_dist': 1392.8782958984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -10.01197815, -2975.05639648, 16.76313019]), + 'frame': 21408, + 'frame_number': 21408, + 'framesequence': 81947, + 'gaze_dir': array([0.972435 , 0.23233032, 0.01730347]), + 'gaze_origin': array([-3.86223745, -0.19441301, -0.25406495]), + 'gaze_valid': True, + 'gaze_vergence': 335.8604431152344, + 'handbrake_input': False, + 'left_eye_openness': 0.6258222460746765, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97428894, 0.22459412, 0.01696777]), + 'left_gaze_origin': array([-3.72295713, 2.59462905, -0.29897615]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5473175048828125, + 'left_pupil_posn': array([ 0.57548666, -0.48867381]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97058105, 0.24006653, 0.01763916]), + 'right_gaze_origin': array([-4.00151825, -2.98345494, -0.20915374]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16546630859375, + 'right_pupil_posn': array([-0.05640852, -0.51295459]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.22618448734283447, + 'timestamp': 692.2425197772682, + 'timestamp_carla': 692245, + 'timestamp_device': 3845670, + 'timestamp_stream': 692.2425197772682, + 'transform': [array([ 4.25779581e+00, 1.22593231e+01, -4.40114969e-03]), + array([ -0.0585757 , -11.8908453 , 0.03473452])]} +{'AngularVelocity': array([-0.07488433, 0.00037152, 0.05247229]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.547115325927734, + 'FR_Wheel_Angle': -20.020910263061523, + 'Location': array([ -6.49765539, -21.46964264, 0.17644325]), + 'Rotation': array([-0.07061733, -3.44534349, 0.00809688]), + 'Velocity': array([-5.79924919e-02, 8.78846738e-03, 3.67164603e-06]), + 'brake_input': 0.0, + 'camera_location': array([-4.73705292, 16.03172112, -0.18965745]), + 'camera_rotation': array([-6.99985075, -1.15770614, -1.38023376]), + 'current_gear_input': False, + 'focus_actor_dist': 1296.33251953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -14.72575378, -2881.14599609, 16.76853943]), + 'frame': 21409, + 'frame_number': 21409, + 'framesequence': 81951, + 'gaze_dir': array([0.97100067, 0.23441315, 0.0455246 ]), + 'gaze_origin': array([-3.86345768, -0.18891984, -0.25382847]), + 'gaze_valid': True, + 'gaze_vergence': 189.2454833984375, + 'handbrake_input': False, + 'left_eye_openness': 0.6819607019424438, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96954346, 0.24186707, 0.03823853]), + 'left_gaze_origin': array([-3.72419763, 2.60103774, -0.30533907]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5679779052734375, + 'left_pupil_posn': array([ 0.56399262, -0.4788568 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97245789, 0.22695923, 0.05281067]), + 'right_gaze_origin': array([-4.00271797, -2.97887731, -0.20231782]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1329345703125, + 'right_pupil_posn': array([-0.0527696 , -0.49982226]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.21428243815898895, + 'timestamp': 692.2741136774421, + 'timestamp_carla': 692276, + 'timestamp_device': 3845704, + 'timestamp_stream': 692.2741136774421, + 'transform': [array([ 4.25647974e+00, 1.22231035e+01, -4.48509213e-03]), + array([ -0.05853472, -11.89059162, 0.03495701])]} +{'AngularVelocity': array([-0.05431004, -0.03828261, 6.0794487 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.28175926208496, + 'FR_Wheel_Angle': -19.824453353881836, + 'Location': array([ -6.58326054, -21.44935417, 0.17667568]), + 'Rotation': array([-0.09603929, -2.78848267, -0.01031494]), + 'Velocity': array([-0.66264051, 0.19002205, 0.0008546 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.7249279 , 16.11715889, -0.25452006]), + 'camera_rotation': array([-7.28823471, -0.63514954, -1.29420495]), + 'current_gear_input': False, + 'focus_actor_dist': 1742.563720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 80.19624329, -3322.67822266, 16.6683197 ]), + 'frame': 21410, + 'frame_number': 21410, + 'framesequence': 81955, + 'gaze_dir': array([0.9927063 , 0.09672546, 0.06199646]), + 'gaze_origin': array([-3.72974491, -0.0975174 , -0.28607255]), + 'gaze_valid': True, + 'gaze_vergence': 58.542476654052734, + 'handbrake_input': False, + 'left_eye_openness': 0.7048017978668213, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99157715, 0.12387085, 0.0377655 ]), + 'left_gaze_origin': array([-3.4956758 , 2.70251012, -0.36421967]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3604736328125, + 'left_pupil_posn': array([ 0.41039503, -0.44587505]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99383545, 0.06958008, 0.08622742]), + 'right_gaze_origin': array([-3.96381402, -2.89754486, -0.20792542]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1802825927734375, + 'right_pupil_posn': array([-0.15876639, -0.49178588]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1904631108045578, + 'timestamp': 692.3062421791255, + 'timestamp_carla': 692308, + 'timestamp_device': 3845737, + 'timestamp_stream': 692.3062421791255, + 'transform': [array([ 4.25510693e+00, 1.21850939e+01, -4.46542725e-03]), + array([ -0.05854155, -11.89034653, 0.03495752])]} +{'AngularVelocity': array([-7.44956825e-03, -3.04473005e-03, 6.23633957e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.180587768554688, + 'FR_Wheel_Angle': -19.74042320251465, + 'Location': array([ -6.75755167, -21.41000366, 0.1767575 ]), + 'Rotation': array([-8.30619261e-02, -1.44653320e+00, 1.00059842e-03]), + 'Velocity': array([-0.81592566, 0.21005687, 0.00096236]), + 'brake_input': 0.0, + 'camera_location': array([-4.70579147, 16.19032097, -0.29045674]), + 'camera_rotation': array([-7.46991777, -0.20655137, -1.32812321]), + 'current_gear_input': False, + 'focus_actor_dist': 1888.89404296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -138.53196716, -3499.54003906, 16.89204407]), + 'frame': 21411, + 'frame_number': 21411, + 'framesequence': 81959, + 'gaze_dir': array([ 0.98151398, -0.17055511, 0.08194733]), + 'gaze_origin': array([-3.85664558, 0.1209549 , -0.2305893 ]), + 'gaze_valid': True, + 'gaze_vergence': 57.40507888793945, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98248291, -0.15394592, 0.10491943]), + 'left_gaze_origin': array([-3.71931005, 2.90917063, -0.24109955]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2245025634765625, + 'left_pupil_posn': array([ 0.1658839 , -0.41419816]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98054504, -0.18716431, 0.05897522]), + 'right_gaze_origin': array([-3.99398065, -2.66726089, -0.22007905]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3551788330078125, + 'right_pupil_posn': array([-0.44107157, -0.48456943]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.16269169747829437, + 'timestamp': 692.3422756791115, + 'timestamp_carla': 692344, + 'timestamp_device': 3845770, + 'timestamp_stream': 692.3422756791115, + 'transform': [array([ 4.25353193e+00, 1.21414032e+01, -4.21585096e-03]), + array([ -0.05863034, -11.8900795 , 0.03444681])]} +{'AngularVelocity': array([-0.00835904, 0.04917968, 7.88907194]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.244863510131836, + 'FR_Wheel_Angle': -18.70710563659668, + 'Location': array([ -6.98980951, -21.364254 , 0.17698176]), + 'Rotation': array([-0.08276822, 0.30441856, 0.00329838]), + 'Velocity': array([-1.10932541e+00, 2.43076220e-01, 1.00319856e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.70471764, 16.23044968, -0.30263093]), + 'camera_rotation': array([-7.58517742, -0.01051385, -1.38183939]), + 'current_gear_input': False, + 'focus_actor_dist': 1768.4205322265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -604.08319092, -3347.85253906, 46.17215729]), + 'frame': 21412, + 'frame_number': 21412, + 'framesequence': 81964, + 'gaze_dir': array([ 0.96367645, -0.25842285, 0.05898285]), + 'gaze_origin': array([-3.87620473, 0.19963838, -0.23485717]), + 'gaze_valid': True, + 'gaze_vergence': 30.392005920410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96492004, -0.24691772, 0.08917236]), + 'left_gaze_origin': array([-3.73543286, 2.98103642, -0.2478821 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.912567138671875, + 'left_pupil_posn': array([ 0.08233929, -0.43490362]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96243286, -0.26992798, 0.02879333]), + 'right_gaze_origin': array([-4.01697731, -2.58175969, -0.22183228]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.414459228515625, + 'right_pupil_posn': array([-0.54997003, -0.50278211]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.1269855797290802, + 'timestamp': 692.3770434781909, + 'timestamp_carla': 692379, + 'timestamp_device': 3845812, + 'timestamp_stream': 692.3770434781909, + 'transform': [array([ 4.25197792e+00, 1.20984163e+01, -3.80487437e-03]), + array([ -0.05877377, -11.88979626, 0.03366662])]} +{'AngularVelocity': array([-0.06092683, -0.1033438 , 5.93530416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.2037410736084, + 'FR_Wheel_Angle': -14.031449317932129, + 'Location': array([ -7.25701332, -21.32637596, 0.17719135]), + 'Rotation': array([-0.07205166, 2.06668162, 0.01871664]), + 'Velocity': array([-1.03828776e+00, 1.45187303e-01, 1.01855281e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.68763924, 16.17826462, -0.28458747]), + 'camera_rotation': array([-7.58795738, -0.38391268, -1.29018676]), + 'current_gear_input': False, + 'focus_actor_dist': 1565.1170654296875, + 'focus_actor_name': 'Plane34', + 'focus_actor_pt': array([ -692.22418213, -3117.34936523, 17.79414368]), + 'frame': 21413, + 'frame_number': 21413, + 'framesequence': 81967, + 'gaze_dir': array([ 0.96411896, -0.25045013, 0.0870285 ]), + 'gaze_origin': array([-3.87828612, 0.19377214, -0.24919663]), + 'gaze_valid': True, + 'gaze_vergence': 149.0559844970703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96530151, -0.24272156, 0.09617615]), + 'left_gaze_origin': array([-3.74055052, 2.98142862, -0.26203462]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0920562744140625, + 'left_pupil_posn': array([ 0.08642197, -0.42809916]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9629364 , -0.25817871, 0.07788086]), + 'right_gaze_origin': array([-4.01602221, -2.59388447, -0.23635866]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.419769287109375, + 'right_pupil_posn': array([-0.53886616, -0.51084757]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.07539482414722443, + 'timestamp': 692.4104274772108, + 'timestamp_carla': 692412, + 'timestamp_device': 3845837, + 'timestamp_stream': 692.4104274772108, + 'transform': [array([ 4.25045443e+00, 1.20565071e+01, -3.30184936e-03]), + array([ -0.0589377 , -11.88951492, 0.03273176])]} +{'AngularVelocity': array([ 0.02428174, -0.02010027, 2.54343247]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.949651718139648, + 'FR_Wheel_Angle': -8.29222583770752, + 'Location': array([ -7.46081448, -21.31241226, 0.17731625]), + 'Rotation': array([-0.05865766, 2.99878502, 0.02446319]), + 'Velocity': array([-7.26809323e-01, 3.97558026e-02, 4.89301689e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.64972496, 16.02771378, -0.26589555]), + 'camera_rotation': array([-7.5484376 , -1.42443991, -1.04792011]), + 'current_gear_input': False, + 'focus_actor_dist': 1640.642822265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -712.4465332 , -3197.21875 , 58.61889648]), + 'frame': 21414, + 'frame_number': 21414, + 'framesequence': 81971, + 'gaze_dir': array([ 0.96787262, -0.23748016, 0.07969666]), + 'gaze_origin': array([-3.87455153, 0.1804474 , -0.25692368]), + 'gaze_valid': True, + 'gaze_vergence': 31.763233184814453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96746826, -0.23214722, 0.10041809]), + 'left_gaze_origin': array([-3.73603058, 2.97091532, -0.27005312]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.058380126953125, + 'left_pupil_posn': array([ 0.09997976, -0.43970668]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96827698, -0.24281311, 0.05897522]), + 'right_gaze_origin': array([-4.01307249, -2.61002064, -0.24379426]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3893585205078125, + 'right_pupil_posn': array([-0.52126849, -0.51333177]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.019836727529764175, + 'timestamp': 692.4432554766536, + 'timestamp_carla': 692445, + 'timestamp_device': 3845870, + 'timestamp_stream': 692.4432554766536, + 'transform': [array([ 4.24904823e+00, 1.20140266e+01, -3.27579491e-03]), + array([ -0.0589377 , -11.88951492, 0.03273176])]} +{'AngularVelocity': array([0.03461398, 0.01078204, 0.68392164]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.2773616313934326, + 'FR_Wheel_Angle': -2.1985607147216797, + 'Location': array([ -7.60106659, -21.3119278 , 0.17745028]), + 'Rotation': array([-0.05822736, 3.33216906, 0.01880882]), + 'Velocity': array([-4.98398572e-01, -7.99622200e-03, 1.79157258e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.62743568, 15.84803581, -0.2743437 ]), + 'camera_rotation': array([-7.61549664, -2.6322186 , -0.96177191]), + 'current_gear_input': False, + 'focus_actor_dist': 2246.870361328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -898.03613281, -3777.36767578, 17.67110443]), + 'frame': 21415, + 'frame_number': 21415, + 'framesequence': 81975, + 'gaze_dir': array([ 0.9681015 , -0.24287415, 0.06048584]), + 'gaze_origin': array([-3.8704536 , 0.16497345, -0.24677582]), + 'gaze_valid': True, + 'gaze_vergence': 6.593279838562012, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96868896, -0.24328613, 0.04942322]), + 'left_gaze_origin': array([-3.73586154, 2.96166229, -0.27053833]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.107879638671875, + 'left_pupil_posn': array([ 0.10689855, -0.43555939]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96751404, -0.24246216, 0.07154846]), + 'right_gaze_origin': array([-4.00504637, -2.63171554, -0.22301331]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.322998046875, + 'right_pupil_posn': array([-0.50790763, -0.51545775]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 692.4748427793384, + 'timestamp_carla': 692477, + 'timestamp_device': 3845904, + 'timestamp_stream': 692.4748427793384, + 'transform': [array([ 4.24765444e+00, 1.19724169e+01, -3.05505749e-03]), + array([ -0.05901966, -11.88948822, 0.03235774])]} +{'AngularVelocity': array([0.03119403, 0.02513364, 0.03351374]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.66540003, -21.31488991, 0.17748488]), + 'Rotation': array([-0.05044094, 3.36313701, 0.0121685 ]), + 'Velocity': array([-0.08334258, -0.00510639, 0.00036359]), + 'brake_input': 0.0, + 'camera_location': array([-4.59819221, 15.66477203, -0.32684666]), + 'camera_rotation': array([-7.81111336, -3.85292149, -0.93787736]), + 'current_gear_input': False, + 'focus_actor_dist': 1625.2974853515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -755.40155029, -3173.41943359, 17.52813721]), + 'frame': 21416, + 'frame_number': 21416, + 'framesequence': 81979, + 'gaze_dir': array([ 0.97325897, -0.21910095, 0.06839752]), + 'gaze_origin': array([-3.86542821, 0.14881364, -0.24370117]), + 'gaze_valid': True, + 'gaze_vergence': 177.24473571777344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97285461, -0.22302246, 0.06163025]), + 'left_gaze_origin': array([-3.73156452, 2.94811416, -0.26625368]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0959320068359375, + 'left_pupil_posn': array([ 0.1268878 , -0.42937958]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97366333, -0.21517944, 0.07516479]), + 'right_gaze_origin': array([-3.99929214, -2.65048695, -0.2211487 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.38909912109375, + 'right_pupil_posn': array([-0.48365688, -0.50632358]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.509344778955, + 'timestamp_carla': 692511, + 'timestamp_device': 3845937, + 'timestamp_stream': 692.509344778955, + 'transform': [array([ 4.24612522e+00, 1.19266138e+01, -2.54611974e-03]), + array([ -0.05919725, -11.88946152, 0.03136942])]} +{'AngularVelocity': array([0.00682094, 0.04262185, 0.00507571]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.67555809, -21.31547546, 0.17756195]), + 'Rotation': array([-0.06238011, 3.36233974, 0.00784547]), + 'Velocity': array([-2.62366980e-02, -1.53335463e-03, 1.06923444e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.58041763, 15.49620056, -0.36940256]), + 'camera_rotation': array([-8.04172039, -5.04836273, -1.01732945]), + 'current_gear_input': False, + 'focus_actor_dist': 1728.410400390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -783.57946777, -3277.28662109, 17.55648041]), + 'frame': 21417, + 'frame_number': 21417, + 'framesequence': 81983, + 'gaze_dir': array([ 0.97557068, -0.19735718, 0.09525299]), + 'gaze_origin': array([-3.86326694, 0.13721544, -0.24811707]), + 'gaze_valid': True, + 'gaze_vergence': 41.86860275268555, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97358704, -0.2003479 , 0.109375 ]), + 'left_gaze_origin': array([-3.72841954, 2.93550587, -0.26620483]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.07830810546875, + 'left_pupil_posn': array([ 0.14378679, -0.42600095]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97755432, -0.19436646, 0.08113098]), + 'right_gaze_origin': array([-3.99811411, -2.66107488, -0.23002931]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.323028564453125, + 'right_pupil_posn': array([-0.46531087, -0.49271762]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.5421305783093, + 'timestamp_carla': 692544, + 'timestamp_device': 3845970, + 'timestamp_stream': 692.5421305783093, + 'transform': [array([ 4.24467897e+00, 1.18830624e+01, -1.81215280e-03]), + array([ -0.05944313, -11.88946056, 0.02997661])]} +{'AngularVelocity': array([ 0.00158099, 0.01108233, -0.00310147]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.68022299, -21.31575584, 0.17760426]), + 'Rotation': array([-0.06829505, 3.36334109, 0.00660492]), + 'Velocity': array([-0.01171958, -0.00068338, 0.00028758]), + 'brake_input': 0.0, + 'camera_location': array([-4.58099842, 15.29913139, -0.3849636 ]), + 'camera_rotation': array([-8.27131748, -6.22082424, -0.94041115]), + 'current_gear_input': False, + 'focus_actor_dist': 1636.18701171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -753.57244873, -3197.16772461, 60.40595245]), + 'frame': 21418, + 'frame_number': 21418, + 'framesequence': 81987, + 'gaze_dir': array([ 0.97975922, -0.17259979, 0.09971619]), + 'gaze_origin': array([-3.82411075, 0.12728348, -0.25885317]), + 'gaze_valid': True, + 'gaze_vergence': 59.54655456542969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97927856, -0.16581726, 0.11621094]), + 'left_gaze_origin': array([-3.73570585, 2.92656708, -0.25810853]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1539459228515625, + 'left_pupil_posn': array([ 0.1560477 , -0.42100143]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98023987, -0.17938232, 0.08322144]), + 'right_gaze_origin': array([-3.91251564, -2.67200017, -0.25959778]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16339111328125, + 'right_pupil_posn': array([-0.44075215, -0.49028599]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.5754377767444, + 'timestamp_carla': 692578, + 'timestamp_device': 3846004, + 'timestamp_stream': 692.5754377767444, + 'transform': [array([ 4.24322033e+00, 1.18390217e+01, -9.32579045e-04]), + array([ -0.05973683, -11.88945961, 0.02828744])]} +{'AngularVelocity': array([-0.00228525, 0.00425831, -1.37922156]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.11138594150543213, + 'FR_Wheel_Angle': 0.13842177391052246, + 'Location': array([ -7.68186426, -21.31595612, 0.17757446]), + 'Rotation': array([-0.06976355, 3.36909699, 0.00635432]), + 'Velocity': array([-0.00407958, -0.0007889 , -0.00058156]), + 'brake_input': 0.0, + 'camera_location': array([-4.58696938, 15.10259247, -0.42129904]), + 'camera_rotation': array([-8.4496603 , -7.24457216, -0.86257917]), + 'current_gear_input': False, + 'focus_actor_dist': 1628.9571533203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -744.14599609, -3197.2109375 , 61.57662201]), + 'frame': 21419, + 'frame_number': 21419, + 'framesequence': 81991, + 'gaze_dir': array([ 0.97846222, -0.17266083, 0.10773468]), + 'gaze_origin': array([-3.678792 , 0.11496811, -0.31059039]), + 'gaze_valid': True, + 'gaze_vergence': 15.56078052520752, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97351074, -0.18019104, 0.14060974]), + 'left_gaze_origin': array([-3.79213738, 2.91591954, -0.2363724 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.973846435546875, + 'left_pupil_posn': array([ 0.16950572, -0.42066753]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9834137 , -0.16513062, 0.07485962]), + 'right_gaze_origin': array([-3.56544662, -2.68598342, -0.38480839]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.344573974609375, + 'right_pupil_posn': array([-0.4292959 , -0.49337327]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.6094267778099, + 'timestamp_carla': 692612, + 'timestamp_device': 3846037, + 'timestamp_stream': 692.6094267778099, + 'transform': [array([4.24174356e+00, 1.17944298e+01, 1.10626215e-05]), + array([ -0.06005102, -11.88945866, 0.02646385])]} +{'AngularVelocity': array([0.0028548 , 0.00245388, 1.20004833]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2709954082965851, + 'FR_Wheel_Angle': 0.27298665046691895, + 'Location': array([ -7.68288851, -21.31611061, 0.17762581]), + 'Rotation': array([-0.07049438, 3.37757754, 0.00620443]), + 'Velocity': array([-5.97453956e-03, -2.88163516e-04, 6.02340697e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.58146191, 14.89907837, -0.42086747]), + 'camera_rotation': array([-8.40493011, -8.21745014, -0.923325 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1633.6488037109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -773.78552246, -3197.16748047, 69.87656403]), + 'frame': 21420, + 'frame_number': 21420, + 'framesequence': 81995, + 'gaze_dir': array([ 0.98232269, -0.15537262, 0.0976944 ]), + 'gaze_origin': array([-3.73509598, 0.09965897, -0.28984147]), + 'gaze_valid': True, + 'gaze_vergence': 23.005659103393555, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97695923, -0.16784668, 0.13180542]), + 'left_gaze_origin': array([-3.89097452, 2.90683913, -0.1975418 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0571746826171875, + 'left_pupil_posn': array([ 0.18578982, -0.41944742]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98768616, -0.14289856, 0.06358337]), + 'right_gaze_origin': array([-3.57921767, -2.7075212 , -0.38214114]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4093170166015625, + 'right_pupil_posn': array([-0.40876746, -0.49775302]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.642829079181, + 'timestamp_carla': 692645, + 'timestamp_device': 3846070, + 'timestamp_stream': 692.642829079181, + 'transform': [array([4.24030447e+00, 1.17510357e+01, 9.27009562e-04]), + array([ -0.06035155, -11.88945866, 0.02470746])]} +{'AngularVelocity': array([0.00252644, 0.0014259 , 1.27823806]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2798888683319092, + 'FR_Wheel_Angle': 0.280644029378891, + 'Location': array([ -7.6845541 , -21.31623459, 0.17760627]), + 'Rotation': array([-0.07073344, 3.37781239, 0.00619127]), + 'Velocity': array([-0.01094958, -0.00050621, -0.00015523]), + 'brake_input': 0.0, + 'camera_location': array([-4.57816696, 14.73679352, -0.4083446 ]), + 'camera_rotation': array([-8.28027248, -8.98861027, -1.02054191]), + 'current_gear_input': False, + 'focus_actor_dist': 1787.9466552734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -823.60095215, -3346.79589844, 46.55541229]), + 'frame': 21421, + 'frame_number': 21421, + 'framesequence': 81999, + 'gaze_dir': array([ 0.98408508, -0.0326004 , -0.07295227]), + 'gaze_origin': array([-5.6333313 , 0.10505371, 0.33499223]), + 'gaze_valid': True, + 'gaze_vergence': 4.053664684295654, + 'handbrake_input': False, + 'left_eye_openness': 0.2174014300107956, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99316406, -0.08950806, 0.0749054 ]), + 'left_gaze_origin': array([-7.13406134, 2.95926523, 0.82781982]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0087127685546875, + 'left_pupil_posn': array([ 0.27445984, -0.58177745]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8689497709274292, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9750061 , 0.02430725, -0.22080994]), + 'right_gaze_origin': array([-4.13260221, -2.74915791, -0.15783539]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0817718505859375, + 'right_pupil_posn': array([-0.35363698, -0.47932005]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.6749821789563, + 'timestamp_carla': 692677, + 'timestamp_device': 3846103, + 'timestamp_stream': 692.6749821789563, + 'transform': [array([4.23893404e+00, 1.17097139e+01, 1.75746914e-03]), + array([ -0.06063158, -11.88945866, 0.02313285])]} +{'AngularVelocity': array([-0.0017761 , 0.00135789, -1.218279 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2798328697681427, + 'FR_Wheel_Angle': 0.28058701753616333, + 'Location': array([ -7.68811703, -21.31640244, 0.17763355]), + 'Rotation': array([-0.07107495, 3.3678472 , 0.0062121 ]), + 'Velocity': array([-2.12728977e-02, -1.40976615e-03, 5.02967814e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.59469414, 14.63094616, -0.39226049]), + 'camera_rotation': array([-8.24044514, -9.30851746, -1.08826828]), + 'current_gear_input': False, + 'focus_actor_dist': 542.71728515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -354.48904419, -2179.19897461, 17.17583466]), + 'frame': 21422, + 'frame_number': 21422, + 'framesequence': 82004, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5419789552688599, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-4.21319008, -2.8578248 , -0.10275727]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.7086486779153, + 'timestamp_carla': 692711, + 'timestamp_device': 3846145, + 'timestamp_stream': 692.7086486779153, + 'transform': [array([4.23751879e+00, 1.16669722e+01, 2.53187167e-03]), + array([ -0.0608843 , -11.8894577 , 0.02163937])]} +{'AngularVelocity': array([ 0.01030757, -0.19570877, 0.26012236]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.68998575, -21.31655693, 0.1775544 ]), + 'Rotation': array([-0.06582253, 3.37516379, 0.00621106]), + 'Velocity': array([ 0.16989197, 0.00977519, -0.00052991]), + 'brake_input': 0.0, + 'camera_location': array([-4.59595394, 14.60287476, -0.3784211 ]), + 'camera_rotation': array([-8.18158245, -9.15079021, -1.22199535]), + 'current_gear_input': False, + 'focus_actor_dist': 815.2545776367188, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -395.74243164, -2463.47900391, 17.17881012]), + 'frame': 21423, + 'frame_number': 21423, + 'framesequence': 82008, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 14.21939754486084, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98443604, 0.16784668, 0.05197144]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.6276039481163025, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.94308496, -2.94934106, -0.20106812]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.666717529296875, + 'right_pupil_posn': array([-0.10291803, -0.47595608]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.7429386787117, + 'timestamp_carla': 692745, + 'timestamp_device': 3846178, + 'timestamp_stream': 692.7429386787117, + 'transform': [array([4.23609114e+00, 1.16239996e+01, 3.22155003e-03]), + array([ -0.06112336, -11.88945675, 0.02030697])]} +{'AngularVelocity': array([-0.00332918, 0.06408471, 0.18068421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.58750057, -21.31053734, 0.17743038]), + 'Rotation': array([-0.05496253, 3.37157655, 0.00623328]), + 'Velocity': array([ 5.14648438e-01, 3.01205423e-02, -3.92084126e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.5879631 , 14.66830826, -0.36149114]), + 'camera_rotation': array([-8.11231041, -8.48983002, -1.38852477]), + 'current_gear_input': False, + 'focus_actor_dist': 821.0504760742188, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -394.85394287, -2473.92822266, 17.17722321]), + 'frame': 21424, + 'frame_number': 21424, + 'framesequence': 82012, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 8.498892784118652, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.96025085, 0.27780151, 0.0266571 ]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.807876467704773, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.954422 , -2.99833369, -0.22110596]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8136444091796875, + 'right_pupil_posn': array([-0.02486467, -0.50759125]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.7758550792933, + 'timestamp_carla': 692778, + 'timestamp_device': 3846212, + 'timestamp_stream': 692.7758550792933, + 'transform': [array([4.23473883e+00, 1.15832949e+01, 3.80058284e-03]), + array([ -0.06130777, -11.88945198, 0.01921664])]} +{'AngularVelocity': array([-0.00213119, 0.03316131, 0.03784304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.47009802, -21.30365944, 0.17738846]), + 'Rotation': array([-0.06722955, 3.37117195, 0.00623084]), + 'Velocity': array([ 4.88843709e-01, 2.86139473e-02, -2.49123579e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.57967663, 14.79140282, -0.34559113]), + 'camera_rotation': array([-8.08861732, -7.54471254, -1.54098499]), + 'current_gear_input': False, + 'focus_actor_dist': 828.017822265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -386.98757935, -2486.90136719, 17.16834259]), + 'frame': 21425, + 'frame_number': 21425, + 'framesequence': 82015, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 6.927038192749023, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.94503784, 0.32356262, 0.04696655]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.96622634, -3.02247953, -0.2344742 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.867828369140625, + 'right_pupil_posn': array([ 0.01115751, -0.51475704]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.808611176908, + 'timestamp_carla': 692811, + 'timestamp_device': 3846237, + 'timestamp_stream': 692.808611176908, + 'transform': [array([4.23339367e+00, 1.15433140e+01, 4.29182034e-03]), + array([ -0.06146487, -11.88941383, 0.01829472])]} +{'AngularVelocity': array([-0.00432351, 0.05462079, -0.3611266 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.797154188156128, + 'FR_Wheel_Angle': 3.1321544647216797, + 'Location': array([ -7.3965888 , -21.29925919, 0.17739971]), + 'Rotation': array([-0.08218766, 3.40692806, 0.00591863]), + 'Velocity': array([0.1605318 , 0.01159297, 0.00022809]), + 'brake_input': 0.0, + 'camera_location': array([-4.58988571, 14.94214916, -0.35614821]), + 'camera_rotation': array([-8.0966835 , -6.45101309, -1.57145226]), + 'current_gear_input': False, + 'focus_actor_dist': 830.4425048828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -374.08078003, -2495.72705078, 17.15462494]), + 'frame': 21426, + 'frame_number': 21426, + 'framesequence': 82019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 7.607988357543945, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.95248413, 0.30169678, 0.04165649]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.96090269, -3.01476169, -0.22795717]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.937530517578125, + 'right_pupil_posn': array([-0.0033499 , -0.50981629]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.8424358777702, + 'timestamp_carla': 692845, + 'timestamp_device': 3846270, + 'timestamp_stream': 692.8424358777702, + 'transform': [array([4.23203135e+00, 1.15026026e+01, 4.71139885e-03]), + array([ -0.06161513, -11.8893795 , 0.01749403])]} +{'AngularVelocity': array([ 0.00186981, -0.04044265, -0.19493496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.430481433868408, + 'FR_Wheel_Angle': 1.9584699869155884, + 'Location': array([ -7.38252592, -21.29819489, 0.17735668]), + 'Rotation': array([-0.08075332, 3.42629123, 0.00637114]), + 'Velocity': array([ 0.00666071, 0.00061556, -0.00028527]), + 'brake_input': 0.0, + 'camera_location': array([-4.61390972, 15.12659836, -0.36064452]), + 'camera_rotation': array([-8.10124588, -5.32232237, -1.68118072]), + 'current_gear_input': False, + 'focus_actor_dist': 829.4612426757812, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -358.41299438, -2501.16699219, 17.13826752]), + 'frame': 21427, + 'frame_number': 21427, + 'framesequence': 82023, + 'gaze_dir': array([0.95442963, 0.29508972, 0.03531647]), + 'gaze_origin': array([-3.88525081, -0.22131805, -0.25454408]), + 'gaze_valid': True, + 'gaze_vergence': 61.40038299560547, + 'handbrake_input': False, + 'left_eye_openness': 0.3274553716182709, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96018982, 0.27891541, 0.01472473]), + 'left_gaze_origin': array([-3.81546354, 2.5670166 , -0.28098756]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4873046875, + 'left_pupil_posn': array([ 0.63631499, -0.48884463]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94866943, 0.31126404, 0.0559082 ]), + 'right_gaze_origin': array([-3.95503855, -3.00965285, -0.2281006 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9814910888671875, + 'right_pupil_posn': array([-0.01625365, -0.51806843]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.8745833784342, + 'timestamp_carla': 692877, + 'timestamp_device': 3846303, + 'timestamp_stream': 692.8745833784342, + 'transform': [array([4.23074341e+00, 1.14644232e+01, 5.05472161e-03]), + array([ -0.06171758, -11.88934422, 0.01686856])]} +{'AngularVelocity': array([ 0.001238 , -0.0165853 , -0.04056493]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.3750405311584473, + 'FR_Wheel_Angle': -2.6987671852111816, + 'Location': array([ -7.38167381, -21.29813194, 0.17733909]), + 'Rotation': array([-0.07342453, 3.42641354, 0.00627732]), + 'Velocity': array([0.00290217, 0.00011608, 0.00038031]), + 'brake_input': 0.0, + 'camera_location': array([-4.63802719, 15.32494831, -0.35902292]), + 'camera_rotation': array([-8.0830431 , -4.19984245, -1.79694498]), + 'current_gear_input': False, + 'focus_actor_dist': 1286.82568359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -17.2905426 , -2950.99902344, 16.77077484]), + 'frame': 21428, + 'frame_number': 21428, + 'framesequence': 82028, + 'gaze_dir': array([0.96553802, 0.25718689, 0.03575897]), + 'gaze_origin': array([-3.87880135, -0.20874023, -0.25606158]), + 'gaze_valid': True, + 'gaze_vergence': 157.31961059570312, + 'handbrake_input': False, + 'left_eye_openness': 0.4543197453022003, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9611969 , 0.27311707, 0.03840637]), + 'left_gaze_origin': array([-3.80356598, 2.57898283, -0.289386 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.457611083984375, + 'left_pupil_posn': array([ 0.59337246, -0.49553084]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96987915, 0.24125671, 0.03311157]), + 'right_gaze_origin': array([-3.95403624, -2.99646306, -0.22273713]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0698089599609375, + 'right_pupil_posn': array([-0.0282141 , -0.50437891]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.9132984764874, + 'timestamp_carla': 692915, + 'timestamp_device': 3846345, + 'timestamp_stream': 692.9132984764874, + 'transform': [array([4.22923470e+00, 1.14191456e+01, 5.33685694e-03]), + array([ -0.06182687, -11.88932037, 0.01624932])]} +{'AngularVelocity': array([ 0.00031967, -0.00382287, -0.06666295]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.5850725173950195, + 'FR_Wheel_Angle': -3.464951515197754, + 'Location': array([ -7.38131332, -21.29812431, 0.17732055]), + 'Rotation': array([-0.07117057, 3.42569089, 0.00620734]), + 'Velocity': array([8.89687508e-04, 2.55696359e-05, 1.99213027e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.65543365, 15.54928875, -0.35638195]), + 'camera_rotation': array([-8.04592133, -2.9455688 , -1.79828477]), + 'current_gear_input': False, + 'focus_actor_dist': 1267.32275390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -45.74160767, -2939.65722656, 16.80007935]), + 'frame': 21429, + 'frame_number': 21429, + 'framesequence': 82031, + 'gaze_dir': array([0.96677399, 0.25365448, 0.02957916]), + 'gaze_origin': array([-3.87388754, -0.19060136, -0.2487137 ]), + 'gaze_valid': True, + 'gaze_vergence': 184.60720825195312, + 'handbrake_input': False, + 'left_eye_openness': 0.5196577310562134, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9644928 , 0.26150513, 0.03663635]), + 'left_gaze_origin': array([-3.79858422, 2.60016036, -0.27756348]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4318695068359375, + 'left_pupil_posn': array([ 0.57682836, -0.48891556]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96905518, 0.24580383, 0.02252197]), + 'right_gaze_origin': array([-3.94919133, -2.98136306, -0.21986391]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.147125244140625, + 'right_pupil_posn': array([-0.04423171, -0.50171053]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.9429725781083, + 'timestamp_carla': 692945, + 'timestamp_device': 3846370, + 'timestamp_stream': 692.9429725781083, + 'transform': [array([4.22810173e+00, 1.13848829e+01, 5.48406597e-03]), + array([ -0.06187468, -11.88932037, 0.01593281])]} +{'AngularVelocity': array([ 5.24921197e-05, -1.18637993e-03, -1.67211235e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.314392566680908, + 'FR_Wheel_Angle': -4.437345027923584, + 'Location': array([ -7.38113403, -21.29812241, 0.177303 ]), + 'Rotation': array([-0.07092468, 3.42490172, 0.00620006]), + 'Velocity': array([8.61905864e-04, 2.57035754e-05, 2.51960755e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.6981678 , 15.78224945, -0.34755516]), + 'camera_rotation': array([-8.03795719, -1.73071992, -1.84398448]), + 'current_gear_input': False, + 'focus_actor_dist': 1192.78466796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -35.47746277, -2866.61328125, 16.78996277]), + 'frame': 21430, + 'frame_number': 21430, + 'framesequence': 82035, + 'gaze_dir': array([0.96954346, 0.24282837, 0.0296936 ]), + 'gaze_origin': array([-3.87088799, -0.18055649, -0.24706042]), + 'gaze_valid': True, + 'gaze_vergence': 122.20198059082031, + 'handbrake_input': False, + 'left_eye_openness': 0.5562215447425842, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96784973, 0.2484436 , 0.03921509]), + 'left_gaze_origin': array([-3.79491305, 2.61180449, -0.27472535]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4472808837890625, + 'left_pupil_posn': array([ 0.56288326, -0.48564899]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97123718, 0.23721313, 0.02017212]), + 'right_gaze_origin': array([-3.94686317, -2.97291732, -0.21939546]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.050201416015625, + 'right_pupil_posn': array([-0.05544907, -0.49916124]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0, + 'timestamp': 692.9747163765132, + 'timestamp_carla': 692977, + 'timestamp_device': 3846403, + 'timestamp_stream': 692.9747163765132, + 'transform': [array([4.22690344e+00, 1.13487139e+01, 5.71100228e-03]), + array([ -0.06193615, -11.88932037, 0.01560336])]} +{'AngularVelocity': array([ 2.97847346e-05, -5.68921620e-04, -1.02068903e-02]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.112707138061523, + 'FR_Wheel_Angle': -5.771158695220947, + 'Location': array([ -7.38092756, -21.29812241, 0.1773008 ]), + 'Rotation': array([-0.07082906, 3.42521977, 0.00620085]), + 'Velocity': array([ 9.95575800e-04, -1.20745972e-06, -2.88172945e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.72244835, 16.00375748, -0.33822462]), + 'camera_rotation': array([-8.01610756, -0.66242915, -1.84002149]), + 'current_gear_input': False, + 'focus_actor_dist': 1189.32568359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -24.43275452, -2864.50537109, 16.77861786]), + 'frame': 21431, + 'frame_number': 21431, + 'framesequence': 82039, + 'gaze_dir': array([0.99662781, 0.04415894, 0.06645203]), + 'gaze_origin': array([-3.87322712, -0.04104843, -0.22033158]), + 'gaze_valid': True, + 'gaze_vergence': 88.29471588134766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99717712, 0.05503845, 0.05101013]), + 'left_gaze_origin': array([-3.67480779, 2.76485896, -0.27875063]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.26739501953125, + 'left_pupil_posn': array([ 0.35405207, -0.42429912]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99607849, 0.03327942, 0.08189392]), + 'right_gaze_origin': array([-4.07164621, -2.84695601, -0.16191255]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.223297119140625, + 'right_pupil_posn': array([-0.22250181, -0.47692263]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.01190203707665205, + 'timestamp': 693.0080461762846, + 'timestamp_carla': 693010, + 'timestamp_device': 3846437, + 'timestamp_stream': 693.0080461762846, + 'transform': [array([4.22566175e+00, 1.13112593e+01, 5.88331232e-03]), + array([ -0.06199079, -11.88932037, 0.01532742])]} +{'AngularVelocity': array([-0.00010814, -0.000213 , -0.00767306]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.6937994956970215, + 'FR_Wheel_Angle': -4.081413269042969, + 'Location': array([ -7.380723 , -21.29810715, 0.17730647]), + 'Rotation': array([-0.07082906, 3.42569685, 0.00616388]), + 'Velocity': array([9.54814430e-04, 1.19023725e-05, 4.62997268e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.75678444, 16.22642517, -0.32344088]), + 'camera_rotation': array([-7.94963646, 0.34965527, -1.79356444]), + 'current_gear_input': False, + 'focus_actor_dist': 1631.44921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -242.64881897, -3331.39135742, 17.00009918]), + 'frame': 21432, + 'frame_number': 21432, + 'framesequence': 82043, + 'gaze_dir': array([ 0.97419739, -0.20004272, 0.09686279]), + 'gaze_origin': array([-3.86511874, 0.1479622 , -0.22187501]), + 'gaze_valid': True, + 'gaze_vergence': 8.72148609161377, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97135925, -0.19523621, 0.13536072]), + 'left_gaze_origin': array([-3.77148461, 2.93667769, -0.22009736]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1712799072265625, + 'left_pupil_posn': array([ 0.13950741, -0.41106904]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97703552, -0.20484924, 0.05836487]), + 'right_gaze_origin': array([-3.95875263, -2.64075327, -0.22365268]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3713836669921875, + 'right_pupil_posn': array([-0.47708654, -0.46811628]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0158693827688694, + 'timestamp': 693.0423755757511, + 'timestamp_carla': 693044, + 'timestamp_device': 3846470, + 'timestamp_stream': 693.0423755757511, + 'transform': [array([4.22440100e+00, 1.12732334e+01, 6.01015100e-03]), + array([ -0.06203178, -11.88932037, 0.01511252])]} +{'AngularVelocity': array([ 1.69045481e-04, -3.28613860e-05, -2.92211352e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.38051367, -21.29811668, 0.17731334]), + 'Rotation': array([-0.07082906, 3.4260211 , 0.00622251]), + 'Velocity': array([ 8.86423630e-04, 3.95427342e-05, -5.63021495e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.78146553, 16.40454483, -0.3001568 ]), + 'camera_rotation': array([-7.85423231, 1.0692364 , -1.73885453]), + 'current_gear_input': False, + 'focus_actor_dist': 1533.20263671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -590.08776855, -3198.62402344, 65.43971252]), + 'frame': 21433, + 'frame_number': 21433, + 'framesequence': 82047, + 'gaze_dir': array([ 0.97212219, -0.22543335, 0.06272888]), + 'gaze_origin': array([-3.86777592, 0.18027268, -0.21883166]), + 'gaze_valid': True, + 'gaze_vergence': 88.20099639892578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96989441, -0.2315979 , 0.07518005]), + 'left_gaze_origin': array([-3.77637482, 2.97066355, -0.22354126]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.173828125, + 'left_pupil_posn': array([ 0.10934258, -0.41790867]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97434998, -0.2192688 , 0.05027771]), + 'right_gaze_origin': array([-3.95917678, -2.61011839, -0.21412203]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.621826171875, + 'right_pupil_posn': array([-0.51753092, -0.48726273]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.019836727529764175, + 'timestamp': 693.0750561766326, + 'timestamp_carla': 693077, + 'timestamp_device': 3846503, + 'timestamp_stream': 693.0750561766326, + 'transform': [array([4.22321796e+00, 1.12375402e+01, 6.11972809e-03]), + array([ -0.0620591 , -11.88931942, 0.01495095])]} +{'AngularVelocity': array([ 9.58293094e-04, -1.55489091e-04, 8.05479050e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.38009644, -21.29815674, 0.17724495]), + 'Rotation': array([-0.07079491, 3.43142033, 0.00621319]), + 'Velocity': array([ 0.0025714 , 0.00013598, -0.00111053]), + 'brake_input': 0.0, + 'camera_location': array([-4.80736828, 16.48629951, -0.27158985]), + 'camera_rotation': array([-7.70396137, 1.24860775, -1.78871548]), + 'current_gear_input': False, + 'focus_actor_dist': 1512.2261962890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -603.12164307, -3174.58544922, 17.37160492]), + 'frame': 21434, + 'frame_number': 21434, + 'framesequence': 82051, + 'gaze_dir': array([ 0.97284698, -0.22103882, 0.0682373 ]), + 'gaze_origin': array([-3.87025023, 0.18835831, -0.22667162]), + 'gaze_valid': True, + 'gaze_vergence': 87.62881469726562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97225952, -0.2219696 , 0.07363892]), + 'left_gaze_origin': array([-3.77932739, 2.98028421, -0.22915651]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1040496826171875, + 'left_pupil_posn': array([ 0.10181963, -0.4177506 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97343445, -0.22010803, 0.06283569]), + 'right_gaze_origin': array([-3.96117258, -2.6035676 , -0.22418672]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4753265380859375, + 'right_pupil_posn': array([-0.51932454, -0.49557221]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0238040741533041, + 'timestamp': 693.1091559790075, + 'timestamp_carla': 693111, + 'timestamp_device': 3846537, + 'timestamp_stream': 693.1091559790075, + 'transform': [array([4.22196913e+00, 1.12015667e+01, 6.60358416e-03]), + array([ -0.06218887, -11.88919926, 0.01402563])]} +{'AngularVelocity': array([-4.34280664e-04, -3.86804386e-05, 6.66332943e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.37930346, -21.29806519, 0.17730503]), + 'Rotation': array([-0.07079491, 3.42908025, 0.00608269]), + 'Velocity': array([0.00410873, 0.00024314, 0.00023635]), + 'brake_input': 0.0, + 'camera_location': array([-4.79368591, 16.40969467, -0.23254541]), + 'camera_rotation': array([-7.51851463, 0.40216151, -1.58847845]), + 'current_gear_input': False, + 'focus_actor_dist': 1527.92626953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -595.92822266, -3196.92529297, 28.15367889]), + 'frame': 21435, + 'frame_number': 21435, + 'framesequence': 82055, + 'gaze_dir': array([ 0.97502136, -0.2134552 , 0.06056976]), + 'gaze_origin': array([-3.86781549, 0.18517609, -0.22425005]), + 'gaze_valid': True, + 'gaze_vergence': 88.5883560180664, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97503662, -0.21096802, 0.06903076]), + 'left_gaze_origin': array([-3.77858758, 2.98146534, -0.23180696]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.030517578125, + 'left_pupil_posn': array([ 0.10248852, -0.42333078]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9750061 , -0.21594238, 0.05210876]), + 'right_gaze_origin': array([-3.95704365, -2.61111307, -0.21669313]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.5716552734375, + 'right_pupil_posn': array([-0.50824356, -0.49031675]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0238040741533041, + 'timestamp': 693.1419930793345, + 'timestamp_carla': 693144, + 'timestamp_device': 3846570, + 'timestamp_stream': 693.1419930793345, + 'transform': [array([4.22080755e+00, 1.11683140e+01, 7.23009091e-03]), + array([ -0.06238694, -11.8890686 , 0.01283925])]} +{'AngularVelocity': array([1.84881035e-04, 1.53113779e-05, 4.77714324e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.37819147, -21.29799843, 0.17730586]), + 'Rotation': array([-0.07079491, 3.42908025, 0.00608269]), + 'Velocity': array([5.47652179e-03, 3.24432593e-04, 8.87694259e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.79029179, 16.22659683, -0.20778352]), + 'camera_rotation': array([-7.4678688 , -1.03567684, -1.26141202]), + 'current_gear_input': False, + 'focus_actor_dist': 1528.1474609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -605.81256104, -3197.96142578, 22.41249084]), + 'frame': 21436, + 'frame_number': 21436, + 'framesequence': 82059, + 'gaze_dir': array([ 0.97570038, -0.20507812, 0.07413483]), + 'gaze_origin': array([-3.86737633, 0.17832872, -0.22852097]), + 'gaze_valid': True, + 'gaze_vergence': 39.84801483154297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97291565, -0.21115112, 0.09393311]), + 'left_gaze_origin': array([-3.77700973, 2.97654891, -0.2364029 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1260528564453125, + 'left_pupil_posn': array([ 0.11252856, -0.42543137]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97848511, -0.19900513, 0.05433655]), + 'right_gaze_origin': array([-3.95774245, -2.61989141, -0.22063905]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4716033935546875, + 'right_pupil_posn': array([-0.50091255, -0.48320949]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0238040741533041, + 'timestamp': 693.174429576844, + 'timestamp_carla': 693176, + 'timestamp_device': 3846603, + 'timestamp_stream': 693.174429576844, + 'transform': [array([4.21970510e+00, 1.11365862e+01, 7.75800692e-03]), + array([-6.25645295e-02, -1.18889503e+01, 1.18430173e-02])]} +{'AngularVelocity': array([2.01568273e-05, 4.53304310e-05, 7.60137336e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.37675571, -21.29792976, 0.17729847]), + 'Rotation': array([-0.07079491, 3.42908025, 0.00608269]), + 'Velocity': array([6.73916703e-03, 3.98896838e-04, 2.02871252e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.76034451, 15.94188881, -0.18358885]), + 'camera_rotation': array([-7.36758137, -2.99015379, -0.9989326 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1532.180419921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -631.49084473, -3200.51904297, 46.04772186]), + 'frame': 21437, + 'frame_number': 21437, + 'framesequence': 82063, + 'gaze_dir': array([ 0.98140717, -0.16979218, 0.08763885]), + 'gaze_origin': array([-3.85346079, 0.15013428, -0.24091797]), + 'gaze_valid': True, + 'gaze_vergence': 55.153804779052734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98098755, -0.16371155, 0.10406494]), + 'left_gaze_origin': array([-3.77101302, 2.94943857, -0.24404757]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1662139892578125, + 'left_pupil_posn': array([ 0.14100444, -0.42326903]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98182678, -0.1758728 , 0.07121277]), + 'right_gaze_origin': array([-3.93590856, -2.64916992, -0.23778839]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.270050048828125, + 'right_pupil_posn': array([-0.4578768 , -0.48455095]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.0238040741533041, + 'timestamp': 693.2094618789852, + 'timestamp_carla': 693212, + 'timestamp_device': 3846637, + 'timestamp_stream': 693.2094618789852, + 'transform': [array([4.21855450e+00, 1.11033821e+01, 8.10087193e-03]), + array([-6.26874715e-02, -1.18888206e+01, 1.11638056e-02])]} \ No newline at end of file diff --git a/PythonAPI/data/trials/trial3.txt b/PythonAPI/data/trials/trial3.txt new file mode 100644 index 0000000..5175469 --- /dev/null +++ b/PythonAPI/data/trials/trial3.txt @@ -0,0 +1,9306 @@ +{'AngularVelocity': array([ 1.57939394e-05, -1.38072399e-04, -6.90358911e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16992511]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([5.37681399e-06, 7.39563234e-07, 8.57949635e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.5890646 , 15.3253212 , 0.43041712]), + 'camera_rotation': array([-2.44270778, -2.36812258, -0.96496898]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.604736328125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -346.00308228, -5331.49023438, 218.74862671]), + 'frame': 25513, + 'frame_number': 25513, + 'framesequence': 98103, + 'gaze_dir': array([0.99705505, 0.04083252, 0.06199646]), + 'gaze_origin': array([-2.91911554, -0.03073959, -0.14533845]), + 'gaze_valid': True, + 'gaze_vergence': 112.26093292236328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99729919, 0.05436707, 0.04910278]), + 'left_gaze_origin': array([-2.71647811, 2.83522344, -0.17643891]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9503326416015625, + 'left_pupil_posn': array([ 0.27733827, -0.15201187]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99681091, 0.02729797, 0.07489014]), + 'right_gaze_origin': array([-3.12175298, -2.89670277, -0.11423798]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.74481201171875, + 'right_pupil_posn': array([-0.18224454, -0.23608053]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 826.8412754759192, + 'timestamp_carla': 826843, + 'timestamp_device': 3980275, + 'timestamp_stream': 826.8412754759192, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54761507e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-3.05523758e-06, 3.12388693e-05, -6.98605709e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.1699197 ]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([5.80395545e-06, 8.48607158e-07, 3.80602578e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.58890343, 15.34765816, 0.43929255]), + 'camera_rotation': array([-2.47693372, -2.30391884, -0.90046144]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.5625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -346.75665283, -5331.49023438, 214.99407959]), + 'frame': 25514, + 'frame_number': 25514, + 'framesequence': 98107, + 'gaze_dir': array([0.99712372, 0.03820801, 0.06359863]), + 'gaze_origin': array([-2.91383219, -0.03051377, -0.14846727]), + 'gaze_valid': True, + 'gaze_vergence': 137.480712890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99740601, 0.0483551 , 0.05305481]), + 'left_gaze_origin': array([-2.71295643, 2.83563542, -0.17855531]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.950714111328125, + 'left_pupil_posn': array([ 0.27726364, -0.15301037]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99684143, 0.02806091, 0.07414246]), + 'right_gaze_origin': array([-3.11470819, -2.89666295, -0.11837921]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7511749267578125, + 'right_pupil_posn': array([-0.18438661, -0.23609757]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 826.8741550780833, + 'timestamp_carla': 826876, + 'timestamp_device': 3980308, + 'timestamp_stream': 826.8741550780833, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54933150e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-8.14414136e-07, 3.53494797e-05, -7.07098661e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16991192]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([5.92155357e-06, 8.74905368e-07, 5.10981248e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.56426239, 15.3790226 , 0.43209338]), + 'camera_rotation': array([-2.48163295, -2.26824951, -0.91721708]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.762939453125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -352.56430054, -5331.49023438, 218.65518188]), + 'frame': 25515, + 'frame_number': 25515, + 'framesequence': 98111, + 'gaze_dir': array([0.99720001, 0.03742981, 0.06261444]), + 'gaze_origin': array([-2.90686655, -0.02992706, -0.15080491]), + 'gaze_valid': True, + 'gaze_vergence': 126.4122314453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99751282, 0.04833984, 0.05114746]), + 'left_gaze_origin': array([-2.70469522, 2.83631468, -0.1813263 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9322509765625, + 'left_pupil_posn': array([ 0.27613461, -0.15323818]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99688721, 0.02651978, 0.07408142]), + 'right_gaze_origin': array([-3.10903788, -2.89616871, -0.12028351]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.751678466796875, + 'right_pupil_posn': array([-0.18475509, -0.2369709 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 826.9074862785637, + 'timestamp_carla': 826909, + 'timestamp_device': 3980341, + 'timestamp_stream': 826.9074862785637, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54685185e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-3.55170130e-07, 2.29313555e-05, -6.92813319e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16993041]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([5.54868939e-06, 7.72455223e-07, 1.48250474e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.56733418, 15.39816284, 0.40307787]), + 'camera_rotation': array([-2.58777404, -2.2492485 , -0.96173453]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.657958984375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -353.17504883, -5331.49023438, 214.38043213]), + 'frame': 25516, + 'frame_number': 25516, + 'framesequence': 98115, + 'gaze_dir': array([0.99707794, 0.03646851, 0.06452942]), + 'gaze_origin': array([-2.91681671, -0.02608337, -0.14923249]), + 'gaze_valid': True, + 'gaze_vergence': 153.4582977294922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99674988, 0.05387878, 0.05979919]), + 'left_gaze_origin': array([-2.71315026, 2.83993697, -0.18054353]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8753814697265625, + 'left_pupil_posn': array([ 0.27134848, -0.15593481]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99740601, 0.01905823, 0.06925964]), + 'right_gaze_origin': array([-3.1204834 , -2.89210367, -0.11792146]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7545623779296875, + 'right_pupil_posn': array([-0.18551445, -0.23449802]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 826.9419705793262, + 'timestamp_carla': 826943, + 'timestamp_device': 3980375, + 'timestamp_stream': 826.9419705793262, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53647599e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-8.96067576e-08, 3.85999556e-05, -6.91460082e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16992298]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([ 5.30542775e-06, 6.95353378e-07, -7.14927446e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.56944275, 15.41177177, 0.36880696]), + 'camera_rotation': array([-2.75167131, -2.22029233, -0.93120897]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.7431640625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -355.98339844, -5331.48974609, 214.68463135]), + 'frame': 25517, + 'frame_number': 25517, + 'framesequence': 98119, + 'gaze_dir': array([0.99710846, 0.04013062, 0.06243896]), + 'gaze_origin': array([-2.91789031, -0.01915894, -0.14715196]), + 'gaze_valid': True, + 'gaze_vergence': 170.01675415039062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99690247, 0.05451965, 0.05641174]), + 'left_gaze_origin': array([-2.72425699, 2.84688425, -0.17727815]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8725738525390625, + 'left_pupil_posn': array([ 0.26919031, -0.15599298]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99731445, 0.02574158, 0.06846619]), + 'right_gaze_origin': array([-3.11152363, -2.88520217, -0.11702576]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.764312744140625, + 'right_pupil_posn': array([-0.19003373, -0.23339176]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 826.9740004763007, + 'timestamp_carla': 826975, + 'timestamp_device': 3980408, + 'timestamp_stream': 826.9740004763007, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54875920e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-1.13688179e-06, 4.90135571e-05, -6.93784841e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16992107]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([5.46307274e-06, 7.46452713e-07, 7.88432590e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.57953739, 15.40381241, 0.37188107]), + 'camera_rotation': array([-2.80375838, -2.25747609, -1.02736735]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.03173828125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -339.11013794, -5331.49072266, 195.06768799]), + 'frame': 25518, + 'frame_number': 25518, + 'framesequence': 98123, + 'gaze_dir': array([0.99687958, 0.04077148, 0.06520081]), + 'gaze_origin': array([-2.91070819, -0.02013474, -0.15218583]), + 'gaze_valid': True, + 'gaze_vergence': 152.40200805664062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99664307, 0.05702209, 0.05870056]), + 'left_gaze_origin': array([-2.72479725, 2.84605885, -0.17895204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8995819091796875, + 'left_pupil_posn': array([ 0.26934099, -0.15608764]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99711609, 0.02452087, 0.07170105]), + 'right_gaze_origin': array([-3.09661889, -2.88632822, -0.12541963]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8500213623046875, + 'right_pupil_posn': array([-0.18843645, -0.23542035]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.0097359791398, + 'timestamp_carla': 827011, + 'timestamp_device': 3980441, + 'timestamp_stream': 827.0097359791398, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.52716835e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 1.52982084e-05, -3.28106694e-06, -6.93301217e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16991882]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([ 5.32178183e-06, 7.02312661e-07, -9.52307619e-06]), + 'brake_input': 0.0, + 'camera_location': array([-7.5800724 , 15.35760498, 0.38525638]), + 'camera_rotation': array([-2.75441027, -2.55474877, -1.38366139]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.17236328125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -339.74902344, -5331.49023438, 202.79785156]), + 'frame': 25519, + 'frame_number': 25519, + 'framesequence': 98127, + 'gaze_dir': array([0.99656677, 0.04199219, 0.06932068]), + 'gaze_origin': array([-2.90364552, -0.02779999, -0.15745698]), + 'gaze_valid': True, + 'gaze_vergence': 161.98175048828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99630737, 0.05761719, 0.06358337]), + 'left_gaze_origin': array([-2.71431589, 2.83915281, -0.18367463]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9575653076171875, + 'left_pupil_posn': array([ 0.27438033, -0.1561408 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99682617, 0.02636719, 0.07505798]), + 'right_gaze_origin': array([-3.0929749 , -2.89475274, -0.13123932]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.840576171875, + 'right_pupil_posn': array([-0.18251234, -0.23710382]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.0420210771263, + 'timestamp_carla': 827043, + 'timestamp_device': 3980475, + 'timestamp_stream': 827.0420210771263, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54219803e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-6.01911142e-06, 2.81356552e-05, -6.94252867e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.1699134 ]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([5.35910931e-06, 7.19900697e-07, 1.10388482e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.60620689, 15.29120159, 0.38971514]), + 'camera_rotation': array([-2.81261706, -2.88509345, -1.69700098]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.976806640625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -357.59396362, -5331.48974609, 223.8163147 ]), + 'frame': 25520, + 'frame_number': 25520, + 'framesequence': 98132, + 'gaze_dir': array([0.99634552, 0.04172516, 0.07115936]), + 'gaze_origin': array([-2.90210295, -0.03345184, -0.15499878]), + 'gaze_valid': True, + 'gaze_vergence': 103.42376708984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99661255, 0.05857849, 0.0574646 ]), + 'left_gaze_origin': array([-2.70226455, 2.83401346, -0.18481293]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.046844482421875, + 'left_pupil_posn': array([ 0.2770766 , -0.15169346]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99607849, 0.02487183, 0.08485413]), + 'right_gaze_origin': array([-3.10194111, -2.90091729, -0.12518463]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.86871337890625, + 'right_pupil_posn': array([-0.17798209, -0.23706782]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.0820851773024, + 'timestamp_carla': 827084, + 'timestamp_device': 3980516, + 'timestamp_stream': 827.0820851773024, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55440534e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-2.38772873e-06, 3.02433036e-05, -6.88494993e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16990738]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([ 4.84016709e-06, 5.63103242e-07, -4.34846908e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.64555454, 15.23819923, 0.3777259 ]), + 'camera_rotation': array([-2.94487691, -3.0746541 , -1.78989112]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.810302734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -383.43136597, -5331.49023438, 228.04493713]), + 'frame': 25521, + 'frame_number': 25521, + 'framesequence': 98136, + 'gaze_dir': array([0.99607086, 0.04936981, 0.0699234 ]), + 'gaze_origin': array([-2.89662576, -0.03701401, -0.15771027]), + 'gaze_valid': True, + 'gaze_vergence': 95.51473999023438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99632263, 0.06568909, 0.05476379]), + 'left_gaze_origin': array([-2.67705107, 2.83051467, -0.19424134]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.045166015625, + 'left_pupil_posn': array([ 0.28170717, -0.1530304 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99581909, 0.03305054, 0.08508301]), + 'right_gaze_origin': array([-3.11620045, -2.90454268, -0.1211792 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8712158203125, + 'right_pupil_posn': array([-0.17302203, -0.23819447]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.1162242777646, + 'timestamp_carla': 827118, + 'timestamp_device': 3980550, + 'timestamp_stream': 827.1162242777646, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54402901e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-2.56316412e-06, 4.96770735e-05, -6.86286194e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.33013225, -13.42747879, 0.16993327]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([ 5.27593284e-06, 6.92657181e-07, -1.14619434e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.68597364, 15.20210743, 0.37097451]), + 'camera_rotation': array([-2.95406342, -3.17140269, -1.68167686]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.076416015625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -366.49737549, -5331.49072266, 215.15319824]), + 'frame': 25522, + 'frame_number': 25522, + 'framesequence': 98139, + 'gaze_dir': array([0.99609375, 0.04134369, 0.07644653]), + 'gaze_origin': array([-2.91778207, -0.03476791, -0.1424942 ]), + 'gaze_valid': True, + 'gaze_vergence': 143.6571502685547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99642944, 0.05195618, 0.06634521]), + 'left_gaze_origin': array([-2.70133066, 2.83119822, -0.17920075]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9731903076171875, + 'left_pupil_posn': array([ 0.2808882 , -0.14712489]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99575806, 0.0307312 , 0.08654785]), + 'right_gaze_origin': array([-3.13423324, -2.90073419, -0.10578766]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7823486328125, + 'right_pupil_posn': array([-0.18013823, -0.22679222]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.146129976958, + 'timestamp_carla': 827148, + 'timestamp_device': 3980575, + 'timestamp_stream': 827.146129976958, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.49493388e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 1.12291627e-06, 3.68642177e-05, -6.91585456e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.021772587671875954, + 'Location': array([ -2.33013225, -13.42747879, 0.16991226]), + 'Rotation': array([ 4.84260404e-03, -9.11534424e+01, 6.50199577e-02]), + 'Velocity': array([ 5.12139877e-06, 6.45199293e-07, -1.95897184e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.73011971, 15.19945908, 0.3609502 ]), + 'camera_rotation': array([-2.97789407, -3.07418442, -1.55426311]), + 'current_gear_input': False, + 'focus_actor_dist': 5817.3955078125, + 'focus_actor_name': 'SM_Shop_22', + 'focus_actor_pt': array([ -471.94827271, -7159.12158203, 287.37475586]), + 'frame': 25523, + 'frame_number': 25523, + 'framesequence': 98143, + 'gaze_dir': array([0.9960022 , 0.03947449, 0.07848358]), + 'gaze_origin': array([-2.91157007, -0.03418503, -0.14610444]), + 'gaze_valid': True, + 'gaze_vergence': 148.66421508789062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99623108, 0.05212402, 0.06921387]), + 'left_gaze_origin': array([-2.7092104 , 2.83154154, -0.17616883]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9881744384765625, + 'left_pupil_posn': array([ 0.2794795, -0.1462276]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99577332, 0.02682495, 0.0877533 ]), + 'right_gaze_origin': array([-3.11392999, -2.89991164, -0.11604004]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.773406982421875, + 'right_pupil_posn': array([-0.18071413, -0.22879338]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.1796509772539, + 'timestamp_carla': 827181, + 'timestamp_device': 3980608, + 'timestamp_stream': 827.1796509772539, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.51656338e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.07200217, 0.00147656, -0.00076793]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021768294274806976, + 'FR_Wheel_Angle': 0.02177504636347294, + 'Location': array([ -2.33007979, -13.4268074 , 0.16993031]), + 'Rotation': array([ 5.15679270e-03, -9.11534882e+01, 6.50258288e-02]), + 'Velocity': array([-0.00063424, -0.04116286, 0.00051401]), + 'brake_input': 0.0, + 'camera_location': array([-7.78130531, 15.22509003, 0.34819674]), + 'camera_rotation': array([-2.9460516 , -2.83008385, -1.49281156]), + 'current_gear_input': False, + 'focus_actor_dist': 5817.67919921875, + 'focus_actor_name': 'SM_Shop_22', + 'focus_actor_pt': array([ -472.2644043 , -7159.12207031, 296.00836182]), + 'frame': 25524, + 'frame_number': 25524, + 'framesequence': 98147, + 'gaze_dir': array([0.99591827, 0.03998566, 0.07962036]), + 'gaze_origin': array([-2.91466308, -0.03365403, -0.14469224]), + 'gaze_valid': True, + 'gaze_vergence': 190.19610595703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99591064, 0.05213928, 0.07359314]), + 'left_gaze_origin': array([-2.71484375, 2.83226037, -0.17355043]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9850311279296875, + 'left_pupil_posn': array([ 0.27944756, -0.14629507]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9959259 , 0.02783203, 0.08564758]), + 'right_gaze_origin': array([-3.11448216, -2.89956832, -0.11583405]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.852569580078125, + 'right_pupil_posn': array([-0.18090719, -0.22723675]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.211227376014, + 'timestamp_carla': 827213, + 'timestamp_device': 3980641, + 'timestamp_stream': 827.211227376014, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54284670e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.0773936 , -0.00271673, -0.03188681]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021701550111174583, + 'FR_Wheel_Angle': 0.021688686683773994, + 'Location': array([ -2.3306458 , -13.45765877, 0.16989131]), + 'Rotation': array([ 1.43775474e-02, -9.11632385e+01, 6.51559159e-02]), + 'Velocity': array([-5.91196446e-03, -2.85064906e-01, 2.83837318e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.81318569, 15.26218987, 0.36455321]), + 'camera_rotation': array([-2.84122205, -2.52305698, -1.4432925 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.719482421875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -386.43896484, -5331.49023438, 251.78543091]), + 'frame': 25525, + 'frame_number': 25525, + 'framesequence': 98151, + 'gaze_dir': array([0.99645996, 0.02916718, 0.07744598]), + 'gaze_origin': array([-2.94126534, -0.02540055, -0.13581848]), + 'gaze_valid': True, + 'gaze_vergence': 189.07798767089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99647522, 0.04238892, 0.0723114 ]), + 'left_gaze_origin': array([-2.74091673, 2.84049702, -0.16529542]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9809417724609375, + 'left_pupil_posn': array([ 0.27040172, -0.14669132]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9964447 , 0.01594543, 0.08258057]), + 'right_gaze_origin': array([-3.14161396, -2.89129806, -0.10634156]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8260040283203125, + 'right_pupil_posn': array([-0.18995255, -0.22647643]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.2407218776643, + 'timestamp_carla': 827242, + 'timestamp_device': 3980675, + 'timestamp_stream': 827.2407218776643, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.50176233e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.0027755 , 0.00056109, -0.06249728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021574512124061584, + 'FR_Wheel_Angle': 0.02155967615544796, + 'Location': array([ -2.33264041, -13.55224323, 0.16988082]), + 'Rotation': array([ 1.94796976e-02, -9.11548920e+01, 6.50142357e-02]), + 'Velocity': array([-1.10848164e-02, -5.46036184e-01, 1.66110985e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.82614851, 15.31180382, 0.39158815]), + 'camera_rotation': array([-2.71954203, -2.2100029 , -1.47965121]), + 'current_gear_input': False, + 'focus_actor_dist': 5818.06396484375, + 'focus_actor_name': 'SM_Shop_22', + 'focus_actor_pt': array([ -475.21600342, -7159.12207031, 301.80645752]), + 'frame': 25526, + 'frame_number': 25526, + 'framesequence': 98155, + 'gaze_dir': array([0.996521 , 0.03213501, 0.07448578]), + 'gaze_origin': array([-2.92268777, -0.01990051, -0.1422966 ]), + 'gaze_valid': True, + 'gaze_vergence': 150.54661560058594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99627686, 0.05004883, 0.06997681]), + 'left_gaze_origin': array([-2.74514341, 2.84632421, -0.16293488]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9289703369140625, + 'left_pupil_posn': array([ 0.26599884, -0.14698792]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99676514, 0.01422119, 0.07899475]), + 'right_gaze_origin': array([-3.10023212, -2.88612533, -0.12165833]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8595428466796875, + 'right_pupil_posn': array([-0.19093245, -0.22977901]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.275487177074, + 'timestamp_carla': 827277, + 'timestamp_device': 3980708, + 'timestamp_stream': 827.275487177074, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.51377872e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.06980165, 0.00068086, -0.30929807]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021437298506498337, + 'FR_Wheel_Angle': 0.015119167976081371, + 'Location': array([ -2.33546066, -13.69542313, 0.16990361]), + 'Rotation': array([ 2.39124913e-02, -9.11655121e+01, 6.50160834e-02]), + 'Velocity': array([-1.80544145e-02, -9.05881941e-01, 7.33203895e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.83238649, 15.36091995, 0.40960404]), + 'camera_rotation': array([-2.65304351, -1.96603286, -1.46235073]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.23583984375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -373.94213867, -5331.49072266, 246.14123535]), + 'frame': 25527, + 'frame_number': 25527, + 'framesequence': 98159, + 'gaze_dir': array([0.99628448, 0.02893829, 0.07888031]), + 'gaze_origin': array([-2.91391611, -0.018293 , -0.14680253]), + 'gaze_valid': True, + 'gaze_vergence': 142.86756896972656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99641418, 0.04548645, 0.07116699]), + 'left_gaze_origin': array([-2.73526931, 2.84868336, -0.16908112]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.919464111328125, + 'left_pupil_posn': array([ 0.26364863, -0.14666319]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99615479, 0.01239014, 0.08659363]), + 'right_gaze_origin': array([-3.09256291, -2.8852694 , -0.12452393]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8383636474609375, + 'right_pupil_posn': array([-0.19309646, -0.2297045 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.3084840774536, + 'timestamp_carla': 827310, + 'timestamp_device': 3980741, + 'timestamp_stream': 827.3084840774536, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53441590e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.00159428, 0.00542904, -0.18539275]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.34075356, -13.94040966, 0.1699871 ]), + 'Rotation': array([ 2.04086043e-02, -9.11893005e+01, 6.57923371e-02]), + 'Velocity': array([-2.90660132e-02, -1.13947535e+00, 2.40106572e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.83891487, 15.40625763, 0.41894865]), + 'camera_rotation': array([-2.66130114, -1.79170859, -1.27823269]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.79443359375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -369.99661255, -5331.49023438, 267.97283936]), + 'frame': 25528, + 'frame_number': 25528, + 'framesequence': 98163, + 'gaze_dir': array([0.99634552, 0.02651215, 0.07897186]), + 'gaze_origin': array([-2.91769361, -0.01737595, -0.14580917]), + 'gaze_valid': True, + 'gaze_vergence': 141.24525451660156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99649048, 0.04350281, 0.07139587]), + 'left_gaze_origin': array([-2.74547124, 2.85001993, -0.16571808]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9099273681640625, + 'left_pupil_posn': array([ 0.26194584, -0.14628398]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99620056, 0.00952148, 0.08654785]), + 'right_gaze_origin': array([-3.08991551, -2.88477182, -0.12590027]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.838134765625, + 'right_pupil_posn': array([-0.19413984, -0.23006141]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.3417975790799, + 'timestamp_carla': 827343, + 'timestamp_device': 3980775, + 'timestamp_stream': 827.3417975790799, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54425812e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.08274501, 0.01764171, -0.5331313 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.5067330598831177, + 'FR_Wheel_Angle': -1.628478765487671, + 'Location': array([ -2.34691954, -14.20593452, 0.1701535 ]), + 'Rotation': array([ 8.35332088e-03, -9.12181244e+01, 6.68112934e-02]), + 'Velocity': array([-3.63510996e-02, -1.07076156e+00, 2.81715387e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.84597206, 15.46565247, 0.40713 ]), + 'camera_rotation': array([-2.71715832, -1.68978477, -1.18945611]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.6845703125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -366.49923706, -5331.49023438, 267.19442749]), + 'frame': 25529, + 'frame_number': 25529, + 'framesequence': 98167, + 'gaze_dir': array([0.99648285, 0.02386475, 0.07795715]), + 'gaze_origin': array([-2.92402577, -0.01667786, -0.14308472]), + 'gaze_valid': True, + 'gaze_vergence': 144.41079711914062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99653625, 0.04162598, 0.0717926 ]), + 'left_gaze_origin': array([-2.75564909, 2.85080433, -0.16130677]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.894012451171875, + 'left_pupil_posn': array([ 0.26043177, -0.14611912]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99642944, 0.00610352, 0.0841217 ]), + 'right_gaze_origin': array([-3.0924027 , -2.88416004, -0.12486267]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.854217529296875, + 'right_pupil_posn': array([-0.19520593, -0.22971165]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.3756342791021, + 'timestamp_carla': 827377, + 'timestamp_device': 3980808, + 'timestamp_stream': 827.3756342791021, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54566954e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.03200452, 0.0061345 , -0.89414334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.5855987071990967, + 'FR_Wheel_Angle': -2.6163737773895264, + 'Location': array([ -2.3558383 , -14.44408417, 0.1702594 ]), + 'Rotation': array([ 5.55977365e-03, -9.13651733e+01, 6.73796237e-02]), + 'Velocity': array([-4.99688201e-02, -1.04060388e+00, 3.21044907e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.84975624, 15.52017975, 0.38463971]), + 'camera_rotation': array([-2.74740243, -1.59775877, -1.05534232]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.506591796875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -369.35339355, -5331.49023438, 258.86486816]), + 'frame': 25530, + 'frame_number': 25530, + 'framesequence': 98171, + 'gaze_dir': array([0.99649811, 0.01892853, 0.07939148]), + 'gaze_origin': array([-2.92856979, -0.01614532, -0.1412674 ]), + 'gaze_valid': True, + 'gaze_vergence': 150.81103515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99674988, 0.0349884 , 0.07243347]), + 'left_gaze_origin': array([-2.7636385, 2.8512392, -0.1581894]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.88604736328125, + 'left_pupil_posn': array([ 0.25916874, -0.14478827]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99624634, 0.00286865, 0.08634949]), + 'right_gaze_origin': array([-3.09350133, -2.8835299 , -0.12434541]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8419342041015625, + 'right_pupil_posn': array([-0.19794011, -0.22927463]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.4081749767065, + 'timestamp_carla': 827410, + 'timestamp_device': 3980841, + 'timestamp_stream': 827.4081749767065, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55543492e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.01055072, -0.00569631, -1.81344843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.8481740951538086, + 'FR_Wheel_Angle': -2.7701704502105713, + 'Location': array([ -2.36804461, -14.70104218, 0.17030452]), + 'Rotation': array([ 1.18503775e-02, -9.15822754e+01, 6.70297891e-02]), + 'Velocity': array([-6.38620481e-02, -1.14530182e+00, 2.52151476e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.84940529, 15.57538795, 0.3717171 ]), + 'camera_rotation': array([-2.78528261, -1.4951458 , -0.96094781]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.9765625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -381.9642334 , -5331.49023438, 261.90942383]), + 'frame': 25531, + 'frame_number': 25531, + 'framesequence': 98175, + 'gaze_dir': array([0.9964447 , 0.01552582, 0.08108521]), + 'gaze_origin': array([-2.93346786, -0.01569596, -0.13964616]), + 'gaze_valid': True, + 'gaze_vergence': 166.03428649902344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99668884, 0.03051758, 0.07518005]), + 'left_gaze_origin': array([-2.77044845, 2.85170007, -0.1560486 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.884613037109375, + 'left_pupil_posn': array([ 0.25817478, -0.14441776]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([9.96200562e-01, 5.34057617e-04, 8.69903564e-02]), + 'right_gaze_origin': array([-3.09648752, -2.88309193, -0.12324372]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.83746337890625, + 'right_pupil_posn': array([-0.19977832, -0.22811246]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.4407860785723, + 'timestamp_carla': 827442, + 'timestamp_device': 3980875, + 'timestamp_stream': 827.4407860785723, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55989828e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.02555531, 0.00317017, -2.06305432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.678058624267578, + 'FR_Wheel_Angle': -2.5062355995178223, + 'Location': array([ -2.38346744, -15.00155449, 0.17038585]), + 'Rotation': array([ 2.02788301e-02, -9.19193115e+01, 6.71288446e-02]), + 'Velocity': array([-8.65494981e-02, -1.43449306e+00, 9.04769870e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.84235764, 15.63167 , 0.36653137]), + 'camera_rotation': array([-2.82261658, -1.39827514, -0.86242801]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.291015625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -387.93496704, -5331.48974609, 265.69503784]), + 'frame': 25532, + 'frame_number': 25532, + 'framesequence': 98179, + 'gaze_dir': array([0.99582672, 0.01300812, 0.0880661 ]), + 'gaze_origin': array([-2.94683027, -0.01404877, -0.13642809]), + 'gaze_valid': True, + 'gaze_vergence': 141.2718963623047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99603271, 0.03198242, 0.08299255]), + 'left_gaze_origin': array([-2.78018975, 2.8531878 , -0.15188599]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.873504638671875, + 'left_pupil_posn': array([ 0.25510752, -0.14139187]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99562073, -0.00596619, 0.09313965]), + 'right_gaze_origin': array([-3.11347055, -2.88128519, -0.12097017]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8244171142578125, + 'right_pupil_posn': array([-0.20046782, -0.22712886]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.4753687791526, + 'timestamp_carla': 827477, + 'timestamp_device': 3980908, + 'timestamp_stream': 827.4753687791526, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54658503e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.00317951, -0.00635946, -1.70541084]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.6145707368850708, + 'FR_Wheel_Angle': -1.477590560913086, + 'Location': array([ -2.40731668, -15.44938564, 0.170489 ]), + 'Rotation': array([ 2.68358123e-02, -9.23192673e+01, 6.51943758e-02]), + 'Velocity': array([-1.03856713e-01, -1.83838499e+00, 8.12787970e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.81856918, 15.66294098, 0.37185964]), + 'camera_rotation': array([-2.83670712, -1.30230129, -0.76339245]), + 'current_gear_input': False, + 'focus_actor_dist': 4050.756103515625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -393.021698 , -5392.86181641, 293.24176025]), + 'frame': 25533, + 'frame_number': 25533, + 'framesequence': 98183, + 'gaze_dir': array([0.99591827, 0.01383972, 0.08650208]), + 'gaze_origin': array([-2.95854664, -0.01142731, -0.13125764]), + 'gaze_valid': True, + 'gaze_vergence': 127.52249145507812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9962616 , 0.03379822, 0.07931519]), + 'left_gaze_origin': array([-2.78710032, 2.85591149, -0.14867249]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8595123291015625, + 'left_pupil_posn': array([ 0.25334859, -0.14035809]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99557495, -0.00611877, 0.09368896]), + 'right_gaze_origin': array([-3.12999296, -2.87876606, -0.11384278]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.814178466796875, + 'right_pupil_posn': array([-0.2015512 , -0.22671628]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.5080621764064, + 'timestamp_carla': 827509, + 'timestamp_device': 3980941, + 'timestamp_stream': 827.5080621764064, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55291755e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.00378728, -0.00216323, -1.08753204]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7384377121925354, + 'FR_Wheel_Angle': -0.6608684659004211, + 'Location': array([ -2.43019414, -15.89754868, 0.17066856]), + 'Rotation': array([ 2.97727939e-02, -9.25358505e+01, 6.35297075e-02]), + 'Velocity': array([-1.14498861e-01, -2.20727968e+00, 1.04018208e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.80095863, 15.6857872 , 0.37472221]), + 'camera_rotation': array([-2.84842777, -1.17918456, -0.6114226 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3989.4365234375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -380.32022095, -5332.24951172, 283.57476807]), + 'frame': 25534, + 'frame_number': 25534, + 'framesequence': 98187, + 'gaze_dir': array([0.99611664, 0.01354218, 0.08428955]), + 'gaze_origin': array([-2.96799016, -0.00878754, -0.12731858]), + 'gaze_valid': True, + 'gaze_vergence': 127.79436492919922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99641418, 0.03379822, 0.07754517]), + 'left_gaze_origin': array([-2.78710032, 2.85875106, -0.14736634]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.845489501953125, + 'left_pupil_posn': array([ 0.25124347, -0.1403476 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99581909, -0.00671387, 0.09103394]), + 'right_gaze_origin': array([-3.14888024, -2.87632608, -0.10727081]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.788421630859375, + 'right_pupil_posn': array([-0.20320952, -0.2264626 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.5402913764119, + 'timestamp_carla': 827542, + 'timestamp_device': 3980975, + 'timestamp_stream': 827.5402913764119, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55932599e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.00499643, -0.00927617, -0.41125458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.030544977635145187, + 'FR_Wheel_Angle': 0.12327422201633453, + 'Location': array([ -2.45754194, -16.4583168 , 0.17089421]), + 'Rotation': array([ 3.08246426e-02, -9.26450119e+01, 6.25829622e-02]), + 'Velocity': array([-1.22882240e-01, -2.60038042e+00, 1.29970547e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.7813797 , 15.70175743, 0.36585805]), + 'camera_rotation': array([-2.85262823, -1.11810386, -0.52818727]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.068359375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -371.90185547, -5331.49023438, 273.70541382]), + 'frame': 25535, + 'frame_number': 25535, + 'framesequence': 98191, + 'gaze_dir': array([0.99622345, 0.01583099, 0.08244324]), + 'gaze_origin': array([-2.96737385, -0.00666351, -0.12656938]), + 'gaze_valid': True, + 'gaze_vergence': 123.6778564453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99649048, 0.03657532, 0.07522583]), + 'left_gaze_origin': array([-2.77927732, 2.86046457, -0.14901581]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.838592529296875, + 'left_pupil_posn': array([ 0.25058985, -0.14035809]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99595642, -0.00491333, 0.08966064]), + 'right_gaze_origin': array([-3.15547037, -2.87379146, -0.10412294]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.783111572265625, + 'right_pupil_posn': array([-0.20397615, -0.22641802]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.5740819759667, + 'timestamp_carla': 827576, + 'timestamp_device': 3981008, + 'timestamp_stream': 827.5740819759667, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55089565e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.00405818, 0.00154479, 0.63095218]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.50214684009552, + 'FR_Wheel_Angle': 0.5816442966461182, + 'Location': array([ -2.4836936 , -17.05242348, 0.17110123]), + 'Rotation': array([ 3.02099250e-02, -9.26009293e+01, 6.14844672e-02]), + 'Velocity': array([-1.22567460e-01, -2.94579434e+00, 1.46037096e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.75526619, 15.69641495, 0.34578446]), + 'camera_rotation': array([-2.90820551, -1.08256543, -0.55465233]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.42041015625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -357.95654297, -5331.49023438, 266.00314331]), + 'frame': 25536, + 'frame_number': 25536, + 'framesequence': 98195, + 'gaze_dir': array([0.99607086, 0.01626587, 0.08467865]), + 'gaze_origin': array([-2.96098876, -0.00487824, -0.12773895]), + 'gaze_valid': True, + 'gaze_vergence': 139.1066131591797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99623108, 0.03533936, 0.0791626 ]), + 'left_gaze_origin': array([-2.76650715, 2.86261916, -0.15140535]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8459014892578125, + 'left_pupil_posn': array([ 0.24967647, -0.13940191]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99591064, -0.00280762, 0.0901947 ]), + 'right_gaze_origin': array([-3.15547037, -2.87237549, -0.10407257]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.77783203125, + 'right_pupil_posn': array([-0.2053526, -0.2249589]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.6069194786251, + 'timestamp_carla': 827608, + 'timestamp_device': 3981041, + 'timestamp_stream': 827.6069194786251, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55276482e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.07686561, 0.06483223, 0.38306841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.51194048, -17.76204872, 0.17143387]), + 'Rotation': array([ 2.41310578e-02, -9.24576797e+01, 6.25007600e-02]), + 'Velocity': array([-1.28683433e-01, -3.14919782e+00, 9.13028722e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.73609924, 15.67815399, 0.31504613]), + 'camera_rotation': array([-3.00938129, -1.05905557, -0.51690739]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.464111328125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -353.98867798, -5331.48974609, 271.08959961]), + 'frame': 25537, + 'frame_number': 25537, + 'framesequence': 98199, + 'gaze_dir': array([0.99557495, 0.06324005, 0.06362915]), + 'gaze_origin': array([-2.97292352, -0.05171357, -0.12698288]), + 'gaze_valid': True, + 'gaze_vergence': 68.74068450927734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99577332, 0.08120728, 0.04267883]), + 'left_gaze_origin': array([-2.75367904, 2.81419086, -0.16750643]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8510894775390625, + 'left_pupil_posn': array([ 0.2981174 , -0.14984214]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99537659, 0.04527283, 0.08457947]), + 'right_gaze_origin': array([-3.19216776, -2.91761804, -0.08645935]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6914520263671875, + 'right_pupil_posn': array([-0.15822566, -0.23340869]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.6401772759855, + 'timestamp_carla': 827642, + 'timestamp_device': 3981075, + 'timestamp_stream': 827.6401772759855, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55036154e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.06085116, -0.02631067, 1.53516257]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.687511920928955, + 'FR_Wheel_Angle': 1.8846484422683716, + 'Location': array([ -2.5394547 , -18.46906281, 0.17181839]), + 'Rotation': array([ 4.96554747e-03, -9.23334122e+01, 5.79744503e-02]), + 'Velocity': array([-7.82037750e-02, -2.92444324e+00, 1.25433924e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.71461296, 15.65395546, 0.28883278]), + 'camera_rotation': array([-3.14106727, -1.0440743 , -0.48140615]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.45361328125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -164.13937378, -5331.48974609, 181.71743774]), + 'frame': 25538, + 'frame_number': 25538, + 'framesequence': 98203, + 'gaze_dir': array([0.99205017, 0.11527252, 0.04434967]), + 'gaze_origin': array([-2.91296935, -0.08569717, -0.15940629]), + 'gaze_valid': True, + 'gaze_vergence': 53.65382385253906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99180603, 0.12559509, 0.0229187 ]), + 'left_gaze_origin': array([-2.68656921, 2.7726748 , -0.20239411]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8609466552734375, + 'left_pupil_posn': array([ 0.34483504, -0.16708696]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99229431, 0.10494995, 0.06578064]), + 'right_gaze_origin': array([-3.13936925, -2.94406891, -0.11641847]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6872100830078125, + 'right_pupil_posn': array([-0.12506151, -0.25126839]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.6748728789389, + 'timestamp_carla': 827676, + 'timestamp_device': 3981108, + 'timestamp_stream': 827.6748728789389, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53750603e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.01603843, 0.00625398, 2.24232674]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.561830520629883, + 'FR_Wheel_Angle': 2.7118186950683594, + 'Location': array([ -2.5534749 , -19.11808777, 0.17210381]), + 'Rotation': array([-3.05309449e-03, -9.18843307e+01, 5.69557436e-02]), + 'Velocity': array([-2.47511100e-02, -2.65489411e+00, 8.81404849e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.6959877 , 15.62029076, 0.26649991]), + 'camera_rotation': array([-3.22435451, -1.04007566, -0.54792893]), + 'current_gear_input': False, + 'focus_actor_dist': 3995.88671875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 46.30755615, -5331.48925781, 97.79663086]), + 'frame': 25539, + 'frame_number': 25539, + 'framesequence': 98207, + 'gaze_dir': array([0.99163818, 0.11855316, 0.04405212]), + 'gaze_origin': array([-2.90566802, -0.08598939, -0.16039582]), + 'gaze_valid': True, + 'gaze_vergence': 50.86631393432617, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99133301, 0.1295929 , 0.02134705]), + 'left_gaze_origin': array([-2.68651438, 2.77343011, -0.20171204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9205474853515625, + 'left_pupil_posn': array([ 0.34518862, -0.16644597]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99194336, 0.10751343, 0.0667572 ]), + 'right_gaze_origin': array([-3.12482166, -2.94540882, -0.11907959]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7021484375, + 'right_pupil_posn': array([-0.12284303, -0.25087678]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 827.7071438767016, + 'timestamp_carla': 827709, + 'timestamp_device': 3981141, + 'timestamp_stream': 827.7071438767016, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54841601e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.02946352, 0.003415 , 2.57502246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.1660900115966797, + 'FR_Wheel_Angle': 3.422785997390747, + 'Location': array([ -2.55766821, -19.72127914, 0.17223293]), + 'Rotation': array([-8.60603806e-03, -9.13237076e+01, 5.99493422e-02]), + 'Velocity': array([ 1.46690672e-02, -2.40131640e+00, -2.60705943e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.6820612 , 15.58352852, 0.2555317 ]), + 'camera_rotation': array([-3.283463 , -1.0377382, -0.6178714]), + 'current_gear_input': False, + 'focus_actor_dist': 3996.969482421875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 59.61239624, -5331.49023438, 91.5388031 ]), + 'frame': 25540, + 'frame_number': 25540, + 'framesequence': 98211, + 'gaze_dir': array([0.99163818, 0.11821747, 0.04515076]), + 'gaze_origin': array([-2.90323806, -0.08657837, -0.16039582]), + 'gaze_valid': True, + 'gaze_vergence': 48.57170104980469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99145508, 0.12846375, 0.02243042]), + 'left_gaze_origin': array([-2.68786478, 2.77385116, -0.20079194]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9210052490234375, + 'left_pupil_posn': array([ 0.34509289, -0.16572785]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99182129, 0.10797119, 0.06787109]), + 'right_gaze_origin': array([-3.11861134, -2.94700789, -0.11999971]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7095184326171875, + 'right_pupil_posn': array([-0.12217474, -0.24989438]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.7406899780035, + 'timestamp_carla': 827742, + 'timestamp_device': 3981174, + 'timestamp_stream': 827.7406899780035, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54547862e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02310945, -0.00358168, 3.2491529 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.570594310760498, + 'FR_Wheel_Angle': 4.99777364730835, + 'Location': array([ -2.55190229, -20.24690819, 0.17226623]), + 'Rotation': array([-1.45551320e-02, -9.06696396e+01, 5.80467582e-02]), + 'Velocity': array([ 6.77395836e-02, -2.17765808e+00, -1.42898556e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.67069626, 15.54646301, 0.2512925 ]), + 'camera_rotation': array([-3.25940704, -1.02305114, -0.68570083]), + 'current_gear_input': False, + 'focus_actor_dist': 3996.82763671875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 58.10452271, -5331.49023438, 92.38666534]), + 'frame': 25541, + 'frame_number': 25541, + 'framesequence': 98215, + 'gaze_dir': array([0.99172211, 0.11804199, 0.04447937]), + 'gaze_origin': array([-2.90354252, -0.08697968, -0.1597992 ]), + 'gaze_valid': True, + 'gaze_vergence': 53.16963195800781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99147034, 0.12814331, 0.02311707]), + 'left_gaze_origin': array([-2.68859887, 2.77424479, -0.19956362]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.91192626953125, + 'left_pupil_posn': array([ 0.34483504, -0.16572785]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99197388, 0.10794067, 0.06584167]), + 'right_gaze_origin': array([-3.11848617, -2.94820428, -0.12003479]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.72564697265625, + 'right_pupil_posn': array([-0.12147737, -0.24968028]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.773920878768, + 'timestamp_carla': 827775, + 'timestamp_device': 3981208, + 'timestamp_stream': 827.773920878768, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54547862e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([1.92415584e-02, 3.15306475e-03, 3.99500656e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.9040727615356445, + 'FR_Wheel_Angle': 6.475512981414795, + 'Location': array([ -2.5313077 , -20.79584885, 0.17228352]), + 'Rotation': array([-2.02651694e-02, -8.97008209e+01, 5.75338006e-02]), + 'Velocity': array([ 1.24884412e-01, -1.94253600e+00, -1.08871456e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.69264317, 15.4784317 , 0.25976208]), + 'camera_rotation': array([-3.24073339, -1.03309524, -0.76165652]), + 'current_gear_input': False, + 'focus_actor_dist': 3996.83154296875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 58.18066406, -5331.49023438, 91.8996582 ]), + 'frame': 25542, + 'frame_number': 25542, + 'framesequence': 98219, + 'gaze_dir': array([0.9916687 , 0.1184082 , 0.04457092]), + 'gaze_origin': array([-2.90327549, -0.08712388, -0.15948334]), + 'gaze_valid': True, + 'gaze_vergence': 55.878963470458984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99133301, 0.12921143, 0.02336121]), + 'left_gaze_origin': array([-2.6905961 , 2.77483988, -0.19853516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9114837646484375, + 'left_pupil_posn': array([ 0.34437239, -0.16543925]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99200439, 0.10760498, 0.06578064]), + 'right_gaze_origin': array([-3.11595488, -2.94908762, -0.12043152]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7379302978515625, + 'right_pupil_posn': array([-0.12051809, -0.24941826]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.8064621761441, + 'timestamp_carla': 827808, + 'timestamp_device': 3981241, + 'timestamp_stream': 827.8064621761441, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55066655e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.01755271, 0.00910955, 4.32845736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.157962322235107, + 'FR_Wheel_Angle': 7.871467113494873, + 'Location': array([ -2.50293303, -21.21981621, 0.17229743]), + 'Rotation': array([-2.43564527e-02, -8.87348328e+01, 5.78960292e-02]), + 'Velocity': array([ 1.67124555e-01, -1.75924969e+00, -1.05123516e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.69894409, 15.43971634, 0.26457098]), + 'camera_rotation': array([-3.27113461, -1.05081034, -0.81817108]), + 'current_gear_input': False, + 'focus_actor_dist': 3996.873046875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 58.64453125, -5331.49023438, 94.21845245]), + 'frame': 25543, + 'frame_number': 25543, + 'framesequence': 98223, + 'gaze_dir': array([0.99169922, 0.11789703, 0.0455246 ]), + 'gaze_origin': array([-2.90283442, -0.0878563 , -0.1597725 ]), + 'gaze_valid': True, + 'gaze_vergence': 55.13671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99145508, 0.12802124, 0.02462769]), + 'left_gaze_origin': array([-2.6905961 , 2.77483988, -0.19853516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.937103271484375, + 'left_pupil_posn': array([ 0.34442413, -0.1652844 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99194336, 0.10777283, 0.06642151]), + 'right_gaze_origin': array([-3.11507273, -2.95055246, -0.12100983]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.73822021484375, + 'right_pupil_posn': array([-0.11993438, -0.24919176]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.8405775763094, + 'timestamp_carla': 827842, + 'timestamp_device': 3981274, + 'timestamp_stream': 827.8405775763094, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54170210e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.02278244, 0.01537271, 3.18043256]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.576066017150879, + 'FR_Wheel_Angle': 8.177218437194824, + 'Location': array([ -2.46700549, -21.60813141, 0.17231189]), + 'Rotation': array([-3.10978498e-02, -8.77151794e+01, 6.15129881e-02]), + 'Velocity': array([ 1.78674087e-01, -1.51893735e+00, 1.64318080e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.69883919, 15.39804649, 0.24374121]), + 'camera_rotation': array([-3.31485462, -1.06604135, -0.85383266]), + 'current_gear_input': False, + 'focus_actor_dist': 3996.576904296875, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 55.05596924, -5331.49023438, 96.35844421]), + 'frame': 25544, + 'frame_number': 25544, + 'framesequence': 98227, + 'gaze_dir': array([0.99170685, 0.11834717, 0.04402161]), + 'gaze_origin': array([-2.90152979, -0.08954774, -0.15783387]), + 'gaze_valid': True, + 'gaze_vergence': 54.04092025756836, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99143982, 0.12854004, 0.02278137]), + 'left_gaze_origin': array([-2.68520975, 2.77443552, -0.19907837]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.93829345703125, + 'left_pupil_posn': array([ 0.34469151, -0.16501105]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99197388, 0.1081543 , 0.06526184]), + 'right_gaze_origin': array([-3.11784983, -2.95353103, -0.11658936]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.747467041015625, + 'right_pupil_posn': array([-0.11768317, -0.24739003]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.8734459765255, + 'timestamp_carla': 827875, + 'timestamp_device': 3981308, + 'timestamp_stream': 827.8734459765255, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54597455e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([1.82097615e-03, 2.84808455e-03, 2.65090179e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.603927135467529, + 'FR_Wheel_Angle': 8.206141471862793, + 'Location': array([ -2.43510985, -21.89997482, 0.17230418]), + 'Rotation': array([-3.32630202e-02, -8.69465561e+01, 6.34096488e-02]), + 'Velocity': array([ 1.79334924e-01, -1.36232662e+00, -2.08892816e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.72265053, 15.36783218, 0.24775252]), + 'camera_rotation': array([-3.31461549, -1.08883429, -0.92848915]), + 'current_gear_input': False, + 'focus_actor_dist': 3996.726318359375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 55.74151611, -5331.49023438, 87.62937164]), + 'frame': 25545, + 'frame_number': 25545, + 'framesequence': 98231, + 'gaze_dir': array([0.9914093 , 0.12033844, 0.04524994]), + 'gaze_origin': array([-2.88805556, -0.09017487, -0.16262208]), + 'gaze_valid': True, + 'gaze_vergence': 62.03446960449219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9908905 , 0.13233948, 0.02474976]), + 'left_gaze_origin': array([-2.67988157, 2.77392912, -0.20005493]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9536285400390625, + 'left_pupil_posn': array([ 0.34495449, -0.16450441]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9919281 , 0.1083374 , 0.06575012]), + 'right_gaze_origin': array([-3.09622979, -2.95427871, -0.12518921]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.795745849609375, + 'right_pupil_posn': array([-0.11603487, -0.24846637]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.907735478133, + 'timestamp_carla': 827909, + 'timestamp_device': 3981341, + 'timestamp_stream': 827.907735478133, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53765877e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.0050917 , -0.00857148, 2.69757915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.891642093658447, + 'FR_Wheel_Angle': 8.730058670043945, + 'Location': array([ -2.39219332, -22.24360466, 0.1723011 ]), + 'Rotation': array([-3.28327194e-02, -8.60290451e+01, 6.35858104e-02]), + 'Velocity': array([ 1.90837279e-01, -1.26549232e+00, 2.81653396e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.72437286, 15.3382225 , 0.24466729]), + 'camera_rotation': array([-3.2485745 , -1.11328387, -1.08627546]), + 'current_gear_input': False, + 'focus_actor_dist': 3997.1640625, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 61.8380127 , -5331.49023438, 93.34468079]), + 'frame': 25546, + 'frame_number': 25546, + 'framesequence': 98235, + 'gaze_dir': array([0.99825287, 0.05349731, 0.00351715]), + 'gaze_origin': array([-2.99109268, -0.04813233, -0.14598846]), + 'gaze_valid': True, + 'gaze_vergence': 113.10224151611328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99697876, 0.076828 , 0.01002502]), + 'left_gaze_origin': array([-2.85245371, 2.81503916, -0.15615235]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0948028564453125, + 'left_pupil_posn': array([ 0.29447925, -0.19109547]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99952698, 0.03016663, -0.00299072]), + 'right_gaze_origin': array([-3.12973189, -2.911304 , -0.13582459]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8712158203125, + 'right_pupil_posn': array([-0.16502351, -0.26679552]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.9410850778222, + 'timestamp_carla': 827943, + 'timestamp_device': 3981374, + 'timestamp_stream': 827.9410850778222, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54032887e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.0199528 , -0.01451812, 3.20051455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.369017601013184, + 'FR_Wheel_Angle': 10.54833984375, + 'Location': array([ -2.34977365, -22.52908707, 0.17220126]), + 'Rotation': array([-3.04011703e-02, -8.51600266e+01, 6.05778769e-02]), + 'Velocity': array([ 2.25015610e-01, -1.23321497e+00, -5.42583468e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.71270847, 15.31672192, 0.24674763]), + 'camera_rotation': array([-3.28056026, -1.10407829, -1.00130916]), + 'current_gear_input': False, + 'focus_actor_dist': 2255.20458984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -229.29231262, -3599.39746094, 16.98475647]), + 'frame': 25547, + 'frame_number': 25547, + 'framesequence': 98239, + 'gaze_dir': array([ 0.99960327, 0.01503754, -0.02037811]), + 'gaze_origin': array([-2.92356277, -0.00795517, -0.200486 ]), + 'gaze_valid': True, + 'gaze_vergence': 191.71885681152344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99931335, 0.02478027, -0.02749634]), + 'left_gaze_origin': array([-2.73547077, 2.8480227 , -0.22321779]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9790802001953125, + 'left_pupil_posn': array([ 0.26197386, -0.21659625]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99989319, 0.0052948 , -0.01325989]), + 'right_gaze_origin': array([-3.111655 , -2.86393285, -0.17775422]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8365325927734375, + 'right_pupil_posn': array([-0.21639997, -0.30463588]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 827.9742189757526, + 'timestamp_carla': 827976, + 'timestamp_device': 3981408, + 'timestamp_stream': 827.9742189757526, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54357127e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.0238892 , -0.01834232, 4.10279131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.717765808105469, + 'FR_Wheel_Angle': 12.171272277832031, + 'Location': array([ -2.3036809 , -22.78950691, 0.17207588]), + 'Rotation': array([-2.59752087e-02, -8.42293472e+01, 5.81480861e-02]), + 'Velocity': array([ 2.75531977e-01, -1.29431343e+00, -1.95789326e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.72284698, 15.29883766, 0.25466275]), + 'camera_rotation': array([-3.29491043, -1.08376431, -1.02963531]), + 'current_gear_input': False, + 'focus_actor_dist': 1517.8798828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -297.00497437, -2860.45336914, 17.05883026]), + 'frame': 25548, + 'frame_number': 25548, + 'framesequence': 98243, + 'gaze_dir': array([ 0.9996109 , 0.01081848, -0.02351379]), + 'gaze_origin': array([-2.92035389, -0.00786514, -0.20109406]), + 'gaze_valid': True, + 'gaze_vergence': 294.9725036621094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99951172, 0.02049255, -0.02352905]), + 'left_gaze_origin': array([-2.72835398, 2.84890151, -0.22470094]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0528411865234375, + 'left_pupil_posn': array([ 0.25988364, -0.21963823]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99971008, 0.00114441, -0.02349854]), + 'right_gaze_origin': array([-3.11235356, -2.86463189, -0.17748719]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.86798095703125, + 'right_pupil_posn': array([-0.21738738, -0.30315852]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.0071725770831, + 'timestamp_carla': 828009, + 'timestamp_device': 3981441, + 'timestamp_stream': 828.0071725770831, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54677595e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.03868173, -0.02869402, 7.25834274]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.651402473449707, + 'FR_Wheel_Angle': 13.24319076538086, + 'Location': array([ -2.2298553 , -23.14333725, 0.17191997]), + 'Rotation': array([-1.84961520e-02, -8.27839050e+01, 5.36250509e-02]), + 'Velocity': array([ 3.84075642e-01, -1.52860820e+00, 1.25083927e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.72815323, 15.29542637, 0.23503652]), + 'camera_rotation': array([-3.29127669, -1.08749712, -1.14497459]), + 'current_gear_input': False, + 'focus_actor_dist': 1453.1231689453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -300.98150635, -2795.36181641, 17.06330872]), + 'frame': 25549, + 'frame_number': 25549, + 'framesequence': 98247, + 'gaze_dir': array([ 0.99965668, 0.01186371, -0.02203369]), + 'gaze_origin': array([-2.91757059, -0.00815887, -0.20200805]), + 'gaze_valid': True, + 'gaze_vergence': 400.8249206542969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9995575 , 0.01885986, -0.02297974]), + 'left_gaze_origin': array([-2.7243228 , 2.84915781, -0.22593385]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0350341796875, + 'left_pupil_posn': array([ 0.26088762, -0.21882069]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99975586, 0.00486755, -0.02108765]), + 'right_gaze_origin': array([-3.11081862, -2.86547565, -0.17808229]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.927978515625, + 'right_pupil_posn': array([-0.21738738, -0.30315852]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.0415269769728, + 'timestamp_carla': 828043, + 'timestamp_device': 3981474, + 'timestamp_stream': 828.0415269769728, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53784922e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.01074882, -0.02050898, 8.75211906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.162311553955078, + 'FR_Wheel_Angle': 13.819311141967773, + 'Location': array([ -2.14861393, -23.47861481, 0.17176166]), + 'Rotation': array([-1.34896226e-02, -8.13146286e+01, 4.94250022e-02]), + 'Velocity': array([ 5.08642912e-01, -1.79222119e+00, -6.65578817e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.73155689, 15.28868294, 0.2254924 ]), + 'camera_rotation': array([-3.25929785, -1.12325025, -1.08184707]), + 'current_gear_input': False, + 'focus_actor_dist': 1481.957275390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -300.31192017, -2824.31640625, 17.06246948]), + 'frame': 25550, + 'frame_number': 25550, + 'framesequence': 98251, + 'gaze_dir': array([ 0.99964905, 0.0121994 , -0.02271271]), + 'gaze_origin': array([-2.91271925, -0.00871124, -0.20248795]), + 'gaze_valid': True, + 'gaze_vergence': 477.55096435546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99954224, 0.01748657, -0.02464294]), + 'left_gaze_origin': array([-2.72182465, 2.84930754, -0.22664186]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0511932373046875, + 'left_pupil_posn': array([ 0.26143956, -0.21874583]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99975586, 0.00691223, -0.02078247]), + 'right_gaze_origin': array([-3.10361338, -2.86672997, -0.17833406]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9225921630859375, + 'right_pupil_posn': array([-0.21698135, -0.30246425]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.0736976787448, + 'timestamp_carla': 828075, + 'timestamp_device': 3981508, + 'timestamp_stream': 828.0736976787448, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54887375e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 7.66086206e-03, -1.71345174e-02, 9.21503544e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.510346412658691, + 'FR_Wheel_Angle': 14.259571075439453, + 'Location': array([ -2.01232171, -23.96487236, 0.17149737]), + 'Rotation': array([-1.19938115e-02, -7.90908890e+01, 4.41596434e-02]), + 'Velocity': array([ 7.01148808e-01, -2.12186384e+00, -1.61485665e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.7223053 , 15.29000664, 0.21717709]), + 'camera_rotation': array([-3.23208642, -1.11472642, -1.1119386 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1479.4141845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -300.69033813, -2821.75683594, 17.06286621]), + 'frame': 25551, + 'frame_number': 25551, + 'framesequence': 98255, + 'gaze_dir': array([ 0.99968719, 0.01271057, -0.02067566]), + 'gaze_origin': array([-2.91053343, -0.00950241, -0.2029053 ]), + 'gaze_valid': True, + 'gaze_vergence': 600.6534423828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99961853, 0.01741028, -0.02122498]), + 'left_gaze_origin': array([-2.71987629, 2.84934545, -0.22699741]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0676727294921875, + 'left_pupil_posn': array([ 0.26175082, -0.21839726]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99975586, 0.00801086, -0.02012634]), + 'right_gaze_origin': array([-3.10119033, -2.86835051, -0.17881317]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91827392578125, + 'right_pupil_posn': array([-0.21586168, -0.30107868]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.1081140786409, + 'timestamp_carla': 828110, + 'timestamp_device': 3981541, + 'timestamp_stream': 828.1081140786409, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53853607e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02364109, -0.02386048, 11.23124695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.986273765563965, + 'FR_Wheel_Angle': 14.935860633850098, + 'Location': array([ -1.8589164 , -24.43642235, 0.17132214]), + 'Rotation': array([-1.22328680e-02, -7.68383560e+01, 3.82183045e-02]), + 'Velocity': array([ 9.06501532e-01, -2.39558029e+00, -9.92460176e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.72028065, 15.29859352, 0.21886513]), + 'camera_rotation': array([-3.26923561, -1.12234592, -1.10587764]), + 'current_gear_input': False, + 'focus_actor_dist': 1527.9345703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -301.04571533, -2870.4453125 , 17.06292725]), + 'frame': 25552, + 'frame_number': 25552, + 'framesequence': 98259, + 'gaze_dir': array([ 0.99963379, 0.01528931, -0.02128601]), + 'gaze_origin': array([-2.90744781, -0.01010284, -0.2034256 ]), + 'gaze_valid': True, + 'gaze_vergence': 493.4302978515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99952698, 0.02098083, -0.02203369]), + 'left_gaze_origin': array([-2.71694493, 2.84924173, -0.22752228]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0478973388671875, + 'left_pupil_posn': array([ 0.26229596, -0.2182821 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9997406 , 0.00959778, -0.02053833]), + 'right_gaze_origin': array([-3.09795094, -2.86944747, -0.17932893]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8938140869140625, + 'right_pupil_posn': array([-0.21385801, -0.30105925]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.1393576785922, + 'timestamp_carla': 828141, + 'timestamp_device': 3981574, + 'timestamp_stream': 828.1393576785922, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55516810e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.07994699, 0.04640805, 12.11681175]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.472251892089844, + 'FR_Wheel_Angle': 15.541440963745117, + 'Location': array([ -1.65025294, -24.98526382, 0.17115185]), + 'Rotation': array([-2.86526419e-02, -7.40561752e+01, 3.79964821e-02]), + 'Velocity': array([ 1.02487981e+00, -2.30819368e+00, -1.05610373e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.6943779 , 15.30368996, 0.22221039]), + 'camera_rotation': array([-3.27576542, -1.1080029 , -1.0563432 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1504.32861328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -296.71725464, -2846.875 , 17.05862427]), + 'frame': 25553, + 'frame_number': 25553, + 'framesequence': 98263, + 'gaze_dir': array([ 0.99962616, 0.01525116, -0.02165222]), + 'gaze_origin': array([-2.90325856, -0.01055679, -0.20452195]), + 'gaze_valid': True, + 'gaze_vergence': 502.5516357421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99951172, 0.02064514, -0.0229187 ]), + 'left_gaze_origin': array([-2.71354079, 2.84915185, -0.22858581]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0488433837890625, + 'left_pupil_posn': array([ 0.2623868, -0.2182672]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9997406 , 0.00985718, -0.02038574]), + 'right_gaze_origin': array([-3.09297657, -2.87026548, -0.18045808]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8502960205078125, + 'right_pupil_posn': array([-0.21339601, -0.30105925]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.1738317757845, + 'timestamp_carla': 828175, + 'timestamp_device': 3981608, + 'timestamp_stream': 828.1738317757845, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54132073e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02983039, 0.03507731, 11.44614697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.753149032592773, + 'FR_Wheel_Angle': 15.856302261352539, + 'Location': array([ -1.4274286 , -25.4884491 , 0.17090747]), + 'Rotation': array([-4.33033966e-02, -7.13520966e+01, 4.33892198e-02]), + 'Velocity': array([ 1.04593575e+00, -2.05928540e+00, -1.20402337e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.68619061, 15.3094368 , 0.22596988]), + 'camera_rotation': array([-3.28989697, -1.11021125, -1.03088784]), + 'current_gear_input': False, + 'focus_actor_dist': 1494.9185791015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -296.18786621, -2837.47583008, 17.05813599]), + 'frame': 25554, + 'frame_number': 25554, + 'framesequence': 98267, + 'gaze_dir': array([ 0.99960327, 0.01521301, -0.02285004]), + 'gaze_origin': array([-2.90155196, -0.01114273, -0.20490037]), + 'gaze_valid': True, + 'gaze_vergence': 449.3487548828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99946594, 0.02049255, -0.0252533 ]), + 'left_gaze_origin': array([-2.7121172 , 2.84915185, -0.22901155]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.040496826171875, + 'left_pupil_posn': array([ 0.2623868, -0.2182821]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9997406 , 0.00993347, -0.02044678]), + 'right_gaze_origin': array([-3.09098673, -2.87143707, -0.18078919]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7872161865234375, + 'right_pupil_posn': array([-0.21263933, -0.30161631]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.2073640786111, + 'timestamp_carla': 828209, + 'timestamp_device': 3981641, + 'timestamp_stream': 828.2073640786111, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54132073e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([6.56889519e-03, 1.84361581e-02, 1.06827364e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.948094367980957, + 'FR_Wheel_Angle': 16.07763671875, + 'Location': array([ -1.19605553, -25.94874954, 0.17066853]), + 'Rotation': array([-4.88631688e-02, -6.87743225e+01, 4.69701365e-02]), + 'Velocity': array([ 1.03711903e+00, -1.81937969e+00, -1.66151044e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.6723938 , 15.32761478, 0.21372128]), + 'camera_rotation': array([-3.30934262, -1.10920501, -1.06967688]), + 'current_gear_input': False, + 'focus_actor_dist': 1467.841064453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -295.62915039, -2810.32836914, 17.05771637]), + 'frame': 25555, + 'frame_number': 25555, + 'framesequence': 98271, + 'gaze_dir': array([ 0.99961853, 0.01496887, -0.0220108 ]), + 'gaze_origin': array([-2.89950585, -0.01174393, -0.20564957]), + 'gaze_valid': True, + 'gaze_vergence': 329.281494140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99945068, 0.02011108, -0.02630615]), + 'left_gaze_origin': array([-2.71024656, 2.84924316, -0.23029177]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.009613037109375, + 'left_pupil_posn': array([ 0.2622484 , -0.21777678]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99978638, 0.00982666, -0.01771545]), + 'right_gaze_origin': array([-3.08876514, -2.87273121, -0.1810074 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7377166748046875, + 'right_pupil_posn': array([-0.21187228, -0.30161631]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.2402515783906, + 'timestamp_carla': 828242, + 'timestamp_device': 3981674, + 'timestamp_stream': 828.2402515783906, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54585999e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([1.91125378e-04, 9.29042324e-03, 9.17163372e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.981162071228027, + 'FR_Wheel_Angle': 16.121675491333008, + 'Location': array([ -0.94912314, -26.3879261 , 0.17036773]), + 'Rotation': array([-5.06868325e-02, -6.62262650e+01, 5.01626208e-02]), + 'Velocity': array([ 1.00711477e+00, -1.59370482e+00, -1.41755096e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.65779781, 15.3363266 , 0.19314581]), + 'camera_rotation': array([-3.34072733, -1.08724439, -1.0642643 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1477.0081787109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -296.16708374, -2819.53125 , 17.05821228]), + 'frame': 25556, + 'frame_number': 25556, + 'framesequence': 98275, + 'gaze_dir': array([ 0.99963379, 0.01410675, -0.02197266]), + 'gaze_origin': array([-2.89637089, -0.01167221, -0.20624085]), + 'gaze_valid': True, + 'gaze_vergence': 461.767578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99951172, 0.01974487, -0.02375793]), + 'left_gaze_origin': array([-2.70516229, 2.8501451 , -0.23135224]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9802398681640625, + 'left_pupil_posn': array([ 0.26109552, -0.2182672 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99975586, 0.00846863, -0.02018738]), + 'right_gaze_origin': array([-3.08757949, -2.87348938, -0.18112946]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7068328857421875, + 'right_pupil_posn': array([-0.21145034, -0.300493 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.2735293768346, + 'timestamp_carla': 828275, + 'timestamp_device': 3981708, + 'timestamp_stream': 828.2735293768346, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54585999e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([4.19531134e-04, 1.35343084e-02, 7.02528906e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.640499114990234, + 'FR_Wheel_Angle': 15.561671257019043, + 'Location': array([ -0.73912382, -26.72980499, 0.1702124 ]), + 'Rotation': array([-5.59392460e-02, -6.41954575e+01, 5.56910820e-02]), + 'Velocity': array([ 8.87062073e-01, -1.30967939e+00, -7.40833289e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.65559673, 15.34834194, 0.18772712]), + 'camera_rotation': array([-3.37930417, -1.10605872, -1.06159306]), + 'current_gear_input': False, + 'focus_actor_dist': 1467.0408935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -296.62695312, -2809.53710938, 17.0587616 ]), + 'frame': 25557, + 'frame_number': 25557, + 'framesequence': 98279, + 'gaze_dir': array([ 0.99970245, 0.0158844 , -0.01689148]), + 'gaze_origin': array([-2.89533782, -0.01153641, -0.206131 ]), + 'gaze_valid': True, + 'gaze_vergence': 473.2353515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99961853, 0.0218811 , -0.0164032 ]), + 'left_gaze_origin': array([-2.7030549 , 2.85111713, -0.23147281]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.981903076171875, + 'left_pupil_posn': array([ 0.26088393, -0.2169801 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99978638, 0.0098877 , -0.01737976]), + 'right_gaze_origin': array([-3.08762074, -2.87419009, -0.18078919]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.671844482421875, + 'right_pupil_posn': array([-0.21015793, -0.29758143]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.3065116778016, + 'timestamp_carla': 828308, + 'timestamp_device': 3981741, + 'timestamp_stream': 828.3065116778016, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54784371e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.14840269, -0.19220023, -0.0004236 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.10262680053711, + 'FR_Wheel_Angle': 14.837804794311523, + 'Location': array([ -0.65066117, -26.86802101, 0.17044185]), + 'Rotation': array([ -0.11227465, -63.3433075 , 0.0854452 ]), + 'Velocity': array([-9.20689999e-05, 1.28221684e-04, 1.28486310e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.6405468 , 15.34660912, 0.17933154]), + 'camera_rotation': array([-3.41241693, -1.10383034, -1.02410495]), + 'current_gear_input': False, + 'focus_actor_dist': 1553.1268310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -296.63684082, -2895.91113281, 17.05822754]), + 'frame': 25558, + 'frame_number': 25558, + 'framesequence': 98283, + 'gaze_dir': array([0.99974823, 0.01131439, 0.0066452 ]), + 'gaze_origin': array([-2.88309193, -0.0090889 , -0.19464722]), + 'gaze_valid': True, + 'gaze_vergence': 159.00753784179688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99957275, 0.02883911, 0.00370789]), + 'left_gaze_origin': array([-2.66692519, 2.85338759, -0.22708741]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.891204833984375, + 'left_pupil_posn': array([ 0.25326443, -0.19771123]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99992371, -0.00621033, 0.00958252]), + 'right_gaze_origin': array([-3.09925866, -2.87156534, -0.16220704]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.775726318359375, + 'right_pupil_posn': array([-0.20923144, -0.28024018]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.3397795781493, + 'timestamp_carla': 828341, + 'timestamp_device': 3981774, + 'timestamp_stream': 828.3397795781493, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54673776e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.09303971, -0.09393542, -0.000258 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.679990768432617, + 'FR_Wheel_Angle': 14.384085655212402, + 'Location': array([ -0.65040344, -26.86825943, 0.17013443]), + 'Rotation': array([-6.23459630e-02, -6.33436012e+01, 6.73832819e-02]), + 'Velocity': array([-4.74148146e-05, 7.46036385e-05, -2.22893475e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.61951447, 15.35117912, 0.18276818]), + 'camera_rotation': array([-3.41493058, -1.12797511, -1.00587988]), + 'current_gear_input': False, + 'focus_actor_dist': 2226.70068359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -323.38549805, -3570.38671875, 17.08165741]), + 'frame': 25559, + 'frame_number': 25559, + 'framesequence': 98287, + 'gaze_dir': array([0.9957428 , 0.00737 , 0.09013367]), + 'gaze_origin': array([-2.92032313, -0.00838623, -0.13233033]), + 'gaze_valid': True, + 'gaze_vergence': 151.61561584472656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99623108, 0.02348328, 0.0834198 ]), + 'left_gaze_origin': array([-2.74836731, 2.84949064, -0.14874879]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.927734375, + 'left_pupil_posn': array([ 0.25608969, -0.13220358]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99525452, -0.00874329, 0.09684753]), + 'right_gaze_origin': array([-3.0922792 , -2.86626291, -0.11591187]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7998504638671875, + 'right_pupil_posn': array([-0.21354973, -0.21918499]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.373364277184, + 'timestamp_carla': 828375, + 'timestamp_device': 3981808, + 'timestamp_stream': 828.373364277184, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54360945e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.02235233, -0.02432103, 0.06387302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.546736717224121, + 'FR_Wheel_Angle': 14.24604606628418, + 'Location': array([ -0.64932156, -26.86987686, 0.17003928]), + 'Rotation': array([-4.64179628e-02, -6.33354683e+01, 6.16987422e-02]), + 'Velocity': array([ 7.77154649e-03, -1.13296434e-02, 3.05643334e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.60782909, 15.35907555, 0.18437833]), + 'camera_rotation': array([-3.42346144, -1.13350725, -1.05997384]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.05322265625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -396.05487061, -5331.49023438, 257.40527344]), + 'frame': 25560, + 'frame_number': 25560, + 'framesequence': 98291, + 'gaze_dir': array([0.99663544, 0.00862885, 0.0790329 ]), + 'gaze_origin': array([-2.9212029 , -0.00940094, -0.13439102]), + 'gaze_valid': True, + 'gaze_vergence': 143.46728515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99671936, 0.02806091, 0.07582092]), + 'left_gaze_origin': array([-2.75707722, 2.85239887, -0.1478058 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.89630126953125, + 'left_pupil_posn': array([ 0.25362337, -0.13806844]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99655151, -0.01080322, 0.08224487]), + 'right_gaze_origin': array([-3.08532882, -2.87120056, -0.12097626]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8284454345703125, + 'right_pupil_posn': array([-0.20868456, -0.22407031]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.4077262766659, + 'timestamp_carla': 828409, + 'timestamp_device': 3981841, + 'timestamp_stream': 828.4077262766659, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53590369e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.00482038, -0.00619378, 0.07231505]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.546516418457031, + 'FR_Wheel_Angle': 14.245874404907227, + 'Location': array([ -0.64749455, -26.87268448, 0.17001197]), + 'Rotation': array([-4.29687165e-02, -6.33206329e+01, 6.02950640e-02]), + 'Velocity': array([ 0.00842939, -0.0122872 , -0.00018217]), + 'brake_input': 0.0, + 'camera_location': array([-7.60789108, 15.35599709, 0.17941573]), + 'camera_rotation': array([-3.43070817, -1.15233576, -1.09531426]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.7392578125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -390.98995972, -5331.49023438, 212.4929657 ]), + 'frame': 25561, + 'frame_number': 25561, + 'framesequence': 98295, + 'gaze_dir': array([0.99658203, 0.00720215, 0.0798645 ]), + 'gaze_origin': array([-2.92630172, -0.00989456, -0.13308106]), + 'gaze_valid': True, + 'gaze_vergence': 145.32406616210938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99682617, 0.02572632, 0.07513428]), + 'left_gaze_origin': array([-2.75923324, 2.85283971, -0.14776611]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8988494873046875, + 'left_pupil_posn': array([ 0.25318229, -0.13766599]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99633789, -0.01132202, 0.08459473]), + 'right_gaze_origin': array([-3.0933702 , -2.87262893, -0.118396 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8142852783203125, + 'right_pupil_posn': array([-0.20852232, -0.22407031]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.441537976265, + 'timestamp_carla': 828443, + 'timestamp_device': 3981874, + 'timestamp_stream': 828.441537976265, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53590369e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.00256332, -0.00256538, 1.19723749]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.546709060668945, + 'FR_Wheel_Angle': 14.245469093322754, + 'Location': array([ -0.64601719, -26.87476921, 0.17002209]), + 'Rotation': array([-4.22378890e-02, -6.33121414e+01, 5.98854795e-02]), + 'Velocity': array([ 0.00782206, -0.01096221, 0.00031094]), + 'brake_input': 0.0, + 'camera_location': array([-7.60172462, 15.35294914, 0.17660414]), + 'camera_rotation': array([-3.43770909, -1.1630187 , -1.06795537]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.043701171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -398.25042725, -5331.49023438, 215.23144531]), + 'frame': 25562, + 'frame_number': 25562, + 'framesequence': 98299, + 'gaze_dir': array([0.99668884, 0.00728607, 0.07880402]), + 'gaze_origin': array([-2.92854786, -0.01018677, -0.1318901 ]), + 'gaze_valid': True, + 'gaze_vergence': 152.4723663330078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99693298, 0.02488708, 0.07417297]), + 'left_gaze_origin': array([-2.75707722, 2.85371709, -0.1478058 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.897674560546875, + 'left_pupil_posn': array([ 0.25290585, -0.13766599]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9964447 , -0.01031494, 0.08343506]), + 'right_gaze_origin': array([-3.1000185 , -2.87409067, -0.11597443]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8194427490234375, + 'right_pupil_posn': array([-0.20781976, -0.22407031]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.4754096791148, + 'timestamp_carla': 828477, + 'timestamp_device': 3981908, + 'timestamp_stream': 828.4754096791148, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53590369e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.06117443, -0.10099655, 1.02769423]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.517178535461426, + 'FR_Wheel_Angle': 14.181227684020996, + 'Location': array([ -0.63430142, -26.89299011, 0.16994914]), + 'Rotation': array([-3.33927944e-02, -6.32195168e+01, 5.60033657e-02]), + 'Velocity': array([ 1.45996302e-01, -2.14259118e-01, -2.28929512e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.58449364, 15.33999157, 0.17535201]), + 'camera_rotation': array([-3.40991712, -1.15650201, -1.08840024]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.951904296875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -398.43661499, -5331.49023438, 210.487854 ]), + 'frame': 25563, + 'frame_number': 25563, + 'framesequence': 98303, + 'gaze_dir': array([0.99660492, 0.00780487, 0.07966614]), + 'gaze_origin': array([-2.93097782, -0.01055069, -0.13163757]), + 'gaze_valid': True, + 'gaze_vergence': 146.200439453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99694824, 0.02537537, 0.07362366]), + 'left_gaze_origin': array([-2.75558186, 2.8539567 , -0.14939271]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.898193359375, + 'left_pupil_posn': array([ 0.25290585, -0.13766599]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9962616 , -0.00976562, 0.08570862]), + 'right_gaze_origin': array([-3.10637379, -2.87505817, -0.11388245]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8188323974609375, + 'right_pupil_posn': array([-0.2069881 , -0.22407031]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.5078000761569, + 'timestamp_carla': 828509, + 'timestamp_device': 3981941, + 'timestamp_stream': 828.5078000761569, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54689004e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.01020372, 0.01974994, 2.57107759]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.429868698120117, + 'FR_Wheel_Angle': 14.088761329650879, + 'Location': array([ -0.57956737, -26.97740936, 0.16982742]), + 'Rotation': array([-2.49575097e-02, -6.27475090e+01, 5.16127236e-02]), + 'Velocity': array([ 0.34197304, -0.49205646, -0.00061075]), + 'brake_input': 0.0, + 'camera_location': array([-7.58174419, 15.33088875, 0.1738003 ]), + 'camera_rotation': array([-3.38454294, -1.15933776, -1.0440129 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.96435546875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -396.09680176, -5331.49023438, 215.917099 ]), + 'frame': 25564, + 'frame_number': 25564, + 'framesequence': 98307, + 'gaze_dir': array([0.99679565, 0.0091095 , 0.07675934]), + 'gaze_origin': array([-2.94710875, -0.01114426, -0.12674561]), + 'gaze_valid': True, + 'gaze_vergence': 125.2162857055664, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99736023, 0.02719116, 0.06732178]), + 'left_gaze_origin': array([-2.75528884, 2.85455632, -0.14973146]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8985137939453125, + 'left_pupil_posn': array([ 0.25276911, -0.13766599]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99623108, -0.00897217, 0.0861969 ]), + 'right_gaze_origin': array([-3.13892841, -2.87684488, -0.10375977]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.855499267578125, + 'right_pupil_posn': array([-0.20518732, -0.22580457]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.5401450768113, + 'timestamp_carla': 828542, + 'timestamp_device': 3981974, + 'timestamp_stream': 828.5401450768113, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55345167e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([7.42347725e-03, 3.46985791e-04, 4.15784121e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.229089736938477, + 'FR_Wheel_Angle': 13.611374855041504, + 'Location': array([ -0.47352472, -27.13617897, 0.16971599]), + 'Rotation': array([-2.34958492e-02, -6.19257011e+01, 4.95595373e-02]), + 'Velocity': array([ 5.78322828e-01, -8.10387850e-01, -6.23760221e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.57840824, 15.34104729, 0.18553032]), + 'camera_rotation': array([-3.35134149, -1.16818953, -1.12382984]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.60791015625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -390.65289307, -5331.49023438, 206.13496399]), + 'frame': 25565, + 'frame_number': 25565, + 'framesequence': 98311, + 'gaze_dir': array([0.99668121, 0.01038361, 0.07785034]), + 'gaze_origin': array([-2.94338536, -0.01118393, -0.12815247]), + 'gaze_valid': True, + 'gaze_vergence': 123.83659362792969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9972229 , 0.02886963, 0.06845093]), + 'left_gaze_origin': array([-2.7514832 , 2.85490274, -0.15141602]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8802642822265625, + 'left_pupil_posn': array([ 0.25276911, -0.13766575]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99613953, -0.00810242, 0.08724976]), + 'right_gaze_origin': array([-3.13528776, -2.8772707 , -0.10488892]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.833526611328125, + 'right_pupil_posn': array([-0.20429391, -0.22543216]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.5736136771739, + 'timestamp_carla': 828575, + 'timestamp_device': 3982008, + 'timestamp_stream': 828.5736136771739, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54875920e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.03800799, 0.05564362, 3.1688354 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.19494915008545, + 'FR_Wheel_Angle': 9.293145179748535, + 'Location': array([ -0.34132126, -27.33320236, 0.16964152]), + 'Rotation': array([-3.71084139e-02, -6.10133667e+01, 5.77755347e-02]), + 'Velocity': array([ 5.69243789e-01, -8.27525377e-01, -4.33793059e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.58743763, 15.33466721, 0.18622576]), + 'camera_rotation': array([-3.40956879, -1.14227271, -1.03177178]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.6025390625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -386.67907715, -5331.49023438, 212.96185303]), + 'frame': 25566, + 'frame_number': 25566, + 'framesequence': 98315, + 'gaze_dir': array([0.996521 , 0.01063538, 0.07988739]), + 'gaze_origin': array([-2.94008279, -0.01101074, -0.13018341]), + 'gaze_valid': True, + 'gaze_vergence': 117.4432144165039, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9972229 , 0.02818298, 0.06878662]), + 'left_gaze_origin': array([-2.74850488, 2.85541534, -0.15431519]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.87872314453125, + 'left_pupil_posn': array([ 0.25278425, -0.13774788]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99581909, -0.00691223, 0.09098816]), + 'right_gaze_origin': array([-3.13166046, -2.87743688, -0.10605165]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8215484619140625, + 'right_pupil_posn': array([-0.20441568, -0.22539937]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.6080619767308, + 'timestamp_carla': 828609, + 'timestamp_device': 3982041, + 'timestamp_stream': 828.6080619767308, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53826878e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.04653041, -0.07719653, 0.00011721]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.240896224975586, + 'FR_Wheel_Angle': 3.632551431655884, + 'Location': array([ -0.27575645, -27.4346962 , 0.16985808]), + 'Rotation': array([ -0.08645653, -60.67415237, 0.07016363]), + 'Velocity': array([-1.90171369e-04, -4.96114517e-05, -1.33219364e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.60344124, 15.34109211, 0.18643275]), + 'camera_rotation': array([-3.4110713 , -1.13297641, -1.10335755]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.591064453125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -383.51953125, -5331.49023438, 217.01396179]), + 'frame': 25567, + 'frame_number': 25567, + 'framesequence': 98319, + 'gaze_dir': array([0.99652863, 0.01044464, 0.07990265]), + 'gaze_origin': array([-2.94107151, -0.0106514 , -0.1299881 ]), + 'gaze_valid': True, + 'gaze_vergence': 118.74738311767578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9972229 , 0.02780151, 0.06892395]), + 'left_gaze_origin': array([-2.74811101, 2.85573578, -0.15445711]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.896942138671875, + 'left_pupil_posn': array([ 0.25257361, -0.13785541]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99583435, -0.00691223, 0.09088135]), + 'right_gaze_origin': array([-3.13403201, -2.87703872, -0.1055191 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8245391845703125, + 'right_pupil_posn': array([-0.20482028, -0.22543812]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.6401708759367, + 'timestamp_carla': 828642, + 'timestamp_device': 3982074, + 'timestamp_stream': 828.6401708759367, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54956060e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-5.97573631e-02, -5.59046753e-02, 6.73190152e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.05127103999257088, + 'FR_Wheel_Angle': -0.19957076013088226, + 'Location': array([ -0.27564293, -27.4348526 , 0.16968314]), + 'Rotation': array([-5.69706038e-02, -6.06741371e+01, 6.19144328e-02]), + 'Velocity': array([-7.56420341e-05, 1.97532790e-05, -1.97656147e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.60323429, 15.33700943, 0.18146899]), + 'camera_rotation': array([-3.3852191 , -1.10268295, -1.08263242]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.62451171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -384.02752686, -5331.49072266, 216.99966431]), + 'frame': 25568, + 'frame_number': 25568, + 'framesequence': 98323, + 'gaze_dir': array([0.99658966, 0.01117706, 0.07943726]), + 'gaze_origin': array([-2.94142628, -0.01012268, -0.13003847]), + 'gaze_valid': True, + 'gaze_vergence': 128.62969970703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9972229 , 0.02711487, 0.06925964]), + 'left_gaze_origin': array([-2.74829745, 2.85651875, -0.15458833]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9014129638671875, + 'left_pupil_posn': array([ 0.25278425, -0.13840687]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99595642, -0.00476074, 0.08961487]), + 'right_gaze_origin': array([-3.13455534, -2.87676406, -0.10548859]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8363037109375, + 'right_pupil_posn': array([-0.20524859, -0.22539663]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.6756750792265, + 'timestamp_carla': 828677, + 'timestamp_device': 3982108, + 'timestamp_stream': 828.6756750792265, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.52987663e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-1.47716375e-02, -1.46062551e-02, 2.04358385e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006408486980944872, + 'FR_Wheel_Angle': 0.006408886052668095, + 'Location': array([ -0.27559441, -27.43490601, 0.16963558]), + 'Rotation': array([-4.71829437e-02, -6.06741371e+01, 5.94350174e-02]), + 'Velocity': array([3.43360698e-05, 3.35686273e-05, 3.67223867e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.61227036, 15.34309101, 0.17721945]), + 'camera_rotation': array([-3.36806178, -1.10559082, -1.1264776 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.46630859375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -378.85427856, -5331.49023438, 216.95629883]), + 'frame': 25569, + 'frame_number': 25569, + 'framesequence': 98327, + 'gaze_dir': array([0.99677277, 0.01050568, 0.07717133]), + 'gaze_origin': array([-2.94157124, -0.00974274, -0.12995377]), + 'gaze_valid': True, + 'gaze_vergence': 128.7681121826172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99737549, 0.02664185, 0.06710815]), + 'left_gaze_origin': array([-2.74756789, 2.85696578, -0.15463257]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9109649658203125, + 'left_pupil_posn': array([ 0.25218737, -0.13911808]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99617004, -0.00563049, 0.0872345 ]), + 'right_gaze_origin': array([-3.13557458, -2.87645125, -0.10527497]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8587493896484375, + 'right_pupil_posn': array([-0.20565522, -0.22626567]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.7088296785951, + 'timestamp_carla': 828710, + 'timestamp_device': 3982141, + 'timestamp_stream': 828.7088296785951, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53784922e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-3.39796348e-03, -3.72225535e-03, -1.06903890e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006408488377928734, + 'FR_Wheel_Angle': 0.006408886518329382, + 'Location': array([ -0.27558061, -27.43491936, 0.16961128]), + 'Rotation': array([-4.47035842e-02, -6.06741600e+01, 5.87434173e-02]), + 'Velocity': array([3.53178007e-06, 4.08492815e-06, 4.54088295e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.62443352, 15.340765 , 0.18087995]), + 'camera_rotation': array([-3.33850741, -1.10039854, -1.12849581]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.40771484375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -381.80218506, -5331.48974609, 209.06149292]), + 'frame': 25570, + 'frame_number': 25570, + 'framesequence': 98331, + 'gaze_dir': array([0.99685669, 0.0102005 , 0.07613373]), + 'gaze_origin': array([-2.93967915, -0.00959091, -0.13025589]), + 'gaze_valid': True, + 'gaze_vergence': 132.38023376464844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99742126, 0.02641296, 0.06661987]), + 'left_gaze_origin': array([-2.7429688 , 2.85740972, -0.15542451]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.922454833984375, + 'left_pupil_posn': array([ 0.2516917, -0.1393224]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99629211, -0.00601196, 0.08564758]), + 'right_gaze_origin': array([-3.13638926, -2.87659168, -0.10508729]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8734283447265625, + 'right_pupil_posn': array([-0.20565063, -0.22650433]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.7448278777301, + 'timestamp_carla': 828746, + 'timestamp_device': 3982174, + 'timestamp_stream': 828.7448278777301, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.51995851e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-8.13779421e-04, -9.80531680e-04, -1.44238247e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.015381328761577606, + 'FR_Wheel_Angle': -0.015379038639366627, + 'Location': array([ -0.2755765 , -27.43492126, 0.16959266]), + 'Rotation': array([-4.43415865e-02, -6.06741600e+01, 5.86284213e-02]), + 'Velocity': array([ 3.75290392e-06, 1.93873120e-06, -3.83610342e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.62177849, 15.34240723, 0.2053567 ]), + 'camera_rotation': array([-3.31022358, -1.11418271, -1.09575284]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.403076171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -382.59332275, -5331.49023438, 206.95053101]), + 'frame': 25571, + 'frame_number': 25571, + 'framesequence': 98335, + 'gaze_dir': array([0.9968338 , 0.01071167, 0.07645416]), + 'gaze_origin': array([-2.93834162, -0.00954895, -0.13089523]), + 'gaze_valid': True, + 'gaze_vergence': 132.4158172607422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99740601, 0.02650452, 0.06671143]), + 'left_gaze_origin': array([-2.74013996, 2.8575685 , -0.15670319]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.922149658203125, + 'left_pupil_posn': array([ 0.25185764, -0.13943708]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9962616 , -0.00508118, 0.0861969 ]), + 'right_gaze_origin': array([-3.13654351, -2.87666631, -0.10508729]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.873443603515625, + 'right_pupil_posn': array([-0.205567 , -0.22650564]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.7765483781695, + 'timestamp_carla': 828778, + 'timestamp_device': 3982208, + 'timestamp_stream': 828.7765483781695, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54277033e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-1.61750882e-04, -2.72956968e-04, -1.42015160e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.015381328761577606, + 'FR_Wheel_Angle': -0.015379038639366627, + 'Location': array([ -0.27557456, -27.43492317, 0.16961227]), + 'Rotation': array([-4.43415865e-02, -6.06741600e+01, 5.86284213e-02]), + 'Velocity': array([4.75650631e-06, 1.36790970e-06, 1.38375995e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.61904907, 15.34037113, 0.22030778]), + 'camera_rotation': array([-3.29084635, -1.09940648, -1.08587289]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.423095703125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -381.35925293, -5331.49023438, 210.23692322]), + 'frame': 25572, + 'frame_number': 25572, + 'framesequence': 98339, + 'gaze_dir': array([0.99689484, 0.01107788, 0.07571411]), + 'gaze_origin': array([-2.93585062, -0.00955429, -0.13218918]), + 'gaze_valid': True, + 'gaze_vergence': 139.3686065673828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99737549, 0.0269928 , 0.06698608]), + 'left_gaze_origin': array([-2.73489094, 2.85758066, -0.15918732]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.938018798828125, + 'left_pupil_posn': array([ 0.25185764, -0.14074636]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99641418, -0.00483704, 0.08444214]), + 'right_gaze_origin': array([-3.1368103 , -2.8766892 , -0.10519104]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.874847412109375, + 'right_pupil_posn': array([-0.20538133, -0.22653162]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.8097122758627, + 'timestamp_carla': 828811, + 'timestamp_device': 3982241, + 'timestamp_stream': 828.8097122758627, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54643229e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-4.59508301e-05, -4.24397513e-05, -1.47625278e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011534708552062511, + 'FR_Wheel_Angle': 0.011535996571183205, + 'Location': array([ -0.27557346, -27.43492317, 0.16960327]), + 'Rotation': array([-4.43415865e-02, -6.06741600e+01, 5.86284213e-02]), + 'Velocity': array([ 4.53775738e-06, 1.27716339e-06, -1.25721504e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.63057232, 15.34263897, 0.22385137]), + 'camera_rotation': array([-3.30327058, -1.07372689, -1.1245265 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.309814453125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -378.76507568, -5331.49023438, 208.65614319]), + 'frame': 25573, + 'frame_number': 25573, + 'framesequence': 98343, + 'gaze_dir': array([0.9969101 , 0.01171875, 0.07531738]), + 'gaze_origin': array([-2.93500614, -0.00962143, -0.13262483]), + 'gaze_valid': True, + 'gaze_vergence': 135.49313354492188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99740601, 0.02798462, 0.06626892]), + 'left_gaze_origin': array([-2.73345208, 2.85769367, -0.15968934]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.946533203125, + 'left_pupil_posn': array([ 0.25185764, -0.14083898]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99641418, -0.00454712, 0.08436584]), + 'right_gaze_origin': array([-3.13656044, -2.87693644, -0.1055603 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8733673095703125, + 'right_pupil_posn': array([-0.2048704 , -0.22701001]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.8405884765089, + 'timestamp_carla': 828842, + 'timestamp_device': 3982274, + 'timestamp_stream': 828.8405884765089, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.56340797e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-2.49052518e-05, 3.43504216e-05, -1.46995008e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.27557233, -27.43492317, 0.16960761]), + 'Rotation': array([-4.43415865e-02, -6.06741600e+01, 5.86284213e-02]), + 'Velocity': array([ 4.60283809e-06, 1.24742655e-06, -1.08155698e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.63560772, 15.34404373, 0.21439295]), + 'camera_rotation': array([-3.31747055, -1.05435586, -1.11702561]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.155517578125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -374.59881592, -5331.49023438, 206.2808075 ]), + 'frame': 25574, + 'frame_number': 25574, + 'framesequence': 98347, + 'gaze_dir': array([0.9969101 , 0.01128387, 0.07552338]), + 'gaze_origin': array([-2.93510675, -0.00957413, -0.13262941]), + 'gaze_valid': True, + 'gaze_vergence': 137.80654907226562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99742126, 0.0269928 , 0.06645203]), + 'left_gaze_origin': array([-2.73340297, 2.85786915, -0.15968934]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.94677734375, + 'left_pupil_posn': array([ 0.25178087, -0.14074636]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99639893, -0.00442505, 0.08459473]), + 'right_gaze_origin': array([-3.1368103 , -2.87701726, -0.10556947]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8842010498046875, + 'right_pupil_posn': array([-0.20516497, -0.2270155 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.8733501769602, + 'timestamp_carla': 828875, + 'timestamp_device': 3982308, + 'timestamp_stream': 828.8733501769602, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.56020329e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-6.01803822e-06, -6.93076163e-06, -1.46418470e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.27557155, -27.43492317, 0.16960773]), + 'Rotation': array([-4.43415865e-02, -6.06741600e+01, 5.86284213e-02]), + 'Velocity': array([ 4.66176289e-06, 1.22791187e-06, -2.50815592e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.63759041, 15.34550095, 0.21155663]), + 'camera_rotation': array([-3.31042171, -1.0183928 , -1.10039973]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.167236328125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -374.9616394 , -5331.49023438, 206.06715393]), + 'frame': 25575, + 'frame_number': 25575, + 'framesequence': 98351, + 'gaze_dir': array([0.99699402, 0.01108551, 0.07447052]), + 'gaze_origin': array([-2.9361856 , -0.00933914, -0.13221589]), + 'gaze_valid': True, + 'gaze_vergence': 140.81568908691406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99749756, 0.02633667, 0.06552124]), + 'left_gaze_origin': array([-2.73543262, 2.85833907, -0.15936279]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.963043212890625, + 'left_pupil_posn': array([ 0.25159502, -0.1413331 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99649048, -0.00416565, 0.0834198 ]), + 'right_gaze_origin': array([-3.13693881, -2.87701726, -0.10506897]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.885955810546875, + 'right_pupil_posn': array([-0.20539838, -0.2270155 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.9063621759415, + 'timestamp_carla': 828908, + 'timestamp_device': 3982341, + 'timestamp_stream': 828.9063621759415, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55577858e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02932387, 0.01760661, -0.70573717]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.03075140342116356, + 'FR_Wheel_Angle': -0.030743883922696114, + 'Location': array([ -0.27527067, -27.43535042, 0.16960613]), + 'Rotation': array([-4.43757363e-02, -6.06786728e+01, 5.86199686e-02]), + 'Velocity': array([-0.00805751, 0.01443712, -0.00025576]), + 'brake_input': 0.0, + 'camera_location': array([-7.65690708, 15.33466148, 0.22244075]), + 'camera_rotation': array([-3.34366417, -0.99462616, -1.12961268]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.051025390625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -373.0869751 , -5331.48974609, 202.31451416]), + 'frame': 25576, + 'frame_number': 25576, + 'framesequence': 98355, + 'gaze_dir': array([0.99677277, 0.01208496, 0.07701874]), + 'gaze_origin': array([-2.93751407, -0.00834122, -0.1321312 ]), + 'gaze_valid': True, + 'gaze_vergence': 132.64703369140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99734497, 0.02761841, 0.06716919]), + 'left_gaze_origin': array([-2.73543262, 2.85929275, -0.1594391 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.964813232421875, + 'left_pupil_posn': array([ 0.25120556, -0.14023089]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99620056, -0.00344849, 0.08686829]), + 'right_gaze_origin': array([-3.13959527, -2.87597513, -0.10482331]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8837127685546875, + 'right_pupil_posn': array([-0.20565897, -0.22677922]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.9418585784733, + 'timestamp_carla': 828943, + 'timestamp_device': 3982374, + 'timestamp_stream': 828.9418585784733, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53285221e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02866566, 0.01703168, -0.70714504]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.025632044300436974, + 'FR_Wheel_Angle': -0.02562755160033703, + 'Location': array([ -0.27577665, -27.43440819, 0.16960746]), + 'Rotation': array([-4.47992086e-02, -6.06775475e+01, 5.86429015e-02]), + 'Velocity': array([-0.01426287, 0.0253334 , -0.00010998]), + 'brake_input': 0.0, + 'camera_location': array([-7.68770695, 15.33626938, 0.22307077]), + 'camera_rotation': array([-3.38345695, -1.00824404, -1.19466913]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.0703125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -367.79986572, -5331.49023438, 210.30023193]), + 'frame': 25577, + 'frame_number': 25577, + 'framesequence': 98359, + 'gaze_dir': array([0.99668884, 0.01125336, 0.07804871]), + 'gaze_origin': array([-2.9391222 , -0.00765762, -0.13147965]), + 'gaze_valid': True, + 'gaze_vergence': 125.9153823852539, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99732971, 0.02735901, 0.06755066]), + 'left_gaze_origin': array([-2.7377336 , 2.86009073, -0.15842591]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.97607421875, + 'left_pupil_posn': array([ 0.25023282, -0.13946462]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99604797, -0.00485229, 0.08854675]), + 'right_gaze_origin': array([-3.14051056, -2.87540603, -0.10453339]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8838348388671875, + 'right_pupil_posn': array([-0.20613599, -0.2266283 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 828.9735553786159, + 'timestamp_carla': 828975, + 'timestamp_device': 3982408, + 'timestamp_stream': 828.9735553786159, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54875920e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02774061, 0.01647807, -0.69665653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02434927597641945, + 'FR_Wheel_Angle': -0.024341512471437454, + 'Location': array([ -0.27761075, -27.43113708, 0.16961066]), + 'Rotation': array([-4.48948294e-02, -6.06771851e+01, 5.86519316e-02]), + 'Velocity': array([-2.15044972e-02, 3.81188318e-02, 6.18839258e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.71027946, 15.33553314, 0.22909907]), + 'camera_rotation': array([-3.34209323, -1.0039916 , -1.18276143]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.257080078125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -372.49356079, -5331.48974609, 211.63998413]), + 'frame': 25578, + 'frame_number': 25578, + 'framesequence': 98363, + 'gaze_dir': array([0.99667358, 0.01054382, 0.07833862]), + 'gaze_origin': array([-2.93961954, -0.00730286, -0.1316887 ]), + 'gaze_valid': True, + 'gaze_vergence': 124.78641510009766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99734497, 0.02648926, 0.06761169]), + 'left_gaze_origin': array([-2.73745751, 2.86035776, -0.15877381]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.98309326171875, + 'left_pupil_posn': array([ 0.24986756, -0.13946462]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9960022 , -0.00540161, 0.08906555]), + 'right_gaze_origin': array([-3.14178181, -2.87496352, -0.10460358]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.87750244140625, + 'right_pupil_posn': array([-0.20674711, -0.22688246]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 829.006345577538, + 'timestamp_carla': 829008, + 'timestamp_device': 3982441, + 'timestamp_stream': 829.006345577538, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.55059065e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.10029306, 0.05398369, 0.56923693]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.030727017670869827, + 'FR_Wheel_Angle': -0.030654223635792732, + 'Location': array([ -0.28336689, -27.42102051, 0.1696281 ]), + 'Rotation': array([-4.63906415e-02, -6.06687546e+01, 5.86159714e-02]), + 'Velocity': array([-6.58404827e-02, 1.17622584e-01, -1.06191634e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.73014069, 15.33963013, 0.24747701]), + 'camera_rotation': array([-3.22130823, -0.98164475, -1.1329565 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.4296875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -374.98165894, -5331.48974609, 215.61868286]), + 'frame': 25579, + 'frame_number': 25579, + 'framesequence': 98367, + 'gaze_dir': array([0.99617004, 0.00773621, 0.08544922]), + 'gaze_origin': array([-2.90778828, -0.00496903, -0.13823777]), + 'gaze_valid': True, + 'gaze_vergence': 151.66563415527344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99681091, 0.02108765, 0.07676697]), + 'left_gaze_origin': array([-2.7310257 , 2.86175847, -0.15574647]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.99017333984375, + 'left_pupil_posn': array([ 0.24875164, -0.13457835]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99552917, -0.00561523, 0.09413147]), + 'right_gaze_origin': array([-3.08455062, -2.87169671, -0.12072907]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8994903564453125, + 'right_pupil_posn': array([-0.21077955, -0.22351694]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 829.0398171767592, + 'timestamp_carla': 829041, + 'timestamp_device': 3982474, + 'timestamp_stream': 829.0398171767592, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54639411e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02513346, 0.01332229, -0.26169088]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0725540816783905, + 'FR_Wheel_Angle': -0.09910338371992111, + 'Location': array([ -0.31654844, -27.36148643, 0.16972232]), + 'Rotation': array([-5.64583391e-02, -6.06909142e+01, 5.84347136e-02]), + 'Velocity': array([-2.08608970e-01, 3.74697357e-01, 2.10409155e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.75817394, 15.3494215 , 0.26595363]), + 'camera_rotation': array([-3.11105537, -0.97681957, -1.1268568 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.62841796875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -384.86395264, -5331.48925781, 252.22677612]), + 'frame': 25580, + 'frame_number': 25580, + 'framesequence': 98371, + 'gaze_dir': array([0.99617004, 0.00777435, 0.08570862]), + 'gaze_origin': array([-2.90808415, -0.00518875, -0.13871384]), + 'gaze_valid': True, + 'gaze_vergence': 175.46995544433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99661255, 0.02113342, 0.07933044]), + 'left_gaze_origin': array([-2.73258829, 2.86193705, -0.15580292]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0446624755859375, + 'left_pupil_posn': array([ 0.24868631, -0.13571012]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99572754, -0.00558472, 0.09208679]), + 'right_gaze_origin': array([-3.08358026, -2.87231469, -0.12162475]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.920166015625, + 'right_pupil_posn': array([-0.21033394, -0.22311008]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 829.0735220760107, + 'timestamp_carla': 829075, + 'timestamp_device': 3982508, + 'timestamp_stream': 829.0735220760107, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54219803e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.01432182, 0.00319144, 0.09911255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.3813129663467407, + 'FR_Wheel_Angle': -0.4691743552684784, + 'Location': array([ -0.37517539, -27.25654984, 0.16979824]), + 'Rotation': array([-5.71618490e-02, -6.06748352e+01, 5.84302843e-02]), + 'Velocity': array([-3.14891130e-01, 5.66272438e-01, 2.82993307e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.80648708, 15.35978699, 0.28179285]), + 'camera_rotation': array([-3.01221561, -0.95256287, -1.07389259]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.907958984375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -384.33816528, -5331.49023438, 260.9473877 ]), + 'frame': 25581, + 'frame_number': 25581, + 'framesequence': 98375, + 'gaze_dir': array([0.99620056, 0.00813293, 0.0850296 ]), + 'gaze_origin': array([-2.90646386, -0.0050766 , -0.13945161]), + 'gaze_valid': True, + 'gaze_vergence': 154.80882263183594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99673462, 0.02267456, 0.0773468 ]), + 'left_gaze_origin': array([-2.73010111, 2.8621614 , -0.15701601]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0385589599609375, + 'left_pupil_posn': array([ 0.24821651, -0.1358273 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9956665 , -0.00640869, 0.0927124 ]), + 'right_gaze_origin': array([-3.08282638, -2.87231469, -0.12188721]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91278076171875, + 'right_pupil_posn': array([-0.20981383, -0.22382951]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 829.1067617759109, + 'timestamp_carla': 829108, + 'timestamp_device': 3982541, + 'timestamp_stream': 829.1067617759109, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54334263e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.01942764, -0.02117104, 0.41972238]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.659773588180542, + 'FR_Wheel_Angle': -1.9786677360534668, + 'Location': array([ -0.44683537, -27.1267395 , 0.16982384]), + 'Rotation': array([-4.87129055e-02, -6.06321602e+01, 5.75564131e-02]), + 'Velocity': array([-3.04264873e-01, 5.63639581e-01, 3.30791459e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.82313728, 15.38030624, 0.30412591]), + 'camera_rotation': array([-2.92267871, -0.91007507, -0.99909812]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.9833984375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -380.83947754, -5331.49072266, 265.12866211]), + 'frame': 25582, + 'frame_number': 25582, + 'framesequence': 98379, + 'gaze_dir': array([0.9961319 , 0.00738525, 0.08586884]), + 'gaze_origin': array([-2.90458155, -0.00494843, -0.14137268]), + 'gaze_valid': True, + 'gaze_vergence': 157.7134552001953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99662781, 0.02236938, 0.07887268]), + 'left_gaze_origin': array([-2.72881174, 2.86239028, -0.1593094 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0556488037109375, + 'left_pupil_posn': array([ 0.24764907, -0.13707983]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99563599, -0.00759888, 0.09286499]), + 'right_gaze_origin': array([-3.08035135, -2.87228703, -0.12343598]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91156005859375, + 'right_pupil_posn': array([-0.20993483, -0.22385991]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 829.1412222757936, + 'timestamp_carla': 829143, + 'timestamp_device': 3982574, + 'timestamp_stream': 829.1412222757936, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.53475956e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.00825199, -0.00793261, 1.53058422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.362552165985107, + 'FR_Wheel_Angle': -5.6641764640808105, + 'Location': array([ -0.52617764, -26.97639275, 0.16994105]), + 'Rotation': array([-5.56933582e-02, -6.04327049e+01, 5.39159328e-02]), + 'Velocity': array([-3.88355047e-01, 7.78238297e-01, 2.37817760e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.83221817, 15.40090656, 0.33181426]), + 'camera_rotation': array([-2.78778934, -0.87684983, -0.99555677]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.309326171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -380.4468689 , -5331.49023438, 274.65463257]), + 'frame': 25583, + 'frame_number': 25583, + 'framesequence': 98383, + 'gaze_dir': array([0.99622345, 0.00711823, 0.08488464]), + 'gaze_origin': array([-2.90441227, -0.00474701, -0.14270554]), + 'gaze_valid': True, + 'gaze_vergence': 162.397216796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9967041 , 0.0216217 , 0.07804871]), + 'left_gaze_origin': array([-2.72872925, 2.8627336 , -0.15991059]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.045806884765625, + 'left_pupil_posn': array([ 0.2474966 , -0.13783956]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9957428 , -0.00738525, 0.09172058]), + 'right_gaze_origin': array([-3.08009505, -2.87222767, -0.12550049]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9161834716796875, + 'right_pupil_posn': array([-0.21026552, -0.22551298]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 829.1740057766438, + 'timestamp_carla': 829175, + 'timestamp_device': 3982608, + 'timestamp_stream': 829.1740057766438, + 'transform': [array([3.64772153e+00, 1.49767685e+01, 4.54280851e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([-0.06215915, -0.03188753, 1.62892818]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.667163372039795, + 'FR_Wheel_Angle': -7.146154403686523, + 'Location': array([ -0.60465735, -26.81939888, 0.16993237]), + 'Rotation': array([-3.79895084e-02, -6.00331383e+01, 5.74287400e-02]), + 'Velocity': array([-2.52276659e-01, 5.35012841e-01, 2.38447188e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.85870361, 15.44290638, 0.34745863]), + 'camera_rotation': array([-2.75088596, -0.80383539, -0.85310715]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.472412109375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -379.08630371, -5331.49023438, 280.1020813 ]), + 'frame': 25584, + 'frame_number': 25584, + 'framesequence': 98387, + 'gaze_dir': array([0.9963913 , 0.00566864, 0.08299255]), + 'gaze_origin': array([-2.90193653, -0.00409851, -0.14361268]), + 'gaze_valid': True, + 'gaze_vergence': 163.04722595214844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99687195, 0.02018738, 0.07624817]), + 'left_gaze_origin': array([-2.72889256, 2.86346912, -0.15991059]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0339202880859375, + 'left_pupil_posn': array([ 0.24650753, -0.13847506]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99591064, -0.0088501 , 0.08973694]), + 'right_gaze_origin': array([-3.07498026, -2.87166619, -0.12731476]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.92779541015625, + 'right_pupil_posn': array([-0.21116656, -0.22639132]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0793621763586998, + 'timestamp': 829.2067552767694, + 'timestamp_carla': 829208, + 'timestamp_device': 3982641, + 'timestamp_stream': 829.2067552767694, + 'transform': [array([3.64772940e+00, 1.49769430e+01, 4.54772962e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.0315473 , -0.0117184 , 1.02808285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.614672660827637, + 'FR_Wheel_Angle': -6.962369918823242, + 'Location': array([ -0.64565074, -26.73701096, 0.16993442]), + 'Rotation': array([-3.29283401e-02, -5.97996407e+01, 6.00477457e-02]), + 'Velocity': array([-1.60805568e-01, 3.40614527e-01, -1.40762320e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.87876701, 15.4812603 , 0.35600302]), + 'camera_rotation': array([-2.74009418, -0.717242 , -0.71337569]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.30322265625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -378.80053711, -5331.49023438, 274.96258545]), + 'frame': 25585, + 'frame_number': 25585, + 'framesequence': 98391, + 'gaze_dir': array([0.9966507 , 0.00538635, 0.07991791]), + 'gaze_origin': array([-2.91152287, -0.00324631, -0.14295655]), + 'gaze_valid': True, + 'gaze_vergence': 173.17234802246094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99688721, 0.02093506, 0.07589722]), + 'left_gaze_origin': array([-2.7504487 , 2.86454773, -0.15590058]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.03436279296875, + 'left_pupil_posn': array([ 0.24568212, -0.14184177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99641418, -0.01016235, 0.0839386 ]), + 'right_gaze_origin': array([-3.07259679, -2.87104034, -0.13001251]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9325714111328125, + 'right_pupil_posn': array([-0.21135902, -0.22790921]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.11903563141822815, + 'timestamp': 829.240445677191, + 'timestamp_carla': 829242, + 'timestamp_device': 3982674, + 'timestamp_stream': 829.240445677191, + 'transform': [array([3.64773989e+00, 1.49771385e+01, 4.54330444e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.02660108, 0.00912267, 0.91706723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.924673080444336, + 'FR_Wheel_Angle': -5.426397800445557, + 'Location': array([ -0.68642151, -26.65718269, 0.17005402]), + 'Rotation': array([-4.47035842e-02, -5.96029053e+01, 5.87351285e-02]), + 'Velocity': array([-1.96046159e-01, 3.87187153e-01, -5.55896731e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.90407276, 15.51317215, 0.35056347]), + 'camera_rotation': array([-2.74700642, -0.64247888, -0.7972185 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.787841796875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -372.92105103, -5331.49023438, 263.34301758]), + 'frame': 25586, + 'frame_number': 25586, + 'framesequence': 98395, + 'gaze_dir': array([0.99667358, 0.003685 , 0.07971954]), + 'gaze_origin': array([-2.91356993e+00, -2.64282245e-03, -1.43416598e-01]), + 'gaze_valid': True, + 'gaze_vergence': 177.78506469726562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99687195, 0.01919556, 0.0765686 ]), + 'left_gaze_origin': array([-2.75899363, 2.86529541, -0.15378724]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.031829833984375, + 'left_pupil_posn': array([ 0.24476397, -0.14239979]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99647522, -0.01182556, 0.08287048]), + 'right_gaze_origin': array([-3.06814599, -2.87058115, -0.13304596]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.934173583984375, + 'right_pupil_posn': array([-0.21229005, -0.22885787]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.15078964829444885, + 'timestamp': 829.273122176528, + 'timestamp_carla': 829275, + 'timestamp_device': 3982707, + 'timestamp_stream': 829.273122176528, + 'transform': [array([3.64774966e+00, 1.49772787e+01, 4.54784371e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([ 0.02117145, -0.00816652, 1.10766673]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.332263469696045, + 'FR_Wheel_Angle': -5.071268081665039, + 'Location': array([ -0.73175144, -26.57163429, 0.17008469]), + 'Rotation': array([-3.96424159e-02, -5.94249115e+01, 5.90515845e-02]), + 'Velocity': array([-0.13111432, 0.25513268, 0.00048303]), + 'brake_input': 0.0, + 'camera_location': array([-7.92850494, 15.5380764 , 0.34949514]), + 'camera_rotation': array([-2.73248529, -0.5775463 , -0.74605173]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.848876953125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -374.93380737, -5331.48974609, 261.99578857]), + 'frame': 25587, + 'frame_number': 25587, + 'framesequence': 98399, + 'gaze_dir': array([0.99678802, 0.00216675, 0.07824707]), + 'gaze_origin': array([-2.91342092e+00, -1.31530769e-03, -1.43352509e-01]), + 'gaze_valid': True, + 'gaze_vergence': 173.4481658935547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99691772, 0.01843262, 0.07611084]), + 'left_gaze_origin': array([-2.76024032, 2.86637425, -0.15339814]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0504150390625, + 'left_pupil_posn': array([ 0.2433064 , -0.14328253]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99665833, -0.01409912, 0.0803833 ]), + 'right_gaze_origin': array([-3.06660175, -2.86900496, -0.13330689]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91400146484375, + 'right_pupil_posn': array([-0.2136299 , -0.22885787]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.17856107652187347, + 'timestamp': 829.3083241768181, + 'timestamp_carla': 829310, + 'timestamp_device': 3982741, + 'timestamp_stream': 829.3083241768181, + 'transform': [array([3.64776087e+00, 1.49774590e+01, 4.53071576e-03]), + array([ -0.06319974, -11.153512 , 0.01605968])]} +{'AngularVelocity': array([0.00758385, 0.00019268, 0.08912914]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.338272571563721, + 'FR_Wheel_Angle': -5.076991558074951, + 'Location': array([ -0.75655562, -26.52510834, 0.17010127]), + 'Rotation': array([-4.04073969e-02, -5.93286057e+01, 5.85253015e-02]), + 'Velocity': array([-0.08585828, 0.16467805, -0.00024356]), + 'brake_input': 0.0, + 'camera_location': array([-7.94682789, 15.56270123, 0.35407177]), + 'camera_rotation': array([-2.66734576, -0.53889835, -0.72463334]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.76513671875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -376.09381104, -5331.49023438, 257.02914429]), + 'frame': 25588, + 'frame_number': 25588, + 'framesequence': 98403, + 'gaze_dir': array([0.99684906, 0.00115204, 0.07736206]), + 'gaze_origin': array([-2.91506529e+00, -5.59234642e-04, -1.42684937e-01]), + 'gaze_valid': True, + 'gaze_vergence': 163.15243530273438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99702454, 0.01837158, 0.07484436]), + 'left_gaze_origin': array([-2.76352859, 2.86698771, -0.15232392]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0497283935546875, + 'left_pupil_posn': array([ 0.24227643, -0.14332533]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99667358, -0.0160675 , 0.07987976]), + 'right_gaze_origin': array([-3.06660175, -2.86810613, -0.13304596]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.92498779296875, + 'right_pupil_posn': array([-0.21427214, -0.22912121]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.21428243815898895, + 'timestamp': 829.3417850770056, + 'timestamp_carla': 829343, + 'timestamp_device': 3982774, + 'timestamp_stream': 829.3417850770056, + 'transform': [array([3.64777875e+00, 1.49775200e+01, 4.46968060e-03]), + array([ -0.06317241, -11.15353966, 0.01618795])]} +{'AngularVelocity': array([0.009621 , 0.00329851, 0.08368078]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.34259557723999, + 'FR_Wheel_Angle': -5.079896926879883, + 'Location': array([ -0.7723428 , -26.49565315, 0.17014259]), + 'Rotation': array([-4.24769446e-02, -5.92685127e+01, 5.79413250e-02]), + 'Velocity': array([-7.09761679e-02, 1.35782152e-01, 1.15652081e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.95457077, 15.58933258, 0.36092684]), + 'camera_rotation': array([-2.59763694, -0.52484393, -0.63458377]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.8671875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -377.26599121, -5331.49023438, 257.97561646]), + 'frame': 25589, + 'frame_number': 25589, + 'framesequence': 98407, + 'gaze_dir': array([ 0.99668884, -0.00151825, 0.07830811]), + 'gaze_origin': array([-2.92118764e+00, 1.73950204e-04, -1.41459659e-01]), + 'gaze_valid': True, + 'gaze_vergence': 134.47377014160156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99685669, 0.01966858, 0.0765686 ]), + 'left_gaze_origin': array([-2.76728678, 2.86733103, -0.15133515]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.053192138671875, + 'left_pupil_posn': array([ 0.23985708, -0.14334321]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.996521 , -0.02270508, 0.08004761]), + 'right_gaze_origin': array([-3.0750885 , -2.86698318, -0.13158417]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.923797607421875, + 'right_pupil_posn': array([-0.21458948, -0.22917271]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.24602121114730835, + 'timestamp': 829.3728196769953, + 'timestamp_carla': 829374, + 'timestamp_device': 3982807, + 'timestamp_stream': 829.3728196769953, + 'transform': [array([3.64779830e+00, 1.49774323e+01, 4.39586630e-03]), + array([ -0.06313827, -11.15356636, 0.01637012])]} +{'AngularVelocity': array([ 0.02250046, -0.00651476, 0.44315577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.378805160522461, + 'FR_Wheel_Angle': -5.122715950012207, + 'Location': array([ -0.78820908, -26.46622467, 0.17017418]), + 'Rotation': array([-4.44986783e-02, -5.91989555e+01, 5.74043766e-02]), + 'Velocity': array([-0.06526415, 0.12826891, 0.0004057 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.95720959, 15.6109581 , 0.37867829]), + 'camera_rotation': array([-2.54789257, -0.45830205, -0.55531734]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.443603515625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -386.46554565, -5331.49023438, 266.5604248 ]), + 'frame': 25590, + 'frame_number': 25590, + 'framesequence': 98411, + 'gaze_dir': array([ 0.99684906, -0.00183105, 0.07633209]), + 'gaze_origin': array([-2.92450428e+00, 5.52368176e-04, -1.41288757e-01]), + 'gaze_valid': True, + 'gaze_vergence': 135.22998046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99702454, 0.01922607, 0.07453918]), + 'left_gaze_origin': array([-2.77210402, 2.86768508, -0.15099335]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.056243896484375, + 'left_pupil_posn': array([ 0.23963535, -0.14466822]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99667358, -0.02288818, 0.078125 ]), + 'right_gaze_origin': array([-3.07690454, -2.86658025, -0.13158417]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.92681884765625, + 'right_pupil_posn': array([-0.21504426, -0.23023427]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.269825279712677, + 'timestamp': 829.4108923785388, + 'timestamp_carla': 829412, + 'timestamp_device': 3982841, + 'timestamp_stream': 829.4108923785388, + 'transform': [array([3.64782000e+00, 1.49773712e+01, 4.28359956e-03]), + array([ -0.0631246 , -11.15359497, 0.01649848])]} +{'AngularVelocity': array([-0.01036698, -0.01112611, -0.36660376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.832001686096191, + 'FR_Wheel_Angle': -5.611830234527588, + 'Location': array([ -0.82553357, -26.39719391, 0.17026141]), + 'Rotation': array([-5.17660007e-02, -5.90783539e+01, 5.58369346e-02]), + 'Velocity': array([-0.15946622, 0.30707797, 0.00032575]), + 'brake_input': 0.0, + 'camera_location': array([-7.95625019, 15.62961578, 0.3864392 ]), + 'camera_rotation': array([-2.55220246, -0.3715325 , -0.4931525 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.1748046875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -382.56161499, -5331.49023438, 262.13494873]), + 'frame': 25591, + 'frame_number': 25591, + 'framesequence': 98416, + 'gaze_dir': array([ 0.99689484, -0.00408936, 0.07593536]), + 'gaze_origin': array([-2.92894220e+00, 1.05514529e-03, -1.41222388e-01]), + 'gaze_valid': True, + 'gaze_vergence': 141.90716552734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99714661, 0.0158844 , 0.07373047]), + 'left_gaze_origin': array([-2.77869415, 2.86821008, -0.15068208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.05572509765625, + 'left_pupil_posn': array([ 0.23898911, -0.14571905]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99664307, -0.02406311, 0.07814026]), + 'right_gaze_origin': array([-3.07919025, -2.86609983, -0.1317627 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91217041015625, + 'right_pupil_posn': array([-0.21655065, -0.23105609]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2737926244735718, + 'timestamp': 829.4507288783789, + 'timestamp_carla': 829452, + 'timestamp_device': 3982882, + 'timestamp_stream': 829.4507288783789, + 'transform': [array([3.64783978e+00, 1.49770603e+01, 4.08727629e-03]), + array([ -0.06307679, -11.15363216, 0.01680165])]} +{'AngularVelocity': array([-0.00839433, -0.02546073, 1.33135784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.515641212463379, + 'FR_Wheel_Angle': -6.23704195022583, + 'Location': array([ -0.87747312, -26.30067635, 0.17034294]), + 'Rotation': array([-5.76741137e-02, -5.88383942e+01, 5.43753840e-02]), + 'Velocity': array([-0.26681855, 0.51862305, 0.00063914]), + 'brake_input': 0.0, + 'camera_location': array([-7.94515419, 15.65420532, 0.37418035]), + 'camera_rotation': array([-2.60709667, -0.26820222, -0.52915668]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.1923828125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -385.17776489, -5331.49023438, 260.19152832]), + 'frame': 25592, + 'frame_number': 25592, + 'framesequence': 98420, + 'gaze_dir': array([ 0.99675751, -0.00585938, 0.07736969]), + 'gaze_origin': array([-2.93074203e+00, 1.84555061e-03, -1.41063690e-01]), + 'gaze_valid': True, + 'gaze_vergence': 135.03492736816406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99710083, 0.01501465, 0.0745697 ]), + 'left_gaze_origin': array([-2.78175974, 2.86897135, -0.1503647 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0692901611328125, + 'left_pupil_posn': array([ 0.23761451, -0.14539409]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99641418, -0.0267334 , 0.08016968]), + 'right_gaze_origin': array([-3.07972431, -2.86528015, -0.1317627 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.892974853515625, + 'right_pupil_posn': array([-0.21740323, -0.23079729]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.20236514508724213, + 'timestamp': 829.4849572777748, + 'timestamp_carla': 829486, + 'timestamp_device': 3982916, + 'timestamp_stream': 829.4849572777748, + 'transform': [array([3.64778304e+00, 1.49750280e+01, 3.24213016e-03]), + array([ -0.06276944, -11.15359592, 0.01851746])]} +{'AngularVelocity': array([ 0.02420441, -0.01769472, 2.00532436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.86110258102417, + 'FR_Wheel_Angle': -7.5912957191467285, + 'Location': array([ -0.94863766, -26.16711807, 0.17041366]), + 'Rotation': array([-5.65539636e-02, -5.84819069e+01, 5.36821410e-02]), + 'Velocity': array([-3.39233130e-01, 6.67987108e-01, 3.58324032e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.93272591, 15.66259766, 0.3597365 ]), + 'camera_rotation': array([-2.69950914, -0.21396878, -0.54415518]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.216064453125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -385.27108765, -5331.49023438, 262.04827881]), + 'frame': 25593, + 'frame_number': 25593, + 'framesequence': 98424, + 'gaze_dir': array([ 0.99668121, -0.00666046, 0.07819366]), + 'gaze_origin': array([-2.93897557, 0.00377274, -0.13785248]), + 'gaze_valid': True, + 'gaze_vergence': 131.7865447998047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99713135, 0.01437378, 0.07423401]), + 'left_gaze_origin': array([-2.78572702, 2.8707993 , -0.14840241]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0426025390625, + 'left_pupil_posn': array([ 0.23612356, -0.14415836]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99623108, -0.0276947 , 0.08215332]), + 'right_gaze_origin': array([-3.09222436, -2.86325383, -0.12730256]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8700714111328125, + 'right_pupil_posn': array([-0.2190153 , -0.23023427]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.17856107652187347, + 'timestamp': 829.518208976835, + 'timestamp_carla': 829520, + 'timestamp_device': 3982949, + 'timestamp_stream': 829.518208976835, + 'transform': [array([3.64995313e+00, 1.49715557e+01, 2.58689886e-03]), + array([ -0.06255087, -11.158041 , 0.01985194])]} +{'AngularVelocity': array([-0.00404233, -0.01954461, 2.71864963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.516511917114258, + 'FR_Wheel_Angle': -8.72028923034668, + 'Location': array([ -1.0343622 , -26.00383186, 0.17049293]), + 'Rotation': array([-5.28520010e-02, -5.79511871e+01, 5.36750294e-02]), + 'Velocity': array([-0.36526835, 0.73342633, 0.00074147]), + 'brake_input': 0.0, + 'camera_location': array([-7.89817619, 15.66263866, 0.33889607]), + 'camera_rotation': array([-2.75902057, -0.18487994, -0.49523026]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.901123046875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -384.79632568, -5331.49072266, 258.98571777]), + 'frame': 25594, + 'frame_number': 25594, + 'framesequence': 98428, + 'gaze_dir': array([ 0.9967041 , -0.00670624, 0.07817841]), + 'gaze_origin': array([-2.94114304, 0.00506592, -0.1355713 ]), + 'gaze_valid': True, + 'gaze_vergence': 141.57984924316406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99707031, 0.01312256, 0.07522583]), + 'left_gaze_origin': array([-2.78968525, 2.87193608, -0.1460495 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0295257568359375, + 'left_pupil_posn': array([ 0.23580527, -0.14364088]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99633789, -0.02653503, 0.08113098]), + 'right_gaze_origin': array([-3.09260106, -2.86180425, -0.12509309]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.87445068359375, + 'right_pupil_posn': array([-0.22040921, -0.2284416 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.17856107652187347, + 'timestamp': 829.5512074790895, + 'timestamp_carla': 829553, + 'timestamp_device': 3982982, + 'timestamp_stream': 829.5512074790895, + 'transform': [array([3.65260315e+00, 1.49663448e+01, 1.56604766e-03]), + array([ -0.06212057, -11.16346931, 0.02188552])]} +{'AngularVelocity': array([ 0.00508023, -0.01865253, 2.61704516]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.552556991577148, + 'FR_Wheel_Angle': -8.787881851196289, + 'Location': array([ -1.10966313, -25.86174583, 0.17054698]), + 'Rotation': array([-4.84260395e-02, -5.74566689e+01, 5.59052601e-02]), + 'Velocity': array([-0.35841128, 0.7054376 , 0.00073876]), + 'brake_input': 0.0, + 'camera_location': array([-7.87195778, 15.66319656, 0.32672438]), + 'camera_rotation': array([-2.84807253, -0.19875534, -0.48625407]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.39013671875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -382.99377441, -5331.49023438, 254.86369324]), + 'frame': 25595, + 'frame_number': 25595, + 'framesequence': 98432, + 'gaze_dir': array([ 0.99662018, -0.00777435, 0.07917786]), + 'gaze_origin': array([-2.94121957, 0.00550919, -0.13452074]), + 'gaze_valid': True, + 'gaze_vergence': 140.8227081298828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99705505, 0.01199341, 0.07569885]), + 'left_gaze_origin': array([-2.78983784, 2.8724153 , -0.14523469]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.041839599609375, + 'left_pupil_posn': array([ 0.23515165, -0.14265752]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9961853 , -0.02754211, 0.08265686]), + 'right_gaze_origin': array([-3.09260106, -2.86139703, -0.12380676]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8779144287109375, + 'right_pupil_posn': array([-0.22106248, -0.22740924]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.17856107652187347, + 'timestamp': 829.5854991786182, + 'timestamp_carla': 829587, + 'timestamp_device': 3983016, + 'timestamp_stream': 829.5854991786182, + 'transform': [array([3.65074754e+00, 1.49605799e+01, 7.32460001e-04]), + array([ -0.06186785, -11.15999126, 0.0235192 ])]} +{'AngularVelocity': array([ 0.01426068, -0.02694478, 2.69358301]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.328651428222656, + 'FR_Wheel_Angle': -9.561111450195312, + 'Location': array([ -1.19638228, -25.70108795, 0.17062041]), + 'Rotation': array([-4.75381128e-02, -5.68809013e+01, 5.58979288e-02]), + 'Velocity': array([-3.50224257e-01, 6.83307886e-01, 1.76362984e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.83627701, 15.65523243, 0.31763613]), + 'camera_rotation': array([-2.93314934, -0.21684998, -0.49263024]), + 'current_gear_input': False, + 'focus_actor_dist': 3987.0205078125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -388.57580566, -5331.49023438, 252.76837158]), + 'frame': 25596, + 'frame_number': 25596, + 'framesequence': 98436, + 'gaze_dir': array([ 0.99661255, -0.00795746, 0.07920837]), + 'gaze_origin': array([-2.94148278, 0.00550919, -0.13388063]), + 'gaze_valid': True, + 'gaze_vergence': 140.2719268798828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99702454, 0.01197815, 0.07597351]), + 'left_gaze_origin': array([-2.79100347, 2.8724153 , -0.14435731]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.046722412109375, + 'left_pupil_posn': array([ 0.23504543, -0.14236581]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99620056, -0.02789307, 0.08244324]), + 'right_gaze_origin': array([-3.09196186, -2.86139703, -0.12340393]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9000091552734375, + 'right_pupil_posn': array([-0.22106248, -0.22696126]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2063324898481369, + 'timestamp': 829.6184416785836, + 'timestamp_carla': 829620, + 'timestamp_device': 3983049, + 'timestamp_stream': 829.6184416785836, + 'transform': [array([3.65556502e+00, 1.49527483e+01, 1.98993672e-04]), + array([ -0.06189517, -11.16993999, 0.02458352])]} +{'AngularVelocity': array([ 0.027109 , -0.0224985, 3.1820035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.834935188293457, + 'FR_Wheel_Angle': -10.784244537353516, + 'Location': array([ -1.28332293, -25.54085159, 0.17074306]), + 'Rotation': array([-4.97442633e-02, -5.62429276e+01, 5.42721972e-02]), + 'Velocity': array([-3.66497099e-01, 7.19157100e-01, 4.70037456e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.79648781, 15.64707947, 0.31360435]), + 'camera_rotation': array([-3.01716757, -0.24585319, -0.53712571]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.2666015625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -390.36413574, -5331.49023438, 247.05804443]), + 'frame': 25597, + 'frame_number': 25597, + 'framesequence': 98440, + 'gaze_dir': array([ 0.99656677, -0.00800323, 0.07967377]), + 'gaze_origin': array([-2.93942356, 0.00545883, -0.13372727]), + 'gaze_valid': True, + 'gaze_vergence': 138.72750854492188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99703979, 0.01191711, 0.07575989]), + 'left_gaze_origin': array([-2.78744221, 2.87234497, -0.14438631]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0725555419921875, + 'left_pupil_posn': array([ 0.23504055, -0.14139462]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99609375, -0.02792358, 0.08358765]), + 'right_gaze_origin': array([-3.09140491, -2.86142755, -0.12306825]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91351318359375, + 'right_pupil_posn': array([-0.22106248, -0.22670889]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2222171425819397, + 'timestamp': 829.6509025767446, + 'timestamp_carla': 829652, + 'timestamp_device': 3983082, + 'timestamp_stream': 829.6509025767446, + 'transform': [array([ 3.65206170e+00, 1.49455366e+01, -2.44998926e-04]), + array([ -0.06166977, -11.16331673, 0.02547338])]} +{'AngularVelocity': array([ 0.01421746, -0.0226641 , 3.54246736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.348172187805176, + 'FR_Wheel_Angle': -11.043684959411621, + 'Location': array([ -1.37576866, -25.37149811, 0.17084186]), + 'Rotation': array([-5.12400754e-02, -5.54908562e+01, 5.41094728e-02]), + 'Velocity': array([-3.87002379e-01, 7.49627590e-01, 1.78155897e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.75869751, 15.64376831, 0.28571296]), + 'camera_rotation': array([-3.1394484 , -0.25932392, -0.58767974]), + 'current_gear_input': False, + 'focus_actor_dist': 3985.547119140625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -393.51882935, -5331.49023438, 243.10470581]), + 'frame': 25598, + 'frame_number': 25598, + 'framesequence': 98444, + 'gaze_dir': array([0.99717712, 0.04017639, 0.05883026]), + 'gaze_origin': array([-2.93974161, -0.02836685, -0.13545151]), + 'gaze_valid': True, + 'gaze_vergence': 109.94586181640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99697876, 0.06080627, 0.04811096]), + 'left_gaze_origin': array([-2.7338655 , 2.83793044, -0.16876374]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.087310791015625, + 'left_pupil_posn': array([ 0.27325106, -0.15231228]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99737549, 0.01954651, 0.06954956]), + 'right_gaze_origin': array([-3.14561796, -2.89466429, -0.10213929]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8062744140625, + 'right_pupil_posn': array([-0.18133605, -0.23304844]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2380865216255188, + 'timestamp': 829.6842679791152, + 'timestamp_carla': 829686, + 'timestamp_device': 3983116, + 'timestamp_stream': 829.6842679791152, + 'transform': [array([ 3.65026855e+00, 1.49362192e+01, -8.24832881e-04]), + array([ -0.06145804, -11.16017723, 0.02660829])]} +{'AngularVelocity': array([ 0.01898743, -0.02371762, 3.76818562]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.549046516418457, + 'FR_Wheel_Angle': -11.417864799499512, + 'Location': array([ -1.47535288, -25.19420624, 0.17097339]), + 'Rotation': array([-5.29476218e-02, -5.46864853e+01, 5.40796444e-02]), + 'Velocity': array([-4.26580966e-01, 7.97388315e-01, 5.46627038e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.71735001, 15.63421917, 0.24968091]), + 'camera_rotation': array([-3.31804419, -0.27828079, -0.54139215]), + 'current_gear_input': False, + 'focus_actor_dist': 3981.488037109375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -201.60066223, -5331.48974609, 153.24928284]), + 'frame': 25599, + 'frame_number': 25599, + 'framesequence': 98448, + 'gaze_dir': array([0.98492432, 0.16941833, 0.0223465 ]), + 'gaze_origin': array([-2.94415379, -0.13049316, -0.15929796]), + 'gaze_valid': True, + 'gaze_vergence': 97.71883392333984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98094177, 0.1938324 , 0.01257324]), + 'left_gaze_origin': array([-2.77244282, 2.71941853, -0.18596497]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3678436279296875, + 'left_pupil_posn': array([ 0.39639449, -0.1853137 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98890686, 0.14500427, 0.03211975]), + 'right_gaze_origin': array([-3.11586475, -2.98040462, -0.13263093]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.744354248046875, + 'right_pupil_posn': array([-0.07662982, -0.26290309]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.269825279712677, + 'timestamp': 829.7186694778502, + 'timestamp_carla': 829720, + 'timestamp_device': 3983149, + 'timestamp_stream': 829.7186694778502, + 'transform': [array([ 3.64884567e+00, 1.49256353e+01, -1.02174759e-03]), + array([ -0.06132827, -11.15779686, 0.02698021])]} +{'AngularVelocity': array([ 0.03564372, -0.03388367, 5.00512934]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.956697463989258, + 'FR_Wheel_Angle': -14.347979545593262, + 'Location': array([ -1.59745896, -24.97929192, 0.17113021]), + 'Rotation': array([-5.38287163e-02, -5.35932350e+01, 5.03000170e-02]), + 'Velocity': array([-4.44150120e-01, 8.55042040e-01, 7.17091549e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.67837906, 15.62911797, 0.22352983]), + 'camera_rotation': array([-3.48072577, -0.2505174 , -0.54906678]), + 'current_gear_input': False, + 'focus_actor_dist': 3564.123291015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 254.27871704, -4876.2578125 , 16.55258942]), + 'frame': 25600, + 'frame_number': 25600, + 'framesequence': 98452, + 'gaze_dir': array([0.97328949, 0.22902679, 0.00997925]), + 'gaze_origin': array([-2.9531908 , -0.17155991, -0.16758958]), + 'gaze_valid': True, + 'gaze_vergence': 203.19309997558594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97116089, 0.23835754, 0.0038147 ]), + 'left_gaze_origin': array([-2.78315449, 2.67183542, -0.19564363]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3202972412109375, + 'left_pupil_posn': array([ 0.45604062, -0.2012068 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97541809, 0.21969604, 0.0161438 ]), + 'right_gaze_origin': array([-3.12322712, -3.01495528, -0.13953553]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.73541259765625, + 'right_pupil_posn': array([-0.03745657, -0.27364695]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.28172731399536133, + 'timestamp': 829.7507810778916, + 'timestamp_carla': 829752, + 'timestamp_device': 3983182, + 'timestamp_stream': 829.7507810778916, + 'transform': [array([ 3.64639306e+00, 1.49146042e+01, -1.38683314e-03]), + array([ -0.06117117, -11.15340805, 0.02772198])]} +{'AngularVelocity': array([ 0.03525909, -0.0425659 , 6.47295713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.774545669555664, + 'FR_Wheel_Angle': -17.84031105041504, + 'Location': array([ -1.6942637 , -24.80470657, 0.17120785]), + 'Rotation': array([-5.41702285e-02, -5.24672127e+01, 4.78529558e-02]), + 'Velocity': array([-4.40531909e-01, 8.89086068e-01, 8.24670773e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.63843918, 15.62164688, 0.21275468]), + 'camera_rotation': array([-3.59730339, -0.22785294, -0.58368003]), + 'current_gear_input': False, + 'focus_actor_dist': 2509.520263671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 253.64221191, -3806.02880859, 16.48709106]), + 'frame': 25601, + 'frame_number': 25601, + 'framesequence': 98456, + 'gaze_dir': array([0.9728241 , 0.23090363, 0.01424408]), + 'gaze_origin': array([-2.95360732, -0.1725609 , -0.16690522]), + 'gaze_valid': True, + 'gaze_vergence': 263.27337646484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97116089, 0.23822021, 0.00953674]), + 'left_gaze_origin': array([-2.78315449, 2.67282271, -0.19544831]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3138427734375, + 'left_pupil_posn': array([ 0.4567194 , -0.20033956]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9744873 , 0.22358704, 0.01895142]), + 'right_gaze_origin': array([-3.12406039, -3.01794457, -0.13836212]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.837310791015625, + 'right_pupil_posn': array([-0.03536665, -0.27096188]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2896620035171509, + 'timestamp': 829.7851380780339, + 'timestamp_carla': 829787, + 'timestamp_device': 3983216, + 'timestamp_stream': 829.7851380780339, + 'transform': [array([ 3.64529109e+00, 1.49014921e+01, -1.43100740e-03]), + array([ -0.0610414 , -11.15169621, 0.02779632])]} +{'AngularVelocity': array([ 0.02195481, -0.0312433 , 8.09654903]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.94809341430664, + 'FR_Wheel_Angle': -19.68655776977539, + 'Location': array([ -1.80812049, -24.5953331 , 0.17136779]), + 'Rotation': array([-5.64310215e-02, -5.08214226e+01, 4.65773568e-02]), + 'Velocity': array([-4.64771956e-01, 9.56762373e-01, 4.66794969e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.59509659, 15.62649822, 0.18184529]), + 'camera_rotation': array([-3.73327184, -0.17866084, -0.58182371]), + 'current_gear_input': False, + 'focus_actor_dist': 2650.0810546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.47943115, -3943.66430664, 16.45042419]), + 'frame': 25602, + 'frame_number': 25602, + 'framesequence': 98460, + 'gaze_dir': array([0.9734726 , 0.22794342, 0.01618195]), + 'gaze_origin': array([-2.95270085, -0.17110367, -0.16537705]), + 'gaze_valid': True, + 'gaze_vergence': 243.28843688964844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97135925, 0.23725891, 0.01208496]), + 'left_gaze_origin': array([-2.7818284 , 2.67645264, -0.19365694]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2450408935546875, + 'left_pupil_posn': array([ 0.45239806, -0.19818294]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97558594, 0.21862793, 0.02027893]), + 'right_gaze_origin': array([-3.1235733 , -3.01866007, -0.13709718]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.838104248046875, + 'right_pupil_posn': array([-0.03526008, -0.26916659]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.29364460706710815, + 'timestamp': 829.817841976881, + 'timestamp_carla': 829819, + 'timestamp_device': 3983249, + 'timestamp_stream': 829.817841976881, + 'transform': [array([ 3.64700317e+00, 1.48863659e+01, -1.99178699e-03]), + array([ -0.06091845, -11.15571499, 0.02891225])]} +{'AngularVelocity': array([ 0.03662504, -0.02329369, 8.55113411]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.107275009155273, + 'FR_Wheel_Angle': -19.719451904296875, + 'Location': array([ -1.93175232, -24.37634659, 0.17151459]), + 'Rotation': array([ -0.0580771 , -48.94426727, 0.04966001]), + 'Velocity': array([-5.17540216e-01, 9.90701675e-01, 8.36348510e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.55033684, 15.62857533, 0.17408293]), + 'camera_rotation': array([-3.90021539, -0.11753245, -0.46261409]), + 'current_gear_input': False, + 'focus_actor_dist': 2622.798095703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.2366333 , -3919.49584961, 16.46214294]), + 'frame': 25603, + 'frame_number': 25603, + 'framesequence': 98464, + 'gaze_dir': array([0.9734726 , 0.22798157, 0.01660919]), + 'gaze_origin': array([-2.95273304, -0.17129213, -0.16549912]), + 'gaze_valid': True, + 'gaze_vergence': 258.70550537109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97158813, 0.23632812, 0.01237488]), + 'left_gaze_origin': array([-2.7818284 , 2.67721272, -0.19435731]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.246002197265625, + 'left_pupil_posn': array([ 0.45223033, -0.19848561]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97535706, 0.21963501, 0.02084351]), + 'right_gaze_origin': array([-3.12363744, -3.01979685, -0.13664094]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8067169189453125, + 'right_pupil_posn': array([-0.03476495, -0.26867139]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.29761195182800293, + 'timestamp': 829.8512978777289, + 'timestamp_carla': 829853, + 'timestamp_device': 3983282, + 'timestamp_stream': 829.8512978777289, + 'transform': [array([ 3.64498711e+00, 1.48699627e+01, -2.56612781e-03]), + array([ -0.06071355, -11.1523695 , 0.0300412 ])]} +{'AngularVelocity': array([ 0.04806755, -0.03378269, 9.29085159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.062572479248047, + 'FR_Wheel_Angle': -19.687868118286133, + 'Location': array([ -2.07158113, -24.14715576, 0.17169277]), + 'Rotation': array([ -0.06200445, -46.93880081, 0.04895359]), + 'Velocity': array([-6.00852549e-01, 1.05639255e+00, 5.84173191e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.52947998, 15.63892937, 0.15978718]), + 'camera_rotation': array([-4.02783728, -0.09012195, -0.51118833]), + 'current_gear_input': False, + 'focus_actor_dist': 2465.026123046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 247.42092896, -3765.87548828, 16.49371338]), + 'frame': 25604, + 'frame_number': 25604, + 'framesequence': 98468, + 'gaze_dir': array([0.9734726 , 0.22782898, 0.01843262]), + 'gaze_origin': array([-2.95268583, -0.17147294, -0.16534425]), + 'gaze_valid': True, + 'gaze_vergence': 247.5589599609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97175598, 0.23556519, 0.0133667 ]), + 'left_gaze_origin': array([-2.78178573, 2.67777872, -0.19427338]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.238677978515625, + 'left_pupil_posn': array([ 0.45200717, -0.19749773]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97518921, 0.22009277, 0.02349854]), + 'right_gaze_origin': array([-3.1235857 , -3.02072477, -0.13641509]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.806488037109375, + 'right_pupil_posn': array([-0.03437823, -0.26813817]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.3015792965888977, + 'timestamp': 829.8845543786883, + 'timestamp_carla': 829886, + 'timestamp_device': 3983316, + 'timestamp_stream': 829.8845543786883, + 'transform': [array([ 3.64593387e+00, 1.48518085e+01, -2.78169615e-03]), + array([ -0.06064525, -11.15498829, 0.03047342])]} +{'AngularVelocity': array([ 0.0575287 , -0.02245569, 9.94409847]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.02086639404297, + 'FR_Wheel_Angle': -19.659330368041992, + 'Location': array([ -2.23100162, -23.90604019, 0.17189197]), + 'Rotation': array([ -0.06436087, -44.78317642, 0.04854581]), + 'Velocity': array([-6.96028173e-01, 1.11840951e+00, 1.01881975e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.5027523 , 15.64597321, 0.13384524]), + 'camera_rotation': array([-4.15407991, -0.03770296, -0.4759661 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2457.79736328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 246.73864746, -3760.31347656, 16.49445343]), + 'frame': 25605, + 'frame_number': 25605, + 'framesequence': 98472, + 'gaze_dir': array([0.97304535, 0.22964478, 0.0189209 ]), + 'gaze_origin': array([-2.95238519, -0.17086945, -0.1651291 ]), + 'gaze_valid': True, + 'gaze_vergence': 273.7317199707031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97151184, 0.23651123, 0.01428223]), + 'left_gaze_origin': array([-2.7813127 , 2.67939019, -0.19431916]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2235260009765625, + 'left_pupil_posn': array([ 0.45182979, -0.19745362]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97457886, 0.22277832, 0.02355957]), + 'right_gaze_origin': array([-3.12345743, -3.02112913, -0.13593903]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.76812744140625, + 'right_pupil_posn': array([-0.03370696, -0.26742923]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.3055466413497925, + 'timestamp': 829.9182607792318, + 'timestamp_carla': 829920, + 'timestamp_device': 3983349, + 'timestamp_stream': 829.9182607792318, + 'transform': [array([ 3.64729857e+00, 1.48314400e+01, -3.20981978e-03]), + array([ -0.06046766, -11.15850258, 0.03131615])]} +{'AngularVelocity': array([ 0.08006751, 0.01429406, 10.64032841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.964012145996094, + 'FR_Wheel_Angle': -19.63066864013672, + 'Location': array([ -2.41331673, -23.65283203, 0.17210609]), + 'Rotation': array([ -0.06722955, -42.45332718, 0.04752801]), + 'Velocity': array([-8.14299822e-01, 1.18302238e+00, 9.83056962e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.47065544, 15.67072868, 0.10193886]), + 'camera_rotation': array([-4.24910831, -0.03696444, -0.49484628]), + 'current_gear_input': False, + 'focus_actor_dist': 2370.770751953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 235.09411621, -3675.51904297, 16.50694275]), + 'frame': 25606, + 'frame_number': 25606, + 'framesequence': 98476, + 'gaze_dir': array([0.97322083, 0.22849274, 0.0228653 ]), + 'gaze_origin': array([-2.95195031, -0.17153855, -0.16405031]), + 'gaze_valid': True, + 'gaze_vergence': 182.59054565429688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97184753, 0.23510742, 0.01527405]), + 'left_gaze_origin': array([-2.78053451, 2.6800952 , -0.19427338]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.185394287109375, + 'left_pupil_posn': array([ 0.45100522, -0.19484675]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97459412, 0.22187805, 0.03045654]), + 'right_gaze_origin': array([-3.12336588, -3.02317214, -0.13382721]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7344207763671875, + 'right_pupil_posn': array([-0.03275293, -0.26552546]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.31348133087158203, + 'timestamp': 829.9502102769911, + 'timestamp_carla': 829952, + 'timestamp_device': 3983382, + 'timestamp_stream': 829.9502102769911, + 'transform': [array([ 3.64794374e+00, 1.48109589e+01, -3.41974245e-03]), + array([ -0.06042668, -11.16060734, 0.03175921])]} +{'AngularVelocity': array([-0.0722573 , -0.03119144, 8.39300442]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.113853454589844, + 'FR_Wheel_Angle': -19.742700576782227, + 'Location': array([ -2.60055423, -23.41415405, 0.17223556]), + 'Rotation': array([ -0.05472347, -40.19630814, 0.05634307]), + 'Velocity': array([-6.78182125e-01, 9.09358501e-01, 7.00426113e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.44546318, 15.69386673, 0.07730381]), + 'camera_rotation': array([-4.37113619e+00, -2.67892634e-03, -4.84211445e-01]), + 'current_gear_input': False, + 'focus_actor_dist': 2490.599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 257.04544067, -3795.53271484, 16.48365021]), + 'frame': 25607, + 'frame_number': 25607, + 'framesequence': 98480, + 'gaze_dir': array([0.97492981, 0.22015381, 0.0267868 ]), + 'gaze_origin': array([-2.95146036, -0.17182617, -0.16334534]), + 'gaze_valid': True, + 'gaze_vergence': 124.63213348388672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97221375, 0.23348999, 0.0158844 ]), + 'left_gaze_origin': array([-2.77955484, 2.68043828, -0.19378664]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1357574462890625, + 'left_pupil_posn': array([ 0.44540405, -0.19137561]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97764587, 0.20681763, 0.03768921]), + 'right_gaze_origin': array([-3.12336588, -3.02409053, -0.13290407]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.738006591796875, + 'right_pupil_posn': array([-0.03267395, -0.26465571]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.3174487054347992, + 'timestamp': 829.9845491759479, + 'timestamp_carla': 829986, + 'timestamp_device': 3983416, + 'timestamp_stream': 829.9845491759479, + 'transform': [array([ 3.64748526e+00, 1.47874937e+01, -3.67858890e-03]), + array([ -0.06033789, -11.16063786, 0.03225659])]} +{'AngularVelocity': array([ 0.01319224, -0.0122454 , 5.83515644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.26038360595703, + 'FR_Wheel_Angle': -19.838191986083984, + 'Location': array([ -2.73943257, -23.24868202, 0.17234954]), + 'Rotation': array([ -0.04769521, -38.5789566 , 0.05687417]), + 'Velocity': array([-4.86372292e-01, 6.15105748e-01, 3.24525812e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.42945862, 15.71092224, 0.06870005]), + 'camera_rotation': array([-4.468822 , 0.03886611, -0.42246115]), + 'current_gear_input': False, + 'focus_actor_dist': 2577.986083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 255.00213623, -3887.36914062, 16.48519897]), + 'frame': 25608, + 'frame_number': 25608, + 'framesequence': 98484, + 'gaze_dir': array([0.97480011, 0.22010803, 0.0295105 ]), + 'gaze_origin': array([-2.95097899, -0.17173767, -0.16300736]), + 'gaze_valid': True, + 'gaze_vergence': 108.66474151611328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97138977, 0.23683167, 0.0174408 ]), + 'left_gaze_origin': array([-2.77850962, 2.68100595, -0.19393769]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.101654052734375, + 'left_pupil_posn': array([ 0.44376969, -0.18983006]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97821045, 0.2033844 , 0.0415802 ]), + 'right_gaze_origin': array([-3.12344837, -3.02448153, -0.13207704]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7405548095703125, + 'right_pupil_posn': array([-0.03120649, -0.26362181]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.3174487054347992, + 'timestamp': 830.0174059793353, + 'timestamp_carla': 830019, + 'timestamp_device': 3983449, + 'timestamp_stream': 830.0174059793353, + 'transform': [array([ 3.64688110e+00, 1.47631674e+01, -4.05494682e-03]), + array([ -0.06020128, -11.16041946, 0.03301667])]} +{'AngularVelocity': array([ 0.04199694, -0.03692402, 3.81153512]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.361764907836914, + 'FR_Wheel_Angle': -19.903409957885742, + 'Location': array([ -2.84933567, -23.12402534, 0.17416798]), + 'Rotation': array([ -0.10877076, -37.32749176, 0.13697462]), + 'Velocity': array([-3.24891031e-01, 3.92751813e-01, 2.98757543e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.40127563, 15.72711945, 0.06896024]), + 'camera_rotation': array([-4.53430939, 0.13138141, -0.37721291]), + 'current_gear_input': False, + 'focus_actor_dist': 2626.0869140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 266.39788818, -3936.53955078, 16.47317505]), + 'frame': 25609, + 'frame_number': 25609, + 'framesequence': 98488, + 'gaze_dir': array([0.98870087, 0.14408112, 0.03184509]), + 'gaze_origin': array([-2.92489481, -0.10911026, -0.15912476]), + 'gaze_valid': True, + 'gaze_vergence': 66.78459930419922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98706055, 0.15994263, 0.01098633]), + 'left_gaze_origin': array([-2.68993235, 2.75574517, -0.20710602]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.015625, + 'left_pupil_posn': array([ 0.36409605, -0.17604482]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99034119, 0.1282196 , 0.05270386]), + 'right_gaze_origin': array([-3.15985727, -2.97396564, -0.1111435 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7662811279296875, + 'right_pupil_posn': array([-0.09250063, -0.25681806]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.32538339495658875, + 'timestamp': 830.0523133762181, + 'timestamp_carla': 830054, + 'timestamp_device': 3983482, + 'timestamp_stream': 830.0523133762181, + 'transform': [array([ 3.64448977e+00, 1.47356462e+01, -4.49274061e-03]), + array([ -0.06005102, -11.15676117, 0.03386422])]} +{'AngularVelocity': array([ 0.02737458, -0.01587373, 2.62249923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.43194007873535, + 'FR_Wheel_Angle': -19.94853401184082, + 'Location': array([ -2.91508508, -23.05203247, 0.17411029]), + 'Rotation': array([ -0.10812872, -36.59072876, 0.12692294]), + 'Velocity': array([-0.2257681 , 0.26615283, -0.00036753]), + 'brake_input': 0.0, + 'camera_location': array([-7.38607025, 15.74363613, 0.06305687]), + 'camera_rotation': array([-4.59300804, 0.19789696, -0.40515083]), + 'current_gear_input': False, + 'focus_actor_dist': 2595.00634765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 66.40731812, -3940.71533203, 16.67873383]), + 'frame': 25610, + 'frame_number': 25610, + 'framesequence': 98492, + 'gaze_dir': array([ 0.99738312, -0.04853821, 0.04759216]), + 'gaze_origin': array([-3.00453115, 0.04376831, -0.12424317]), + 'gaze_valid': True, + 'gaze_vergence': 93.4659652709961, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99758911, -0.02964783, 0.06260681]), + 'left_gaze_origin': array([-2.93287373, 2.90805674, -0.10268403]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8242645263671875, + 'left_pupil_posn': array([ 0.19950628, -0.15837598]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99717712, -0.06742859, 0.03257751]), + 'right_gaze_origin': array([-3.0761888 , -2.82052016, -0.1458023 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.90460205078125, + 'right_pupil_posn': array([-0.26381195, -0.24316478]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.32538339495658875, + 'timestamp': 830.0838845781982, + 'timestamp_carla': 830085, + 'timestamp_device': 3983516, + 'timestamp_stream': 830.0838845781982, + 'transform': [array([ 3.64837694e+00, 1.47075062e+01, -4.96551488e-03]), + array([ -0.05987344, -11.16561127, 0.03483918])]} +{'AngularVelocity': array([ 0.31499854, -0.88950777, 1.90495908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.475872039794922, + 'FR_Wheel_Angle': -19.975894927978516, + 'Location': array([ -2.95358706, -23.01072121, 0.17322508]), + 'Rotation': array([ -0.07079491, -36.16275024, 0.05509901]), + 'Velocity': array([-0.17398317, 0.18934329, -0.01193489]), + 'brake_input': 0.0, + 'camera_location': array([-7.37432957, 15.75998497, 0.04806089]), + 'camera_rotation': array([-4.65082598, 0.23447435, -0.47159716]), + 'current_gear_input': False, + 'focus_actor_dist': 3617.05517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -498.05349731, -4979.19921875, 17.25973511]), + 'frame': 25611, + 'frame_number': 25611, + 'framesequence': 98496, + 'gaze_dir': array([ 0.9814682 , -0.17880249, 0.06330872]), + 'gaze_origin': array([-2.96101236, 0.14029847, -0.144899 ]), + 'gaze_valid': True, + 'gaze_vergence': 102.93061065673828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98580933, -0.15289307, 0.06912231]), + 'left_gaze_origin': array([-2.80529642, 2.99196959, -0.14820252]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8139801025390625, + 'left_pupil_posn': array([ 0.09508336, -0.15671003]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97712708, -0.20471191, 0.05749512]), + 'right_gaze_origin': array([-3.11672831, -2.71137238, -0.14159547]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.915740966796875, + 'right_pupil_posn': array([-0.38317776, -0.24627244]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2856946587562561, + 'timestamp': 830.117876175791, + 'timestamp_carla': 830119, + 'timestamp_device': 3983549, + 'timestamp_stream': 830.117876175791, + 'transform': [array([ 3.64971185e+00, 1.46760998e+01, -5.20246476e-03]), + array([ -0.05981879, -11.16952229, 0.03530768])]} +{'AngularVelocity': array([0.00598673, 0.03078641, 1.38600171]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.504043579101562, + 'FR_Wheel_Angle': -19.994205474853516, + 'Location': array([ -2.98323607, -22.97942352, 0.17256528]), + 'Rotation': array([ -0.05550895, -35.83608627, 0.03618115]), + 'Velocity': array([-0.12109332, 0.13904142, 0.00040878]), + 'brake_input': 0.0, + 'camera_location': array([-7.33960629, 15.73999405, 0.03296952]), + 'camera_rotation': array([-4.65208244, 0.1657232 , -0.42168131]), + 'current_gear_input': False, + 'focus_actor_dist': 1859.6903076171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -623.94818115, -3198.17626953, 101.9103775 ]), + 'frame': 25612, + 'frame_number': 25612, + 'framesequence': 98500, + 'gaze_dir': array([ 0.97853088, -0.19605255, 0.05921173]), + 'gaze_origin': array([-2.96522522, 0.15597382, -0.14620362]), + 'gaze_valid': True, + 'gaze_vergence': 118.0250473022461, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98246765, -0.1743927 , 0.06582642]), + 'left_gaze_origin': array([-2.80872369, 3.00910044, -0.15091249]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.842926025390625, + 'left_pupil_posn': array([ 0.07920432, -0.16098452]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97459412, -0.2177124 , 0.05259705]), + 'right_gaze_origin': array([-3.12172723, -2.69715285, -0.14149475]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9755096435546875, + 'right_pupil_posn': array([-0.40103304, -0.2481941 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00021973327966406941, + 'throttle_input': 0.21428243815898895, + 'timestamp': 830.1516756787896, + 'timestamp_carla': 830153, + 'timestamp_device': 3983582, + 'timestamp_stream': 830.1516756787896, + 'transform': [array([ 3.65069509e+00, 1.46430311e+01, -5.40660834e-03]), + array([ -0.05977098, -11.1728096 , 0.03572224])]} +{'AngularVelocity': array([-0.00047542, 0.00624182, -0.18234587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.53871726989746, + 'FR_Wheel_Angle': -20.017934799194336, + 'Location': array([ -3.00167346, -22.96012306, 0.17268439]), + 'Rotation': array([ -0.05865766, -35.63583374, 0.03806779]), + 'Velocity': array([-0.07216171, 0.08460277, 0.00046318]), + 'brake_input': 0.0, + 'camera_location': array([-7.28713608, 15.67311478, 0.03230534]), + 'camera_rotation': array([-4.61897659, -0.23293523, -0.38494751]), + 'current_gear_input': False, + 'focus_actor_dist': 1863.1773681640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -658.85809326, -3197.44238281, 94.73667908]), + 'frame': 25613, + 'frame_number': 25613, + 'framesequence': 98504, + 'gaze_dir': array([ 0.98023987, -0.18728638, 0.05957794]), + 'gaze_origin': array([-2.96438003, 0.15100327, -0.14904405]), + 'gaze_valid': True, + 'gaze_vergence': 125.75120544433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98419189, -0.16557312, 0.06283569]), + 'left_gaze_origin': array([-2.80934 , 3.00664997, -0.15425873]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8203582763671875, + 'left_pupil_posn': array([ 0.08384693, -0.1619544 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97628784, -0.20899963, 0.05632019]), + 'right_gaze_origin': array([-3.11942005, -2.70464349, -0.14382935]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8977813720703125, + 'right_pupil_posn': array([-0.3925575 , -0.25075579]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0005859553930349648, + 'throttle_input': 0.15475699305534363, + 'timestamp': 830.1849222779274, + 'timestamp_carla': 830186, + 'timestamp_device': 3983616, + 'timestamp_stream': 830.1849222779274, + 'transform': [array([ 3.65137315e+00, 1.46087427e+01, -5.55294007e-03]), + array([ -0.05977098, -11.17556572, 0.03603479])]} +{'AngularVelocity': array([ 0.01199712, 0.01440295, -0.28784999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.544679641723633, + 'FR_Wheel_Angle': -20.032752990722656, + 'Location': array([ -3.01336932, -22.94776726, 0.17275748]), + 'Rotation': array([ -0.06210008, -35.50265884, 0.03695584]), + 'Velocity': array([-0.06414989, 0.07353316, 0.00023145]), + 'brake_input': 0.0, + 'camera_location': array([-7.21284103, 15.57363033, 0.03787535]), + 'camera_rotation': array([-4.5053153 , -0.8477307 , -0.32274407]), + 'current_gear_input': False, + 'focus_actor_dist': 1859.1588134765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -654.55560303, -3197.65527344, 96.64505005]), + 'frame': 25614, + 'frame_number': 25614, + 'framesequence': 98508, + 'gaze_dir': array([ 0.98078156, -0.18600464, 0.05412292]), + 'gaze_origin': array([-2.9641695 , 0.14770737, -0.15147325]), + 'gaze_valid': True, + 'gaze_vergence': 119.47065734863281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98451233, -0.16444397, 0.06054688]), + 'left_gaze_origin': array([-2.80989528, 3.00532699, -0.15754701]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7227783203125, + 'left_pupil_posn': array([ 0.08514369, -0.16698813]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97705078, -0.20756531, 0.04769897]), + 'right_gaze_origin': array([-3.11844349, -2.7099123 , -0.14539948]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8586273193359375, + 'right_pupil_posn': array([-0.38851732, -0.25231338]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00188604393042624, + 'throttle_input': 0.11903563141822815, + 'timestamp': 830.2191835790873, + 'timestamp_carla': 830221, + 'timestamp_device': 3983649, + 'timestamp_stream': 830.2191835790873, + 'transform': [array([ 3.65138364e+00, 1.45723886e+01, -5.30773168e-03]), + array([ -0.05998272, -11.17714596, 0.03556531])]} +{'AngularVelocity': array([0.00327952, 0.005597 , 1.52988541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.86452293395996, + 'FR_Wheel_Angle': -20.293174743652344, + 'Location': array([ -3.0249505 , -22.9359169 , 0.17280179]), + 'Rotation': array([ -0.06350709, -35.36203003, 0.03677177]), + 'Velocity': array([-4.48592938e-02, 4.98776697e-02, 9.09662194e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.14787865, 15.46279526, 0.02403558]), + 'camera_rotation': array([-4.61964607, -1.4780612 , -0.33244738]), + 'current_gear_input': False, + 'focus_actor_dist': 1859.136474609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -671.71691895, -3197.19458008, 90.49267578]), + 'frame': 25615, + 'frame_number': 25615, + 'framesequence': 98512, + 'gaze_dir': array([ 0.98279572, -0.17592621, 0.05046844]), + 'gaze_origin': array([-2.94800591, 0.14229508, -0.15417023]), + 'gaze_valid': True, + 'gaze_vergence': 101.37969207763672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98594666, -0.15490723, 0.06251526]), + 'left_gaze_origin': array([-2.81095457, 3.00159168, -0.15476838]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6541748046875, + 'left_pupil_posn': array([ 0.09128451, -0.16828799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97964478, -0.19694519, 0.03842163]), + 'right_gaze_origin': array([-3.08505726, -2.71700144, -0.15357208]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8333740234375, + 'right_pupil_posn': array([-0.37963861, -0.25058961]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0035706658381968737, + 'throttle_input': 0.08729686588048935, + 'timestamp': 830.25134607777, + 'timestamp_carla': 830253, + 'timestamp_device': 3983682, + 'timestamp_stream': 830.25134607777, + 'transform': [array([ 3.65178084e+00, 1.45372057e+01, -4.89343610e-03]), + array([ -0.06027642, -11.17950153, 0.03479924])]} +{'AngularVelocity': array([0.22006975, 0.09344415, 2.39203191]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.359130859375, + 'FR_Wheel_Angle': -20.598575592041016, + 'Location': array([ -3.03696465, -22.92354012, 0.17285265]), + 'Rotation': array([-6.98250234e-02, -3.52191772e+01, 3.13364901e-02]), + 'Velocity': array([-1.82672635e-01, 1.95909977e-01, 7.20405587e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.10304260e+00, 1.53289204e+01, -4.75792121e-03]), + 'camera_rotation': array([-4.8987751 , -2.32144189, -0.41904509]), + 'current_gear_input': False, + 'focus_actor_dist': 1855.97509765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -672.57214355, -3197.20849609, 79.8883667 ]), + 'frame': 25616, + 'frame_number': 25616, + 'framesequence': 98516, + 'gaze_dir': array([ 0.98296356, -0.17142487, 0.06304169]), + 'gaze_origin': array([-2.88740873, 0.13469391, -0.17323838]), + 'gaze_valid': True, + 'gaze_vergence': 105.39289093017578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98469543, -0.1565094 , 0.07658386]), + 'left_gaze_origin': array([-2.81951308, 2.9954989 , -0.14999238]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7025909423828125, + 'left_pupil_posn': array([ 0.09906423, -0.16297209]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98123169, -0.18634033, 0.04949951]), + 'right_gaze_origin': array([-2.95530415, -2.72611094, -0.19648439]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.878753662109375, + 'right_pupil_posn': array([-0.37181664, -0.24986637]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.005584887228906155, + 'throttle_input': 0.051590751856565475, + 'timestamp': 830.285780377686, + 'timestamp_carla': 830287, + 'timestamp_device': 3983716, + 'timestamp_stream': 830.285780377686, + 'transform': [array([ 3.65294313e+00, 1.44988890e+01, -4.15285118e-03]), + array([ -0.06073404, -11.18362236, 0.03335409])]} +{'AngularVelocity': array([ 0.07537294, -0.02788177, 4.84489298]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.873085021972656, + 'FR_Wheel_Angle': -20.959835052490234, + 'Location': array([ -3.09379053, -22.86527443, 0.17295957]), + 'Rotation': array([-8.16002637e-02, -3.45784454e+01, 2.26484500e-02]), + 'Velocity': array([-0.36100388, 0.41624141, 0.00153739]), + 'brake_input': 0.0, + 'camera_location': array([-7.03020287, 15.17667007, -0.02238172]), + 'camera_rotation': array([-5.05153227, -3.18281245, -0.42863926]), + 'current_gear_input': False, + 'focus_actor_dist': 1856.33349609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -691.52197266, -3197.16894531, 93.74785614]), + 'frame': 25617, + 'frame_number': 25617, + 'framesequence': 98520, + 'gaze_dir': array([ 0.98592377, -0.15538025, 0.05835724]), + 'gaze_origin': array([-2.93505883, 0.1254036 , -0.15939637]), + 'gaze_valid': True, + 'gaze_vergence': 100.74311828613281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98721313, -0.14187622, 0.07263184]), + 'left_gaze_origin': array([-2.87070489, 2.9876008 , -0.13562775]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.737274169921875, + 'left_pupil_posn': array([ 0.1105293 , -0.16477871]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9846344 , -0.16888428, 0.04408264]), + 'right_gaze_origin': array([-2.99941254, -2.73679376, -0.183165 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8220062255859375, + 'right_pupil_posn': array([-0.36006349, -0.25020659]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.007507553789764643, + 'throttle_input': 0.0238040741533041, + 'timestamp': 830.3203151784837, + 'timestamp_carla': 830322, + 'timestamp_device': 3983749, + 'timestamp_stream': 830.3203151784837, + 'transform': [array([ 3.65486622e+00, 1.44600439e+01, -3.21117393e-03]), + array([ -0.06125313, -11.18938255, 0.03152332])]} +{'AngularVelocity': array([-0.10301363, 0.0146114 , 4.20429611]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.444726943969727, + 'FR_Wheel_Angle': -21.408647537231445, + 'Location': array([ -3.17100644, -22.78620529, 0.1730274 ]), + 'Rotation': array([-7.33357370e-02, -3.36760712e+01, 2.90823672e-02]), + 'Velocity': array([-3.71883839e-01, 4.04980153e-01, 3.87029635e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.93997478, 15.00811958, -0.04950819]), + 'camera_rotation': array([-5.13835764, -4.1543541 , -0.45388541]), + 'current_gear_input': False, + 'focus_actor_dist': 1852.25244140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -688.61956787, -3197.16894531, 79.97465515]), + 'frame': 25618, + 'frame_number': 25618, + 'framesequence': 98524, + 'gaze_dir': array([ 0.98838806, -0.13986969, 0.05573273]), + 'gaze_origin': array([-3.02436543, 0.1201233 , -0.13067169]), + 'gaze_valid': True, + 'gaze_vergence': 43.61216735839844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9881134 , -0.13426208, 0.07467651]), + 'left_gaze_origin': array([-3.04127526, 2.98632073, -0.08046418]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.852935791015625, + 'left_pupil_posn': array([ 0.12036896, -0.1629926 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98866272, -0.14547729, 0.03678894]), + 'right_gaze_origin': array([-3.00745559, -2.7460742 , -0.18087922]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8936614990234375, + 'right_pupil_posn': array([-0.351053 , -0.24955904]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00948515348136425, + 'throttle_input': 0.0, + 'timestamp': 830.3526419773698, + 'timestamp_carla': 830354, + 'timestamp_device': 3983782, + 'timestamp_stream': 830.3526419773698, + 'transform': [array([ 3.65464377e+00, 1.44230709e+01, -2.67276750e-03]), + array([ -0.06093894, -11.19057274, 0.03052498])]} +{'AngularVelocity': array([-0.07598091, 0.03719231, 4.34951019]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.151935577392578, + 'FR_Wheel_Angle': -22.695648193359375, + 'Location': array([ -3.24807334, -22.70800018, 0.17298123]), + 'Rotation': array([ -0.06689487, -32.74066925, 0.03287359]), + 'Velocity': array([-0.33841377, 0.3653343 , -0.00093563]), + 'brake_input': 0.0, + 'camera_location': array([-6.89854431, 14.8317318 , -0.09196937]), + 'camera_rotation': array([-5.3524704 , -5.21198082, -0.52304721]), + 'current_gear_input': False, + 'focus_actor_dist': 1849.1756591796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -690.56958008, -3197.16894531, 72.11442566]), + 'frame': 25619, + 'frame_number': 25619, + 'framesequence': 98528, + 'gaze_dir': array([ 0.97289276, -0.2260437 , 0.03972626]), + 'gaze_origin': array([-2.96368575, 0.1721428 , -0.1634102 ]), + 'gaze_valid': True, + 'gaze_vergence': 69.43815612792969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97640991, -0.20732117, 0.06015015]), + 'left_gaze_origin': array([-2.86768794, 3.02944207, -0.14613342]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8304290771484375, + 'left_pupil_posn': array([ 0.05652094, -0.1810925 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96937561, -0.24476624, 0.01930237]), + 'right_gaze_origin': array([-3.05968332, -2.68515635, -0.18068697]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0232391357421875, + 'right_pupil_posn': array([-0.42047483, -0.26575005]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.011224707588553429, + 'throttle_input': 0.0, + 'timestamp': 830.3847438767552, + 'timestamp_carla': 830386, + 'timestamp_device': 3983816, + 'timestamp_stream': 830.3847438767552, + 'transform': [array([ 3.65389252e+00, 1.43858337e+01, -2.16951361e-03]), + array([ -0.06080234, -11.19063663, 0.02958587])]} +{'AngularVelocity': array([-0.01205618, -0.0057644 , 4.62076616]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.165973663330078, + 'FR_Wheel_Angle': -23.86111068725586, + 'Location': array([ -3.31312132, -22.64239883, 0.17308985]), + 'Rotation': array([ -0.06390325, -31.89686203, 0.03490723]), + 'Velocity': array([-0.27095923, 0.30037963, 0.0006622 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.85232353, 14.67423248, -0.14619628]), + 'camera_rotation': array([-5.5926199 , -6.13563824, -0.57385623]), + 'current_gear_input': False, + 'focus_actor_dist': 977.769775390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -588.04248047, -2323.60180664, 82.62968445]), + 'frame': 25620, + 'frame_number': 25620, + 'framesequence': 98532, + 'gaze_dir': array([ 0.97368622, -0.22245789, 0.04377747]), + 'gaze_origin': array([-2.96387959, 0.17402191, -0.16231538]), + 'gaze_valid': True, + 'gaze_vergence': 90.80390167236328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97671509, -0.20614624, 0.05938721]), + 'left_gaze_origin': array([-2.86922765, 3.03073144, -0.14669496]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8769073486328125, + 'left_pupil_posn': array([ 0.05774367, -0.17865741]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97065735, -0.23876953, 0.02816772]), + 'right_gaze_origin': array([-3.05853128, -2.68268752, -0.17793581]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.99237060546875, + 'right_pupil_posn': array([-0.42170799, -0.26388347]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.012561419047415257, + 'throttle_input': 0.0, + 'timestamp': 830.4189672768116, + 'timestamp_carla': 830421, + 'timestamp_device': 3983849, + 'timestamp_stream': 830.4189672768116, + 'transform': [array([ 3.65305042e+00, 1.43458786e+01, -1.50341028e-03]), + array([ -0.06091845, -11.19063568, 0.02828927])]} +{'AngularVelocity': array([-0.02587678, 0.0065329 , 4.15072441]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.797924041748047, + 'FR_Wheel_Angle': -24.909358978271484, + 'Location': array([ -3.37315702, -22.582304 , 0.17317507]), + 'Rotation': array([ -0.06403302, -31.08216095, 0.03425255]), + 'Velocity': array([-2.22327292e-01, 2.43981227e-01, 7.86304445e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.80333042, 14.5139246 , -0.16967709]), + 'camera_rotation': array([-5.82329607, -6.98875809, -0.67160428]), + 'current_gear_input': False, + 'focus_actor_dist': 976.9473266601562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -599.40582275, -2322.45141602, 82.36043549]), + 'frame': 25621, + 'frame_number': 25621, + 'framesequence': 98536, + 'gaze_dir': array([ 0.97625732, -0.21150208, 0.04388428]), + 'gaze_origin': array([-2.96134281, 0.16510926, -0.16210482]), + 'gaze_valid': True, + 'gaze_vergence': 152.92864990234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97859192, -0.19895935, 0.05249023]), + 'left_gaze_origin': array([-2.86956334, 3.02291584, -0.14362337]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9018707275390625, + 'left_pupil_posn': array([ 0.06805897, -0.17399287]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97392273, -0.2240448 , 0.03527832]), + 'right_gaze_origin': array([-3.05312204, -2.69269729, -0.18058625]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0113067626953125, + 'right_pupil_posn': array([-0.41210902, -0.26686025]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0142277292907238, + 'throttle_input': 0.0, + 'timestamp': 830.4509480781853, + 'timestamp_carla': 830453, + 'timestamp_device': 3983882, + 'timestamp_stream': 830.4509480781853, + 'transform': [array([ 3.65226674e+00, 1.43085566e+01, -7.32479093e-04]), + array([ -0.06115751, -11.19063568, 0.02682585])]} +{'AngularVelocity': array([ 0.09578031, -0.01334366, 3.19644618]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.33918762207031, + 'FR_Wheel_Angle': -25.875539779663086, + 'Location': array([ -3.42676783, -22.52861023, 0.17324026]), + 'Rotation': array([ -0.06671046, -30.31805992, 0.03059316]), + 'Velocity': array([-0.22433215, 0.25850552, 0.00039234]), + 'brake_input': 0.0, + 'camera_location': array([-6.75636482, 14.33387375, -0.17852885]), + 'camera_rotation': array([-5.93558455, -7.95181942, -0.91784918]), + 'current_gear_input': False, + 'focus_actor_dist': 972.6514892578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -601.46502686, -2320.99829102, 78.36112976]), + 'frame': 25622, + 'frame_number': 25622, + 'framesequence': 98540, + 'gaze_dir': array([ 0.97805023, -0.2014389 , 0.0483017 ]), + 'gaze_origin': array([-2.95738697, 0.15408936, -0.16267702]), + 'gaze_valid': True, + 'gaze_vergence': 89.38516998291016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98033142, -0.18655396, 0.06427002]), + 'left_gaze_origin': array([-2.87097335, 3.01313639, -0.14263764]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0614776611328125, + 'left_pupil_posn': array([ 0.0773747 , -0.17460835]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97576904, -0.21632385, 0.03233337]), + 'right_gaze_origin': array([-3.04380035, -2.70495772, -0.18271637]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.966766357421875, + 'right_pupil_posn': array([-0.39883006, -0.26245403]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.016150396317243576, + 'throttle_input': 0.0, + 'timestamp': 830.4854373782873, + 'timestamp_carla': 830487, + 'timestamp_device': 3983916, + 'timestamp_stream': 830.4854373782873, + 'transform': [array([3.65142632e+00, 1.42685089e+01, 1.51004788e-04]), + array([ -0.0614717 , -11.19063473, 0.02509854])]} +{'AngularVelocity': array([-0.0990483 , 0.01797272, 3.28365517]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.28447341918945, + 'FR_Wheel_Angle': -27.15733528137207, + 'Location': array([ -3.47848392, -22.47742653, 0.17332032]), + 'Rotation': array([-7.06514716e-02, -2.95456829e+01, 2.64743529e-02]), + 'Velocity': array([-0.2516152 , 0.27632317, 0.00055512]), + 'brake_input': 0.0, + 'camera_location': array([-6.73504829, 14.16003036, -0.21131516]), + 'camera_rotation': array([-6.11680269, -8.86361313, -1.06047928]), + 'current_gear_input': False, + 'focus_actor_dist': 970.9197998046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -607.24707031, -2320.9375 , 79.94128418]), + 'frame': 25623, + 'frame_number': 25623, + 'framesequence': 98544, + 'gaze_dir': array([ 0.98104858, -0.18609619, 0.04829407]), + 'gaze_origin': array([-2.95284128, 0.14591447, -0.16151504]), + 'gaze_valid': True, + 'gaze_vergence': 76.43522644042969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98294067, -0.17137146, 0.06666565]), + 'left_gaze_origin': array([-2.8777802 , 3.00583196, -0.13960877]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9954833984375, + 'left_pupil_posn': array([ 0.08764553, -0.17451823]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97915649, -0.20082092, 0.02992249]), + 'right_gaze_origin': array([-3.02790236, -2.71400309, -0.18342134]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8815155029296875, + 'right_pupil_posn': array([-0.38673526, -0.25882232]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01820123940706253, + 'throttle_input': 0.0238040741533041, + 'timestamp': 830.5186339765787, + 'timestamp_carla': 830520, + 'timestamp_device': 3983949, + 'timestamp_stream': 830.5186339765787, + 'transform': [array([3.65557051e+00, 1.42300529e+01, 1.40388485e-03]), + array([ -0.06305631, -11.20101452, 0.02266606])]} +{'AngularVelocity': array([-0.13588962, 0.02233449, 3.66887474]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.05134201049805, + 'FR_Wheel_Angle': -28.923038482666016, + 'Location': array([ -3.53762221, -22.41825676, 0.17336752]), + 'Rotation': array([ -0.06735249, -28.60390282, 0.02931458]), + 'Velocity': array([-2.06533730e-01, 2.26554558e-01, 1.21269222e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.7351799 , 13.99630928, -0.25047705]), + 'camera_rotation': array([-6.28121901, -9.73366928, -1.25967407]), + 'current_gear_input': False, + 'focus_actor_dist': 967.5931396484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -606.5847168 , -2321.54174805, 76.55574036]), + 'frame': 25624, + 'frame_number': 25624, + 'framesequence': 98548, + 'gaze_dir': array([ 0.98439026, -0.16881561, 0.04331207]), + 'gaze_origin': array([-3.02935123, 0.13836594, -0.13435899]), + 'gaze_valid': True, + 'gaze_vergence': 81.57351684570312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98638916, -0.15266418, 0.06080627]), + 'left_gaze_origin': array([-2.90643167, 2.99932408, -0.12671967]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9695587158203125, + 'left_pupil_posn': array([ 0.09749782, -0.17249644]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98239136, -0.18496704, 0.02581787]), + 'right_gaze_origin': array([-3.15227056, -2.72259235, -0.14199831]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0223388671875, + 'right_pupil_posn': array([-0.37606233, -0.25676906]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.020123906433582306, + 'throttle_input': 0.059525445103645325, + 'timestamp': 830.5525568760931, + 'timestamp_carla': 830554, + 'timestamp_device': 3983982, + 'timestamp_stream': 830.5525568760931, + 'transform': [array([3.66299248e+00, 1.41915302e+01, 2.85957335e-03]), + array([ -0.06434721, -11.21821404, 0.01982813])]} +{'AngularVelocity': array([ 0.01689759, -0.00974277, 3.37787008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.28738784790039, + 'FR_Wheel_Angle': -30.771278381347656, + 'Location': array([ -3.58946919, -22.36499214, 0.17343344]), + 'Rotation': array([ -0.06610256, -27.692276 , 0.02959598]), + 'Velocity': array([-1.62121996e-01, 1.96650699e-01, 7.17449147e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.7422657 , 13.84357071, -0.26276651]), + 'camera_rotation': array([ -6.3588171 , -10.62875462, -1.56075454]), + 'current_gear_input': False, + 'focus_actor_dist': 963.4154663085938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -603.26049805, -2321.54174805, 68.67995453]), + 'frame': 25625, + 'frame_number': 25625, + 'framesequence': 98552, + 'gaze_dir': array([ 0.9861908 , -0.1546402 , 0.04872894]), + 'gaze_origin': array([-3.05029917, 0.13262863, -0.12860183]), + 'gaze_valid': True, + 'gaze_vergence': 1.5713471174240112, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98448181, -0.1550293 , 0.08204651]), + 'left_gaze_origin': array([-3.15203261, 3.00253153, -0.04775086]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.02850341796875, + 'left_pupil_posn': array([ 0.10705173, -0.17040324]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98789978, -0.1542511 , 0.01541138]), + 'right_gaze_origin': array([-2.94856572, -2.73727417, -0.20945284]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.10076904296875, + 'right_pupil_posn': array([-0.36375999, -0.25541401]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.021936707198619843, + 'throttle_input': 0.1111009418964386, + 'timestamp': 830.5858887769282, + 'timestamp_carla': 830587, + 'timestamp_device': 3984016, + 'timestamp_stream': 830.5858887769282, + 'transform': [array([3.67106915e+00, 1.41546612e+01, 4.11525695e-03]), + array([ -0.06507804, -11.23675728, 0.01739789])]} +{'AngularVelocity': array([-0.03503913, 0.01861494, 3.6503098 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.854122161865234, + 'FR_Wheel_Angle': -30.899221420288086, + 'Location': array([ -3.6256249 , -22.32747078, 0.1734411 ]), + 'Rotation': array([ -0.06679925, -27.00175285, 0.02908105]), + 'Velocity': array([-0.13532721, 0.15662037, -0.00023129]), + 'brake_input': 0.0, + 'camera_location': array([-6.77470779, 13.70611286, -0.26487294]), + 'camera_rotation': array([ -6.4116621 , -11.34519291, -1.51515532]), + 'current_gear_input': False, + 'focus_actor_dist': 959.9803466796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -604.02832031, -2321.54174805, 72.07247925]), + 'frame': 25626, + 'frame_number': 25626, + 'framesequence': 98556, + 'gaze_dir': array([ 0.98842621, -0.14128113, 0.04640198]), + 'gaze_origin': array([-3.06364298, 0.12859803, -0.12309571]), + 'gaze_valid': True, + 'gaze_vergence': 12.469494819641113, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9863739 , -0.14605713, 0.07559204]), + 'left_gaze_origin': array([-3.18323231, 2.99826813, -0.03767395]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9454345703125, + 'left_pupil_posn': array([ 0.11630833, -0.16879213]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99047852, -0.13650513, 0.01721191]), + 'right_gaze_origin': array([-2.94405365, -2.74107218, -0.20851746]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09576416015625, + 'right_pupil_posn': array([-0.35787845, -0.25615168]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.024079104885458946, + 'throttle_input': 0.15475699305534363, + 'timestamp': 830.61872067675, + 'timestamp_carla': 830620, + 'timestamp_device': 3984049, + 'timestamp_stream': 830.61872067675, + 'transform': [array([3.67908621e+00, 1.41190987e+01, 4.99378191e-03]), + array([ -0.06546053, -11.25522518, 0.01571161])]} +{'AngularVelocity': array([-0.01141131, 0.01344737, 3.20731354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.88270950317383, + 'FR_Wheel_Angle': -30.919340133666992, + 'Location': array([ -3.6542387 , -22.29848671, 0.17349622]), + 'Rotation': array([ -0.06722955, -26.46564674, 0.02878093]), + 'Velocity': array([-0.11062159, 0.12383206, 0.00022001]), + 'brake_input': 0.0, + 'camera_location': array([-6.81938934, 13.60276031, -0.25530148]), + 'camera_rotation': array([ -6.42708492, -11.94879818, -1.56490815]), + 'current_gear_input': False, + 'focus_actor_dist': 956.182861328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -602.1151123 , -2321.54174805, 69.43104553]), + 'frame': 25627, + 'frame_number': 25627, + 'framesequence': 98560, + 'gaze_dir': array([ 0.98880005, -0.13923645, 0.04460144]), + 'gaze_origin': array([-3.04478168, 0.1198555 , -0.1299431 ]), + 'gaze_valid': True, + 'gaze_vergence': 7.614500045776367, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98768616, -0.13766479, 0.07421875]), + 'left_gaze_origin': array([-3.11629343, 2.98824954, -0.05827942]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0478057861328125, + 'left_pupil_posn': array([ 0.12135983, -0.17058873]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98991394, -0.14080811, 0.01498413]), + 'right_gaze_origin': array([-2.97326994, -2.74853826, -0.20160675]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0060272216796875, + 'right_pupil_posn': array([-0.35025907, -0.25743604]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.026496171951293945, + 'throttle_input': 0.16665904223918915, + 'timestamp': 830.6518041789532, + 'timestamp_carla': 830653, + 'timestamp_device': 3984082, + 'timestamp_stream': 830.6518041789532, + 'transform': [array([3.68749142e+00, 1.40836201e+01, 5.46035776e-03]), + array([ -0.06565861, -11.27460384, 0.01482369])]} +{'AngularVelocity': array([-0.02112735, 0.00638216, 2.41160297]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.9217529296875, + 'FR_Wheel_Angle': -30.940889358520508, + 'Location': array([ -3.6765573 , -22.2763195 , 0.17350183]), + 'Rotation': array([ -0.06713393, -26.05933571, 0.02883878]), + 'Velocity': array([-0.07506975, 0.08136889, -0.00010268]), + 'brake_input': 0.0, + 'camera_location': array([-6.84151554, 13.48830414, -0.25062022]), + 'camera_rotation': array([ -6.35461664, -12.54382229, -1.73468947]), + 'current_gear_input': False, + 'focus_actor_dist': 955.9832153320312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -610.02337646, -2321.54174805, 67.3611145 ]), + 'frame': 25628, + 'frame_number': 25628, + 'framesequence': 98564, + 'gaze_dir': array([ 0.99032593, -0.1293869 , 0.04284668]), + 'gaze_origin': array([-3.05940557, 0.11286469, -0.12702943]), + 'gaze_valid': True, + 'gaze_vergence': 2.297666549682617, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98919678, -0.12960815, 0.06826782]), + 'left_gaze_origin': array([-3.15252256, 2.98333907, -0.04762726]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.87847900390625, + 'left_pupil_posn': array([ 0.12892675, -0.16937077]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99145508, -0.12916565, 0.01742554]), + 'right_gaze_origin': array([-2.96628881, -2.75760961, -0.20643158]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9751129150390625, + 'right_pupil_posn': array([-0.34124893, -0.26136303]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.028894925490021706, + 'throttle_input': 0.16665904223918915, + 'timestamp': 830.6869905777276, + 'timestamp_carla': 830689, + 'timestamp_device': 3984116, + 'timestamp_stream': 830.6869905777276, + 'transform': [array([3.69695544e+00, 1.40458746e+01, 5.49837109e-03]), + array([ -0.06570642, -11.29639339, 0.01474172])]} +{'AngularVelocity': array([-0.01184968, 0.00981795, 2.12951231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.94895935058594, + 'FR_Wheel_Angle': -30.954071044921875, + 'Location': array([ -3.6887958 , -22.2642746 , 0.17347628]), + 'Rotation': array([ -0.0671066 , -25.83267975, 0.02843669]), + 'Velocity': array([-0.05158391, 0.0546122 , -0.00060098]), + 'brake_input': 0.0, + 'camera_location': array([-6.87553024, 13.38635921, -0.25029871]), + 'camera_rotation': array([ -6.27583694, -12.9985714 , -1.90146303]), + 'current_gear_input': False, + 'focus_actor_dist': 952.7852172851562, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -609.77819824, -2321.54174805, 66.84130096]), + 'frame': 25629, + 'frame_number': 25629, + 'framesequence': 98568, + 'gaze_dir': array([ 0.99042511, -0.12856293, 0.04232788]), + 'gaze_origin': array([-3.06502032, 0.11239395, -0.12496033]), + 'gaze_valid': True, + 'gaze_vergence': 5.036912441253662, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98901367, -0.13061523, 0.06918335]), + 'left_gaze_origin': array([-3.15417957, 2.98278379, -0.04681397]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9478302001953125, + 'left_pupil_posn': array([ 0.13028371, -0.1698724 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99183655, -0.12651062, 0.01547241]), + 'right_gaze_origin': array([-2.97586083, -2.75799584, -0.20310669]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0306549072265625, + 'right_pupil_posn': array([-0.34142148, -0.26076245]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03153172507882118, + 'throttle_input': 0.16665904223918915, + 'timestamp': 830.7182389758527, + 'timestamp_carla': 830720, + 'timestamp_device': 3984149, + 'timestamp_stream': 830.7182389758527, + 'transform': [array([3.70610189e+00, 1.40119114e+01, 5.22855762e-03]), + array([ -0.06565861, -11.31735706, 0.01532942])]} +{'AngularVelocity': array([-0.11099528, 0.02059952, 0.60876852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.94755935668945, + 'FR_Wheel_Angle': -30.95376968383789, + 'Location': array([ -3.70074344, -22.25234795, 0.17356661]), + 'Rotation': array([ -0.06787159, -25.61213303, 0.02735369]), + 'Velocity': array([-2.67518442e-02, 2.25274656e-02, 9.58633391e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.9182744 , 13.30893612, -0.23847847]), + 'camera_rotation': array([ -6.18933249, -13.23765659, -2.08397245]), + 'current_gear_input': False, + 'focus_actor_dist': 951.8336791992188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -616.34899902, -2321.54174805, 67.37028503]), + 'frame': 25630, + 'frame_number': 25630, + 'framesequence': 98572, + 'gaze_dir': array([ 0.99060059, -0.12758636, 0.04180145]), + 'gaze_origin': array([-3.06662369, 0.11208192, -0.12451249]), + 'gaze_valid': True, + 'gaze_vergence': 0.1618739515542984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9894104 , -0.12835693, 0.06771851]), + 'left_gaze_origin': array([-3.15315127, 2.98225117, -0.04739533]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.936553955078125, + 'left_pupil_posn': array([ 0.13055205, -0.16997516]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99179077, -0.1268158 , 0.0158844 ]), + 'right_gaze_origin': array([-2.98009658, -2.75808716, -0.20162964]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.04754638671875, + 'right_pupil_posn': array([-0.34062076, -0.26114535]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.033564258366823196, + 'throttle_input': 0.16665904223918915, + 'timestamp': 830.7517281770706, + 'timestamp_carla': 830753, + 'timestamp_device': 3984182, + 'timestamp_stream': 830.7517281770706, + 'transform': [array([3.71583676e+00, 1.39751997e+01, 4.78584273e-03]), + array([ -0.06554249, -11.33988094, 0.01621078])]} +{'AngularVelocity': array([0.11062495, 0.00983538, 4.23832703]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.75712585449219, + 'FR_Wheel_Angle': -30.83808708190918, + 'Location': array([ -3.72575164, -22.22979164, 0.17363542]), + 'Rotation': array([-7.98039287e-02, -2.52028275e+01, 1.20939454e-02]), + 'Velocity': array([-2.34035656e-01, 2.45755270e-01, 1.14440918e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.95775032, 13.21469879, -0.21970131]), + 'camera_rotation': array([ -6.00948 , -13.48535728, -2.21840239]), + 'current_gear_input': False, + 'focus_actor_dist': 949.8159790039062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -619.01208496, -2321.54174805, 68.08340454]), + 'frame': 25631, + 'frame_number': 25631, + 'framesequence': 98576, + 'gaze_dir': array([ 0.9905014 , -0.12837982, 0.04434967]), + 'gaze_origin': array([-2.94648075, 0.09393082, -0.16435777]), + 'gaze_valid': True, + 'gaze_vergence': 117.20591735839844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99232483, -0.11058044, 0.0552063 ]), + 'left_gaze_origin': array([-2.87432122, 2.95580912, -0.13880615]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9864654541015625, + 'left_pupil_posn': array([ 0.14008641, -0.17175734]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98867798, -0.1461792 , 0.03349304]), + 'right_gaze_origin': array([-3.01864028, -2.76794744, -0.18990937]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.024017333984375, + 'right_pupil_posn': array([-0.32811785, -0.2650224 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03568834438920021, + 'throttle_input': 0.16665904223918915, + 'timestamp': 830.7851792760193, + 'timestamp_carla': 830787, + 'timestamp_device': 3984215, + 'timestamp_stream': 830.7851792760193, + 'transform': [array([3.72693014e+00, 1.39378777e+01, 4.30232985e-03]), + array([ -0.06539223, -11.36524677, 0.01717571])]} +{'AngularVelocity': array([ 0.02140341, -0.0338759 , 4.69430447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.750946044921875, + 'FR_Wheel_Angle': -30.839305877685547, + 'Location': array([ -3.78945804, -22.1699295 , 0.17368394]), + 'Rotation': array([-7.46129826e-02, -2.40625687e+01, 1.78009514e-02]), + 'Velocity': array([-2.62363911e-01, 2.87546158e-01, 2.80723558e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.98126459, 13.11755753, -0.20516421]), + 'camera_rotation': array([ -5.86128569, -13.66051769, -2.44166565]), + 'current_gear_input': False, + 'focus_actor_dist': 947.8790893554688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -623.62298584, -2321.54174805, 73.24107361]), + 'frame': 25632, + 'frame_number': 25632, + 'framesequence': 98580, + 'gaze_dir': array([ 0.99537659, -0.06587219, 0.06846619]), + 'gaze_origin': array([-2.92147446, 0.04673767, -0.15596467]), + 'gaze_valid': True, + 'gaze_vergence': 211.8177032470703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99613953, -0.05259705, 0.07012939]), + 'left_gaze_origin': array([-2.80757308, 2.90483403, -0.14595339]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.064666748046875, + 'left_pupil_posn': array([ 0.19625318, -0.15186954]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99461365, -0.07914734, 0.06680298]), + 'right_gaze_origin': array([-3.03537607, -2.81135893, -0.16597596]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9444580078125, + 'right_pupil_posn': array([-0.27791947, -0.24684215]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.037647634744644165, + 'throttle_input': 0.16665904223918915, + 'timestamp': 830.8195922784507, + 'timestamp_carla': 830821, + 'timestamp_device': 3984249, + 'timestamp_stream': 830.8195922784507, + 'transform': [array([3.73919058e+00, 1.38988619e+01, 3.79581447e-03]), + array([ -0.06523513, -11.39320183, 0.01817439])]} +{'AngularVelocity': array([ 0.0917123 , -0.01158168, 4.21980143]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.7781867980957, + 'FR_Wheel_Angle': -30.84250259399414, + 'Location': array([ -3.84726286, -22.11760521, 0.17370905]), + 'Rotation': array([ -0.06936739, -23.04310608, 0.02432529]), + 'Velocity': array([-0.24290802, 0.24994659, 0.00025602]), + 'brake_input': 0.0, + 'camera_location': array([-7.00332308, 13.02992821, -0.19253366]), + 'camera_rotation': array([ -5.85358095, -13.77547455, -2.68435168]), + 'current_gear_input': False, + 'focus_actor_dist': 940.5950317382812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -570.32116699, -2338.82104492, 100.18714142]), + 'frame': 25633, + 'frame_number': 25633, + 'framesequence': 98584, + 'gaze_dir': array([ 0.99569702, -0.06295776, 0.06679535]), + 'gaze_origin': array([-2.93113875, 0.04235153, -0.14835282]), + 'gaze_valid': True, + 'gaze_vergence': 224.60025024414062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99617004, -0.05148315, 0.07060242]), + 'left_gaze_origin': array([-2.80665278, 2.90060902, -0.14295959]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0712738037109375, + 'left_pupil_posn': array([ 0.20068908, -0.15109801]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.995224 , -0.07443237, 0.06298828]), + 'right_gaze_origin': array([-3.05562449, -2.81590605, -0.15374604]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9518890380859375, + 'right_pupil_posn': array([-0.27447754, -0.24213898]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.039094213396310806, + 'throttle_input': 0.1745937317609787, + 'timestamp': 830.8520595766604, + 'timestamp_carla': 830854, + 'timestamp_device': 3984282, + 'timestamp_stream': 830.8520595766604, + 'transform': [array([3.75187254e+00, 1.38613625e+01, 3.35390074e-03]), + array([ -0.06506438, -11.42194939, 0.01908185])]} +{'AngularVelocity': array([ 0.07108432, -0.04420513, 6.23856211]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69243621826172, + 'FR_Wheel_Angle': -30.806798934936523, + 'Location': array([ -3.90607023, -22.06720352, 0.17381029]), + 'Rotation': array([-7.39436224e-02, -2.20125923e+01, 1.69820897e-02]), + 'Velocity': array([-0.31045201, 0.32354435, 0.00052459]), + 'brake_input': 0.0, + 'camera_location': array([-7.01374865, 12.94672775, -0.18758965]), + 'camera_rotation': array([ -5.83468866, -13.82350636, -2.8346777 ]), + 'current_gear_input': False, + 'focus_actor_dist': 935.5709228515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -568.71850586, -2337.640625 , 98.8013916 ]), + 'frame': 25634, + 'frame_number': 25634, + 'framesequence': 98588, + 'gaze_dir': array([ 0.99571228, -0.06092072, 0.06855011]), + 'gaze_origin': array([-2.9312129 , 0.04145356, -0.14814454]), + 'gaze_valid': True, + 'gaze_vergence': 232.9188232421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9961853 , -0.04956055, 0.0717926 ]), + 'left_gaze_origin': array([-2.81074524, 2.90039229, -0.14170685]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.058685302734375, + 'left_pupil_posn': array([ 0.20159459, -0.15020382]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99523926, -0.07228088, 0.06530762]), + 'right_gaze_origin': array([-3.05168009, -2.81748509, -0.15458223]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.95794677734375, + 'right_pupil_posn': array([-0.27268893, -0.24154592]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04013794660568237, + 'throttle_input': 0.18252842128276825, + 'timestamp': 830.8854522779584, + 'timestamp_carla': 830887, + 'timestamp_device': 3984315, + 'timestamp_stream': 830.8854522779584, + 'transform': [array([3.76456904e+00, 1.38222628e+01, 2.86043156e-03]), + array([ -0.06488679, -11.45100784, 0.02007001])]} +{'AngularVelocity': array([-0.07123218, -0.03208258, 4.57715559]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.748191833496094, + 'FR_Wheel_Angle': -30.8376407623291, + 'Location': array([ -3.98461509, -22.00043678, 0.17384797]), + 'Rotation': array([ -0.06708612, -20.66292572, 0.02558129]), + 'Velocity': array([-2.28117421e-01, 2.24604622e-01, 1.09910965e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.02303076, 12.86717796, -0.18972649]), + 'camera_rotation': array([ -5.82390404, -13.82369804, -3.00755906]), + 'current_gear_input': False, + 'focus_actor_dist': 933.057373046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -567.7644043 , -2338.88232422, 100.7806015 ]), + 'frame': 25635, + 'frame_number': 25635, + 'framesequence': 98592, + 'gaze_dir': array([ 0.99568939, -0.06144714, 0.06838226]), + 'gaze_origin': array([-2.93081617, 0.04075318, -0.14816208]), + 'gaze_valid': True, + 'gaze_vergence': 224.62939453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99597168, -0.05117798, 0.07342529]), + 'left_gaze_origin': array([-2.81047535, 2.90001845, -0.14163361]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.06500244140625, + 'left_pupil_posn': array([ 0.20203793, -0.15077686]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9954071 , -0.07171631, 0.06333923]), + 'right_gaze_origin': array([-3.05115676, -2.8185122 , -0.15469056]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9821929931640625, + 'right_pupil_posn': array([-0.27253801, -0.24100375]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04110843688249588, + 'throttle_input': 0.1904631108045578, + 'timestamp': 830.9196372777224, + 'timestamp_carla': 830921, + 'timestamp_device': 3984349, + 'timestamp_stream': 830.9196372777224, + 'transform': [array([3.77854228e+00, 1.37815075e+01, 2.43226998e-03]), + array([ -0.06468189, -11.482831 , 0.02092141])]} +{'AngularVelocity': array([-0.02040099, -0.00546582, 3.37008524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.80615234375, + 'FR_Wheel_Angle': -30.876480102539062, + 'Location': array([ -4.03319502, -21.96137619, 0.17389089]), + 'Rotation': array([ -0.065884 , -19.84930229, 0.02664667]), + 'Velocity': array([-2.02639446e-01, 1.84379891e-01, 1.50766369e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.0275631 , 12.81400585, -0.21252064]), + 'camera_rotation': array([ -5.90643311, -13.75982666, -3.10985494]), + 'current_gear_input': False, + 'focus_actor_dist': 929.6770629882812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -567.99572754, -2338.88183594, 100.7317276 ]), + 'frame': 25636, + 'frame_number': 25636, + 'framesequence': 98596, + 'gaze_dir': array([ 0.9956131 , -0.06156158, 0.0694046 ]), + 'gaze_origin': array([-2.92926955, 0.04013672, -0.14857483]), + 'gaze_valid': True, + 'gaze_vergence': 234.3282928466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99598694, -0.05091858, 0.07350159]), + 'left_gaze_origin': array([-2.81136036, 2.90001845, -0.14151764]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.066986083984375, + 'left_pupil_posn': array([ 0.20187736, -0.15020382]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99523926, -0.07220459, 0.06530762]), + 'right_gaze_origin': array([-3.04717898, -2.81974506, -0.15563202]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.96258544921875, + 'right_pupil_posn': array([-0.27158034, -0.24081635]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04151127487421036, + 'throttle_input': 0.21031509339809418, + 'timestamp': 830.9513746760786, + 'timestamp_carla': 830953, + 'timestamp_device': 3984382, + 'timestamp_stream': 830.9513746760786, + 'transform': [array([3.79201221e+00, 1.37429295e+01, 2.03863136e-03]), + array([ -0.06447698, -11.51351166, 0.02174383])]} +{'AngularVelocity': array([ 0.00278526, -0.01353334, 2.31863451]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.880516052246094, + 'FR_Wheel_Angle': -30.92010498046875, + 'Location': array([ -4.07628822, -21.92748642, 0.17393564]), + 'Rotation': array([ -0.06490728, -19.13104248, 0.02666862]), + 'Velocity': array([-1.31959304e-01, 1.21438883e-01, 1.05667110e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.01446295, 12.77084351, -0.2431397 ]), + 'camera_rotation': array([ -5.98767138, -13.62644005, -3.1698451 ]), + 'current_gear_input': False, + 'focus_actor_dist': 925.9031372070312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -566.76318359, -2339.09277344, 100.36556244]), + 'frame': 25637, + 'frame_number': 25637, + 'framesequence': 98600, + 'gaze_dir': array([ 0.9955368 , -0.06086731, 0.07058716]), + 'gaze_origin': array([-2.92943215, 0.04013672, -0.1480507 ]), + 'gaze_valid': True, + 'gaze_vergence': 171.2352294921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9957428 , -0.04879761, 0.07809448]), + 'left_gaze_origin': array([-2.81539774, 2.90001845, -0.13910829]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0672454833984375, + 'left_pupil_posn': array([ 0.20168197, -0.15013838]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99533081, -0.07293701, 0.06307983]), + 'right_gaze_origin': array([-3.04346633, -2.81974506, -0.15699312]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.963104248046875, + 'right_pupil_posn': array([-0.27079469, -0.23941433]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041584521532058716, + 'throttle_input': 0.2222171425819397, + 'timestamp': 830.9843240790069, + 'timestamp_carla': 830986, + 'timestamp_device': 3984415, + 'timestamp_stream': 830.9843240790069, + 'transform': [array([3.80540633e+00, 1.37022200e+01, 1.57342909e-03]), + array([ -0.0642311 , -11.54432583, 0.02267967])]} +{'AngularVelocity': array([0.0331736 , 0.00896834, 1.43738198]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.91940689086914, + 'FR_Wheel_Angle': -30.939102172851562, + 'Location': array([ -4.10059786, -21.90868568, 0.17395361]), + 'Rotation': array([ -0.06552883, -18.72763443, 0.02497502]), + 'Velocity': array([-0.08967993, 0.07870688, -0.00020655]), + 'brake_input': 0.0, + 'camera_location': array([-6.99309731, 12.73425198, -0.24453463]), + 'camera_rotation': array([ -6.01005411, -13.55239105, -3.2908082 ]), + 'current_gear_input': False, + 'focus_actor_dist': 924.7779541015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -564.56488037, -2342.24682617, 100.14988708]), + 'frame': 25638, + 'frame_number': 25638, + 'framesequence': 98604, + 'gaze_dir': array([ 0.99555206, -0.059021 , 0.07170868]), + 'gaze_origin': array([-2.93354201, 0.04175339, -0.14306946]), + 'gaze_valid': True, + 'gaze_vergence': 126.87285614013672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99536133, -0.04855347, 0.08300781]), + 'left_gaze_origin': array([-2.83921528, 2.90318179, -0.12794954]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0612945556640625, + 'left_pupil_posn': array([ 0.20101786, -0.14811826]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9957428 , -0.06948853, 0.06040955]), + 'right_gaze_origin': array([-3.02786875, -2.81967473, -0.1581894 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9105224609375, + 'right_pupil_posn': array([-0.27059263, -0.2354002 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041584521532058716, + 'throttle_input': 0.23411917686462402, + 'timestamp': 831.0194144770503, + 'timestamp_carla': 831021, + 'timestamp_device': 3984449, + 'timestamp_stream': 831.0194144770503, + 'transform': [array([3.82222891e+00, 1.36576509e+01, 1.24933245e-03]), + array([ -0.06395106, -11.5823555 , 0.02331 ])]} +{'AngularVelocity': array([ 0.01295976, -0.00958399, -0.00061023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.93532180786133, + 'FR_Wheel_Angle': -30.946006774902344, + 'Location': array([ -4.12175274, -21.89268684, 0.17397664]), + 'Rotation': array([ -0.06765302, -18.37644005, 0.02209339]), + 'Velocity': array([-0.06624157, 0.05982994, -0.00019588]), + 'brake_input': 0.0, + 'camera_location': array([-6.95768595, 12.70217705, -0.24146768]), + 'camera_rotation': array([ -6.0297246 , -13.48722076, -3.34105349]), + 'current_gear_input': False, + 'focus_actor_dist': 925.91015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -563.06481934, -2347.79174805, 100.76664734]), + 'frame': 25639, + 'frame_number': 25639, + 'framesequence': 98608, + 'gaze_dir': array([ 0.99525452, -0.05962372, 0.07504272]), + 'gaze_origin': array([-2.93354201, 0.04202347, -0.14306946]), + 'gaze_valid': True, + 'gaze_vergence': 106.3392562866211, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99487305, -0.04953003, 0.08811951]), + 'left_gaze_origin': array([-2.83921528, 2.90337849, -0.12794954]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0134735107421875, + 'left_pupil_posn': array([ 0.20079768, -0.14755237]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99563599, -0.06971741, 0.06196594]), + 'right_gaze_origin': array([-3.02786875, -2.81933165, -0.1581894 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8415985107421875, + 'right_pupil_posn': array([-0.27114075, -0.23343837]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041584521532058716, + 'throttle_input': 0.24998855590820312, + 'timestamp': 831.0514121763408, + 'timestamp_carla': 831053, + 'timestamp_device': 3984482, + 'timestamp_stream': 831.0514121763408, + 'transform': [array([3.84207511e+00, 1.36151781e+01, 8.91704520e-04]), + array([ -0.063712 , -11.62618637, 0.02406373])]} +{'AngularVelocity': array([-0.11776135, 0.03554984, 0.24840532]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.947879791259766, + 'FR_Wheel_Angle': -30.954517364501953, + 'Location': array([ -4.13735771, -21.88091278, 0.1740278 ]), + 'Rotation': array([ -0.06823359, -18.11725998, 0.02141871]), + 'Velocity': array([-0.06068426, 0.03545392, -0.0001375 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.93627644, 12.65427971, -0.25673234]), + 'camera_rotation': array([ -6.0753026 , -13.47196102, -3.23204422]), + 'current_gear_input': False, + 'focus_actor_dist': 928.05810546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -564.35375977, -2353.86132812, 103.4016571 ]), + 'frame': 25640, + 'frame_number': 25640, + 'framesequence': 98612, + 'gaze_dir': array([ 0.99520111, -0.05873108, 0.07611084]), + 'gaze_origin': array([-2.93307734, 0.04393769, -0.14296037]), + 'gaze_valid': True, + 'gaze_vergence': 109.14546203613281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99488831, -0.04704285, 0.08918762]), + 'left_gaze_origin': array([-2.83707762, 2.90505242, -0.12925416]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.97540283203125, + 'left_pupil_posn': array([ 0.19938207, -0.14755237]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99551392, -0.07041931, 0.06303406]), + 'right_gaze_origin': array([-3.02907729, -2.81717706, -0.15666658]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.808624267578125, + 'right_pupil_posn': array([-0.27172363, -0.23219502]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041584521532058716, + 'throttle_input': 0.269825279712677, + 'timestamp': 831.0844391770661, + 'timestamp_carla': 831086, + 'timestamp_device': 3984515, + 'timestamp_stream': 831.0844391770661, + 'transform': [array([3.86254930e+00, 1.35702858e+01, 4.09088127e-04]), + array([ -0.06349344, -11.67156029, 0.02503793])]} +{'AngularVelocity': array([-0.01172452, -0.00805446, 3.33246398]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.82695007324219, + 'FR_Wheel_Angle': -30.844247817993164, + 'Location': array([ -4.1636219 , -21.86211586, 0.17410204]), + 'Rotation': array([-7.65664130e-02, -1.76758499e+01, 9.57027543e-03]), + 'Velocity': array([-0.19546653, 0.16743892, 0.00025787]), + 'brake_input': 0.0, + 'camera_location': array([-6.90983725, 12.60426521, -0.28537279]), + 'camera_rotation': array([ -6.22649574, -13.60250282, -3.33507824]), + 'current_gear_input': False, + 'focus_actor_dist': 938.8939819335938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -567.65478516, -2368.04125977, 103.45996094]), + 'frame': 25641, + 'frame_number': 25641, + 'framesequence': 98616, + 'gaze_dir': array([ 0.99514008, -0.05873871, 0.07685089]), + 'gaze_origin': array([-2.93360829, 0.04511566, -0.14240037]), + 'gaze_valid': True, + 'gaze_vergence': 106.97416687011719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99479675, -0.04714966, 0.09014893]), + 'left_gaze_origin': array([-2.83707762, 2.90675211, -0.12925416]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8545684814453125, + 'left_pupil_posn': array([ 0.19823503, -0.14725077]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9954834 , -0.07032776, 0.06355286]), + 'right_gaze_origin': array([-3.03013945, -2.81652093, -0.15554658]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6547698974609375, + 'right_pupil_posn': array([-0.27220017, -0.23122299]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041584521532058716, + 'throttle_input': 0.2896620035171509, + 'timestamp': 831.1191444769502, + 'timestamp_carla': 831121, + 'timestamp_device': 3984549, + 'timestamp_stream': 831.1191444769502, + 'transform': [array([ 3.88441181e+00, 1.35217218e+01, -1.80511473e-04]), + array([ -0.06330219, -11.72017479, 0.0261969 ])]} +{'AngularVelocity': array([ 0.09306635, -0.04457131, 5.17608929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.75278091430664, + 'FR_Wheel_Angle': -30.79380989074707, + 'Location': array([ -4.22314453, -21.81937408, 0.1741474 ]), + 'Rotation': array([-7.43397772e-02, -1.67107391e+01, 1.13909626e-02]), + 'Velocity': array([-0.26407328, 0.23681901, 0.00060654]), + 'brake_input': 0.0, + 'camera_location': array([-6.87378407, 12.56646538, -0.31454837]), + 'camera_rotation': array([ -6.37583113, -13.74489212, -3.44758105]), + 'current_gear_input': False, + 'focus_actor_dist': 917.3009643554688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -563.78546143, -2350.578125 , 102.32205963]), + 'frame': 25642, + 'frame_number': 25642, + 'framesequence': 98620, + 'gaze_dir': array([ 0.98165894, -0.17743683, 0.06507111]), + 'gaze_origin': array([-2.97409773, 0.13274232, -0.1443184 ]), + 'gaze_valid': True, + 'gaze_vergence': 86.82659149169922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98382568, -0.15940857, 0.08154297]), + 'left_gaze_origin': array([-2.91909361, 2.99301457, -0.11295014]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.697906494140625, + 'left_pupil_posn': array([ 0.09773743, -0.15748835]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97949219, -0.19546509, 0.04859924]), + 'right_gaze_origin': array([-3.02910161, -2.72753 , -0.17568666]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.843170166015625, + 'right_pupil_posn': array([-0.3730793 , -0.24825585]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041584521532058716, + 'throttle_input': 0.3015792965888977, + 'timestamp': 831.1527641788125, + 'timestamp_carla': 831154, + 'timestamp_device': 3984582, + 'timestamp_stream': 831.1527641788125, + 'transform': [array([ 3.90599775e+00, 1.34731750e+01, -8.24661227e-04]), + array([ -0.06311777, -11.76830482, 0.02749035])]} +{'AngularVelocity': array([-0.05393592, -0.03146958, 6.95994902]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.527626037597656, + 'FR_Wheel_Angle': -30.688621520996094, + 'Location': array([ -4.32415247, -21.75115204, 0.17429601]), + 'Rotation': array([-7.99268708e-02, -1.51543751e+01, 5.32629946e-03]), + 'Velocity': array([-0.48798689, 0.37725079, 0.00064841]), + 'brake_input': 0.0, + 'camera_location': array([-6.84377289, 12.50040913, -0.33253288]), + 'camera_rotation': array([ -6.41071272, -14.00544357, -3.39168811]), + 'current_gear_input': False, + 'focus_actor_dist': 929.5377807617188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -672.7053833 , -2322.37084961, 83.41123962]), + 'frame': 25643, + 'frame_number': 25643, + 'framesequence': 98625, + 'gaze_dir': array([ 0.98292542, -0.17384338, 0.05696869]), + 'gaze_origin': array([-2.9873836 , 0.13910142, -0.1440056 ]), + 'gaze_valid': True, + 'gaze_vergence': 104.32816314697266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98452759, -0.16027832, 0.07072449]), + 'left_gaze_origin': array([-2.92620397, 2.99309707, -0.1150116 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.58624267578125, + 'left_pupil_posn': array([ 0.10051525, -0.16194773]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98132324, -0.18740845, 0.04321289]), + 'right_gaze_origin': array([-3.04856277, -2.71489406, -0.17299958]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.866790771484375, + 'right_pupil_posn': array([-0.38249224, -0.25382245]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041584521532058716, + 'throttle_input': 0.30951398611068726, + 'timestamp': 831.1868537776172, + 'timestamp_carla': 831188, + 'timestamp_device': 3984624, + 'timestamp_stream': 831.1868537776172, + 'transform': [array([ 3.92838311e+00, 1.34222994e+01, -1.50863640e-03]), + array([ -0.06294702, -11.81835556, 0.02885485])]} +{'AngularVelocity': array([-0.02573508, -0.02339963, 7.77288866]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.52275848388672, + 'FR_Wheel_Angle': -30.703866958618164, + 'Location': array([ -4.47360325, -21.65632439, 0.17442614]), + 'Rotation': array([ -0.07311717, -12.87163162, 0.01327543]), + 'Velocity': array([-0.55660897, 0.39723495, 0.00083273]), + 'brake_input': 0.0, + 'camera_location': array([-6.8363862 , 12.41372585, -0.35652 ]), + 'camera_rotation': array([ -6.57506084, -14.43276596, -3.44917226]), + 'current_gear_input': False, + 'focus_actor_dist': 924.7796020507812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -671.75360107, -2321.49902344, 75.92219543]), + 'frame': 25644, + 'frame_number': 25644, + 'framesequence': 98628, + 'gaze_dir': array([ 0.98305511, -0.17295837, 0.05729675]), + 'gaze_origin': array([-2.9908874 , 0.1375435 , -0.14172439]), + 'gaze_valid': True, + 'gaze_vergence': 102.60372924804688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9846344 , -0.15933228, 0.07128906]), + 'left_gaze_origin': array([-2.93004775, 2.99234629, -0.11268464]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.59197998046875, + 'left_pupil_posn': array([ 0.10132635, -0.16110158]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98147583, -0.18658447, 0.04330444]), + 'right_gaze_origin': array([-3.05172753, -2.71725941, -0.17076416]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.866607666015625, + 'right_pupil_posn': array([-0.38053924, -0.25271976]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04136478900909424, + 'throttle_input': 0.31348133087158203, + 'timestamp': 831.2201307788491, + 'timestamp_carla': 831222, + 'timestamp_device': 3984649, + 'timestamp_stream': 831.2201307788491, + 'transform': [array([ 3.95096970e+00, 1.33708363e+01, -2.21332535e-03]), + array([ -0.06278992, -11.86894894, 0.03027503])]} +{'AngularVelocity': array([-3.46890208e-03, -1.40358992e-02, 7.13885784e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.55408477783203, + 'FR_Wheel_Angle': -30.72173500061035, + 'Location': array([ -4.60221815, -21.58071327, 0.17453516]), + 'Rotation': array([ -0.06878683, -10.94328499, 0.01706403]), + 'Velocity': array([-0.52991211, 0.35300466, 0.0007104 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.82264805, 12.32408619, -0.37420249]), + 'camera_rotation': array([ -6.71587896, -14.99544239, -3.50917053]), + 'current_gear_input': False, + 'focus_actor_dist': 923.1088256835938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -677.48937988, -2321.31445312, 73.61299133]), + 'frame': 25645, + 'frame_number': 25645, + 'framesequence': 98632, + 'gaze_dir': array([ 0.98313141, -0.17259979, 0.05680847]), + 'gaze_origin': array([-2.99252319, 0.13657379, -0.14070511]), + 'gaze_valid': True, + 'gaze_vergence': 98.42652893066406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98472595, -0.15872192, 0.07139587]), + 'left_gaze_origin': array([-2.93327808, 2.99205661, -0.11073303]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5905303955078125, + 'left_pupil_posn': array([ 0.10158384, -0.16080821]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98153687, -0.18647766, 0.04222107]), + 'right_gaze_origin': array([-3.05176854, -2.71890879, -0.17067719]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9466400146484375, + 'right_pupil_posn': array([-0.379179 , -0.25265193]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04063234478235245, + 'throttle_input': 0.31348133087158203, + 'timestamp': 831.2516970783472, + 'timestamp_carla': 831253, + 'timestamp_device': 3984682, + 'timestamp_stream': 831.2516970783472, + 'transform': [array([ 3.97351241e+00, 1.33202076e+01, -2.87391664e-03]), + array([ -0.06259185, -11.91940594, 0.03162761])]} +{'AngularVelocity': array([ 3.07755098e-02, -4.66248905e-03, 6.35971737e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.598350524902344, + 'FR_Wheel_Angle': -30.75309944152832, + 'Location': array([ -4.71410894, -21.51950645, 0.17463727]), + 'Rotation': array([-0.0666763 , -9.29343796, 0.01749845]), + 'Velocity': array([-0.48573989, 0.30597007, 0.0005056 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.80157614, 12.2108345 , -0.37142435]), + 'camera_rotation': array([ -6.68189192, -15.58319569, -3.50879145]), + 'current_gear_input': False, + 'focus_actor_dist': 922.9583740234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -686.20294189, -2321.28417969, 70.81224823]), + 'frame': 25646, + 'frame_number': 25646, + 'framesequence': 98636, + 'gaze_dir': array([ 0.98313904, -0.17172241, 0.05908966]), + 'gaze_origin': array([-2.95676899, 0.13135758, -0.15502778]), + 'gaze_valid': True, + 'gaze_vergence': 87.28079223632812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98445129, -0.15861511, 0.0753479 ]), + 'left_gaze_origin': array([-2.93647933, 2.99186587, -0.11163025]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5834503173828125, + 'left_pupil_posn': array([ 0.10227633, -0.16176045]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98182678, -0.18482971, 0.04283142]), + 'right_gaze_origin': array([-2.97705841, -2.72915053, -0.19842531]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8760223388671875, + 'right_pupil_posn': array([-0.37101865, -0.25548029]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.039313942193984985, + 'throttle_input': 0.31348133087158203, + 'timestamp': 831.2856675758958, + 'timestamp_carla': 831287, + 'timestamp_device': 3984715, + 'timestamp_stream': 831.2856675758958, + 'transform': [array([ 3.99797106e+00, 1.32640657e+01, -3.45493318e-03]), + array([ -0.06233913, -11.97432709, 0.03278296])]} +{'AngularVelocity': array([3.26495580e-02, 5.14783803e-03, 5.65083885e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.64235305786133, + 'FR_Wheel_Angle': -30.77987289428711, + 'Location': array([ -4.82053041, -21.46508217, 0.17474756]), + 'Rotation': array([-0.06649872, -7.74631357, 0.01660041]), + 'Velocity': array([-0.44115874, 0.26166594, 0.00050381]), + 'brake_input': 0.0, + 'camera_location': array([-6.76995468, 12.07767105, -0.36982936]), + 'camera_rotation': array([ -6.66143513, -16.37210083, -3.5729444 ]), + 'current_gear_input': False, + 'focus_actor_dist': 922.6234130859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -694.94476318, -2321.30859375, 73.52151489]), + 'frame': 25647, + 'frame_number': 25647, + 'framesequence': 98640, + 'gaze_dir': array([ 0.9839859 , -0.16644287, 0.05962372]), + 'gaze_origin': array([-2.96284938, 0.12971193, -0.15310594]), + 'gaze_valid': True, + 'gaze_vergence': 68.71869659423828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98475647, -0.15515137, 0.07843018]), + 'left_gaze_origin': array([-2.94297957, 2.98997521, -0.11042786]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6244964599609375, + 'left_pupil_posn': array([ 0.1060909 , -0.16288805]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98321533, -0.17773438, 0.04081726]), + 'right_gaze_origin': array([-2.98271966, -2.73055124, -0.195784 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8546295166015625, + 'right_pupil_posn': array([-0.36888975, -0.25365949]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.037739191204309464, + 'throttle_input': 0.31348133087158203, + 'timestamp': 831.3198254778981, + 'timestamp_carla': 831321, + 'timestamp_device': 3984749, + 'timestamp_stream': 831.3198254778981, + 'transform': [array([ 4.02246571e+00, 1.32059717e+01, -3.93733988e-03]), + array([ -0.06205226, -12.02956581, 0.03375194])]} +{'AngularVelocity': array([0.04441502, 0.00861525, 5.16075087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69029998779297, + 'FR_Wheel_Angle': -30.796829223632812, + 'Location': array([ -4.90492964, -21.42452049, 0.17482622]), + 'Rotation': array([-0.06673777, -6.5337882 , 0.01610197]), + 'Velocity': array([-0.40410185, 0.22830075, 0.00075129]), + 'brake_input': 0.0, + 'camera_location': array([-6.75804758, 11.92333984, -0.38499549]), + 'camera_rotation': array([ -6.71030521, -17.31463623, -3.71823025]), + 'current_gear_input': False, + 'focus_actor_dist': 502.02838134765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -505.00216675, -1952.23083496, 101.52204895]), + 'frame': 25648, + 'frame_number': 25648, + 'framesequence': 98644, + 'gaze_dir': array([ 0.98911285, -0.1357193 , 0.05054474]), + 'gaze_origin': array([-3.0446229 , 0.12654038, -0.13064501]), + 'gaze_valid': True, + 'gaze_vergence': 32.516239166259766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98672485, -0.14405823, 0.07496643]), + 'left_gaze_origin': array([-3.13442683, 2.99223495, -0.05557251]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.715484619140625, + 'left_pupil_posn': array([ 0.12319195, -0.16784894]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99150085, -0.12738037, 0.02612305]), + 'right_gaze_origin': array([-2.95481896, -2.7391541 , -0.20571747]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9452056884765625, + 'right_pupil_posn': array([-0.35879636, -0.25598371]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03550523519515991, + 'throttle_input': 0.3174487054347992, + 'timestamp': 831.352016877383, + 'timestamp_carla': 831354, + 'timestamp_device': 3984782, + 'timestamp_stream': 831.352016877383, + 'transform': [array([ 4.04467773e+00, 1.31497326e+01, -4.39435942e-03]), + array([ -0.06171076, -12.08003426, 0.03470452])]} +{'AngularVelocity': array([-3.32300691e-03, -8.98634666e-04, 4.04940796e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.649173736572266, + 'FR_Wheel_Angle': -29.8518123626709, + 'Location': array([ -5.00724411, -21.37862015, 0.17492609]), + 'Rotation': array([-0.06802185, -5.07956123, 0.01466962]), + 'Velocity': array([-3.68241310e-01, 1.89120263e-01, 2.93607707e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.75298071, 11.69354343, -0.40192208]), + 'camera_rotation': array([ -6.74169016, -18.65786362, -3.95267677]), + 'current_gear_input': False, + 'focus_actor_dist': 909.4349975585938, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -685.64373779, -2321.24804688, 67.1750946 ]), + 'frame': 25649, + 'frame_number': 25649, + 'framesequence': 98648, + 'gaze_dir': array([ 0.9912262 , -0.11917114, 0.0488205 ]), + 'gaze_origin': array([-3.07962751, 0.11539231, -0.11911698]), + 'gaze_valid': True, + 'gaze_vergence': 29.04831314086914, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98869324, -0.12884521, 0.07655334]), + 'left_gaze_origin': array([-3.1811676 , 2.98226953, -0.03899078]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7130279541015625, + 'left_pupil_posn': array([ 0.13657856, -0.16731954]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99375916, -0.10949707, 0.02108765]), + 'right_gaze_origin': array([-2.97808695, -2.75148487, -0.19924317]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.828704833984375, + 'right_pupil_posn': array([-0.3452664 , -0.25539875]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.032850123941898346, + 'throttle_input': 0.32538339495658875, + 'timestamp': 831.386238977313, + 'timestamp_carla': 831388, + 'timestamp_device': 3984815, + 'timestamp_stream': 831.386238977313, + 'transform': [array([ 4.06726980e+00, 1.30884552e+01, -4.78588091e-03]), + array([ -0.06127362, -12.13180256, 0.03549565])]} +{'AngularVelocity': array([4.25130576e-02, 5.98099921e-03, 6.16686916e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.573486328125, + 'FR_Wheel_Angle': -26.583749771118164, + 'Location': array([ -5.10388803, -21.34127235, 0.17504182]), + 'Rotation': array([-0.0719014 , -3.8446672 , 0.01187631]), + 'Velocity': array([-4.43174988e-01, 1.93489030e-01, 4.10594919e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.76805878, 11.43419456, -0.42927414]), + 'camera_rotation': array([ -6.84493494, -20.17278481, -4.12009144]), + 'current_gear_input': False, + 'focus_actor_dist': 907.521240234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -691.32702637, -2321.23046875, 65.57862854]), + 'frame': 25650, + 'frame_number': 25650, + 'framesequence': 98652, + 'gaze_dir': array([ 0.99285126, -0.1037674 , 0.05589294]), + 'gaze_origin': array([-2.97763538, 0.08980942, -0.15204239]), + 'gaze_valid': True, + 'gaze_vergence': 97.98489379882812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9932251 , -0.09240723, 0.07026672]), + 'left_gaze_origin': array([-2.9245286 , 2.94891977, -0.12351074]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.829071044921875, + 'left_pupil_posn': array([ 0.15544629, -0.16767132]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99247742, -0.11512756, 0.04151917]), + 'right_gaze_origin': array([-3.03074193, -2.76930094, -0.18057404]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.68145751953125, + 'right_pupil_posn': array([-0.32085603, -0.25492525]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.030579548329114914, + 'throttle_input': 0.32538339495658875, + 'timestamp': 831.4212058782578, + 'timestamp_carla': 831423, + 'timestamp_device': 3984849, + 'timestamp_stream': 831.4212058782578, + 'transform': [array([ 4.08954048e+00, 1.30242567e+01, -5.08483872e-03]), + array([ -0.06084332, -12.18320084, 0.03610484])]} +{'AngularVelocity': array([1.90635379e-02, 3.97677999e-03, 5.07504654e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.0565185546875, + 'FR_Wheel_Angle': -22.383968353271484, + 'Location': array([ -5.22034788, -21.30477333, 0.17515413]), + 'Rotation': array([-0.07257076, -2.61935425, 0.01337957]), + 'Velocity': array([-5.14077008e-01, 1.73790485e-01, 3.66325374e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.76391983, 11.12059402, -0.46543592]), + 'camera_rotation': array([ -6.94725132, -21.85122299, -4.26682568]), + 'current_gear_input': False, + 'focus_actor_dist': 906.8250122070312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -701.59875488, -2321.27978516, 70.8368988 ]), + 'frame': 25651, + 'frame_number': 25651, + 'framesequence': 98656, + 'gaze_dir': array([ 0.99419403, -0.09583282, 0.04450989]), + 'gaze_origin': array([-3.10659432, 0.09168625, -0.11370316]), + 'gaze_valid': True, + 'gaze_vergence': 13.410083770751953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99343872, -0.09443665, 0.06436157]), + 'left_gaze_origin': array([-3.15755939, 2.96028304, -0.04940338]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.805450439453125, + 'left_pupil_posn': array([ 0.15584087, -0.16867709]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99494934, -0.097229 , 0.0246582 ]), + 'right_gaze_origin': array([-3.05562925, -2.77691054, -0.17800294]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7434539794921875, + 'right_pupil_posn': array([-0.31665456, -0.26033711]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.028070924803614616, + 'throttle_input': 0.3293507397174835, + 'timestamp': 831.4531192779541, + 'timestamp_carla': 831455, + 'timestamp_device': 3984882, + 'timestamp_stream': 831.4531192779541, + 'transform': [array([ 4.10847235e+00, 1.29641905e+01, -5.41250221e-03]), + array([ -0.0603857 , -12.22745705, 0.03682281])]} +{'AngularVelocity': array([ 0.02457197, -0.04381915, 5.51587439]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.689380645751953, + 'FR_Wheel_Angle': -17.270275115966797, + 'Location': array([ -5.3582859 , -21.27192879, 0.17531103]), + 'Rotation': array([-0.07827397, -1.50506604, 0.01063856]), + 'Velocity': array([-6.99551880e-01, 1.87520579e-01, 4.90770326e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.85239124, 10.80025673, -0.51997876]), + 'camera_rotation': array([ -7.20501566, -23.79851723, -4.54446507]), + 'current_gear_input': False, + 'focus_actor_dist': 426.65802001953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -481.38665771, -1901.19836426, 98.74199677]), + 'frame': 25652, + 'frame_number': 25652, + 'framesequence': 98661, + 'gaze_dir': array([ 0.96738434, -0.24785614, 0.04644775]), + 'gaze_origin': array([-3.01949024, 0.19071732, -0.15237886]), + 'gaze_valid': True, + 'gaze_vergence': 45.21812057495117, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96846008, -0.23956299, 0.06829834]), + 'left_gaze_origin': array([-3.01198912, 3.0451355 , -0.10301972]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.714996337890625, + 'left_pupil_posn': array([ 0.04172742, -0.17836308]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96630859, -0.25614929, 0.02459717]), + 'right_gaze_origin': array([-3.02699137, -2.66370106, -0.201738 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.842041015625, + 'right_pupil_posn': array([-0.44673944, -0.27110362]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.025983460247516632, + 'throttle_input': 0.3333180844783783, + 'timestamp': 831.489150878042, + 'timestamp_carla': 831491, + 'timestamp_device': 3984924, + 'timestamp_stream': 831.489150878042, + 'transform': [array([ 4.12888670e+00, 1.28947716e+01, -5.63705433e-03]), + array([ -0.05992808, -12.27560806, 0.03727034])]} +{'AngularVelocity': array([-0.05277757, -0.02048044, 3.20905876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.485489845275879, + 'FR_Wheel_Angle': -11.86497688293457, + 'Location': array([ -5.51585007, -21.24499702, 0.17542928]), + 'Rotation': array([-0.07229072, -0.54153442, 0.01767296]), + 'Velocity': array([-6.94382548e-01, 1.10225491e-01, 3.91864778e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.92149925, 10.52744484, -0.58449024]), + 'camera_rotation': array([ -7.59769011, -25.42836571, -4.66433191]), + 'current_gear_input': False, + 'focus_actor_dist': 353.1780700683594, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -499.89239502, -1804.40222168, 100.66469574]), + 'frame': 25653, + 'frame_number': 25653, + 'framesequence': 98665, + 'gaze_dir': array([ 0.95392609, -0.29542542, 0.04476166]), + 'gaze_origin': array([-3.02917409, 0.22822113, -0.15477829]), + 'gaze_valid': True, + 'gaze_vergence': 9.363327026367188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95178223, -0.29827881, 0.07156372]), + 'left_gaze_origin': array([-3.01933312, 3.07764459, -0.10605317]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6599578857421875, + 'left_pupil_posn': array([ 0.00673604, -0.18483114]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95606995, -0.29257202, 0.01795959]), + 'right_gaze_origin': array([-3.03901529, -2.62120223, -0.20350343]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8919677734375, + 'right_pupil_posn': array([-0.49882543, -0.27498281]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02385937236249447, + 'throttle_input': 0.3333180844783783, + 'timestamp': 831.523310277611, + 'timestamp_carla': 831525, + 'timestamp_device': 3984957, + 'timestamp_stream': 831.523310277611, + 'transform': [array([ 4.14721203e+00, 1.28272905e+01, -5.85201243e-03]), + array([ -0.05954559, -12.31937122, 0.03774907])]} +{'AngularVelocity': array([2.97632515e-02, 2.91448610e-04, 2.29100227e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.667762756347656, + 'FR_Wheel_Angle': -6.335680961608887, + 'Location': array([ -5.69197369, -21.22764206, 0.17562021]), + 'Rotation': array([-0.07272785, 0.12090768, 0.01750416]), + 'Velocity': array([-0.75607187, 0.06699354, 0.00082832]), + 'brake_input': 0.0, + 'camera_location': array([-6.97794437, 10.24189377, -0.61604458]), + 'camera_rotation': array([ -7.75225735, -26.9978447 , -4.72188425]), + 'current_gear_input': False, + 'focus_actor_dist': 337.51568603515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -509.46075439, -1780.5579834 , 98.44623566]), + 'frame': 25654, + 'frame_number': 25654, + 'framesequence': 98669, + 'gaze_dir': array([ 0.95796967, -0.28264618, 0.04325104]), + 'gaze_origin': array([-3.02390385, 0.20562364, -0.15621109]), + 'gaze_valid': True, + 'gaze_vergence': 18.458534240722656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95782471, -0.27967834, 0.0657959 ]), + 'left_gaze_origin': array([-3.01491261, 3.0577898 , -0.10802766]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.721435546875, + 'left_pupil_posn': array([ 0.0227412, -0.1842984]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95811462, -0.28561401, 0.02070618]), + 'right_gaze_origin': array([-3.03289509, -2.64654255, -0.20439455]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9265594482421875, + 'right_pupil_posn': array([-0.4738214 , -0.27582669]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02217474952340126, + 'throttle_input': 0.33728542923927307, + 'timestamp': 831.5573862791061, + 'timestamp_carla': 831559, + 'timestamp_device': 3984990, + 'timestamp_stream': 831.5573862791061, + 'transform': [array([ 4.16430044e+00, 1.27583332e+01, -6.07225392e-03]), + array([ -0.05920408, -12.36078739, 0.03823755])]} +{'AngularVelocity': array([ 0.01769691, -0.01313576, 0.6256187 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.9914505481719971, + 'FR_Wheel_Angle': 0.04679911211133003, + 'Location': array([ -5.86868382, -21.22076797, 0.17578745]), + 'Rotation': array([-0.07067879, 0.42624426, 0.01783736]), + 'Velocity': array([-7.48871684e-01, 1.42357359e-02, 4.74405271e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.03641224, 9.93432045, -0.62200475]), + 'camera_rotation': array([ -7.73075581, -28.6508007 , -4.82961035]), + 'current_gear_input': False, + 'focus_actor_dist': 332.5716857910156, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -509.85479736, -1779.70898438, 97.66555786]), + 'frame': 25655, + 'frame_number': 25655, + 'framesequence': 98673, + 'gaze_dir': array([ 0.96617889, -0.25409698, 0.03932953]), + 'gaze_origin': array([-3.01958108, 0.19198991, -0.15546723]), + 'gaze_valid': True, + 'gaze_vergence': 20.828855514526367, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96458435, -0.25718689, 0.0585022 ]), + 'left_gaze_origin': array([-3.0115068 , 3.04567432, -0.10742645]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.79632568359375, + 'left_pupil_posn': array([ 0.04329574, -0.18283725]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96777344, -0.25100708, 0.02015686]), + 'right_gaze_origin': array([-3.02765512, -2.66169429, -0.203508 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7964935302734375, + 'right_pupil_posn': array([-0.4547357, -0.2761842]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01988586224615574, + 'throttle_input': 0.34125277400016785, + 'timestamp': 831.5896731764078, + 'timestamp_carla': 831591, + 'timestamp_device': 3985024, + 'timestamp_stream': 831.5896731764078, + 'transform': [array([ 4.17892838e+00, 1.26914644e+01, -6.33487664e-03]), + array([ -0.05883525, -12.39704227, 0.038831 ])]} +{'AngularVelocity': array([ 0.02674436, -0.01005808, 0.02541782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0367111973464489, + 'FR_Wheel_Angle': 0.10513152182102203, + 'Location': array([ -6.03675604, -21.22160149, 0.17594133]), + 'Rotation': array([-0.06753691, 0.43473357, 0.01347332]), + 'Velocity': array([-0.67919099, -0.00454892, 0.00077729]), + 'brake_input': 0.0, + 'camera_location': array([-7.08058691, 9.65846825, -0.64168483]), + 'camera_rotation': array([ -7.74918365, -30.0663166 , -4.71965218]), + 'current_gear_input': False, + 'focus_actor_dist': 328.7404479980469, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -507.53179932, -1783.46606445, 97.16950989]), + 'frame': 25656, + 'frame_number': 25656, + 'framesequence': 98675, + 'gaze_dir': array([ 0.96843719, -0.24537659, 0.03991699]), + 'gaze_origin': array([-3.01849008, 0.18431473, -0.15471955]), + 'gaze_valid': True, + 'gaze_vergence': 11.079303741455078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96794128, -0.24446106, 0.05754089]), + 'left_gaze_origin': array([-3.01099563, 3.0402391 , -0.106839 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.699066162109375, + 'left_pupil_posn': array([ 0.04863644, -0.18152523]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96893311, -0.24629211, 0.02229309]), + 'right_gaze_origin': array([-3.02598429, -2.67160964, -0.20260009]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8866424560546875, + 'right_pupil_posn': array([-0.44300061, -0.27557933]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.017835017293691635, + 'throttle_input': 0.34125277400016785, + 'timestamp': 831.6095504760742, + 'timestamp_carla': 831611, + 'timestamp_device': 3985040, + 'timestamp_stream': 831.6095504760742, + 'transform': [array([ 4.18752480e+00, 1.26496897e+01, -6.36810297e-03]), + array([ -0.05861668, -12.41856003, 0.03886143])]} +{'AngularVelocity': array([ 0.00769584, -0.00731844, 0.23605247]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1051870584487915, + 'FR_Wheel_Angle': 0.10530385375022888, + 'Location': array([ -6.19629335, -21.22281647, 0.17608602]), + 'Rotation': array([-0.0651805 , 0.42782453, 0.01035187]), + 'Velocity': array([-5.65020382e-01, -4.23071347e-03, 2.70013814e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.09273815, 9.40021706, -0.66982883]), + 'camera_rotation': array([ -7.7642169 , -31.28373909, -4.87165928]), + 'current_gear_input': False, + 'focus_actor_dist': 323.68536376953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -508.10528564, -1782.44543457, 98.09889221]), + 'frame': 25657, + 'frame_number': 25657, + 'framesequence': 98679, + 'gaze_dir': array([ 0.97399139, -0.22088623, 0.04238892]), + 'gaze_origin': array([-3.01780868, 0.16820221, -0.15636674]), + 'gaze_valid': True, + 'gaze_vergence': 8.249054908752441, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97319031, -0.21920776, 0.06951904]), + 'left_gaze_origin': array([-3.00940394, 3.02608061, -0.10796662]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7456512451171875, + 'left_pupil_posn': array([ 0.06663311, -0.18408799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97479248, -0.2225647 , 0.01525879]), + 'right_gaze_origin': array([-3.02621317, -2.68967605, -0.20476684]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.95611572265625, + 'right_pupil_posn': array([-0.42122585, -0.27242351]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0165532398968935, + 'throttle_input': 0.3452201187610626, + 'timestamp': 831.6428992785513, + 'timestamp_carla': 831645, + 'timestamp_device': 3985074, + 'timestamp_stream': 831.6428992785513, + 'transform': [array([ 4.20084953e+00, 1.25783091e+01, -6.51605614e-03]), + array([ -0.05822736, -12.45255184, 0.03923687])]} +{'AngularVelocity': array([-0.00071444, 0.0301038 , -0.27819848]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10538016259670258, + 'FR_Wheel_Angle': 0.1054968610405922, + 'Location': array([ -6.30817747, -21.22360039, 0.17616816]), + 'Rotation': array([-0.06521464, 0.41429624, 0.00972866]), + 'Velocity': array([-5.04210293e-01, -4.19730972e-03, 1.09930035e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.12146759, 9.1690979 , -0.66814864]), + 'camera_rotation': array([ -7.84674644, -32.41819763, -4.96582794]), + 'current_gear_input': False, + 'focus_actor_dist': 321.4457702636719, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -506.23010254, -1785.71252441, 99.22037506]), + 'frame': 25658, + 'frame_number': 25658, + 'framesequence': 98683, + 'gaze_dir': array([ 0.97751617, -0.20600128, 0.03803253]), + 'gaze_origin': array([-3.01737309, 0.15370789, -0.15483475]), + 'gaze_valid': True, + 'gaze_vergence': 16.51819610595703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97720337, -0.203125 , 0.06166077]), + 'left_gaze_origin': array([-3.01093769, 3.01322031, -0.10658875]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7899017333984375, + 'left_pupil_posn': array([ 0.08007765, -0.18345857]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97782898, -0.20887756, 0.0144043 ]), + 'right_gaze_origin': array([-3.02380848, -2.70580459, -0.20308076]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.858062744140625, + 'right_pupil_posn': array([-0.40416861, -0.27329218]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014392529614269733, + 'throttle_input': 0.3452201187610626, + 'timestamp': 831.6774850785732, + 'timestamp_carla': 831679, + 'timestamp_device': 3985107, + 'timestamp_stream': 831.6774850785732, + 'transform': [array([ 4.21294165e+00, 1.25026999e+01, -6.66753761e-03]), + array([ -0.05788585, -12.48447418, 0.03959235])]} +{'AngularVelocity': array([-0.00463166, 0.00378685, 0.14314882]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10552594065666199, + 'FR_Wheel_Angle': 0.10569161921739578, + 'Location': array([ -6.41386175, -21.22440147, 0.1762982 ]), + 'Rotation': array([-0.06512585, 0.41171354, 0.00959264]), + 'Velocity': array([-0.39400539, -0.00374612, 0.00077597]), + 'brake_input': 0.0, + 'camera_location': array([-7.15320683, 8.99574661, -0.69268751]), + 'camera_rotation': array([ -7.96165037, -33.29491043, -4.85358191]), + 'current_gear_input': False, + 'focus_actor_dist': 317.01678466796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -504.48175049, -1788.16552734, 98.04094696]), + 'frame': 25659, + 'frame_number': 25659, + 'framesequence': 98687, + 'gaze_dir': array([ 0.9681778 , -0.23647308, 0.08065033]), + 'gaze_origin': array([-3.02042031, 0.16992112, -0.13798676]), + 'gaze_valid': True, + 'gaze_vergence': 109.37639617919922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96891785, -0.22940063, 0.092453 ]), + 'left_gaze_origin': array([-3.01386595, 3.02494216, -0.08942109]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.82952880859375, + 'left_pupil_posn': array([ 0.05973136, -0.15406477]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96743774, -0.24354553, 0.06884766]), + 'right_gaze_origin': array([-3.02697468, -2.68509984, -0.18655244]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8585968017578125, + 'right_pupil_posn': array([-0.42763799, -0.25219905]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.012469862587749958, + 'throttle_input': 0.3452201187610626, + 'timestamp': 831.7103124782443, + 'timestamp_carla': 831712, + 'timestamp_device': 3985140, + 'timestamp_stream': 831.7103124782443, + 'transform': [array([ 4.22277594e+00, 1.24293861e+01, -6.83059683e-03]), + array([ -0.05760581, -12.51157665, 0.03999464])]} +{'AngularVelocity': array([-0.00072189, -0.03278137, 0.54602993]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10585903376340866, + 'FR_Wheel_Angle': 0.10598865151405334, + 'Location': array([ -6.48556423, -21.22400093, 0.17636129]), + 'Rotation': array([-0.06210008, 0.36627078, 0.00939435]), + 'Velocity': array([-2.02940255e-01, 1.28328684e-03, 1.92155829e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.1550107 , 8.84410667, -0.72437125]), + 'camera_rotation': array([ -7.987988 , -34.07652664, -4.84289408]), + 'current_gear_input': False, + 'focus_actor_dist': 332.27642822265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -527.93182373, -1794.13256836, 109.38667297]), + 'frame': 25660, + 'frame_number': 25660, + 'framesequence': 98691, + 'gaze_dir': array([ 0.96729279, -0.21907043, 0.12701416]), + 'gaze_origin': array([-3.01939392, 0.16459122, -0.1020073 ]), + 'gaze_valid': True, + 'gaze_vergence': 49.96697998046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9662323 , -0.21578979, 0.14074707]), + 'left_gaze_origin': array([-3.01223612, 3.01380324, -0.052565 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6938323974609375, + 'left_pupil_posn': array([ 0.07443011, -0.11311162]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96835327, -0.22235107, 0.11328125]), + 'right_gaze_origin': array([-3.02655196, -2.68462086, -0.15144959]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.923797607421875, + 'right_pupil_posn': array([-0.42222017, -0.21109557]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.010986663401126862, + 'throttle_input': 0.3491874635219574, + 'timestamp': 831.7433105781674, + 'timestamp_carla': 831745, + 'timestamp_device': 3985174, + 'timestamp_stream': 831.7433105781674, + 'transform': [array([ 4.23117781e+00, 1.23541327e+01, -6.97727175e-03]), + array([ -0.05739408, -12.5359621 , 0.04035235])]} +{'AngularVelocity': array([ 0.00337551, -0.01084276, 0.43236354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10602670907974243, + 'FR_Wheel_Angle': 0.10622186958789825, + 'Location': array([ -6.5233469 , -21.22364235, 0.17640692]), + 'Rotation': array([-0.06371883, 0.33910218, 0.00971914]), + 'Velocity': array([-0.10527442, 0.00114915, 0.00025596]), + 'brake_input': 0.0, + 'camera_location': array([-7.16954088, 8.71128082, -0.75672704]), + 'camera_rotation': array([ -8.10062408, -34.78408432, -4.88312626]), + 'current_gear_input': False, + 'focus_actor_dist': 372.9571533203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -560.01586914, -1827.96704102, 123.92412567]), + 'frame': 25661, + 'frame_number': 25661, + 'framesequence': 98695, + 'gaze_dir': array([ 0.9688797 , -0.21040344, 0.12918091]), + 'gaze_origin': array([-3.01887918, 0.15959093, -0.10260011]), + 'gaze_valid': True, + 'gaze_vergence': 39.349334716796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96746826, -0.20657349, 0.14596558]), + 'left_gaze_origin': array([-3.01230931, 3.0127871 , -0.05331879]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.690826416015625, + 'left_pupil_posn': array([ 0.0779525 , -0.11375713]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97029114, -0.2142334 , 0.11239624]), + 'right_gaze_origin': array([-3.0254488 , -2.69360518, -0.15188141]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9635009765625, + 'right_pupil_posn': array([-0.41264725, -0.20916772]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00990630779415369, + 'throttle_input': 0.3531548082828522, + 'timestamp': 831.7759651765227, + 'timestamp_carla': 831778, + 'timestamp_device': 3985207, + 'timestamp_stream': 831.7759651765227, + 'transform': [array([ 4.23837900e+00, 1.22780609e+01, -7.10721966e-03]), + array([ -0.05727113, -12.55798531, 0.04067648])]} +{'AngularVelocity': array([ 0.00152317, -0.03325884, -0.65473461]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.11116475611925125, + 'FR_Wheel_Angle': 0.11130627989768982, + 'Location': array([ -6.55237722, -21.22400093, 0.17644052]), + 'Rotation': array([-0.0671954 , 0.34803814, 0.00998745]), + 'Velocity': array([-0.07683327, -0.00173763, 0.0003786 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.18439245, 8.62952518, -0.75081158]), + 'camera_rotation': array([ -8.06671906, -35.27564621, -4.66699266]), + 'current_gear_input': False, + 'focus_actor_dist': 370.9111633300781, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -559.92724609, -1832.69311523, 124.16711426]), + 'frame': 25662, + 'frame_number': 25662, + 'framesequence': 98699, + 'gaze_dir': array([ 0.96887207, -0.21084595, 0.12864685]), + 'gaze_origin': array([-3.01856542, 0.15789337, -0.10242081]), + 'gaze_valid': True, + 'gaze_vergence': 29.55525779724121, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96731567, -0.20852661, 0.14416504]), + 'left_gaze_origin': array([-3.01264215, 3.01243305, -0.05494843]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6899871826171875, + 'left_pupil_posn': array([ 0.07856393, -0.11465299]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97042847, -0.21316528, 0.11312866]), + 'right_gaze_origin': array([-3.02448916, -2.69664621, -0.14989319]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.83905029296875, + 'right_pupil_posn': array([-0.41120243, -0.20822906]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00875270925462246, + 'throttle_input': 0.3531548082828522, + 'timestamp': 831.809882376343, + 'timestamp_carla': 831812, + 'timestamp_device': 3985240, + 'timestamp_stream': 831.809882376343, + 'transform': [array([ 4.24496746e+00, 1.21973619e+01, -7.17437733e-03]), + array([ -0.05718917, -12.57920265, 0.04085698])]} +{'AngularVelocity': array([-3.79663281e-04, -2.74337996e-02, -6.82443202e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.11251749098300934, + 'FR_Wheel_Angle': 0.11264996975660324, + 'Location': array([ -6.56858873, -21.22438431, 0.17647325]), + 'Rotation': array([-0.06774864, 0.35872313, 0.00972234]), + 'Velocity': array([-0.03937769, -0.00109081, -0.00031419]), + 'brake_input': 0.0, + 'camera_location': array([-7.21197796, 8.57170105, -0.72815394]), + 'camera_rotation': array([ -7.94875526, -35.69205856, -4.57142639]), + 'current_gear_input': False, + 'focus_actor_dist': 368.592529296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -560.68774414, -1836.0123291 , 124.54512024]), + 'frame': 25663, + 'frame_number': 25663, + 'framesequence': 98703, + 'gaze_dir': array([ 0.96886444, -0.21098328, 0.12843323]), + 'gaze_origin': array([-3.01900887, 0.15581284, -0.10530168]), + 'gaze_valid': True, + 'gaze_vergence': 16.237016677856445, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96696472, -0.20970154, 0.14482117]), + 'left_gaze_origin': array([-3.01315165, 3.01235533, -0.05646668]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.680694580078125, + 'left_pupil_posn': array([ 0.07893336, -0.11612666]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97076416, -0.21226501, 0.11204529]), + 'right_gaze_origin': array([-3.02486587, -2.70072937, -0.15413667]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.777557373046875, + 'right_pupil_posn': array([-0.40885025, -0.21114469]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00774559797719121, + 'throttle_input': 0.3531548082828522, + 'timestamp': 831.8433731794357, + 'timestamp_carla': 831845, + 'timestamp_device': 3985274, + 'timestamp_stream': 831.8433731794357, + 'transform': [array([ 4.25056791e+00, 1.21159954e+01, -7.21004466e-03]), + array([ -0.05714136, -12.59848785, 0.04098753])]} +{'AngularVelocity': array([-0.00121326, -0.02854973, -0.6851719 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.11255841702222824, + 'FR_Wheel_Angle': 0.11268118768930435, + 'Location': array([ -6.57818222, -21.22461891, 0.17647791]), + 'Rotation': array([-0.06860241, 0.36526108, 0.0096784 ]), + 'Velocity': array([-0.0230449 , -0.00083628, -0.00016021]), + 'brake_input': 0.0, + 'camera_location': array([-7.21721077, 8.52972603, -0.70087057]), + 'camera_rotation': array([ -7.85654783, -35.99977875, -4.57531404]), + 'current_gear_input': False, + 'focus_actor_dist': 368.4825439453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -562.80725098, -1841.58850098, 125.3575592 ]), + 'frame': 25664, + 'frame_number': 25664, + 'framesequence': 98707, + 'gaze_dir': array([ 0.96965027, -0.20898438, 0.12612915]), + 'gaze_origin': array([-3.01982212, 0.15690079, -0.10797577]), + 'gaze_valid': True, + 'gaze_vergence': 66.62866973876953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96884155, -0.20516968, 0.13867188]), + 'left_gaze_origin': array([-3.01507592, 3.01337743, -0.05994721]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.65478515625, + 'left_pupil_posn': array([ 0.07806337, -0.11835587]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97045898, -0.21279907, 0.11358643]), + 'right_gaze_origin': array([-3.02456832, -2.6995759 , -0.15600434]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8375244140625, + 'right_pupil_posn': array([-0.40814477, -0.21403015]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.006463820580393076, + 'throttle_input': 0.35712215304374695, + 'timestamp': 831.8764804787934, + 'timestamp_carla': 831878, + 'timestamp_device': 3985307, + 'timestamp_stream': 831.8764804787934, + 'transform': [array([ 4.25489664e+00, 1.20339785e+01, -7.23627070e-03]), + array([ -0.05706623, -12.61524868, 0.04110622])]} +{'AngularVelocity': array([0.00133341, 0.03972821, 0.66322827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.11256947368383408, + 'FR_Wheel_Angle': 0.11267752945423126, + 'Location': array([ -6.58848238, -21.22480011, 0.17651875]), + 'Rotation': array([-0.07009823, 0.37531921, 0.00958204]), + 'Velocity': array([-6.40020519e-02, -6.15842000e-05, 6.98156364e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.2288661 , 8.53290367, -0.69708335]), + 'camera_rotation': array([ -7.79217291, -35.96216583, -4.39822197]), + 'current_gear_input': False, + 'focus_actor_dist': 364.9200744628906, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -561.25006104, -1846.26037598, 125.21803284]), + 'frame': 25665, + 'frame_number': 25665, + 'framesequence': 98711, + 'gaze_dir': array([ 0.96768188, -0.21858215, 0.12418365]), + 'gaze_origin': array([-3.02066588, 0.16342087, -0.10830841]), + 'gaze_valid': True, + 'gaze_vergence': 6.225554466247559, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96536255, -0.21809387, 0.14309692]), + 'left_gaze_origin': array([-3.01500416, 3.01970983, -0.06166992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.604644775390625, + 'left_pupil_posn': array([ 0.07146943, -0.12217903]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97000122, -0.21907043, 0.10527039]), + 'right_gaze_origin': array([-3.02632761, -2.69286823, -0.15494691]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8916473388671875, + 'right_pupil_posn': array([-0.41736591, -0.21276379]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004651021212339401, + 'throttle_input': 0.35712215304374695, + 'timestamp': 831.909696277231, + 'timestamp_carla': 831911, + 'timestamp_device': 3985340, + 'timestamp_stream': 831.909696277231, + 'transform': [array([ 4.25768805e+00, 1.19502010e+01, -7.24681839e-03]), + array([ -0.05689547, -12.6290102 , 0.04119299])]} +{'AngularVelocity': array([-0.00046158, 0.0063276 , -0.00497897]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10617978125810623, + 'FR_Wheel_Angle': 0.10499317198991776, + 'Location': array([ -6.59934998, -21.22485352, 0.17656499]), + 'Rotation': array([-0.07065147, 0.37335187, 0.00964078]), + 'Velocity': array([-5.93060367e-02, -4.38215793e-04, 1.74045563e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.19543552, 8.54883385, -0.69715375]), + 'camera_rotation': array([ -7.69922113, -35.95296097, -4.37736654]), + 'current_gear_input': False, + 'focus_actor_dist': 360.4574890136719, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -560.17138672, -1848.91625977, 125.10248566]), + 'frame': 25666, + 'frame_number': 25666, + 'framesequence': 98715, + 'gaze_dir': array([ 0.96881866, -0.21855164, 0.11614227]), + 'gaze_origin': array([-3.0203073 , 0.16668245, -0.1096695 ]), + 'gaze_valid': True, + 'gaze_vergence': 8.837014198303223, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96742249, -0.21908569, 0.12678528]), + 'left_gaze_origin': array([-3.01521635, 3.02174544, -0.06166992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.622772216796875, + 'left_pupil_posn': array([ 0.07048845, -0.12217903]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97021484, -0.21801758, 0.10549927]), + 'right_gaze_origin': array([-3.02539849, -2.68838048, -0.15766907]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.801025390625, + 'right_pupil_posn': array([-0.4209435 , -0.21993625]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.002728354884311557, + 'throttle_input': 0.35712215304374695, + 'timestamp': 831.9434229768813, + 'timestamp_carla': 831945, + 'timestamp_device': 3985374, + 'timestamp_stream': 831.9434229768813, + 'transform': [array([ 4.25876331e+00, 1.18636732e+01, -7.20977783e-03]), + array([ -0.05663592, -12.63950443, 0.04118195])]} +{'AngularVelocity': array([-0.00052816, 0.00909514, -0.00381608]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10487356781959534, + 'FR_Wheel_Angle': 0.10496944934129715, + 'Location': array([ -6.60964346, -21.22490883, 0.17656194]), + 'Rotation': array([-0.07065147, 0.37335187, 0.00964078]), + 'Velocity': array([-6.57002255e-02, -4.84972057e-04, 7.12585461e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.18293953, 8.59001541, -0.67026335]), + 'camera_rotation': array([ -7.65350676, -35.81480026, -4.33681583]), + 'current_gear_input': False, + 'focus_actor_dist': 349.36419677734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -551.66937256, -1850.42114258, 123.1177063 ]), + 'frame': 25667, + 'frame_number': 25667, + 'framesequence': 98719, + 'gaze_dir': array([ 0.98595428, -0.13319397, 0.09916687]), + 'gaze_origin': array([-2.9776032 , 0.08874284, -0.13291626]), + 'gaze_valid': True, + 'gaze_vergence': 146.6559600830078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98718262, -0.11807251, 0.10726929]), + 'left_gaze_origin': array([-2.8793366 , 2.94112563, -0.11641236]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.784576416015625, + 'left_pupil_posn': array([ 0.14871943, -0.13758945]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98472595, -0.14831543, 0.09106445]), + 'right_gaze_origin': array([-3.07587004, -2.76363993, -0.14942017]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.834564208984375, + 'right_pupil_posn': array([-0.33372331, -0.230106 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0004577776708174497, + 'throttle_input': 0.35712215304374695, + 'timestamp': 831.9752996787429, + 'timestamp_carla': 831977, + 'timestamp_device': 3985407, + 'timestamp_stream': 831.9752996787429, + 'transform': [array([ 4.25764322e+00, 1.17806215e+01, -7.18587870e-03]), + array([ -0.05628075, -12.64512253, 0.04122382])]} +{'AngularVelocity': array([-0.00238679, 0.01499773, 0.05821492]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10391480475664139, + 'FR_Wheel_Angle': 0.10400889068841934, + 'Location': array([ -6.67159939, -21.22550011, 0.17673714]), + 'Rotation': array([-0.09264468, 0.40615821, 0.0098534 ]), + 'Velocity': array([-5.75661898e-01, -4.73350938e-03, 3.19538114e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.16486454, 8.66671848, -0.65211517]), + 'camera_rotation': array([ -7.6333437 , -35.39844131, -4.27855682]), + 'current_gear_input': False, + 'focus_actor_dist': 352.9998474121094, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -534.04815674, -1885.13500977, 118.84634399]), + 'frame': 25668, + 'frame_number': 25668, + 'framesequence': 98723, + 'gaze_dir': array([ 0.98588562, -0.13234711, 0.10145569]), + 'gaze_origin': array([-2.97797418, 0.08990327, -0.13323289]), + 'gaze_valid': True, + 'gaze_vergence': 101.39189147949219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98558044, -0.12513733, 0.11381531]), + 'left_gaze_origin': array([-2.88801289, 2.94215727, -0.11452637]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7783660888671875, + 'left_pupil_posn': array([ 0.15111828, -0.13855815]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9861908 , -0.13955688, 0.08909607]), + 'right_gaze_origin': array([-3.06793523, -2.76235056, -0.15193939]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8399505615234375, + 'right_pupil_posn': array([-0.33703101, -0.22801602]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0018494217656552792, + 'throttle_input': 0.35712215304374695, + 'timestamp': 832.0093174763024, + 'timestamp_carla': 832011, + 'timestamp_device': 3985440, + 'timestamp_stream': 832.0093174763024, + 'transform': [array([ 4.25411224e+00, 1.16907225e+01, -7.10506411e-03]), + array([ -0.05585045, -12.64633942, 0.04112099])]} +{'AngularVelocity': array([-0.00075629, 0.00078471, -0.08599906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10368505120277405, + 'FR_Wheel_Angle': 0.1037464439868927, + 'Location': array([ -6.79341221, -21.22639656, 0.17681997]), + 'Rotation': array([-0.08462604, 0.39960593, 0.00985049]), + 'Velocity': array([-7.07958579e-01, -5.35229687e-03, 6.34737022e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.12388515, 8.74621391, -0.65318865]), + 'camera_rotation': array([ -7.61553764, -34.94255447, -4.28307343]), + 'current_gear_input': False, + 'focus_actor_dist': 361.3516540527344, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -538.47625732, -1901.22766113, 119.53413391]), + 'frame': 25669, + 'frame_number': 25669, + 'framesequence': 98727, + 'gaze_dir': array([ 0.98455048, -0.14509583, 0.09721375]), + 'gaze_origin': array([-2.9651866 , 0.09504853, -0.13642196]), + 'gaze_valid': True, + 'gaze_vergence': 154.114013671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9848175 , -0.13711548, 0.10644531]), + 'left_gaze_origin': array([-2.86957097, 2.94838881, -0.11890107]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.842071533203125, + 'left_pupil_posn': array([ 0.14222753, -0.13863742]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98428345, -0.15307617, 0.08798218]), + 'right_gaze_origin': array([-3.06080198, -2.75829172, -0.15394288]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.836090087890625, + 'right_pupil_posn': array([-0.34404284, -0.23057604]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.003625598968937993, + 'throttle_input': 0.3610894978046417, + 'timestamp': 832.0430593788624, + 'timestamp_carla': 832045, + 'timestamp_device': 3985474, + 'timestamp_stream': 832.0430593788624, + 'transform': [array([ 4.24873114e+00, 1.16001806e+01, -6.99871033e-03]), + array([ -0.05548845, -12.64371777, 0.04098041])]} +{'AngularVelocity': array([ 0.00020239, -0.07901447, -0.02941734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10331131517887115, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.94878721, -21.22748947, 0.1769658 ]), + 'Rotation': array([-0.08407279, 0.38895422, 0.00995628]), + 'Velocity': array([-8.92154217e-01, -6.52526412e-03, 7.09257089e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.07628155, 8.88371754, -0.62585109]), + 'camera_rotation': array([ -7.61081791, -34.28971481, -4.27615547]), + 'current_gear_input': False, + 'focus_actor_dist': 352.3472900390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -533.43615723, -1902.77648926, 118.24000549]), + 'frame': 25670, + 'frame_number': 25670, + 'framesequence': 98731, + 'gaze_dir': array([ 0.98600769, -0.14284515, 0.08296204]), + 'gaze_origin': array([-3.11499786, 0.11513291, -0.08790284]), + 'gaze_valid': True, + 'gaze_vergence': 37.03340530395508, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98327637, -0.14964294, 0.10369873]), + 'left_gaze_origin': array([-3.16927505, 2.97597814, -0.02122955]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7890777587890625, + 'left_pupil_posn': array([ 0.13142431, -0.13885117]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98873901, -0.13604736, 0.06222534]), + 'right_gaze_origin': array([-3.06072116, -2.74571228, -0.15457611]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8046722412109375, + 'right_pupil_posn': array([-0.35723692, -0.23176968]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004943998530507088, + 'throttle_input': 0.3610894978046417, + 'timestamp': 832.0756979770958, + 'timestamp_carla': 832077, + 'timestamp_device': 3985507, + 'timestamp_stream': 832.0756979770958, + 'transform': [array([ 4.24169827e+00, 1.15112457e+01, -6.91808667e-03]), + array([ -0.05522891, -12.63749504, 0.04090664])]} +{'AngularVelocity': array([ 3.91009708e-05, -1.95963979e-02, -2.98288651e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.976717 , -21.22768593, 0.17666033]), + 'Rotation': array([-0.02587959, 0.38802278, 0.00987222]), + 'Velocity': array([ 0.33911926, 0.00214907, -0.00046761]), + 'brake_input': 0.0, + 'camera_location': array([-6.99966574, 9.07034492, -0.59222877]), + 'camera_rotation': array([ -7.51060534, -33.31889343, -4.32853222]), + 'current_gear_input': False, + 'focus_actor_dist': 335.99468994140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -518.22558594, -1903.87915039, 114.34210205]), + 'frame': 25671, + 'frame_number': 25671, + 'framesequence': 98735, + 'gaze_dir': array([ 0.98365021, -0.15740204, 0.08299255]), + 'gaze_origin': array([-3.12525177, 0.13108596, -0.08683854]), + 'gaze_valid': True, + 'gaze_vergence': 52.10377883911133, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97943115, -0.17175293, 0.10577393]), + 'left_gaze_origin': array([-3.23248768e+00, 2.99424314e+00, -2.52380385e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.788421630859375, + 'left_pupil_posn': array([ 0.11666822, -0.13891399]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98786926, -0.14305115, 0.06021118]), + 'right_gaze_origin': array([-3.0180161 , -2.73207116, -0.17115328]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8355865478515625, + 'right_pupil_posn': array([-0.37393743, -0.23440981]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0055482652969658375, + 'throttle_input': 0.3610894978046417, + 'timestamp': 832.1095017790794, + 'timestamp_carla': 832111, + 'timestamp_device': 3985540, + 'timestamp_stream': 832.1095017790794, + 'transform': [array([ 4.23318768e+00, 1.14176073e+01, -6.83729164e-03]), + array([ -0.05512645, -12.62860394, 0.04081267])]} +{'AngularVelocity': array([-6.27935282e-04, 1.29347518e-01, 1.70482817e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.90083551, -21.22720718, 0.17669222]), + 'Rotation': array([-0.04470358, 0.3880243 , 0.00985985]), + 'Velocity': array([ 0.45768759, 0.00289478, -0.00050714]), + 'brake_input': 0.0, + 'camera_location': array([-6.92394686, 9.27383232, -0.5553354 ]), + 'camera_rotation': array([ -7.37790155, -32.34315872, -4.40977097]), + 'current_gear_input': False, + 'focus_actor_dist': 339.49737548828125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -520.43328857, -1915.90637207, 114.45574951]), + 'frame': 25672, + 'frame_number': 25672, + 'framesequence': 98741, + 'gaze_dir': array([ 0.97825623, -0.18875885, 0.08226013]), + 'gaze_origin': array([-3.05363083, 0.14310381, -0.11120301]), + 'gaze_valid': True, + 'gaze_vergence': 5.722165107727051, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97590637, -0.19042969, 0.10636902]), + 'left_gaze_origin': array([-3.0701983 , 3.00201273, -0.05465699]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8572845458984375, + 'left_pupil_posn': array([ 0.09535766, -0.14446414]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98060608, -0.18708801, 0.05815125]), + 'right_gaze_origin': array([-3.03706384, -2.71580505, -0.16774903]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9568023681640625, + 'right_pupil_posn': array([-0.39208353, -0.23613024]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005932798609137535, + 'throttle_input': 0.3610894978046417, + 'timestamp': 832.1551998779178, + 'timestamp_carla': 832157, + 'timestamp_device': 3985590, + 'timestamp_stream': 832.1551998779178, + 'transform': [array([ 4.21960783e+00, 1.12887611e+01, -6.68840390e-03]), + array([ -0.05523574, -12.61249924, 0.04056134])]} +{'AngularVelocity': array([-0.00056316, 0.14573854, 0.00955679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10445188730955124, + 'FR_Wheel_Angle': 0.1045965626835823, + 'Location': array([ -6.81470299, -21.22664261, 0.17673269]), + 'Rotation': array([-0.0668334 , 0.38847253, 0.00976045]), + 'Velocity': array([ 0.31592491, 0.00227726, -0.00043061]), + 'brake_input': 0.0, + 'camera_location': array([-6.84860706, 9.49259567, -0.51732087]), + 'camera_rotation': array([ -7.30271482, -31.23250961, -4.28073597]), + 'current_gear_input': False, + 'focus_actor_dist': 335.9927062988281, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -521.65649414, -1919.49853516, 114.53476715]), + 'frame': 25673, + 'frame_number': 25673, + 'framesequence': 98745, + 'gaze_dir': array([ 0.97581482, -0.20246887, 0.0788269 ]), + 'gaze_origin': array([-3.04963541, 0.14445725, -0.1111435 ]), + 'gaze_valid': True, + 'gaze_vergence': 0.3846755623817444, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9737854 , -0.20301819, 0.10255432]), + 'left_gaze_origin': array([-3.06296706, 3.00551939, -0.05527192]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.916290283203125, + 'left_pupil_posn': array([ 0.08785105, -0.14485943]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97784424, -0.20191956, 0.05509949]), + 'right_gaze_origin': array([-3.03630376, -2.71660471, -0.16701508]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.02410888671875, + 'right_pupil_posn': array([-0.39600801, -0.23714721]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.006793420296162367, + 'throttle_input': 0.3610894978046417, + 'timestamp': 832.1888919770718, + 'timestamp_carla': 832191, + 'timestamp_device': 3985624, + 'timestamp_stream': 832.1888919770718, + 'transform': [array([ 4.20976305e+00, 1.11916780e+01, -6.56925188e-03]), + array([ -0.05530404, -12.60101891, 0.04042769])]} +{'AngularVelocity': array([ 0.00018664, -0.00077246, 0.00510523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10480724275112152, + 'FR_Wheel_Angle': 0.1036420613527298, + 'Location': array([ -6.77732849, -21.22637177, 0.17677881]), + 'Rotation': array([-0.0794351 , 0.38981909, 0.00977199]), + 'Velocity': array([1.06431141e-01, 8.39045504e-04, 7.12823821e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.74611425, 9.75721741, -0.50858635]), + 'camera_rotation': array([ -7.32649755, -29.76264763, -4.07478142]), + 'current_gear_input': False, + 'focus_actor_dist': 359.03076171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -537.10986328, -1950.08068848, 112.38704681]), + 'frame': 25674, + 'frame_number': 25674, + 'framesequence': 98749, + 'gaze_dir': array([ 0.99501801, -0.00695801, 0.09779358]), + 'gaze_origin': array([-2.99277878, -0.01268997, -0.10394135]), + 'gaze_valid': True, + 'gaze_vergence': 160.66412353515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99520874, 0.010849 , 0.09713745]), + 'left_gaze_origin': array([-2.80481124, 2.85075402, -0.11677857]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0832061767578125, + 'left_pupil_posn': array([ 0.25076032, -0.12146759]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99482727, -0.02476501, 0.09844971]), + 'right_gaze_origin': array([-3.18074679, -2.87613392, -0.09110413]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7336578369140625, + 'right_pupil_posn': array([-0.21117127, -0.21449316]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0076174200512468815, + 'throttle_input': 0.3610894978046417, + 'timestamp': 832.2217058762908, + 'timestamp_carla': 832223, + 'timestamp_device': 3985657, + 'timestamp_stream': 832.2217058762908, + 'transform': [array([ 4.19873381e+00, 1.10956831e+01, -6.49757357e-03]), + array([ -0.05528355, -12.58695507, 0.04039022])]} +{'AngularVelocity': array([ 0.00042299, -0.02243837, 0.00077359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.05508236587047577, + 'FR_Wheel_Angle': 0.05509672686457634, + 'Location': array([ -6.76853371, -21.22631264, 0.17675787]), + 'Rotation': array([-0.078554 , 0.39003089, 0.00977787]), + 'Velocity': array([ 9.06016771e-03, 9.50413669e-05, -1.63097371e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.61380816, 10.05893326, -0.48639804]), + 'camera_rotation': array([ -7.2944231 , -27.97717476, -4.04699564]), + 'current_gear_input': False, + 'focus_actor_dist': 743.3204345703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -686.69189453, -2332.38818359, 111.88912201]), + 'frame': 25675, + 'frame_number': 25675, + 'framesequence': 98752, + 'gaze_dir': array([0.97903442, 0.17813873, 0.0952301 ]), + 'gaze_origin': array([-3.04920959, -0.15979233, -0.07648163]), + 'gaze_valid': True, + 'gaze_vergence': 108.06157684326172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97442627, 0.2036438 , 0.09483337]), + 'left_gaze_origin': array([-3.02988601, 2.69187927, -0.04244538]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.02252197265625, + 'left_pupil_posn': array([ 0.42628622, -0.11671209]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98364258, 0.15263367, 0.09562683]), + 'right_gaze_origin': array([-3.06853342, -3.01146412, -0.11051788]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7946319580078125, + 'right_pupil_posn': array([-0.05155915, -0.21025133]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00878933072090149, + 'throttle_input': 0.3293507397174835, + 'timestamp': 832.2534150779247, + 'timestamp_carla': 832255, + 'timestamp_device': 3985682, + 'timestamp_stream': 832.2534150779247, + 'transform': [array([ 4.18661928e+00, 1.10016127e+01, -6.42248150e-03]), + array([ -0.05516744, -12.57040882, 0.04034839])]} +{'AngularVelocity': array([ 5.78859435e-05, -2.14497987e-02, -1.95403839e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.053731586784124374, + 'FR_Wheel_Angle': 0.053674228489398956, + 'Location': array([ -6.77813387, -21.22637177, 0.17675501]), + 'Rotation': array([-0.07626589, 0.38987052, 0.00978568]), + 'Velocity': array([-7.19815940e-02, -4.99334710e-04, -3.69071968e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.47955942, 10.41262913, -0.45400977]), + 'camera_rotation': array([ -7.2299118 , -25.84450722, -3.72900939]), + 'current_gear_input': False, + 'focus_actor_dist': 1579.322265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -839.14221191, -3197.15649414, 107.45930481]), + 'frame': 25676, + 'frame_number': 25676, + 'framesequence': 98756, + 'gaze_dir': array([0.95476532, 0.28517151, 0.08144379]), + 'gaze_origin': array([-3.06855869, -0.22989275, -0.08092194]), + 'gaze_valid': True, + 'gaze_vergence': 124.86666870117188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94845581, 0.3052063 , 0.08526611]), + 'left_gaze_origin': array([-3.0514679 , 2.61224079, -0.05622559]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1484832763671875, + 'left_pupil_posn': array([ 0.52546728, -0.13920534]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96107483, 0.26513672, 0.07762146]), + 'right_gaze_origin': array([-3.08564925, -3.07202625, -0.10561829]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7653045654296875, + 'right_pupil_posn': array([ 0.02585506, -0.21655881]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.010126041248440742, + 'throttle_input': 0.2737926244735718, + 'timestamp': 832.2869665771723, + 'timestamp_carla': 832289, + 'timestamp_device': 3985715, + 'timestamp_stream': 832.2869665771723, + 'transform': [array([ 4.17213202e+00, 1.09008703e+01, -6.25202153e-03]), + array([ -0.05498302, -12.54947853, 0.04008749])]} +{'AngularVelocity': array([-0.0013916 , 0.05243078, -0.34983203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.053297627717256546, + 'FR_Wheel_Angle': 0.05330364406108856, + 'Location': array([ -6.84893131, -21.22685814, 0.1768588 ]), + 'Rotation': array([-0.09109423, 0.3819333 , 0.00976906]), + 'Velocity': array([-0.57626861, -0.00355843, 0.00069674]), + 'brake_input': 0.0, + 'camera_location': array([-6.32780027, 10.87936211, -0.44602805]), + 'camera_rotation': array([ -7.18028355, -22.94100189, -3.54512978]), + 'current_gear_input': False, + 'focus_actor_dist': 1501.8699951171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -597.87414551, -3197.49633789, 103.29516602]), + 'frame': 25677, + 'frame_number': 25677, + 'framesequence': 98760, + 'gaze_dir': array([0.93442535, 0.34954834, 0.06525421]), + 'gaze_origin': array([-3.08325911, -0.26921692, -0.09299622]), + 'gaze_valid': True, + 'gaze_vergence': 130.07762145996094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92822266, 0.36720276, 0.05952454]), + 'left_gaze_origin': array([-3.06833959, 2.56640482, -0.06924591]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.243194580078125, + 'left_pupil_posn': array([ 0.58623278, -0.15623951]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94062805, 0.33189392, 0.07098389]), + 'right_gaze_origin': array([-3.09817839, -3.10483885, -0.11674652]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8816375732421875, + 'right_pupil_posn': array([ 0.07020259, -0.23826802]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01146275270730257, + 'throttle_input': 0.1904631108045578, + 'timestamp': 832.3194830790162, + 'timestamp_carla': 832321, + 'timestamp_device': 3985748, + 'timestamp_stream': 832.3194830790162, + 'transform': [array([ 4.15645504e+00, 1.08023729e+01, -5.88079449e-03]), + array([ -0.05483276, -12.52576542, 0.03945006])]} +{'AngularVelocity': array([-3.84243722e-05, -4.20721881e-02, -6.06999137e-02]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.05323599651455879, + 'FR_Wheel_Angle': 0.053257912397384644, + 'Location': array([ -6.98402739, -21.22766304, 0.17692915]), + 'Rotation': array([-0.07849253, 0.37461111, 0.00997618]), + 'Velocity': array([-5.90833843e-01, -3.78229097e-03, 4.04777529e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.17602968, 11.35260868, -0.41602564]), + 'camera_rotation': array([ -6.9220891 , -20.04870605, -3.73197365]), + 'current_gear_input': False, + 'focus_actor_dist': 3862.75634765625, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -637.9196167 , -5584.671875 , 17.46865082]), + 'frame': 25678, + 'frame_number': 25678, + 'framesequence': 98764, + 'gaze_dir': array([0.94342041, 0.32566833, 0.0610199 ]), + 'gaze_origin': array([-3.07562351, -0.25235063, -0.09299241]), + 'gaze_valid': True, + 'gaze_vergence': 195.2826690673828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93994141, 0.33670044, 0.05593872]), + 'left_gaze_origin': array([-3.05990767, 2.5884583 , -0.07109375]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.370880126953125, + 'left_pupil_posn': array([ 0.56255436, -0.15679741]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94689941, 0.31463623, 0.06610107]), + 'right_gaze_origin': array([-3.09133911, -3.09315968, -0.11489106]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.904296875, + 'right_pupil_posn': array([ 0.05107844, -0.23569453]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.012561419047415257, + 'throttle_input': 0.11903563141822815, + 'timestamp': 832.35221657902, + 'timestamp_carla': 832354, + 'timestamp_device': 3985782, + 'timestamp_stream': 832.35221657902, + 'transform': [array([ 4.13931751e+00, 1.07027130e+01, -5.23653021e-03]), + array([ -0.0547986 , -12.49900341, 0.03827171])]} +{'AngularVelocity': array([ 0.00052633, -0.01876688, -0.07014749]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.05319472402334213, + 'FR_Wheel_Angle': 0.05323049798607826, + 'Location': array([ -7.12862396, -21.22861099, 0.17705438]), + 'Rotation': array([-0.07397778, 0.37222794, 0.01011211]), + 'Velocity': array([-6.32358134e-01, -4.03886428e-03, 3.73010640e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.08824492, 11.82375908, -0.35261661]), + 'camera_rotation': array([ -6.54158592, -17.45169258, -3.91917944]), + 'current_gear_input': False, + 'focus_actor_dist': 3263.321044921875, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ -499.44058228, -5004.84765625, 30.63626862]), + 'frame': 25679, + 'frame_number': 25679, + 'framesequence': 98768, + 'gaze_dir': array([0.95760345, 0.28083038, 0.0614624 ]), + 'gaze_origin': array([-3.06227136, -0.21077195, -0.0889885 ]), + 'gaze_valid': True, + 'gaze_vergence': 99.67240142822266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95329285, 0.29260254, 0.07492065]), + 'left_gaze_origin': array([-3.04248667, 2.63638163, -0.06708985]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.28314208984375, + 'left_pupil_posn': array([ 0.50912488, -0.15565491]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96191406, 0.26905823, 0.04800415]), + 'right_gaze_origin': array([-3.08205581, -3.0579257 , -0.11088715]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.762298583984375, + 'right_pupil_posn': array([ 0.0114944 , -0.22264028]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.013733330182731152, + 'throttle_input': 0.0634927898645401, + 'timestamp': 832.3843059763312, + 'timestamp_carla': 832386, + 'timestamp_device': 3985815, + 'timestamp_stream': 832.3843059763312, + 'transform': [array([ 4.12130833e+00, 1.06049347e+01, -4.30601090e-03]), + array([ -0.05488057, -12.47011948, 0.03653898])]} +{'AngularVelocity': array([ 7.56917638e-04, -1.20264776e-01, -5.70212724e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.19522429, -21.22905159, 0.17690694]), + 'Rotation': array([-0.03485445, 0.37275675, 0.01012981]), + 'Velocity': array([ 2.51977146e-01, 1.53029733e-03, -9.68742315e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.03819847, 12.26452255, -0.26535133]), + 'camera_rotation': array([ -6.04102898, -15.05553436, -4.21463633]), + 'current_gear_input': False, + 'focus_actor_dist': 3252.938232421875, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ -503.418396 , -5004.86865234, 41.05242157]), + 'frame': 25680, + 'frame_number': 25680, + 'framesequence': 98772, + 'gaze_dir': array([0.96696472, 0.24888611, 0.05101013]), + 'gaze_origin': array([-3.05554581, -0.19349596, -0.09410477]), + 'gaze_valid': True, + 'gaze_vergence': 133.99658203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96191406, 0.26873779, 0.04985046]), + 'left_gaze_origin': array([-3.03596807, 2.6548326 , -0.06893921]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.31103515625, + 'left_pupil_posn': array([ 0.48071396, -0.1529876 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97201538, 0.22903442, 0.0521698 ]), + 'right_gaze_origin': array([-3.07512379, -3.04182458, -0.11927032]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9951324462890625, + 'right_pupil_posn': array([-0.00860667, -0.23533535]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.014337596483528614, + 'throttle_input': 0.01190203707665205, + 'timestamp': 832.4184581786394, + 'timestamp_carla': 832420, + 'timestamp_device': 3985848, + 'timestamp_stream': 832.4184581786394, + 'transform': [array([ 4.11088419e+00, 1.04987240e+01, -3.30675114e-03]), + array([ -0.05735309, -12.45775986, 0.03461766])]} +{'AngularVelocity': array([-4.71456180e-04, 1.11600548e-01, 1.73766639e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.1189971 , -21.22858429, 0.17694765]), + 'Rotation': array([-0.04736736, 0.37275797, 0.01008996]), + 'Velocity': array([ 4.25583959e-01, 2.57791881e-03, -3.30233568e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.02372885, 12.64064884, -0.15377912]), + 'camera_rotation': array([ -5.45350981, -13.34911156, -3.90289021]), + 'current_gear_input': False, + 'focus_actor_dist': 3241.626220703125, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ -471.2824707 , -5005.37646484, 28.72601318]), + 'frame': 25681, + 'frame_number': 25681, + 'framesequence': 98776, + 'gaze_dir': array([0.97426605, 0.21694183, 0.05768585]), + 'gaze_origin': array([-3.05000019, -0.18355866, -0.10417863]), + 'gaze_valid': True, + 'gaze_vergence': 139.34410095214844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96989441, 0.23634338, 0.05853271]), + 'left_gaze_origin': array([-3.02648163, 2.66703343, -0.08204498]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3028564453125, + 'left_pupil_posn': array([ 0.46023107, -0.15768218]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9786377 , 0.19754028, 0.05683899]), + 'right_gaze_origin': array([-3.07351851, -3.03415084, -0.12631227]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.93621826171875, + 'right_pupil_posn': array([-0.02500457, -0.23549044]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.014795374125242233, + 'throttle_input': 0.0, + 'timestamp': 832.4507661759853, + 'timestamp_carla': 832453, + 'timestamp_device': 3985882, + 'timestamp_stream': 832.4507661759853, + 'transform': [array([ 4.10559845e+00, 1.03975620e+01, -2.08608620e-03]), + array([ -0.05944996, -12.4557476 , 0.03230172])]} +{'AngularVelocity': array([-7.28410087e-05, 5.75039610e-02, 2.44742296e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.04465199, -21.22813606, 0.17695463]), + 'Rotation': array([-0.06231181, 0.37276155, 0.01002836]), + 'Velocity': array([ 4.12847370e-01, 2.50097737e-03, -3.21950909e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.05126762, 13.04044914, -0.09724961]), + 'camera_rotation': array([ -5.22677469, -11.34958839, -3.13240838]), + 'current_gear_input': False, + 'focus_actor_dist': 3557.126953125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -500.33514404, -5331.49023438, 62.47196198]), + 'frame': 25682, + 'frame_number': 25682, + 'framesequence': 98780, + 'gaze_dir': array([0.97761536, 0.19838715, 0.06941223]), + 'gaze_origin': array([-2.91893935, -0.15502931, -0.14744644]), + 'gaze_valid': True, + 'gaze_vergence': 252.99520874023438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97653198, 0.20556641, 0.06411743]), + 'left_gaze_origin': array([-2.76831365, 2.69702458, -0.16971132]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3809814453125, + 'left_pupil_posn': array([ 0.42874253, -0.16047013]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97869873, 0.19120789, 0.07470703]), + 'right_gaze_origin': array([-3.06956482, -3.00708318, -0.12518159]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.87841796875, + 'right_pupil_posn': array([-0.05436873, -0.23131549]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015637684613466263, + 'throttle_input': 0.0, + 'timestamp': 832.4845966771245, + 'timestamp_carla': 832486, + 'timestamp_device': 3985915, + 'timestamp_stream': 832.4845966771245, + 'transform': [array([ 4.10077763e+00, 1.02922688e+01, -5.82027424e-04]), + array([ -0.06075453, -12.4551363 , 0.02941734])]} +{'AngularVelocity': array([7.78514877e-05, 1.87816266e-02, 2.67993109e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.96544886, -21.22766113, 0.17690907]), + 'Rotation': array([-0.06921713, 0.37276649, 0.00995605]), + 'Velocity': array([ 3.83000553e-01, 2.32048519e-03, -3.54318618e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.09107971, 13.48782921, -0.1286903 ]), + 'camera_rotation': array([-5.42981577, -9.09037781, -2.93158984]), + 'current_gear_input': False, + 'focus_actor_dist': 3696.6103515625, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -449.04846191, -5484.74707031, 101.4264679 ]), + 'frame': 25683, + 'frame_number': 25683, + 'framesequence': 98784, + 'gaze_dir': array([0.98152924, 0.17175293, 0.08316803]), + 'gaze_origin': array([-2.85027409, -0.13945009, -0.16364214]), + 'gaze_valid': True, + 'gaze_vergence': 80.62935638427734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98176575, 0.17630005, 0.0710144 ]), + 'left_gaze_origin': array([-2.6230638 , 2.71215534, -0.2098572 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3829345703125, + 'left_pupil_posn': array([ 0.40473604, -0.15224659]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98129272, 0.16720581, 0.09532166]), + 'right_gaze_origin': array([-3.07748437, -2.99105549, -0.11742707]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6903076171875, + 'right_pupil_posn': array([-0.07513732, -0.22405553]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.017102573066949844, + 'throttle_input': 0.0, + 'timestamp': 832.518599178642, + 'timestamp_carla': 832520, + 'timestamp_device': 3985948, + 'timestamp_stream': 832.518599178642, + 'transform': [array([4.09617805e+00, 1.01874294e+01, 1.01560587e-03]), + array([ -0.06150585, -12.45494938, 0.02636022])]} +{'AngularVelocity': array([3.39067687e-04, 5.20136906e-03, 2.69439552e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.8918767 , -21.22720718, 0.17684114]), + 'Rotation': array([-0.07129351, 0.37277144, 0.00989046]), + 'Velocity': array([ 3.53747845e-01, 2.14302633e-03, -1.03855127e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.16762257, 13.92036533, -0.18801697]), + 'camera_rotation': array([-5.88077879, -7.09248352, -2.76262522]), + 'current_gear_input': False, + 'focus_actor_dist': 5318.9833984375, + 'focus_actor_name': 'SM_Shop_22', + 'focus_actor_pt': array([ -459.17120361, -7118.671875 , 128.11489868]), + 'frame': 25684, + 'frame_number': 25684, + 'framesequence': 98788, + 'gaze_dir': array([0.98737335, 0.13838959, 0.07474518]), + 'gaze_origin': array([-2.94400191, -0.10029069, -0.11564484]), + 'gaze_valid': True, + 'gaze_vergence': 47.91040802001953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98796082, 0.14360046, 0.05728149]), + 'left_gaze_origin': array([-2.70599985, 2.75563383, -0.16768952]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.190582275390625, + 'left_pupil_posn': array([ 0.36622071, -0.14012837]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98678589, 0.13317871, 0.09220886]), + 'right_gaze_origin': array([-3.18200397, -2.95621514, -0.06360017]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7901611328125, + 'right_pupil_posn': array([-0.10943896, -0.211707 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.018530840054154396, + 'throttle_input': 0.0, + 'timestamp': 832.5493689775467, + 'timestamp_carla': 832551, + 'timestamp_device': 3985982, + 'timestamp_stream': 832.5493689775467, + 'transform': [array([4.09227467e+00, 1.00935011e+01, 2.45018001e-03]), + array([ -0.06194981, -12.45525169, 0.02366439])]} +{'AngularVelocity': array([-0.00031894, 0.03175027, 0.00244246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.05621544271707535, + 'FR_Wheel_Angle': 0.05625172704458237, + 'Location': array([ -6.8462472 , -21.22691917, 0.17683332]), + 'Rotation': array([-0.07821249, 0.37330282, 0.00984254]), + 'Velocity': array([ 0.16301648, 0.00107732, -0.00044093]), + 'brake_input': 0.0, + 'camera_location': array([-6.19487286, 14.36045647, -0.24018045]), + 'camera_rotation': array([-6.08308887, -4.88768053, -2.7203548 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3520.94287109375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -392.57794189, -5331.48925781, 63.7193222 ]), + 'frame': 25685, + 'frame_number': 25685, + 'framesequence': 98792, + 'gaze_dir': array([0.99012756, 0.11177826, 0.08115387]), + 'gaze_origin': array([-2.90935755, -0.05104141, -0.11968919]), + 'gaze_valid': True, + 'gaze_vergence': 51.881412506103516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99078369, 0.12156677, 0.05969238]), + 'left_gaze_origin': array([-2.72277546, 2.80632043, -0.15738069]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2099456787109375, + 'left_pupil_posn': array([ 0.32207608, -0.132442 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98947144, 0.10198975, 0.10261536]), + 'right_gaze_origin': array([-3.09593964, -2.90840316, -0.08199769]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.830718994140625, + 'right_pupil_posn': array([-0.150383 , -0.20629442]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.020233772695064545, + 'throttle_input': 0.0, + 'timestamp': 832.5842662788928, + 'timestamp_carla': 832586, + 'timestamp_device': 3986015, + 'timestamp_stream': 832.5842662788928, + 'transform': [array([4.07378149e+00, 9.99169922e+00, 4.26645251e-03]), + array([ -0.05912894, -12.42571449, 0.02019152])]} +{'AngularVelocity': array([ 0.00030012, -0.01952718, 0.00199298]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.05374825373291969, + 'FR_Wheel_Angle': 0.05379164591431618, + 'Location': array([ -6.82496738, -21.22677612, 0.17681143]), + 'Rotation': array([-0.07775487, 0.37362161, 0.00983968]), + 'Velocity': array([ 6.58862367e-02, 4.69255989e-04, -3.28207025e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.21142292, 14.6525631 , -0.19337407]), + 'camera_rotation': array([-5.73260498, -3.64421225, -2.86457562]), + 'current_gear_input': False, + 'focus_actor_dist': 3510.404052734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -352.10845947, -5331.49023438, 67.95694733]), + 'frame': 25686, + 'frame_number': 25686, + 'framesequence': 98796, + 'gaze_dir': array([0.99216461, 0.09619904, 0.07810211]), + 'gaze_origin': array([-2.93226552, -0.05080719, -0.11892166]), + 'gaze_valid': True, + 'gaze_vergence': 86.58580780029297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99255371, 0.10353088, 0.06411743]), + 'left_gaze_origin': array([-2.72217274, 2.80657816, -0.15982667]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.128662109375, + 'left_pupil_posn': array([ 0.31746852, -0.13727307]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99177551, 0.08886719, 0.09208679]), + 'right_gaze_origin': array([-3.1423583 , -2.90819263, -0.07801667]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.717254638671875, + 'right_pupil_posn': array([-0.15669554, -0.21074402]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02211981639266014, + 'throttle_input': 0.0, + 'timestamp': 832.6178499758244, + 'timestamp_carla': 832620, + 'timestamp_device': 3986048, + 'timestamp_stream': 832.6178499758244, + 'transform': [array([4.04871655e+00, 9.89682961e+00, 5.81077579e-03]), + array([ -0.0570594 , -12.38154697, 0.01727347])]} +{'AngularVelocity': array([-0.00010504, -0.00644458, -0.00022251]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021783504635095596, + 'FR_Wheel_Angle': 0.020507751032710075, + 'Location': array([ -6.81970549, -21.22674179, 0.17679162]), + 'Rotation': array([-0.07550091, 0.37371662, 0.00983803]), + 'Velocity': array([-4.21632826e-03, -1.99508850e-05, 1.35488503e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.21188259, 14.79345894, -0.1207734 ]), + 'camera_rotation': array([-5.29220772, -3.45984197, -2.54993606]), + 'current_gear_input': False, + 'focus_actor_dist': 3499.36572265625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -329.34243774, -5331.48974609, 76.19430542]), + 'frame': 25687, + 'frame_number': 25687, + 'framesequence': 98800, + 'gaze_dir': array([0.99298859, 0.08596802, 0.07857513]), + 'gaze_origin': array([-2.92411757, -0.0599701 , -0.12908554]), + 'gaze_valid': True, + 'gaze_vergence': 27.196949005126953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99424744, 0.0891571 , 0.0592041 ]), + 'left_gaze_origin': array([-2.67047739, 2.79982924, -0.18529055]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.97930908203125, + 'left_pupil_posn': array([ 0.31876254, -0.14217234]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99172974, 0.08277893, 0.09794617]), + 'right_gaze_origin': array([-3.1777575 , -2.91976953, -0.07288055]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.664764404296875, + 'right_pupil_posn': array([-0.15363586, -0.21533 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02382274903357029, + 'throttle_input': 0.0, + 'timestamp': 832.650621779263, + 'timestamp_carla': 832652, + 'timestamp_device': 3986082, + 'timestamp_stream': 832.650621779263, + 'transform': [array([4.02207088e+00, 9.80605698e+00, 7.04431534e-03]), + array([ -0.05623294, -12.33347893, 0.01495731])]} +{'AngularVelocity': array([-0.00013129, -0.00173872, -0.00033739]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020499425008893013, + 'FR_Wheel_Angle': 0.02050326205790043, + 'Location': array([ -6.82163763, -21.22674179, 0.17672662]), + 'Rotation': array([-0.07275517, 0.37370792, 0.0098374 ]), + 'Velocity': array([-2.11249720e-02, -1.26987681e-04, -7.08961452e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.20904827, 14.9230423 , -0.06736994]), + 'camera_rotation': array([-5.1036334 , -3.16671062, -2.19406271]), + 'current_gear_input': False, + 'focus_actor_dist': 3489.347412109375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -349.76751709, -5331.49023438, 101.01191711]), + 'frame': 25688, + 'frame_number': 25688, + 'framesequence': 98804, + 'gaze_dir': array([0.96971893, 0.23538971, 0.05979156]), + 'gaze_origin': array([-2.97072315, -0.18899538, -0.13453293]), + 'gaze_valid': True, + 'gaze_vergence': 89.91851806640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96557617, 0.25610352, 0.04545593]), + 'left_gaze_origin': array([-2.81402302, 2.65745258, -0.15617982]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.051788330078125, + 'left_pupil_posn': array([ 0.46501851, -0.16027558]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97386169, 0.2146759 , 0.0741272 ]), + 'right_gaze_origin': array([-3.12742329, -3.03544331, -0.11288605]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6291351318359375, + 'right_pupil_posn': array([-0.01635092, -0.24183393]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.025855282321572304, + 'throttle_input': 0.0, + 'timestamp': 832.6837653778493, + 'timestamp_carla': 832686, + 'timestamp_device': 3986115, + 'timestamp_stream': 832.6837653778493, + 'transform': [array([3.99346542e+00, 9.71597004e+00, 8.06827564e-03]), + array([ -0.05602121, -12.2810154 , 0.01303304])]} +{'AngularVelocity': array([ 8.26999662e-04, -6.00220449e-02, -2.80729073e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.79345179, -21.2265625 , 0.17661561]), + 'Rotation': array([-0.054662 , 0.37368819, 0.00981028]), + 'Velocity': array([ 0.36954108, 0.00224594, -0.000403 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.19643307, 15.09625149, -0.05493659]), + 'camera_rotation': array([-5.10147476, -2.51000309, -2.06055999]), + 'current_gear_input': False, + 'focus_actor_dist': 3513.460693359375, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ 205.21060181, -5331.48925781, 71.45088959]), + 'frame': 25689, + 'frame_number': 25689, + 'framesequence': 98808, + 'gaze_dir': array([0.91098785, 0.41017151, 0.04266357]), + 'gaze_origin': array([-3.01649952, -0.31534272, -0.14536744]), + 'gaze_valid': True, + 'gaze_vergence': 617.7741088867188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90948486, 0.41363525, 0.04151917]), + 'left_gaze_origin': array([-2.86484385, 2.51379108, -0.16707611]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1188201904296875, + 'left_pupil_posn': array([ 0.64392436, -0.19612002]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91249084, 0.40670776, 0.04380798]), + 'right_gaze_origin': array([-3.16815495, -3.14447665, -0.12365875]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7212982177734375, + 'right_pupil_posn': array([ 0.11604047, -0.26524496]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02838221564888954, + 'throttle_input': 0.0, + 'timestamp': 832.7183904759586, + 'timestamp_carla': 832720, + 'timestamp_device': 3986148, + 'timestamp_stream': 832.7183904759586, + 'transform': [array([3.96151090e+00, 9.62374115e+00, 8.94931797e-03]), + array([-5.59938885e-02, -1.22214937e+01, 1.13643641e-02])]} +{'AngularVelocity': array([1.01814789e-04, 4.95731756e-02, 2.01230650e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.69575548, -21.22596359, 0.17657579]), + 'Rotation': array([-0.0620386 , 0.37369317, 0.00971984]), + 'Velocity': array([ 0.43174732, 0.00262257, -0.00045074]), + 'brake_input': 0.0, + 'camera_location': array([-6.18360901, 15.33393192, -0.07514708]), + 'camera_rotation': array([-5.15112352, -1.28254664, -1.84186709]), + 'current_gear_input': False, + 'focus_actor_dist': 3735.74951171875, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 953.04797363, -5386.54736328, 43.98981476]), + 'frame': 25690, + 'frame_number': 25690, + 'framesequence': 98812, + 'gaze_dir': array([0.91111755, 0.41030121, 0.03768921]), + 'gaze_origin': array([-3.0151329 , -0.31496814, -0.14255601]), + 'gaze_valid': True, + 'gaze_vergence': 158.3958740234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90945435, 0.41468811, 0.0302124 ]), + 'left_gaze_origin': array([-2.86336994, 2.51608276, -0.16570589]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1298980712890625, + 'left_pupil_posn': array([ 0.64192045, -0.19427168]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91278076, 0.40591431, 0.04516602]), + 'right_gaze_origin': array([-3.1668961 , -3.14601922, -0.11940613]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6393890380859375, + 'right_pupil_posn': array([ 0.11744273, -0.26607978]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.031147191300988197, + 'throttle_input': 0.0, + 'timestamp': 832.7510748766363, + 'timestamp_carla': 832753, + 'timestamp_device': 3986182, + 'timestamp_stream': 832.7510748766363, + 'transform': [array([3.92955709, 9.53840065, 0.00966181]), + array([-5.59802279e-02, -1.21612005e+01, 1.00574885e-02])]} +{'AngularVelocity': array([-4.47050588e-05, -4.23733518e-03, 5.02606417e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.62955666, -21.22555351, 0.17655516]), + 'Rotation': array([-0.07477008, 0.37407446, 0.00965866]), + 'Velocity': array([0.27032435, 0.00165042, 0.00071957]), + 'brake_input': 0.0, + 'camera_location': array([-6.17081642, 15.59427834, -0.11305638]), + 'camera_rotation': array([-5.17821217, 0.21948501, -1.92075181]), + 'current_gear_input': False, + 'focus_actor_dist': 3755.504638671875, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 1040.78063965, -5384.77392578, 15.90257263]), + 'frame': 25691, + 'frame_number': 25691, + 'framesequence': 98816, + 'gaze_dir': array([0.91879272, 0.39261627, 0.0404129 ]), + 'gaze_origin': array([-3.00964665, -0.30548248, -0.13723451]), + 'gaze_valid': True, + 'gaze_vergence': 554.9254150390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9175415 , 0.39576721, 0.03833008]), + 'left_gaze_origin': array([-2.85578775, 2.53002334, -0.15852661]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.007781982421875, + 'left_pupil_posn': array([ 0.62419176, -0.18759716]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92004395, 0.38946533, 0.04249573]), + 'right_gaze_origin': array([-3.16350579, -3.14098811, -0.11594238]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5783538818359375, + 'right_pupil_posn': array([ 0.10709667, -0.25917268]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03327127918601036, + 'throttle_input': 0.0, + 'timestamp': 832.7838518768549, + 'timestamp_carla': 832786, + 'timestamp_device': 3986215, + 'timestamp_stream': 832.7838518768549, + 'transform': [array([3.89580989, 9.45447159, 0.01025284]), + array([-5.60143776e-02, -1.20968008e+01, 8.97783507e-03])]} +{'AngularVelocity': array([3.58776713e-04, 2.00214286e-04, 8.01172209e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02932608686387539, + 'FR_Wheel_Angle': 0.0293508879840374, + 'Location': array([ -6.55906248, -21.22511864, 0.1764684 ]), + 'Rotation': array([-0.07089053, 0.37407956, 0.00960581]), + 'Velocity': array([ 0.29658225, 0.00180562, -0.00047087]), + 'brake_input': 0.0, + 'camera_location': array([-6.19005775, 15.84838486, -0.12683204]), + 'camera_rotation': array([-5.28068542, 1.58710122, -1.8318615 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3948.754638671875, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 1137.5480957 , -5564.07177734, 15.83885193]), + 'frame': 25692, + 'frame_number': 25692, + 'framesequence': 98820, + 'gaze_dir': array([0.92531586, 0.37593079, 0.04800415]), + 'gaze_origin': array([-3.0041368 , -0.29340744, -0.13259278]), + 'gaze_valid': True, + 'gaze_vergence': 83.73847961425781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92755127, 0.3717804 , 0.03742981]), + 'left_gaze_origin': array([-2.84950113, 2.54760432, -0.1532547 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.07403564453125, + 'left_pupil_posn': array([ 0.60693574, -0.1767844 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92308044, 0.38008118, 0.05857849]), + 'right_gaze_origin': array([-3.15877247, -3.13441944, -0.11193085]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.549713134765625, + 'right_pupil_posn': array([ 0.09395146, -0.25449049]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03506577014923096, + 'throttle_input': 0.0, + 'timestamp': 832.8172284774482, + 'timestamp_carla': 832819, + 'timestamp_device': 3986248, + 'timestamp_stream': 832.8172284774482, + 'transform': [array([3.86008263, 9.37061214, 0.01073273]), + array([-5.61441518e-02, -1.20280132e+01, 8.10157228e-03])]} +{'AngularVelocity': array([ 0.00025023, -0.01258752, 0.00156513]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.029420802369713783, + 'FR_Wheel_Angle': 0.029438147321343422, + 'Location': array([ -6.51418304, -21.22483635, 0.17641069]), + 'Rotation': array([-0.07696257, 0.37448487, 0.0095644 ]), + 'Velocity': array([ 0.1230871 , 0.00081218, -0.00100424]), + 'brake_input': 0.0, + 'camera_location': array([-6.21165276, 16.1063633 , -0.13202113]), + 'camera_rotation': array([-5.33485556, 3.13139343, -1.60425723]), + 'current_gear_input': False, + 'focus_actor_dist': 3698.824462890625, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1071.05603027, -5331.49023438, 38.688797 ]), + 'frame': 25693, + 'frame_number': 25693, + 'framesequence': 98824, + 'gaze_dir': array([0.93490601, 0.35006714, 0.05797577]), + 'gaze_origin': array([-2.99909234, -0.28159028, -0.12946092]), + 'gaze_valid': True, + 'gaze_vergence': 564.4197387695312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93330383, 0.35421753, 0.0587616 ]), + 'left_gaze_origin': array([-2.84291553, 2.55951405, -0.15186921]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9250640869140625, + 'left_pupil_posn': array([ 0.58451831, -0.17324626]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93650818, 0.34591675, 0.05718994]), + 'right_gaze_origin': array([-3.15526915, -3.12269449, -0.10705262]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.712371826171875, + 'right_pupil_posn': array([ 0.07936239, -0.24236131]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03643910214304924, + 'throttle_input': 0.0, + 'timestamp': 832.8502970784903, + 'timestamp_carla': 832852, + 'timestamp_device': 3986282, + 'timestamp_stream': 832.8502970784903, + 'transform': [array([3.82385826, 9.28896713, 0.01110903]), + array([-5.63695468e-02, -1.19577932e+01, 7.43012130e-03])]} +{'AngularVelocity': array([ 0.00106504, 0.12037514, -0.45819074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03060832805931568, + 'FR_Wheel_Angle': 0.030497072264552116, + 'Location': array([ -6.50313568, -21.22470474, 0.1764787 ]), + 'Rotation': array([-0.07845838, 0.36537167, 0.00955153]), + 'Velocity': array([-0.10165577, -0.00010542, 0.00036453]), + 'brake_input': 0.0, + 'camera_location': array([-6.24064064, 16.39255524, -0.10707869]), + 'camera_rotation': array([-5.29955053, 4.83535004, -1.45669365]), + 'current_gear_input': False, + 'focus_actor_dist': 3688.875, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1068.64855957, -5331.49023438, 60.8761673 ]), + 'frame': 25694, + 'frame_number': 25694, + 'framesequence': 98828, + 'gaze_dir': array([0.94081879, 0.33499146, 0.05056 ]), + 'gaze_origin': array([-2.9933908 , -0.26757202, -0.12854996]), + 'gaze_valid': True, + 'gaze_vergence': 49.539188385009766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94085693, 0.33613586, 0.04229736]), + 'left_gaze_origin': array([-2.83730793, 2.57516193, -0.15167084]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6817626953125, + 'left_pupil_posn': array([ 0.56822765, -0.17087078]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94078064, 0.33384705, 0.05882263]), + 'right_gaze_origin': array([-3.14947367, -3.11030602, -0.10542908]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6131134033203125, + 'right_pupil_posn': array([ 0.06396973, -0.24523592]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03806878998875618, + 'throttle_input': 0.0, + 'timestamp': 832.8838360756636, + 'timestamp_carla': 832886, + 'timestamp_device': 3986315, + 'timestamp_stream': 832.8838360756636, + 'transform': [array([3.78624201, 9.2076149 , 0.01141644]), + array([-5.66222668e-02, -1.18843985e+01, 6.88490970e-03])]} +{'AngularVelocity': array([-0.00086774, -0.02268667, 0.04392201]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.030289873480796814, + 'FR_Wheel_Angle': 0.030252693220973015, + 'Location': array([ -6.62808943, -21.22574234, 0.17670782]), + 'Rotation': array([-0.09560898, 0.38225794, 0.00967045]), + 'Velocity': array([-0.74155706, -0.0048151 , 0.00085665]), + 'brake_input': 0.0, + 'camera_location': array([-6.27104759, 16.70092773, -0.08186152]), + 'camera_rotation': array([-5.13558483, 6.75515747, -1.32133675]), + 'current_gear_input': False, + 'focus_actor_dist': 3340.952392578125, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ 988.69177246, -4996.95654297, 38.92294312]), + 'frame': 25695, + 'frame_number': 25695, + 'framesequence': 98833, + 'gaze_dir': array([0.95638275, 0.28672028, 0.05492401]), + 'gaze_origin': array([-2.98324895, -0.23526002, -0.12683031]), + 'gaze_valid': True, + 'gaze_vergence': 142.34024047851562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95561218, 0.29083252, 0.04684448]), + 'left_gaze_origin': array([-2.8270905 , 2.61081243, -0.15122987]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.826507568359375, + 'left_pupil_posn': array([ 0.52306128, -0.1650697 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95715332, 0.28260803, 0.06300354]), + 'right_gaze_origin': array([-3.13940763, -3.08133245, -0.10243073]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3652496337890625, + 'right_pupil_posn': array([ 0.0281862 , -0.23724461]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.039387188851833344, + 'throttle_input': 0.0, + 'timestamp': 832.9222807772458, + 'timestamp_carla': 832924, + 'timestamp_device': 3986357, + 'timestamp_stream': 832.9222807772458, + 'transform': [array([3.74140191, 9.11629295, 0.01162949]), + array([-5.69569431e-02, -1.17963247e+01, 6.44756667e-03])]} +{'AngularVelocity': array([-0.00053644, -0.02016519, -0.02605115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03134050965309143, + 'FR_Wheel_Angle': 0.03134220838546753, + 'Location': array([ -6.85931158, -21.22721481, 0.1769055 ]), + 'Rotation': array([-0.09255589, 0.37921247, 0.00988911]), + 'Velocity': array([-1.15776145, -0.00747922, 0.00130986]), + 'brake_input': 0.0, + 'camera_location': array([-6.316576 , 17.03003693, -0.08174501]), + 'camera_rotation': array([-5.00915098, 8.86078453, -1.29737377]), + 'current_gear_input': False, + 'focus_actor_dist': 3669.109619140625, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1059.43554688, -5331.49023438, 43.37531281]), + 'frame': 25696, + 'frame_number': 25696, + 'framesequence': 98836, + 'gaze_dir': array([0.96214294, 0.26570129, 0.05872345]), + 'gaze_origin': array([-2.97687864, -0.21177065, -0.12326203]), + 'gaze_valid': True, + 'gaze_vergence': 154.33111572265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.959198 , 0.27813721, 0.05070496]), + 'left_gaze_origin': array([-2.81951308, 2.63501143, -0.14753419]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.884002685546875, + 'left_pupil_posn': array([ 0.49488735, -0.15902233]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96508789, 0.25326538, 0.06674194]), + 'right_gaze_origin': array([-3.13424397, -3.05855274, -0.09898987]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.420989990234375, + 'right_pupil_posn': array([ 0.00793314, -0.23206365]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04063234478235245, + 'throttle_input': 0.0, + 'timestamp': 832.9530755765736, + 'timestamp_carla': 832955, + 'timestamp_device': 3986382, + 'timestamp_stream': 832.9530755765736, + 'transform': [array([3.70617723, 9.04410362, 0.01186693]), + array([-5.76058105e-02, -1.17268372e+01, 6.09777588e-03])]} +{'AngularVelocity': array([ 1.03657789e-04, 1.56977177e-02, -4.01862890e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.96083593, -21.22786331, 0.17657438]), + 'Rotation': array([-0.015928 , 0.37800601, 0.00993814]), + 'Velocity': array([ 4.01694655e-01, 2.47354107e-03, -1.23424528e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.35883331, 17.32189369, -0.07647885]), + 'camera_rotation': array([-4.9038229 , 10.70035267, -1.35466695]), + 'current_gear_input': False, + 'focus_actor_dist': 3681.9833984375, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1120.26025391, -5331.49023438, 60.64624023]), + 'frame': 25697, + 'frame_number': 25697, + 'framesequence': 98841, + 'gaze_dir': array([0.96879578, 0.24237823, 0.04879761]), + 'gaze_origin': array([-2.9687531 , -0.19094621, -0.12145386]), + 'gaze_valid': True, + 'gaze_vergence': 87.30159759521484, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96730042, 0.25128174, 0.0342865 ]), + 'left_gaze_origin': array([-2.80984354, 2.65795898, -0.14728241]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.826568603515625, + 'left_pupil_posn': array([ 0.47135866, -0.15749788]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97029114, 0.23347473, 0.06330872]), + 'right_gaze_origin': array([-3.1276629 , -3.03985167, -0.09562531]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.478790283203125, + 'right_pupil_posn': array([-0.0147835 , -0.23357284]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.041438035666942596, + 'throttle_input': 0.0, + 'timestamp': 832.9899310767651, + 'timestamp_carla': 832992, + 'timestamp_device': 3986423, + 'timestamp_stream': 832.9899310767651, + 'transform': [array([3.66279602, 8.95934105, 0.01211508]), + array([-5.88147566e-02, -1.16408463e+01, 5.59931947e-03])]} +{'AngularVelocity': array([-0.00518006, 0.70605642, -0.00580527]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612316936254501, + 'FR_Wheel_Angle': 0.046143900603055954, + 'Location': array([ -6.87182474, -21.22731972, 0.17670953]), + 'Rotation': array([-0.05667008, 0.37796566, 0.00987481]), + 'Velocity': array([ 6.39388058e-03, 3.90642890e-05, -1.84073258e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.39556026, 17.58589554, -0.05053158]), + 'camera_rotation': array([-4.73808146, 12.22977257, -1.44997251]), + 'current_gear_input': False, + 'focus_actor_dist': 3913.830322265625, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1242.47106934, -5538.78466797, 20.83414459]), + 'frame': 25698, + 'frame_number': 25698, + 'framesequence': 98845, + 'gaze_dir': array([0.97348022, 0.22367859, 0.04468536]), + 'gaze_origin': array([-2.95758677, -0.16868439, -0.127948 ]), + 'gaze_valid': True, + 'gaze_vergence': 47.02408218383789, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97315979, 0.2283783 , 0.0282135 ]), + 'left_gaze_origin': array([-2.79099441, 2.68293619, -0.1557724 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.835296630859375, + 'left_pupil_posn': array([ 0.44830489, -0.15984821]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97380066, 0.21897888, 0.06115723]), + 'right_gaze_origin': array([-3.12417936, -3.02030492, -0.1001236 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3809356689453125, + 'right_pupil_posn': array([-0.03626662, -0.23718488]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04275643453001976, + 'throttle_input': 0.0, + 'timestamp': 833.0218564793468, + 'timestamp_carla': 833024, + 'timestamp_device': 3986457, + 'timestamp_stream': 833.0218564793468, + 'transform': [array([3.62562561, 8.88696194, 0.01253609]), + array([-5.94499633e-02, -1.15668335e+01, 4.84349951e-03])]} +{'AngularVelocity': array([ 1.51728920e-04, -2.78307442e-02, 9.83809741e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612336680293083, + 'FR_Wheel_Angle': 0.04614397510886192, + 'Location': array([ -6.8719449 , -21.22732162, 0.17683035]), + 'Rotation': array([-0.07550091, 0.37795916, 0.00988323]), + 'Velocity': array([-1.66473110e-05, 6.99392740e-06, 3.31928168e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.41689491, 17.82072067, -0.02713234]), + 'camera_rotation': array([-4.55292177, 13.55853462, -1.50643003]), + 'current_gear_input': False, + 'focus_actor_dist': 3854.359130859375, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 1251.19628906, -5479.66113281, 15.7229538 ]), + 'frame': 25699, + 'frame_number': 25699, + 'framesequence': 98849, + 'gaze_dir': array([0.97675323, 0.20773315, 0.05047607]), + 'gaze_origin': array([-2.92025328, -0.15977022, -0.13464279]), + 'gaze_valid': True, + 'gaze_vergence': 42.81720733642578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97683716, 0.2109375 , 0.03575134]), + 'left_gaze_origin': array([-2.71627831, 2.69174814, -0.17360689]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.91741943359375, + 'left_pupil_posn': array([ 0.43458021, -0.15587902]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97666931, 0.20452881, 0.06520081]), + 'right_gaze_origin': array([-3.124228 , -3.01128864, -0.09567872]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5374908447265625, + 'right_pupil_posn': array([-0.0486967 , -0.23128831]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04383678734302521, + 'throttle_input': 0.0, + 'timestamp': 833.0552824772894, + 'timestamp_carla': 833057, + 'timestamp_device': 3986490, + 'timestamp_stream': 833.0552824772894, + 'transform': [array([3.58607721, 8.81246567, 0.01302794]), + array([-5.99007569e-02, -1.14877377e+01, 3.89937963e-03])]} +{'AngularVelocity': array([ 1.11956997e-05, -6.63566543e-03, -6.87392730e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612337425351143, + 'FR_Wheel_Angle': 0.04614398255944252, + 'Location': array([ -6.87191439, -21.22732162, 0.17674597]), + 'Rotation': array([-0.07125936, 0.377958 , 0.00988626]), + 'Velocity': array([-3.55327484e-06, 7.52274673e-06, -1.02638954e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.459692 , 17.98006821, -0.03713057]), + 'camera_rotation': array([-4.63702869, 14.36778069, -1.37161648]), + 'current_gear_input': False, + 'focus_actor_dist': 3330.426025390625, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ 1067.32910156, -4997.45849609, 59.95437622]), + 'frame': 25700, + 'frame_number': 25700, + 'framesequence': 98853, + 'gaze_dir': array([0.95878601, 0.27926636, 0.05120087]), + 'gaze_origin': array([-2.9689188 , -0.21014786, -0.1275612 ]), + 'gaze_valid': True, + 'gaze_vergence': 214.0340576171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95692444, 0.2868042 , 0.04493713]), + 'left_gaze_origin': array([-2.80390787, 2.63298368, -0.15444337]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8011627197265625, + 'left_pupil_posn': array([ 0.50238109, -0.16418743]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96064758, 0.27172852, 0.0574646 ]), + 'right_gaze_origin': array([-3.13392949, -3.05327916, -0.10067902]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.410888671875, + 'right_pupil_posn': array([ 0.00737131, -0.23541427]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04491714388132095, + 'throttle_input': 0.0, + 'timestamp': 833.0883353762329, + 'timestamp_carla': 833090, + 'timestamp_device': 3986523, + 'timestamp_stream': 833.0883353762329, + 'transform': [array([3.54670858, 8.73997688, 0.01352481]), + array([-6.02490939e-02, -1.14086914e+01, 2.93995277e-03])]} +{'AngularVelocity': array([ 3.11182230e-05, -1.86827383e-03, -1.30382896e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612337797880173, + 'FR_Wheel_Angle': 0.04614398628473282, + 'Location': array([ -6.87190914, -21.22731972, 0.1768128 ]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 1.07895585e-06, 2.70519507e-07, -3.43073589e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.47359276, 18.11315536, -0.02255259]), + 'camera_rotation': array([-4.60957146, 15.02644253, -1.03119397]), + 'current_gear_input': False, + 'focus_actor_dist': 2356.484130859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 861.25543213, -4021.85986328, 86.11045837]), + 'frame': 25701, + 'frame_number': 25701, + 'framesequence': 98857, + 'gaze_dir': array([0.96000671, 0.27416229, 0.05560303]), + 'gaze_origin': array([-2.96755767, -0.21270829, -0.1188553 ]), + 'gaze_valid': True, + 'gaze_vergence': 234.04920959472656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95785522, 0.28271484, 0.05058289]), + 'left_gaze_origin': array([-2.80196381, 2.63081384, -0.14628144]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9334259033203125, + 'left_pupil_posn': array([ 0.50153172, -0.15713108]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9621582 , 0.26560974, 0.06062317]), + 'right_gaze_origin': array([-3.13315129, -3.05623031, -0.09142914]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4580841064453125, + 'right_pupil_posn': array([ 0.00781298, -0.22712553]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.046473585069179535, + 'throttle_input': 0.0, + 'timestamp': 833.1230823770165, + 'timestamp_carla': 833125, + 'timestamp_device': 3986557, + 'timestamp_stream': 833.1230823770165, + 'transform': [array([3.50458527, 8.66511726, 0.01402775]), + array([-6.05359636e-02, -1.13237638e+01, 1.93492253e-03])]} +{'AngularVelocity': array([-2.03026902e-05, -5.59907523e-04, -1.31834468e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015379038639366627, + 'FR_Wheel_Angle': 0.014099550433456898, + 'Location': array([ -6.87190914, -21.22731972, 0.17679265]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 1.93891105e-06, 3.27452426e-07, -5.87005852e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.50059891, 18.24495888, -0.02021655]), + 'camera_rotation': array([-4.63159895, 15.72034931, -0.87290806]), + 'current_gear_input': False, + 'focus_actor_dist': 2348.053955078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 873.34179688, -4013.76660156, 93.32435608]), + 'frame': 25702, + 'frame_number': 25702, + 'framesequence': 98860, + 'gaze_dir': array([0.96360016, 0.26274109, 0.04774475]), + 'gaze_origin': array([-2.96503019, -0.22315218, -0.10247651]), + 'gaze_valid': True, + 'gaze_vergence': 138.7480926513672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96211243, 0.2699585 , 0.03807068]), + 'left_gaze_origin': array([-2.79941726, 2.61990047, -0.12773895]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9518890380859375, + 'left_pupil_posn': array([ 0.50516057, -0.14536679]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96508789, 0.25552368, 0.05741882]), + 'right_gaze_origin': array([-3.13064265, -3.06620502, -0.07721405]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6067047119140625, + 'right_pupil_posn': array([ 0.00993896, -0.22110188]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.048744168132543564, + 'throttle_input': 0.0, + 'timestamp': 833.1538022756577, + 'timestamp_carla': 833156, + 'timestamp_device': 3986582, + 'timestamp_stream': 833.1538022756577, + 'transform': [array([3.46677351, 8.6000452 , 0.01450018]), + array([-6.06315844e-02, -1.12471876e+01, 1.05284341e-03])]} +{'AngularVelocity': array([ 3.81437749e-05, -1.58775612e-04, -1.29811142e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.17679498]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([2.82627525e-06, 3.61492255e-07, 4.86396777e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.45975876, 18.4117775 , 0.03326593]), + 'camera_rotation': array([-4.14042616, 16.38542557, -0.93226194]), + 'current_gear_input': False, + 'focus_actor_dist': 2336.152587890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 871.58068848, -4009.00024414, 71.50964355]), + 'frame': 25703, + 'frame_number': 25703, + 'framesequence': 98864, + 'gaze_dir': array([0.96733093, 0.25114441, 0.03119659]), + 'gaze_origin': array([-2.96502852, -0.22303697, -0.12157898]), + 'gaze_valid': True, + 'gaze_vergence': 98.82777404785156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96588135, 0.25823975, 0.0188446 ]), + 'left_gaze_origin': array([-2.79944468, 2.62120533, -0.14738922]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9372100830078125, + 'left_pupil_posn': array([ 0.50022852, -0.16297579]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96878052, 0.24404907, 0.04354858]), + 'right_gaze_origin': array([-3.13061213, -3.06727934, -0.09576874]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6531829833984375, + 'right_pupil_posn': array([ 0.0061444 , -0.24038553]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.051051363348960876, + 'throttle_input': 0.0, + 'timestamp': 833.1866799779236, + 'timestamp_carla': 833189, + 'timestamp_device': 3986615, + 'timestamp_stream': 833.1866799779236, + 'transform': [array([3.42490339, 8.53172684, 0.01497398]), + array([-6.06179237e-02, -1.11620369e+01, 1.21625701e-04])]} +{'AngularVelocity': array([-6.94851915e-05, -7.06760284e-06, -1.31672850e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.17680192]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 2.25698568e-06, 3.30216722e-07, -1.39906610e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.4462347 , 18.63831711, 0.2350373 ]), + 'camera_rotation': array([-2.77873945, 17.5578537 , -1.00013626]), + 'current_gear_input': False, + 'focus_actor_dist': 2333.213134765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 872.48162842, -4011.89550781, 51.92259216]), + 'frame': 25704, + 'frame_number': 25704, + 'framesequence': 98869, + 'gaze_dir': array([0.97268677, 0.23051453, 0.01805878]), + 'gaze_origin': array([-2.96019769, -0.20297624, -0.13922654]), + 'gaze_valid': True, + 'gaze_vergence': 87.13217163085938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97009277, 0.24266052, 0.00248718]), + 'left_gaze_origin': array([-2.79162908, 2.644696 , -0.16633913]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.884368896484375, + 'left_pupil_posn': array([ 0.4744873 , -0.17673802]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97528076, 0.21836853, 0.03363037]), + 'right_gaze_origin': array([-3.12876582, -3.05064869, -0.11211396]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6192474365234375, + 'right_pupil_posn': array([-0.01100069, -0.25642896]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.054164253175258636, + 'throttle_input': 0.0, + 'timestamp': 833.222017776221, + 'timestamp_carla': 833224, + 'timestamp_device': 3986657, + 'timestamp_stream': 833.222017776221, + 'transform': [array([3.37804866, 8.45987797, 0.01545459]), + array([-6.04949817e-02, -1.10662994e+01, -8.60645552e-04])]} +{'AngularVelocity': array([-3.57168233e-06, 2.03767577e-05, -1.31562410e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.17679991]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 2.38710072e-06, 3.40485713e-07, -5.03290757e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.49627686, 18.9230175 , 0.35824469]), + 'camera_rotation': array([-2.12246752, 19.27143669, -1.07017744]), + 'current_gear_input': False, + 'focus_actor_dist': 2322.04150390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 869.21569824, -4009.61767578, 74.58502197]), + 'frame': 25705, + 'frame_number': 25705, + 'framesequence': 98873, + 'gaze_dir': array([0.97692108, 0.21253967, 0.01382446]), + 'gaze_origin': array([-2.94365239, -0.18080063, -0.14365083]), + 'gaze_valid': True, + 'gaze_vergence': 95.12055206298828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([9.75387573e-01, 2.20443726e-01, 6.56127930e-04]), + 'left_gaze_origin': array([-2.76285124, 2.66877007, -0.17522736]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.898040771484375, + 'left_pupil_posn': array([ 0.45196056, -0.17899084]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97845459, 0.20463562, 0.0269928 ]), + 'right_gaze_origin': array([-3.12445378, -3.03037119, -0.11207429]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6555938720703125, + 'right_pupil_posn': array([-0.03285211, -0.25556803]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05775322765111923, + 'throttle_input': 0.0, + 'timestamp': 833.2544323764741, + 'timestamp_carla': 833256, + 'timestamp_device': 3986690, + 'timestamp_stream': 833.2544323764741, + 'transform': [array([3.33340406, 8.39533997, 0.01591226]), + array([-6.02832474e-02, -1.09746914e+01, -1.73438946e-03])]} +{'AngularVelocity': array([-1.70690564e-05, 1.37940924e-06, -1.30300268e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.17679392]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([2.63365905e-06, 3.71140771e-07, 1.92065127e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.60134697, 19.16652298, 0.36228985]), + 'camera_rotation': array([-2.10699034, 20.81935501, -1.16745138]), + 'current_gear_input': False, + 'focus_actor_dist': 2331.1796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 900.73718262, -4010.71386719, 90.0093689 ]), + 'frame': 25706, + 'frame_number': 25706, + 'framesequence': 98876, + 'gaze_dir': array([0.98021698, 0.19721222, 0.00684357]), + 'gaze_origin': array([-2.94051671, -0.16079026, -0.14054108]), + 'gaze_valid': True, + 'gaze_vergence': 81.03068542480469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9790802 , 0.20333862, -0.00654602]), + 'left_gaze_origin': array([-2.76049972, 2.68971109, -0.17183991]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9963531494140625, + 'left_pupil_posn': array([ 0.43262088, -0.17840517]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98135376, 0.19108582, 0.02023315]), + 'right_gaze_origin': array([-3.12053394, -3.01129174, -0.10924225]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.647003173828125, + 'right_pupil_posn': array([-0.05200362, -0.2548914 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06115909665822983, + 'throttle_input': 0.0, + 'timestamp': 833.2866935767233, + 'timestamp_carla': 833289, + 'timestamp_device': 3986715, + 'timestamp_stream': 833.2866935767233, + 'transform': [array([3.28708982, 8.33248425, 0.01635311]), + array([-6.00510202e-02, -1.08792591e+01, -2.58206180e-03])]} +{'AngularVelocity': array([-1.59591582e-05, 9.92959954e-08, -1.34712664e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.17678072]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 1.88140200e-06, 2.89670993e-07, -4.36523143e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.68519497, 19.38729477, 0.32800665]), + 'camera_rotation': array([-2.33759785, 22.04518127, -1.12535 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2346.536865234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 934.98693848, -4015.26416016, 73.76115417]), + 'frame': 25707, + 'frame_number': 25707, + 'framesequence': 98880, + 'gaze_dir': array([0.98194122, 0.1873703 , 0.01327515]), + 'gaze_origin': array([-2.90801406, -0.14689636, -0.14634934]), + 'gaze_valid': True, + 'gaze_vergence': 59.08576965332031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98031616, 0.19728088, -0.00634766]), + 'left_gaze_origin': array([-2.69583917, 2.7057054 , -0.18669739]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.94439697265625, + 'left_pupil_posn': array([ 0.41498363, -0.17109799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98356628, 0.17745972, 0.03289795]), + 'right_gaze_origin': array([-3.12018895, -2.99949813, -0.10600129]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.599609375, + 'right_pupil_posn': array([-0.06212646, -0.25224495]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06461989134550095, + 'throttle_input': 0.0, + 'timestamp': 833.3198677785695, + 'timestamp_carla': 833322, + 'timestamp_device': 3986748, + 'timestamp_stream': 833.3198677785695, + 'transform': [array([3.23754764, 8.26923084, 0.01678239]), + array([-5.98256253e-02, -1.07768106e+01, -3.42653971e-03])]} +{'AngularVelocity': array([ 5.42975977e-06, -2.55349119e-06, -1.33816920e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.176789 ]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 2.06631603e-06, 2.99033701e-07, -2.90146010e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.76116753, 19.57452965, 0.26065692]), + 'camera_rotation': array([-2.54278374, 22.88918686, -1.04582536]), + 'current_gear_input': False, + 'focus_actor_dist': 2375.2734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 976.38635254, -4031.13769531, 77.86597443]), + 'frame': 25708, + 'frame_number': 25708, + 'framesequence': 98884, + 'gaze_dir': array([0.98573303, 0.16709137, 0.00857544]), + 'gaze_origin': array([-2.96215987, -0.13995056, -0.12702179]), + 'gaze_valid': True, + 'gaze_vergence': 64.09689331054688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98469543, 0.17405701, -0.00773621]), + 'left_gaze_origin': array([-2.76686096, 2.71272755, -0.16187592]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.958038330078125, + 'left_pupil_posn': array([ 0.40623081, -0.17068553]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98677063, 0.16012573, 0.02488708]), + 'right_gaze_origin': array([-3.15745878, -2.99262881, -0.09216767]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6570587158203125, + 'right_pupil_posn': array([-0.07464129, -0.25020623]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06784264743328094, + 'throttle_input': 0.0, + 'timestamp': 833.3532873764634, + 'timestamp_carla': 833355, + 'timestamp_device': 3986782, + 'timestamp_stream': 833.3532873764634, + 'transform': [array([3.18591475, 8.20685673, 0.01720259]), + array([-5.96958511e-02, -1.06696978e+01, -4.25597792e-03])]} +{'AngularVelocity': array([-2.06645909e-05, 3.81745340e-05, -1.34049724e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.17679204]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 1.95674602e-06, 2.90072620e-07, -4.19778342e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.81612015, 19.72415543, 0.21092378]), + 'camera_rotation': array([-2.75167823, 23.47865105, -0.74382329]), + 'current_gear_input': False, + 'focus_actor_dist': 2678.8232421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST11', + 'focus_actor_pt': array([ 1127.88867188, -4300.93945312, 46.44733429]), + 'frame': 25709, + 'frame_number': 25709, + 'framesequence': 98888, + 'gaze_dir': array([0.98623657, 0.16408539, 0.01122284]), + 'gaze_origin': array([-2.97720885, -0.1307335 , -0.11914749]), + 'gaze_valid': True, + 'gaze_vergence': 41.5964241027832, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98580933, 0.16777039, -0.00460815]), + 'left_gaze_origin': array([-2.78483748, 2.72338104, -0.15505677]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9297943115234375, + 'left_pupil_posn': array([ 0.3996892 , -0.16876376]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98666382, 0.16040039, 0.02705383]), + 'right_gaze_origin': array([-3.16958022, -2.98484826, -0.08323822]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6385650634765625, + 'right_pupil_posn': array([-0.08197898, -0.24515796]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07106540352106094, + 'throttle_input': 0.0, + 'timestamp': 833.386533677578, + 'timestamp_carla': 833389, + 'timestamp_device': 3986815, + 'timestamp_stream': 833.386533677578, + 'transform': [array([3.13301873, 8.14609241, 0.01760321]), + array([-5.96275479e-02, -1.05595875e+01, -5.04250266e-03])]} +{'AngularVelocity': array([-2.35722791e-06, -1.94386689e-06, -1.33663198e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.87190819, -21.22731972, 0.17678659]), + 'Rotation': array([-0.07070611, 0.37795752, 0.00988583]), + 'Velocity': array([ 2.11644920e-06, 3.09164164e-07, -2.40535912e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.84101677, 19.84440613, 0.17491305]), + 'camera_rotation': array([-3.0266273 , 23.81770706, -0.39016539]), + 'current_gear_input': False, + 'focus_actor_dist': 2552.69287109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 1081.57641602, -4188.53027344, 45.70487213]), + 'frame': 25710, + 'frame_number': 25710, + 'framesequence': 98893, + 'gaze_dir': array([0.98635101, 0.16346741, 0.01844788]), + 'gaze_origin': array([-2.98092508, -0.13048325, -0.11705171]), + 'gaze_valid': True, + 'gaze_vergence': 342.35406494140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98577881, 0.1673584 , 0.01431274]), + 'left_gaze_origin': array([-2.78598189, 2.7240603 , -0.15309602]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9384613037109375, + 'left_pupil_posn': array([ 0.39898264, -0.16922879]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98692322, 0.15957642, 0.02258301]), + 'right_gaze_origin': array([-3.17586851, -2.9850266 , -0.08100738]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6281585693359375, + 'right_pupil_posn': array([-0.08177012, -0.23810089]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07423322647809982, + 'throttle_input': 0.0, + 'timestamp': 833.4208243787289, + 'timestamp_carla': 833423, + 'timestamp_device': 3986857, + 'timestamp_stream': 833.4208243787289, + 'transform': [array([3.07685137, 8.08471394, 0.01799051]), + array([-5.96138872e-02, -1.04423628e+01, -5.81843825e-03])]} diff --git a/PythonAPI/data/trials/trial4.txt b/PythonAPI/data/trials/trial4.txt new file mode 100644 index 0000000..66eb930 --- /dev/null +++ b/PythonAPI/data/trials/trial4.txt @@ -0,0 +1,9118 @@ +{'AngularVelocity': array([-2.29032030e-05, -4.61775089e-05, -7.55744531e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.59471703, -13.76090431, 0.17028177]), + 'Rotation': array([ 2.29494344e-03, -8.80530014e+01, 6.61301762e-02]), + 'Velocity': array([ 4.85134296e-06, 7.43076669e-07, -4.37985436e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.86137104e+00, 1.59521036e+01, 1.44846914e-02]), + 'camera_rotation': array([-5.84612942, 3.59101868, 0.21015102]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ -286.20639038, -1382.10168457, 134.33232117]), + 'frame': 28202, + 'frame_number': 28202, + 'framesequence': 108438, + 'gaze_dir': array([ 0.98894501, -0.0998764 , 0.10599518]), + 'gaze_origin': array([-2.97124791, 0.08660813, -0.0895218 ]), + 'gaze_valid': True, + 'gaze_vergence': 57.84949493408203, + 'handbrake_input': False, + 'left_eye_openness': 0.707149088382721, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98799133, -0.08494568, 0.12896729]), + 'left_gaze_origin': array([-2.88298965, 2.95701313, -0.05813599]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7607574462890625, + 'left_pupil_posn': array([ 0.14944279, -0.10131013]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8082725405693054, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98989868, -0.11480713, 0.08302307]), + 'right_gaze_origin': array([-3.05950642, -2.78379679, -0.1209076 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9612884521484375, + 'right_pupil_posn': array([-0.30743575, -0.20007038]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005310220876708627, + 'throttle_input': 0.0, + 'timestamp': 912.9519756771624, + 'timestamp_carla': 912952, + 'timestamp_device': 4066381, + 'timestamp_stream': 912.9519756771624, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.06763829e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 2.04685621e-05, -4.72394640e-05, -7.58924216e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.59471703, -13.76090431, 0.17029279]), + 'Rotation': array([ 2.29494344e-03, -8.80530014e+01, 6.61301762e-02]), + 'Velocity': array([ 5.27867087e-06, 8.46593139e-07, -6.72302704e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.84212875e+00, 1.58319120e+01, 5.84604684e-03]), + 'camera_rotation': array([-5.82974386, 2.85676098, 0.1452076 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.386474609375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -298.25759888, -5331.49023438, 154.67230225]), + 'frame': 28203, + 'frame_number': 28203, + 'framesequence': 108442, + 'gaze_dir': array([ 0.99097443, -0.07606506, 0.10735321]), + 'gaze_origin': array([-3.03493977, 0.08020478, -0.07554322]), + 'gaze_valid': True, + 'gaze_vergence': 44.412288665771484, + 'handbrake_input': False, + 'left_eye_openness': 0.8104293942451477, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98916626, -0.06636047, 0.13090515]), + 'left_gaze_origin': array([-3.01093936, 2.95168304, -0.02671204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.801513671875, + 'left_pupil_posn': array([ 0.16432047, -0.10458159]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9492264986038208, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99278259, -0.08576965, 0.08380127]), + 'right_gaze_origin': array([-3.05894041, -2.79127359, -0.12437439]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.93060302734375, + 'right_pupil_posn': array([-0.29581505, -0.20182693]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005310220876708627, + 'throttle_input': 0.0, + 'timestamp': 912.983920276165, + 'timestamp_carla': 912984, + 'timestamp_device': 4066414, + 'timestamp_stream': 912.983920276165, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08110428e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 2.58396194e-05, -4.61905365e-05, -7.77769856e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.59471703, -13.76090431, 0.17025934]), + 'Rotation': array([ 2.29494344e-03, -8.80530014e+01, 6.61301762e-02]), + 'Velocity': array([5.84864983e-06, 9.97206598e-07, 4.98405076e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.81786442e+00, 1.57085285e+01, -9.80690587e-04]), + 'camera_rotation': array([-5.82425213, 2.12116289, 0.01275306]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.56201171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -254.9619751 , -5331.49023438, 159.59796143]), + 'frame': 28204, + 'frame_number': 28204, + 'framesequence': 108446, + 'gaze_dir': array([ 0.99181366, -0.06664276, 0.10630035]), + 'gaze_origin': array([-3.04325104, 0.06832352, -0.07858735]), + 'gaze_valid': True, + 'gaze_vergence': 49.83198928833008, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99012756, -0.05732727, 0.12782288]), + 'left_gaze_origin': array([-3.00444961, 2.93952799, -0.03784943]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7044525146484375, + 'left_pupil_posn': array([ 0.17580259, -0.11015165]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99349976, -0.07595825, 0.08477783]), + 'right_gaze_origin': array([-3.08205271, -2.802881 , -0.11932527]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.951446533203125, + 'right_pupil_posn': array([-0.28487867, -0.20392025]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005310220876708627, + 'throttle_input': 0.0, + 'timestamp': 913.0186668783426, + 'timestamp_carla': 913019, + 'timestamp_device': 4066448, + 'timestamp_stream': 913.0186668783426, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.06798148e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 2.48021915e-05, -4.70746927e-05, -7.59023260e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.59471703, -13.76090431, 0.1702971 ]), + 'Rotation': array([ 2.29494344e-03, -8.80530014e+01, 6.61301762e-02]), + 'Velocity': array([ 5.38914446e-06, 8.60933199e-07, -1.52075627e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.80111790e+00, 1.55759840e+01, 5.89903444e-04]), + 'camera_rotation': array([-5.80033302, 1.38022816, -0.05135344]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.42724609375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -269.4180603 , -5331.49023438, 154.81022644]), + 'frame': 28205, + 'frame_number': 28205, + 'framesequence': 108450, + 'gaze_dir': array([ 0.99230957, -0.06099701, 0.10619354]), + 'gaze_origin': array([-3.02070713, 0.06078568, -0.08736268]), + 'gaze_valid': True, + 'gaze_vergence': 105.42082214355469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99156189, -0.04953003, 0.11973572]), + 'left_gaze_origin': array([-2.94534922, 2.9311142 , -0.05767365]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.960968017578125, + 'left_pupil_posn': array([ 0.18212521, -0.10970032]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99305725, -0.07246399, 0.09265137]), + 'right_gaze_origin': array([-3.09606504, -2.80954289, -0.11705171]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.93255615234375, + 'right_pupil_posn': array([-0.27776301, -0.20782733]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 913.0509450770915, + 'timestamp_carla': 913051, + 'timestamp_device': 4066481, + 'timestamp_stream': 913.0509450770915, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07923511e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.00829016, -0.00054364, 0.00030192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06404362618923187, + 'FR_Wheel_Angle': 0.06408370286226273, + 'Location': array([ -2.59470725, -13.76086617, 0.17029805]), + 'Rotation': array([ 2.29494344e-03, -8.80530014e+01, 6.61301762e-02]), + 'Velocity': array([ 0.00035389, -0.00402794, 0.00022493]), + 'brake_input': 0.0, + 'camera_location': array([-7.78509140e+00, 1.54438009e+01, 9.70754772e-04]), + 'camera_rotation': array([-5.7647543 , 0.69432724, -0.11353663]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.37158203125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -298.6812439 , -5331.49023438, 155.58343506]), + 'frame': 28206, + 'frame_number': 28206, + 'framesequence': 108454, + 'gaze_dir': array([ 0.9919281 , -0.05906677, 0.11006165]), + 'gaze_origin': array([-2.99388051, 0.04866257, -0.09978256]), + 'gaze_valid': True, + 'gaze_vergence': 119.8836898803711, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99191284, -0.0405426 , 0.12014771]), + 'left_gaze_origin': array([-2.89909363, 2.91605091, -0.0768158 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.84735107421875, + 'left_pupil_posn': array([ 0.19006515, -0.11158419]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99194336, -0.07759094, 0.09997559]), + 'right_gaze_origin': array([-3.08866739, -2.81872559, -0.12274934]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.97509765625, + 'right_pupil_posn': array([-0.26832932, -0.21007371]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 913.0841827765107, + 'timestamp_carla': 913085, + 'timestamp_device': 4066514, + 'timestamp_stream': 913.0841827765107, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07923511e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([0.02809836, 0.00132793, 0.00376577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06391365826129913, + 'FR_Wheel_Angle': 0.06399458646774292, + 'Location': array([ -2.59454727, -13.7642622 , 0.17028372]), + 'Rotation': array([ 4.54207556e-03, -8.80527344e+01, 6.61422312e-02]), + 'Velocity': array([ 0.0014392 , -0.03705034, 0.00018857]), + 'brake_input': 0.0, + 'camera_location': array([-7.77945518e+00, 1.53293915e+01, -1.19331367e-02]), + 'camera_rotation': array([-5.75187969, 0.09834533, -0.20405594]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.78759765625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -338.92132568, -5331.49023438, 173.17663574]), + 'frame': 28207, + 'frame_number': 28207, + 'framesequence': 108458, + 'gaze_dir': array([ 0.99192047, -0.05206299, 0.1131897 ]), + 'gaze_origin': array([-2.9680407 , 0.04059983, -0.11067963]), + 'gaze_valid': True, + 'gaze_vergence': 109.67909240722656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99183655, -0.03100586, 0.12367249]), + 'left_gaze_origin': array([-2.89058566, 2.90866566, -0.08075104]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.85906982421875, + 'left_pupil_posn': array([ 0.19650435, -0.11185396]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99200439, -0.07312012, 0.10270691]), + 'right_gaze_origin': array([-3.04549575, -2.82746601, -0.14060822]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.912384033203125, + 'right_pupil_posn': array([-0.25886732, -0.21285582]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005493331700563431, + 'throttle_input': 0.0, + 'timestamp': 913.1170796789229, + 'timestamp_carla': 913117, + 'timestamp_device': 4066548, + 'timestamp_stream': 913.1170796789229, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08137110e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.03068126, -0.00577441, -0.44423547]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06360998004674911, + 'FR_Wheel_Angle': 0.06362888216972351, + 'Location': array([ -2.59247851, -13.82375813, 0.17022623]), + 'Rotation': array([ 1.56206414e-02, -8.80473938e+01, 6.61815107e-02]), + 'Velocity': array([ 1.42117022e-02, -4.08088982e-01, 2.36415854e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.75314522, 15.22668743, -0.03365919]), + 'camera_rotation': array([-5.79614592, -0.42442173, -0.3453396 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3950.1142578125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -353.11550903, -5331.49023438, 186.085495 ]), + 'frame': 28208, + 'frame_number': 28208, + 'framesequence': 108462, + 'gaze_dir': array([ 0.99150085, -0.04957581, 0.11947632]), + 'gaze_origin': array([-2.94403768, 0.04100494, -0.11238251]), + 'gaze_valid': True, + 'gaze_vergence': 208.65884399414062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9919281 , -0.03613281, 0.12149048]), + 'left_gaze_origin': array([-2.81566644, 2.90615702, -0.10098114]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9822540283203125, + 'left_pupil_posn': array([ 0.20073056, -0.10616767]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99107361, -0.0630188 , 0.11746216]), + 'right_gaze_origin': array([-3.07240915, -2.82414722, -0.12378388]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9462890625, + 'right_pupil_posn': array([-0.26291949, -0.20719206]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0005676443106494844, + 'throttle_input': 0.0, + 'timestamp': 913.1501133777201, + 'timestamp_carla': 913150, + 'timestamp_device': 4066581, + 'timestamp_stream': 913.1501133777201, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08137110e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.01476577, 0.00196998, -0.2492799 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06314928829669952, + 'FR_Wheel_Angle': 0.06315822899341583, + 'Location': array([ -2.58790851, -13.9590683 , 0.17016649]), + 'Rotation': array([ 2.14263014e-02, -8.80186157e+01, 6.60549924e-02]), + 'Velocity': array([ 2.69610062e-02, -7.71602213e-01, -7.53955799e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.7375679 , 15.1316433 , -0.05188171]), + 'camera_rotation': array([-5.83278322, -0.83938062, -0.45322391]), + 'current_gear_input': False, + 'focus_actor_dist': 3950.955322265625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -380.59915161, -5331.49023438, 207.47807312]), + 'frame': 28209, + 'frame_number': 28209, + 'framesequence': 108466, + 'gaze_dir': array([ 0.99190521, -0.04277802, 0.11836243]), + 'gaze_origin': array([-2.96950912, 0.03638001, -0.10466079]), + 'gaze_valid': True, + 'gaze_vergence': 174.13938903808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9921875 , -0.0269928 , 0.12168884]), + 'left_gaze_origin': array([-2.85051131, 2.90318775, -0.08976746]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9976348876953125, + 'left_pupil_posn': array([ 0.20465267, -0.10609019]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99162292, -0.05856323, 0.11503601]), + 'right_gaze_origin': array([-3.08850718, -2.83042765, -0.11955415]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9190216064453125, + 'right_pupil_posn': array([-0.25550997, -0.20736051]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006408886983990669, + 'throttle_input': 0.0, + 'timestamp': 913.183491576463, + 'timestamp_carla': 913184, + 'timestamp_device': 4066614, + 'timestamp_stream': 913.183491576463, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07866282e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.0336997 , 0.00139317, -0.1747344 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.58137512, -14.1493206 , 0.17030272]), + 'Rotation': array([ 1.97870564e-02, -8.80133591e+01, 6.61683828e-02]), + 'Velocity': array([ 3.49679254e-02, -1.01702416e+00, 2.99854262e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.73137665, 15.04071808, -0.05776999]), + 'camera_rotation': array([-5.82074833, -1.18955994, -0.53913957]), + 'current_gear_input': False, + 'focus_actor_dist': 3950.896728515625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -383.2623291 , -5331.49072266, 200.25083923]), + 'frame': 28210, + 'frame_number': 28210, + 'framesequence': 108470, + 'gaze_dir': array([ 0.99123383, -0.04444885, 0.12322998]), + 'gaze_origin': array([-2.93908095, 0.03072586, -0.11678925]), + 'gaze_valid': True, + 'gaze_vergence': 171.50161743164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99189758, -0.02775574, 0.12388611]), + 'left_gaze_origin': array([-2.8060534 , 2.89725351, -0.10728455]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.016357421875, + 'left_pupil_posn': array([ 0.20724499, -0.10708404]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99057007, -0.06114197, 0.12257385]), + 'right_gaze_origin': array([-3.07210851, -2.83580184, -0.12629396]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.768341064453125, + 'right_pupil_posn': array([-0.25206065, -0.20826054]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006591998389922082, + 'throttle_input': 0.0, + 'timestamp': 913.2169691771269, + 'timestamp_carla': 913217, + 'timestamp_device': 4066648, + 'timestamp_stream': 913.2169691771269, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07629772e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.06682293, 0.01143223, -1.2628665 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5836001634597778, + 'FR_Wheel_Angle': -0.599290132522583, + 'Location': array([ -2.57267714, -14.40677452, 0.17045507]), + 'Rotation': array([ 3.89320753e-03, -8.80290451e+01, 6.68375045e-02]), + 'Velocity': array([ 2.63279602e-02, -9.15629327e-01, 1.02357859e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.73026371, 14.97641373, -0.06731996]), + 'camera_rotation': array([-5.8273325 , -1.42718565, -0.59830326]), + 'current_gear_input': False, + 'focus_actor_dist': 5728.2978515625, + 'focus_actor_name': 'SM_Shop_22', + 'focus_actor_pt': array([ -472.49853516, -7106.29541016, 258.86483765]), + 'frame': 28211, + 'frame_number': 28211, + 'framesequence': 108474, + 'gaze_dir': array([ 0.99168396, -0.04350281, 0.11928558]), + 'gaze_origin': array([-2.97159886, 0.02752228, -0.1046814 ]), + 'gaze_valid': True, + 'gaze_vergence': 137.54884338378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99279785, -0.02282715, 0.11758423]), + 'left_gaze_origin': array([-2.83223271, 2.89260578, -0.09866791]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9771270751953125, + 'left_pupil_posn': array([ 0.20961523, -0.10676944]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99057007, -0.06417847, 0.12098694]), + 'right_gaze_origin': array([-3.11096525, -2.83756137, -0.11069489]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.85791015625, + 'right_pupil_posn': array([-0.24924123, -0.20717359]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006591998389922082, + 'throttle_input': 0.0, + 'timestamp': 913.2505578771234, + 'timestamp_carla': 913251, + 'timestamp_device': 4066681, + 'timestamp_stream': 913.2505578771234, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07412308e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.07143828, -0.00459616, -0.78168648]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6587553024291992, + 'FR_Wheel_Angle': -0.6540096402168274, + 'Location': array([ -2.56633162, -14.62593079, 0.17050195]), + 'Rotation': array([ 9.46664158e-03, -8.80755615e+01, 6.67720288e-02]), + 'Velocity': array([ 2.92968079e-02, -1.07687831e+00, 6.28538139e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.71621799, 14.92972469, -0.08357926]), + 'camera_rotation': array([-5.82214165, -1.58242834, -0.65235168]), + 'current_gear_input': False, + 'focus_actor_dist': 5878.583984375, + 'focus_actor_name': 'SM_Shop_22', + 'focus_actor_pt': array([ -496.76293945, -7256.25732422, 237.93974304]), + 'frame': 28212, + 'frame_number': 28212, + 'framesequence': 108478, + 'gaze_dir': array([ 0.99182129, -0.03800201, 0.12024689]), + 'gaze_origin': array([-2.97145247, 0.02671204, -0.104982 ]), + 'gaze_valid': True, + 'gaze_vergence': 150.13584899902344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99284363, -0.01927185, 0.11772156]), + 'left_gaze_origin': array([-2.82762003, 2.89149189, -0.10040741]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9722747802734375, + 'left_pupil_posn': array([ 0.21282947, -0.10637116]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99079895, -0.05673218, 0.12277222]), + 'right_gaze_origin': array([-3.11528492, -2.83806777, -0.10955659]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8513946533203125, + 'right_pupil_posn': array([-0.24766111, -0.20717359]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006591998389922082, + 'throttle_input': 0.0, + 'timestamp': 913.2830673791468, + 'timestamp_carla': 913283, + 'timestamp_device': 4066714, + 'timestamp_stream': 913.2830673791468, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08076062e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-5.32325804e-02, 8.35409955e-05, -1.16632020e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6540389060974121, + 'FR_Wheel_Angle': -0.6490862369537354, + 'Location': array([ -2.5581131 , -14.92175102, 0.17049852]), + 'Rotation': array([ 2.16175467e-02, -8.81563034e+01, 6.68349192e-02]), + 'Velocity': array([ 3.77191380e-02, -1.47436368e+00, 3.00121290e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.69331169, 14.88141823, -0.09642281]), + 'camera_rotation': array([-5.79249191, -1.68229759, -0.73271525]), + 'current_gear_input': False, + 'focus_actor_dist': 5878.14013671875, + 'focus_actor_name': 'SM_Shop_22', + 'focus_actor_pt': array([ -481.06109619, -7256.2578125 , 244.08537292]), + 'frame': 28213, + 'frame_number': 28213, + 'framesequence': 108482, + 'gaze_dir': array([ 0.99649811, -0.04195404, 0.0714798 ]), + 'gaze_origin': array([-2.9747653, 0.0352623, -0.1336998]), + 'gaze_valid': True, + 'gaze_vergence': 272.7727966308594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99684143, -0.03160095, 0.07270813]), + 'left_gaze_origin': array([-2.87549448, 2.89584351, -0.11470947]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.97552490234375, + 'left_pupil_posn': array([ 0.21218443, -0.14276648]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99615479, -0.05230713, 0.07025146]), + 'right_gaze_origin': array([-3.07403588, -2.82531905, -0.15269013]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8690185546875, + 'right_pupil_posn': array([-0.26124239, -0.2442416 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006775109213776886, + 'throttle_input': 0.0, + 'timestamp': 913.3174530789256, + 'timestamp_carla': 913318, + 'timestamp_device': 4066748, + 'timestamp_stream': 913.3174530789256, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07046112e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.02543558, 0.0075397 , -1.36471689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.9551933407783508, + 'FR_Wheel_Angle': -1.0055359601974487, + 'Location': array([ -2.54771066, -15.3329401 , 0.17055501]), + 'Rotation': array([ 3.13505679e-02, -8.82583542e+01, 6.77969828e-02]), + 'Velocity': array([ 4.27971929e-02, -2.01656294e+00, 3.90415196e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.67891502, 14.8486042 , -0.10532662]), + 'camera_rotation': array([-5.77341509, -1.75605321, -0.81623918]), + 'current_gear_input': False, + 'focus_actor_dist': 3912.53564453125, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -436.93688965, -5290.28417969, 17.24347687]), + 'frame': 28214, + 'frame_number': 28214, + 'framesequence': 108486, + 'gaze_dir': array([ 0.99349976, -0.08460236, -0.07568359]), + 'gaze_origin': array([-2.99038482, 0.07020264, -0.21880877]), + 'gaze_valid': True, + 'gaze_vergence': 331.67547607421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99267578, -0.09101868, -0.07936096]), + 'left_gaze_origin': array([-2.88875914, 2.9043169 , -0.19166413]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8662109375, + 'left_pupil_posn': array([ 0.19825387, -0.24583209]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99432373, -0.07818604, -0.07200623]), + 'right_gaze_origin': array([-3.09201074, -2.76391149, -0.24595338]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9286346435546875, + 'right_pupil_posn': array([-0.32729739, -0.36621463]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.3540342785418, + 'timestamp_carla': 913354, + 'timestamp_device': 4066781, + 'timestamp_stream': 913.3540342785418, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.04616152e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.00179262, 0.00299938, -1.50445569]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0774015188217163, + 'FR_Wheel_Angle': -1.1364504098892212, + 'Location': array([ -2.53667092, -15.86917782, 0.1707029 ]), + 'Rotation': array([ 3.49500775e-02, -8.84413452e+01, 6.78938255e-02]), + 'Velocity': array([ 4.30076048e-02, -2.56945467e+00, 6.35223347e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.68679142, 14.82899094, -0.12895429]), + 'camera_rotation': array([-5.83604097, -1.84846723, -0.94487756]), + 'current_gear_input': False, + 'focus_actor_dist': 663.0994873046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -340.47424316, -2032.88964844, 17.15661621]), + 'frame': 28215, + 'frame_number': 28215, + 'framesequence': 108490, + 'gaze_dir': array([ 0.99346924, -0.08248901, -0.0783844 ]), + 'gaze_origin': array([-2.98978591, 0.06894226, -0.22128525]), + 'gaze_valid': True, + 'gaze_vergence': 366.5695495605469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99275208, -0.0900116 , -0.07955933]), + 'left_gaze_origin': array([-2.89616704, 2.905159 , -0.19270784]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.790618896484375, + 'left_pupil_posn': array([ 0.19887197, -0.24977601]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9941864 , -0.07496643, -0.07720947]), + 'right_gaze_origin': array([-3.08340478, -2.76727462, -0.2498627 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.857940673828125, + 'right_pupil_posn': array([-0.32451993, -0.36717618]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.3826073780656, + 'timestamp_carla': 913383, + 'timestamp_device': 4066814, + 'timestamp_stream': 913.3826073780656, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.02487568e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.08257377, 0.01000754, -1.57748783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.647924780845642, + 'FR_Wheel_Angle': -1.7367035150527954, + 'Location': array([ -2.52844 , -16.41665649, 0.17093369]), + 'Rotation': array([ 2.86526419e-02, -8.86777878e+01, 6.97134212e-02]), + 'Velocity': array([ 2.34467890e-02, -2.84686232e+00, 1.10895152e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.70364094, 14.7969265 , -0.15964556]), + 'camera_rotation': array([-6.03938961, -1.98685706, -0.92863292]), + 'current_gear_input': False, + 'focus_actor_dist': 648.615966796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -338.84313965, -2018.25256348, 17.1498642 ]), + 'frame': 28216, + 'frame_number': 28216, + 'framesequence': 108494, + 'gaze_dir': array([ 0.99391174, -0.0816803 , -0.07299805]), + 'gaze_origin': array([-2.9947443 , 0.06525727, -0.21589662]), + 'gaze_valid': True, + 'gaze_vergence': 256.91497802734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99290466, -0.09239197, -0.07479858]), + 'left_gaze_origin': array([-2.85693359, 2.90453815, -0.20475465]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8905792236328125, + 'left_pupil_posn': array([ 0.20018637, -0.24794507]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99491882, -0.07096863, -0.07119751]), + 'right_gaze_origin': array([-3.13255501, -2.77402353, -0.22703859]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8890380859375, + 'right_pupil_posn': array([-0.32099122, -0.35991848]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.4166138768196, + 'timestamp_carla': 913417, + 'timestamp_device': 4066848, + 'timestamp_stream': 913.4166138768196, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.04520785e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.07242552, 0.0048504 , -2.21578741]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.5662479400634766, + 'FR_Wheel_Angle': -2.59633469581604, + 'Location': array([ -2.52558565, -17.06580925, 0.17129083]), + 'Rotation': array([ 5.96275460e-03, -8.90995483e+01, 7.15453178e-02]), + 'Velocity': array([-2.01475807e-02, -2.66787720e+00, 1.09291077e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.74184418, 14.77262115, -0.20164904]), + 'camera_rotation': array([-6.21198177, -2.16140628, -0.95141661]), + 'current_gear_input': False, + 'focus_actor_dist': 655.278564453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -340.49749756, -2024.89819336, 17.15381622]), + 'frame': 28217, + 'frame_number': 28217, + 'framesequence': 108498, + 'gaze_dir': array([ 0.99394989, -0.08138275, -0.0728302 ]), + 'gaze_origin': array([-2.97980046, 0.0634224 , -0.22448197]), + 'gaze_valid': True, + 'gaze_vergence': 234.43690490722656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99279785, -0.09118652, -0.07756042]), + 'left_gaze_origin': array([-2.86101079, 2.90540028, -0.2062439 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8783416748046875, + 'left_pupil_posn': array([ 0.19944656, -0.24867177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99510193, -0.07157898, -0.06809998]), + 'right_gaze_origin': array([-3.09859037, -2.77855539, -0.24272004]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.96807861328125, + 'right_pupil_posn': array([-0.31720412, -0.36486065]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.4500524774194, + 'timestamp_carla': 913450, + 'timestamp_device': 4066881, + 'timestamp_stream': 913.4500524774194, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.06199261e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.01614071, -0.00451205, -2.51965761]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.218280553817749, + 'FR_Wheel_Angle': -3.202688217163086, + 'Location': array([ -2.53179049, -17.65851784, 0.17156278]), + 'Rotation': array([-3.23750940e-03, -8.96415405e+01, 7.11343512e-02]), + 'Velocity': array([-5.68049736e-02, -2.42175937e+00, 8.37268832e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.76000881, 14.74851894, -0.21226574]), + 'camera_rotation': array([-6.13732767, -2.31795764, -0.95374888]), + 'current_gear_input': False, + 'focus_actor_dist': 644.8873291015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -341.38793945, -2014.20800781, 17.15097046]), + 'frame': 28218, + 'frame_number': 28218, + 'framesequence': 108502, + 'gaze_dir': array([ 0.99452972, -0.07697296, -0.07003784]), + 'gaze_origin': array([-2.98175001, 0.06056137, -0.22058412]), + 'gaze_valid': True, + 'gaze_vergence': 314.9449768066406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99372864, -0.08392334, -0.07382202]), + 'left_gaze_origin': array([-2.85209203, 2.90596175, -0.20766144]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8858642578125, + 'left_pupil_posn': array([ 0.19948602, -0.24720001]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99533081, -0.07002258, -0.06625366]), + 'right_gaze_origin': array([-3.11140752, -2.78483915, -0.23350678]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8808746337890625, + 'right_pupil_posn': array([-0.31026167, -0.35945714]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.4836726784706, + 'timestamp_carla': 913484, + 'timestamp_device': 4066914, + 'timestamp_stream': 913.4836726784706, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07065205e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-2.35927990e-03, -7.38143828e-03, -2.48921132e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.685110092163086, + 'FR_Wheel_Angle': -3.592428207397461, + 'Location': array([ -2.54794312, -18.2681694 , 0.1717906 ]), + 'Rotation': array([-4.24154708e-03, -9.03300476e+01, 6.99893683e-02]), + 'Velocity': array([-8.96234885e-02, -2.16421556e+00, 1.25111581e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.77526379, 14.72371292, -0.20474066]), + 'camera_rotation': array([-6.17778301, -2.4405911 , -0.85414022]), + 'current_gear_input': False, + 'focus_actor_dist': 659.6094360351562, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -341.53106689, -2029.19921875, 17.15639496]), + 'frame': 28219, + 'frame_number': 28219, + 'framesequence': 108506, + 'gaze_dir': array([ 0.99628448, -0.07987976, -0.03170013]), + 'gaze_origin': array([-3.00629902, 0.05982895, -0.19256669]), + 'gaze_valid': True, + 'gaze_vergence': 662.9121704101562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9961853 , -0.08195496, -0.02957153]), + 'left_gaze_origin': array([-2.87357497, 2.90435648, -0.17918244]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8460540771484375, + 'left_pupil_posn': array([ 0.19816446, -0.22144389]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99638367, -0.07780457, -0.03382874]), + 'right_gaze_origin': array([-3.13902307, -2.78469872, -0.20595093]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.90777587890625, + 'right_pupil_posn': array([-0.30918241, -0.33026075]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.5160689763725, + 'timestamp_carla': 913516, + 'timestamp_device': 4066948, + 'timestamp_stream': 913.5160689763725, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08415576e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.0058975 , -0.01069075, -2.3730104 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6114776134490967, + 'FR_Wheel_Angle': -3.2794692516326904, + 'Location': array([ -2.56421423, -18.67962074, 0.17197156]), + 'Rotation': array([-3.38777364e-03, -9.08350220e+01, 6.83223531e-02]), + 'Velocity': array([-1.01324335e-01, -1.98866820e+00, 1.03489391e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.76675224, 14.70458508, -0.17813647]), + 'camera_rotation': array([-6.01628971, -2.52068877, -0.86935657]), + 'current_gear_input': False, + 'focus_actor_dist': 835.9674682617188, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -360.84439087, -2206.73901367, 17.17681122]), + 'frame': 28220, + 'frame_number': 28220, + 'framesequence': 108510, + 'gaze_dir': array([ 0.9977417 , -0.06442261, -0.00380707]), + 'gaze_origin': array([-3.04653096, 0.06319504, -0.15323105]), + 'gaze_valid': True, + 'gaze_vergence': 11.684907913208008, + 'handbrake_input': False, + 'left_eye_openness': 0.9849436283111572, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99771118, -0.06591797, 0.0144043 ]), + 'left_gaze_origin': array([-2.92897344, 2.91011524, -0.13352509]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8949127197265625, + 'left_pupil_posn': array([ 0.19982564, -0.19720054]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9860787987709045, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99777222, -0.06292725, -0.02201843]), + 'right_gaze_origin': array([-3.16408873, -2.78372502, -0.17293702]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9087677001953125, + 'right_pupil_posn': array([-0.30368346, -0.29657197]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.5507696792483, + 'timestamp_carla': 913551, + 'timestamp_device': 4066981, + 'timestamp_stream': 913.5507696792483, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07416127e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.03444433, -0.03134188, 0.26047096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1512605845928192, + 'FR_Wheel_Angle': 0.3470233082771301, + 'Location': array([ -2.581707 , -19.12081528, 0.17212175]), + 'Rotation': array([-2.04905658e-03, -9.12130203e+01, 6.05048016e-02]), + 'Velocity': array([-5.74202091e-02, -1.81096387e+00, 4.09297936e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.75997734, 14.69190502, -0.18619277]), + 'camera_rotation': array([-6.00838041, -2.52995658, -1.05341136]), + 'current_gear_input': False, + 'focus_actor_dist': 1070.6524658203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -366.92132568, -2443.49023438, 17.15068817]), + 'frame': 28221, + 'frame_number': 28221, + 'framesequence': 108514, + 'gaze_dir': array([ 0.99790192, -0.06108856, -0.00613403]), + 'gaze_origin': array([-3.07993937, 0.06556321, -0.14084397]), + 'gaze_valid': True, + 'gaze_vergence': 33.75945281982422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99771118, -0.06610107, 0.01344299]), + 'left_gaze_origin': array([-2.99094415, 2.91998315, -0.11358185]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9003753662109375, + 'left_pupil_posn': array([ 0.19623303, -0.19718325]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99809265, -0.05607605, -0.02571106]), + 'right_gaze_origin': array([-3.16893506, -2.78885651, -0.16810609]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8087615966796875, + 'right_pupil_posn': array([-0.30019957, -0.29448628]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.5827724784613, + 'timestamp_carla': 913583, + 'timestamp_device': 4067014, + 'timestamp_stream': 913.5827724784613, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08804682e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-0.05587264, 0.01641129, 0.01257534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.1291892528533936, + 'FR_Wheel_Angle': 1.3523768186569214, + 'Location': array([ -2.58988953, -19.58590317, 0.17214148]), + 'Rotation': array([ 1.24992458e-02, -9.11390762e+01, 6.04476929e-02]), + 'Velocity': array([-2.25986168e-02, -2.07598472e+00, 4.46648599e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.74533367, 14.67001915, -0.20028722]), + 'camera_rotation': array([-5.9095273 , -2.57292271, -1.08691692]), + 'current_gear_input': False, + 'focus_actor_dist': 1048.2181396484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -361.87765503, -2421.20263672, 17.14698029]), + 'frame': 28222, + 'frame_number': 28222, + 'framesequence': 108518, + 'gaze_dir': array([ 0.99765015, -0.0619812 , 0.00102997]), + 'gaze_origin': array([-3.00047779, 0.06145478, -0.16820908]), + 'gaze_valid': True, + 'gaze_vergence': 20.918487548828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99720764, -0.06867981, 0.02929688]), + 'left_gaze_origin': array([-2.98562956, 2.92022276, -0.11544495]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9153289794921875, + 'left_pupil_posn': array([ 0.19629443, -0.19795072]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99809265, -0.05528259, -0.02723694]), + 'right_gaze_origin': array([-3.01532626, -2.79731297, -0.22097321]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8542327880859375, + 'right_pupil_posn': array([-0.2939927 , -0.29440165]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 913.6165260784328, + 'timestamp_carla': 913617, + 'timestamp_device': 4067048, + 'timestamp_stream': 913.6165260784328, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08297344e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.00824657, -0.01942011, 2.9448266 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.051743507385254, + 'FR_Wheel_Angle': 3.3268134593963623, + 'Location': array([ -2.59190893, -20.13521004, 0.17211798]), + 'Rotation': array([ 1.77994724e-02, -9.07899628e+01, 5.70392124e-02]), + 'Velocity': array([ 3.01387906e-02, -2.49928999e+00, -3.25336441e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.74903774, 14.65424919, -0.10522769]), + 'camera_rotation': array([-5.84194231, -2.658144 , -1.10547507]), + 'current_gear_input': False, + 'focus_actor_dist': 1137.3677978515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -370.27322388, -2510.59277344, 17.14975739]), + 'frame': 28223, + 'frame_number': 28223, + 'framesequence': 108522, + 'gaze_dir': array([ 0.99785614, -0.06030273, -0.0022049 ]), + 'gaze_origin': array([-3.0010438 , 0.06048966, -0.16778946]), + 'gaze_valid': True, + 'gaze_vergence': 19.28813362121582, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99763489, -0.06489563, 0.02220154]), + 'left_gaze_origin': array([-2.98117995, 2.92042398, -0.11705934]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.911651611328125, + 'left_pupil_posn': array([ 0.19595683, -0.19795072]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99807739, -0.05570984, -0.02661133]), + 'right_gaze_origin': array([-3.02090764, -2.79944468, -0.2185196 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9830474853515625, + 'right_pupil_posn': array([-0.29129654, -0.29633641]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0007507553673349321, + 'throttle_input': 0.0, + 'timestamp': 913.6498767770827, + 'timestamp_carla': 913650, + 'timestamp_device': 4067081, + 'timestamp_stream': 913.6498767770827, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08297344e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.02137808, -0.01474827, 4.20553923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.097494125366211, + 'FR_Wheel_Angle': 4.514745235443115, + 'Location': array([ -2.58001184, -20.7829113 , 0.17213403]), + 'Rotation': array([ 1.25812078e-02, -9.00401535e+01, 5.39859273e-02]), + 'Velocity': array([ 1.05497785e-01, -2.91485143e+00, 6.86182932e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.7227869 , 14.6287508 , -0.08378905]), + 'camera_rotation': array([-5.85974169, -2.70078897, -1.08501816]), + 'current_gear_input': False, + 'focus_actor_dist': 1116.03662109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -368.42599487, -2489.21142578, 17.1492691 ]), + 'frame': 28224, + 'frame_number': 28224, + 'framesequence': 108526, + 'gaze_dir': array([ 0.99804688, -0.05847931, -0.00682068]), + 'gaze_origin': array([-3.00417805, 0.05717773, -0.16644059]), + 'gaze_valid': True, + 'gaze_vergence': 4.825500011444092, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99812317, -0.05953979, 0.01367188]), + 'left_gaze_origin': array([-2.97920847, 2.92054152, -0.11752015]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9127960205078125, + 'left_pupil_posn': array([ 0.19526875, -0.19813168]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99797058, -0.05741882, -0.02731323]), + 'right_gaze_origin': array([-3.02914762, -2.8061862 , -0.21536103]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.92620849609375, + 'right_pupil_posn': array([-0.28492308, -0.2988261 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0007690664497204125, + 'throttle_input': 0.0, + 'timestamp': 913.6830814778805, + 'timestamp_carla': 913683, + 'timestamp_device': 4067114, + 'timestamp_stream': 913.6830814778805, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08297344e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 0.09632695, -0.01170093, 6.00566101]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.402884006500244, + 'FR_Wheel_Angle': 5.84285831451416, + 'Location': array([ -2.5487051 , -21.49950409, 0.17222284]), + 'Rotation': array([ 1.71437743e-03, -8.89176941e+01, 4.85448614e-02]), + 'Velocity': array([ 2.20737517e-01, -3.21520352e+00, 2.19769470e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.69402599, 14.60171127, -0.06877623]), + 'camera_rotation': array([-5.85446882, -2.73169398, -1.09471583]), + 'current_gear_input': False, + 'focus_actor_dist': 1066.860107421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -363.62017822, -2439.9921875 , 17.14755249]), + 'frame': 28225, + 'frame_number': 28225, + 'framesequence': 108530, + 'gaze_dir': array([ 0.99794006, -0.05916595, -0.00266266]), + 'gaze_origin': array([-2.99872279, 0.05619125, -0.16874313]), + 'gaze_valid': True, + 'gaze_vergence': 0.4099889099597931, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99798584, -0.05950928, 0.02145386]), + 'left_gaze_origin': array([-2.97812963, 2.92064071, -0.11812287]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.913665771484375, + 'left_pupil_posn': array([ 0.19470549, -0.19813538]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99789429, -0.05882263, -0.02677917]), + 'right_gaze_origin': array([-3.0193162 , -2.80825806, -0.21936342]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9318695068359375, + 'right_pupil_posn': array([-0.28338867, -0.29684412]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0008056886726990342, + 'throttle_input': 0.0, + 'timestamp': 913.71639527753, + 'timestamp_carla': 913717, + 'timestamp_device': 4067148, + 'timestamp_stream': 913.71639527753, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08297344e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([0.09633338, 0.0105547 , 6.76003265]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.264986515045166, + 'FR_Wheel_Angle': 6.800683498382568, + 'Location': array([ -2.48596883, -22.31315804, 0.17235251]), + 'Rotation': array([-2.72797737e-02, -8.72966919e+01, 4.83779125e-02]), + 'Velocity': array([ 3.30478013e-01, -3.05682206e+00, -1.85785291e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.66335869, 14.59120941, -0.07825004]), + 'camera_rotation': array([-5.88930988, -2.74322367, -1.17584229]), + 'current_gear_input': False, + 'focus_actor_dist': 1109.5374755859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -368.14654541, -2482.73803711, 17.14939117]), + 'frame': 28226, + 'frame_number': 28226, + 'framesequence': 108534, + 'gaze_dir': array([ 0.99793243, -0.06054688, 0.00123596]), + 'gaze_origin': array([-2.99085259, 0.05488358, -0.17307587]), + 'gaze_valid': True, + 'gaze_vergence': 5.686735153198242, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99794006, -0.06004333, 0.0222168 ]), + 'left_gaze_origin': array([-2.9756639 , 2.92090917, -0.12248535]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8684234619140625, + 'left_pupil_posn': array([ 0.19370985, -0.19813168]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9979248 , -0.06105042, -0.01974487]), + 'right_gaze_origin': array([-3.00604105, -2.81114197, -0.22366638]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.92266845703125, + 'right_pupil_posn': array([-0.28150743, -0.29693294]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0008789331186562777, + 'throttle_input': 0.0, + 'timestamp': 913.7502845786512, + 'timestamp_carla': 913751, + 'timestamp_device': 4067181, + 'timestamp_stream': 913.7502845786512, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07774733e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([2.00725719e-02, 6.48900121e-03, 6.97107887e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.194915771484375, + 'FR_Wheel_Angle': 7.938363075256348, + 'Location': array([ -2.40851736, -22.9929409 , 0.17226461]), + 'Rotation': array([-3.73543017e-02, -8.57140732e+01, 4.94250692e-02]), + 'Velocity': array([ 4.07246441e-01, -2.77544546e+00, -6.21075626e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.63787365, 14.57925797, -0.10187022]), + 'camera_rotation': array([-5.97452307, -2.71415234, -1.21282232]), + 'current_gear_input': False, + 'focus_actor_dist': 1143.8221435546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -372.54153442, -2517.01855469, 17.15166473]), + 'frame': 28227, + 'frame_number': 28227, + 'framesequence': 108538, + 'gaze_dir': array([0.99638367, 0.00467682, 0.08070374]), + 'gaze_origin': array([-3.00023365e+00, -2.22625746e-03, -1.23559579e-01]), + 'gaze_valid': True, + 'gaze_vergence': 109.8848876953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99595642, 0.03010559, 0.08447266]), + 'left_gaze_origin': array([-2.90300298, 2.85373712, -0.10180664]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9133148193359375, + 'left_pupil_posn': array([ 0.25165498, -0.13695002]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99681091, -0.02075195, 0.07693481]), + 'right_gaze_origin': array([-3.09746408, -2.85818958, -0.1453125 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8759613037109375, + 'right_pupil_posn': array([-0.21715254, -0.23989952]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0008972442010417581, + 'throttle_input': 0.0, + 'timestamp': 913.7838364765048, + 'timestamp_carla': 913784, + 'timestamp_device': 4067214, + 'timestamp_stream': 913.7838364765048, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.07774733e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([3.38658545e-04, 1.41045013e-02, 7.13064718e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.050267219543457, + 'FR_Wheel_Angle': 8.853045463562012, + 'Location': array([ -2.31514645, -23.60811234, 0.17208627]), + 'Rotation': array([-3.94579992e-02, -8.40530548e+01, 5.07548153e-02]), + 'Velocity': array([ 4.66676354e-01, -2.49997807e+00, -7.72743195e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.60740185, 14.5630722 , -0.12364917]), + 'camera_rotation': array([-6.0485692 , -2.73220944, -1.22367549]), + 'current_gear_input': False, + 'focus_actor_dist': 3950.369140625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -328.67242432, -5331.49023438, 42.18208313]), + 'frame': 28228, + 'frame_number': 28228, + 'framesequence': 108542, + 'gaze_dir': array([0.99563599, 0.02190399, 0.08802032]), + 'gaze_origin': array([-3.00948119, -0.02057877, -0.10469666]), + 'gaze_valid': True, + 'gaze_vergence': 126.77549743652344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99572754, 0.04258728, 0.08184814]), + 'left_gaze_origin': array([-2.86419845, 2.83591795, -0.10212708]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9263763427734375, + 'left_pupil_posn': array([ 0.27055895, -0.12436879]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99554443, 0.0012207 , 0.0941925 ]), + 'right_gaze_origin': array([-3.15476394, -2.87707543, -0.10726624]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.783355712890625, + 'right_pupil_posn': array([-0.1995877 , -0.22608113]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.01190203707665205, + 'timestamp': 913.8169757761061, + 'timestamp_carla': 913817, + 'timestamp_device': 4067248, + 'timestamp_stream': 913.8169757761061, + 'transform': [array([1.83809781e+00, 1.49250908e+01, 6.08034106e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([ 2.44101000e-04, -1.24510156e-03, 7.23199701e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.007041931152344, + 'FR_Wheel_Angle': 10.107000350952148, + 'Location': array([ -2.20904279, -24.16955566, 0.17191713]), + 'Rotation': array([-3.94853204e-02, -8.23664322e+01, 5.19833043e-02]), + 'Velocity': array([ 5.12176812e-01, -2.24454498e+00, -5.77778788e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.60153389, 14.56679249, -0.13460092]), + 'camera_rotation': array([-6.08472824, -2.76574707, -1.22284353]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.69921875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -262.5526123 , -5331.48974609, 67.52568054]), + 'frame': 28229, + 'frame_number': 28229, + 'framesequence': 108546, + 'gaze_dir': array([0.9954834 , 0.0230484 , 0.08809662]), + 'gaze_origin': array([-3.02208281, -0.0216362 , -0.09986801]), + 'gaze_valid': True, + 'gaze_vergence': 90.65789031982422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99621582, 0.0456543 , 0.07388306]), + 'left_gaze_origin': array([-2.87905288, 2.83643961, -0.09980012]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9995269775390625, + 'left_pupil_posn': array([ 0.27019131, -0.12265682]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([9.94750977e-01, 4.42504883e-04, 1.02310181e-01]), + 'right_gaze_origin': array([-3.1651125 , -2.8797121 , -0.09993592]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.77032470703125, + 'right_pupil_posn': array([-0.19671541, -0.22601044]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.0634927898645401, + 'timestamp': 913.8510082773864, + 'timestamp_carla': 913851, + 'timestamp_device': 4067281, + 'timestamp_stream': 913.8510082773864, + 'transform': [array([1.83810174e+00, 1.49251156e+01, 6.07500086e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-3.86608212e-04, -1.73886109e-03, 7.68493319e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.73510456085205, + 'FR_Wheel_Angle': 12.244050025939941, + 'Location': array([ -2.1117003 , -24.59295654, 0.1717132 ]), + 'Rotation': array([-3.94579992e-02, -8.08787689e+01, 5.05262315e-02]), + 'Velocity': array([ 5.57867885e-01, -2.04291081e+00, -1.95598604e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.59640598, 14.56313515, -0.13404077]), + 'camera_rotation': array([-6.12596893, -2.75738907, -1.19014525]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.75439453125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -260.33288574, -5331.48974609, 65.47937775]), + 'frame': 28230, + 'frame_number': 28230, + 'framesequence': 108550, + 'gaze_dir': array([0.99488068, 0.0256958 , 0.09494781]), + 'gaze_origin': array([-2.98076487, -0.02113953, -0.11569061]), + 'gaze_valid': True, + 'gaze_vergence': 98.4794921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99577332, 0.04359436, 0.08076477]), + 'left_gaze_origin': array([-2.81091166, 2.83845687, -0.12404329]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0426025390625, + 'left_pupil_posn': array([ 0.27019536, -0.12380719]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99398804, 0.00779724, 0.10913086]), + 'right_gaze_origin': array([-3.15061808, -2.88073587, -0.10733795]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.748870849609375, + 'right_pupil_posn': array([-0.19671541, -0.22574568]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.11506828665733337, + 'timestamp': 913.8833883777261, + 'timestamp_carla': 913884, + 'timestamp_device': 4067314, + 'timestamp_stream': 913.8833883777261, + 'transform': [array([1.83810759e+00, 1.49251289e+01, 6.08392712e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([-2.30602501e-03, 1.31226620e-02, 7.77965784e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.234660148620605, + 'FR_Wheel_Angle': 14.186999320983887, + 'Location': array([ -1.98386467, -25.05490685, 0.17151795]), + 'Rotation': array([-3.94853204e-02, -7.89556885e+01, 5.11574224e-02]), + 'Velocity': array([ 5.97671032e-01, -1.81940603e+00, -1.26215932e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.59483242, 14.57352066, -0.12856619]), + 'camera_rotation': array([-6.09534931, -2.70832109, -1.17414021]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.45068359375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -249.64891052, -5331.49023438, 89.94618225]), + 'frame': 28231, + 'frame_number': 28231, + 'framesequence': 108554, + 'gaze_dir': array([0.99473572, 0.02848816, 0.09524536]), + 'gaze_origin': array([-2.96230483, -0.02061844, -0.12124558]), + 'gaze_valid': True, + 'gaze_vergence': 80.75463104248047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99595642, 0.04518127, 0.07745361]), + 'left_gaze_origin': array([-2.78509068, 2.84029388, -0.13387606]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0269317626953125, + 'left_pupil_posn': array([ 0.26986456, -0.12414706]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99351501, 0.01179504, 0.11303711]), + 'right_gaze_origin': array([-3.13951898, -2.88153076, -0.10861512]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7498321533203125, + 'right_pupil_posn': array([-0.1956256 , -0.22561002]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.15078964829444885, + 'timestamp': 913.9167200773954, + 'timestamp_carla': 913917, + 'timestamp_device': 4067347, + 'timestamp_stream': 913.9167200773954, + 'transform': [array([1.83811462e+00, 1.49251318e+01, 6.08194340e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([2.69421400e-03, 7.60554709e-03, 8.54444218e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.980271339416504, + 'FR_Wheel_Angle': 16.353506088256836, + 'Location': array([ -1.8507055 , -25.45755386, 0.17138578]), + 'Rotation': array([-4.03459258e-02, -7.69819717e+01, 5.13241179e-02]), + 'Velocity': array([ 6.32623971e-01, -1.61413765e+00, -1.83606142e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.5892477 , 14.58326054, -0.10862719]), + 'camera_rotation': array([-6.05160856, -2.63363051, -1.22167087]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.560302734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -235.13540649, -5331.48925781, 93.46349335]), + 'frame': 28232, + 'frame_number': 28232, + 'framesequence': 108558, + 'gaze_dir': array([0.99471283, 0.02886963, 0.09560394]), + 'gaze_origin': array([-2.95797372, -0.02036133, -0.12281419]), + 'gaze_valid': True, + 'gaze_vergence': 83.12490844726562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99591064, 0.04495239, 0.07832336]), + 'left_gaze_origin': array([-2.77888966, 2.84092426, -0.13584596]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.03961181640625, + 'left_pupil_posn': array([ 0.26967227, -0.12434328]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99351501, 0.01278687, 0.11288452]), + 'right_gaze_origin': array([-3.13705754, -2.88164687, -0.10978242]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7498779296875, + 'right_pupil_posn': array([-0.1956256 , -0.22564077]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.1904631108045578, + 'timestamp': 913.9507164768875, + 'timestamp_carla': 913951, + 'timestamp_device': 4067381, + 'timestamp_stream': 913.9507164768875, + 'transform': [array([1.83812284e+00, 1.49250984e+01, 6.07530586e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([7.15420581e-04, 1.17921578e-02, 8.50363350e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.031170845031738, + 'FR_Wheel_Angle': 17.6182918548584, + 'Location': array([ -1.70088804, -25.84260368, 0.17118174]), + 'Rotation': array([-4.15343791e-02, -7.48079605e+01, 5.33978939e-02]), + 'Velocity': array([ 6.45198524e-01, -1.41804659e+00, -1.35560031e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.60048008, 14.60135746, -0.11278677]), + 'camera_rotation': array([-6.01566124, -2.54844522, -1.21705234]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.595947265625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -228.81594849, -5331.48974609, 98.02175903]), + 'frame': 28233, + 'frame_number': 28233, + 'framesequence': 108562, + 'gaze_dir': array([0.99449921, 0.02920532, 0.09783173]), + 'gaze_origin': array([-2.95347071, -0.01973801, -0.12551652]), + 'gaze_valid': True, + 'gaze_vergence': 85.78941345214844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99568176, 0.04495239, 0.08106995]), + 'left_gaze_origin': array([-2.77261972, 2.84217095, -0.13906556]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.040924072265625, + 'left_pupil_posn': array([ 0.26896381, -0.1247586 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99331665, 0.01345825, 0.11459351]), + 'right_gaze_origin': array([-3.13432169, -2.88164687, -0.11196747]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.758270263671875, + 'right_pupil_posn': array([-0.1956256 , -0.22564077]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.22618448734283447, + 'timestamp': 913.9832935780287, + 'timestamp_carla': 913984, + 'timestamp_device': 4067414, + 'timestamp_stream': 913.9832935780287, + 'transform': [array([1.83813322e+00, 1.49249983e+01, 6.08167658e-03]), + array([-0.0647297 , -8.05306911, 0.01374352])]} +{'AngularVelocity': array([1.88228441e-04, 8.93504731e-03, 8.28824425e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.790486335754395, + 'FR_Wheel_Angle': 18.726430892944336, + 'Location': array([ -1.57980347, -26.11842537, 0.17104258]), + 'Rotation': array([-4.21490967e-02, -7.31184235e+01, 5.55008017e-02]), + 'Velocity': array([ 6.40720367e-01, -1.27976418e+00, -7.17992778e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.61425972, 14.61638069, -0.13062167]), + 'camera_rotation': array([-6.06910753, -2.48140144, -1.18072546]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.62451171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -221.74829102, -5331.49023438, 109.33995056]), + 'frame': 28234, + 'frame_number': 28234, + 'framesequence': 108566, + 'gaze_dir': array([0.99481201, 0.02840424, 0.0945282 ]), + 'gaze_origin': array([-2.95042729, -0.01895523, -0.12574692]), + 'gaze_valid': True, + 'gaze_vergence': 78.9012451171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99607849, 0.04449463, 0.0763855 ]), + 'left_gaze_origin': array([-2.76999974, 2.84365702, -0.13952637]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.048553466796875, + 'left_pupil_posn': array([ 0.26753461, -0.12519276]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99354553, 0.01231384, 0.1126709 ]), + 'right_gaze_origin': array([-3.13085508, -2.88156748, -0.11196747]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8249664306640625, + 'right_pupil_posn': array([-0.19588661, -0.22673905]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.24998855590820312, + 'timestamp': 914.016045678407, + 'timestamp_carla': 914016, + 'timestamp_device': 4067447, + 'timestamp_stream': 914.016045678407, + 'transform': [array([1.83815849e+00, 1.49247971e+01, 6.01526257e-03]), + array([-0.06470238, -8.05309296, 0.01387843])]} +{'AngularVelocity': array([-7.92103005e-04, 1.13348076e-02, 7.57534266e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.197080612182617, + 'FR_Wheel_Angle': 19.106815338134766, + 'Location': array([ -1.42990029, -26.42620087, 0.17089342]), + 'Rotation': array([-4.29413952e-02, -7.11014938e+01, 5.73434308e-02]), + 'Velocity': array([ 6.25321269e-01, -1.12632287e+00, -4.55951667e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.61614323, 14.63675499, -0.13584363]), + 'camera_rotation': array([-6.13844109, -2.45254087, -1.13541234]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.80078125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -219.77752686, -5331.48974609, 92.39653015]), + 'frame': 28235, + 'frame_number': 28235, + 'framesequence': 108570, + 'gaze_dir': array([0.99473572, 0.02867889, 0.09562683]), + 'gaze_origin': array([-2.94897008, -0.01798096, -0.12637101]), + 'gaze_valid': True, + 'gaze_vergence': 79.95945739746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99601746, 0.04302979, 0.07795715]), + 'left_gaze_origin': array([-2.76726532, 2.84515238, -0.14058228]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0653076171875, + 'left_pupil_posn': array([ 0.26717877, -0.12520719]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99345398, 0.014328 , 0.11329651]), + 'right_gaze_origin': array([-3.13067484, -2.88111448, -0.11215974]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8354644775390625, + 'right_pupil_posn': array([-0.19670886, -0.22630191]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.2658579349517822, + 'timestamp': 914.0500230789185, + 'timestamp_carla': 914050, + 'timestamp_device': 4067481, + 'timestamp_stream': 914.0500230789185, + 'transform': [array([1.83819306e+00, 1.49244127e+01, 5.89694967e-03]), + array([-0.06466823, -8.05312347, 0.01409434])]} +{'AngularVelocity': array([7.16049050e-04, 5.36158774e-03, 6.89267540e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.22354507446289, + 'FR_Wheel_Angle': 19.140199661254883, + 'Location': array([ -1.29619396, -26.67808342, 0.17073716]), + 'Rotation': array([-4.35834341e-02, -6.93992310e+01, 5.91223016e-02]), + 'Velocity': array([ 5.98227859e-01, -1.00454569e+00, -4.91724000e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.61201668, 14.65770531, -0.13177654]), + 'camera_rotation': array([-6.0965991 , -2.36779475, -1.07456315]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.84521484375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -216.4753418 , -5331.49023438, 91.91194153]), + 'frame': 28236, + 'frame_number': 28236, + 'framesequence': 108574, + 'gaze_dir': array([0.99481964, 0.02812958, 0.09507751]), + 'gaze_origin': array([-2.948066 , -0.01761627, -0.126651 ]), + 'gaze_valid': True, + 'gaze_vergence': 83.49364471435547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99604797, 0.04211426, 0.07810974]), + 'left_gaze_origin': array([-2.76512909, 2.84548187, -0.14089204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.07061767578125, + 'left_pupil_posn': array([ 0.26686335, -0.12544048]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99359131, 0.0141449 , 0.11204529]), + 'right_gaze_origin': array([-3.1310029 , -2.88071442, -0.11240998]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8632049560546875, + 'right_pupil_posn': array([-0.19731498, -0.22653604]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.2737926244735718, + 'timestamp': 914.0836162790656, + 'timestamp_carla': 914084, + 'timestamp_device': 4067514, + 'timestamp_stream': 914.0836162790656, + 'transform': [array([1.83823788e+00, 1.49237118e+01, 5.70268603e-03]), + array([-0.06460676, -8.0531559 , 0.01447127])]} +{'AngularVelocity': array([1.50715373e-03, 2.13468005e-03, 6.28065252e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.23779296875, + 'FR_Wheel_Angle': 19.160541534423828, + 'Location': array([ -1.16936111, -26.90133476, 0.17059679]), + 'Rotation': array([-4.41025272e-02, -6.78651810e+01, 5.96970432e-02]), + 'Velocity': array([ 5.68074405e-01, -8.97487998e-01, -4.96363617e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.61722469, 14.68797302, -0.12172614]), + 'camera_rotation': array([-6.01163149, -2.30484939, -1.04986 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.87353515625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -212.34402466, -5331.49023438, 92.46092224]), + 'frame': 28237, + 'frame_number': 28237, + 'framesequence': 108578, + 'gaze_dir': array([0.99471283, 0.0278244 , 0.09667206]), + 'gaze_origin': array([-2.94811726, -0.01665268, -0.12748031]), + 'gaze_valid': True, + 'gaze_vergence': 88.26195526123047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99591064, 0.04049683, 0.08073425]), + 'left_gaze_origin': array([-2.76384735, 2.84652877, -0.14159547]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0749664306640625, + 'left_pupil_posn': array([ 0.2664845 , -0.12548971]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99351501, 0.01515198, 0.11260986]), + 'right_gaze_origin': array([-3.13238692, -2.87983418, -0.11336518]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8628997802734375, + 'right_pupil_posn': array([-0.19848448, -0.22653604]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.27775996923446655, + 'timestamp': 914.1160684786737, + 'timestamp_carla': 914116, + 'timestamp_device': 4067547, + 'timestamp_stream': 914.1160684786737, + 'transform': [array([1.83812833e+00, 1.49217482e+01, 4.94995108e-03]), + array([-0.06434721, -8.05279636, 0.0159586 ])]} +{'AngularVelocity': array([1.64072611e-03, 1.26786670e-03, 5.77819061e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.26153564453125, + 'FR_Wheel_Angle': 19.191320419311523, + 'Location': array([ -1.06516576, -27.07477951, 0.17047285]), + 'Rotation': array([-4.44645286e-02, -6.66548004e+01, 5.98418191e-02]), + 'Velocity': array([ 5.40723383e-01, -8.14904213e-01, -4.32777393e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.59985065, 14.70422745, -0.12072872]), + 'camera_rotation': array([-6.06285143, -2.26903272, -0.99530458]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.763671875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -209.12841797, -5331.49023438, 104.58686829]), + 'frame': 28238, + 'frame_number': 28238, + 'framesequence': 108582, + 'gaze_dir': array([0.99477386, 0.02439117, 0.09700012]), + 'gaze_origin': array([-2.94861627, -0.01531372, -0.12768708]), + 'gaze_valid': True, + 'gaze_vergence': 89.32975006103516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9960022 , 0.03645325, 0.08135986]), + 'left_gaze_origin': array([-2.76361847, 2.84823918, -0.14200898]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.077423095703125, + 'left_pupil_posn': array([ 0.26437902, -0.12568676]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99354553, 0.0123291 , 0.11264038]), + 'right_gaze_origin': array([-3.13361359, -2.87886667, -0.11336518]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8661956787109375, + 'right_pupil_posn': array([-0.20056105, -0.22653604]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.27775996923446655, + 'timestamp': 914.149864576757, + 'timestamp_carla': 914150, + 'timestamp_device': 4067581, + 'timestamp_stream': 914.149864576757, + 'transform': [array([1.83862913e+00, 1.49175301e+01, 3.58209596e-03]), + array([-0.06388959, -8.05348969, 0.01862451])]} +{'AngularVelocity': array([1.41397503e-03, 1.23418798e-03, 5.24138594e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.243408203125, + 'FR_Wheel_Angle': 19.157127380371094, + 'Location': array([ -0.94986331, -27.25743294, 0.17034212]), + 'Rotation': array([-4.48948294e-02, -6.53613434e+01, 5.98779842e-02]), + 'Velocity': array([ 5.07821977e-01, -7.28895485e-01, -3.35674267e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.57320881, 14.70652008, -0.11830742]), + 'camera_rotation': array([-6.09107351, -2.26383352, -0.94111156]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.373291015625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -219.84197998, -5331.49023438, 102.10995483]), + 'frame': 28239, + 'frame_number': 28239, + 'framesequence': 108586, + 'gaze_dir': array([0.9947052 , 0.02297211, 0.09775543]), + 'gaze_origin': array([-2.94898248, -0.01429215, -0.12817307]), + 'gaze_valid': True, + 'gaze_vergence': 82.92181396484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99606323, 0.03605652, 0.08088684]), + 'left_gaze_origin': array([-2.76497221, 2.84924936, -0.14234619]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0734405517578125, + 'left_pupil_posn': array([ 0.26290035, -0.12548971]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99334717, 0.0098877 , 0.11462402]), + 'right_gaze_origin': array([-3.13299251, -2.8778336 , -0.11399995]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8665008544921875, + 'right_pupil_posn': array([-0.20141786, -0.22699666]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.27775996923446655, + 'timestamp': 914.182978078723, + 'timestamp_carla': 914183, + 'timestamp_device': 4067614, + 'timestamp_stream': 914.182978078723, + 'transform': [array([1.84216118e+00, 1.49122372e+01, 2.90708547e-03]), + array([-0.06362321, -8.06012535, 0.01995103])]} +{'AngularVelocity': array([0.22405055, 0.26200098, 0.00110422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.978107452392578, + 'FR_Wheel_Angle': 16.7938289642334, + 'Location': array([ -0.84777838, -27.41283226, 0.17040281]), + 'Rotation': array([ -0.07671668, -64.26472473, 0.08079629]), + 'Velocity': array([ 9.08610382e-05, -2.06878176e-04, -3.33616917e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.5530405 , 14.70238209, -0.13001569]), + 'camera_rotation': array([-6.11726046, -2.346977 , -0.98152 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3948.84619140625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -224.80661011, -5331.49023438, 103.18319702]), + 'frame': 28240, + 'frame_number': 28240, + 'framesequence': 108590, + 'gaze_dir': array([0.99443817, 0.02983093, 0.09873962]), + 'gaze_origin': array([-2.9352479 , -0.00689163, -0.13331833]), + 'gaze_valid': True, + 'gaze_vergence': 111.71204376220703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99510193, 0.04734802, 0.08676147]), + 'left_gaze_origin': array([-2.7662859 , 2.85502791, -0.14319305]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.00921630859375, + 'left_pupil_posn': array([ 0.25989008, -0.12750995]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99377441, 0.01231384, 0.11071777]), + 'right_gaze_origin': array([-3.10421014, -2.86881113, -0.1234436 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7560272216796875, + 'right_pupil_posn': array([-0.20358813, -0.22563994]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.27775996923446655, + 'timestamp': 914.2165134772658, + 'timestamp_carla': 914217, + 'timestamp_device': 4067647, + 'timestamp_stream': 914.2165134772658, + 'transform': [array([1.83722532e+00, 1.49057150e+01, 1.59170153e-03]), + array([-0.06314509, -8.04987717, 0.02252313])]} +{'AngularVelocity': array([-0.08273498, -0.09952441, -0.00021386]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.56750774383545, + 'FR_Wheel_Angle': 10.989946365356445, + 'Location': array([ -0.84766722, -27.41289902, 0.17031603]), + 'Rotation': array([-6.09730966e-02, -6.42649078e+01, 7.01665580e-02]), + 'Velocity': array([-4.26502193e-05, 7.22489858e-05, -2.59304798e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.52300072, 14.66605186, -0.1452429 ]), + 'camera_rotation': array([-6.17266035, -2.57174158, -1.00589085]), + 'current_gear_input': False, + 'focus_actor_dist': 3948.69921875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -204.21627808, -5331.49023438, 105.92974854]), + 'frame': 28241, + 'frame_number': 28241, + 'framesequence': 108594, + 'gaze_dir': array([ 0.99584961, -0.01004791, 0.08503723]), + 'gaze_origin': array([-2.98664331, 0.03792572, -0.1231247 ]), + 'gaze_valid': True, + 'gaze_vergence': 86.8946533203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99514771, 0.01815796, 0.09660339]), + 'left_gaze_origin': array([-2.86673141, 2.90285206, -0.11313783]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.75982666015625, + 'left_pupil_posn': array([ 0.21208394, -0.1386255 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99655151, -0.03825378, 0.07347107]), + 'right_gaze_origin': array([-3.10655546, -2.82700062, -0.13311158]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.834197998046875, + 'right_pupil_posn': array([-0.2424652 , -0.22876096]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.2539559006690979, + 'timestamp': 914.2497688792646, + 'timestamp_carla': 914250, + 'timestamp_device': 4067681, + 'timestamp_stream': 914.2497688792646, + 'transform': [array([1.83367670e+00, 1.48980293e+01, 1.02479931e-03]), + array([-0.06286506, -8.04224968, 0.02363869])]} +{'AngularVelocity': array([-2.15072874e-02, -2.70889625e-02, -3.27446287e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.575311660766602, + 'FR_Wheel_Angle': 5.129671573638916, + 'Location': array([ -0.84757841, -27.41297722, 0.17021948]), + 'Rotation': array([-4.55983393e-02, -6.42650146e+01, 6.31370395e-02]), + 'Velocity': array([-6.30912837e-06, 2.04382322e-05, 3.12021468e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.47386169, 14.56468964, -0.15995046]), + 'camera_rotation': array([-6.188766 , -3.24476051, -1.02062094]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.002197265625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -375.73519897, -5331.48974609, 45.36454773]), + 'frame': 28242, + 'frame_number': 28242, + 'framesequence': 108598, + 'gaze_dir': array([ 0.98219299, -0.16877747, 0.07487488]), + 'gaze_origin': array([-2.96868753, 0.1556984 , -0.14818421]), + 'gaze_valid': True, + 'gaze_vergence': 80.22955322265625, + 'handbrake_input': False, + 'left_eye_openness': 0.9768053889274597, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98724365, -0.13574219, 0.08309937]), + 'left_gaze_origin': array([-2.81965804, 3.00923038, -0.14003906]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7958831787109375, + 'left_pupil_posn': array([ 0.08450115, -0.15070236]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9782742857933044, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97714233, -0.20181274, 0.06665039]), + 'right_gaze_origin': array([-3.11771703, -2.69783354, -0.15632935]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.874603271484375, + 'right_pupil_posn': array([-0.38660657, -0.25142705]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.24205386638641357, + 'timestamp': 914.2838255763054, + 'timestamp_carla': 914284, + 'timestamp_device': 4067714, + 'timestamp_stream': 914.2838255763054, + 'transform': [array([1.83645594e+00, 1.48872910e+01, 3.22017673e-04]), + array([-0.0627626 , -8.04701233, 0.02500621])]} +{'AngularVelocity': array([-5.12767816e-03, -7.16980128e-03, -1.14496315e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2335426807403564, + 'FR_Wheel_Angle': 0.8280280828475952, + 'Location': array([ -0.84755397, -27.41299438, 0.17019342]), + 'Rotation': array([-4.17802632e-02, -6.42652740e+01, 6.12130463e-02]), + 'Velocity': array([2.98638815e-06, 5.99725490e-06, 6.03883935e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.4021039 , 14.34719181, -0.16028267]), + 'camera_rotation': array([-6.21235704, -4.66746664, -0.8505851 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1854.5712890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -643.77636719, -3204.24267578, 71.02267456]), + 'frame': 28243, + 'frame_number': 28243, + 'framesequence': 108602, + 'gaze_dir': array([ 0.98286438, -0.16601562, 0.07653046]), + 'gaze_origin': array([-2.97295547, 0.14380112, -0.14986955]), + 'gaze_valid': True, + 'gaze_vergence': 116.96218872070312, + 'handbrake_input': False, + 'left_eye_openness': 0.9792242646217346, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98608398, -0.14387512, 0.08317566]), + 'left_gaze_origin': array([-2.82584715, 2.99810338, -0.1407074 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6562347412109375, + 'left_pupil_posn': array([ 0.09674978, -0.15126479]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9911695718765259, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97964478, -0.18815613, 0.06988525]), + 'right_gaze_origin': array([-3.12006402, -2.71050119, -0.15903169]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9706573486328125, + 'right_pupil_posn': array([-0.38086396, -0.25393426]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.2380865216255188, + 'timestamp': 914.3167461790144, + 'timestamp_carla': 914317, + 'timestamp_device': 4067747, + 'timestamp_stream': 914.3167461790144, + 'transform': [array([ 1.83572745e+00, 1.48760633e+01, -1.48029329e-04]), + array([-0.06263283, -8.04480743, 0.02594192])]} +{'AngularVelocity': array([-1.17404922e-03, -1.89951854e-03, -1.34722923e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.23456525802612305, + 'FR_Wheel_Angle': -0.2340337485074997, + 'Location': array([ -0.84754753, -27.41300011, 0.17020044]), + 'Rotation': array([-4.09811325e-02, -6.42652740e+01, 6.07549436e-02]), + 'Velocity': array([ 3.94891003e-06, 2.30721503e-06, -2.71965924e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.33345604, 14.11336708, -0.1684487 ]), + 'camera_rotation': array([-6.3120575 , -6.15469265, -0.80067003]), + 'current_gear_input': False, + 'focus_actor_dist': 1854.503662109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -683.55371094, -3197.16894531, 74.3021698 ]), + 'frame': 28244, + 'frame_number': 28244, + 'framesequence': 108606, + 'gaze_dir': array([ 0.98677826, -0.14558411, 0.06917572]), + 'gaze_origin': array([-2.98509002, 0.12886888, -0.14455949]), + 'gaze_valid': True, + 'gaze_vergence': 112.65333557128906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98744202, -0.13511658, 0.08183289]), + 'left_gaze_origin': array([-2.92444777, 2.98984528, -0.10855256]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6578521728515625, + 'left_pupil_posn': array([ 0.11367965, -0.15262222]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9861145 , -0.15605164, 0.05651855]), + 'right_gaze_origin': array([-3.04573226, -2.73210764, -0.18056642]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.912017822265625, + 'right_pupil_posn': array([-0.36166078, -0.25441158]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.2380865216255188, + 'timestamp': 914.3505977764726, + 'timestamp_carla': 914351, + 'timestamp_device': 4067781, + 'timestamp_stream': 914.3505977764726, + 'transform': [array([ 1.83752620e+00, 1.48626356e+01, -6.25572167e-04]), + array([-0.06246208, -8.04746723, 0.02687569])]} +{'AngularVelocity': array([-2.70747318e-04, -5.56432758e-04, -1.41041155e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.23456525802612305, + 'FR_Wheel_Angle': -0.2340337485074997, + 'Location': array([ -0.84754568, -27.41300201, 0.17019613]), + 'Rotation': array([-4.09811325e-02, -6.42652740e+01, 6.07549436e-02]), + 'Velocity': array([ 4.68447797e-06, 1.41581825e-06, -4.53883058e-06]), + 'brake_input': 0.0, + 'camera_location': array([-7.27416801, 13.88689041, -0.20017712]), + 'camera_rotation': array([-6.51076841, -7.46381426, -0.81235278]), + 'current_gear_input': False, + 'focus_actor_dist': 1855.9998779296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -693.07910156, -3197.20166016, 57.55219269]), + 'frame': 28245, + 'frame_number': 28245, + 'framesequence': 108610, + 'gaze_dir': array([ 0.99057007, -0.11737823, 0.06565857]), + 'gaze_origin': array([-3.0709703 , 0.11726456, -0.11434479]), + 'gaze_valid': True, + 'gaze_vergence': 6.844653129577637, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98895264, -0.11665344, 0.09136963]), + 'left_gaze_origin': array([-3.172014 , 2.98649764, -0.02472229]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6981658935546875, + 'left_pupil_posn': array([ 0.13042736, -0.14894176]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9921875 , -0.11810303, 0.03994751]), + 'right_gaze_origin': array([-2.9699266 , -2.75196838, -0.2039673 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.760955810546875, + 'right_pupil_posn': array([-0.34053665, -0.25174701]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.2380865216255188, + 'timestamp': 914.3837241791189, + 'timestamp_carla': 914384, + 'timestamp_device': 4067814, + 'timestamp_stream': 914.3837241791189, + 'transform': [array([ 1.83688653e+00, 1.48488617e+01, -7.73296342e-04]), + array([-0.06238011, -8.04524994, 0.02717924])]} +{'AngularVelocity': array([-7.84246949e-05, -1.30276865e-04, -1.38600772e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.84754425, -27.41300201, 0.17020597]), + 'Rotation': array([-4.09811325e-02, -6.42652740e+01, 6.07549436e-02]), + 'Velocity': array([5.11899589e-06, 1.18129662e-06, 2.54289364e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.20010519, 13.65830708, -0.22998621]), + 'camera_rotation': array([-6.68907022, -8.69518471, -0.86861134]), + 'current_gear_input': False, + 'focus_actor_dist': 2416.73486328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -802.49822998, -3747.36230469, 17.57306671]), + 'frame': 28246, + 'frame_number': 28246, + 'framesequence': 108614, + 'gaze_dir': array([ 0.99014282, -0.11368561, 0.0786438 ]), + 'gaze_origin': array([-3.00626636, 0.09465943, -0.13156435]), + 'gaze_valid': True, + 'gaze_vergence': 97.55706024169922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99082947, -0.0974884 , 0.09339905]), + 'left_gaze_origin': array([-2.93519449, 2.95692921, -0.09886169]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.761627197265625, + 'left_pupil_posn': array([ 0.14487982, -0.14537811]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98945618, -0.12988281, 0.06388855]), + 'right_gaze_origin': array([-3.07733774, -2.76761031, -0.16426697]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.87408447265625, + 'right_pupil_posn': array([-0.32409227, -0.24499512]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.27775996923446655, + 'timestamp': 914.4178045764565, + 'timestamp_carla': 914418, + 'timestamp_device': 4067847, + 'timestamp_stream': 914.4178045764565, + 'transform': [array([ 1.83492887e+00, 1.48334579e+01, -9.99431591e-04]), + array([-0.06220253, -8.04026508, 0.02762055])]} +{'AngularVelocity': array([-5.48880162e-05, -3.41057639e-05, -1.43327625e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.84754318, -27.41300201, 0.17019464]), + 'Rotation': array([-4.09811325e-02, -6.42652740e+01, 6.07549436e-02]), + 'Velocity': array([4.86007866e-06, 1.17925754e-06, 7.20087382e-06]), + 'brake_input': 0.0, + 'camera_location': array([-7.09566498, 13.45700264, -0.24962109]), + 'camera_rotation': array([-6.73873234, -9.7770052 , -1.04434669]), + 'current_gear_input': False, + 'focus_actor_dist': 1858.236328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -716.24084473, -3197.28564453, 62.72514343]), + 'frame': 28247, + 'frame_number': 28247, + 'framesequence': 108618, + 'gaze_dir': array([ 0.99137115, -0.09983826, 0.08235931]), + 'gaze_origin': array([-2.9567163 , 0.07633209, -0.14449845]), + 'gaze_valid': True, + 'gaze_vergence': 88.4818344116211, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99131775, -0.08714294, 0.09831238]), + 'left_gaze_origin': array([-2.87682056, 2.93875122, -0.1160782 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6837310791015625, + 'left_pupil_posn': array([ 0.16258001, -0.14472151]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99142456, -0.11253357, 0.06640625]), + 'right_gaze_origin': array([-3.03661203, -2.78608727, -0.17291871]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.913421630859375, + 'right_pupil_posn': array([-0.30727488, -0.24160886]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.30951398611068726, + 'timestamp': 914.4508025757968, + 'timestamp_carla': 914451, + 'timestamp_device': 4067881, + 'timestamp_stream': 914.4508025757968, + 'transform': [array([ 1.83692110e+00, 1.48162079e+01, -1.33287429e-03]), + array([-0.06215472, -8.043046 , 0.02829112])]} +{'AngularVelocity': array([-1.24507560e-05, -1.19752376e-05, -1.42151848e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.5110018253326416, + 'FR_Wheel_Angle': -2.6891167163848877, + 'Location': array([ -0.84754181, -27.41300201, 0.17019708]), + 'Rotation': array([-4.09811325e-02, -6.42652740e+01, 6.07549436e-02]), + 'Velocity': array([ 4.93098059e-06, 1.08381846e-06, -3.69996110e-06]), + 'brake_input': 0.0, + 'camera_location': array([-7.0195508 , 13.25527763, -0.30130723]), + 'camera_rotation': array([ -7.02568245, -10.77580166, -1.07762241]), + 'current_gear_input': False, + 'focus_actor_dist': 1858.4307861328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -725.72473145, -3197.16748047, 67.51376343]), + 'frame': 28248, + 'frame_number': 28248, + 'framesequence': 108622, + 'gaze_dir': array([ 0.99279785, -0.0869751 , 0.08045197]), + 'gaze_origin': array([-2.96083689, 0.0575943 , -0.13357238]), + 'gaze_valid': True, + 'gaze_vergence': 118.21858215332031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99290466, -0.07444763, 0.09266663]), + 'left_gaze_origin': array([-2.87268543, 2.91982269, -0.10633088]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.678009033203125, + 'left_pupil_posn': array([ 0.1797086, -0.1367625]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99269104, -0.09950256, 0.0682373 ]), + 'right_gaze_origin': array([-3.04898834, -2.80463409, -0.16081391]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.766357421875, + 'right_pupil_posn': array([-0.29014063, -0.2375623 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.3333180844783783, + 'timestamp': 914.4857338778675, + 'timestamp_carla': 914486, + 'timestamp_device': 4067914, + 'timestamp_stream': 914.4857338778675, + 'transform': [array([ 1.83152068e+00, 1.47970953e+01, -1.76721567e-03]), + array([-0.06202494, -8.0310154 , 0.02912794])]} +{'AngularVelocity': array([ 0.02322452, 0.01314787, -0.68851388]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9028594493865967, + 'FR_Wheel_Angle': -3.8002889156341553, + 'Location': array([ -0.84885544, -27.40985298, 0.17020696]), + 'Rotation': array([-4.18075845e-02, -6.42665558e+01, 6.06288761e-02]), + 'Velocity': array([-1.51480529e-02, 3.37795578e-02, 4.13894622e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.95121145, 13.07208443, -0.38714132]), + 'camera_rotation': array([ -7.4875536 , -11.63853645, -1.0243324 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1084.880615234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -548.29138184, -2446.23535156, 87.74101257]), + 'frame': 28249, + 'frame_number': 28249, + 'framesequence': 108626, + 'gaze_dir': array([ 0.99201202, -0.08805084, 0.08840942]), + 'gaze_origin': array([-2.95472431, 0.05832138, -0.13228302]), + 'gaze_valid': True, + 'gaze_vergence': 157.94618225097656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99343872, -0.07015991, 0.09017944]), + 'left_gaze_origin': array([-2.84519506, 2.9196701 , -0.11328278]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.798858642578125, + 'left_pupil_posn': array([ 0.17736328, -0.13024306]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99058533, -0.10594177, 0.0866394 ]), + 'right_gaze_origin': array([-3.06425333, -2.80302739, -0.15128326]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9636077880859375, + 'right_pupil_posn': array([-0.28979474, -0.23513234]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.3452201187610626, + 'timestamp': 914.5168388783932, + 'timestamp_carla': 914517, + 'timestamp_device': 4067947, + 'timestamp_stream': 914.5168388783932, + 'transform': [array([ 1.82937956e+00, 1.47781334e+01, -2.06464762e-03]), + array([-0.06190883, -8.02546406, 0.02976075])]} +{'AngularVelocity': array([ 0.02669176, 0.01415644, -0.63208979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9448416233062744, + 'FR_Wheel_Angle': -3.7996041774749756, + 'Location': array([ -0.85075653, -27.40535355, 0.17022166]), + 'Rotation': array([-4.15685289e-02, -6.42635422e+01, 6.07153364e-02]), + 'Velocity': array([-0.01732502, 0.0383372 , 0.00017445]), + 'brake_input': 0.0, + 'camera_location': array([-6.88189888, 12.8970089 , -0.47418618]), + 'camera_rotation': array([ -7.94449329, -12.31939793, -1.00268018]), + 'current_gear_input': False, + 'focus_actor_dist': 1020.5494995117188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -548.72644043, -2381.90136719, 90.48690796]), + 'frame': 28250, + 'frame_number': 28250, + 'framesequence': 108631, + 'gaze_dir': array([ 0.98741913, -0.12966156, 0.08813477]), + 'gaze_origin': array([-2.95041966, 0.0848877 , -0.13323212]), + 'gaze_valid': True, + 'gaze_vergence': 117.65731048583984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98861694, -0.11288452, 0.09945679]), + 'left_gaze_origin': array([-2.87651229, 2.94331217, -0.10361329]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9001312255859375, + 'left_pupil_posn': array([ 0.14801776, -0.13353646]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98622131, -0.1464386 , 0.07681274]), + 'right_gaze_origin': array([-3.02432728, -2.77353668, -0.16285096]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9080047607421875, + 'right_pupil_posn': array([-0.3245787 , -0.23211682]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.3491874635219574, + 'timestamp': 914.5544452778995, + 'timestamp_carla': 914555, + 'timestamp_device': 4067989, + 'timestamp_stream': 914.5544452778995, + 'transform': [array([ 1.82788479e+00, 1.47524157e+01, -2.74665817e-03]), + array([-0.06156049, -8.02067757, 0.0310311 ])]} +{'AngularVelocity': array([ 0.02974832, 0.0150811 , -0.70188546]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.8026487827301025, + 'FR_Wheel_Angle': -3.58599853515625, + 'Location': array([ -0.85385525, -27.3983345 , 0.17019804]), + 'Rotation': array([-4.19305302e-02, -6.42546310e+01, 6.06851019e-02]), + 'Velocity': array([-0.02405083, 0.05331059, -0.00047302]), + 'brake_input': 0.0, + 'camera_location': array([-6.82062531, 12.76722908, -0.53558248]), + 'camera_rotation': array([ -8.27139282, -12.82985592, -1.08684433]), + 'current_gear_input': False, + 'focus_actor_dist': 973.9237670898438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -586.89794922, -2323.82543945, 84.42591858]), + 'frame': 28251, + 'frame_number': 28251, + 'framesequence': 108634, + 'gaze_dir': array([ 0.98731232, -0.12901306, 0.09111786]), + 'gaze_origin': array([-2.935534 , 0.08037949, -0.13611908]), + 'gaze_valid': True, + 'gaze_vergence': 144.77450561523438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98809814, -0.11624146, 0.10064697]), + 'left_gaze_origin': array([-2.86330724, 2.93866277, -0.10520936]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8267364501953125, + 'left_pupil_posn': array([ 0.15257585, -0.13037288]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98652649, -0.14178467, 0.08158875]), + 'right_gaze_origin': array([-3.00776076, -2.7779038 , -0.16702881]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.901092529296875, + 'right_pupil_posn': array([-0.32256913, -0.23156452]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.30951398611068726, + 'timestamp': 914.584336977452, + 'timestamp_carla': 914585, + 'timestamp_device': 4068014, + 'timestamp_stream': 914.584336977452, + 'transform': [array([ 1.82768953e+00, 1.47295294e+01, -3.56313703e-03]), + array([-0.06132827, -8.01869297, 0.03257118])]} +{'AngularVelocity': array([-0.09249112, -0.03302772, -0.76155913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.4169914722442627, + 'FR_Wheel_Angle': -3.2737767696380615, + 'Location': array([ -0.88703412, -27.3242569 , 0.17031156]), + 'Rotation': array([-5.20596988e-02, -6.41639023e+01, 5.96979596e-02]), + 'Velocity': array([-1.48214146e-01, 3.36209029e-01, 1.38463976e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.73052454, 12.65568924, -0.59150511]), + 'camera_rotation': array([ -8.45104694, -13.19565964, -1.24690342]), + 'current_gear_input': False, + 'focus_actor_dist': 974.75927734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -594.86791992, -2324.64160156, 81.57564545]), + 'frame': 28252, + 'frame_number': 28252, + 'framesequence': 108638, + 'gaze_dir': array([ 0.98891449, -0.11707306, 0.08959198]), + 'gaze_origin': array([-2.96335936, 0.07565156, -0.12009278]), + 'gaze_valid': True, + 'gaze_vergence': 76.0069351196289, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98843384, -0.10939026, 0.10496521]), + 'left_gaze_origin': array([-2.89706111, 2.93678761, -0.08629609]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8667144775390625, + 'left_pupil_posn': array([ 0.15998852, -0.12654185]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98939514, -0.12475586, 0.07421875]), + 'right_gaze_origin': array([-3.02965713, -2.78548455, -0.15388948]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9234466552734375, + 'right_pupil_posn': array([-0.31506562, -0.22521853]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.2539559006690979, + 'timestamp': 914.6180072762072, + 'timestamp_carla': 914618, + 'timestamp_device': 4068047, + 'timestamp_stream': 914.6180072762072, + 'transform': [array([ 1.83192778e+00, 1.47022572e+01, -3.46044544e-03]), + array([-0.06150585, -8.02525711, 0.03244253])]} +{'AngularVelocity': array([-0.02164738, -0.0063145 , -0.98546284]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.2765681743621826, + 'FR_Wheel_Angle': -3.175739288330078, + 'Location': array([ -0.91085094, -27.27152824, 0.17024973]), + 'Rotation': array([-3.94033603e-02, -6.40985184e+01, 6.10243604e-02]), + 'Velocity': array([-9.79825258e-02, 2.19721630e-01, -3.90624991e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.66026688, 12.56688881, -0.61939013]), + 'camera_rotation': array([ -8.57584858, -13.40446758, -1.34100056]), + 'current_gear_input': False, + 'focus_actor_dist': 969.9500732421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -588.27185059, -2323.85205078, 77.01741791]), + 'frame': 28253, + 'frame_number': 28253, + 'framesequence': 108642, + 'gaze_dir': array([ 0.98913574, -0.1193161 , 0.0845871 ]), + 'gaze_origin': array([-2.96799183, 0.07323228, -0.11729126]), + 'gaze_valid': True, + 'gaze_vergence': 125.9663314819336, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98925781, -0.11030579, 0.0958252 ]), + 'left_gaze_origin': array([-2.89396214, 2.93515015, -0.08650513]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.898956298828125, + 'left_pupil_posn': array([ 0.15985703, -0.1264714 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98901367, -0.12832642, 0.073349 ]), + 'right_gaze_origin': array([-3.04202127, -2.7886858 , -0.1480774 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.906890869140625, + 'right_pupil_posn': array([-0.31334001, -0.22680545]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0009155553416348994, + 'throttle_input': 0.18252842128276825, + 'timestamp': 914.6507878787816, + 'timestamp_carla': 914651, + 'timestamp_device': 4068081, + 'timestamp_stream': 914.6507878787816, + 'transform': [array([ 1.83381557e+00, 1.46743689e+01, -3.48033896e-03]), + array([-0.06142389, -8.02708054, 0.03254519])]} +{'AngularVelocity': array([0.09715146, 0.04017631, 0.1613587 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.256645441055298, + 'FR_Wheel_Angle': -3.154991865158081, + 'Location': array([ -0.93566597, -27.21666145, 0.17030229]), + 'Rotation': array([-4.40069064e-02, -6.40356903e+01, 6.04486503e-02]), + 'Velocity': array([-1.47997171e-01, 3.29486281e-01, 2.30407713e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.60164547, 12.49326897, -0.63794613]), + 'camera_rotation': array([ -8.62680817, -13.5474844 , -1.45072687]), + 'current_gear_input': False, + 'focus_actor_dist': 967.0115966796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -592.80322266, -2321.54174805, 70.04061127]), + 'frame': 28254, + 'frame_number': 28254, + 'framesequence': 108646, + 'gaze_dir': array([ 0.98915863, -0.11772156, 0.08677673]), + 'gaze_origin': array([-2.96331501, 0.07250443, -0.12037965]), + 'gaze_valid': True, + 'gaze_vergence': 166.44525146484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98951721, -0.10830688, 0.09542847]), + 'left_gaze_origin': array([-2.88956618, 2.93426394, -0.0895279 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9094085693359375, + 'left_pupil_posn': array([ 0.1608218 , -0.12603545]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98880005, -0.12713623, 0.078125 ]), + 'right_gaze_origin': array([-3.03706384, -2.7892549 , -0.15123139]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.922882080078125, + 'right_pupil_posn': array([-0.31222308, -0.22817326]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0008789331186562777, + 'throttle_input': 0.09919890016317368, + 'timestamp': 914.6852560788393, + 'timestamp_carla': 914686, + 'timestamp_device': 4068114, + 'timestamp_stream': 914.6852560788393, + 'transform': [array([ 1.82808769e+00, 1.46451731e+01, -3.19402688e-03]), + array([-0.06146487, -8.01368809, 0.03200629])]} +{'AngularVelocity': array([-0.05107233, -0.02009267, 0.52183014]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9499216079711914, + 'FR_Wheel_Angle': -4.004730701446533, + 'Location': array([ -0.9795118 , -27.12017441, 0.17036596]), + 'Rotation': array([-4.59603406e-02, -6.39193573e+01, 6.00818433e-02]), + 'Velocity': array([-1.75631195e-01, 3.95817935e-01, 4.77123249e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.56697845, 12.43835449, -0.66951162]), + 'camera_rotation': array([ -8.7911768 , -13.60011387, -1.57507074]), + 'current_gear_input': False, + 'focus_actor_dist': 964.3020629882812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -592.96160889, -2321.54174805, 71.25798798]), + 'frame': 28255, + 'frame_number': 28255, + 'framesequence': 108650, + 'gaze_dir': array([ 0.98937225, -0.11434174, 0.08904266]), + 'gaze_origin': array([-2.96943998, 0.07371445, -0.11736146]), + 'gaze_valid': True, + 'gaze_vergence': 202.1195526123047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98974609, -0.10571289, 0.09603882]), + 'left_gaze_origin': array([-2.90295577, 2.93640304, -0.08319703]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8624725341796875, + 'left_pupil_posn': array([ 0.16087902, -0.12289095]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98899841, -0.12297058, 0.08204651]), + 'right_gaze_origin': array([-3.03592396, -2.78897405, -0.15152588]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.90850830078125, + 'right_pupil_posn': array([-0.31149346, -0.22789037]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006775109213776886, + 'throttle_input': 0.0, + 'timestamp': 914.7185471765697, + 'timestamp_carla': 914719, + 'timestamp_device': 4068147, + 'timestamp_stream': 914.7185471765697, + 'transform': [array([ 1.82830930e+00, 1.46145563e+01, -3.05557251e-03]), + array([-0.06155366, -8.01204109, 0.03177122])]} +{'AngularVelocity': array([ 0.00064458, -0.01974809, 0.48923692]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.933439254760742, + 'FR_Wheel_Angle': -5.902169227600098, + 'Location': array([ -1.01484323, -27.04058456, 0.17035654]), + 'Rotation': array([-3.57970186e-02, -6.37877350e+01, 6.05784990e-02]), + 'Velocity': array([-0.09635574, 0.23547438, 0.00038236]), + 'brake_input': 0.0, + 'camera_location': array([-6.57306862, 12.40462685, -0.7217375 ]), + 'camera_rotation': array([ -9.00374603, -13.54600048, -1.78184867]), + 'current_gear_input': False, + 'focus_actor_dist': 959.7794189453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -589.21636963, -2321.02514648, 70.75494385]), + 'frame': 28256, + 'frame_number': 28256, + 'framesequence': 108654, + 'gaze_dir': array([ 0.98995209, -0.10935211, 0.08860779]), + 'gaze_origin': array([-2.99230886, 0.0747078 , -0.10641861]), + 'gaze_valid': True, + 'gaze_vergence': 159.94076538085938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99012756, -0.10047913, 0.09764099]), + 'left_gaze_origin': array([-2.90635991, 2.93659067, -0.07961731]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.01531982421875, + 'left_pupil_posn': array([ 0.16254139, -0.12226927]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98977661, -0.1182251 , 0.07957458]), + 'right_gaze_origin': array([-3.0782578 , -2.78717494, -0.13321993]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.929718017578125, + 'right_pupil_posn': array([-0.3111676 , -0.22311318]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 914.7518523782492, + 'timestamp_carla': 914752, + 'timestamp_device': 4068181, + 'timestamp_stream': 914.7518523782492, + 'transform': [array([ 1.82936978e+00, 1.45819426e+01, -3.10194003e-03]), + array([-0.06155366, -8.01191044, 0.03188952])]} +{'AngularVelocity': array([0.07601336, 0.02599849, 1.22942913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.374237060546875, + 'FR_Wheel_Angle': -8.027689933776855, + 'Location': array([ -1.03148603, -27.00281906, 0.17037237]), + 'Rotation': array([-3.75318862e-02, -6.36619492e+01, 6.06270842e-02]), + 'Velocity': array([-8.64199400e-02, 2.07442731e-01, -1.13220209e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.58587694, 12.37677193, -0.7655853 ]), + 'camera_rotation': array([ -9.2076273 , -13.56392193, -1.84705043]), + 'current_gear_input': False, + 'focus_actor_dist': 955.5318603515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -582.58734131, -2321.46166992, 66.73706818]), + 'frame': 28257, + 'frame_number': 28257, + 'framesequence': 108659, + 'gaze_dir': array([ 0.99208069, -0.04924774, 0.11404419]), + 'gaze_origin': array([-2.97381449, 0.03319474, -0.09933396]), + 'gaze_valid': True, + 'gaze_vergence': 151.13064575195312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9924469 , -0.03143311, 0.11854553]), + 'left_gaze_origin': array([-2.83442855, 2.89397287, -0.09090882]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0568695068359375, + 'left_pupil_posn': array([ 0.20781636, -0.10605085]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99171448, -0.06706238, 0.10954285]), + 'right_gaze_origin': array([-3.11320043, -2.82758355, -0.1077591 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9423370361328125, + 'right_pupil_posn': array([-0.25906426, -0.20539701]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 914.7936217784882, + 'timestamp_carla': 914794, + 'timestamp_device': 4068222, + 'timestamp_stream': 914.7936217784882, + 'transform': [array([ 1.83159113e+00, 1.45396872e+01, -2.62166979e-03]), + array([-0.06173125, -8.01344013, 0.03097652])]} +{'AngularVelocity': array([0.0101997 , 0.00824465, 2.29203963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.04223918914795, + 'FR_Wheel_Angle': -9.231209754943848, + 'Location': array([ -1.05283833, -26.95133781, 0.17044252]), + 'Rotation': array([-4.60149832e-02, -6.34675484e+01, 5.82854301e-02]), + 'Velocity': array([-1.08833112e-01, 2.85246402e-01, -1.14107126e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.64376163, 12.37574768, -0.78842187]), + 'camera_rotation': array([ -9.35037804, -13.51419067, -1.95254588]), + 'current_gear_input': False, + 'focus_actor_dist': 1033.7960205078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -548.35675049, -2417.49365234, 84.9568634 ]), + 'frame': 28258, + 'frame_number': 28258, + 'framesequence': 108664, + 'gaze_dir': array([ 0.99124146, -0.03768158, 0.12439728]), + 'gaze_origin': array([-2.96388936, 0.01957092, -0.09325944]), + 'gaze_valid': True, + 'gaze_vergence': 122.80641174316406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99168396, -0.01490784, 0.12776184]), + 'left_gaze_origin': array([-2.81123376, 2.87575078, -0.09044647]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.165924072265625, + 'left_pupil_posn': array([ 0.22196162, -0.09784496]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99079895, -0.06045532, 0.12103271]), + 'right_gaze_origin': array([-3.1165452 , -2.83660913, -0.09607239]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.84423828125, + 'right_pupil_posn': array([-0.24689847, -0.19471538]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0009521775064058602, + 'throttle_input': 0.0, + 'timestamp': 914.8284921757877, + 'timestamp_carla': 914829, + 'timestamp_device': 4068264, + 'timestamp_stream': 914.8284921757877, + 'transform': [array([ 1.83300138e+00, 1.45040340e+01, -1.81522360e-03]), + array([-0.06200445, -8.01379871, 0.02939637])]} +{'AngularVelocity': array([0.0400062 , 0.01295787, 1.38471437]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.092689514160156, + 'FR_Wheel_Angle': -9.200051307678223, + 'Location': array([ -1.09385133, -26.85041618, 0.17052571]), + 'Rotation': array([-5.30364178e-02, -6.31384430e+01, 5.71960732e-02]), + 'Velocity': array([-2.12371379e-01, 5.44426084e-01, -5.03730771e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.69455242, 12.413064 , -0.78380257]), + 'camera_rotation': array([ -9.35496807, -13.394104 , -2.05784822]), + 'current_gear_input': False, + 'focus_actor_dist': 1830.0556640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -728.0168457 , -3197.27832031, 62.28842163]), + 'frame': 28259, + 'frame_number': 28259, + 'framesequence': 108668, + 'gaze_dir': array([ 0.99081421, -0.03762817, 0.12747192]), + 'gaze_origin': array([-2.96996856, 0.01972046, -0.09159623]), + 'gaze_valid': True, + 'gaze_vergence': 114.64310455322266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99125671, -0.01329041, 0.1312561 ]), + 'left_gaze_origin': array([-2.80949259, 2.87654877, -0.0927826 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1349334716796875, + 'left_pupil_posn': array([ 0.22086573, -0.09809983]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9903717 , -0.06196594, 0.12368774]), + 'right_gaze_origin': array([-3.13044453, -2.83710814, -0.09040985]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8058013916015625, + 'right_pupil_posn': array([-0.24599195, -0.19223094]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.001538132899440825, + 'throttle_input': 0.0, + 'timestamp': 914.8628069758415, + 'timestamp_carla': 914863, + 'timestamp_device': 4068297, + 'timestamp_stream': 914.8628069758415, + 'transform': [array([ 1.83410001e+00, 1.44689312e+01, -7.99655914e-04]), + array([-0.0623528 , -8.01358891, 0.02742545])]} +{'AngularVelocity': array([-0.07430229, 0.013011 , 2.28672671]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.986239433288574, + 'FR_Wheel_Angle': -9.038627624511719, + 'Location': array([ -1.16899061, -26.66988373, 0.1706101 ]), + 'Rotation': array([-5.20938486e-02, -6.25034676e+01, 5.80443703e-02]), + 'Velocity': array([-2.87714839e-01, 7.12258339e-01, 3.94182192e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.74335289, 12.48222542, -0.69335139]), + 'camera_rotation': array([ -8.7944212 , -13.27645206, -2.27241278]), + 'current_gear_input': False, + 'focus_actor_dist': 1825.3074951171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -723.55981445, -3197.16748047, 67.80691528]), + 'frame': 28260, + 'frame_number': 28260, + 'framesequence': 108671, + 'gaze_dir': array([ 0.99137115, -0.04444885, 0.12213135]), + 'gaze_origin': array([-2.94881678, 0.01993942, -0.10130157]), + 'gaze_valid': True, + 'gaze_vergence': 173.95375061035156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99200439, -0.02806091, 0.12297058]), + 'left_gaze_origin': array([-2.80584884, 2.87725687, -0.09396821]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.136871337890625, + 'left_pupil_posn': array([ 0.2207402 , -0.09900522]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99073792, -0.06083679, 0.12129211]), + 'right_gaze_origin': array([-3.09178472, -2.83737803, -0.10863495]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8983917236328125, + 'right_pupil_posn': array([-0.25100172, -0.20029032]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.003094576997682452, + 'throttle_input': 0.0, + 'timestamp': 914.8877294771373, + 'timestamp_carla': 914888, + 'timestamp_device': 4068322, + 'timestamp_stream': 914.8877294771373, + 'transform': [array([1.83429742e+00, 1.44435987e+01, 7.62939408e-07]), + array([-0.06263283, -8.01224995, 0.02588492])]} +{'AngularVelocity': array([ 3.13441618e-04, -3.12222876e-02, 2.42940950e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.707975387573242, + 'FR_Wheel_Angle': -8.98632526397705, + 'Location': array([ -1.23726583, -26.51099014, 0.17058435]), + 'Rotation': array([-4.44372073e-02, -6.19551392e+01, 6.01573028e-02]), + 'Velocity': array([-2.73266494e-01, 6.69742346e-01, -6.51779177e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.74335289, 12.48222542, -0.69335139]), + 'camera_rotation': array([ -8.7944212 , -13.27645206, -2.27241278]), + 'current_gear_input': False, + 'focus_actor_dist': 1823.7489013671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -731.93548584, -3197.16748047, 75.13937378]), + 'frame': 28261, + 'frame_number': 28261, + 'framesequence': 108675, + 'gaze_dir': array([ 0.9914093 , -0.04401398, 0.12190247]), + 'gaze_origin': array([-2.94460702, 0.02086716, -0.10432816]), + 'gaze_valid': True, + 'gaze_vergence': 166.97299194335938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99229431, -0.02697754, 0.12080383]), + 'left_gaze_origin': array([-2.80267048, 2.8782227 , -0.09694367]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.13665771484375, + 'left_pupil_posn': array([ 0.21997726, -0.09982419]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99052429, -0.06105042, 0.1230011 ]), + 'right_gaze_origin': array([-3.08654356, -2.83648849, -0.11171266]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.93060302734375, + 'right_pupil_posn': array([-0.25124246, -0.20217884]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00437635462731123, + 'throttle_input': 0.0, + 'timestamp': 914.9233046770096, + 'timestamp_carla': 914924, + 'timestamp_device': 4068356, + 'timestamp_stream': 914.9233046770096, + 'transform': [array([1.83531034e+00, 1.44075537e+01, 1.12831115e-03]), + array([-0.06301532, -8.0117979 , 0.02367172])]} +{'AngularVelocity': array([ 0.01458951, -0.03180153, 2.56763339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.060254096984863, + 'FR_Wheel_Angle': -10.28940200805664, + 'Location': array([ -1.30143952, -26.36363029, 0.17069376]), + 'Rotation': array([-4.22378890e-02, -6.14258423e+01, 5.94519041e-02]), + 'Velocity': array([-2.46938705e-01, 6.11718655e-01, -1.43451689e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.76027966, 12.52722931, -0.64317709]), + 'camera_rotation': array([ -8.53778362, -13.13559437, -2.29494977]), + 'current_gear_input': False, + 'focus_actor_dist': 1820.9176025390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -730.33056641, -3197.16772461, 74.78835297]), + 'frame': 28262, + 'frame_number': 28262, + 'framesequence': 108678, + 'gaze_dir': array([ 0.99295044, -0.04853821, 0.10494995]), + 'gaze_origin': array([-2.98980498, 0.02454224, -0.09487229]), + 'gaze_valid': True, + 'gaze_vergence': 109.98043060302734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99378967, -0.02311707, 0.10882568]), + 'left_gaze_origin': array([-2.86428547, 2.88335729, -0.08183442]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1071014404296875, + 'left_pupil_posn': array([ 0.21295655, -0.10861635]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99211121, -0.07395935, 0.10107422]), + 'right_gaze_origin': array([-3.1153245 , -2.83427286, -0.10791016]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.97821044921875, + 'right_pupil_posn': array([-0.25165939, -0.20942414]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0058595542795956135, + 'throttle_input': 0.0, + 'timestamp': 914.9519760757685, + 'timestamp_carla': 914952, + 'timestamp_device': 4068381, + 'timestamp_stream': 914.9519760757685, + 'transform': [array([1.83827507e+00, 1.43784189e+01, 1.97715755e-03]), + array([-0.06331585, -8.01569271, 0.02197669])]} +{'AngularVelocity': array([ 0.00384707, -0.02626842, 2.66040754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.082876205444336, + 'FR_Wheel_Angle': -11.823535919189453, + 'Location': array([ -1.35076201, -26.24892235, 0.17075105]), + 'Rotation': array([-4.16231714e-02, -6.09451866e+01, 5.88541888e-02]), + 'Velocity': array([-0.21633905, 0.55001915, 0.00087121]), + 'brake_input': 0.0, + 'camera_location': array([-6.73689127, 12.56615067, -0.56774747]), + 'camera_rotation': array([ -8.24743271, -13.00259495, -2.24917507]), + 'current_gear_input': False, + 'focus_actor_dist': 1064.2515869140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -547.43908691, -2466.30810547, 85.75991058]), + 'frame': 28263, + 'frame_number': 28263, + 'framesequence': 108682, + 'gaze_dir': array([ 0.99293518, -0.04827881, 0.10663605]), + 'gaze_origin': array([-2.98579264, 0.03032608, -0.10178681]), + 'gaze_valid': True, + 'gaze_vergence': 137.43780517578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99295044, -0.03082275, 0.11436462]), + 'left_gaze_origin': array([-2.88054371, 2.89090586, -0.08062287]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1158447265625, + 'left_pupil_posn': array([ 0.21094465, -0.11155438]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99291992, -0.06573486, 0.09890747]), + 'right_gaze_origin': array([-3.0910418 , -2.83025384, -0.12295075]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.090179443359375, + 'right_pupil_posn': array([-0.25709128, -0.21329474]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.006830042693763971, + 'throttle_input': 0.0, + 'timestamp': 914.9849264770746, + 'timestamp_carla': 914985, + 'timestamp_device': 4068414, + 'timestamp_stream': 914.9849264770746, + 'transform': [array([1.83897305e+00, 1.43456621e+01, 2.92245857e-03]), + array([-0.06363004, -8.01484203, 0.02019452])]} +{'AngularVelocity': array([ 0.06370349, -0.02889087, 2.83788037]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.148045539855957, + 'FR_Wheel_Angle': -13.489333152770996, + 'Location': array([ -1.40705228, -26.11670303, 0.17081827]), + 'Rotation': array([-4.24496233e-02, -6.03028488e+01, 5.82352653e-02]), + 'Velocity': array([-0.19175965, 0.50184482, 0.00065671]), + 'brake_input': 0.0, + 'camera_location': array([-6.71550179, 12.61696815, -0.53970623]), + 'camera_rotation': array([ -8.11704445, -12.83210182, -2.28409696]), + 'current_gear_input': False, + 'focus_actor_dist': 1814.2958984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -726.41564941, -3197.30908203, 64.21975708]), + 'frame': 28264, + 'frame_number': 28264, + 'framesequence': 108686, + 'gaze_dir': array([ 0.99299622, -0.04956055, 0.10532379]), + 'gaze_origin': array([-2.9846499 , 0.0324585 , -0.10123596]), + 'gaze_valid': True, + 'gaze_vergence': 135.28021240234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9931488 , -0.03115845, 0.11250305]), + 'left_gaze_origin': array([-2.87988305, 2.89233708, -0.08045807]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.11627197265625, + 'left_pupil_posn': array([ 0.20920932, -0.11157393]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99284363, -0.06796265, 0.09814453]), + 'right_gaze_origin': array([-3.0894165 , -2.82742 , -0.12201386]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1094970703125, + 'right_pupil_posn': array([-0.25912005, -0.21268618]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.007782220374792814, + 'throttle_input': 0.0238040741533041, + 'timestamp': 915.0174424760044, + 'timestamp_carla': 915018, + 'timestamp_device': 4068447, + 'timestamp_stream': 915.0174424760044, + 'transform': [array([1.84400392e+00, 1.43137341e+01, 4.11699293e-03]), + array([-0.06441551, -8.02282524, 0.01790622])]} +{'AngularVelocity': array([-1.24292425e-03, -7.89314974e-03, 3.48205185e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.17169761657715, + 'FR_Wheel_Angle': -14.969307899475098, + 'Location': array([ -1.45306945, -26.00714111, 0.17087336]), + 'Rotation': array([-4.38771322e-02, -5.96962471e+01, 5.79462536e-02]), + 'Velocity': array([-1.71416298e-01, 4.49831218e-01, 2.05430973e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.72946978, 12.65453148, -0.56279153]), + 'camera_rotation': array([ -8.26366138, -12.72006989, -2.09457612]), + 'current_gear_input': False, + 'focus_actor_dist': 1810.0863037109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -722.27429199, -3197.33203125, 65.94464874]), + 'frame': 28265, + 'frame_number': 28265, + 'framesequence': 108690, + 'gaze_dir': array([ 0.9931488 , -0.05273438, 0.10227966]), + 'gaze_origin': array([-2.99414921, 0.03224793, -0.09476852]), + 'gaze_valid': True, + 'gaze_vergence': 140.43264770507812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99382019, -0.03302002, 0.105896 ]), + 'left_gaze_origin': array([-2.87922239, 2.89145994, -0.08062287]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1351165771484375, + 'left_pupil_posn': array([ 0.20827091, -0.11145055]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99247742, -0.07244873, 0.09866333]), + 'right_gaze_origin': array([-3.10907602, -2.8269639 , -0.1089142 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9621124267578125, + 'right_pupil_posn': array([-0.26011711, -0.20981944]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.008478042669594288, + 'throttle_input': 0.12300297617912292, + 'timestamp': 915.0521765761077, + 'timestamp_carla': 915053, + 'timestamp_device': 4068481, + 'timestamp_stream': 915.0521765761077, + 'transform': [array([1.84813559e+00, 1.42810669e+01, 5.37868496e-03]), + array([-0.06514634, -8.02910423, 0.01544033])]} +{'AngularVelocity': array([ 0.03855783, -0.03591286, 3.30730867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.518604278564453, + 'FR_Wheel_Angle': -15.783388137817383, + 'Location': array([ -1.49688351, -25.90195656, 0.17093599]), + 'Rotation': array([-4.71214727e-02, -5.90619125e+01, 5.59298433e-02]), + 'Velocity': array([-1.75312892e-01, 4.80250090e-01, 1.41992568e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.73911285, 12.67585564, -0.59120095]), + 'camera_rotation': array([ -8.38749886, -12.72999954, -1.99057233]), + 'current_gear_input': False, + 'focus_actor_dist': 1807.5435791015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -723.05700684, -3197.17602539, 55.97935486]), + 'frame': 28266, + 'frame_number': 28266, + 'framesequence': 108694, + 'gaze_dir': array([ 0.9930191 , -0.05146027, 0.10405731]), + 'gaze_origin': array([-2.9940958 , 0.03265839, -0.09414597]), + 'gaze_valid': True, + 'gaze_vergence': 140.38336181640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99403381, -0.03111267, 0.10446167]), + 'left_gaze_origin': array([-2.88054371, 2.89196324, -0.07975007]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1401824951171875, + 'left_pupil_posn': array([ 0.20815861, -0.10944629]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99200439, -0.07180786, 0.10365295]), + 'right_gaze_origin': array([-3.1076479 , -2.82664657, -0.10854188]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0079803466796875, + 'right_pupil_posn': array([-0.25966001, -0.20989966]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00875270925462246, + 'throttle_input': 0.21824978291988373, + 'timestamp': 915.08493167907, + 'timestamp_carla': 915085, + 'timestamp_device': 4068514, + 'timestamp_stream': 915.08493167907, + 'transform': [array([1.85194337e+00, 1.42511444e+01, 6.33676536e-03]), + array([-0.06554249, -8.03493881, 0.01360354])]} +{'AngularVelocity': array([ 0.02990216, -0.04439497, 3.08026338]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.344724655151367, + 'FR_Wheel_Angle': -15.513276100158691, + 'Location': array([ -1.53606057, -25.80885506, 0.17096707]), + 'Rotation': array([-4.68687564e-02, -5.84705696e+01, 5.71573675e-02]), + 'Velocity': array([-1.72875971e-01, 4.62501377e-01, 1.40209202e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.72984982, 12.71528053, -0.60188824]), + 'camera_rotation': array([ -8.34013844, -12.73993778, -2.04878068]), + 'current_gear_input': False, + 'focus_actor_dist': 1803.7486572265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -720.07055664, -3197.17041016, 55.62265015]), + 'frame': 28267, + 'frame_number': 28267, + 'framesequence': 108698, + 'gaze_dir': array([ 0.99319458, -0.0534668 , 0.10095215]), + 'gaze_origin': array([-2.99586272, 0.0329834 , -0.0918892 ]), + 'gaze_valid': True, + 'gaze_vergence': 127.48582458496094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99414062, -0.03131104, 0.10343933]), + 'left_gaze_origin': array([-2.88487411, 2.89247918, -0.07468567]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.134307861328125, + 'left_pupil_posn': array([ 0.20656359, -0.10863698]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99224854, -0.07562256, 0.09846497]), + 'right_gaze_origin': array([-3.10685134, -2.82651234, -0.10909272]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.01092529296875, + 'right_pupil_posn': array([-0.25983149, -0.21045876]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009100619703531265, + 'throttle_input': 0.2896620035171509, + 'timestamp': 915.119675077498, + 'timestamp_carla': 915120, + 'timestamp_device': 4068547, + 'timestamp_stream': 915.119675077498, + 'transform': [array([1.85582483e+00, 1.42198439e+01, 6.84116362e-03]), + array([-0.06572691, -8.04088783, 0.01261602])]} +{'AngularVelocity': array([-0.07513781, -0.00389552, 3.73456359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.032062530517578, + 'FR_Wheel_Angle': -14.5677490234375, + 'Location': array([ -1.6081773 , -25.64873886, 0.1711141 ]), + 'Rotation': array([-5.49010560e-02, -5.75117874e+01, 5.52896820e-02]), + 'Velocity': array([-2.75804311e-01, 6.44849539e-01, 4.56128124e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.69662476, 12.7493248 , -0.58775944]), + 'camera_rotation': array([ -8.2471323 , -12.70269012, -1.97049987]), + 'current_gear_input': False, + 'focus_actor_dist': 2536.66650390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -901.66772461, -3909.17822266, 17.67403412]), + 'frame': 28268, + 'frame_number': 28268, + 'framesequence': 108702, + 'gaze_dir': array([ 0.99337006, -0.05155945, 0.10062408]), + 'gaze_origin': array([-2.99881053, 0.03590851, -0.0927475 ]), + 'gaze_valid': True, + 'gaze_vergence': 138.20680236816406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9940033 , -0.03161621, 0.104599 ]), + 'left_gaze_origin': array([-2.8923707 , 2.89820886, -0.07548981]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15338134765625, + 'left_pupil_posn': array([ 0.20427382, -0.11134684]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99273682, -0.07150269, 0.09664917]), + 'right_gaze_origin': array([-3.10525084, -2.8263917 , -0.11000519]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.033905029296875, + 'right_pupil_posn': array([-0.26001418, -0.21042144]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009338663890957832, + 'throttle_input': 0.31348133087158203, + 'timestamp': 915.1502837762237, + 'timestamp_carla': 915151, + 'timestamp_device': 4068581, + 'timestamp_stream': 915.1502837762237, + 'transform': [array([1.85951447e+00, 1.41919947e+01, 6.80696452e-03]), + array([-0.06565861, -8.0466671 , 0.01274336])]} +{'AngularVelocity': array([-0.02506451, -0.00698442, 2.41580057]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.404799461364746, + 'FR_Wheel_Angle': -13.1356201171875, + 'Location': array([ -1.66784894, -25.5242939 , 0.17109907]), + 'Rotation': array([-4.28184532e-02, -5.68036385e+01, 6.12113662e-02]), + 'Velocity': array([-0.20792314, 0.45141712, 0.00054067]), + 'brake_input': 0.0, + 'camera_location': array([-6.69743538, 12.76972961, -0.58676755]), + 'camera_rotation': array([ -8.22813702, -12.53548622, -1.82496047]), + 'current_gear_input': False, + 'focus_actor_dist': 2616.21923828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -914.25299072, -3991.19018555, 17.68645477]), + 'frame': 28269, + 'frame_number': 28269, + 'framesequence': 108706, + 'gaze_dir': array([ 0.99272919, -0.0533371 , 0.10585785]), + 'gaze_origin': array([-2.99332976, 0.03654404, -0.09609909]), + 'gaze_valid': True, + 'gaze_vergence': 136.685791015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9934082 , -0.03308105, 0.10964966]), + 'left_gaze_origin': array([-2.88914061, 2.89904785, -0.07777558]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1303253173828125, + 'left_pupil_posn': array([ 0.20288694, -0.11022794]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99205017, -0.07359314, 0.10206604]), + 'right_gaze_origin': array([-3.09751916, -2.82595992, -0.11442262]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0669097900390625, + 'right_pupil_posn': array([-0.26078987, -0.21023464]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009338663890957832, + 'throttle_input': 0.31348133087158203, + 'timestamp': 915.1838966757059, + 'timestamp_carla': 915184, + 'timestamp_device': 4068614, + 'timestamp_stream': 915.1838966757059, + 'transform': [array([1.86319733e+00, 1.41605177e+01, 6.11301418e-03]), + array([-0.06539223, -8.05224037, 0.01410302])]} +{'AngularVelocity': array([-0.02646778, 0.01982642, 0.86546725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.461568832397461, + 'FR_Wheel_Angle': -10.021890640258789, + 'Location': array([ -1.71150422, -25.43944359, 0.17110682]), + 'Rotation': array([-3.92462648e-02, -5.63929253e+01, 6.19978495e-02]), + 'Velocity': array([-0.12904844, 0.2469565 , 0.0015456 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.74005795, 12.80263233, -0.60843849]), + 'camera_rotation': array([ -8.36881828, -12.45057201, -1.89704335]), + 'current_gear_input': False, + 'focus_actor_dist': 1793.8233642578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -714.87731934, -3197.31274414, 64.39083099]), + 'frame': 28270, + 'frame_number': 28270, + 'framesequence': 108710, + 'gaze_dir': array([ 0.99328613, -0.0528183 , 0.10173035]), + 'gaze_origin': array([-3.01526213, 0.03987656, -0.08341141]), + 'gaze_valid': True, + 'gaze_vergence': 167.7619171142578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99328613, -0.03936768, 0.10876465]), + 'left_gaze_origin': array([-2.91759491, 2.90241885, -0.06122895]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1092987060546875, + 'left_pupil_posn': array([ 0.20347691, -0.10701478]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99328613, -0.06626892, 0.09469604]), + 'right_gaze_origin': array([-3.11292887, -2.82266545, -0.10559388]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9912109375, + 'right_pupil_posn': array([-0.26526392, -0.20732975]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009558397345244884, + 'throttle_input': 0.31348133087158203, + 'timestamp': 915.2174627780914, + 'timestamp_carla': 915218, + 'timestamp_device': 4068647, + 'timestamp_stream': 915.2174627780914, + 'transform': [array([1.86761105e+00, 1.41275892e+01, 5.03955828e-03]), + array([-0.06498925, -8.05920601, 0.01621106])]} +{'AngularVelocity': array([0.06180585, 0.00860715, 0.61525565]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.197099685668945, + 'FR_Wheel_Angle': -8.255047798156738, + 'Location': array([ -1.73523271, -25.39635277, 0.17119314]), + 'Rotation': array([-4.30575088e-02, -5.62281342e+01, 5.89712150e-02]), + 'Velocity': array([-9.67141241e-02, 1.77485362e-01, -4.72450229e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.79793358, 12.83097267, -0.61970454]), + 'camera_rotation': array([ -8.4762373 , -12.36117077, -2.00406909]), + 'current_gear_input': False, + 'focus_actor_dist': 2561.4462890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -893.32971191, -3945.59472656, 17.66523743]), + 'frame': 28271, + 'frame_number': 28271, + 'framesequence': 108714, + 'gaze_dir': array([ 0.99316406, -0.05581665, 0.10074615]), + 'gaze_origin': array([-3.01414514, 0.04000244, -0.08379288]), + 'gaze_valid': True, + 'gaze_vergence': 144.73123168945312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99345398, -0.03855896, 0.10742188]), + 'left_gaze_origin': array([-2.91444564, 2.90248108, -0.06233216]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.099639892578125, + 'left_pupil_posn': array([ 0.20105565, -0.10733283]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99287415, -0.07307434, 0.09407043]), + 'right_gaze_origin': array([-3.11384439, -2.82247615, -0.10525361]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.009979248046875, + 'right_pupil_posn': array([-0.26512605, -0.20779479]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.3333180844783783, + 'timestamp': 915.2515706792474, + 'timestamp_carla': 915252, + 'timestamp_device': 4068681, + 'timestamp_stream': 915.2515706792474, + 'transform': [array([1.87223995e+00, 1.40925941e+01, 3.82944103e-03]), + array([-0.06455211, -8.0664978 , 0.01858201])]} +{'AngularVelocity': array([ 0.00291444, -0.00478959, 0.47754928]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.078973770141602, + 'FR_Wheel_Angle': -7.497259140014648, + 'Location': array([ -1.75462425, -25.3627224 , 0.17121236]), + 'Rotation': array([-4.67458107e-02, -5.61218987e+01, 5.68993688e-02]), + 'Velocity': array([-8.54805857e-02, 1.52291805e-01, -1.06058120e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.80297422, 12.85280037, -0.57781667]), + 'camera_rotation': array([ -8.25776672, -12.21535492, -1.90663671]), + 'current_gear_input': False, + 'focus_actor_dist': 2403.197021484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -859.66027832, -3793.87792969, 17.63155365]), + 'frame': 28272, + 'frame_number': 28272, + 'framesequence': 108718, + 'gaze_dir': array([ 0.9921875 , -0.05886078, 0.10809326]), + 'gaze_origin': array([-2.97331786, 0.04168091, -0.10281068]), + 'gaze_valid': True, + 'gaze_vergence': 122.29496765136719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99203491, -0.04193115, 0.11865234]), + 'left_gaze_origin': array([-2.8828311 , 2.90324569, -0.0778946 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0738525390625, + 'left_pupil_posn': array([ 0.19922483, -0.11055148]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99234009, -0.07579041, 0.09753418]), + 'right_gaze_origin': array([-3.06380486, -2.81988382, -0.12772675]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0064849853515625, + 'right_pupil_posn': array([-0.26786476, -0.20966923]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.3531548082828522, + 'timestamp': 915.2832294777036, + 'timestamp_carla': 915284, + 'timestamp_device': 4068714, + 'timestamp_stream': 915.2832294777036, + 'transform': [array([1.87777710e+00, 1.40582991e+01, 2.65756599e-03]), + array([-0.06411498, -8.07563114, 0.02091772])]} +{'AngularVelocity': array([ 0.00293665, -0.00155436, 0.32993609]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.15188217163086, + 'FR_Wheel_Angle': -7.619149208068848, + 'Location': array([ -1.77196562, -25.33297157, 0.17121693]), + 'Rotation': array([-4.66911718e-02, -5.60318451e+01, 5.60311452e-02]), + 'Velocity': array([-5.88281713e-02, 1.04498066e-01, 1.20544428e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.8233614 , 12.87708187, -0.54091877]), + 'camera_rotation': array([ -7.99286461, -12.00253582, -1.86505306]), + 'current_gear_input': False, + 'focus_actor_dist': 1783.8221435546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -713.05603027, -3197.16796875, 67.65216827]), + 'frame': 28273, + 'frame_number': 28273, + 'framesequence': 108722, + 'gaze_dir': array([ 0.99221039, -0.06065369, 0.10675812]), + 'gaze_origin': array([-2.96754313, 0.04321747, -0.10636903]), + 'gaze_valid': True, + 'gaze_vergence': 125.95983123779297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99232483, -0.0425415 , 0.11598206]), + 'left_gaze_origin': array([-2.87520599, 2.90409112, -0.08196869]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0432586669921875, + 'left_pupil_posn': array([ 0.1975491 , -0.11182892]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99209595, -0.07876587, 0.09753418]), + 'right_gaze_origin': array([-3.05988026, -2.81765604, -0.13076936]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.03790283203125, + 'right_pupil_posn': array([-0.26961732, -0.21181095]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.37299153208732605, + 'timestamp': 915.3168464787304, + 'timestamp_carla': 915317, + 'timestamp_device': 4068747, + 'timestamp_stream': 915.3168464787304, + 'transform': [array([1.88418305e+00, 1.40202913e+01, 1.59828179e-03]), + array([-0.06374615, -8.08631325, 0.02299662])]} +{'AngularVelocity': array([0.02411453, 0.01580708, 0.88178653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.689942359924316, + 'FR_Wheel_Angle': -9.195643424987793, + 'Location': array([ -1.78294623, -25.31435013, 0.17125075]), + 'Rotation': array([-4.66911718e-02, -5.59695282e+01, 5.58139868e-02]), + 'Velocity': array([-0.0412016 , 0.06956037, 0.00029209]), + 'brake_input': 0.0, + 'camera_location': array([-6.84478235, 12.91015625, -0.51596576]), + 'camera_rotation': array([ -7.85594654, -11.84516716, -1.94613123]), + 'current_gear_input': False, + 'focus_actor_dist': 1779.355224609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -708.66455078, -3197.16845703, 73.72858429]), + 'frame': 28274, + 'frame_number': 28274, + 'framesequence': 108726, + 'gaze_dir': array([ 0.99185181, -0.06507111, 0.10704041]), + 'gaze_origin': array([-2.96198368, 0.04684144, -0.10857773]), + 'gaze_valid': True, + 'gaze_vergence': 102.13652038574219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99165344, -0.04624939, 0.12030029]), + 'left_gaze_origin': array([-2.8640871 , 2.90963769, -0.08609162]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.02099609375, + 'left_pupil_posn': array([ 0.19191778, -0.11361837]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99205017, -0.08389282, 0.09378052]), + 'right_gaze_origin': array([-3.05988026, -2.81595469, -0.13106385]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0174560546875, + 'right_pupil_posn': array([-0.27205414, -0.21051824]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.38887616991996765, + 'timestamp': 915.3509063757956, + 'timestamp_carla': 915351, + 'timestamp_device': 4068781, + 'timestamp_stream': 915.3509063757956, + 'transform': [array([1.89205956e+00, 1.39801683e+01, 7.60173774e-04]), + array([-0.06344562, -8.09980488, 0.02464219])]} +{'AngularVelocity': array([-0.01603837, -0.01601091, -0.47254363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.845340728759766, + 'FR_Wheel_Angle': -10.864592552185059, + 'Location': array([ -1.78914726, -25.30353928, 0.17127134]), + 'Rotation': array([-4.79752459e-02, -5.59238739e+01, 5.50900400e-02]), + 'Velocity': array([-0.00933571, 0.02254394, 0.00045031]), + 'brake_input': 0.0, + 'camera_location': array([-6.86959553, 12.92987442, -0.48557362]), + 'camera_rotation': array([ -7.77274799, -11.67847824, -1.89835453]), + 'current_gear_input': False, + 'focus_actor_dist': 1776.2928466796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -711.32299805, -3197.16796875, 78.30323792]), + 'frame': 28275, + 'frame_number': 28275, + 'framesequence': 108730, + 'gaze_dir': array([ 0.9916153 , -0.06620026, 0.10839081]), + 'gaze_origin': array([-2.97009659, 0.04941788, -0.10847549]), + 'gaze_valid': True, + 'gaze_vergence': 107.09105682373047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.991745 , -0.04566956, 0.11979675]), + 'left_gaze_origin': array([-2.88582635, 2.91340804, -0.08408356]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0236968994140625, + 'left_pupil_posn': array([ 0.18862116, -0.11520052]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9914856 , -0.08673096, 0.09698486]), + 'right_gaze_origin': array([-3.0543673 , -2.81457233, -0.13286744]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9971923828125, + 'right_pupil_posn': array([-0.27276784, -0.21074593]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.400778204202652, + 'timestamp': 915.3836344778538, + 'timestamp_carla': 915384, + 'timestamp_device': 4068814, + 'timestamp_stream': 915.3836344778538, + 'transform': [array([ 1.90109468e+00, 1.39395885e+01, -9.09423834e-05]), + array([-0.06319974, -8.11561584, 0.0263385 ])]} +{'AngularVelocity': array([0.02900633, 0.02135959, 0.87136495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.175419807434082, + 'FR_Wheel_Angle': -12.786948204040527, + 'Location': array([ -1.79384458, -25.29509163, 0.17127936]), + 'Rotation': array([-4.95940000e-02, -5.58720512e+01, 5.46507314e-02]), + 'Velocity': array([-0.03143283, 0.05715337, 0.00016704]), + 'brake_input': 0.0, + 'camera_location': array([-6.87819386, 12.93110085, -0.45717105]), + 'camera_rotation': array([ -7.67724848, -11.51085186, -1.80438161]), + 'current_gear_input': False, + 'focus_actor_dist': 1771.4666748046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -707.33990479, -3197.16796875, 83.55331421]), + 'frame': 28276, + 'frame_number': 28276, + 'framesequence': 108734, + 'gaze_dir': array([ 0.99105072, -0.08541107, 0.09859467]), + 'gaze_origin': array([-3.00564051, 0.06764603, -0.09762574]), + 'gaze_valid': True, + 'gaze_vergence': 73.96817016601562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99081421, -0.06552124, 0.11819458]), + 'left_gaze_origin': array([-2.94946909, 2.93436599, -0.06190949]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.990264892578125, + 'left_pupil_posn': array([ 0.16883492, -0.1186353 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99128723, -0.1053009 , 0.07899475]), + 'right_gaze_origin': array([-3.06181192, -2.79907393, -0.13334198]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.843048095703125, + 'right_pupil_posn': array([-0.29041517, -0.21262681]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.40871289372444153, + 'timestamp': 915.4168593771756, + 'timestamp_carla': 915417, + 'timestamp_device': 4068847, + 'timestamp_stream': 915.4168593771756, + 'transform': [array([ 1.90746665e+00, 1.38971882e+01, -8.18176253e-04]), + array([-0.06292653, -8.12604809, 0.02778247])]} +{'AngularVelocity': array([-0.00814405, 0.0183196 , 2.37125468]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.337675094604492, + 'FR_Wheel_Angle': -14.330916404724121, + 'Location': array([ -1.815552 , -25.25328064, 0.17137612]), + 'Rotation': array([-6.13350943e-02, -5.56394196e+01, 4.88811508e-02]), + 'Velocity': array([-1.49269313e-01, 3.08008403e-01, 7.51400003e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.88514423, 12.94272232, -0.44909328]), + 'camera_rotation': array([ -7.62983322, -11.44685173, -1.91543889]), + 'current_gear_input': False, + 'focus_actor_dist': 1775.2337646484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -735.82446289, -3197.16723633, 68.54961395]), + 'frame': 28277, + 'frame_number': 28277, + 'framesequence': 108738, + 'gaze_dir': array([ 0.49558258, -0.04563141, 0.0480957 ]), + 'gaze_origin': array([-3.12538791, 0.09232636, -0.04750824]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.7818045616149902, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99116516, -0.09126282, 0.09619141]), + 'left_gaze_origin': array([-3.03534555, 2.96494746, -0.02344971]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.6932393312454224, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.21543002, -2.7802949 , -0.07156678]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8047027587890625, + 'right_pupil_posn': array([-0.31356794, -0.20855236]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.40871289372444153, + 'timestamp': 915.4503703787923, + 'timestamp_carla': 915451, + 'timestamp_device': 4068880, + 'timestamp_stream': 915.4503703787923, + 'transform': [array([ 1.91355836e+00, 1.38524609e+01, -1.63448334e-03]), + array([-0.06264649, -8.13581562, 0.02939793])]} +{'AngularVelocity': array([-0.03038997, 0.02883599, 2.23788238]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.99905776977539, + 'FR_Wheel_Angle': -15.534485816955566, + 'Location': array([ -1.84851134, -25.18819046, 0.17134237]), + 'Rotation': array([-5.19982278e-02, -5.52288628e+01, 5.35237193e-02]), + 'Velocity': array([-1.28375590e-01, 2.62821108e-01, -8.70990698e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.88731718, 12.93181992, -0.46108338]), + 'camera_rotation': array([ -7.62760639, -11.49065685, -1.94535327]), + 'current_gear_input': False, + 'focus_actor_dist': 1773.5938720703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -743.81402588, -3197.21362305, 65.32659149]), + 'frame': 28278, + 'frame_number': 28278, + 'framesequence': 108742, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.021359199658036232, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.13051605, -2.81063867, -0.19549562]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.4126802384853363, + 'timestamp': 915.483495477587, + 'timestamp_carla': 915484, + 'timestamp_device': 4068914, + 'timestamp_stream': 915.483495477587, + 'transform': [array([ 1.91975999e+00, 1.38060179e+01, -2.51585012e-03]), + array([-0.06234596, -8.14573669, 0.03114935])]} +{'AngularVelocity': array([0.0163957 , 0.01256194, 0.25840974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.584362030029297, + 'FR_Wheel_Angle': -15.852663040161133, + 'Location': array([ -1.86877966, -25.14886093, 0.1713392 ]), + 'Rotation': array([-4.71487939e-02, -5.49628181e+01, 5.55986129e-02]), + 'Velocity': array([-8.53868201e-02, 1.79404736e-01, -8.05854797e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.90775824, 12.90091133, -0.47420126]), + 'camera_rotation': array([ -7.70444632, -11.641078 , -1.99820542]), + 'current_gear_input': False, + 'focus_actor_dist': 880.5189819335938, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -431.76385498, -2353.23095703, 17.22426605]), + 'frame': 28279, + 'frame_number': 28279, + 'framesequence': 108746, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.80293417, -2.80816197, 0.03490753]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.4166475832462311, + 'timestamp': 915.5173630788922, + 'timestamp_carla': 915518, + 'timestamp_device': 4068947, + 'timestamp_stream': 915.5173630788922, + 'transform': [array([ 1.92641306e+00, 1.37561483e+01, -3.39986803e-03]), + array([-0.0620591 , -8.15639496, 0.03289495])]} +{'AngularVelocity': array([-0.03679264, -0.00399954, 2.91769361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.590147018432617, + 'FR_Wheel_Angle': -15.827741622924805, + 'Location': array([ -1.90993524, -25.06897926, 0.17146593]), + 'Rotation': array([-5.84664159e-02, -5.44308662e+01, 4.97667119e-02]), + 'Velocity': array([-0.18060647, 0.38212714, 0.00054744]), + 'brake_input': 0.0, + 'camera_location': array([-6.91573334, 12.85580254, -0.46982166]), + 'camera_rotation': array([ -7.6910181, -11.8805275, -2.0148499]), + 'current_gear_input': False, + 'focus_actor_dist': 871.8640747070312, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -432.59585571, -2348.75366211, 17.22587585]), + 'frame': 28280, + 'frame_number': 28280, + 'framesequence': 108751, + 'gaze_dir': array([ 0.49680328, -0.0476532 , 0.03025055]), + 'gaze_origin': array([-3.55139637, 0.07434769, 0.06598893]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.48547035455703735, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99360657, -0.0953064 , 0.0605011 ]), + 'left_gaze_origin': array([-3.91898966, 2.94200611, 0.18873444]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.15580029785633087, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.18380308, -2.79331088, -0.0567566 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6941070556640625, + 'right_pupil_posn': array([-0.30562598, -0.20380306]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009595019742846489, + 'throttle_input': 0.4166475832462311, + 'timestamp': 915.5535623766482, + 'timestamp_carla': 915554, + 'timestamp_device': 4068989, + 'timestamp_stream': 915.5535623766482, + 'transform': [array([ 1.93388963e+00, 1.37002764e+01, -4.20919387e-03]), + array([-0.06180638, -8.16838455, 0.03446474])]} +{'AngularVelocity': array([-0.01350983, -0.00430356, 3.8552084 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.581880569458008, + 'FR_Wheel_Angle': -15.795547485351562, + 'Location': array([ -1.95292699, -24.9872036 , 0.17149626]), + 'Rotation': array([-5.64924926e-02, -5.38728600e+01, 5.11003993e-02]), + 'Velocity': array([-2.12344810e-01, 4.35931623e-01, 1.48248670e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.90358734, 12.81440639, -0.44695917]), + 'camera_rotation': array([ -7.64744139, -12.13304043, -2.05028272]), + 'current_gear_input': False, + 'focus_actor_dist': 944.4592895507812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -538.80847168, -2405.58984375, 62.69441223]), + 'frame': 28281, + 'frame_number': 28281, + 'framesequence': 108754, + 'gaze_dir': array([ 0.49462891, -0.0411377 , 0.06038666]), + 'gaze_origin': array([-3.04899597, 0.07842713, -0.06926651]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.6265552043914795, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98925781, -0.08227539, 0.12077332]), + 'left_gaze_origin': array([-2.9910388 , 2.95050359, -0.03383484]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.563351571559906, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.10695362, -2.79364944, -0.10469819]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.987396240234375, + 'right_pupil_posn': array([-0.30019546, -0.20128739]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.009704886004328728, + 'throttle_input': 0.4166475832462311, + 'timestamp': 915.5853394791484, + 'timestamp_carla': 915586, + 'timestamp_device': 4069014, + 'timestamp_stream': 915.5853394791484, + 'transform': [array([ 1.94048989e+00, 1.36486273e+01, -5.05743036e-03]), + array([-0.06154683, -8.17888451, 0.03619413])]} +{'AngularVelocity': array([ 0.04583676, -0.03121306, 4.14050436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.51142120361328, + 'FR_Wheel_Angle': -15.737972259521484, + 'Location': array([ -2.01903129, -24.86465836, 0.17159571]), + 'Rotation': array([-6.06042668e-02, -5.30636635e+01, 4.88247499e-02]), + 'Velocity': array([-3.05383474e-01, 6.15129411e-01, 5.58543194e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.88294554, 12.76440239, -0.43711698]), + 'camera_rotation': array([ -7.58410501, -12.38157082, -2.05993009]), + 'current_gear_input': False, + 'focus_actor_dist': 1754.557373046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -746.76342773, -3197.16772461, 109.04182434]), + 'frame': 28282, + 'frame_number': 28282, + 'framesequence': 108758, + 'gaze_dir': array([ 0.99075317, -0.09692383, 0.09026337]), + 'gaze_origin': array([-3.02335739, 0.07698441, -0.08263169]), + 'gaze_valid': True, + 'gaze_vergence': 24.324140548706055, + 'handbrake_input': False, + 'left_eye_openness': 0.7511609792709351, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98883057, -0.09016418, 0.11857605]), + 'left_gaze_origin': array([-3.00168467, 2.94814014, -0.03515167]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.184295654296875, + 'left_pupil_posn': array([ 0.16067851, -0.11659813]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.8361257910728455, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99267578, -0.10368347, 0.06195068]), + 'right_gaze_origin': array([-3.04503036, -2.79417133, -0.13011169]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.069854736328125, + 'right_pupil_posn': array([-0.30215853, -0.20757711]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00994293112307787, + 'throttle_input': 0.42061492800712585, + 'timestamp': 915.6171404793859, + 'timestamp_carla': 915618, + 'timestamp_device': 4069047, + 'timestamp_stream': 915.6171404793859, + 'transform': [array([ 1.94778466e+00, 1.35943565e+01, -5.90213761e-03]), + array([-0.06130094, -8.19066906, 0.03790015])]} +{'AngularVelocity': array([-0.04038138, 0.05377274, 5.31077576]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.42536735534668, + 'FR_Wheel_Angle': -15.699014663696289, + 'Location': array([ -2.12564254, -24.67548943, 0.17173113]), + 'Rotation': array([-6.43881932e-02, -5.18183517e+01, 4.80837934e-02]), + 'Velocity': array([-4.53039706e-01, 8.31548154e-01, 6.07757538e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.88578415, 12.73353386, -0.44051671]), + 'camera_rotation': array([ -7.63617134, -12.53733158, -2.03143239]), + 'current_gear_input': False, + 'focus_actor_dist': 941.4572143554688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -548.9342041 , -2412.48974609, 92.50778198]), + 'frame': 28283, + 'frame_number': 28283, + 'framesequence': 108762, + 'gaze_dir': array([ 0.98989105, -0.10049438, 0.09745789]), + 'gaze_origin': array([-3.05635858, 0.07546921, -0.0796196 ]), + 'gaze_valid': True, + 'gaze_vergence': 57.40458297729492, + 'handbrake_input': False, + 'left_eye_openness': 0.8926887512207031, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98887634, -0.09112549, 0.11743164]), + 'left_gaze_origin': array([-3.06642175, 2.9478929 , -0.0252533 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0626220703125, + 'left_pupil_posn': array([ 0.15915549, -0.11681795]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9752403497695923, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99090576, -0.10986328, 0.07748413]), + 'right_gaze_origin': array([-3.04629517, -2.79695439, -0.13398591]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1311187744140625, + 'right_pupil_posn': array([-0.30063856, -0.21084905]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.010638752020895481, + 'throttle_input': 0.42061492800712585, + 'timestamp': 915.6502614766359, + 'timestamp_carla': 915651, + 'timestamp_device': 4069080, + 'timestamp_stream': 915.6502614766359, + 'transform': [array([ 1.95607162e+00, 1.35352068e+01, -6.65184017e-03]), + array([-0.06116434, -8.20424938, 0.03939329])]} +{'AngularVelocity': array([-3.48947523e-03, 5.86957391e-03, 7.05396557e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.264789581298828, + 'FR_Wheel_Angle': -15.560032844543457, + 'Location': array([ -2.24531364, -24.47480392, 0.1719687 ]), + 'Rotation': array([-7.34586790e-02, -5.04823799e+01, 4.40420322e-02]), + 'Velocity': array([-6.55115783e-01, 1.15877414e+00, 8.75525468e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.89079428, 12.71160889, -0.45206851]), + 'camera_rotation': array([ -7.71112585, -12.63003349, -2.09575438]), + 'current_gear_input': False, + 'focus_actor_dist': 937.2637939453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -553.70178223, -2412.21679688, 98.61203003]), + 'frame': 28284, + 'frame_number': 28284, + 'framesequence': 108767, + 'gaze_dir': array([ 0.99029541, -0.09803772, 0.09712219]), + 'gaze_origin': array([-2.97997522, 0.07107849, -0.10685197]), + 'gaze_valid': True, + 'gaze_vergence': 92.1436538696289, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98976135, -0.08958435, 0.11109924]), + 'left_gaze_origin': array([-2.90899062, 2.9400897 , -0.078125 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.046905517578125, + 'left_pupil_posn': array([ 0.16424942, -0.12052917]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99082947, -0.10649109, 0.08314514]), + 'right_gaze_origin': array([-3.05095983, -2.79793262, -0.13557893]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1253662109375, + 'right_pupil_posn': array([-0.29954284, -0.21524441]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.011737418361008167, + 'throttle_input': 0.42458227276802063, + 'timestamp': 915.6847490780056, + 'timestamp_carla': 915685, + 'timestamp_device': 4069122, + 'timestamp_stream': 915.6847490780056, + 'transform': [array([ 1.96567225e+00, 1.34708576e+01, -7.25561148e-03]), + array([-0.06113702, -8.22026825, 0.04058369])]} +{'AngularVelocity': array([-6.32191673e-02, -4.37147077e-03, 9.27172661e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.044361114501953, + 'FR_Wheel_Angle': -15.438350677490234, + 'Location': array([ -2.39785767, -24.23372078, 0.17210104]), + 'Rotation': array([-6.98250234e-02, -4.88259544e+01, 4.83216830e-02]), + 'Velocity': array([-7.67813981e-01, 1.26784444e+00, 4.77490423e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.88640356, 12.69454575, -0.45849857]), + 'camera_rotation': array([ -7.78724861, -12.63473988, -2.18607378]), + 'current_gear_input': False, + 'focus_actor_dist': 931.927734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -551.56829834, -2413.05712891, 97.20013428]), + 'frame': 28285, + 'frame_number': 28285, + 'framesequence': 108770, + 'gaze_dir': array([ 0.98950195, -0.10466766, 0.09819794]), + 'gaze_origin': array([-2.97285938, 0.06995316, -0.10877533]), + 'gaze_valid': True, + 'gaze_vergence': 129.74102783203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98973083, -0.09211731, 0.10925293]), + 'left_gaze_origin': array([-2.89436054, 2.93780684, -0.08223878]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0336761474609375, + 'left_pupil_posn': array([ 0.16200209, -0.11932766]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98927307, -0.11721802, 0.08714294]), + 'right_gaze_origin': array([-3.05135798, -2.79790044, -0.13531189]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1227569580078125, + 'right_pupil_posn': array([-0.30046356, -0.21577787]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01301919762045145, + 'throttle_input': 0.4285496175289154, + 'timestamp': 915.7175728790462, + 'timestamp_carla': 915718, + 'timestamp_device': 4069147, + 'timestamp_stream': 915.7175728790462, + 'transform': [array([ 1.97587621e+00, 1.34068098e+01, -7.80977216e-03]), + array([-0.06119849, -8.23763371, 0.04171094])]} +{'AngularVelocity': array([-0.02031506, -0.00991775, 9.43521976]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.887300491333008, + 'FR_Wheel_Angle': -16.16073226928711, + 'Location': array([ -2.54070115, -24.02004433, 0.1722165 ]), + 'Rotation': array([ -0.06200445, -47.31137466, 0.0518738 ]), + 'Velocity': array([-7.81999409e-01, 1.23563278e+00, 9.17515717e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.90309954, 12.69216728, -0.47026673]), + 'camera_rotation': array([ -7.85912943, -12.54371643, -2.16134071]), + 'current_gear_input': False, + 'focus_actor_dist': 917.7390747070312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -553.69683838, -2403.84326172, 97.26722717]), + 'frame': 28286, + 'frame_number': 28286, + 'framesequence': 108774, + 'gaze_dir': array([ 0.98901367, -0.10774994, 0.09918213]), + 'gaze_origin': array([-2.96696806, 0.06975022, -0.10977631]), + 'gaze_valid': True, + 'gaze_vergence': 111.91616821289062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98936462, -0.09277344, 0.11192322]), + 'left_gaze_origin': array([-2.88406086, 2.93701935, -0.08459625]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0789642333984375, + 'left_pupil_posn': array([ 0.16055036, -0.11921215]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98866272, -0.12272644, 0.08644104]), + 'right_gaze_origin': array([-3.04987502, -2.79751897, -0.13495637]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1262054443359375, + 'right_pupil_posn': array([-0.30091631, -0.21432817]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014154484495520592, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.7519296780229, + 'timestamp_carla': 915752, + 'timestamp_device': 4069180, + 'timestamp_stream': 915.7519296780229, + 'transform': [array([ 1.98788249e+00, 1.33368979e+01, -8.27869400e-03]), + array([-0.06132143, -8.25845242, 0.04264718])]} +{'AngularVelocity': array([4.46684808e-02, 3.15042422e-03, 8.21730328e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.275114059448242, + 'FR_Wheel_Angle': -17.233047485351562, + 'Location': array([ -2.69063616, -23.80386353, 0.17231058]), + 'Rotation': array([ -0.05355551, -45.71128082, 0.05478001]), + 'Velocity': array([-0.71780354, 1.09367478, 0.00168869]), + 'brake_input': 0.0, + 'camera_location': array([-6.91478729, 12.68644333, -0.4862864 ]), + 'camera_rotation': array([ -7.9050622 , -12.39974594, -2.17900443]), + 'current_gear_input': False, + 'focus_actor_dist': 912.7000122070312, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -553.66040039, -2404.77709961, 97.22784424]), + 'frame': 28287, + 'frame_number': 28287, + 'framesequence': 108778, + 'gaze_dir': array([ 0.98944855, -0.10495758, 0.09816742]), + 'gaze_origin': array([-2.97244048, 0.07175828, -0.10609208]), + 'gaze_valid': True, + 'gaze_vergence': 104.45722961425781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98928833, -0.09371948, 0.11180115]), + 'left_gaze_origin': array([-2.89598846, 2.94022536, -0.07729035]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0734100341796875, + 'left_pupil_posn': array([ 0.16070521, -0.11709046]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98960876, -0.11619568, 0.08453369]), + 'right_gaze_origin': array([-3.04889226, -2.79670882, -0.1348938 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1600189208984375, + 'right_pupil_posn': array([-0.3017897 , -0.21415091]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.015070040710270405, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.7842362783849, + 'timestamp_carla': 915785, + 'timestamp_device': 4069214, + 'timestamp_stream': 915.7842362783849, + 'transform': [array([ 2.00025272e+00, 1.32683277e+01, -8.72543361e-03]), + array([-0.06136242, -8.28018188, 0.04357766])]} +{'AngularVelocity': array([-0.04945183, -0.02330744, 8.22058868]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.46645736694336, + 'FR_Wheel_Angle': -19.571449279785156, + 'Location': array([ -2.82772374, -23.61180878, 0.17245016]), + 'Rotation': array([ -0.05227827, -44.11478424, 0.05247413]), + 'Velocity': array([-6.25463307e-01, 9.56006348e-01, 8.28938442e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.90428638, 12.67756844, -0.49293762]), + 'camera_rotation': array([ -7.9530921 , -12.20454788, -2.33445191]), + 'current_gear_input': False, + 'focus_actor_dist': 915.8014526367188, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -550.06872559, -2415.80126953, 95.46813202]), + 'frame': 28288, + 'frame_number': 28288, + 'framesequence': 108782, + 'gaze_dir': array([9.92233276e-01, 5.56945801e-04, 1.22032166e-01]), + 'gaze_origin': array([-2.93831563, -0.00692062, -0.10453568]), + 'gaze_valid': True, + 'gaze_vergence': 118.12488555908203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99157715, 0.02354431, 0.12727356]), + 'left_gaze_origin': array([-2.77131677, 2.85843825, -0.10934754]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.19671630859375, + 'left_pupil_posn': array([ 0.24585831, -0.10416389]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9928894 , -0.02243042, 0.11679077]), + 'right_gaze_origin': array([-3.10531473, -2.87227941, -0.09972382]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.914459228515625, + 'right_pupil_posn': array([-0.20903033, -0.19590831]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0154362628236413, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.816753976047, + 'timestamp_carla': 915817, + 'timestamp_device': 4069247, + 'timestamp_stream': 915.816753976047, + 'transform': [array([ 2.01355433e+00, 1.31965733e+01, -9.11695417e-03]), + array([-0.06131461, -8.30373859, 0.04439293])]} +{'AngularVelocity': array([-3.73401307e-03, -1.04225567e-02, 6.92325544e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.831140518188477, + 'FR_Wheel_Angle': -21.893871307373047, + 'Location': array([ -2.9371624 , -23.45930672, 0.17254072]), + 'Rotation': array([ -0.04607645, -42.66353226, 0.05496598]), + 'Velocity': array([-0.45948178, 0.70952904, 0.00083061]), + 'brake_input': 0.0, + 'camera_location': array([-6.90216684, 12.68317318, -0.48634565]), + 'camera_rotation': array([ -7.96523619, -12.03357601, -2.485641 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1680.5216064453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -597.08306885, -3197.92138672, 107.51202393]), + 'frame': 28289, + 'frame_number': 28289, + 'framesequence': 108786, + 'gaze_dir': array([0.98223877, 0.15389252, 0.10249329]), + 'gaze_origin': array([-2.99104166, -0.12536775, -0.08491135]), + 'gaze_valid': True, + 'gaze_vergence': 77.33538055419922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97964478, 0.18106079, 0.08660889]), + 'left_gaze_origin': array([-2.88392353, 2.72821069, -0.07924195]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3015289306640625, + 'left_pupil_posn': array([ 0.38697433, -0.1064235 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98483276, 0.12672424, 0.11837769]), + 'right_gaze_origin': array([-3.09816003, -2.97894597, -0.09058075]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.947601318359375, + 'right_pupil_posn': array([-0.0814386 , -0.20492315]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.015546129085123539, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.850948177278, + 'timestamp_carla': 915851, + 'timestamp_device': 4069280, + 'timestamp_stream': 915.850948177278, + 'transform': [array([ 2.02820802e+00, 1.31183586e+01, -9.37652588e-03]), + array([-0.06119166, -8.32980824, 0.04492653])]} +{'AngularVelocity': array([ 3.15593071e-02, -5.67629095e-03, 5.69284868e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.67315101623535, + 'FR_Wheel_Angle': -24.383819580078125, + 'Location': array([ -3.01569748, -23.34887695, 0.17424121]), + 'Rotation': array([ -0.10431065, -41.46497726, 0.1389914 ]), + 'Velocity': array([-0.33223742, 0.52373552, 0.001709 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.90298367, 12.69087982, -0.48528412]), + 'camera_rotation': array([ -7.96997643, -11.78689766, -2.54281497]), + 'current_gear_input': False, + 'focus_actor_dist': 4247.90576171875, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -413.23721313, -5798.27246094, 17.29242706]), + 'frame': 28290, + 'frame_number': 28290, + 'framesequence': 108790, + 'gaze_dir': array([0.94161224, 0.31845093, 0.10590363]), + 'gaze_origin': array([-3.02886295, -0.24503785, -0.09497147]), + 'gaze_valid': True, + 'gaze_vergence': 80.340087890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93655396, 0.33888245, 0.08943176]), + 'left_gaze_origin': array([-2.93044925, 2.59380817, -0.08956604]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4882659912109375, + 'left_pupil_posn': array([ 0.54554081, -0.12451971]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94667053, 0.29801941, 0.12237549]), + 'right_gaze_origin': array([-3.1272769 , -3.08388376, -0.1003769 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.118377685546875, + 'right_pupil_posn': array([ 0.04642117, -0.22135878]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.015564440749585629, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.8838268779218, + 'timestamp_carla': 915884, + 'timestamp_device': 4069314, + 'timestamp_stream': 915.8838268779218, + 'transform': [array([ 2.04280758e+00, 1.30404329e+01, -9.59527958e-03]), + array([-0.06101407, -8.35586643, 0.04540952])]} +{'AngularVelocity': array([ 0.02234924, -0.01382272, 4.28723097]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.40116500854492, + 'FR_Wheel_Angle': -25.97506332397461, + 'Location': array([ -3.08335495, -23.25304413, 0.17424774]), + 'Rotation': array([ -0.10400329, -40.30916595, 0.13063502]), + 'Velocity': array([-2.25359336e-01, 3.61009806e-01, 1.97367670e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.89234972, 12.71066093, -0.49058077]), + 'camera_rotation': array([ -7.97570038, -11.50310326, -2.56703615]), + 'current_gear_input': False, + 'focus_actor_dist': 3808.7958984375, + 'focus_actor_name': 'SM_Shop_68', + 'focus_actor_pt': array([ 256.49926758, -5331.48974609, 90.72039795]), + 'frame': 28291, + 'frame_number': 28291, + 'framesequence': 108794, + 'gaze_dir': array([0.92149353, 0.37923431, 0.08133698]), + 'gaze_origin': array([-3.04469943, -0.28871614, -0.09788971]), + 'gaze_valid': True, + 'gaze_vergence': 104.89117431640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91636658, 0.39431763, 0.06915283]), + 'left_gaze_origin': array([-2.94678974, 2.5470674 , -0.09294892]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.386688232421875, + 'left_pupil_posn': array([ 0.60644257, -0.14235163]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92662048, 0.364151 , 0.09352112]), + 'right_gaze_origin': array([-3.14260864, -3.1244998 , -0.10283051]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.036407470703125, + 'right_pupil_posn': array([ 0.09451449, -0.23548245]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.015564440749585629, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.9169745780528, + 'timestamp_carla': 915918, + 'timestamp_device': 4069347, + 'timestamp_stream': 915.9169745780528, + 'transform': [array([ 2.05797362e+00, 1.29591770e+01, -9.76984017e-03]), + array([-0.06084332, -8.38299274, 0.04580111])]} +{'AngularVelocity': array([ 0.01935701, -0.00298227, 2.95530653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.33919906616211, + 'FR_Wheel_Angle': -27.029085159301758, + 'Location': array([ -3.13554215, -23.17907715, 0.17423214]), + 'Rotation': array([ -0.10622992, -39.34775925, 0.12467979]), + 'Velocity': array([-1.44732177e-01, 2.33925372e-01, 8.19110865e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.88118887, 12.76253986, -0.49515378]), + 'camera_rotation': array([ -7.98789215, -11.0647049 , -2.55706096]), + 'current_gear_input': False, + 'focus_actor_dist': 3512.20361328125, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ 457.59985352, -5000.45166016, 27.82847595]), + 'frame': 28292, + 'frame_number': 28292, + 'framesequence': 108798, + 'gaze_dir': array([0.92728424, 0.3629303 , 0.09038544]), + 'gaze_origin': array([-3.04242253, -0.28640518, -0.09953614]), + 'gaze_valid': True, + 'gaze_vergence': 156.6707763671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92285156, 0.37591553, 0.08375549]), + 'left_gaze_origin': array([-2.94299626, 2.55220056, -0.09585572]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30157470703125, + 'left_pupil_posn': array([ 0.59683061, -0.14185381]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93171692, 0.34994507, 0.09701538]), + 'right_gaze_origin': array([-3.1418488 , -3.12501073, -0.10321656]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0298004150390625, + 'right_pupil_posn': array([ 0.08822858, -0.22981989]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.015692617744207382, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.9499524757266, + 'timestamp_carla': 915950, + 'timestamp_device': 4069380, + 'timestamp_stream': 915.9499524757266, + 'transform': [array([ 2.07355261e+00, 1.28756676e+01, -9.89740342e-03]), + array([-0.06075453, -8.41095257, 0.04610496])]} +{'AngularVelocity': array([ 1.47166187e-02, -1.51309406e-03, 2.03016806e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.51995849609375, + 'FR_Wheel_Angle': -27.085893630981445, + 'Location': array([ -3.16578341, -23.13662338, 0.17425956]), + 'Rotation': array([ -0.10833362, -38.77533722, 0.12144727]), + 'Velocity': array([-0.10086469, 0.15952724, 0.00060478]), + 'brake_input': 0.0, + 'camera_location': array([-6.85124969, 12.85717583, -0.51549137]), + 'camera_rotation': array([ -8.03471279, -10.40370083, -2.63205028]), + 'current_gear_input': False, + 'focus_actor_dist': 3833.444091796875, + 'focus_actor_name': 'SM_Shop_68', + 'focus_actor_pt': array([ 485.03753662, -5331.48974609, 45.68077087]), + 'frame': 28293, + 'frame_number': 28293, + 'framesequence': 108802, + 'gaze_dir': array([0.92893219, 0.3578186 , 0.09242249]), + 'gaze_origin': array([-3.0398469 , -0.28053361, -0.09826432]), + 'gaze_valid': True, + 'gaze_vergence': 117.092529296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92146301, 0.37825012, 0.08842468]), + 'left_gaze_origin': array([-2.9379046 , 2.56181049, -0.09559631]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3919525146484375, + 'left_pupil_posn': array([ 0.58450222, -0.14036679]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93640137, 0.33738708, 0.09642029]), + 'right_gaze_origin': array([-3.14178944, -3.1228776 , -0.10093231]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9615936279296875, + 'right_pupil_posn': array([ 0.0877943 , -0.22654772]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.016132084652781487, + 'throttle_input': 0.4325169622898102, + 'timestamp': 915.9842739775777, + 'timestamp_carla': 915985, + 'timestamp_device': 4069414, + 'timestamp_stream': 915.9842739775777, + 'transform': [array([ 2.09046531e+00, 1.27860165e+01, -9.93158296e-03]), + array([-0.06078868, -8.44144535, 0.04620881])]} +{'AngularVelocity': array([ 1.74268503e-02, -7.07495667e-04, 1.11907804e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.56959533691406, + 'FR_Wheel_Angle': -27.11638069152832, + 'Location': array([ -3.18186736, -23.11417198, 0.1742429 ]), + 'Rotation': array([ -0.10877076, -38.46988678, 0.11978856]), + 'Velocity': array([-0.05457289, 0.08973528, -0.00046524]), + 'brake_input': 0.0, + 'camera_location': array([-6.84155655, 12.97179222, -0.50464118]), + 'camera_rotation': array([-8.13534927, -9.63329315, -2.53588533]), + 'current_gear_input': False, + 'focus_actor_dist': 3829.292236328125, + 'focus_actor_name': 'SM_Shop_68', + 'focus_actor_pt': array([ 504.58267212, -5331.48974609, 50.54689789]), + 'frame': 28294, + 'frame_number': 28294, + 'framesequence': 108806, + 'gaze_dir': array([0.9319458 , 0.35134125, 0.08556366]), + 'gaze_origin': array([-3.03779221, -0.27778015, -0.10055314]), + 'gaze_valid': True, + 'gaze_vergence': 88.3403091430664, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92488098, 0.37322998, 0.07266235]), + 'left_gaze_origin': array([-2.93721628, 2.56336212, -0.09935303]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3443450927734375, + 'left_pupil_posn': array([ 0.58025455, -0.14145231]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93901062, 0.32945251, 0.09846497]), + 'right_gaze_origin': array([-3.13836813, -3.11892247, -0.10175324]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.96490478515625, + 'right_pupil_posn': array([ 0.08291388, -0.2318176 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.017230750992894173, + 'throttle_input': 0.38887616991996765, + 'timestamp': 916.016477778554, + 'timestamp_carla': 916017, + 'timestamp_device': 4069447, + 'timestamp_stream': 916.016477778554, + 'transform': [array([ 2.10746169e+00, 1.26991949e+01, -9.97352600e-03]), + array([-0.06096626, -8.47237492, 0.04636413])]} +{'AngularVelocity': array([ 0.12635048, -0.03576785, 2.04250836]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.59600830078125, + 'FR_Wheel_Angle': -27.130178451538086, + 'Location': array([ -3.19169402, -23.10061073, 0.17425686]), + 'Rotation': array([ -0.11062174, -38.27616119, 0.1172841 ]), + 'Velocity': array([-0.04377793, 0.07933185, 0.00011501]), + 'brake_input': 0.0, + 'camera_location': array([-6.83481979, 13.09396172, -0.49949685]), + 'camera_rotation': array([-8.1243248 , -8.83362389, -2.4472847 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3731.205810546875, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 508.66513062, -5238.109375 , 16.36980438]), + 'frame': 28295, + 'frame_number': 28295, + 'framesequence': 108810, + 'gaze_dir': array([0.93800354, 0.33538818, 0.08724213]), + 'gaze_origin': array([-3.03212285, -0.26299059, -0.09897614]), + 'gaze_valid': True, + 'gaze_vergence': 302.8948669433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93644714, 0.33868408, 0.09138489]), + 'left_gaze_origin': array([-2.930089 , 2.58257151, -0.09785309]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.29974365234375, + 'left_pupil_posn': array([ 0.56670165, -0.14455843]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93955994, 0.33209229, 0.08309937]), + 'right_gaze_origin': array([-3.1341567 , -3.10855269, -0.10009919]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0047454833984375, + 'right_pupil_posn': array([ 0.06344199, -0.2219559 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01832941733300686, + 'throttle_input': 0.3293507397174835, + 'timestamp': 916.0505255758762, + 'timestamp_carla': 916051, + 'timestamp_device': 4069480, + 'timestamp_stream': 916.0505255758762, + 'transform': [array([ 2.12685347e+00, 1.26047649e+01, -9.87476297e-03]), + array([-0.06129412, -8.50802422, 0.04621333])]} +{'AngularVelocity': array([ 0.02318648, -0.00987583, -0.40472764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.73183822631836, + 'FR_Wheel_Angle': -27.268600463867188, + 'Location': array([ -3.1997292 , -23.08935165, 0.17433514]), + 'Rotation': array([ -0.1121517 , -38.13656998, 0.11544771]), + 'Velocity': array([-0.02571078, 0.0432675 , 0.00041463]), + 'brake_input': 0.0, + 'camera_location': array([-6.84904051, 13.24082661, -0.49682888]), + 'camera_rotation': array([-8.11715317, -8.05683231, -2.43936276]), + 'current_gear_input': False, + 'focus_actor_dist': 3706.85400390625, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 490.81347656, -5225.50976562, 16.3843689 ]), + 'frame': 28296, + 'frame_number': 28296, + 'framesequence': 108814, + 'gaze_dir': array([0.94229126, 0.32180023, 0.09192657]), + 'gaze_origin': array([-3.02982712, -0.25646287, -0.09952622]), + 'gaze_valid': True, + 'gaze_vergence': 311.2914123535156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93954468, 0.32926941, 0.09393311]), + 'left_gaze_origin': array([-2.92805815, 2.58841872, -0.09976654]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3433990478515625, + 'left_pupil_posn': array([ 0.55561674, -0.14229965]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94503784, 0.31433105, 0.08992004]), + 'right_gaze_origin': array([-3.13159633, -3.10134435, -0.09928589]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.819915771484375, + 'right_pupil_posn': array([ 0.05529165, -0.21939135]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01973937451839447, + 'throttle_input': 0.2380865216255188, + 'timestamp': 916.0835432782769, + 'timestamp_carla': 916084, + 'timestamp_device': 4069514, + 'timestamp_stream': 916.0835432782769, + 'transform': [array([ 2.14723039e+00, 1.25108614e+01, -9.58837476e-03]), + array([-0.06173808, -8.54589748, 0.04571646])]} +{'AngularVelocity': array([ 0.01439186, -0.0133495 , -0.62707663]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.14659118652344, + 'FR_Wheel_Angle': -28.283266067504883, + 'Location': array([ -3.20482588, -23.08227539, 0.1743159 ]), + 'Rotation': array([ -0.11282789, -38.03849411, 0.11447483]), + 'Velocity': array([-0.02179002, 0.03808382, -0.00057593]), + 'brake_input': 0.0, + 'camera_location': array([-6.85927582, 13.36053181, -0.50615615]), + 'camera_rotation': array([-8.11089039, -7.40348911, -2.39725518]), + 'current_gear_input': False, + 'focus_actor_dist': 4010.9052734375, + 'focus_actor_name': 'SM_Shop_68', + 'focus_actor_pt': array([ 548.16540527, -5533.61621094, 20.88341522]), + 'frame': 28297, + 'frame_number': 28297, + 'framesequence': 108818, + 'gaze_dir': array([0.94029999, 0.32212067, 0.10941315]), + 'gaze_origin': array([-3.02998829, -0.24916078, -0.0985138 ]), + 'gaze_valid': True, + 'gaze_vergence': 273.0428771972656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93804932, 0.32997131, 0.10562134]), + 'left_gaze_origin': array([-2.928334 , 2.59768081, -0.09894562]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1494903564453125, + 'left_pupil_posn': array([ 0.54896867, -0.13375032]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94255066, 0.31427002, 0.11320496]), + 'right_gaze_origin': array([-3.1316421 , -3.09600234, -0.09808197]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.697601318359375, + 'right_pupil_posn': array([ 0.05216599, -0.21431112]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.020947905257344246, + 'throttle_input': 0.1269855797290802, + 'timestamp': 916.1159583777189, + 'timestamp_carla': 916116, + 'timestamp_device': 4069547, + 'timestamp_stream': 916.1159583777189, + 'transform': [array([ 2.16870546e+00, 1.24168348e+01, -9.03352723e-03]), + array([-0.06227083, -8.58621216, 0.04470081])]} +{'AngularVelocity': array([ 0.24851167, -0.05893042, 3.99637794]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.975032806396484, + 'FR_Wheel_Angle': -30.032169342041016, + 'Location': array([ -3.21750808, -23.06549835, 0.17431876]), + 'Rotation': array([ -0.11984249, -37.75114059, 0.10486 ]), + 'Velocity': array([-0.12354925, 0.20918149, -0.00082556]), + 'brake_input': 0.0, + 'camera_location': array([-6.8699398 , 13.46757221, -0.51865888]), + 'camera_rotation': array([-8.19470978, -6.88254452, -2.41982675]), + 'current_gear_input': False, + 'focus_actor_dist': 3462.2431640625, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ 469.83776855, -4999.70800781, 96.72138214]), + 'frame': 28298, + 'frame_number': 28298, + 'framesequence': 108822, + 'gaze_dir': array([0.98780823, 0.10720825, 0.10664368]), + 'gaze_origin': array([-2.96232152, -0.08847199, -0.10027389]), + 'gaze_valid': True, + 'gaze_vergence': 49.39826202392578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9884491 , 0.12995911, 0.07783508]), + 'left_gaze_origin': array([-2.71355891, 2.77615833, -0.14537354]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1043853759765625, + 'left_pupil_posn': array([ 0.33601069, -0.11169112]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98716736, 0.0844574 , 0.13545227]), + 'right_gaze_origin': array([-3.21108389, -2.95310235, -0.05517426]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8690032958984375, + 'right_pupil_posn': array([-0.11604166, -0.20421827]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02219306118786335, + 'throttle_input': 0.0476234070956707, + 'timestamp': 916.1502149775624, + 'timestamp_carla': 916151, + 'timestamp_device': 4069580, + 'timestamp_stream': 916.1502149775624, + 'transform': [array([ 2.19289088e+00, 1.23162317e+01, -7.99455587e-03]), + array([-0.06294702, -8.63202477, 0.04271058])]} +{'AngularVelocity': array([-0.09185643, 0.03159983, 3.5143199 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.856502532958984, + 'FR_Wheel_Angle': -30.897218704223633, + 'Location': array([ -3.24529529, -23.02496719, 0.17283891]), + 'Rotation': array([-6.22844920e-02, -3.71042328e+01, 2.91706063e-02]), + 'Velocity': array([-0.10491136, 0.17254551, -0.00036247]), + 'brake_input': 0.0, + 'camera_location': array([-6.91242504, 13.55511951, -0.54530084]), + 'camera_rotation': array([-8.35299301, -6.53327465, -2.47490835]), + 'current_gear_input': False, + 'focus_actor_dist': 3858.067138671875, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -253.39866638, -5485.69335938, 17.10249329]), + 'frame': 28299, + 'frame_number': 28299, + 'framesequence': 108826, + 'gaze_dir': array([ 0.98727417, -0.10494232, 0.11687469]), + 'gaze_origin': array([-3.00433278, 0.08046036, -0.09110566]), + 'gaze_valid': True, + 'gaze_vergence': 92.1343994140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98754883, -0.08560181, 0.13195801]), + 'left_gaze_origin': array([-2.89620829, 2.93500543, -0.07722779]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.866119384765625, + 'left_pupil_posn': array([ 0.16122758, -0.11090589]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98699951, -0.12428284, 0.10179138]), + 'right_gaze_origin': array([-3.11245751, -2.77408457, -0.10498352]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9665985107421875, + 'right_pupil_posn': array([-0.31482339, -0.19851124]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.023529771715402603, + 'throttle_input': 0.0, + 'timestamp': 916.1830004788935, + 'timestamp_carla': 916183, + 'timestamp_device': 4069614, + 'timestamp_stream': 916.1830004788935, + 'transform': [array([ 2.21690655e+00, 1.22192183e+01, -6.73791859e-03]), + array([-0.06368468, -8.67788887, 0.04032302])]} +{'AngularVelocity': array([2.66272500e-02, 2.13571638e-03, 3.31693649e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.88685607910156, + 'FR_Wheel_Angle': -30.918262481689453, + 'Location': array([ -3.2699461 , -22.98924065, 0.17294008]), + 'Rotation': array([ -0.06268747, -36.53181458, 0.03686742]), + 'Velocity': array([-0.08562866, 0.14616178, 0.00016352]), + 'brake_input': 0.0, + 'camera_location': array([-6.94802475, 13.60830879, -0.54580992]), + 'camera_rotation': array([-8.40320206, -6.36209679, -2.64954185]), + 'current_gear_input': False, + 'focus_actor_dist': 1595.0228271484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -599.01220703, -3201.42333984, 83.54350281]), + 'frame': 28300, + 'frame_number': 28300, + 'framesequence': 108830, + 'gaze_dir': array([ 0.97543335, -0.1921463 , 0.10661316]), + 'gaze_origin': array([-3.01692057, 0.14974213, -0.09463883]), + 'gaze_valid': True, + 'gaze_vergence': 187.43896484375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97842407, -0.17752075, 0.10560608]), + 'left_gaze_origin': array([-2.90768147, 2.99791265, -0.08195954]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.697052001953125, + 'left_pupil_posn': array([ 0.09041727, -0.11479878]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97244263, -0.20677185, 0.10762024]), + 'right_gaze_origin': array([-3.12615967, -2.69842863, -0.10731812]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9702301025390625, + 'right_pupil_posn': array([-0.40042979, -0.21225595]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.024811549112200737, + 'throttle_input': 0.0, + 'timestamp': 916.2172967791557, + 'timestamp_carla': 916218, + 'timestamp_device': 4069647, + 'timestamp_stream': 916.2172967791557, + 'transform': [array([ 2.24388480e+00, 1.21174030e+01, -5.11543266e-03]), + array([-0.06451114, -8.72988987, 0.03719687])]} +{'AngularVelocity': array([ 0.07750899, -0.05846233, 2.39481521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.90083312988281, + 'FR_Wheel_Angle': -30.914024353027344, + 'Location': array([ -3.28926659, -22.96149445, 0.17304662]), + 'Rotation': array([ -0.06438819, -36.08750916, 0.03695974]), + 'Velocity': array([-0.06372838, 0.13033442, 0.00035317]), + 'brake_input': 0.0, + 'camera_location': array([-6.95492029, 13.60962486, -0.5381645 ]), + 'camera_rotation': array([-8.38861942, -6.45978785, -2.73090577]), + 'current_gear_input': False, + 'focus_actor_dist': 1616.3087158203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -737.61914062, -3197.24658203, 60.98177338]), + 'frame': 28301, + 'frame_number': 28301, + 'framesequence': 108834, + 'gaze_dir': array([ 0.97491455, -0.19439697, 0.10701752]), + 'gaze_origin': array([-3.01661706, 0.14942552, -0.0964325 ]), + 'gaze_valid': True, + 'gaze_vergence': 169.30715942382812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97824097, -0.17814636, 0.10626221]), + 'left_gaze_origin': array([-2.90829325, 3.00041366, -0.08242799]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7451934814453125, + 'left_pupil_posn': array([ 0.08741534, -0.11529338]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97158813, -0.21064758, 0.10777283]), + 'right_gaze_origin': array([-3.12494063, -2.70156264, -0.11043702]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.904541015625, + 'right_pupil_posn': array([-0.39852393, -0.21378052]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.026587726548314095, + 'throttle_input': 0.0, + 'timestamp': 916.2499133758247, + 'timestamp_carla': 916250, + 'timestamp_device': 4069680, + 'timestamp_stream': 916.2499133758247, + 'transform': [array([ 2.27062321e+00, 1.20207863e+01, -3.37011321e-03]), + array([-0.06537174, -8.78185272, 0.0338595 ])]} +{'AngularVelocity': array([ 1.39621571e-01, -3.23081273e-03, 4.23745060e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.79275894165039, + 'FR_Wheel_Angle': -30.81673240661621, + 'Location': array([ -3.31864738, -22.92118835, 0.17312247]), + 'Rotation': array([-7.24136606e-02, -3.54371338e+01, 2.85411905e-02]), + 'Velocity': array([-1.96570873e-01, 2.94877589e-01, 2.06041324e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.99511051, 13.57826805, -0.53730565]), + 'camera_rotation': array([-8.45270729, -6.77315569, -2.71078587]), + 'current_gear_input': False, + 'focus_actor_dist': 1608.531005859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -743.14483643, -3197.21630859, 61.81315613]), + 'frame': 28302, + 'frame_number': 28302, + 'framesequence': 108838, + 'gaze_dir': array([ 0.97473907, -0.19434357, 0.10889435]), + 'gaze_origin': array([-3.01641703, 0.14752884, -0.09792863]), + 'gaze_valid': True, + 'gaze_vergence': 183.06805419921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97756958, -0.17932129, 0.11039734]), + 'left_gaze_origin': array([-2.90827799, 3.00102711, -0.08234253]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7330169677734375, + 'left_pupil_posn': array([ 0.08743119, -0.11529338]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97190857, -0.20936584, 0.10739136]), + 'right_gaze_origin': array([-3.12455606, -2.70596933, -0.11351472]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9299163818359375, + 'right_pupil_posn': array([-0.39589852, -0.2144227 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.028272347524762154, + 'throttle_input': 0.0, + 'timestamp': 916.2834821790457, + 'timestamp_carla': 916284, + 'timestamp_device': 4069714, + 'timestamp_stream': 916.2834821790457, + 'transform': [array([ 2.29967475e+00, 1.19217787e+01, -1.51666638e-03]), + array([-0.06625966, -8.83876514, 0.03029215])]} +{'AngularVelocity': array([ 0.02793246, -0.06481891, 6.89669418]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.655643463134766, + 'FR_Wheel_Angle': -30.761791229248047, + 'Location': array([ -3.38173008, -22.8372097 , 0.17320684]), + 'Rotation': array([-7.42851347e-02, -3.40585136e+01, 2.52612568e-02]), + 'Velocity': array([-2.57317066e-01, 4.20591354e-01, 3.22866428e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.0230813 , 13.5356636 , -0.54689115]), + 'camera_rotation': array([-8.42801571, -7.21047926, -2.73210263]), + 'current_gear_input': False, + 'focus_actor_dist': 1601.9344482421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -750.96142578, -3197.17333984, 63.41243744]), + 'frame': 28303, + 'frame_number': 28303, + 'framesequence': 108842, + 'gaze_dir': array([ 0.97535706, -0.19174957, 0.10769653]), + 'gaze_origin': array([-3.01551151, 0.14480515, -0.09974595]), + 'gaze_valid': True, + 'gaze_vergence': 165.57135009765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97845459, -0.17510986, 0.10932922]), + 'left_gaze_origin': array([-2.90832067, 3.00050974, -0.08239747]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5961761474609375, + 'left_pupil_posn': array([ 0.08809757, -0.11574209]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97225952, -0.20838928, 0.10606384]), + 'right_gaze_origin': array([-3.12270212, -2.71089959, -0.11709443]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.021331787109375, + 'right_pupil_posn': array([-0.39098281, -0.21681905]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.030231637880206108, + 'throttle_input': 0.0, + 'timestamp': 916.3162293769419, + 'timestamp_carla': 916317, + 'timestamp_device': 4069747, + 'timestamp_stream': 916.3162293769419, + 'transform': [array([2.32931995e+00, 1.18258095e+01, 2.50415789e-04]), + array([-0.06711344, -8.89726734, 0.02690543])]} +{'AngularVelocity': array([-0.01440352, -0.01898181, 6.70277405]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.65156555175781, + 'FR_Wheel_Angle': -30.775245666503906, + 'Location': array([ -3.4551332 , -22.74370766, 0.17327257]), + 'Rotation': array([-6.97977021e-02, -3.25128326e+01, 3.22735906e-02]), + 'Velocity': array([-2.84923285e-01, 4.13160235e-01, 2.19202033e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.04989529, 13.46032238, -0.53751802]), + 'camera_rotation': array([-8.37296486, -7.64266968, -2.63043642]), + 'current_gear_input': False, + 'focus_actor_dist': 1595.1214599609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -758.00524902, -3197.16748047, 62.33467102]), + 'frame': 28304, + 'frame_number': 28304, + 'framesequence': 108846, + 'gaze_dir': array([ 0.97544098, -0.1904068 , 0.10958099]), + 'gaze_origin': array([-3.01431441, 0.13947755, -0.10199433]), + 'gaze_valid': True, + 'gaze_vergence': 161.34771728515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97703552, -0.1776886 , 0.11749268]), + 'left_gaze_origin': array([-2.90838337, 2.99439716, -0.0848877 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5969696044921875, + 'left_pupil_posn': array([ 0.09405112, -0.11884832]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97384644, -0.203125 , 0.10166931]), + 'right_gaze_origin': array([-3.1202457 , -2.71544194, -0.11910095]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9163818359375, + 'right_pupil_posn': array([-0.38866323, -0.21512318]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03248390555381775, + 'throttle_input': 0.0, + 'timestamp': 916.3497554771602, + 'timestamp_carla': 916350, + 'timestamp_device': 4069780, + 'timestamp_stream': 916.3497554771602, + 'transform': [array([2.36138415e+00, 1.17282419e+01, 1.92028040e-03]), + array([-0.06798087, -8.96101856, 0.02369423])]} +{'AngularVelocity': array([ 0.10700063, -0.0541588 , 7.53706312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.622032165527344, + 'FR_Wheel_Angle': -30.756072998046875, + 'Location': array([ -3.51744676, -22.66837883, 0.17335057]), + 'Rotation': array([-7.04670548e-02, -3.12396927e+01, 2.98430994e-02]), + 'Velocity': array([-3.10648263e-01, 4.47833002e-01, 4.05921921e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.07759666, 13.40178299, -0.52974474]), + 'camera_rotation': array([-8.36262321, -8.0459528 , -2.53150439]), + 'current_gear_input': False, + 'focus_actor_dist': 1588.961669921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -766.94665527, -3197.16796875, 67.62494659]), + 'frame': 28305, + 'frame_number': 28305, + 'framesequence': 108850, + 'gaze_dir': array([ 0.97641754, -0.18830872, 0.10439301]), + 'gaze_origin': array([-3.01187682, 0.13636933, -0.10339355]), + 'gaze_valid': True, + 'gaze_vergence': 141.3206787109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97763062, -0.1764679 , 0.11437988]), + 'left_gaze_origin': array([-2.90848565, 2.99229598, -0.0855423 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5964508056640625, + 'left_pupil_posn': array([ 0.09637141, -0.12144291]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97520447, -0.20014954, 0.09440613]), + 'right_gaze_origin': array([-3.11526799, -2.71955729, -0.12124483]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9777679443359375, + 'right_pupil_posn': array([-0.38530427, -0.21669042]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.034553058445453644, + 'throttle_input': 0.0, + 'timestamp': 916.3841272778809, + 'timestamp_carla': 916385, + 'timestamp_device': 4069814, + 'timestamp_stream': 916.3841272778809, + 'transform': [array([2.39593148e+00, 1.16290178e+01, 3.44802858e-03]), + array([-0.06875951, -9.03016472, 0.02075234])]} +{'AngularVelocity': array([ 0.07331074, -0.05386466, 7.75671864]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.607810974121094, + 'FR_Wheel_Angle': -30.75177001953125, + 'Location': array([ -3.59936023, -22.5730114 , 0.17342798]), + 'Rotation': array([-7.08563775e-02, -2.95848370e+01, 2.89315488e-02]), + 'Velocity': array([-3.31220001e-01, 4.54348296e-01, 2.26964941e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.10306549, 13.34686089, -0.51654345]), + 'camera_rotation': array([-8.33627987, -8.37150097, -2.53262329]), + 'current_gear_input': False, + 'focus_actor_dist': 1582.549072265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -773.40423584, -3197.16796875, 60.4380722 ]), + 'frame': 28306, + 'frame_number': 28306, + 'framesequence': 108854, + 'gaze_dir': array([ 0.97651672, -0.18772125, 0.1043396 ]), + 'gaze_origin': array([-3.0114007 , 0.1349823 , -0.10370941]), + 'gaze_valid': True, + 'gaze_vergence': 141.1818389892578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97810364, -0.17417908, 0.11384583]), + 'left_gaze_origin': array([-2.90910053, 2.99120045, -0.08572235]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6310882568359375, + 'left_pupil_posn': array([ 0.09675646, -0.1216172 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97492981, -0.20126343, 0.09483337]), + 'right_gaze_origin': array([-3.11370111, -2.72123575, -0.12169648]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9782257080078125, + 'right_pupil_posn': array([-0.38328862, -0.21687841]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0367870107293129, + 'throttle_input': 0.0, + 'timestamp': 916.4171875789762, + 'timestamp_carla': 916418, + 'timestamp_device': 4069847, + 'timestamp_stream': 916.4171875789762, + 'transform': [array([2.43041015e+00, 1.15344296e+01, 4.74023819e-03]), + array([-0.06942204, -9.09961128, 0.01829594])]} +{'AngularVelocity': array([ 0.0983571 , -0.05803546, 7.18644142]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.64386749267578, + 'FR_Wheel_Angle': -30.780757904052734, + 'Location': array([ -3.68218017, -22.48246002, 0.17351656]), + 'Rotation': array([ -0.0688483 , -27.99556351, 0.0306022 ]), + 'Velocity': array([-0.31733635, 0.41370901, 0.00041862]), + 'brake_input': 0.0, + 'camera_location': array([-7.15042639, 13.27859402, -0.50692147]), + 'camera_rotation': array([-8.28216362, -8.60227489, -2.54993796]), + 'current_gear_input': False, + 'focus_actor_dist': 1576.0233154296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -780.82861328, -3197.16748047, 61.326828 ]), + 'frame': 28307, + 'frame_number': 28307, + 'framesequence': 108858, + 'gaze_dir': array([ 0.9765625 , -0.18904877, 0.10168457]), + 'gaze_origin': array([-3.01158071, 0.13384934, -0.10422745]), + 'gaze_valid': True, + 'gaze_vergence': 155.3433380126953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9781189 , -0.17645264, 0.11019897]), + 'left_gaze_origin': array([-2.90980244, 2.99027419, -0.08599091]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6653289794921875, + 'left_pupil_posn': array([ 0.09731674, -0.12262309]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9750061 , -0.2016449 , 0.09317017]), + 'right_gaze_origin': array([-3.11335921, -2.72257543, -0.12246399]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9753265380859375, + 'right_pupil_posn': array([-0.38319361, -0.21862638]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.038489945232868195, + 'throttle_input': 0.0, + 'timestamp': 916.4509968757629, + 'timestamp_carla': 916451, + 'timestamp_device': 4069880, + 'timestamp_stream': 916.4509968757629, + 'transform': [array([2.46696782e+00, 1.14385910e+01, 5.87493880e-03]), + array([-0.06994797, -9.17364883, 0.01613405])]} +{'AngularVelocity': array([-0.08470501, 0.04061079, 4.9315753 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.711570739746094, + 'FR_Wheel_Angle': -30.813323974609375, + 'Location': array([ -3.75909328, -22.40212631, 0.17363283]), + 'Rotation': array([ -0.0668334 , -26.54123878, 0.03304076]), + 'Velocity': array([-2.74674207e-01, 3.06241423e-01, 2.06356039e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.1681242 , 13.21298218, -0.48324507]), + 'camera_rotation': array([-8.15672112, -8.78717041, -2.60323596]), + 'current_gear_input': False, + 'focus_actor_dist': 1570.1385498046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -788.68847656, -3196.97412109, 58.69672394]), + 'frame': 28308, + 'frame_number': 28308, + 'framesequence': 108862, + 'gaze_dir': array([ 0.97683716, -0.19195557, 0.09401703]), + 'gaze_origin': array([-3.00972676, 0.13193589, -0.10713425]), + 'gaze_valid': True, + 'gaze_vergence': 296.4971008300781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97827148, -0.18331909, 0.09671021]), + 'left_gaze_origin': array([-2.91054702, 2.98986673, -0.08674164]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6985321044921875, + 'left_pupil_posn': array([ 0.0980022 , -0.12394249]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97540283, -0.20059204, 0.09132385]), + 'right_gaze_origin': array([-3.10890675, -2.72599506, -0.12752686]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9441986083984375, + 'right_pupil_posn': array([-0.38336349, -0.22589827]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0399182103574276, + 'throttle_input': 0.0, + 'timestamp': 916.4834495782852, + 'timestamp_carla': 916484, + 'timestamp_device': 4069914, + 'timestamp_stream': 916.4834495782852, + 'transform': [array([2.50272036e+00, 1.13475428e+01, 6.81314431e-03]), + array([-0.07028265, -9.24639797, 0.01437617])]} +{'AngularVelocity': array([0.10562666, 0.02422684, 5.29467869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68699264526367, + 'FR_Wheel_Angle': -30.79324722290039, + 'Location': array([ -3.80727053, -22.35402298, 0.17369501]), + 'Rotation': array([ -0.06899857, -25.65625954, 0.02916684]), + 'Velocity': array([-2.92476058e-01, 3.21139753e-01, 2.61502253e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.19541502, 13.14542389, -0.47043934]), + 'camera_rotation': array([-8.00703716, -9.01857758, -2.64042521]), + 'current_gear_input': False, + 'focus_actor_dist': 1725.2020263671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -850.55700684, -3347.85302734, 41.25497437]), + 'frame': 28309, + 'frame_number': 28309, + 'framesequence': 108866, + 'gaze_dir': array([ 0.97782135, -0.18695831, 0.0932312 ]), + 'gaze_origin': array([-3.00627685, 0.13165055, -0.11205903]), + 'gaze_valid': True, + 'gaze_vergence': 159.01589965820312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97906494, -0.17604065, 0.10203552]), + 'left_gaze_origin': array([-2.91236424, 2.98974633, -0.08834992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7570953369140625, + 'left_pupil_posn': array([ 0.09907293, -0.12771058]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97657776, -0.19787598, 0.08442688]), + 'right_gaze_origin': array([-3.10018945, -2.7264452 , -0.13576813]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.884796142578125, + 'right_pupil_posn': array([-0.38038456, -0.22784853]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04110843688249588, + 'throttle_input': 0.0, + 'timestamp': 916.5162607766688, + 'timestamp_carla': 916517, + 'timestamp_device': 4069947, + 'timestamp_stream': 916.5162607766688, + 'transform': [array([2.53950071e+00, 1.12564449e+01, 7.60923373e-03]), + array([-0.07048072, -9.32156086, 0.01288483])]} +{'AngularVelocity': array([-0.09149634, -0.02125275, 3.90921211]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.77267837524414, + 'FR_Wheel_Angle': -30.852615356445312, + 'Location': array([ -3.86765289, -22.29655266, 0.17373739]), + 'Rotation': array([ -0.06820627, -24.58218956, 0.02979189]), + 'Velocity': array([-0.23182102, 0.25101331, 0.00061434]), + 'brake_input': 0.0, + 'camera_location': array([-7.22522163, 13.09414101, -0.45880532]), + 'camera_rotation': array([-7.96363831, -9.19288158, -2.80887246]), + 'current_gear_input': False, + 'focus_actor_dist': 1716.25390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -848.13885498, -3347.85302734, 44.6783905 ]), + 'frame': 28310, + 'frame_number': 28310, + 'framesequence': 108870, + 'gaze_dir': array([ 0.97811127, -0.18639374, 0.09130859]), + 'gaze_origin': array([-3.00390935, 0.13063584, -0.11557236]), + 'gaze_valid': True, + 'gaze_vergence': 149.38719177246094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97911072, -0.17642212, 0.10092163]), + 'left_gaze_origin': array([-2.91553354, 2.98780227, -0.09091339]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.79022216796875, + 'left_pupil_posn': array([ 0.10100186, -0.13106203]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97711182, -0.19636536, 0.08169556]), + 'right_gaze_origin': array([-3.09228516, -2.72653055, -0.14023134]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.891082763671875, + 'right_pupil_posn': array([-0.38038456, -0.22970903]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04217047989368439, + 'throttle_input': 0.0, + 'timestamp': 916.5500018782914, + 'timestamp_carla': 916551, + 'timestamp_device': 4069980, + 'timestamp_stream': 916.5500018782914, + 'transform': [array([2.57776189e+00, 1.11637964e+01, 8.29021446e-03]), + array([-0.07056268, -9.40008259, 0.01160478])]} +{'AngularVelocity': array([ 0.09270706, -0.01262619, 3.24938011]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.813480377197266, + 'FR_Wheel_Angle': -30.889955520629883, + 'Location': array([ -3.90922356, -22.25780487, 0.17376593]), + 'Rotation': array([ -0.06597962, -23.84534645, 0.03041454]), + 'Velocity': array([-0.18175942, 0.19895692, 0.00022358]), + 'brake_input': 0.0, + 'camera_location': array([-7.24363708, 13.04920959, -0.47078884]), + 'camera_rotation': array([-7.99686003, -9.318367 , -2.96405506]), + 'current_gear_input': False, + 'focus_actor_dist': 1709.8955078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -852.48059082, -3347.85327148, 42.02649689]), + 'frame': 28311, + 'frame_number': 28311, + 'framesequence': 108874, + 'gaze_dir': array([ 0.97833252, -0.1856308 , 0.09030151]), + 'gaze_origin': array([-3.00419474, 0.13078614, -0.1166092 ]), + 'gaze_valid': True, + 'gaze_vergence': 121.53692626953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97911072, -0.17584229, 0.10198975]), + 'left_gaze_origin': array([-2.9189744 , 2.98780227, -0.09112702]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8172607421875, + 'left_pupil_posn': array([ 0.10140443, -0.13302088]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97755432, -0.19541931, 0.07861328]), + 'right_gaze_origin': array([-3.08941507, -2.72623014, -0.14209138]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.892730712890625, + 'right_pupil_posn': array([-0.38034904, -0.23006094]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04339732229709625, + 'throttle_input': 0.0, + 'timestamp': 916.5845167785883, + 'timestamp_carla': 916585, + 'timestamp_device': 4070014, + 'timestamp_stream': 916.5845167785883, + 'transform': [array([2.61741686e+00, 1.10700912e+01, 8.85040220e-03]), + array([-0.07057634, -9.48177814, 0.01055484])]} +{'AngularVelocity': array([ 0.02127157, -0.00616591, 2.4975493 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.86315155029297, + 'FR_Wheel_Angle': -30.905858993530273, + 'Location': array([ -3.94205213, -22.22789764, 0.17380574]), + 'Rotation': array([ -0.06689487, -23.26779747, 0.02903055]), + 'Velocity': array([-0.13315037, 0.13961278, 0.00080481]), + 'brake_input': 0.0, + 'camera_location': array([-7.26241159, 12.99126911, -0.45435178]), + 'camera_rotation': array([-7.9885478 , -9.4660368 , -2.99585915]), + 'current_gear_input': False, + 'focus_actor_dist': 1702.854248046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -854.98254395, -3347.85302734, 38.84061432]), + 'frame': 28312, + 'frame_number': 28312, + 'framesequence': 108878, + 'gaze_dir': array([ 0.97827911, -0.18566895, 0.09085083]), + 'gaze_origin': array([-3.00472426, 0.13079071, -0.11735459]), + 'gaze_valid': True, + 'gaze_vergence': 128.34286499023438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97909546, -0.17588806, 0.10198975]), + 'left_gaze_origin': array([-2.9218049 , 2.98781896, -0.09184723]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8298187255859375, + 'left_pupil_posn': array([ 0.10140443, -0.13366461]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97746277, -0.19544983, 0.07971191]), + 'right_gaze_origin': array([-3.08764362, -2.72623777, -0.14286195]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9514312744140625, + 'right_pupil_posn': array([-0.38032758, -0.23030078]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.044825587421655655, + 'throttle_input': 0.0, + 'timestamp': 916.6169630773365, + 'timestamp_carla': 916618, + 'timestamp_device': 4070047, + 'timestamp_stream': 916.6169630773365, + 'transform': [array([2.65492916e+00, 1.09829922e+01, 9.28506814e-03]), + array([-0.07060366, -9.55938435, 0.00978393])]} +{'AngularVelocity': array([-1.15419179e-03, -4.69596172e-03, 2.06364155e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.887516021728516, + 'FR_Wheel_Angle': -30.917953491210938, + 'Location': array([ -3.97027206, -22.2027874 , 0.17377977]), + 'Rotation': array([ -0.06872536, -22.76313782, 0.02600778]), + 'Velocity': array([-0.11324063, 0.1161592 , 0.00107172]), + 'brake_input': 0.0, + 'camera_location': array([-7.2733345 , 12.94316101, -0.40547729]), + 'camera_rotation': array([-7.8789711 , -9.68113136, -3.05201602]), + 'current_gear_input': False, + 'focus_actor_dist': 1696.1788330078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -859.46887207, -3347.85327148, 40.2016449 ]), + 'frame': 28313, + 'frame_number': 28313, + 'framesequence': 108882, + 'gaze_dir': array([ 0.97883606, -0.18278503, 0.09063721]), + 'gaze_origin': array([-2.9833107 , 0.13162537, -0.12919161]), + 'gaze_valid': True, + 'gaze_vergence': 125.14371490478516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97975159, -0.17216492, 0.10215759]), + 'left_gaze_origin': array([-2.92505956, 2.98922896, -0.09202118]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.875244140625, + 'left_pupil_posn': array([ 0.10120893, -0.13463175]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97792053, -0.19340515, 0.07911682]), + 'right_gaze_origin': array([-3.04156208, -2.72597814, -0.16636202]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9231414794921875, + 'right_pupil_posn': array([-0.3786025 , -0.23734665]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.046180609613657, + 'throttle_input': 0.0, + 'timestamp': 916.6506207771599, + 'timestamp_carla': 916651, + 'timestamp_device': 4070080, + 'timestamp_stream': 916.6506207771599, + 'transform': [array([2.69453025e+00, 1.08935890e+01, 9.62903909e-03]), + array([-7.06173256e-02, -9.64160061e+00, 9.16669052e-03])]} +{'AngularVelocity': array([ 0.01652733, -0.00304454, 1.95244145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.902870178222656, + 'FR_Wheel_Angle': -30.918413162231445, + 'Location': array([ -3.99348783, -22.18244743, 0.17381865]), + 'Rotation': array([ -0.06955181, -22.35899353, 0.02416606]), + 'Velocity': array([-1.01404175e-01, 1.04008794e-01, -4.73213186e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.26804638, 12.90084267, -0.37399653]), + 'camera_rotation': array([-7.7962575 , -9.93170643, -3.13434505]), + 'current_gear_input': False, + 'focus_actor_dist': 1688.897216796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -860.72692871, -3347.85302734, 43.24207306]), + 'frame': 28314, + 'frame_number': 28314, + 'framesequence': 108886, + 'gaze_dir': array([ 0.97975922, -0.17734528, 0.09156799]), + 'gaze_origin': array([-2.9701221 , 0.12919006, -0.13759919]), + 'gaze_valid': True, + 'gaze_vergence': 144.21348571777344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98077393, -0.16656494, 0.10154724]), + 'left_gaze_origin': array([-2.939641 , 2.98857427, -0.09510194]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.803680419921875, + 'left_pupil_posn': array([ 0.10345733, -0.13843799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97874451, -0.18812561, 0.08158875]), + 'right_gaze_origin': array([-3.00060296, -2.73019433, -0.18009645]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9692230224609375, + 'right_pupil_posn': array([-0.37321573, -0.23869157]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.048048343509435654, + 'throttle_input': 0.0, + 'timestamp': 916.6827888786793, + 'timestamp_carla': 916683, + 'timestamp_device': 4070114, + 'timestamp_stream': 916.6827888786793, + 'transform': [array([2.73299527e+00, 1.08090115e+01, 9.88349877e-03]), + array([-7.06719607e-02, -9.72176552e+00, 8.74356087e-03])]} +{'AngularVelocity': array([-0.02614264, 0.00392191, 2.35048318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.918846130371094, + 'FR_Wheel_Angle': -30.938207626342773, + 'Location': array([ -4.01638317, -22.16279221, 0.17389414]), + 'Rotation': array([ -0.06942887, -21.96147346, 0.02441877]), + 'Velocity': array([-0.08063446, 0.07578576, 0.00016252]), + 'brake_input': 0.0, + 'camera_location': array([-7.26994991, 12.84512711, -0.33832595]), + 'camera_rotation': array([ -7.77752209, -10.20114326, -3.06998014]), + 'current_gear_input': False, + 'focus_actor_dist': 1519.1177978515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -803.41003418, -3196.72753906, 55.77779388]), + 'frame': 28315, + 'frame_number': 28315, + 'framesequence': 108890, + 'gaze_dir': array([ 0.98618317, -0.13622284, 0.09207916]), + 'gaze_origin': array([-3.11689162, 0.10505066, -0.08490983]), + 'gaze_valid': True, + 'gaze_vergence': 21.93398094177246, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98469543, -0.1335907 , 0.11190796]), + 'left_gaze_origin': array([-3.14890289, 2.96957707, -0.02242279]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8704833984375, + 'left_pupil_posn': array([ 0.13474476, -0.13243473]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9876709 , -0.13885498, 0.07225037]), + 'right_gaze_origin': array([-3.08488035, -2.75947571, -0.14739686]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0395050048828125, + 'right_pupil_posn': array([-0.34216583, -0.22944641]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.049311812967061996, + 'throttle_input': 0.0, + 'timestamp': 916.7181611768901, + 'timestamp_carla': 916719, + 'timestamp_device': 4070147, + 'timestamp_stream': 916.7181611768901, + 'transform': [array([2.77619314e+00, 1.07169704e+01, 1.00704003e-02]), + array([-7.06719607e-02, -9.81206512e+00, 8.40234477e-03])]} +{'AngularVelocity': array([-0.02191405, 0.0027504 , 1.15826845]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.929569244384766, + 'FR_Wheel_Angle': -30.939422607421875, + 'Location': array([ -4.03881216, -22.1438179 , 0.17389967]), + 'Rotation': array([ -0.07034411, -21.57890701, 0.02287209]), + 'Velocity': array([-0.07452688, 0.06893441, 0.00041271]), + 'brake_input': 0.0, + 'camera_location': array([-7.26306105, 12.80484772, -0.28839812]), + 'camera_rotation': array([ -7.63869858, -10.48754787, -3.23338294]), + 'current_gear_input': False, + 'focus_actor_dist': 1492.90869140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -744.44744873, -3197.20898438, 60.65264893]), + 'frame': 28316, + 'frame_number': 28316, + 'framesequence': 108894, + 'gaze_dir': array([ 0.98678589, -0.13131714, 0.09182739]), + 'gaze_origin': array([-3.13583612, 0.10530243, -0.08161011]), + 'gaze_valid': True, + 'gaze_vergence': 9.091104507446289, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98477173, -0.13011169, 0.11521912]), + 'left_gaze_origin': array([-3.17315841, 2.97085881, -0.01766357]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.813873291015625, + 'left_pupil_posn': array([ 0.13619947, -0.13502645]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98880005, -0.13252258, 0.06843567]), + 'right_gaze_origin': array([-3.09851384, -2.76025414, -0.14555664]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.942840576171875, + 'right_pupil_posn': array([-0.34061068, -0.2295866 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0509231872856617, + 'throttle_input': 0.0, + 'timestamp': 916.7501723766327, + 'timestamp_carla': 916751, + 'timestamp_device': 4070180, + 'timestamp_stream': 916.7501723766327, + 'transform': [array([2.81541800e+00, 1.06346111e+01, 1.02258874e-02]), + array([-7.06651360e-02, -9.89438248e+00, 8.18293542e-03])]} +{'AngularVelocity': array([ 0.0882507 , -0.03043362, 4.30776501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.8003044128418, + 'FR_Wheel_Angle': -30.867115020751953, + 'Location': array([ -4.07813311, -22.11107826, 0.17400129]), + 'Rotation': array([-7.63615072e-02, -2.09012375e+01, 1.36328461e-02]), + 'Velocity': array([-0.20270933, 0.20939782, 0.00048548]), + 'brake_input': 0.0, + 'camera_location': array([-7.27379227, 12.77685928, -0.25699338]), + 'camera_rotation': array([ -7.51669788, -10.73562241, -3.3399415 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1484.9066162109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -744.82928467, -3197.20751953, 63.96650696]), + 'frame': 28317, + 'frame_number': 28317, + 'framesequence': 108898, + 'gaze_dir': array([ 0.98725891, -0.12982178, 0.08969879]), + 'gaze_origin': array([-3.1330049 , 0.10468064, -0.08368836]), + 'gaze_valid': True, + 'gaze_vergence': 12.771971702575684, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98562622, -0.12852478, 0.10957336]), + 'left_gaze_origin': array([-3.17675328, 2.97085285, -0.01769562]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8227691650390625, + 'left_pupil_posn': array([ 0.13673437, -0.13528204]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9888916 , -0.13111877, 0.06982422]), + 'right_gaze_origin': array([-3.08925629, -2.76149154, -0.14968109]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9383544921875, + 'right_pupil_posn': array([-0.33914447, -0.23242807]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.051838744431734085, + 'throttle_input': 0.0, + 'timestamp': 916.7849466763437, + 'timestamp_carla': 916785, + 'timestamp_device': 4070214, + 'timestamp_stream': 916.7849466763437, + 'transform': [array([2.85859680e+00, 1.05460863e+01, 1.03338240e-02]), + array([-7.05558509e-02, -9.98526478e+00, 8.00923817e-03])]} +{'AngularVelocity': array([-0.0951111 , -0.01691019, 5.47525644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.740440368652344, + 'FR_Wheel_Angle': -30.836091995239258, + 'Location': array([ -4.14179611, -22.06023407, 0.17405702]), + 'Rotation': array([-7.58970603e-02, -1.98312969e+01, 1.54162180e-02]), + 'Velocity': array([-0.27335697, 0.24554066, 0.00043765]), + 'brake_input': 0.0, + 'camera_location': array([-7.28428364, 12.75953579, -0.25828576]), + 'camera_rotation': array([ -7.46868849, -10.94120026, -3.29283023]), + 'current_gear_input': False, + 'focus_actor_dist': 1479.1663818359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -749.24609375, -3197.18310547, 63.93391418]), + 'frame': 28318, + 'frame_number': 28318, + 'framesequence': 108903, + 'gaze_dir': array([ 0.98440552, -0.14358521, 0.0994873 ]), + 'gaze_origin': array([-2.9785676 , 0.08993302, -0.13718338]), + 'gaze_valid': True, + 'gaze_vergence': 110.13356018066406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98539734, -0.12791443, 0.11227417]), + 'left_gaze_origin': array([-2.88666248, 2.94780445, -0.11405487]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8482208251953125, + 'left_pupil_posn': array([ 0.14057982, -0.13909578]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9834137 , -0.15925598, 0.08670044]), + 'right_gaze_origin': array([-3.07047296, -2.76793838, -0.16031189]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9766693115234375, + 'right_pupil_posn': array([-0.33433229, -0.2352252 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05299234390258789, + 'throttle_input': 0.0, + 'timestamp': 916.8212108761072, + 'timestamp_carla': 916822, + 'timestamp_device': 4070255, + 'timestamp_stream': 916.8212108761072, + 'transform': [array([2.90405917e+00, 1.04548140e+01, 1.03800204e-02]), + array([-7.03714341e-02, -1.00812387e+01, 7.94578623e-03])]} +{'AngularVelocity': array([ 0.07645321, -0.0169674 , 5.50095797]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.773216247558594, + 'FR_Wheel_Angle': -30.851030349731445, + 'Location': array([ -4.1972785 , -22.01660347, 0.17407908]), + 'Rotation': array([ -0.07143694, -18.89719009, 0.01939889]), + 'Velocity': array([-2.65665859e-01, 2.45026052e-01, 2.60286324e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.29368544, 12.7501564 , -0.27169624]), + 'camera_rotation': array([ -7.43012524, -11.06704712, -3.24989581]), + 'current_gear_input': False, + 'focus_actor_dist': 1479.853759765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -777.19744873, -3197.16772461, 78.97261047]), + 'frame': 28319, + 'frame_number': 28319, + 'framesequence': 108906, + 'gaze_dir': array([ 0.98532867, -0.13930511, 0.09658813]), + 'gaze_origin': array([-3.03134465, 0.09183502, -0.12089616]), + 'gaze_valid': True, + 'gaze_vergence': 69.01013946533203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9848938 , -0.13032532, 0.11398315]), + 'left_gaze_origin': array([-3.00478077, 2.95431828, -0.07657319]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7884674072265625, + 'left_pupil_posn': array([ 0.14079213, -0.13890588]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98576355, -0.14828491, 0.07919312]), + 'right_gaze_origin': array([-3.05790877, -2.77064824, -0.16521913]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.018157958984375, + 'right_pupil_posn': array([-0.33316749, -0.2356472 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05363323166966438, + 'throttle_input': 0.0, + 'timestamp': 916.8503827787936, + 'timestamp_carla': 916851, + 'timestamp_device': 4070280, + 'timestamp_stream': 916.8503827787936, + 'transform': [array([2.93823719e+00, 1.03826647e+01, 1.03810877e-02]), + array([-7.01596960e-02, -1.01539040e+01, 7.94049352e-03])]} +{'AngularVelocity': array([-0.06210602, 0.00864811, 4.80162334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.803504943847656, + 'FR_Wheel_Angle': -30.872346878051758, + 'Location': array([ -4.25801325, -21.97044373, 0.17407015]), + 'Rotation': array([ -0.06909419, -17.89072418, 0.02191621]), + 'Velocity': array([-0.21928504, 0.18386494, 0.00023088]), + 'brake_input': 0.0, + 'camera_location': array([-7.27638578, 12.78009987, -0.26419216]), + 'camera_rotation': array([ -7.45465231, -11.0116291 , -3.27694297]), + 'current_gear_input': False, + 'focus_actor_dist': 1471.0001220703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -773.49926758, -3197.16772461, 76.40310669]), + 'frame': 28320, + 'frame_number': 28320, + 'framesequence': 108910, + 'gaze_dir': array([ 0.98577881, -0.13774872, 0.09429932]), + 'gaze_origin': array([-3.03915572, 0.09387665, -0.11882477]), + 'gaze_valid': True, + 'gaze_vergence': 90.34465026855469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98580933, -0.12715149, 0.10948181]), + 'left_gaze_origin': array([-3.00694442, 2.95484471, -0.0756546 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.75396728515625, + 'left_pupil_posn': array([ 0.14043963, -0.13874531]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98574829, -0.14834595, 0.07911682]), + 'right_gaze_origin': array([-3.07136703, -2.76709151, -0.16199495]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0480804443359375, + 'right_pupil_posn': array([-0.33468336, -0.23741293]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05407269671559334, + 'throttle_input': 0.0, + 'timestamp': 916.8838234767318, + 'timestamp_carla': 916884, + 'timestamp_device': 4070314, + 'timestamp_stream': 916.8838234767318, + 'transform': [array([ 2.97998476, 10.30034447, 0.01043032]), + array([-6.99001551e-02, -1.02425146e+01, 7.95589853e-03])]} +{'AngularVelocity': array([-1.56333279e-02, 3.67289394e-05, 3.43617845e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.860443115234375, + 'FR_Wheel_Angle': -30.902082443237305, + 'Location': array([ -4.3066411 , -21.93500137, 0.17420489]), + 'Rotation': array([ -0.06741396, -17.1105175 , 0.02347629]), + 'Velocity': array([-1.53586581e-01, 1.25134766e-01, -1.21498102e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.25810575, 12.83793831, -0.24598108]), + 'camera_rotation': array([ -7.41338444, -10.77293682, -3.32567787]), + 'current_gear_input': False, + 'focus_actor_dist': 1463.5755615234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -769.2956543 , -3197.16772461, 72.70957184]), + 'frame': 28321, + 'frame_number': 28321, + 'framesequence': 108914, + 'gaze_dir': array([ 0.98618317, -0.13807678, 0.08857727]), + 'gaze_origin': array([-3.10442519, 0.1040657 , -0.10127793]), + 'gaze_valid': True, + 'gaze_vergence': 0.9472372531890869, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98403931, -0.13882446, 0.11129761]), + 'left_gaze_origin': array([-3.14759684, 2.9695437 , -0.03282318]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7937164306640625, + 'left_pupil_posn': array([ 0.13522208, -0.14124537]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98832703, -0.1373291 , 0.06585693]), + 'right_gaze_origin': array([-3.06125355, -2.76141214, -0.16973267]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.995849609375, + 'right_pupil_posn': array([-0.3426773 , -0.24037051]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05478683114051819, + 'throttle_input': 0.0, + 'timestamp': 916.917272977531, + 'timestamp_carla': 916918, + 'timestamp_device': 4070347, + 'timestamp_stream': 916.917272977531, + 'transform': [array([ 3.0210948 , 10.21907425, 0.01046614]), + array([-6.96610957e-02, -1.03301039e+01, 7.97608402e-03])]} +{'AngularVelocity': array([ 1.59669407e-02, -2.96186074e-04, 6.85720205e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.890480041503906, + 'FR_Wheel_Angle': -30.924257278442383, + 'Location': array([ -4.33810425, -21.91237831, 0.17417425]), + 'Rotation': array([ -0.06799453, -16.61585808, 0.02148869]), + 'Velocity': array([-0.11637461, 0.09767515, -0.00121377]), + 'brake_input': 0.0, + 'camera_location': array([-7.24212742, 12.89917564, -0.24655923]), + 'camera_rotation': array([ -7.37431574, -10.48383141, -3.23043919]), + 'current_gear_input': False, + 'focus_actor_dist': 1454.898681640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -763.05493164, -3197.16748047, 65.62332153]), + 'frame': 28322, + 'frame_number': 28322, + 'framesequence': 108918, + 'gaze_dir': array([ 0.98505402, -0.14835358, 0.08561707]), + 'gaze_origin': array([-3.08821273, 0.10638962, -0.10577546]), + 'gaze_valid': True, + 'gaze_vergence': 10.992456436157227, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98326111, -0.15007019, 0.10325623]), + 'left_gaze_origin': array([-3.15247822, 2.97139597, -0.03121033]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7919921875, + 'left_pupil_posn': array([ 0.13074446, -0.14054823]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98684692, -0.14663696, 0.06797791]), + 'right_gaze_origin': array([-3.02394724, -2.75861669, -0.18034059]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91802978515625, + 'right_pupil_posn': array([-0.34817594, -0.24300146]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0552995428442955, + 'throttle_input': 0.0, + 'timestamp': 916.9499974772334, + 'timestamp_carla': 916951, + 'timestamp_device': 4070380, + 'timestamp_stream': 916.9499974772334, + 'transform': [array([ 3.06106997, 10.14053154, 0.01048376]), + array([-6.94220364e-02, -1.04155302e+01, 8.02666973e-03])]} +{'AngularVelocity': array([ 0.02076026, -0.0019452 , 0.48493636]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.92905807495117, + 'FR_Wheel_Angle': -30.945240020751953, + 'Location': array([ -4.35826588, -21.89826775, 0.17422964]), + 'Rotation': array([ -0.06820627, -16.29347229, 0.02075787]), + 'Velocity': array([-0.0813227 , 0.06908828, 0.0015404 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.24333286, 12.96238899, -0.25377002]), + 'camera_rotation': array([ -7.39240217, -10.22277641, -3.18578911]), + 'current_gear_input': False, + 'focus_actor_dist': 1450.7313232421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -770.81567383, -3197.16772461, 62.27349854]), + 'frame': 28323, + 'frame_number': 28323, + 'framesequence': 108922, + 'gaze_dir': array([ 0.98451996, -0.15215302, 0.08442688]), + 'gaze_origin': array([-3.08699131, 0.11115037, -0.1053444 ]), + 'gaze_valid': True, + 'gaze_vergence': 18.814884185791016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98312378, -0.1499176 , 0.10481262]), + 'left_gaze_origin': array([-3.14158797, 2.97559667, -0.03330841]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8509979248046875, + 'left_pupil_posn': array([ 0.12519217, -0.14150584]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98591614, -0.15438843, 0.06404114]), + 'right_gaze_origin': array([-3.03239441, -2.75329614, -0.17738038]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9878692626953125, + 'right_pupil_posn': array([-0.35184759, -0.24208224]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05562914162874222, + 'throttle_input': 0.0, + 'timestamp': 916.9832986779511, + 'timestamp_carla': 916984, + 'timestamp_device': 4070413, + 'timestamp_stream': 916.9832986779511, + 'transform': [array([ 3.10126495, 10.0616169 , 0.01047791]), + array([-6.91556633e-02, -1.05016861e+01, 8.10326543e-03])]} +{'AngularVelocity': array([-0.01289217, 0.01514314, 1.16167319]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.940032958984375, + 'FR_Wheel_Angle': -30.950490951538086, + 'Location': array([ -4.37525892, -21.88637161, 0.17428236]), + 'Rotation': array([ -0.06992064, -16.01029968, 0.01816689]), + 'Velocity': array([-7.35736564e-02, 5.64112701e-02, -8.04614974e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.21994495, 13.03221607, -0.23318671]), + 'camera_rotation': array([-7.29815245, -9.96422768, -3.21061707]), + 'current_gear_input': False, + 'focus_actor_dist': 1443.7747802734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -769.56518555, -3197.16772461, 60.42808533]), + 'frame': 28324, + 'frame_number': 28324, + 'framesequence': 108926, + 'gaze_dir': array([ 0.98505402, -0.15190887, 0.07899475]), + 'gaze_origin': array([-3.10489225, 0.11899873, -0.10278092]), + 'gaze_valid': True, + 'gaze_vergence': 16.553821563720703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98381042, -0.15057373, 0.09706116]), + 'left_gaze_origin': array([-3.19469762, 2.98587513, -0.01865082]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.835601806640625, + 'left_pupil_posn': array([ 0.11878157, -0.14277864]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98629761, -0.15324402, 0.06092834]), + 'right_gaze_origin': array([-3.01508641, -2.7478776 , -0.18691102]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0350341796875, + 'right_pupil_posn': array([-0.35570914, -0.2478056 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.055885497480630875, + 'throttle_input': 0.0, + 'timestamp': 917.0155062787235, + 'timestamp_carla': 917016, + 'timestamp_device': 4070447, + 'timestamp_stream': 917.0155062787235, + 'transform': [array([3.13978314, 9.98622417, 0.01047646]), + array([-6.88824505e-02, -1.05844793e+01, 8.17917008e-03])]} +{'AngularVelocity': array([ 0.02254997, -0.00130728, 1.07631946]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.946895599365234, + 'FR_Wheel_Angle': -30.953384399414062, + 'Location': array([ -4.38967943, -21.87649345, 0.17427568]), + 'Rotation': array([ -0.07012555, -15.77885628, 0.01772898]), + 'Velocity': array([-0.05839632, 0.0489903 , 0.00116182]), + 'brake_input': 0.0, + 'camera_location': array([-7.19279385, 13.11035728, -0.21842358]), + 'camera_rotation': array([-7.21409988, -9.64008427, -3.15402603]), + 'current_gear_input': False, + 'focus_actor_dist': 2117.684326171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -989.1449585 , -3840.01025391, 17.76437378]), + 'frame': 28325, + 'frame_number': 28325, + 'framesequence': 108930, + 'gaze_dir': array([ 0.98248291, -0.16493988, 0.08396912]), + 'gaze_origin': array([-3.10756326, 0.12394639, -0.10157929]), + 'gaze_valid': True, + 'gaze_vergence': 22.6107234954834, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97999573, -0.16921997, 0.10466003]), + 'left_gaze_origin': array([-3.20660734, 2.99107075, -0.01512909]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8492889404296875, + 'left_pupil_posn': array([ 0.11266804, -0.14198744]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98497009, -0.16065979, 0.0632782 ]), + 'right_gaze_origin': array([-3.00851917, -2.74317789, -0.18802948]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.99493408203125, + 'right_pupil_posn': array([-0.36538237, -0.24485505]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05599536374211311, + 'throttle_input': 0.0, + 'timestamp': 917.049455575645, + 'timestamp_carla': 917050, + 'timestamp_device': 4070480, + 'timestamp_stream': 917.049455575645, + 'transform': [array([3.17969394, 9.90781307, 0.01044565]), + array([-6.85819238e-02, -1.06705322e+01, 8.28087237e-03])]} +{'AngularVelocity': array([-0.0143587 , 0.00797253, 0.71387458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.95623016357422, + 'FR_Wheel_Angle': -30.957143783569336, + 'Location': array([ -4.40453768, -21.86639404, 0.17423482]), + 'Rotation': array([ -0.07040559, -15.54927349, 0.01741229]), + 'Velocity': array([-5.26052415e-02, 3.79890203e-02, -8.83388493e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.17914677, 13.19324684, -0.23300092]), + 'camera_rotation': array([-7.34558105, -9.29843903, -3.13928509]), + 'current_gear_input': False, + 'focus_actor_dist': 1431.9561767578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -773.65905762, -3197.16748047, 64.31214142]), + 'frame': 28326, + 'frame_number': 28326, + 'framesequence': 108934, + 'gaze_dir': array([ 0.98355865, -0.16078186, 0.07980347]), + 'gaze_origin': array([-3.13678765, 0.13041687, -0.08738098]), + 'gaze_valid': True, + 'gaze_vergence': 58.021183013916016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98083496, -0.16889954, 0.09706116]), + 'left_gaze_origin': array([-3.23763752e+00, 2.99829888e+00, -2.40020757e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8648681640625, + 'left_pupil_posn': array([ 0.11057806, -0.13930607]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98628235, -0.15266418, 0.06254578]), + 'right_gaze_origin': array([-3.03593755, -2.7374649 , -0.17236176]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9434814453125, + 'right_pupil_posn': array([-0.36946142, -0.24240279]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05599536374211311, + 'throttle_input': 0.0, + 'timestamp': 917.0836364775896, + 'timestamp_carla': 917084, + 'timestamp_device': 4070513, + 'timestamp_stream': 917.0836364775896, + 'transform': [array([3.2191925 , 9.82993603, 0.01040163]), + array([-6.82609081e-02, -1.07559509e+01, 8.41049664e-03])]} +{'AngularVelocity': array([0.30208042, 0.04543261, 4.71279716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.75567626953125, + 'FR_Wheel_Angle': -30.81197166442871, + 'Location': array([ -4.42955112, -21.85040474, 0.17435487]), + 'Rotation': array([-8.12109411e-02, -1.51728697e+01, 2.10720208e-03]), + 'Velocity': array([-0.28331405, 0.22570449, 0.00051282]), + 'brake_input': 0.0, + 'camera_location': array([-7.16184759, 13.27749062, -0.27078497]), + 'camera_rotation': array([-7.47843504, -8.96887589, -3.14413118]), + 'current_gear_input': False, + 'focus_actor_dist': 1420.515380859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -757.9644165 , -3197.16796875, 55.98803711]), + 'frame': 28327, + 'frame_number': 28327, + 'framesequence': 108938, + 'gaze_dir': array([ 0.9822464 , -0.17234802, 0.0712738 ]), + 'gaze_origin': array([-3.11050582, 0.13102418, -0.0909752 ]), + 'gaze_valid': True, + 'gaze_vergence': 38.718544006347656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98170471, -0.16741943, 0.09068298]), + 'left_gaze_origin': array([-3.16396356, 2.99719548, -0.01956482]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.932891845703125, + 'left_pupil_posn': array([ 0.10252392, -0.14099228]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98278809, -0.17727661, 0.05186462]), + 'right_gaze_origin': array([-3.05704808, -2.73514724, -0.16238557]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.99169921875, + 'right_pupil_posn': array([-0.37087435, -0.24168479]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.055153049528598785, + 'throttle_input': 0.0, + 'timestamp': 917.1158944778144, + 'timestamp_carla': 917116, + 'timestamp_device': 4070547, + 'timestamp_stream': 917.1158944778144, + 'transform': [array([3.25568557, 9.75743771, 0.01037905]), + array([-6.78715855e-02, -1.08350849e+01, 8.52811337e-03])]} +{'AngularVelocity': array([-0.10292446, 0.01580315, 9.85751915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.426841735839844, + 'FR_Wheel_Angle': -30.624608993530273, + 'Location': array([ -4.53990316, -21.78081894, 0.17455976]), + 'Rotation': array([-9.03633982e-02, -1.35072222e+01, -7.50732236e-03]), + 'Velocity': array([-6.30516350e-01, 4.39605504e-01, 9.31262985e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.12133121, 13.36768723, -0.26203832]), + 'camera_rotation': array([-7.48124933, -8.6569376 , -3.19767404]), + 'current_gear_input': False, + 'focus_actor_dist': 1758.12353515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -882.02905273, -3516.53735352, 17.65621185]), + 'frame': 28328, + 'frame_number': 28328, + 'framesequence': 108942, + 'gaze_dir': array([ 0.98049164, -0.17935944, 0.07752228]), + 'gaze_origin': array([-3.10414743, 0.13826676, -0.09569245]), + 'gaze_valid': True, + 'gaze_vergence': 37.50412368774414, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97984314, -0.17417908, 0.09770203]), + 'left_gaze_origin': array([-3.15691686, 3.00297403, -0.02510986]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.940582275390625, + 'left_pupil_posn': array([ 0.09599054, -0.14162362]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98114014, -0.18453979, 0.05734253]), + 'right_gaze_origin': array([-3.05137801, -2.72644043, -0.16627504]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0444183349609375, + 'right_pupil_posn': array([-0.37918013, -0.24098551]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.053486742079257965, + 'throttle_input': 0.0, + 'timestamp': 917.1523087769747, + 'timestamp_carla': 917153, + 'timestamp_device': 4070580, + 'timestamp_stream': 917.1523087769747, + 'transform': [array([3.29452682, 9.6770668 , 0.010324 ]), + array([-6.72910213e-02, -1.09197369e+01, 8.64309631e-03])]} +{'AngularVelocity': array([-0.1404703 , -0.06384686, 12.83091354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.32867431640625, + 'FR_Wheel_Angle': -30.59173583984375, + 'Location': array([ -4.72705078, -21.67227936, 0.17469332]), + 'Rotation': array([-8.28296989e-02, -1.07501678e+01, 2.12764484e-03]), + 'Velocity': array([-0.79859906, 0.52506864, 0.00103534]), + 'brake_input': 0.0, + 'camera_location': array([-7.05572367, 13.4628315 , -0.2284849 ]), + 'camera_rotation': array([-7.37734842, -8.25229073, -3.24779391]), + 'current_gear_input': False, + 'focus_actor_dist': 1572.7293701171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -824.53234863, -3347.75585938, 39.11096191]), + 'frame': 28329, + 'frame_number': 28329, + 'framesequence': 108946, + 'gaze_dir': array([ 0.98612213, -0.15158844, 0.06552124]), + 'gaze_origin': array([-3.15338087, 0.11529542, -0.07976685]), + 'gaze_valid': True, + 'gaze_vergence': 38.509708404541016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98554993, -0.1481781 , 0.08204651]), + 'left_gaze_origin': array([-3.20656753, 2.98582792, -0.00978088]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.117401123046875, + 'left_pupil_posn': array([ 0.1183852, -0.1433835]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98669434, -0.15499878, 0.04899597]), + 'right_gaze_origin': array([-3.10019374, -2.7552371 , -0.14975281]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.12127685546875, + 'right_pupil_posn': array([-0.35065079, -0.24471605]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05013580992817879, + 'throttle_input': 0.0, + 'timestamp': 917.18331887573, + 'timestamp_carla': 917184, + 'timestamp_device': 4070613, + 'timestamp_stream': 917.18331887573, + 'transform': [array([3.32610488, 9.60972977, 0.01034451]), + array([-6.65943399e-02, -1.09887400e+01, 8.70630145e-03])]} +{'AngularVelocity': array([-0.04982259, -0.02957866, 11.19929028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.41301345825195, + 'FR_Wheel_Angle': -30.643939971923828, + 'Location': array([ -4.90295982, -21.57822227, 0.17486387]), + 'Rotation': array([-0.06976355, -8.21308327, 0.01736164]), + 'Velocity': array([-0.71734798, 0.42818144, 0.00109895]), + 'brake_input': 0.0, + 'camera_location': array([-6.9814477 , 13.55943298, -0.24475443]), + 'camera_rotation': array([-7.43841696, -7.8667717 , -3.22307444]), + 'current_gear_input': False, + 'focus_actor_dist': 1668.50927734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -803.31469727, -3462.40917969, 17.57563019]), + 'frame': 28330, + 'frame_number': 28330, + 'framesequence': 108950, + 'gaze_dir': array([0.99628448, 0.02757263, 0.07659912]), + 'gaze_origin': array([-2.93351364, -0.04275513, -0.14272843]), + 'gaze_valid': True, + 'gaze_vergence': 72.52286529541016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99728394, 0.04676819, 0.05662537]), + 'left_gaze_origin': array([-2.70119023, 2.81604171, -0.17471772]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2261199951171875, + 'left_pupil_posn': array([ 0.28353977, -0.14130569]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99528503, 0.00837708, 0.09657288]), + 'right_gaze_origin': array([-3.16583729, -2.90155196, -0.11073914]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.979522705078125, + 'right_pupil_posn': array([-0.18163836, -0.24019682]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04434949904680252, + 'throttle_input': 0.07142747938632965, + 'timestamp': 917.2172140777111, + 'timestamp_carla': 917218, + 'timestamp_device': 4070647, + 'timestamp_stream': 917.2172140777111, + 'transform': [array([3.35568666, 9.53845024, 0.01060978]), + array([-6.55288324e-02, -1.10539837e+01, 8.23948160e-03])]} +{'AngularVelocity': array([ 9.37701203e-03, -6.61357958e-03, 7.92120981e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.46546173095703, + 'FR_Wheel_Angle': -30.352474212646484, + 'Location': array([ -5.05248451, -21.50575638, 0.17497712]), + 'Rotation': array([-0.06567226, -6.09885073, 0.02083699]), + 'Velocity': array([-6.16595626e-01, 3.40296239e-01, 4.44192876e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.90324974, 13.67837715, -0.28116897]), + 'camera_rotation': array([-7.57638025, -7.38808298, -3.24234319]), + 'current_gear_input': False, + 'focus_actor_dist': 2145.610107421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST40', + 'focus_actor_pt': array([ -566.68969727, -4011.08032227, 23.62724304]), + 'frame': 28331, + 'frame_number': 28331, + 'framesequence': 108954, + 'gaze_dir': array([0.98239136, 0.17662811, 0.05279541]), + 'gaze_origin': array([-3.06921101, -0.16095124, -0.10342865]), + 'gaze_valid': True, + 'gaze_vergence': 89.94015502929688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97756958, 0.20558167, 0.04571533]), + 'left_gaze_origin': array([-3.06455541, 2.68211985, -0.06705476]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2939453125, + 'left_pupil_posn': array([ 0.43275213, -0.15277278]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98721313, 0.14767456, 0.05987549]), + 'right_gaze_origin': array([-3.07386637, -3.00402236, -0.13980256]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9655303955078125, + 'right_pupil_posn': array([-0.05681002, -0.2487483 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03731803596019745, + 'throttle_input': 0.11903563141822815, + 'timestamp': 917.2490045763552, + 'timestamp_carla': 917250, + 'timestamp_device': 4070680, + 'timestamp_stream': 917.2490045763552, + 'transform': [array([3.38017273, 9.47343731, 0.01090059]), + array([-6.43540397e-02, -1.11082754e+01, 7.75300805e-03])]} +{'AngularVelocity': array([8.50508269e-03, 4.41112462e-03, 5.86688519e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.38175582885742, + 'FR_Wheel_Angle': -26.340839385986328, + 'Location': array([ -5.16895962, -21.45648575, 0.17508765]), + 'Rotation': array([-0.06616404, -4.56637764, 0.02294633]), + 'Velocity': array([-0.55657709, 0.25560194, 0.0005752 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.83423233, 13.81459808, -0.30065849]), + 'camera_rotation': array([-7.72958136, -6.70771027, -3.34863091]), + 'current_gear_input': False, + 'focus_actor_dist': 1736.7689208984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -239.02957153, -3625.29467773, 16.99461365]), + 'frame': 28332, + 'frame_number': 28332, + 'framesequence': 108958, + 'gaze_dir': array([0.98125458, 0.18074799, 0.0594101 ]), + 'gaze_origin': array([-3.0667901 , -0.15925294, -0.09765931]), + 'gaze_valid': True, + 'gaze_vergence': 92.00714111328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97587585, 0.21054077, 0.05761719]), + 'left_gaze_origin': array([-3.05887604, 2.68605661, -0.06350556]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2132415771484375, + 'left_pupil_posn': array([ 0.43100286, -0.14889193]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9866333, 0.1509552, 0.061203 ]), + 'right_gaze_origin': array([-3.07470417, -3.00456238, -0.13181305]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0755462646484375, + 'right_pupil_posn': array([-0.05453372, -0.23944485]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03008514828979969, + 'throttle_input': 0.1587243527173996, + 'timestamp': 917.2833930775523, + 'timestamp_carla': 917284, + 'timestamp_device': 4070713, + 'timestamp_stream': 917.2833930775523, + 'transform': [array([3.40138197, 9.40525818, 0.01105948]), + array([-6.29879981e-02, -1.11559467e+01, 7.48059899e-03])]} +{'AngularVelocity': array([ 2.18040831e-02, -1.43615808e-03, 3.67092991e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.315994262695312, + 'FR_Wheel_Angle': -21.907684326171875, + 'Location': array([ -5.2899847 , -21.41581917, 0.17519437]), + 'Rotation': array([-0.06649872, -3.27423143, 0.02233608]), + 'Velocity': array([-4.77045417e-01, 1.67785585e-01, 4.37049865e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.75033665, 13.97693539, -0.35409772]), + 'camera_rotation': array([-7.8097744 , -5.96045494, -3.6536088 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1864.4541015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -208.6153717 , -3758.24902344, 16.96252441]), + 'frame': 28333, + 'frame_number': 28333, + 'framesequence': 108962, + 'gaze_dir': array([0.98382568, 0.16586304, 0.06217957]), + 'gaze_origin': array([-3.0495708 , -0.15391466, -0.10190201]), + 'gaze_valid': True, + 'gaze_vergence': 106.31768798828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97962952, 0.19168091, 0.05979919]), + 'left_gaze_origin': array([-3.0251832 , 2.69462895, -0.07157899]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3621826171875, + 'left_pupil_posn': array([ 0.41995299, -0.14652407]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98802185, 0.14004517, 0.06455994]), + 'right_gaze_origin': array([-3.07395792, -3.00245833, -0.13222505]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0038604736328125, + 'right_pupil_posn': array([-0.06254441, -0.23838317]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02131412737071514, + 'throttle_input': 0.20236514508724213, + 'timestamp': 917.3159662783146, + 'timestamp_carla': 917317, + 'timestamp_device': 4070747, + 'timestamp_stream': 917.3159662783146, + 'transform': [array([3.41622043, 9.34237289, 0.01095562]), + array([-6.15536608e-02, -1.11900663e+01, 7.75518315e-03])]} +{'AngularVelocity': array([ 0.01330677, -0.00337825, 1.81922936]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.91025733947754, + 'FR_Wheel_Angle': -16.74534034729004, + 'Location': array([ -5.39348078, -21.38942146, 0.17529817]), + 'Rotation': array([-0.06677192, -2.42370629, 0.01946353]), + 'Velocity': array([-4.02964622e-01, 1.04882054e-01, 3.92808899e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.62739658, 14.17228889, -0.37340733]), + 'camera_rotation': array([-7.76837683, -5.26054287, -3.86938977]), + 'current_gear_input': False, + 'focus_actor_dist': 1894.150390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -214.08267212, -3794.64453125, 16.96794128]), + 'frame': 28334, + 'frame_number': 28334, + 'framesequence': 108966, + 'gaze_dir': array([0.98365021, 0.16494751, 0.0681076 ]), + 'gaze_origin': array([-2.94819045, -0.14872514, -0.1341919 ]), + 'gaze_valid': True, + 'gaze_vergence': 99.65234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98118591, 0.18492126, 0.05534363]), + 'left_gaze_origin': array([-2.82316446, 2.69992685, -0.13622743]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.424591064453125, + 'left_pupil_posn': array([ 0.4114331 , -0.14587367]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9861145 , 0.14497375, 0.08087158]), + 'right_gaze_origin': array([-3.07321644, -2.99737716, -0.13215637]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.944793701171875, + 'right_pupil_posn': array([-0.06841278, -0.23956406]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01186559721827507, + 'throttle_input': 0.24998855590820312, + 'timestamp': 917.3505813777447, + 'timestamp_carla': 917351, + 'timestamp_device': 4070780, + 'timestamp_stream': 917.3505813777447, + 'transform': [array([3.42569017, 9.27722263, 0.01059832]), + array([-5.99349067e-02, -1.12130718e+01, 8.49297456e-03])]} +{'AngularVelocity': array([0.07216967, 0.03899527, 2.98781157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.220714569091797, + 'FR_Wheel_Angle': -15.56057071685791, + 'Location': array([ -5.48494148, -21.37206459, 0.17538217]), + 'Rotation': array([-0.06783743, -1.84817505, 0.01412773]), + 'Velocity': array([-3.67560267e-01, 8.04350004e-02, 2.52733211e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.53335094, 14.3720932 , -0.40323871]), + 'camera_rotation': array([-7.97297478, -4.51134634, -3.70026422]), + 'current_gear_input': False, + 'focus_actor_dist': 2140.658203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -183.4468689 , -4046.60522461, 16.93494415]), + 'frame': 28335, + 'frame_number': 28335, + 'framesequence': 108970, + 'gaze_dir': array([0.98330688, 0.15947723, 0.08624268]), + 'gaze_origin': array([-2.86993194, -0.14250946, -0.15218125]), + 'gaze_valid': True, + 'gaze_vergence': 107.33528137207031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98304749, 0.1678009 , 0.07380676]), + 'left_gaze_origin': array([-2.66296244, 2.70701313, -0.18297426]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4393768310546875, + 'left_pupil_posn': array([ 0.40387678, -0.14100492]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98356628, 0.15115356, 0.09867859]), + 'right_gaze_origin': array([-3.07690144, -2.99203181, -0.12138825]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8809356689453125, + 'right_pupil_posn': array([-0.07775313, -0.22616053]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0022339550778269768, + 'throttle_input': 0.3015792965888977, + 'timestamp': 917.383904479444, + 'timestamp_carla': 917384, + 'timestamp_device': 4070813, + 'timestamp_stream': 917.383904479444, + 'transform': [array([3.42868614, 9.21571922, 0.00998449]), + array([-5.83366416e-02, -1.12223253e+01, 9.75901447e-03])]} +{'AngularVelocity': array([-0.04325866, -0.02604232, 1.11887908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.21406364440918, + 'FR_Wheel_Angle': -15.518216133117676, + 'Location': array([ -5.55778408, -21.35945511, 0.17548247]), + 'Rotation': array([-0.06851362, -1.42486584, 0.01132543]), + 'Velocity': array([-0.29216921, 0.0561813 , 0.00073034]), + 'brake_input': 0.0, + 'camera_location': array([-6.47110748, 14.58353424, -0.45381644]), + 'camera_rotation': array([-8.27198696, -3.65915632, -3.31798053]), + 'current_gear_input': False, + 'focus_actor_dist': 2852.173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -131.80458069, -4763.63476562, 16.89071655]), + 'frame': 28336, + 'frame_number': 28336, + 'framesequence': 108974, + 'gaze_dir': array([0.98473358, 0.14765167, 0.09091949]), + 'gaze_origin': array([-2.85925221, -0.13494645, -0.15209046]), + 'gaze_valid': True, + 'gaze_vergence': 148.70635986328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98400879, 0.15837097, 0.08135986]), + 'left_gaze_origin': array([-2.62773919, 2.71568465, -0.19096985]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.308807373046875, + 'left_pupil_posn': array([ 0.39210272, -0.13849866]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98545837, 0.13693237, 0.10047913]), + 'right_gaze_origin': array([-3.09076548, -2.98557758, -0.11321106]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.914642333984375, + 'right_pupil_posn': array([-0.08511549, -0.22025096]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005127109587192535, + 'throttle_input': 0.3293507397174835, + 'timestamp': 917.4155413769186, + 'timestamp_carla': 917416, + 'timestamp_device': 4070847, + 'timestamp_stream': 917.4155413769186, + 'transform': [array([3.42651749e+00, 9.15783215e+00, 9.11424588e-03]), + array([ -0.05695011, -11.2205286 , 0.01154024])]} +{'AngularVelocity': array([0.00885964, 0.04727558, 2.72486901]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.034873962402344, + 'FR_Wheel_Angle': -13.492283821105957, + 'Location': array([ -5.63790035, -21.34683609, 0.17557158]), + 'Rotation': array([-0.07489302, -0.96960443, 0.00751384]), + 'Velocity': array([-4.45885658e-01, 7.75065646e-02, 1.57270435e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.40959549, 14.81766891, -0.4670966 ]), + 'camera_rotation': array([-8.42765427, -2.79709935, -3.27615762]), + 'current_gear_input': False, + 'focus_actor_dist': 2693.951416015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -131.93873596, -4611.15527344, 16.87852478]), + 'frame': 28337, + 'frame_number': 28337, + 'framesequence': 108978, + 'gaze_dir': array([0.98693848, 0.13053894, 0.09224701]), + 'gaze_origin': array([-2.94139433, -0.12583008, -0.12274399]), + 'gaze_valid': True, + 'gaze_vergence': 41.8589973449707, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98800659, 0.13574219, 0.07339478]), + 'left_gaze_origin': array([-2.67064071, 2.72778487, -0.17156373]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4712371826171875, + 'left_pupil_posn': array([ 0.38124514, -0.13013661]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98587036, 0.12533569, 0.11109924]), + 'right_gaze_origin': array([-3.21214747, -2.97944498, -0.07392426]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8739776611328125, + 'right_pupil_posn': array([-0.09619403, -0.21945524]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.008825953118503094, + 'throttle_input': 0.3491874635219574, + 'timestamp': 917.4490649774671, + 'timestamp_carla': 917450, + 'timestamp_device': 4070880, + 'timestamp_stream': 917.4490649774671, + 'transform': [array([3.42065668e+00, 9.09642315e+00, 8.01269524e-03]), + array([ -0.05642419, -11.21106243, 0.01372197])]} +{'AngularVelocity': array([-0.0624662 , -0.0431992 , 2.44538045]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.699716567993164, + 'FR_Wheel_Angle': -9.010124206542969, + 'Location': array([ -5.79901743, -21.32792473, 0.17579171]), + 'Rotation': array([-0.08239257, -0.27722171, 0.00808047]), + 'Velocity': array([-0.70754164, 0.07702552, 0.00099296]), + 'brake_input': 0.0, + 'camera_location': array([-6.33840561, 15.06610489, -0.4855873 ]), + 'camera_rotation': array([-8.53205299, -1.97522938, -3.1952858 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2535.073486328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -146.472229 , -4458.48046875, 16.89440918]), + 'frame': 28338, + 'frame_number': 28338, + 'framesequence': 108983, + 'gaze_dir': array([0.98871613, 0.11688995, 0.09091949]), + 'gaze_origin': array([-2.9595902 , -0.11311188, -0.11443177]), + 'gaze_valid': True, + 'gaze_vergence': 39.58750915527344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98991394, 0.12333679, 0.06956482]), + 'left_gaze_origin': array([-2.69181848, 2.74157262, -0.16280824]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.384429931640625, + 'left_pupil_posn': array([ 0.36743116, -0.12775254]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98751831, 0.11044312, 0.11227417]), + 'right_gaze_origin': array([-3.22736216, -2.96779656, -0.0660553 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8858489990234375, + 'right_pupil_posn': array([-0.10845029, -0.2180711 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011316264048218727, + 'throttle_input': 0.3650568425655365, + 'timestamp': 917.4928820766509, + 'timestamp_carla': 917493, + 'timestamp_device': 4070922, + 'timestamp_stream': 917.4928820766509, + 'transform': [array([3.41331935e+00, 9.01449203e+00, 6.49456028e-03]), + array([ -0.05677936, -11.19895077, 0.01668368])]} +{'AngularVelocity': array([0.01055555, 0.01832377, 1.55059743]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.208676815032959, + 'FR_Wheel_Angle': -4.166239261627197, + 'Location': array([ -5.97200489, -21.31688881, 0.17595601]), + 'Rotation': array([-0.08102653, 0.15626892, 0.01227241]), + 'Velocity': array([-8.76156211e-01, 4.65663709e-02, 5.87005576e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.2807827 , 15.39966583, -0.49203265]), + 'camera_rotation': array([-8.57697582, -0.79644662, -2.79423738]), + 'current_gear_input': False, + 'focus_actor_dist': 2320.35302734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -155.93502808, -4250.00878906, 16.9054184 ]), + 'frame': 28339, + 'frame_number': 28339, + 'framesequence': 108987, + 'gaze_dir': array([0.99022675, 0.10346222, 0.09268188]), + 'gaze_origin': array([-2.94517827, -0.10130387, -0.11611328]), + 'gaze_valid': True, + 'gaze_vergence': 156.171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99026489, 0.11132812, 0.08351135]), + 'left_gaze_origin': array([-2.70833445, 2.75300312, -0.15342408]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2583465576171875, + 'left_pupil_posn': array([ 0.35517085, -0.12765908]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9901886 , 0.09559631, 0.10185242]), + 'right_gaze_origin': array([-3.18202233, -2.95561075, -0.07880249]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8007049560546875, + 'right_pupil_posn': array([-0.12121767, -0.21263015]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.013129062950611115, + 'throttle_input': 0.3650568425655365, + 'timestamp': 917.5264042764902, + 'timestamp_carla': 917527, + 'timestamp_device': 4070955, + 'timestamp_stream': 917.5264042764902, + 'transform': [array([3.40334225e+00, 8.95105457e+00, 5.38507430e-03]), + array([ -0.05696378, -11.18079185, 0.01887321])]} +{'AngularVelocity': array([-0.00428592, -0.03798447, 1.2715342 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.056501902639865875, + 'FR_Wheel_Angle': 0.1618393212556839, + 'Location': array([ -6.19990396, -21.3131218 , 0.17615286]), + 'Rotation': array([-0.08309608, 0.3512103 , 0.01487868]), + 'Velocity': array([-1.11289346e+00, 1.18976308e-03, 8.19482782e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.26332664, 15.66700172, -0.52874315]), + 'camera_rotation': array([-8.75025749, 0.20282665, -2.58036518]), + 'current_gear_input': False, + 'focus_actor_dist': 2291.693603515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -139.44802856, -4228.67138672, 16.88858795]), + 'frame': 28340, + 'frame_number': 28340, + 'framesequence': 108992, + 'gaze_dir': array([0.98693848, 0.13075256, 0.09102631]), + 'gaze_origin': array([-2.9487474 , -0.12081528, -0.11716767]), + 'gaze_valid': True, + 'gaze_vergence': 65.39148712158203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9871521 , 0.14311218, 0.07098389]), + 'left_gaze_origin': array([-2.68288732, 2.7349534 , -0.16311036]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2812042236328125, + 'left_pupil_posn': array([ 0.37441862, -0.12656915]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98672485, 0.11839294, 0.11106873]), + 'right_gaze_origin': array([-3.21460748, -2.97658396, -0.07122498]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8792572021484375, + 'right_pupil_posn': array([-0.09552526, -0.21897411]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0135135967284441, + 'throttle_input': 0.3650568425655365, + 'timestamp': 917.5611293762922, + 'timestamp_carla': 917562, + 'timestamp_device': 4070997, + 'timestamp_stream': 917.5611293762922, + 'transform': [array([3.39216280e+00, 8.88381672e+00, 4.33235150e-03]), + array([ -0.05721649, -11.16020489, 0.02092231])]} +{'AngularVelocity': array([0.01037565, 0.01872604, 0.74764323]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.014986874535679817, + 'FR_Wheel_Angle': 0.0037449218798428774, + 'Location': array([ -6.54881477, -21.31501198, 0.17656514]), + 'Rotation': array([-0.08468751, 0.35060486, 0.01050684]), + 'Velocity': array([-1.42804742, -0.00818542, 0.00179758]), + 'brake_input': 0.0, + 'camera_location': array([-6.28872585, 15.93398571, -0.60054159]), + 'camera_rotation': array([-8.95551109, 1.23056173, -2.3231132 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2153.378173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -50.3120575 , -4088.45239258, 16.79779053]), + 'frame': 28341, + 'frame_number': 28341, + 'framesequence': 108995, + 'gaze_dir': array([0.94952393, 0.30097198, 0.08411407]), + 'gaze_origin': array([-2.98839736, -0.24925691, -0.11731949]), + 'gaze_valid': True, + 'gaze_vergence': 51.54001998901367, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9473877 , 0.31428528, 0.06059265]), + 'left_gaze_origin': array([-2.80266881, 2.58685613, -0.14018098]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3953094482421875, + 'left_pupil_posn': array([ 0.54051316, -0.1390475 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95166016, 0.28765869, 0.1076355 ]), + 'right_gaze_origin': array([-3.17412567, -3.08537006, -0.09445801]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9699554443359375, + 'right_pupil_posn': array([ 0.03925252, -0.23568714]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01468550693243742, + 'throttle_input': 0.3650568425655365, + 'timestamp': 917.5933390781283, + 'timestamp_carla': 917594, + 'timestamp_device': 4071022, + 'timestamp_stream': 917.5933390781283, + 'transform': [array([3.38085508e+00, 8.81982327e+00, 3.38420854e-03]), + array([ -0.05735309, -11.1391449 , 0.02280604])]} +{'AngularVelocity': array([ 0.00379448, -0.06612132, 0.97959018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.002495646011084318, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.85069942, -21.31670189, 0.17681749]), + 'Rotation': array([-0.07974245, 0.3516503 , 0.00921729]), + 'Velocity': array([-1.49165511e+00, -8.25636648e-03, 1.12587924e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.31723404, 16.17702484, -0.65515459]), + 'camera_rotation': array([-9.25595093, 2.43603659, -1.9310267 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2222.90380859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 377.3454895 , -4076.41088867, 16.35830688]), + 'frame': 28342, + 'frame_number': 28342, + 'framesequence': 108999, + 'gaze_dir': array([0.94322968, 0.32266998, 0.07788086]), + 'gaze_origin': array([-2.99060392, -0.25992051, -0.11029129]), + 'gaze_valid': True, + 'gaze_vergence': 101.6334228515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94549561, 0.31834412, 0.06837463]), + 'left_gaze_origin': array([-2.80520201, 2.57553411, -0.13545685]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.280670166015625, + 'left_pupil_posn': array([ 0.56342363, -0.14427555]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94096375, 0.32699585, 0.08738708]), + 'right_gaze_origin': array([-3.1760056 , -3.0953753 , -0.08512574]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.910552978515625, + 'right_pupil_posn': array([ 0.04785359, -0.22698104]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.016956085339188576, + 'throttle_input': 0.3650568425655365, + 'timestamp': 917.6262227781117, + 'timestamp_carla': 917627, + 'timestamp_device': 4071055, + 'timestamp_stream': 917.6262227781117, + 'transform': [array([3.36772656e+00, 8.75296593e+00, 2.54821777e-03]), + array([ -0.05731894, -11.11433887, 0.02444916])]} +{'AngularVelocity': array([-0.00047454, 0.1154736 , -0.27434871]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.96073103, -21.31702614, 0.17652024]), + 'Rotation': array([-0.01215091, 0.30468166, 0.00889809]), + 'Velocity': array([0.2314046 , 0.0011131 , 0.00025811]), + 'brake_input': 0.0, + 'camera_location': array([-6.33210182, 16.4557991 , -0.66640276]), + 'camera_rotation': array([-9.38743877, 3.91703677, -1.72872055]), + 'current_gear_input': False, + 'focus_actor_dist': 1823.5516357421875, + 'focus_actor_name': 'Plane21', + 'focus_actor_pt': array([ 335.86923218, -3674.89892578, 16.62490845]), + 'frame': 28343, + 'frame_number': 28343, + 'framesequence': 109004, + 'gaze_dir': array([0.95167542, 0.29066467, 0.09780884]), + 'gaze_origin': array([-2.98647857, -0.24284136, -0.11208192]), + 'gaze_valid': True, + 'gaze_vergence': 69.50357055664062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95140076, 0.29640198, 0.08345032]), + 'left_gaze_origin': array([-2.80041218, 2.59608936, -0.13933411]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3151092529296875, + 'left_pupil_posn': array([ 0.53295255, -0.1362108 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95195007, 0.28492737, 0.11216736]), + 'right_gaze_origin': array([-3.17254519, -3.08177185, -0.08482972]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8072967529296875, + 'right_pupil_posn': array([ 0.03088343, -0.2197969 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.020105592906475067, + 'throttle_input': 0.3690241873264313, + 'timestamp': 917.662341978401, + 'timestamp_carla': 917663, + 'timestamp_device': 4071097, + 'timestamp_stream': 917.662341978401, + 'transform': [array([3.35068679e+00, 8.67816830e+00, 1.95262907e-03]), + array([ -0.05710038, -11.08156395, 0.02556894])]} +{'AngularVelocity': array([-0.00613662, 0.37987408, -0.00126575]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.006408614572137594, + 'FR_Wheel_Angle': -0.006408471614122391, + 'Location': array([ -6.89159393, -21.31648064, 0.17677335]), + 'Rotation': array([-0.06210008, 0.27322432, 0.00868571]), + 'Velocity': array([0.00034808, 0.00019276, 0.00064058]), + 'brake_input': 0.0, + 'camera_location': array([-6.34671116, 16.70975685, -0.65262777]), + 'camera_rotation': array([-9.24784374, 5.40271616, -1.64263642]), + 'current_gear_input': False, + 'focus_actor_dist': 2341.510009765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 495.98083496, -4175.61816406, 16.23749542]), + 'frame': 28344, + 'frame_number': 28344, + 'framesequence': 109007, + 'gaze_dir': array([0.95742798, 0.2743454 , 0.08914185]), + 'gaze_origin': array([-2.98141026, -0.22839816, -0.10776826]), + 'gaze_valid': True, + 'gaze_vergence': 195.19984436035156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95629883, 0.28059387, 0.08203125]), + 'left_gaze_origin': array([-2.7937119 , 2.61298847, -0.1355301 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2202301025390625, + 'left_pupil_posn': array([ 0.51445568, -0.13709974]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95855713, 0.26809692, 0.09625244]), + 'right_gaze_origin': array([-3.16910863, -3.06978464, -0.08000641]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.732452392578125, + 'right_pupil_posn': array([ 0.01704884, -0.21559477]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02464674785733223, + 'throttle_input': 0.3690241873264313, + 'timestamp': 917.6928121782839, + 'timestamp_carla': 917693, + 'timestamp_device': 4071122, + 'timestamp_stream': 917.6928121782839, + 'transform': [array([3.33328485e+00, 8.61378670e+00, 1.47722242e-03]), + array([ -0.05653347, -11.0475111 , 0.02655826])]} +{'AngularVelocity': array([ 5.76015736e-04, -1.26813743e-02, -1.50587255e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006408488377928734, + 'FR_Wheel_Angle': 0.006408886052668095, + 'Location': array([ -6.89167023, -21.31648064, 0.17684613]), + 'Rotation': array([-0.07390948, 0.27322254, 0.00866809]), + 'Velocity': array([-6.46733679e-06, 2.97338261e-06, -4.44457764e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.39089489, 16.91414452, -0.6877175 ]), + 'camera_rotation': array([-9.46270752, 6.73406029, -1.68788612]), + 'current_gear_input': False, + 'focus_actor_dist': 2017.8575439453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 406.66964722, -3871.15869141, 16.32939148]), + 'frame': 28345, + 'frame_number': 28345, + 'framesequence': 109011, + 'gaze_dir': array([0.96099091, 0.25790405, 0.0978775 ]), + 'gaze_origin': array([-2.97865462, -0.21739578, -0.10359498]), + 'gaze_valid': True, + 'gaze_vergence': 59.73957443237305, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96069336, 0.26585388, 0.07992554]), + 'left_gaze_origin': array([-2.79144597, 2.62520003, -0.13150331]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2558746337890625, + 'left_pupil_posn': array([ 0.49921536, -0.12701201]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96128845, 0.24995422, 0.11582947]), + 'right_gaze_origin': array([-3.16586304, -3.0599916 , -0.07568665]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8201751708984375, + 'right_pupil_posn': array([ 0.00500178, -0.21228611]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.028748435899615288, + 'throttle_input': 0.3690241873264313, + 'timestamp': 917.7256776764989, + 'timestamp_carla': 917726, + 'timestamp_device': 4071155, + 'timestamp_stream': 917.7256776764989, + 'transform': [array([3.31078458e+00, 8.54321480e+00, 1.11959456e-03]), + array([ -0.05578898, -11.00288868, 0.02726655])]} +{'AngularVelocity': array([ 1.78509843e-04, -4.10312787e-03, -8.41767076e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0064084893092513084, + 'FR_Wheel_Angle': 0.006408886983990669, + 'Location': array([ -6.89165688, -21.31648064, 0.17682874]), + 'Rotation': array([-0.07196287, 0.27322149, 0.00860273]), + 'Velocity': array([-2.81436371e-07, 6.56954126e-06, 1.25703198e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.43972206, 17.13296509, -0.71995676]), + 'camera_rotation': array([-9.65890503, 7.96608162, -1.90593278]), + 'current_gear_input': False, + 'focus_actor_dist': 2174.091064453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 473.59329224, -4020.05981445, 16.25969696]), + 'frame': 28346, + 'frame_number': 28346, + 'framesequence': 109016, + 'gaze_dir': array([0.96739197, 0.23696899, 0.08698273]), + 'gaze_origin': array([-2.97252297, -0.19704361, -0.09908448]), + 'gaze_valid': True, + 'gaze_vergence': 76.57466125488281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96615601, 0.24830627, 0.06983948]), + 'left_gaze_origin': array([-2.78378916, 2.64860392, -0.12497101]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2076873779296875, + 'left_pupil_posn': array([ 0.47380173, -0.1243639 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96862793, 0.22563171, 0.10412598]), + 'right_gaze_origin': array([-3.16125631, -3.04269123, -0.07319794]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.72821044921875, + 'right_pupil_posn': array([-0.01324964, -0.21260417]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03413190320134163, + 'throttle_input': 0.3690241873264313, + 'timestamp': 917.7677717767656, + 'timestamp_carla': 917768, + 'timestamp_device': 4071197, + 'timestamp_stream': 917.7677717767656, + 'transform': [array([3.27327299e+00, 8.45190525e+00, 9.53731535e-04]), + array([ -0.05474396, -10.92760849, 0.02758878])]} +{'AngularVelocity': array([ 1.15896612e-04, -2.47553503e-03, 1.34510117e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.89163065, -21.31648064, 0.17682302]), + 'Rotation': array([-0.07183993, 0.27322122, 0.00859929]), + 'Velocity': array([ 1.30028650e-03, 5.81270297e-06, -7.94598818e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.44363594, 17.32598114, -0.71086758]), + 'camera_rotation': array([-9.63170719, 8.96233559, -1.97324324]), + 'current_gear_input': False, + 'focus_actor_dist': 1703.74951171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 310.22137451, -3585.63671875, 16.43026733]), + 'frame': 28347, + 'frame_number': 28347, + 'framesequence': 109020, + 'gaze_dir': array([0.96898651, 0.22879028, 0.09105682]), + 'gaze_origin': array([-2.97104812, -0.18946992, -0.10119171]), + 'gaze_valid': True, + 'gaze_vergence': 76.53650665283203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96800232, 0.23973083, 0.07403564]), + 'left_gaze_origin': array([-2.78150201, 2.65684676, -0.12829132]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.29986572265625, + 'left_pupil_posn': array([ 0.46526182, -0.12472951]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9699707 , 0.21784973, 0.108078 ]), + 'right_gaze_origin': array([-3.16059446, -3.03578663, -0.07409211]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.778411865234375, + 'right_pupil_posn': array([-0.02110046, -0.21151698]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03966185823082924, + 'throttle_input': 0.3690241873264313, + 'timestamp': 917.7987137772143, + 'timestamp_carla': 917799, + 'timestamp_device': 4071230, + 'timestamp_stream': 917.7987137772143, + 'transform': [array([3.24320245e+00, 8.38320827e+00, 9.14649921e-04]), + array([ -0.0538697 , -10.86665726, 0.02770529])]} +{'AngularVelocity': array([ 1.13023125e-05, -2.43325834e-04, 1.35818084e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.89097452, -21.31648064, 0.17686555]), + 'Rotation': array([-0.07183993, 0.27322122, 0.00859929]), + 'Velocity': array([ 4.99824015e-03, 2.16247281e-05, -1.36532472e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.42152214, 17.49312019, -0.69310749]), + 'camera_rotation': array([-9.52006054, 9.75405216, -1.73799944]), + 'current_gear_input': False, + 'focus_actor_dist': 1811.4971923828125, + 'focus_actor_name': 'Plane21', + 'focus_actor_pt': array([ 365.05813599, -3690.33251953, 16.62490082]), + 'frame': 28348, + 'frame_number': 28348, + 'framesequence': 109024, + 'gaze_dir': array([0.97126007, 0.21853638, 0.09228516]), + 'gaze_origin': array([-2.96885681, -0.17954941, -0.10443115]), + 'gaze_valid': True, + 'gaze_vergence': 46.75080871582031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97169495, 0.22428894, 0.07414246]), + 'left_gaze_origin': array([-2.77826715, 2.66934371, -0.13084871]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.29052734375, + 'left_pupil_posn': array([ 0.45475399, -0.12489557]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9708252 , 0.21278381, 0.11042786]), + 'right_gaze_origin': array([-3.15944695, -3.02844262, -0.07801361]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7875213623046875, + 'right_pupil_posn': array([-0.03161561, -0.21343982]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04336069896817207, + 'throttle_input': 0.37299153208732605, + 'timestamp': 917.8328710794449, + 'timestamp_carla': 917833, + 'timestamp_device': 4071263, + 'timestamp_stream': 917.8328710794449, + 'transform': [array([3.20565200e+00, 8.30635357e+00, 1.04408257e-03]), + array([ -0.0530774 , -10.79003525, 0.02743387])]} +{'AngularVelocity': array([-0.00198727, -0.00604165, -0.00697473]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006407514680176973, + 'FR_Wheel_Angle': 0.006407150067389011, + 'Location': array([ -6.891325 , -21.31635666, 0.17686144]), + 'Rotation': array([-0.0726937 , 0.25806394, 0.00854236]), + 'Velocity': array([-9.57204960e-03, 1.91167259e-04, -4.36258306e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.42147541, 17.63679314, -0.70797145]), + 'camera_rotation': array([-9.54314709, 10.43744755, -1.58185256]), + 'current_gear_input': False, + 'focus_actor_dist': 1859.4991455078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 390.65338135, -3739.58569336, 16.3466568 ]), + 'frame': 28349, + 'frame_number': 28349, + 'framesequence': 109028, + 'gaze_dir': array([0.97416687, 0.20720673, 0.08753967]), + 'gaze_origin': array([-2.96568918, -0.17473146, -0.101091 ]), + 'gaze_valid': True, + 'gaze_vergence': 76.14486694335938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97351074, 0.21739197, 0.07077026]), + 'left_gaze_origin': array([-2.77315092, 2.67260909, -0.12976685]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.19354248046875, + 'left_pupil_posn': array([ 0.44671786, -0.12488437]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.974823 , 0.19702148, 0.10430908]), + 'right_gaze_origin': array([-3.15822768, -3.02207184, -0.07241517]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8782196044921875, + 'right_pupil_posn': array([-0.03844041, -0.21037376]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04707785323262215, + 'throttle_input': 0.37299153208732605, + 'timestamp': 917.8658198788762, + 'timestamp_carla': 917866, + 'timestamp_device': 4071297, + 'timestamp_stream': 917.8658198788762, + 'transform': [array([3.16541457e+00, 8.23110199e+00, 1.26281730e-03]), + array([ -0.05244219, -10.70748425, 0.02701622])]} +{'AngularVelocity': array([ 2.65184281e-05, 6.84805959e-03, -1.04831808e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006406736094504595, + 'FR_Wheel_Angle': 0.0064079416915774345, + 'Location': array([ -6.89337206, -21.31635857, 0.17685308]), + 'Rotation': array([-0.0722634 , 0.25812024, 0.00857545]), + 'Velocity': array([-1.45782614e-02, -4.80932067e-05, 1.23677251e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.44652939, 17.73793411, -0.77232277]), + 'camera_rotation': array([-9.88850117, 10.94529533, -1.37476051]), + 'current_gear_input': False, + 'focus_actor_dist': 1686.54296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.0456543 , -3585.35302734, 16.40885162]), + 'frame': 28350, + 'frame_number': 28350, + 'framesequence': 109032, + 'gaze_dir': array([0.97462463, 0.20139313, 0.09481812]), + 'gaze_origin': array([-2.96402979, -0.16987991, -0.09481049]), + 'gaze_valid': True, + 'gaze_vergence': 56.99256896972656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97444153, 0.2119751 , 0.07417297]), + 'left_gaze_origin': array([-2.76974344, 2.67791295, -0.12296296]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.196319580078125, + 'left_pupil_posn': array([ 0.44077516, -0.11559439]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97480774, 0.19081116, 0.11546326]), + 'right_gaze_origin': array([-3.15831614, -3.01767302, -0.06665802]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6962738037109375, + 'right_pupil_posn': array([-0.04328126, -0.20509028]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04986114054918289, + 'throttle_input': 0.37299153208732605, + 'timestamp': 917.8990330770612, + 'timestamp_carla': 917900, + 'timestamp_device': 4071330, + 'timestamp_stream': 917.8990330770612, + 'transform': [array([3.12134695e+00, 8.15400887e+00, 1.54815672e-03]), + array([ -0.05197091, -10.61666203, 0.02646192])]} +{'AngularVelocity': array([ 1.04292143e-04, -2.86712009e-03, -9.15209603e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006403742823749781, + 'FR_Wheel_Angle': 0.006404749117791653, + 'Location': array([ -6.89785767, -21.31635857, 0.17685625]), + 'Rotation': array([-0.07281664, 0.25812024, 0.00857518]), + 'Velocity': array([-0.03372719, -0.00012059, -0.00018448]), + 'brake_input': 0.0, + 'camera_location': array([-6.45915985, 17.83659554, -0.81315839]), + 'camera_rotation': array([-10.19168663, 11.32975101, -1.22168159]), + 'current_gear_input': False, + 'focus_actor_dist': 1694.188720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 341.13623047, -3598.04760742, 16.39839935]), + 'frame': 28351, + 'frame_number': 28351, + 'framesequence': 109036, + 'gaze_dir': array([0.97556305, 0.19271088, 0.1033783 ]), + 'gaze_origin': array([-2.96315479, -0.16683199, -0.09307785]), + 'gaze_valid': True, + 'gaze_vergence': 61.47732925415039, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97572327, 0.20199585, 0.08457947]), + 'left_gaze_origin': array([-2.76590133, 2.68121338, -0.12299348]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0710601806640625, + 'left_pupil_posn': array([ 0.43580747, -0.11247241]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97540283, 0.1834259 , 0.12217712]), + 'right_gaze_origin': array([-3.16040802, -3.01487732, -0.06316223]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.778045654296875, + 'right_pupil_posn': array([-0.04859877, -0.19925261]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0523514524102211, + 'throttle_input': 0.3769741356372833, + 'timestamp': 917.9320145770907, + 'timestamp_carla': 917933, + 'timestamp_device': 4071363, + 'timestamp_stream': 917.9320145770907, + 'transform': [array([3.07439303e+00, 8.07614231e+00, 1.88249582e-03]), + array([ -0.05164989, -10.51950932, 0.02581478])]} +{'AngularVelocity': array([ 0.00020387, 0.15329663, -0.13367011]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00633933674544096, + 'FR_Wheel_Angle': 0.006333110388368368, + 'Location': array([ -6.94091463, -21.31652832, 0.17702879]), + 'Rotation': array([-0.09325939, 0.24400854, 0.0086839 ]), + 'Velocity': array([-0.56477875, -0.00242423, 0.00069394]), + 'brake_input': 0.0, + 'camera_location': array([-6.47912788, 17.92068481, -0.82912594]), + 'camera_rotation': array([-10.28248692, 11.71146488, -1.10123074]), + 'current_gear_input': False, + 'focus_actor_dist': 1754.48046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 362.85568237, -3663.1809082 , 16.37567139]), + 'frame': 28352, + 'frame_number': 28352, + 'framesequence': 109040, + 'gaze_dir': array([0.97728729, 0.18231201, 0.10437775]), + 'gaze_origin': array([-2.9346993 , -0.15134735, -0.10606537]), + 'gaze_valid': True, + 'gaze_vergence': 14.869155883789062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97956848, 0.18565369, 0.07713318]), + 'left_gaze_origin': array([-2.69168115, 2.69713616, -0.15039673]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0931854248046875, + 'left_pupil_posn': array([ 0.42097151, -0.11349738]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9750061 , 0.17897034, 0.13162231]), + 'right_gaze_origin': array([-3.17771769, -2.99983072, -0.06173401]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8202972412109375, + 'right_pupil_posn': array([-0.06461769, -0.20388651]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05442060902714729, + 'throttle_input': 0.3809414803981781, + 'timestamp': 917.9682198762894, + 'timestamp_carla': 917969, + 'timestamp_device': 4071397, + 'timestamp_stream': 917.9682198762894, + 'transform': [array([3.01964402e+00, 7.98925257e+00, 2.38992693e-03]), + array([ -0.05154061, -10.40580463, 0.02477532])]} +{'AngularVelocity': array([ 1.29098375e-03, -3.01605910e-01, 6.28338603e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.00381041, -21.31678963, 0.17682783]), + 'Rotation': array([-0.05517427, 0.25011563, 0.00868418]), + 'Velocity': array([ 0.13792753, 0.00053659, -0.0003164 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.50714493, 17.98502159, -0.8577801 ]), + 'camera_rotation': array([-10.37945557, 12.00356865, -1.03711212]), + 'current_gear_input': False, + 'focus_actor_dist': 1715.818359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 345.57696533, -3637.24584961, 16.39360046]), + 'frame': 28353, + 'frame_number': 28353, + 'framesequence': 109045, + 'gaze_dir': array([0.9786911 , 0.17681885, 0.10166168]), + 'gaze_origin': array([-2.93279362, -0.15068589, -0.10234604]), + 'gaze_valid': True, + 'gaze_vergence': 25.401561737060547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98028564, 0.18121338, 0.07867432]), + 'left_gaze_origin': array([-2.68602753, 2.69837046, -0.1488373 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21136474609375, + 'left_pupil_posn': array([ 0.41767669, -0.11390078]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97709656, 0.17242432, 0.12464905]), + 'right_gaze_origin': array([-3.17955947, -2.99974227, -0.0558548 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8339996337890625, + 'right_pupil_posn': array([-0.06618237, -0.1996181 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.056691184639930725, + 'throttle_input': 0.38887616991996765, + 'timestamp': 918.0026275776327, + 'timestamp_carla': 918003, + 'timestamp_device': 4071438, + 'timestamp_stream': 918.0026275776327, + 'transform': [array([2.96454954e+00, 7.90518045e+00, 2.89710984e-03]), + array([ -0.05141766, -10.29096603, 0.02379004])]} +{'AngularVelocity': array([7.25463105e-05, 8.89175609e-02, 4.11526089e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.92445946, -21.31648445, 0.17673174]), + 'Rotation': array([-0.05273589, 0.25011763, 0.00860834]), + 'Velocity': array([ 4.05654669e-01, 1.56494882e-03, -3.06358328e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.52321148, 18.07130241, -0.88313037]), + 'camera_rotation': array([-10.49977589, 12.35926247, -0.53695565]), + 'current_gear_input': False, + 'focus_actor_dist': 1600.5718994140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 305.79980469, -3538.66845703, 16.43508911]), + 'frame': 28354, + 'frame_number': 28354, + 'framesequence': 109049, + 'gaze_dir': array([0.97906494, 0.17500305, 0.10083008]), + 'gaze_origin': array([-2.93309808, -0.15068589, -0.10247574]), + 'gaze_valid': True, + 'gaze_vergence': 22.822704315185547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98078918, 0.17936707, 0.07652283]), + 'left_gaze_origin': array([-2.68599558, 2.69837046, -0.14909668]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2233123779296875, + 'left_pupil_posn': array([ 0.41705763, -0.11390078]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9773407 , 0.17063904, 0.12513733]), + 'right_gaze_origin': array([-3.18020034, -2.99974227, -0.0558548 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.835174560546875, + 'right_pupil_posn': array([-0.06684691, -0.20044315]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05872371792793274, + 'throttle_input': 0.3928435146808624, + 'timestamp': 918.0393922775984, + 'timestamp_carla': 918040, + 'timestamp_device': 4071472, + 'timestamp_stream': 918.0393922775984, + 'transform': [array([2.90245414e+00, 7.81375980e+00, 3.49422451e-03]), + array([ -0.0513357 , -10.16109371, 0.02259011])]} +{'AngularVelocity': array([2.91935808e-04, 3.07027753e-02, 7.98896508e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.006371541414409876, + 'Location': array([ -6.81852198, -21.31608391, 0.17672655]), + 'Rotation': array([-0.068418 , 0.25012448, 0.00850104]), + 'Velocity': array([ 3.81764293e-01, 1.47263787e-03, -2.70652759e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.52940273, 18.11268234, -0.8651396 ]), + 'camera_rotation': array([-10.51748657, 12.56566715, -0.48335886]), + 'current_gear_input': False, + 'focus_actor_dist': 1507.6336669921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.88192749, -3457.51318359, 16.4601593 ]), + 'frame': 28355, + 'frame_number': 28355, + 'framesequence': 109053, + 'gaze_dir': array([0.97962189, 0.17142487, 0.10199738]), + 'gaze_origin': array([-2.93461704, -0.15045547, -0.1021141 ]), + 'gaze_valid': True, + 'gaze_vergence': 29.56107521057129, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9810791 , 0.17651367, 0.07940674]), + 'left_gaze_origin': array([-2.68619251, 2.69869089, -0.1488373 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2337799072265625, + 'left_pupil_posn': array([ 0.41535032, -0.11390078]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97816467, 0.16633606, 0.12458801]), + 'right_gaze_origin': array([-3.18304157, -2.99960184, -0.05539094]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.831207275390625, + 'right_pupil_posn': array([-0.06789458, -0.1996181 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.061580248177051544, + 'throttle_input': 0.3928435146808624, + 'timestamp': 918.071617577225, + 'timestamp_carla': 918072, + 'timestamp_device': 4071505, + 'timestamp_stream': 918.071617577225, + 'transform': [array([2.84486842e+00, 7.73209715e+00, 3.94554110e-03]), + array([ -0.05098053, -10.04022598, 0.02176467])]} +{'AngularVelocity': array([0.00021219, 0.01408182, 0.00038057]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006394211668521166, + 'FR_Wheel_Angle': 0.006397658493369818, + 'Location': array([ -6.76806021, -21.31589127, 0.17676401]), + 'Rotation': array([-0.07971513, 0.25029361, 0.00845414]), + 'Velocity': array([0.13287005, 0.00053427, 0.00095877]), + 'brake_input': 0.0, + 'camera_location': array([-6.54171944, 18.14382553, -0.86577612]), + 'camera_rotation': array([-10.57443714, 12.73715305, -0.33820978]), + 'current_gear_input': False, + 'focus_actor_dist': 1518.4989013671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.50234985, -3476.74243164, 16.45220947]), + 'frame': 28356, + 'frame_number': 28356, + 'framesequence': 109057, + 'gaze_dir': array([0.97915649, 0.17260742, 0.10470581]), + 'gaze_origin': array([-2.93893528, -0.14934312, -0.10106736]), + 'gaze_valid': True, + 'gaze_vergence': 25.705331802368164, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98077393, 0.1763916 , 0.08332825]), + 'left_gaze_origin': array([-2.69069839, 2.70048857, -0.14776307]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2336883544921875, + 'left_pupil_posn': array([ 0.41514754, -0.11357284]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97753906, 0.16882324, 0.12608337]), + 'right_gaze_origin': array([-3.18717217, -2.99917459, -0.05437165]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9129638671875, + 'right_pupil_posn': array([-0.06814927, -0.19835472]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06438185274600983, + 'throttle_input': 0.3928435146808624, + 'timestamp': 918.1049238778651, + 'timestamp_carla': 918105, + 'timestamp_device': 4071538, + 'timestamp_stream': 918.1049238778651, + 'transform': [array([2.78161764e+00, 7.64625454e+00, 4.37635416e-03]), + array([-0.05047509, -9.9070549 , 0.02094703])]} +{'AngularVelocity': array([-1.77232560e-05, -7.02118222e-03, 2.37112632e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006404420826584101, + 'FR_Wheel_Angle': 0.006407876033335924, + 'Location': array([ -6.75366068, -21.31582642, 0.17674807]), + 'Rotation': array([-0.078916 , 0.25033668, 0.00844011]), + 'Velocity': array([ 0.02601929, 0.00011349, -0.0004404 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.54564095, 18.17351151, -0.86467463]), + 'camera_rotation': array([-10.46099377, 12.94151878, -0.1861507 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1545.7203369140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 309.44247437, -3507.5222168 , 16.43154144]), + 'frame': 28357, + 'frame_number': 28357, + 'framesequence': 109061, + 'gaze_dir': array([0.98081207, 0.16711426, 0.09680939]), + 'gaze_origin': array([-2.98294091, -0.14659578, -0.08676071]), + 'gaze_valid': True, + 'gaze_vergence': 4.18960428237915, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98336792, 0.16734314, 0.07049561]), + 'left_gaze_origin': array([-2.69414544, 2.70261383, -0.14519806]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.24346923828125, + 'left_pupil_posn': array([ 0.41313243, -0.1134932 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97825623, 0.16688538, 0.12312317]), + 'right_gaze_origin': array([-3.27173615, -2.9958055 , -0.02832337]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.873779296875, + 'right_pupil_posn': array([-0.07289338, -0.2012856 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06820887327194214, + 'throttle_input': 0.3928435146808624, + 'timestamp': 918.1369988769293, + 'timestamp_carla': 918138, + 'timestamp_device': 4071572, + 'timestamp_stream': 918.1369988769293, + 'transform': [array([2.71657658e+00, 7.56231165e+00, 4.82440926e-03]), + array([-0.04976476, -9.76968575, 0.02010767])]} +{'AngularVelocity': array([-9.18521473e-05, 2.81490991e-03, 8.23277165e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006403712090104818, + 'FR_Wheel_Angle': 0.006404039449989796, + 'Location': array([ -6.7542448 , -21.31582451, 0.17674959]), + 'Rotation': array([-0.07668936, 0.25035125, 0.00843884]), + 'Velocity': array([-0.03643562, -0.00013142, 0.00021027]), + 'brake_input': 0.0, + 'camera_location': array([-6.56479263, 18.1884613 , -0.88175935]), + 'camera_rotation': array([-10.48427868, 13.06541634, 0.17670202]), + 'current_gear_input': False, + 'focus_actor_dist': 1421.6878662109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 262.83587646, -3402.14599609, 16.48007202]), + 'frame': 28358, + 'frame_number': 28358, + 'framesequence': 109065, + 'gaze_dir': array([0.98084259, 0.16574097, 0.09658051]), + 'gaze_origin': array([-2.99667287, -0.14166108, -0.08556366]), + 'gaze_valid': True, + 'gaze_vergence': 5.471401214599609, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98397827, 0.16667175, 0.06318665]), + 'left_gaze_origin': array([-2.66223454, 2.71061707, -0.15933838]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.254486083984375, + 'left_pupil_posn': array([ 0.40607953, -0.11456156]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97770691, 0.16481018, 0.12997437]), + 'right_gaze_origin': array([-3.33111143, -2.99393916, -0.01178894]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.841583251953125, + 'right_pupil_posn': array([-0.0738312 , -0.20395815]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07157811522483826, + 'throttle_input': 0.3333180844783783, + 'timestamp': 918.1701105758548, + 'timestamp_carla': 918171, + 'timestamp_device': 4071605, + 'timestamp_stream': 918.1701105758548, + 'transform': [array([2.64473057e+00, 7.47447729e+00, 5.37570938e-03]), + array([-0.04899294, -9.61753082, 0.01904119])]} +{'AngularVelocity': array([ 0.00057793, -0.05955613, -0.07787716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006348141469061375, + 'FR_Wheel_Angle': 0.0063460818491876125, + 'Location': array([ -6.82329369, -21.31612968, 0.1769134 ]), + 'Rotation': array([-0.09369653, 0.24036396, 0.00842644]), + 'Velocity': array([-0.52139914, -0.00185502, 0.000666 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.57706356, 18.1612606 , -0.90875393]), + 'camera_rotation': array([-10.67380238, 13.17233276, 0.6646986 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1392.9339599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 256.99951172, -3383.1574707 , 16.48618317]), + 'frame': 28359, + 'frame_number': 28359, + 'framesequence': 109069, + 'gaze_dir': array([0.97872925, 0.17179871, 0.1109314 ]), + 'gaze_origin': array([-2.93575764, -0.13606264, -0.09979706]), + 'gaze_valid': True, + 'gaze_vergence': 44.51948928833008, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9798584 , 0.17544556, 0.0953064 ]), + 'left_gaze_origin': array([-2.66753721, 2.71448231, -0.15229036]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2794647216796875, + 'left_pupil_posn': array([ 0.40475202, -0.11217892]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9776001 , 0.16815186, 0.1265564 ]), + 'right_gaze_origin': array([-3.20397806, -2.98660755, -0.04730377]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.842041015625, + 'right_pupil_posn': array([-0.07688856, -0.19264305]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07527695596218109, + 'throttle_input': 0.2658579349517822, + 'timestamp': 918.2043328769505, + 'timestamp_carla': 918205, + 'timestamp_device': 4071638, + 'timestamp_stream': 918.2043328769505, + 'transform': [array([2.56559992e+00, 7.38268280e+00, 6.16352074e-03]), + array([-0.04827578, -9.44949532, 0.0174945 ])]} +{'AngularVelocity': array([-0.00425597, 0.17269342, 0.22122589]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0063002947717905045, + 'FR_Wheel_Angle': 0.006293757352977991, + 'Location': array([ -6.95603561, -21.31662369, 0.17705613]), + 'Rotation': array([-0.09560898, 0.24615888, 0.00854231]), + 'Velocity': array([-0.9855423 , -0.00336175, 0.00109848]), + 'brake_input': 0.0, + 'camera_location': array([-6.56041718, 18.07454109, -0.91032237]), + 'camera_rotation': array([-10.75568295, 13.2386446 , 0.97214419]), + 'current_gear_input': False, + 'focus_actor_dist': 1577.125732421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 345.86294556, -3556.54980469, 16.39381409]), + 'frame': 28360, + 'frame_number': 28360, + 'framesequence': 109073, + 'gaze_dir': array([0.97891235, 0.16999817, 0.11237335]), + 'gaze_origin': array([-2.9423945 , -0.13646851, -0.09529953]), + 'gaze_valid': True, + 'gaze_vergence': 36.08574676513672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98010254, 0.17195129, 0.0990448 ]), + 'left_gaze_origin': array([-2.67488885, 2.71475387, -0.14872742]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.273773193359375, + 'left_pupil_posn': array([ 0.40476108, -0.11142421]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97772217, 0.16804504, 0.1257019 ]), + 'right_gaze_origin': array([-3.20990014, -2.98769093, -0.04187164]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9342193603515625, + 'right_pupil_posn': array([-0.07726407, -0.18874049]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07815180718898773, + 'throttle_input': 0.1904631108045578, + 'timestamp': 918.2362965792418, + 'timestamp_carla': 918237, + 'timestamp_device': 4071672, + 'timestamp_stream': 918.2362965792418, + 'transform': [array([2.48786712e+00, 7.29616213e+00, 7.12818140e-03]), + array([-0.047784 , -9.2839613 , 0.01563824])]} +{'AngularVelocity': array([-7.58156355e-04, -1.10245615e-01, -8.27053070e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.006288648117333651, + 'FR_Wheel_Angle': 0.00629059411585331, + 'Location': array([ -7.1443119 , -21.31739426, 0.17719762]), + 'Rotation': array([-0.08850559, 0.25123093, 0.00886576]), + 'Velocity': array([-1.04746842, -0.00423214, 0.00106588]), + 'brake_input': 0.0, + 'camera_location': array([-6.5479393 , 17.97623062, -0.89340883]), + 'camera_rotation': array([-10.63210392, 13.21669579, 0.84913385]), + 'current_gear_input': False, + 'focus_actor_dist': 1557.9749755859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 342.68222046, -3547.93652344, 16.39711761]), + 'frame': 28361, + 'frame_number': 28361, + 'framesequence': 109077, + 'gaze_dir': array([0.97879028, 0.17047882, 0.11263275]), + 'gaze_origin': array([-2.94309783, -0.13700791, -0.09512406]), + 'gaze_valid': True, + 'gaze_vergence': 54.287139892578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97976685, 0.17419434, 0.098526 ]), + 'left_gaze_origin': array([-2.67625904, 2.71422744, -0.14845887]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.28656005859375, + 'left_pupil_posn': array([ 0.40471065, -0.11117983]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97781372, 0.16676331, 0.1267395 ]), + 'right_gaze_origin': array([-3.20993662, -2.98824334, -0.04178925]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9053497314453125, + 'right_pupil_posn': array([-0.07606721, -0.18884504]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0808984637260437, + 'throttle_input': 0.15475699305534363, + 'timestamp': 918.2704364769161, + 'timestamp_carla': 918271, + 'timestamp_device': 4071705, + 'timestamp_stream': 918.2704364769161, + 'transform': [array([2.40085363, 7.20329094, 0.00845333]), + array([-0.04756543, -9.09820366, 0.01303361])]} +{'AngularVelocity': array([ 0.00144229, -0.41505367, 0.29165918]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.34352541, -21.31822395, 0.17728308]), + 'Rotation': array([-0.06951766, 0.25803334, 0.0090727 ]), + 'Velocity': array([-0.69302827, -0.00302894, 0.00092702]), + 'brake_input': 0.0, + 'camera_location': array([-6.52709484, 17.91017914, -0.87216043]), + 'camera_rotation': array([-10.55534649, 13.20381832, 0.75495136]), + 'current_gear_input': False, + 'focus_actor_dist': 1617.0897216796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 370.95019531, -3610.64355469, 16.36768341]), + 'frame': 28362, + 'frame_number': 28362, + 'framesequence': 109081, + 'gaze_dir': array([0.97883606, 0.17027283, 0.11249542]), + 'gaze_origin': array([-2.94201064, -0.13754044, -0.09562454]), + 'gaze_valid': True, + 'gaze_vergence': 60.65567398071289, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97970581, 0.17448425, 0.09851074]), + 'left_gaze_origin': array([-2.67488885, 2.71350718, -0.14872742]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2867431640625, + 'left_pupil_posn': array([ 0.40491343, -0.11118269]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97796631, 0.1660614 , 0.1264801 ]), + 'right_gaze_origin': array([-3.20913267, -2.98858809, -0.04252167]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9315185546875, + 'right_pupil_posn': array([-0.07576728, -0.1892699 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0840296670794487, + 'throttle_input': 0.11903563141822815, + 'timestamp': 918.3023280762136, + 'timestamp_carla': 918303, + 'timestamp_device': 4071738, + 'timestamp_stream': 918.3023280762136, + 'transform': [array([2.3165586 , 7.11633539, 0.00995655]), + array([-0.04750396, -8.91775322, 0.0101181 ])]} +{'AngularVelocity': array([-0.00015511, 0.10029306, 0.10616399]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.32997608, -21.31825829, 0.17700365]), + 'Rotation': array([-0.02337291, 0.2761589 , 0.00883942]), + 'Velocity': array([ 3.82789344e-01, 1.64384558e-03, -2.38494875e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.49654961, 17.8115387 , -0.83372903]), + 'camera_rotation': array([-10.48739243, 13.1929493 , 0.6562953 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1649.7706298828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 388.6522522 , -3649.88305664, 16.34925079]), + 'frame': 28363, + 'frame_number': 28363, + 'framesequence': 109084, + 'gaze_dir': array([0.98039246, 0.17028809, 0.09589386]), + 'gaze_origin': array([-2.94954848, -0.14390336, -0.09566422]), + 'gaze_valid': True, + 'gaze_vergence': 4.611133098602295, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98275757, 0.170578 , 0.07118225]), + 'left_gaze_origin': array([-2.6785295 , 2.70765996, -0.15126649]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3040924072265625, + 'left_pupil_posn': array([ 0.4103061 , -0.11555266]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97802734, 0.16999817, 0.12060547]), + 'right_gaze_origin': array([-3.22056746, -2.99546671, -0.04006195]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9532470703125, + 'right_pupil_posn': array([-0.07259935, -0.19944918]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08644673228263855, + 'throttle_input': 0.0952315554022789, + 'timestamp': 918.3335830792785, + 'timestamp_carla': 918334, + 'timestamp_device': 4071763, + 'timestamp_stream': 918.3335830792785, + 'transform': [array([2.23118711, 7.03116417, 0.01160799]), + array([-4.76269051e-02, -8.73455238e+00, 6.90963399e-03])]} +{'AngularVelocity': array([-5.71765704e-04, 1.17904104e-01, 2.07999456e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.2439642 , -21.31788063, 0.17708513]), + 'Rotation': array([-0.05154061, 0.27552739, 0.00883979]), + 'Velocity': array([4.43944931e-01, 1.90978835e-03, 1.74808505e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.45323372, 17.71991539, -0.80755544]), + 'camera_rotation': array([-10.45081043, 13.18039417, 0.45221165]), + 'current_gear_input': False, + 'focus_actor_dist': 1358.42333984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 273.68811035, -3391.73974609, 16.46898651]), + 'frame': 28364, + 'frame_number': 28364, + 'framesequence': 109088, + 'gaze_dir': array([0.98006439, 0.17059326, 0.09931183]), + 'gaze_origin': array([-2.94783807, -0.14741898, -0.09779663]), + 'gaze_valid': True, + 'gaze_vergence': 24.508625030517578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98162842, 0.17422485, 0.07757568]), + 'left_gaze_origin': array([-2.67687845, 2.70506454, -0.15201417]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3248138427734375, + 'left_pupil_posn': array([ 0.4109534, -0.1156528]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97850037, 0.16696167, 0.12104797]), + 'right_gaze_origin': array([-3.21879768, -2.99990249, -0.04357911]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9414520263671875, + 'right_pupil_posn': array([-0.06817305, -0.19920611]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08860743790864944, + 'throttle_input': 0.07539482414722443, + 'timestamp': 918.3640590757132, + 'timestamp_carla': 918365, + 'timestamp_device': 4071797, + 'timestamp_stream': 918.3640590757132, + 'transform': [array([2.14592838, 6.94828367, 0.01333389]), + array([-4.79206033e-02, -8.55113697e+00, 3.55315721e-03])]} +{'AngularVelocity': array([-0.000283 , 0.10554883, 0.00068752]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0063779354095458984, + 'FR_Wheel_Angle': 0.006382530555129051, + 'Location': array([ -7.17382812, -21.31757355, 0.17712335]), + 'Rotation': array([-0.070952 , 0.27558169, 0.00879617]), + 'Velocity': array([ 2.84535289e-01, 1.25254365e-03, -1.73029897e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.44720268, 17.6546154 , -0.81535602]), + 'camera_rotation': array([-10.45178032, 13.24479294, 0.28351557]), + 'current_gear_input': False, + 'focus_actor_dist': 1435.61083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 309.74246216, -3470.89013672, 16.43144226]), + 'frame': 28365, + 'frame_number': 28365, + 'framesequence': 109092, + 'gaze_dir': array([0.97953796, 0.17329407, 0.09939575]), + 'gaze_origin': array([-2.94864058, -0.14860612, -0.09819412]), + 'gaze_valid': True, + 'gaze_vergence': 23.911178588867188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98118591, 0.17753601, 0.07577515]), + 'left_gaze_origin': array([-2.67643595, 2.70430923, -0.15287323]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.334991455078125, + 'left_pupil_posn': array([ 0.41218174, -0.1155231 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97789001, 0.16905212, 0.12301636]), + 'right_gaze_origin': array([-3.22084498, -3.00152159, -0.04351502]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.937255859375, + 'right_pupil_posn': array([-0.06592149, -0.20033157]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09098789095878601, + 'throttle_input': 0.05555810034275055, + 'timestamp': 918.394320178777, + 'timestamp_carla': 918395, + 'timestamp_device': 4071830, + 'timestamp_stream': 918.394320178777, + 'transform': [array([2.05948019, 6.86632776, 0.01512462]), + array([-4.83235866e-02, -8.36470127e+00, 6.10790157e-05])]} +{'AngularVelocity': array([-0.00020539, 0.02231303, 0.00104317]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0064009749330580235, + 'FR_Wheel_Angle': 0.0064022596925497055, + 'Location': array([ -7.13973999, -21.31742859, 0.17714708]), + 'Rotation': array([-0.08083528, 0.27568135, 0.00877925]), + 'Velocity': array([0.07658371, 0.00034439, 0.00028012]), + 'brake_input': 0.0, + 'camera_location': array([-6.46504402, 17.61903191, -0.85500079]), + 'camera_rotation': array([-10.47891617, 13.31537151, 0.09539559]), + 'current_gear_input': False, + 'focus_actor_dist': 1446.0736083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.5604248 , -3486.29248047, 16.41716766]), + 'frame': 28366, + 'frame_number': 28366, + 'framesequence': 109096, + 'gaze_dir': array([0.97942352, 0.17404938, 0.09893036]), + 'gaze_origin': array([-2.95008469, -0.14957276, -0.09755173]), + 'gaze_valid': True, + 'gaze_vergence': 21.4520206451416, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98118591, 0.17810059, 0.07434082]), + 'left_gaze_origin': array([-2.67631698, 2.70301056, -0.15261689]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.319976806640625, + 'left_pupil_posn': array([ 0.41338575, -0.11514044]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97766113, 0.16999817, 0.1235199 ]), + 'right_gaze_origin': array([-3.22385287, -3.00215602, -0.04248657]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.942901611328125, + 'right_pupil_posn': array([-0.06526434, -0.2007426 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09292886406183243, + 'throttle_input': 0.03967345505952835, + 'timestamp': 918.4274483770132, + 'timestamp_carla': 918428, + 'timestamp_device': 4071863, + 'timestamp_stream': 918.4274483770132, + 'transform': [array([1.96292257, 6.77720928, 0.0171352 ]), + array([-4.89997752e-02, -8.15602016e+00, -3.91055131e-03])]} +{'AngularVelocity': array([-0.00774635, 0.13710192, -0.69094521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005089330021291971, + 'FR_Wheel_Angle': 0.005074463784694672, + 'Location': array([ -7.14874792, -21.31738281, 0.17713223]), + 'Rotation': array([-0.08575985, 0.26250938, 0.00885313]), + 'Velocity': array([-2.47762337e-01, -2.05171225e-03, 4.94003280e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.51320648, 17.60988808, -0.84101593]), + 'camera_rotation': array([-10.53112698, 13.40308952, -0.1044838 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1438.5904541015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.50216675, -3486.27832031, 16.41307831]), + 'frame': 28367, + 'frame_number': 28367, + 'framesequence': 109099, + 'gaze_dir': array([0.97907257, 0.17610168, 0.09880829]), + 'gaze_origin': array([-2.95075774, -0.14996414, -0.09696808]), + 'gaze_valid': True, + 'gaze_vergence': 20.471399307250977, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98086548, 0.17988586, 0.07432556]), + 'left_gaze_origin': array([-2.67600274, 2.70280623, -0.15202332]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3202362060546875, + 'left_pupil_posn': array([ 0.41431093, -0.11480677]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97727966, 0.1723175 , 0.12329102]), + 'right_gaze_origin': array([-3.22551274, -3.00273442, -0.04191284]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.950225830078125, + 'right_pupil_posn': array([-0.06422102, -0.2007426 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09496139734983444, + 'throttle_input': 0.0317387655377388, + 'timestamp': 918.4592268764973, + 'timestamp_carla': 918460, + 'timestamp_device': 4071888, + 'timestamp_stream': 918.4592268764973, + 'transform': [array([1.86920309, 6.69233608, 0.01905991]), + array([-4.97374348e-02, -7.95295238e+00, -7.68399844e-03])]} +{'AngularVelocity': array([0.0001153 , 0.0134704 , 0.04210323]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005030798260122538, + 'FR_Wheel_Angle': 0.005016666371375322, + 'Location': array([ -7.30689621, -21.3182621 , 0.17742357]), + 'Rotation': array([-0.10412623, 0.27940476, 0.00889718]), + 'Velocity': array([-0.99020857, -0.00399627, 0.00125339]), + 'brake_input': 0.0, + 'camera_location': array([-6.55518627, 17.6145916 , -0.81763369]), + 'camera_rotation': array([-10.43352985, 13.51243019, -0.25097376]), + 'current_gear_input': False, + 'focus_actor_dist': 1431.5948486328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 334.26470947, -3486.33056641, 16.40615845]), + 'frame': 28368, + 'frame_number': 28368, + 'framesequence': 109103, + 'gaze_dir': array([0.97924042, 0.17491913, 0.09902954]), + 'gaze_origin': array([-2.9510324 , -0.15125734, -0.09661485]), + 'gaze_valid': True, + 'gaze_vergence': 22.693124771118164, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98097229, 0.17951965, 0.07380676]), + 'left_gaze_origin': array([-2.67585468, 2.70126963, -0.15185547]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3187713623046875, + 'left_pupil_posn': array([ 0.41464841, -0.11431217]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97750854, 0.1703186 , 0.12425232]), + 'right_gaze_origin': array([-3.22621012, -3.00378418, -0.04137421]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9550323486328125, + 'right_pupil_posn': array([-0.06363034, -0.20069206]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09662771224975586, + 'throttle_input': 0.0238040741533041, + 'timestamp': 918.492700278759, + 'timestamp_carla': 918493, + 'timestamp_device': 4071921, + 'timestamp_stream': 918.492700278759, + 'transform': [array([1.76938379, 6.6037159 , 0.02101975]), + array([-0.05065268, -7.73617077, -0.01155305])]} +{'AngularVelocity': array([-0.00197631, -0.08484814, 0.88976967]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60826206, -21.31971169, 0.17769507]), + 'Rotation': array([-0.09915385, 0.29284132, 0.00924044]), + 'Velocity': array([-1.45372736e+00, -6.62701065e-03, 1.25970843e-03]), + 'brake_input': 0.0, + 'camera_location': array([-6.59621239, 17.62055016, -0.76584482]), + 'camera_rotation': array([-10.18079281, 13.64508057, -0.13959077]), + 'current_gear_input': False, + 'focus_actor_dist': 1472.179931640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 357.80178833, -3530.71875 , 16.38169861]), + 'frame': 28369, + 'frame_number': 28369, + 'framesequence': 109107, + 'gaze_dir': array([0.97938538, 0.17475128, 0.0978775 ]), + 'gaze_origin': array([-2.95227599, -0.15168075, -0.09559937]), + 'gaze_valid': True, + 'gaze_vergence': 22.145719528198242, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98110962, 0.17921448, 0.07264709]), + 'left_gaze_origin': array([-2.67629099, 2.70126963, -0.15104829]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3182220458984375, + 'left_pupil_posn': array([ 0.41464841, -0.11424625]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97766113, 0.17028809, 0.12310791]), + 'right_gaze_origin': array([-3.22826099, -3.00463128, -0.04015045]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9658660888671875, + 'right_pupil_posn': array([-0.06314254, -0.20069468]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09860531240701675, + 'throttle_input': 0.0158693827688694, + 'timestamp': 918.5259811766446, + 'timestamp_carla': 918527, + 'timestamp_device': 4071955, + 'timestamp_stream': 918.5259811766446, + 'transform': [array([1.66937196, 6.51646233, 0.0228669 ]), + array([-0.05164989, -7.51843786, -0.01518757])]} +{'AngularVelocity': array([-1.16140596e-04, 1.23059615e-01, -1.91738600e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.63892126, -21.31984329, 0.1773039 ]), + 'Rotation': array([-0.01849615, 0.29345572, 0.00926364]), + 'Velocity': array([ 3.85025352e-01, 1.77571585e-03, -2.29616155e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.64237595, 17.64978409, -0.72044629]), + 'camera_rotation': array([-9.90111637, 13.76413536, -0.14614332]), + 'current_gear_input': False, + 'focus_actor_dist': 1526.068359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 390.43893433, -3585.97338867, 16.34779358]), + 'frame': 28370, + 'frame_number': 28370, + 'framesequence': 109111, + 'gaze_dir': array([0.98020172, 0.1722641 , 0.09273529]), + 'gaze_origin': array([-2.9604311 , -0.15136109, -0.09534455]), + 'gaze_valid': True, + 'gaze_vergence': 14.109681129455566, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9823761, 0.1759491, 0.0629425]), + 'left_gaze_origin': array([-2.6761353 , 2.70136881, -0.15104829]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.320159912109375, + 'left_pupil_posn': array([ 0.41397977, -0.11438692]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97802734, 0.1685791 , 0.12252808]), + 'right_gaze_origin': array([-3.24472666, -3.00409102, -0.03964081]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.99786376953125, + 'right_pupil_posn': array([-0.06463575, -0.20696902]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10083926469087601, + 'throttle_input': 0.0, + 'timestamp': 918.55966437608, + 'timestamp_carla': 918560, + 'timestamp_device': 4071988, + 'timestamp_stream': 918.55966437608, + 'transform': [array([1.56785691, 6.42893553, 0.02453523]), + array([-0.05238072, -7.29671621, -0.01846747])]} +{'AngularVelocity': array([-4.21605160e-04, 7.01406151e-02, -5.74246322e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00512685114517808, + 'FR_Wheel_Angle': 0.0051271067932248116, + 'Location': array([ -7.60844183, -21.31969833, 0.1775234 ]), + 'Rotation': array([-0.06882098, 0.29338536, 0.00921907]), + 'Velocity': array([5.19351270e-05, 7.16825571e-06, 6.06461661e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.65610313, 17.69153404, -0.66842288]), + 'camera_rotation': array([-9.57051563, 13.85533524, -0.11575744]), + 'current_gear_input': False, + 'focus_actor_dist': 1517.20849609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 392.08966064, -3586.11865234, 16.34610748]), + 'frame': 28371, + 'frame_number': 28371, + 'framesequence': 109116, + 'gaze_dir': array([0.98053741, 0.17236328, 0.0894928 ]), + 'gaze_origin': array([-2.95513225, -0.15074769, -0.09968109]), + 'gaze_valid': True, + 'gaze_vergence': 17.10747718811035, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9823761 , 0.17654419, 0.06134033]), + 'left_gaze_origin': array([-2.67588973, 2.70207071, -0.15240327]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3168182373046875, + 'left_pupil_posn': array([ 0.41335237, -0.11685658]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97869873, 0.16818237, 0.11764526]), + 'right_gaze_origin': array([-3.23437524, -3.00356627, -0.04695893]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.887237548828125, + 'right_pupil_posn': array([-0.0648483 , -0.21032214]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10278024524450302, + 'throttle_input': 0.0, + 'timestamp': 918.5933546759188, + 'timestamp_carla': 918594, + 'timestamp_device': 4072030, + 'timestamp_stream': 918.5933546759188, + 'transform': [array([1.46573329, 6.34229946, 0.02578016]), + array([-0.05300226, -7.07308531, -0.02093063])]} +{'AngularVelocity': array([3.96518408e-05, 4.63465258e-04, 1.72299463e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17757708]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([3.12886186e-06, 6.54906034e-06, 1.53450790e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.66328621, 17.7217865 , -0.61566103]), + 'camera_rotation': array([-9.32771587, 13.94033718, -0.03030379]), + 'current_gear_input': False, + 'focus_actor_dist': 1563.8272705078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 421.55502319, -3634.64770508, 16.31552124]), + 'frame': 28372, + 'frame_number': 28372, + 'framesequence': 109120, + 'gaze_dir': array([0.98068237, 0.17383575, 0.08537292]), + 'gaze_origin': array([-2.94734192, -0.14960176, -0.10674134]), + 'gaze_valid': True, + 'gaze_vergence': 13.257035255432129, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9825592 , 0.17654419, 0.05830383]), + 'left_gaze_origin': array([-2.66031504, 2.70433974, -0.1656006 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2926788330078125, + 'left_pupil_posn': array([ 0.41238725, -0.12435389]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97880554, 0.17112732, 0.11244202]), + 'right_gaze_origin': array([-3.23436904, -3.00354314, -0.04788208]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.834014892578125, + 'right_pupil_posn': array([-0.0648483 , -0.21190763]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10528885573148727, + 'throttle_input': 0.0, + 'timestamp': 918.6282506771386, + 'timestamp_carla': 918629, + 'timestamp_device': 4072063, + 'timestamp_stream': 918.6282506771386, + 'transform': [array([1.35897398, 6.25365973, 0.02675371]), + array([-0.05345989, -6.8387723 , -0.02289373])]} +{'AngularVelocity': array([-3.68173205e-05, -2.60818924e-04, 3.19351375e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17756833]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([3.20625486e-06, 6.70521104e-06, 6.39186183e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.67271137, 17.76128387, -0.59190476]), + 'camera_rotation': array([-9.21022987, 14.02042389, -0.06862096]), + 'current_gear_input': False, + 'focus_actor_dist': 1559.800537109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 430.57806396, -3636.44995117, 16.3062439 ]), + 'frame': 28373, + 'frame_number': 28373, + 'framesequence': 109123, + 'gaze_dir': array([0.98130035, 0.17233276, 0.08157349]), + 'gaze_origin': array([-2.9491837 , -0.14904709, -0.1062668 ]), + 'gaze_valid': True, + 'gaze_vergence': 16.581315994262695, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98287964, 0.17562866, 0.05561829]), + 'left_gaze_origin': array([-2.66163635, 2.70532084, -0.16538849]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2840118408203125, + 'left_pupil_posn': array([ 0.41103983, -0.12602353]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97972107, 0.16903687, 0.10752869]), + 'right_gaze_origin': array([-3.23673105, -3.00341511, -0.04714508]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.878326416015625, + 'right_pupil_posn': array([-0.06529945, -0.21286678]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10733970254659653, + 'throttle_input': 0.0, + 'timestamp': 918.660210378468, + 'timestamp_carla': 918661, + 'timestamp_device': 4072088, + 'timestamp_stream': 918.660210378468, + 'transform': [array([1.26100338, 6.17337656, 0.02749021]), + array([-0.05384238, -6.62319756, -0.02434523])]} +{'AngularVelocity': array([-2.12100513e-05, -6.75430492e-05, -1.21037565e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17756703]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.83825216e-06, 5.52817937e-07, 2.47830787e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.70048332, 17.79434967, -0.58533055]), + 'camera_rotation': array([-9.15319061e+00, 1.40865355e+01, -1.34017942e-02]), + 'current_gear_input': False, + 'focus_actor_dist': 1524.4404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 420.99377441, -3612.66650391, 16.31622314]), + 'frame': 28374, + 'frame_number': 28374, + 'framesequence': 109127, + 'gaze_dir': array([0.98136139, 0.17203522, 0.0819397 ]), + 'gaze_origin': array([-2.94992232, -0.14858247, -0.10675202]), + 'gaze_valid': True, + 'gaze_vergence': 12.08841323852539, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.983078 , 0.17391968, 0.05747986]), + 'left_gaze_origin': array([-2.66052103, 2.70618916, -0.16562197]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2840728759765625, + 'left_pupil_posn': array([ 0.41080475, -0.12637925]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97964478, 0.17015076, 0.10639954]), + 'right_gaze_origin': array([-3.23932362, -3.00335407, -0.04788208]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8704681396484375, + 'right_pupil_posn': array([-0.06590652, -0.21319842]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1089877039194107, + 'throttle_input': 0.0, + 'timestamp': 918.6929806768894, + 'timestamp_carla': 918694, + 'timestamp_device': 4072121, + 'timestamp_stream': 918.6929806768894, + 'transform': [array([1.1601454 , 6.09202385, 0.02809731]), + array([-0.05425219, -6.40080404, -0.02557383])]} +{'AngularVelocity': array([-3.65176493e-05, -4.74543813e-05, -1.30360795e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17752214]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.54175620e-06, 3.59310064e-07, 1.41578013e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.72381973, 17.8278904 , -0.59863508]), + 'camera_rotation': array([-9.23052883e+00, 1.41135817e+01, -4.54360154e-03]), + 'current_gear_input': False, + 'focus_actor_dist': 1547.6448974609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 439.10540771, -3639.59106445, 16.29745483]), + 'frame': 28375, + 'frame_number': 28375, + 'framesequence': 109132, + 'gaze_dir': array([0.98149872, 0.17070007, 0.0823822 ]), + 'gaze_origin': array([-2.95145512, -0.14818802, -0.10754166]), + 'gaze_valid': True, + 'gaze_vergence': 5.474575996398926, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98362732, 0.17129517, 0.05578613]), + 'left_gaze_origin': array([-2.66031504, 2.70645308, -0.16701967]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2738189697265625, + 'left_pupil_posn': array([ 0.41061556, -0.12637925]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97937012, 0.17010498, 0.10897827]), + 'right_gaze_origin': array([-3.2425952 , -3.00282907, -0.04806366]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8621063232421875, + 'right_pupil_posn': array([-0.06718004, -0.21448255]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1111484095454216, + 'throttle_input': 0.0, + 'timestamp': 918.7270949780941, + 'timestamp_carla': 918728, + 'timestamp_device': 4072163, + 'timestamp_stream': 918.7270949780941, + 'transform': [array([1.0547148 , 6.00837612, 0.02861137]), + array([-0.054662 , -6.16782761, -0.02664885])]} +{'AngularVelocity': array([-2.19007561e-05, -1.73410263e-05, -1.29479267e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17754583]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.56118369e-06, 3.63589493e-07, 1.07983193e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.74004936, 17.86307907, -0.59138745]), + 'camera_rotation': array([-9.31667805, 14.11666965, 0.03762783]), + 'current_gear_input': False, + 'focus_actor_dist': 1528.109619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 435.33886719, -3629.69824219, 16.3013916 ]), + 'frame': 28376, + 'frame_number': 28376, + 'framesequence': 109135, + 'gaze_dir': array([0.98188019, 0.16860962, 0.08235168]), + 'gaze_origin': array([-2.95312595, -0.14751817, -0.10755464]), + 'gaze_valid': True, + 'gaze_vergence': 0.2770071029663086, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98420715, 0.16775513, 0.05639648]), + 'left_gaze_origin': array([-2.65825343, 2.70713663, -0.16795655]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.256988525390625, + 'left_pupil_posn': array([ 0.4098779 , -0.12678158]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97955322, 0.16946411, 0.10830688]), + 'right_gaze_origin': array([-3.24799824, -3.00217319, -0.04715271]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8595733642578125, + 'right_pupil_posn': array([-0.06882715, -0.21461928]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11365703493356705, + 'throttle_input': 0.0, + 'timestamp': 918.760444778949, + 'timestamp_carla': 918761, + 'timestamp_device': 4072188, + 'timestamp_stream': 918.760444778949, + 'transform': [array([0.95115554, 5.92760706, 0.02903313]), + array([-0.05496936, -5.93854856, -0.02752471])]} +{'AngularVelocity': array([ 3.55242264e-05, 1.90195988e-05, -1.31250772e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17752974]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.74233503e-06, 3.93454087e-07, 3.12572636e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.74732494, 17.87244606, -0.60160786]), + 'camera_rotation': array([-9.29193878, 14.02358246, 0.19319929]), + 'current_gear_input': False, + 'focus_actor_dist': 1494.9156494140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 423.90219116, -3608.64575195, 16.31326294]), + 'frame': 28377, + 'frame_number': 28377, + 'framesequence': 109139, + 'gaze_dir': array([0.98223877, 0.16628265, 0.08122253]), + 'gaze_origin': array([-2.95681024, -0.13796541, -0.10545426]), + 'gaze_valid': True, + 'gaze_vergence': 14.112305641174316, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98410034, 0.1700592 , 0.05096436]), + 'left_gaze_origin': array([-2.66058826, 2.7177217 , -0.16628571]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30242919921875, + 'left_pupil_posn': array([ 0.40042591, -0.12500381]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9803772 , 0.1625061 , 0.11148071]), + 'right_gaze_origin': array([-3.25303197, -2.99365234, -0.0446228 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.791778564453125, + 'right_pupil_posn': array([-0.0738067 , -0.21563077]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11631214618682861, + 'throttle_input': 0.0, + 'timestamp': 918.7928182780743, + 'timestamp_carla': 918793, + 'timestamp_device': 4072221, + 'timestamp_stream': 918.7928182780743, + 'transform': [array([0.84994704, 5.850173 , 0.02936128]), + array([-0.0551606 , -5.71409082, -0.02820343])]} +{'AngularVelocity': array([-1.71460561e-05, 4.22462399e-05, -1.31498364e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17753316]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.64189202e-06, 3.36291265e-07, 2.07211386e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.75909042, 17.85192871, -0.62908292]), + 'camera_rotation': array([-9.25621033, 13.8036232 , 0.4754034 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1471.922607421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 414.76690674, -3597.57666016, 16.32273102]), + 'frame': 28378, + 'frame_number': 28378, + 'framesequence': 109143, + 'gaze_dir': array([0.98970032, 0.11452484, 0.08318329]), + 'gaze_origin': array([-2.94612813, -0.09061814, -0.10637208]), + 'gaze_valid': True, + 'gaze_vergence': 42.369815826416016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99067688, 0.12068176, 0.06307983]), + 'left_gaze_origin': array([-2.69580388, 2.76470661, -0.15357056]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2928314208984375, + 'left_pupil_posn': array([ 0.35133696, -0.1250993 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98872375, 0.10836792, 0.10328674]), + 'right_gaze_origin': array([-3.19645262, -2.94594288, -0.05917359]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9293365478515625, + 'right_pupil_posn': array([-0.12457079, -0.2094965 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11935178935527802, + 'throttle_input': 0.0, + 'timestamp': 918.8267205767334, + 'timestamp_carla': 918827, + 'timestamp_device': 4072255, + 'timestamp_stream': 918.8267205767334, + 'transform': [array([0.74279845, 5.77014399, 0.02963517]), + array([-0.05525623, -5.47614622, -0.02880626])]} +{'AngularVelocity': array([ 8.18809349e-05, -1.85765066e-06, -1.35083101e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17753629]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.07094467e-06, 1.81856450e-07, -2.73436948e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.77372742, 17.81563568, -0.62765801]), + 'camera_rotation': array([-9.37125778, 13.478549 , 0.49157062]), + 'current_gear_input': False, + 'focus_actor_dist': 1489.3594970703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 354.86251831, -3656.30908203, 16.38394928]), + 'frame': 28379, + 'frame_number': 28379, + 'framesequence': 109148, + 'gaze_dir': array([0.99007416, 0.11277771, 0.0799408 ]), + 'gaze_origin': array([-2.94502592, -0.09597398, -0.10577469]), + 'gaze_valid': True, + 'gaze_vergence': 42.8065299987793, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99095154, 0.12167358, 0.05654907]), + 'left_gaze_origin': array([-2.68164539, 2.75980854, -0.15782167]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3013458251953125, + 'left_pupil_posn': array([ 0.35274649, -0.12523639]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98919678, 0.10388184, 0.10333252]), + 'right_gaze_origin': array([-3.20840621, -2.95175648, -0.05372773]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.882537841796875, + 'right_pupil_posn': array([-0.12014717, -0.21032226]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12211676687002182, + 'throttle_input': 0.0, + 'timestamp': 918.8606137782335, + 'timestamp_carla': 918861, + 'timestamp_device': 4072296, + 'timestamp_stream': 918.8606137782335, + 'transform': [array([0.63477749, 5.69115973, 0.02984923]), + array([-0.05534502, -5.23590136, -0.02928665])]} +{'AngularVelocity': array([ 3.72322647e-05, 1.43064790e-05, -1.32602854e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17752698]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.59732815e-06, 3.26737052e-07, 2.05944190e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.77475739, 17.76953888, -0.59391129]), + 'camera_rotation': array([-9.41540813, 13.02016163, 0.28006351]), + 'current_gear_input': False, + 'focus_actor_dist': 1395.5675048828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 312.69152832, -3582.13085938, 16.42773438]), + 'frame': 28380, + 'frame_number': 28380, + 'framesequence': 109151, + 'gaze_dir': array([0.98918915, 0.11950684, 0.0821991 ]), + 'gaze_origin': array([-2.94071364, -0.10078431, -0.10743714]), + 'gaze_valid': True, + 'gaze_vergence': 52.2899169921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98988342, 0.12718201, 0.06268311]), + 'left_gaze_origin': array([-2.68410063, 2.75455928, -0.15526123]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.215179443359375, + 'left_pupil_posn': array([ 0.35901976, -0.12445188]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98849487, 0.11183167, 0.10171509]), + 'right_gaze_origin': array([-3.1973269 , -2.95612812, -0.05961304]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.91015625, + 'right_pupil_posn': array([-0.11527878, -0.21021688]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12446059286594391, + 'throttle_input': 0.0, + 'timestamp': 918.8923340775073, + 'timestamp_carla': 918893, + 'timestamp_device': 4072321, + 'timestamp_stream': 918.8923340775073, + 'transform': [array([0.53331083, 5.61807871, 0.02999943]), + array([-0.05546796, -5.00984144, -0.02960531])]} +{'AngularVelocity': array([ 2.60537745e-05, 2.04680018e-05, -1.28159772e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.60846186, -21.31969833, 0.17756838]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.64410846e-06, 3.02848633e-07, 1.16563817e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.75027657, 17.7279644 , -0.54289311]), + 'camera_rotation': array([-9.25657272, 12.62909126, 0.29581195]), + 'current_gear_input': False, + 'focus_actor_dist': 1429.95556640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.80401611, -3621.22314453, 16.40785217]), + 'frame': 28381, + 'frame_number': 28381, + 'framesequence': 109156, + 'gaze_dir': array([0.98851013, 0.12657928, 0.07975006]), + 'gaze_origin': array([-2.9687767 , -0.10564195, -0.10246277]), + 'gaze_valid': True, + 'gaze_vergence': 35.63591766357422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98950195, 0.13174438, 0.05926514]), + 'left_gaze_origin': array([-2.71705627, 2.74998498, -0.14863586]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1605377197265625, + 'left_pupil_posn': array([ 0.36624205, -0.12673891]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98751831, 0.12141418, 0.10023499]), + 'right_gaze_origin': array([-3.22049737, -2.9612689 , -0.05628968]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7600860595703125, + 'right_pupil_posn': array([-0.10991091, -0.21345234]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12603534758090973, + 'throttle_input': 0.0, + 'timestamp': 918.928097076714, + 'timestamp_carla': 918929, + 'timestamp_device': 4072363, + 'timestamp_stream': 918.928097076714, + 'transform': [array([0.41864395, 5.53662586, 0.03007566]), + array([-0.05577532, -4.75394821, -0.02986052])]} +{'AngularVelocity': array([-5.07413006e-06, -4.34764042e-05, -1.30940753e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17754591]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.39798783e-06, 3.50244221e-07, -6.67075710e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.75615215, 17.68006134, -0.53454733]), + 'camera_rotation': array([-9.07124233, 12.29010677, 0.33171025]), + 'current_gear_input': False, + 'focus_actor_dist': 1436.999755859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 341.5632019 , -3633.64111328, 16.39774323]), + 'frame': 28382, + 'frame_number': 28382, + 'framesequence': 109159, + 'gaze_dir': array([0.98825836, 0.12967682, 0.0789566 ]), + 'gaze_origin': array([-2.96871519, -0.1068802 , -0.10561447]), + 'gaze_valid': True, + 'gaze_vergence': 57.353721618652344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98881531, 0.13514709, 0.06298828]), + 'left_gaze_origin': array([-2.73900938, 2.74942327, -0.143602 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17364501953125, + 'left_pupil_posn': array([ 0.36814666, -0.12936258]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98770142, 0.12420654, 0.09492493]), + 'right_gaze_origin': array([-3.198421 , -2.96318388, -0.06762696]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.786285400390625, + 'right_pupil_posn': array([-0.1075989 , -0.21572137]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12793970108032227, + 'throttle_input': 0.0, + 'timestamp': 918.9605516791344, + 'timestamp_carla': 918961, + 'timestamp_device': 4072388, + 'timestamp_stream': 918.9605516791344, + 'transform': [array([0.31507796, 5.46346426, 0.03012687]), + array([-0.05610317, -4.52228928, -0.02998973])]} +{'AngularVelocity': array([-1.03728162e-05, -3.31828664e-06, -1.34743750e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17752828]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 1.88699914e-06, 3.10048335e-07, -4.26852843e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.7399683 , 17.60825157, -0.53893954]), + 'camera_rotation': array([-8.9836998 , 11.88412857, 0.38918275]), + 'current_gear_input': False, + 'focus_actor_dist': 1476.661376953125, + 'focus_actor_name': 'Plane21', + 'focus_actor_pt': array([ 362.05099487, -3678.20410156, 16.62490845]), + 'frame': 28383, + 'frame_number': 28383, + 'framesequence': 109163, + 'gaze_dir': array([0.98795319, 0.13465881, 0.07457733]), + 'gaze_origin': array([-2.97015405, -0.1098465 , -0.1084526 ]), + 'gaze_valid': True, + 'gaze_vergence': 67.30634307861328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98831177, 0.14007568, 0.06011963]), + 'left_gaze_origin': array([-2.75453663, 2.74682951, -0.14344178]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1175689697265625, + 'left_pupil_posn': array([ 0.37208247, -0.13412678]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9875946 , 0.12924194, 0.08903503]), + 'right_gaze_origin': array([-3.18577147, -2.96652246, -0.07346344]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7459259033203125, + 'right_pupil_posn': array([-0.10368514, -0.2182889 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12951445579528809, + 'throttle_input': 0.0, + 'timestamp': 918.993344578892, + 'timestamp_carla': 918994, + 'timestamp_device': 4072421, + 'timestamp_stream': 918.993344578892, + 'transform': [array([0.21055664, 5.39028788, 0.030137 ]), + array([-0.05643102, -4.28808928, -0.03005455])]} +{'AngularVelocity': array([ 4.35345682e-05, 1.57419072e-05, -1.30575472e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17754664]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.63120978e-06, 2.99965620e-07, 1.65404446e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.70591831, 17.51352501, -0.53546721]), + 'camera_rotation': array([-9.02003574, 11.35534286, 0.44579747]), + 'current_gear_input': False, + 'focus_actor_dist': 1426.789794921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 344.8548584 , -3640.13232422, 16.39431 ]), + 'frame': 28384, + 'frame_number': 28384, + 'framesequence': 109167, + 'gaze_dir': array([0.9865036 , 0.14291382, 0.07813263]), + 'gaze_origin': array([-2.93433166, -0.11604767, -0.12066041]), + 'gaze_valid': True, + 'gaze_vergence': 120.91718292236328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98579407, 0.15431213, 0.06625366]), + 'left_gaze_origin': array([-2.70923471, 2.73979807, -0.15788576]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2244873046875, + 'left_pupil_posn': array([ 0.37635767, -0.13507891]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98721313, 0.1315155 , 0.0900116 ]), + 'right_gaze_origin': array([-3.15942836, -2.97189331, -0.08343507]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8587188720703125, + 'right_pupil_posn': array([-0.09527677, -0.21831834]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1306314319372177, + 'throttle_input': 0.0, + 'timestamp': 919.0263558775187, + 'timestamp_carla': 919027, + 'timestamp_device': 4072455, + 'timestamp_stream': 919.0263558775187, + 'transform': [array([0.105896 , 5.31733894, 0.03010562]), + array([-0.05684083, -4.05306721, -0.03004625])]} +{'AngularVelocity': array([ 4.56799135e-05, 1.58800376e-05, -1.33375615e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17753671]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.23199822e-06, 3.17102518e-07, -1.60790936e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.68076038, 17.42448807, -0.53932172]), + 'camera_rotation': array([-9.11812401, 10.80883789, 0.34137338]), + 'current_gear_input': False, + 'focus_actor_dist': 1475.95361328125, + 'focus_actor_name': 'Plane21', + 'focus_actor_pt': array([ 371.55566406, -3691.28173828, 16.62488556]), + 'frame': 28385, + 'frame_number': 28385, + 'framesequence': 109172, + 'gaze_dir': array([0.98855591, 0.11487579, 0.09459686]), + 'gaze_origin': array([-3.08409119, -0.10702821, -0.04432755]), + 'gaze_valid': True, + 'gaze_vergence': 109.46517944335938, + 'handbrake_input': False, + 'left_eye_openness': 0.9028258919715881, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98667908, 0.13781738, 0.08638 ]), + 'left_gaze_origin': array([-2.92816043, 2.75341487, -0.05387269]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([ 0.35919034, -0.1019119 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.825742244720459, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99043274, 0.0919342 , 0.10281372]), + 'right_gaze_origin': array([-3.24002242, -2.96747136, -0.03478241]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.800201416015625, + 'right_pupil_posn': array([-0.10310507, -0.19346976]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13244423270225525, + 'throttle_input': 0.0, + 'timestamp': 919.0636125765741, + 'timestamp_carla': 919064, + 'timestamp_device': 4072496, + 'timestamp_stream': 919.0636125765741, + 'transform': [array([-0.01244965, 5.23592758, 0.03001489]), + array([-0.05727113, -3.78699136, -0.03000063])]} +{'AngularVelocity': array([-6.14449027e-06, -4.03058766e-05, -1.33314479e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17753001]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.16558578e-06, 3.45288413e-07, -1.66521466e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.65434647, 17.30373383, -0.52989823]), + 'camera_rotation': array([-9.18249893, 10.27532959, 0.37613302]), + 'current_gear_input': False, + 'focus_actor_dist': 1816.8253173828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 463.11187744, -4033.82080078, 16.27037811]), + 'frame': 28386, + 'frame_number': 28386, + 'framesequence': 109176, + 'gaze_dir': array([0.48990631, 0.0696106 , 0.07167816]), + 'gaze_origin': array([-3.01214933, -0.10340348, -0.00476227]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.6369674205780029, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97981262, 0.13922119, 0.14335632]), + 'left_gaze_origin': array([-2.78539276, 2.75176859, -0.03605652]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.4757601022720337, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.23890567, -2.95857573, 0.02653198]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9599151611328125, + 'right_pupil_posn': array([-0.10752749, -0.13087118]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1339457482099533, + 'throttle_input': 0.0, + 'timestamp': 919.099091976881, + 'timestamp_carla': 919100, + 'timestamp_device': 4072530, + 'timestamp_stream': 919.099091976881, + 'transform': [array([-0.12433594, 5.15916252, 0.02994326]), + array([-0.05770143, -3.53485918, -0.02992395])]} +{'AngularVelocity': array([ 3.36967787e-05, 2.05632205e-05, -1.33819431e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17753229]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.20052902e-06, 2.53841847e-07, -1.80922245e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.62425137, 17.19701004, -0.52050191]), + 'camera_rotation': array([-9.11975002, 9.76937199, 0.3574281 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3245.873046875, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1092.9465332 , -5331.48974609, 80.02809143]), + 'frame': 28387, + 'frame_number': 28387, + 'framesequence': 109180, + 'gaze_dir': array([0.48756409, 0.07647705, 0.08016205]), + 'gaze_origin': array([-2.98230529, -0.11047135, -0.00636444]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.7031784057617188, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97512817, 0.1529541 , 0.1603241 ]), + 'left_gaze_origin': array([-2.74134827, 2.74464583, -0.03908997]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.6819007992744446, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.22326231, -2.96558857, 0.02636109]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7979888916015625, + 'right_pupil_posn': array([-0.09780389, -0.12254345]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1356486827135086, + 'throttle_input': 0.0, + 'timestamp': 919.1320024766028, + 'timestamp_carla': 919133, + 'timestamp_device': 4072563, + 'timestamp_stream': 919.1320024766028, + 'transform': [array([-0.2274646 , 5.08862066, 0.02990914]), + array([-0.05800196, -3.30194473, -0.02987199])]} +{'AngularVelocity': array([ 4.25921316e-05, -2.05073975e-05, -1.28339525e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17755346]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.79637970e-06, 3.70487101e-07, 3.12048564e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.6033535 , 17.10133171, -0.48549604]), + 'camera_rotation': array([-8.9723959 , 9.46238995, 0.29408216]), + 'current_gear_input': False, + 'focus_actor_dist': 3249.979248046875, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1124.39758301, -5331.49023438, 140.19412231]), + 'frame': 28388, + 'frame_number': 28388, + 'framesequence': 109184, + 'gaze_dir': array([0.97045898, 0.14544678, 0.19098663]), + 'gaze_origin': array([-2.98590708, -0.12179719, -0.02119141]), + 'gaze_valid': True, + 'gaze_vergence': 50.2338981628418, + 'handbrake_input': False, + 'left_eye_openness': 0.869521975517273, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97329712, 0.15467834, 0.16954041]), + 'left_gaze_origin': array([-2.74708724, 2.72989988, -0.05827637]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2250213623046875, + 'left_pupil_posn': array([ 0.38578427, -0.03579068]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9937959909439087, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96762085, 0.13621521, 0.21243286]), + 'right_gaze_origin': array([-3.22472715, -2.97349405, 0.01589356]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8930816650390625, + 'right_pupil_posn': array([-0.09183061, -0.12708628]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13791926205158234, + 'throttle_input': 0.0, + 'timestamp': 919.1663569770753, + 'timestamp_carla': 919167, + 'timestamp_device': 4072596, + 'timestamp_stream': 919.1663569770753, + 'transform': [array([-0.33516386, 5.01574469, 0.0298676 ]), + array([-0.05817272, -3.05836105, -0.02984177])]} +{'AngularVelocity': array([ 4.02830556e-05, 2.60146189e-05, -1.32408577e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17754187]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.40134068e-06, 2.77615044e-07, -2.72972811e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.55956364, 17.02888489, -0.43996277]), + 'camera_rotation': array([-8.8118248 , 9.18827152, 0.10629699]), + 'current_gear_input': False, + 'focus_actor_dist': 3230.061279296875, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1090.87402344, -5331.49023438, 249.28237915]), + 'frame': 28389, + 'frame_number': 28389, + 'framesequence': 109188, + 'gaze_dir': array([0.97107697, 0.14887238, 0.18499756]), + 'gaze_origin': array([-2.98575139, -0.12978517, -0.02990189]), + 'gaze_valid': True, + 'gaze_vergence': 19.654308319091797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97511292, 0.15234375, 0.16101074]), + 'left_gaze_origin': array([-2.74499989, 2.7250092 , -0.07101593]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2568206787109375, + 'left_pupil_posn': array([ 0.39223146, -0.0451709 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96704102, 0.145401 , 0.20898438]), + 'right_gaze_origin': array([-3.2265029 , -2.98457956, 0.01121216]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.864776611328125, + 'right_pupil_posn': array([-0.0850842 , -0.13339913]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14055605232715607, + 'throttle_input': 0.0, + 'timestamp': 919.1983000785112, + 'timestamp_carla': 919199, + 'timestamp_device': 4072630, + 'timestamp_stream': 919.1983000785112, + 'transform': [array([-0.43529403, 4.94863749, 0.029857 ]), + array([-0.0582137 , -2.83155155, -0.02983369])]} +{'AngularVelocity': array([-1.40935372e-05, -3.63091276e-05, -1.33033627e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17753008]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.32160096e-06, 2.74105702e-07, -2.02664542e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.56101608, 16.94904518, -0.42311588]), + 'camera_rotation': array([-8.78974247, 8.99608135, -0.14422786]), + 'current_gear_input': False, + 'focus_actor_dist': 3224.006591796875, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1096.67675781, -5331.48974609, 240.14025879]), + 'frame': 28390, + 'frame_number': 28390, + 'framesequence': 109192, + 'gaze_dir': array([0.97000885, 0.15384674, 0.18743896]), + 'gaze_origin': array([-2.98602009, -0.13459779, -0.03345795]), + 'gaze_valid': True, + 'gaze_vergence': 90.89654541015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97143555, 0.1619873 , 0.17338562]), + 'left_gaze_origin': array([-2.74424005, 2.72007012, -0.07479096]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2876129150390625, + 'left_pupil_posn': array([ 0.39562106, -0.0500021 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96858215, 0.14570618, 0.20149231]), + 'right_gaze_origin': array([-3.22780013, -2.98926544, 0.00787506]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8567962646484375, + 'right_pupil_posn': array([-0.07833815, -0.13184166]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14330272376537323, + 'throttle_input': 0.0, + 'timestamp': 919.2311216779053, + 'timestamp_carla': 919232, + 'timestamp_device': 4072663, + 'timestamp_stream': 919.2311216779053, + 'transform': [array([-0.53876448, 4.8803978 , 0.02983874]), + array([-0.05819321, -2.59699106, -0.02983811])]} +{'AngularVelocity': array([ 3.24979519e-05, 2.13502153e-05, -1.30207736e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17755434]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([2.54876909e-06, 3.46507278e-07, 7.10142267e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.54518032, 16.8872261 , -0.41589031]), + 'camera_rotation': array([-8.68958473, 8.88924599, -0.38078192]), + 'current_gear_input': False, + 'focus_actor_dist': 3223.26611328125, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1111.67883301, -5331.49023438, 251.7512207 ]), + 'frame': 28391, + 'frame_number': 28391, + 'framesequence': 109196, + 'gaze_dir': array([0.96994019, 0.15644073, 0.18515015]), + 'gaze_origin': array([-2.98600698, -0.14066316, -0.03373566]), + 'gaze_valid': True, + 'gaze_vergence': 69.66412353515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97175598, 0.16654968, 0.167099 ]), + 'left_gaze_origin': array([-2.74476957, 2.71492314, -0.07544404]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.304351806640625, + 'left_pupil_posn': array([ 0.39934504, -0.04992187]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96812439, 0.14633179, 0.20320129]), + 'right_gaze_origin': array([-3.22724462, -2.99624944, 0.00797272]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.941253662109375, + 'right_pupil_posn': array([-0.07201636, -0.13405645]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1469283252954483, + 'throttle_input': 0.0, + 'timestamp': 919.2630863785744, + 'timestamp_carla': 919264, + 'timestamp_device': 4072696, + 'timestamp_stream': 919.2630863785744, + 'transform': [array([-0.64041001, 4.81461906, 0.02983578]), + array([-0.05804978, -2.36645889, -0.02986297])]} +{'AngularVelocity': array([-1.38770420e-05, -3.96217074e-05, -1.32919222e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.1775316 ]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.20874313e-06, 3.43332061e-07, -1.33353213e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.53278732, 16.84241867, -0.36641929]), + 'camera_rotation': array([-8.39480019, 8.8364315 , -0.63839966]), + 'current_gear_input': False, + 'focus_actor_dist': 3221.001708984375, + 'focus_actor_name': 'SM_Shop_66', + 'focus_actor_pt': array([ 1124.16259766, -5331.49023438, 252.05007935]), + 'frame': 28392, + 'frame_number': 28392, + 'framesequence': 109200, + 'gaze_dir': array([0.96573639, 0.14626312, 0.21328735]), + 'gaze_origin': array([-2.98763061, -0.13731919, -0.01332245]), + 'gaze_valid': True, + 'gaze_vergence': 79.92342376708984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96769714, 0.15846252, 0.19606018]), + 'left_gaze_origin': array([-2.74730706, 2.71064615, -0.05491486]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3056488037109375, + 'left_pupil_posn': array([ 0.39811099, -0.02786422]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96377563, 0.13406372, 0.23051453]), + 'right_gaze_origin': array([-3.22795439, -2.98528457, 0.02826996]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.859130859375, + 'right_pupil_posn': array([-0.08194292, -0.11006606]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15053561329841614, + 'throttle_input': 0.0, + 'timestamp': 919.2940183766186, + 'timestamp_carla': 919295, + 'timestamp_device': 4072730, + 'timestamp_stream': 919.2940183766186, + 'transform': [array([-0.73978955, 4.75159168, 0.02984106]), + array([-0.05785853, -2.14099813, -0.02989741])]} +{'AngularVelocity': array([ 3.35236909e-05, -2.11827064e-05, -1.32864507e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17753705]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.30321666e-06, 3.00100055e-07, -7.28532104e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.53426743, 16.79851341, -0.27850556]), + 'camera_rotation': array([-8.09355545, 8.75899315, -0.95529538]), + 'current_gear_input': False, + 'focus_actor_dist': 6013.43115234375, + 'focus_actor_name': 'AmericanLights_Town04_13_TrafficLight', + 'focus_actor_pt': array([ 2266.60717773, -7873.66308594, 559.43658447]), + 'frame': 28393, + 'frame_number': 28393, + 'framesequence': 109204, + 'gaze_dir': array([0.96510315, 0.15248108, 0.21095276]), + 'gaze_origin': array([-2.98912811, -0.14271775, -0.01569138]), + 'gaze_valid': True, + 'gaze_vergence': 55.50014114379883, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96794128, 0.16746521, 0.18714905]), + 'left_gaze_origin': array([-2.74888325, 2.70811462, -0.05670777]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.221527099609375, + 'left_pupil_posn': array([ 0.4011029 , -0.02774978]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96226501, 0.13749695, 0.23475647]), + 'right_gaze_origin': array([-3.22937322, -2.9935503 , 0.02532501]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.874114990234375, + 'right_pupil_posn': array([-0.07318175, -0.11565828]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1544725000858307, + 'throttle_input': 0.0, + 'timestamp': 919.3279178775847, + 'timestamp_carla': 919329, + 'timestamp_device': 4072763, + 'timestamp_stream': 919.3279178775847, + 'transform': [array([-0.85002422, 4.68322754, 0.02982232]), + array([-0.05760581, -1.89087903, -0.02994014])]} +{'AngularVelocity': array([ 2.64382434e-05, 1.36579411e-05, -1.32786154e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17753598]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.34158711e-06, 3.01966793e-07, -5.94731464e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.53580284, 16.79115677, -0.18474376]), + 'camera_rotation': array([-7.73354292, 8.71873569, -1.31570089]), + 'current_gear_input': False, + 'focus_actor_dist': 6028.73095703125, + 'focus_actor_name': 'AmericanLights_Town04_13_TrafficLight', + 'focus_actor_pt': array([ 2316.20458984, -7873.18945312, 583.88952637]), + 'frame': 28394, + 'frame_number': 28394, + 'framesequence': 109207, + 'gaze_dir': array([0.96470642, 0.15681458, 0.20973206]), + 'gaze_origin': array([-2.98921919, -0.14710924, -0.02057648]), + 'gaze_valid': True, + 'gaze_vergence': 43.23698806762695, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96838379, 0.16757202, 0.18478394]), + 'left_gaze_origin': array([-2.74911499, 2.70644855, -0.05802613]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.246826171875, + 'left_pupil_posn': array([ 0.4052397 , -0.02883995]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96102905, 0.14605713, 0.23468018]), + 'right_gaze_origin': array([-3.22932291, -3.00066686, 0.01687317]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9976043701171875, + 'right_pupil_posn': array([-0.06846339, -0.12261546]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15892209112644196, + 'throttle_input': 0.0, + 'timestamp': 919.3589931763709, + 'timestamp_carla': 919360, + 'timestamp_device': 4072788, + 'timestamp_stream': 919.3589931763709, + 'transform': [array([-0.95237458, 4.62116194, 0.02983401]), + array([-0.05734627, -1.65863514, -0.02998703])]} +{'AngularVelocity': array([ 3.36485828e-05, -2.12215818e-05, -1.32982977e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.60846186, -21.31969833, 0.17753649]), + 'Rotation': array([-0.07158721, 0.29338536, 0.00921458]), + 'Velocity': array([ 2.29432248e-06, 2.67912981e-07, -8.10643905e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.57194519, 16.80854797, -0.10283144]), + 'camera_rotation': array([-7.37344837, 8.76188564, -1.35891485]), + 'current_gear_input': False, + 'focus_actor_dist': 12826.240234375, + 'focus_actor_name': 'TreePine_601', + 'focus_actor_pt': array([ 5281.52587891, -13970.69628906, 1168.54003906]), + 'frame': 28395, + 'frame_number': 28395, + 'framesequence': 109211, + 'gaze_dir': array([0.96659851, 0.15608978, 0.20114899]), + 'gaze_origin': array([-2.98896813, -0.14846268, -0.02151337]), + 'gaze_valid': True, + 'gaze_vergence': 39.94408416748047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97032166, 0.16723633, 0.17459106]), + 'left_gaze_origin': array([-2.74901128, 2.70510101, -0.05922547]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.247406005859375, + 'left_pupil_posn': array([ 0.40571809, -0.0319072 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96287537, 0.14494324, 0.22770691]), + 'right_gaze_origin': array([-3.22892475, -3.00202656, 0.01619873]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9023590087890625, + 'right_pupil_posn': array([-0.06767499, -0.12627888]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16346324980258942, + 'throttle_input': 0.0, + 'timestamp': 919.3887457773089, + 'timestamp_carla': 919389, + 'timestamp_device': 4072821, + 'timestamp_stream': 919.3887457773089, + 'transform': [array([-1.05180597, 4.56231213, 0.02978184]), + array([-0.05705257, -1.43305433, -0.03003874])]} diff --git a/PythonAPI/data/trials/trial5.txt b/PythonAPI/data/trials/trial5.txt new file mode 100644 index 0000000..75758de --- /dev/null +++ b/PythonAPI/data/trials/trial5.txt @@ -0,0 +1,7097 @@ +{'AngularVelocity': array([-8.55245071e-06, -8.51651130e-05, -7.87573117e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.029460424557328224, + 'Location': array([ -2.46604896, -12.84768295, 0.16989081]), + 'Rotation': array([-2.32226425e-03, -8.66278687e+01, 6.70062304e-02]), + 'Velocity': array([ 5.26613530e-06, 9.40337770e-07, -7.39531679e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.96131039, 15.31366253, 0.06405509]), + 'camera_rotation': array([-5.75922203, -3.39118052, -0.55746907]), + 'current_gear_input': False, + 'focus_actor_dist': 4042.994873046875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -153.70425415, -5331.49023438, 171.77841187]), + 'frame': 30784, + 'frame_number': 30784, + 'framesequence': 118268, + 'gaze_dir': array([0.99321747, 0.03372192, 0.11032104]), + 'gaze_origin': array([-2.93438435, -0.03104706, -0.1007576 ]), + 'gaze_valid': True, + 'gaze_vergence': 188.43081665039062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99345398, 0.04615784, 0.10438538]), + 'left_gaze_origin': array([-2.73073435, 2.83325052, -0.12244568]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.741668701171875, + 'left_pupil_posn': array([ 0.27671981, -0.10480332]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99298096, 0.02128601, 0.11625671]), + 'right_gaze_origin': array([-3.13803411, -2.8953445 , -0.07906953]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5388031005859375, + 'right_pupil_posn': array([-0.18519622, -0.1953181 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 994.8502327762544, + 'timestamp_carla': 994850, + 'timestamp_device': 4148280, + 'timestamp_stream': 994.8502327762544, + 'transform': [array([1.25194657e+00, 1.59397039e+01, 7.89077766e-03]), + array([-0.06638943, -6.62792158, 0.00935146])]} +{'AngularVelocity': array([-0.07458043, -0.00424073, -0.00076322]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.029453635215759277, + 'FR_Wheel_Angle': 0.02946929633617401, + 'Location': array([ -2.46598673, -12.84806728, 0.16988946]), + 'Rotation': array([-1.98758487e-03, -8.66278000e+01, 6.69775605e-02]), + 'Velocity': array([ 2.87763914e-03, -4.54946421e-02, -6.67572021e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.96076584, 15.31460381, 0.04249553]), + 'camera_rotation': array([-5.85208511, -3.27699304, -0.64617401]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.3330078125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -142.99804688, -5331.49023438, 176.36891174]), + 'frame': 30785, + 'frame_number': 30785, + 'framesequence': 118272, + 'gaze_dir': array([0.99300385, 0.03499603, 0.11183167]), + 'gaze_origin': array([-2.92752385, -0.03014755, -0.1025345 ]), + 'gaze_valid': True, + 'gaze_vergence': 177.29432678222656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99337769, 0.04704285, 0.10470581]), + 'left_gaze_origin': array([-2.71842051, 2.83456588, -0.12635805]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6898040771484375, + 'left_pupil_posn': array([ 0.27618217, -0.10412967]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99263 , 0.02294922, 0.11895752]), + 'right_gaze_origin': array([-3.13662744, -2.89486098, -0.07871094]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.53936767578125, + 'right_pupil_posn': array([-0.18521148, -0.19472277]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0317387655377388, + 'timestamp': 994.8834384791553, + 'timestamp_carla': 994883, + 'timestamp_device': 4148313, + 'timestamp_stream': 994.8834384791553, + 'transform': [array([1.25189531e+00, 1.59396467e+01, 7.77065242e-03]), + array([-0.06632797, -6.62779856, 0.00958874])]} +{'AngularVelocity': array([-0.06126988, -0.00612827, 0.83346373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02932450920343399, + 'FR_Wheel_Angle': 0.029322443529963493, + 'Location': array([ -2.46468425, -12.86881065, 0.16983972]), + 'Rotation': array([ 6.50233962e-03, -8.66296921e+01, 6.69552311e-02]), + 'Velocity': array([ 0.01443072, -0.23619428, -0.00034034]), + 'brake_input': 0.0, + 'camera_location': array([-8.95296764, 15.30945206, 0.02003165]), + 'camera_rotation': array([-5.85638142, -3.23795199, -0.70274425]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.74560546875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -130.54685974, -5331.49023438, 176.21481323]), + 'frame': 30786, + 'frame_number': 30786, + 'framesequence': 118276, + 'gaze_dir': array([0.99224091, 0.03282166, 0.11856842]), + 'gaze_origin': array([-2.92735529, -0.029422 , -0.10259706]), + 'gaze_valid': True, + 'gaze_vergence': 132.0206298828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99305725, 0.0464325 , 0.10795593]), + 'left_gaze_origin': array([-2.71667647, 2.83545709, -0.12703705]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.682220458984375, + 'left_pupil_posn': array([ 0.27428305, -0.1007483 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99142456, 0.01921082, 0.12918091]), + 'right_gaze_origin': array([-3.13803411, -2.89430094, -0.07815704]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.547332763671875, + 'right_pupil_posn': array([-0.18578458, -0.19348145]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0952315554022789, + 'timestamp': 994.9159672781825, + 'timestamp_carla': 994915, + 'timestamp_device': 4148347, + 'timestamp_stream': 994.9159672781825, + 'transform': [array([1.25193429e+00, 1.59395895e+01, 7.73069356e-03]), + array([-0.06630065, -6.62786007, 0.00967707])]} +{'AngularVelocity': array([-0.0167064 , -0.00043461, 0.42069444]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02917283959686756, + 'FR_Wheel_Angle': 0.029119616374373436, + 'Location': array([ -2.45885849, -12.96702385, 0.16981703]), + 'Rotation': array([ 1.43297361e-02, -8.66423950e+01, 6.69620112e-02]), + 'Velocity': array([ 3.46483216e-02, -5.88689744e-01, 2.38227840e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.93594074e+00, 1.52873926e+01, 5.72044961e-03]), + 'camera_rotation': array([-5.88136625, -3.20917058, -0.72678077]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.871337890625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -137.32102966, -5331.49072266, 203.36080933]), + 'frame': 30787, + 'frame_number': 30787, + 'framesequence': 118280, + 'gaze_dir': array([0.99212646, 0.03196716, 0.11952972]), + 'gaze_origin': array([-2.92371464, -0.02875595, -0.10189591]), + 'gaze_valid': True, + 'gaze_vergence': 113.35623168945312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9932251 , 0.04551697, 0.10678101]), + 'left_gaze_origin': array([-2.70927763, 2.83622146, -0.12753296]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6600799560546875, + 'left_pupil_posn': array([ 0.27336574, -0.09861636]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99102783, 0.01841736, 0.13227844]), + 'right_gaze_origin': array([-3.13815165, -2.8937335 , -0.07625885]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5392913818359375, + 'right_pupil_posn': array([-0.18647677, -0.19258511]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.15078964829444885, + 'timestamp': 994.9505263790488, + 'timestamp_carla': 994950, + 'timestamp_device': 4148380, + 'timestamp_stream': 994.9505263790488, + 'transform': [array([1.25194168e+00, 1.59395924e+01, 7.71825761e-03]), + array([-0.06630065, -6.62786007, 0.00967707])]} +{'AngularVelocity': array([-0.02853134, -0.00086836, -0.36830881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003782507963478565, + 'FR_Wheel_Angle': -0.06673306226730347, + 'Location': array([ -2.44886708, -13.13707161, 0.16986166]), + 'Rotation': array([ 1.46917365e-02, -8.66507874e+01, 6.70451820e-02]), + 'Velocity': array([ 5.19960970e-02, -8.96382809e-01, 2.58607848e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.92355442e+00, 1.52631092e+01, -6.91127824e-03]), + 'camera_rotation': array([-6.00041628, -3.31837869, -0.74271655]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.82470703125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -139.01797485, -5331.49023438, 205.51960754]), + 'frame': 30788, + 'frame_number': 30788, + 'framesequence': 118284, + 'gaze_dir': array([0.99217224, 0.03195953, 0.11940002]), + 'gaze_origin': array([-2.92071629, -0.02878571, -0.10162278]), + 'gaze_valid': True, + 'gaze_vergence': 125.45368194580078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99311829, 0.04522705, 0.10800171]), + 'left_gaze_origin': array([-2.70416117, 2.83622146, -0.12703858]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6609344482421875, + 'left_pupil_posn': array([ 0.27336574, -0.09783506]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9912262 , 0.01869202, 0.13079834]), + 'right_gaze_origin': array([-3.13727117, -2.89379287, -0.07620697]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.53277587890625, + 'right_pupil_posn': array([-0.18652481, -0.19194651]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.1904631108045578, + 'timestamp': 994.9851193763316, + 'timestamp_carla': 994984, + 'timestamp_device': 4148413, + 'timestamp_stream': 994.9851193763316, + 'transform': [array([1.25195003e+00, 1.59395819e+01, 7.71116232e-03]), + array([-0.06630065, -6.62786007, 0.00967707])]} +{'AngularVelocity': array([-0.00141158, 0.0076915 , -0.63969558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1494770050048828, + 'FR_Wheel_Angle': -1.2406095266342163, + 'Location': array([ -2.43565464, -13.38086987, 0.16992773]), + 'Rotation': array([ 1.40292076e-02, -8.66360779e+01, 6.82798475e-02]), + 'Velocity': array([ 5.77004291e-02, -1.17071044e+00, 2.42900845e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.89789772e+00, 1.52336607e+01, -1.19649591e-02]), + 'camera_rotation': array([-6.06285143, -3.42851663, -0.81045687]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.4052734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -146.92436218, -5331.49023438, 196.60862732]), + 'frame': 30789, + 'frame_number': 30789, + 'framesequence': 118288, + 'gaze_dir': array([0.99184418, 0.03208923, 0.12186432]), + 'gaze_origin': array([-2.9213655 , -0.02878571, -0.10147554]), + 'gaze_valid': True, + 'gaze_vergence': 111.63523864746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99301147, 0.04516602, 0.10888672]), + 'left_gaze_origin': array([-2.70416117, 2.83622146, -0.12703858]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6629791259765625, + 'left_pupil_posn': array([ 0.27347863, -0.09649813]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99067688, 0.01901245, 0.13484192]), + 'right_gaze_origin': array([-3.13856983, -2.89379287, -0.07591248]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.509033203125, + 'right_pupil_posn': array([-0.18653077, -0.1916306 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.21428243815898895, + 'timestamp': 995.01668997854, + 'timestamp_carla': 995016, + 'timestamp_device': 4148447, + 'timestamp_stream': 995.01668997854, + 'transform': [array([1.25196397e+00, 1.59394627e+01, 7.72874802e-03]), + array([-0.06630065, -6.62786007, 0.00967707])]} +{'AngularVelocity': array([-0.02305823, 0.00529545, -1.01762176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.1723618507385254, + 'FR_Wheel_Angle': -2.33560848236084, + 'Location': array([ -2.42271042, -13.66902447, 0.17003621]), + 'Rotation': array([ 9.58958548e-03, -8.67211227e+01, 6.92997798e-02]), + 'Velocity': array([ 5.05981371e-02, -1.33210933e+00, 7.12027540e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.86782455, 15.20032883, -0.02924532]), + 'camera_rotation': array([-6.11636591, -3.5614233 , -0.76441097]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.2294921875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -154.89761353, -5331.49023438, 202.41096497]), + 'frame': 30790, + 'frame_number': 30790, + 'framesequence': 118292, + 'gaze_dir': array([0.99191284, 0.03303528, 0.12151337]), + 'gaze_origin': array([-2.92201948, -0.02978211, -0.09961701]), + 'gaze_valid': True, + 'gaze_vergence': 128.70367431640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99293518, 0.04379272, 0.11026001]), + 'left_gaze_origin': array([-2.70416117, 2.83537292, -0.12504883]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.673858642578125, + 'left_pupil_posn': array([ 0.27514911, -0.09590328]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9908905 , 0.02227783, 0.13276672]), + 'right_gaze_origin': array([-3.13987732, -2.89493728, -0.07418519]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5089263916015625, + 'right_pupil_posn': array([-0.18620282, -0.19021606]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2222171425819397, + 'timestamp': 995.050234477967, + 'timestamp_carla': 995050, + 'timestamp_device': 4148480, + 'timestamp_stream': 995.050234477967, + 'transform': [array([1.25197947e+00, 1.59393225e+01, 7.72504788e-03]), + array([-0.06630065, -6.62786007, 0.00967707])]} +{'AngularVelocity': array([-0.05011049, 0.00314536, -1.7780993 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.316396713256836, + 'FR_Wheel_Angle': -3.259721517562866, + 'Location': array([ -2.41170335, -14.0045948 , 0.17010695]), + 'Rotation': array([ 1.26358494e-02, -8.69540329e+01, 7.11734295e-02]), + 'Velocity': array([ 3.46596874e-02, -1.58573306e+00, 3.81002406e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.84273338, 15.1903677 , -0.04376721]), + 'camera_rotation': array([-6.21110058, -3.65233278, -0.80043375]), + 'current_gear_input': False, + 'focus_actor_dist': 4042.95263671875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -160.07609558, -5331.48974609, 197.1370697 ]), + 'frame': 30791, + 'frame_number': 30791, + 'framesequence': 118296, + 'gaze_dir': array([0.99160767, 0.03727722, 0.12252808]), + 'gaze_origin': array([-2.93200016, -0.03248138, -0.09670182]), + 'gaze_valid': True, + 'gaze_vergence': 130.5398712158203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99247742, 0.05014038, 0.11157227]), + 'left_gaze_origin': array([-2.70416117, 2.83338642, -0.12504883]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.673858642578125, + 'left_pupil_posn': array([ 0.27719438, -0.09570158]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99073792, 0.02441406, 0.13348389]), + 'right_gaze_origin': array([-3.15983891, -2.89834905, -0.0683548 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4769439697265625, + 'right_pupil_posn': array([-0.18157351, -0.18961763]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.23411917686462402, + 'timestamp': 995.0851641781628, + 'timestamp_carla': 995084, + 'timestamp_device': 4148513, + 'timestamp_stream': 995.0851641781628, + 'transform': [array([1.25199997e+00, 1.59391060e+01, 7.71169644e-03]), + array([-0.06630065, -6.62786007, 0.00967707])]} +{'AngularVelocity': array([-3.64486016e-02, -2.00413121e-03, -2.32630134e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.4497344493865967, + 'FR_Wheel_Angle': -3.390838146209717, + 'Location': array([ -2.40260983, -14.4122448 , 0.17019762]), + 'Rotation': array([ 1.81683023e-02, -8.73458176e+01, 7.11791813e-02]), + 'Velocity': array([ 2.56571136e-02, -1.92863655e+00, 5.25102601e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.80876446, 15.17751122, -0.06554013]), + 'camera_rotation': array([-6.29948997, -3.67689514, -0.80424613]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.194580078125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -149.69898987, -5331.49023438, 194.97322083]), + 'frame': 30792, + 'frame_number': 30792, + 'framesequence': 118300, + 'gaze_dir': array([0.99153137, 0.04026794, 0.12232971]), + 'gaze_origin': array([-2.93209934, -0.0332756 , -0.09640656]), + 'gaze_valid': True, + 'gaze_vergence': 136.9691619873047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99229431, 0.05296326, 0.11196899]), + 'left_gaze_origin': array([-2.70088959, 2.83285379, -0.12565002]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6757354736328125, + 'left_pupil_posn': array([ 0.27856922, -0.0957458 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99076843, 0.02757263, 0.13269043]), + 'right_gaze_origin': array([-3.1633091 , -2.899405 , -0.06716309]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.47003173828125, + 'right_pupil_posn': array([-0.17983758, -0.18934083]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.24205386638641357, + 'timestamp': 995.116729978472, + 'timestamp_carla': 995116, + 'timestamp_device': 4148547, + 'timestamp_stream': 995.116729978472, + 'transform': [array([1.25206268e+00, 1.59386473e+01, 7.60587677e-03]), + array([-0.06626649, -6.62792158, 0.00991808])]} +{'AngularVelocity': array([-2.55321190e-02, 9.13453987e-04, -2.87163520e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6151530742645264, + 'FR_Wheel_Angle': -3.4898416996002197, + 'Location': array([ -2.39598727, -14.90010452, 0.17032872]), + 'Rotation': array([ 2.10164916e-02, -8.78695679e+01, 7.20802173e-02]), + 'Velocity': array([ 5.68425003e-03, -2.27600384e+00, 8.46347772e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.78304577, 15.18056679, -0.08804987]), + 'camera_rotation': array([-6.39488697, -3.70247293, -0.75055635]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.371826171875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -139.36808777, -5331.49023438, 188.12490845]), + 'frame': 30793, + 'frame_number': 30793, + 'framesequence': 118305, + 'gaze_dir': array([0.99113464, 0.04121399, 0.12516785]), + 'gaze_origin': array([-2.92664576, -0.03427429, -0.09645157]), + 'gaze_valid': True, + 'gaze_vergence': 121.92156219482422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9921875 , 0.05209351, 0.11326599]), + 'left_gaze_origin': array([-2.68396306, 2.83235478, -0.12986146]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6808929443359375, + 'left_pupil_posn': array([ 0.27953434, -0.09398866]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99008179, 0.03033447, 0.1370697 ]), + 'right_gaze_origin': array([-3.16932845, -2.90090346, -0.06304169]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4701080322265625, + 'right_pupil_posn': array([-0.17907256, -0.18723023]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2539559006690979, + 'timestamp': 995.1523036770523, + 'timestamp_carla': 995152, + 'timestamp_device': 4148588, + 'timestamp_stream': 995.1523036770523, + 'transform': [array([1.25215769e+00, 1.59377317e+01, 7.29368208e-03]), + array([-0.06616404, -6.62798357, 0.01048971])]} +{'AngularVelocity': array([-0.01653484, -0.00786212, -3.13989711]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.301274538040161, + 'FR_Wheel_Angle': -3.085017681121826, + 'Location': array([ -2.39389157, -15.46969223, 0.17049806]), + 'Rotation': array([ 2.26693973e-02, -8.85053101e+01, 7.20651746e-02]), + 'Velocity': array([-1.79010015e-02, -2.61629319e+00, 8.95671837e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.75675392, 15.17468548, -0.10548349]), + 'camera_rotation': array([-6.48071527, -3.71298718, -0.67899543]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.440673828125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -137.0196228 , -5331.48974609, 192.88508606]), + 'frame': 30794, + 'frame_number': 30794, + 'framesequence': 118308, + 'gaze_dir': array([0.99105835, 0.04118347, 0.12571716]), + 'gaze_origin': array([-2.91882348, -0.03304596, -0.09786911]), + 'gaze_valid': True, + 'gaze_vergence': 114.51582336425781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99220276, 0.05198669, 0.11314392]), + 'left_gaze_origin': array([-2.68129277, 2.83193207, -0.12987062]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.67974853515625, + 'left_pupil_posn': array([ 0.27977967, -0.09310424]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98991394, 0.03038025, 0.13829041]), + 'right_gaze_origin': array([-3.15635395, -2.89802432, -0.06586762]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4621124267578125, + 'right_pupil_posn': array([-0.18109667, -0.18667269]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.269825279712677, + 'timestamp': 995.1847746782005, + 'timestamp_carla': 995184, + 'timestamp_device': 4148613, + 'timestamp_stream': 995.1847746782005, + 'transform': [array([1.25199783e+00, 1.59355278e+01, 6.59177778e-03]), + array([-0.06593181, -6.62740612, 0.01188892])]} +{'AngularVelocity': array([ 0.00444706, -0.00936724, -2.69331455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.4396069049835205, + 'FR_Wheel_Angle': -2.208641767501831, + 'Location': array([ -2.39601636, -16.12478447, 0.17072351]), + 'Rotation': array([ 2.26079244e-02, -8.91357040e+01, 6.97101802e-02]), + 'Velocity': array([-3.00454963e-02, -2.93436480e+00, 1.50202750e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.72433949, 15.18276024, -0.11521893]), + 'camera_rotation': array([-6.55116177, -3.7039392 , -0.63014305]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.25146484375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -137.28733826, -5331.49023438, 188.89710999]), + 'frame': 30795, + 'frame_number': 30795, + 'framesequence': 118312, + 'gaze_dir': array([ 0.99201202, -0.03938293, 0.11803436]), + 'gaze_origin': array([-2.95343113, 0.01678696, -0.09430237]), + 'gaze_valid': True, + 'gaze_vergence': 136.74891662597656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99208069, -0.02015686, 0.12385559]), + 'left_gaze_origin': array([-2.83120275, 2.88331294, -0.08158417]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6994781494140625, + 'left_pupil_posn': array([ 0.21755719, -0.09758914]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99194336, -0.05860901, 0.11221313]), + 'right_gaze_origin': array([-3.07565928, -2.84973931, -0.10702057]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5371856689453125, + 'right_pupil_posn': array([-0.23963666, -0.19504142]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.28172731399536133, + 'timestamp': 995.2163752764463, + 'timestamp_carla': 995216, + 'timestamp_device': 4148647, + 'timestamp_stream': 995.2163752764463, + 'transform': [array([1.25350189e+00, 1.59315195e+01, 5.54206828e-03]), + array([-0.06550151, -6.62987375, 0.01397019])]} +{'AngularVelocity': array([ 0.07681202, -0.00852149, -1.55130577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.4314990043640137, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.39967489, -16.80798149, 0.17105082]), + 'Rotation': array([ 1.00198872e-02, -8.95867615e+01, 6.60600662e-02]), + 'Velocity': array([-2.40031872e-02, -2.90970278e+00, 1.08731270e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.67623425, 15.19853973, -0.12476776]), + 'camera_rotation': array([-6.6328783 , -3.66366029, -0.6036877 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4044.75146484375, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -461.6628418 , -5331.48974609, 149.41952515]), + 'frame': 30796, + 'frame_number': 30796, + 'framesequence': 118316, + 'gaze_dir': array([ 0.990448 , -0.07051849, 0.11618042]), + 'gaze_origin': array([-3.01489735, 0.04942169, -0.07666931]), + 'gaze_valid': True, + 'gaze_vergence': 118.6317138671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99108887, -0.04899597, 0.12376404]), + 'left_gaze_origin': array([-2.90970922, 2.91281605, -0.05747833]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5977020263671875, + 'left_pupil_posn': array([ 0.18713236, -0.09716511]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98980713, -0.09204102, 0.1085968 ]), + 'right_gaze_origin': array([-3.12008524, -2.81397247, -0.09586029]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6037139892578125, + 'right_pupil_posn': array([-0.27447039, -0.19592535]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2856946587562561, + 'timestamp': 995.24877037853, + 'timestamp_carla': 995248, + 'timestamp_device': 4148680, + 'timestamp_stream': 995.24877037853, + 'transform': [array([1.25313807e+00, 1.59258652e+01, 4.29395679e-03]), + array([-0.06506438, -6.62847567, 0.01641761])]} +{'AngularVelocity': array([0.03324652, 0.01970835, 0.1628032 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.39778471, -17.46043205, 0.17133436]), + 'Rotation': array([-3.29898112e-03, -8.96516418e+01, 6.16919510e-02]), + 'Velocity': array([ 1.48945889e-02, -2.66038632e+00, 1.14539149e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.64220715, 15.21179771, -0.14124118]), + 'camera_rotation': array([-6.74000311, -3.63071799, -0.58519518]), + 'current_gear_input': False, + 'focus_actor_dist': 4051.975830078125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -585.12799072, -5331.48925781, 136.00740051]), + 'frame': 30797, + 'frame_number': 30797, + 'framesequence': 118320, + 'gaze_dir': array([ 0.99029541, -0.07211304, 0.11750793]), + 'gaze_origin': array([-3.00571609, 0.04905472, -0.0791916 ]), + 'gaze_valid': True, + 'gaze_vergence': 143.3009490966797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99032593, -0.05729675, 0.12634277]), + 'left_gaze_origin': array([-2.91436172, 2.91331506, -0.05550538]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6330718994140625, + 'left_pupil_posn': array([ 0.18867719, -0.09686232]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99026489, -0.08692932, 0.1086731 ]), + 'right_gaze_origin': array([-3.09707046, -2.81520557, -0.10287782]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6240081787109375, + 'right_pupil_posn': array([-0.27640814, -0.1954627 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2856946587562561, + 'timestamp': 995.2835119776428, + 'timestamp_carla': 995283, + 'timestamp_device': 4148713, + 'timestamp_stream': 995.2835119776428, + 'transform': [array([1.25423169e+00, 1.59184322e+01, 3.45354062e-03]), + array([-0.06480483, -6.62975979, 0.01803026])]} +{'AngularVelocity': array([0.00483506, 0.00654505, 0.12456676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.39449883, -18.05127525, 0.17157759]), + 'Rotation': array([-7.07607577e-03, -8.96515808e+01, 6.44927472e-02]), + 'Velocity': array([ 1.34598697e-02, -2.41128159e+00, 6.83402992e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.61526299, 15.22031879, -0.15715468]), + 'camera_rotation': array([-6.81661034, -3.58900476, -0.59257638]), + 'current_gear_input': False, + 'focus_actor_dist': 4051.665771484375, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -588.96405029, -5331.48974609, 134.05847168]), + 'frame': 30798, + 'frame_number': 30798, + 'framesequence': 118324, + 'gaze_dir': array([ 0.99046326, -0.07326508, 0.11528778]), + 'gaze_origin': array([-3.00431466, 0.04949646, -0.07856903]), + 'gaze_valid': True, + 'gaze_vergence': 130.60108947753906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99026489, -0.05921936, 0.12591553]), + 'left_gaze_origin': array([-2.92661309, 2.91501641, -0.05062104]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.599151611328125, + 'left_pupil_posn': array([ 0.18750238, -0.09716618]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99066162, -0.08731079, 0.10466003]), + 'right_gaze_origin': array([-3.08201599, -2.81602335, -0.10651704]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6702423095703125, + 'right_pupil_posn': array([-0.27642608, -0.19526398]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2856946587562561, + 'timestamp': 995.3179309777915, + 'timestamp_carla': 995317, + 'timestamp_device': 4148746, + 'timestamp_stream': 995.3179309777915, + 'transform': [array([1.25961423e+00, 1.59086227e+01, 2.57600774e-03]), + array([-0.06468189, -6.63934278, 0.01973518])]} +{'AngularVelocity': array([-0.0027375 , 0.00194075, 0.12578532]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.39151978, -18.58646774, 0.17175828]), + 'Rotation': array([-7.17169838e-03, -8.96514359e+01, 6.52228743e-02]), + 'Velocity': array([ 1.21800425e-02, -2.18530869e+00, 6.18696213e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.59459782, 15.23534966, -0.17025082]), + 'camera_rotation': array([-6.89308119, -3.59057903, -0.54735249]), + 'current_gear_input': False, + 'focus_actor_dist': 4051.0732421875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -590.67041016, -5331.49023438, 119.65939331]), + 'frame': 30799, + 'frame_number': 30799, + 'framesequence': 118328, + 'gaze_dir': array([ 0.99044037, -0.07446289, 0.11476135]), + 'gaze_origin': array([-3.00312686, 0.04963684, -0.07840043]), + 'gaze_valid': True, + 'gaze_vergence': 129.001953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9901886 , -0.06092834, 0.1257019 ]), + 'left_gaze_origin': array([-2.92833567, 2.91561747, -0.0496872 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6208343505859375, + 'left_pupil_posn': array([ 0.18689549, -0.09718049]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99069214, -0.08799744, 0.1038208 ]), + 'right_gaze_origin': array([-3.07791758, -2.81634378, -0.10711366]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6737518310546875, + 'right_pupil_posn': array([-0.27677697, -0.1949563 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.26189059019088745, + 'timestamp': 995.3502131775022, + 'timestamp_carla': 995350, + 'timestamp_device': 4148780, + 'timestamp_stream': 995.3502131775022, + 'transform': [array([1.25685763e+00, 1.58986359e+01, 1.76214217e-03]), + array([-0.06438819, -6.63276243, 0.0213553 ])]} +{'AngularVelocity': array([-0.00411108, 0.00043706, 0.03828643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': -0.05689635127782822, + 'Location': array([ -2.3884747 , -19.13262749, 0.17195517]), + 'Rotation': array([-6.19498128e-03, -8.96516953e+01, 6.54569641e-02]), + 'Velocity': array([ 1.09016057e-02, -1.95451295e+00, 8.75377620e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.57417393, 15.24618721, -0.17371932]), + 'camera_rotation': array([-6.93826294, -3.60710335, -0.49627772]), + 'current_gear_input': False, + 'focus_actor_dist': 4050.588134765625, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -595.81756592, -5331.49023438, 112.47155762]), + 'frame': 30800, + 'frame_number': 30800, + 'framesequence': 118332, + 'gaze_dir': array([ 0.99048615, -0.07511139, 0.11394501]), + 'gaze_origin': array([-3.00457239, 0.05032578, -0.077108 ]), + 'gaze_valid': True, + 'gaze_vergence': 109.41752624511719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98982239, -0.06404114, 0.1269989 ]), + 'left_gaze_origin': array([-2.93909025, 2.91740417, -0.04520569]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6251373291015625, + 'left_pupil_posn': array([ 0.18644595, -0.09719479]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9911499 , -0.08618164, 0.10089111]), + 'right_gaze_origin': array([-3.07005477, -2.81675267, -0.10901032]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7081756591796875, + 'right_pupil_posn': array([-0.2775293, -0.1943742]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2539559006690979, + 'timestamp': 995.3828571774065, + 'timestamp_carla': 995382, + 'timestamp_device': 4148813, + 'timestamp_stream': 995.3828571774065, + 'transform': [array([1.25880492e+00, 1.58863325e+01, 1.11852644e-03]), + array([-0.06410132, -6.63520193, 0.02262924])]} +{'AngularVelocity': array([-0.00512458, 0.00076794, 0.76551563]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.007445415947586298, + 'FR_Wheel_Angle': -0.007444433867931366, + 'Location': array([ -2.38645506, -19.50066757, 0.17203897]), + 'Rotation': array([-8.12109467e-03, -8.96518555e+01, 6.64231181e-02]), + 'Velocity': array([ 9.80906188e-03, -1.77578974e+00, 2.04401018e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.5723772 , 15.24586678, -0.17818007]), + 'camera_rotation': array([-6.97976971, -3.57909656, -0.46761838]), + 'current_gear_input': False, + 'focus_actor_dist': 4049.795654296875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -598.57751465, -5331.49023438, 106.35381317]), + 'frame': 30801, + 'frame_number': 30801, + 'framesequence': 118336, + 'gaze_dir': array([ 0.99040222, -0.07570648, 0.11430359]), + 'gaze_origin': array([-3.00261474, 0.05043488, -0.07724991]), + 'gaze_valid': True, + 'gaze_vergence': 103.85062408447266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98965454, -0.06497192, 0.12788391]), + 'left_gaze_origin': array([-2.94047117, 2.91803432, -0.04413452]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.634918212890625, + 'left_pupil_posn': array([ 0.18594432, -0.09680212]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9911499 , -0.08644104, 0.10072327]), + 'right_gaze_origin': array([-3.06475854, -2.81716466, -0.1103653 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.728271484375, + 'right_pupil_posn': array([-0.2775293 , -0.19405329]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2539559006690979, + 'timestamp': 995.4158673770726, + 'timestamp_carla': 995415, + 'timestamp_device': 4148846, + 'timestamp_stream': 995.4158673770726, + 'transform': [array([1.26238215e+00, 1.58718138e+01, 4.59117873e-04]), + array([-0.06378713, -6.6405797 , 0.02392581])]} +{'AngularVelocity': array([-7.31952442e-03, 2.70871969e-04, -8.54893744e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00495846476405859, + 'FR_Wheel_Angle': 0.05081797391176224, + 'Location': array([ -2.38410735, -19.91991615, 0.17199141]), + 'Rotation': array([-3.41509446e-03, -8.96590958e+01, 6.64360821e-02]), + 'Velocity': array([ 9.98369977e-03, -1.81218076e+00, -5.67264564e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.57384109, 15.24461746, -0.19074614]), + 'camera_rotation': array([-7.02469206, -3.57142687, -0.4535279 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4048.6171875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -598.80175781, -5331.48925781, 105.14255524]), + 'frame': 30802, + 'frame_number': 30802, + 'framesequence': 118340, + 'gaze_dir': array([ 0.99042511, -0.07537842, 0.11427307]), + 'gaze_origin': array([-2.99899769, 0.05046616, -0.07799225]), + 'gaze_valid': True, + 'gaze_vergence': 99.19889831542969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98959351, -0.06523132, 0.12820435]), + 'left_gaze_origin': array([-2.94171929, 2.91853952, -0.04316407]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.656036376953125, + 'left_pupil_posn': array([ 0.18594432, -0.09654188]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99125671, -0.08552551, 0.1003418 ]), + 'right_gaze_origin': array([-3.05627608, -2.8176074 , -0.11282044]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7668914794921875, + 'right_pupil_posn': array([-0.27726394, -0.19405329]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.24998855590820312, + 'timestamp': 995.4498890787363, + 'timestamp_carla': 995449, + 'timestamp_device': 4148880, + 'timestamp_stream': 995.4498890787363, + 'transform': [array([1.26588726e+00, 1.58556442e+01, 1.90944673e-04]), + array([-0.06365053, -6.64560843, 0.02444274])]} +{'AngularVelocity': array([ 0.01343683, -0.00417079, 1.18841302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5832512378692627, + 'FR_Wheel_Angle': 0.6358659267425537, + 'Location': array([ -2.38086367, -20.37602234, 0.17197305]), + 'Rotation': array([-3.02577368e-03, -8.96192017e+01, 6.51588812e-02]), + 'Velocity': array([ 2.04245914e-02, -1.91239202e+00, -5.53512538e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.55780506, 15.24414349, -0.20081429]), + 'camera_rotation': array([-7.00905085, -3.58517337, -0.46089911]), + 'current_gear_input': False, + 'focus_actor_dist': 4047.0947265625, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -596.99829102, -5331.49023438, 102.01946259]), + 'frame': 30803, + 'frame_number': 30803, + 'framesequence': 118344, + 'gaze_dir': array([ 0.99054718, -0.07540894, 0.11333466]), + 'gaze_origin': array([-2.99655557, 0.05067826, -0.07784119]), + 'gaze_valid': True, + 'gaze_vergence': 106.78864288330078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98979187, -0.06584167, 0.12632751]), + 'left_gaze_origin': array([-2.94232798, 2.9191103 , -0.04232483]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6976776123046875, + 'left_pupil_posn': array([ 0.18576813, -0.09612727]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99130249, -0.0849762 , 0.1003418 ]), + 'right_gaze_origin': array([-3.05078292, -2.81775379, -0.11335754]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7785797119140625, + 'right_pupil_posn': array([-0.27733642, -0.19405329]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.24998855590820312, + 'timestamp': 995.4828882776201, + 'timestamp_carla': 995482, + 'timestamp_device': 4148913, + 'timestamp_stream': 995.4828882776201, + 'transform': [array([ 1.26799631e+00, 1.58384504e+01, -2.82859801e-05]), + array([-0.06360955, -6.64777756, 0.0248857 ])]} +{'AngularVelocity': array([-1.20534170e-02, 7.91739963e-04, 1.11838496e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7651525139808655, + 'FR_Wheel_Angle': 0.7718855142593384, + 'Location': array([ -2.37535429, -20.82784843, 0.17204954]), + 'Rotation': array([-3.78392451e-03, -8.95150146e+01, 6.47805929e-02]), + 'Velocity': array([ 3.18859927e-02, -2.08170319e+00, 9.77005926e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.54948521, 15.24547005, -0.20142625]), + 'camera_rotation': array([-7.04339981, -3.58270478, -0.44624683]), + 'current_gear_input': False, + 'focus_actor_dist': 4045.6318359375, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -598.25378418, -5331.49023438, 99.28894043]), + 'frame': 30804, + 'frame_number': 30804, + 'framesequence': 118348, + 'gaze_dir': array([ 0.99042511, -0.0766983 , 0.11348724]), + 'gaze_origin': array([-2.99472976, 0.05071487, -0.07844696]), + 'gaze_valid': True, + 'gaze_vergence': 100.11065673828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98960876, -0.0670166 , 0.12718201]), + 'left_gaze_origin': array([-2.94261956, 2.9195497 , -0.04222107]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.71063232421875, + 'left_pupil_posn': array([ 0.18502319, -0.0964241 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99124146, -0.08638 , 0.09979248]), + 'right_gaze_origin': array([-3.04683995, -2.81812 , -0.11467285]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7895355224609375, + 'right_pupil_posn': array([-0.27746862, -0.19395685]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.24998855590820312, + 'timestamp': 995.5168520770967, + 'timestamp_carla': 995516, + 'timestamp_device': 4148946, + 'timestamp_stream': 995.5168520770967, + 'transform': [array([ 1.26643932e+00, 1.58193674e+01, -4.65869904e-04]), + array([-0.06345928, -6.64246893, 0.02573992])]} +{'AngularVelocity': array([ 0.03609541, -0.00899773, -0.01302496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.174273133277893, + 'FR_Wheel_Angle': 1.3017756938934326, + 'Location': array([ -2.3660686 , -21.40837288, 0.17201322]), + 'Rotation': array([-8.12109467e-03, -8.93555222e+01, 6.41481876e-02]), + 'Velocity': array([ 4.88378517e-02, -2.26541567e+00, -3.13978177e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.54599476, 15.24623203, -0.20260909]), + 'camera_rotation': array([-7.07598686, -3.57760262, -0.41671887]), + 'current_gear_input': False, + 'focus_actor_dist': 4044.341796875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -603.1307373 , -5331.48974609, 97.63233185]), + 'frame': 30805, + 'frame_number': 30805, + 'framesequence': 118352, + 'gaze_dir': array([ 0.99040985, -0.07632446, 0.11386871]), + 'gaze_origin': array([-2.99429798, 0.05103149, -0.07883912]), + 'gaze_valid': True, + 'gaze_vergence': 89.8854751586914, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98942566, -0.06776428, 0.12815857]), + 'left_gaze_origin': array([-2.94175577, 2.92033076, -0.04236298]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7357025146484375, + 'left_pupil_posn': array([ 0.18502319, -0.09647679]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99139404, -0.08488464, 0.09957886]), + 'right_gaze_origin': array([-3.04683995, -2.81826806, -0.11531526]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7913665771484375, + 'right_pupil_posn': array([-0.27763742, -0.19405258]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.24998855590820312, + 'timestamp': 995.5512125790119, + 'timestamp_carla': 995551, + 'timestamp_device': 4148980, + 'timestamp_stream': 995.5512125790119, + 'transform': [array([ 1.26939178e+00, 1.57990065e+01, -7.90977429e-05]), + array([-0.0636437 , -6.64594078, 0.02498132])]} +{'AngularVelocity': array([ 0.05734975, -0.00371419, 0.75898594]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9713521003723145, + 'FR_Wheel_Angle': 2.212963342666626, + 'Location': array([ -2.35510755, -21.86365128, 0.17216238]), + 'Rotation': array([-1.96777731e-02, -8.91266479e+01, 6.25960827e-02]), + 'Velocity': array([ 7.17068836e-02, -2.23594451e+00, 1.37654773e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.53659725, 15.24664783, -0.21026751]), + 'camera_rotation': array([-7.05967617, -3.59397864, -0.47167784]), + 'current_gear_input': False, + 'focus_actor_dist': 4042.190673828125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -600.3762207 , -5331.48974609, 97.12643433]), + 'frame': 30806, + 'frame_number': 30806, + 'framesequence': 118356, + 'gaze_dir': array([ 0.99027252, -0.07637024, 0.11503601]), + 'gaze_origin': array([-2.99311686, 0.05095215, -0.07982865]), + 'gaze_valid': True, + 'gaze_vergence': 87.97724151611328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98924255, -0.06797791, 0.12944031]), + 'left_gaze_origin': array([-2.93939376, 2.92044997, -0.04375 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.80230712890625, + 'left_pupil_posn': array([ 0.1850009 , -0.09674549]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99130249, -0.08476257, 0.10063171]), + 'right_gaze_origin': array([-3.04683995, -2.81854582, -0.1159073 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.770355224609375, + 'right_pupil_posn': array([-0.27752411, -0.19395685]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2896620035171509, + 'timestamp': 995.5848020762205, + 'timestamp_carla': 995584, + 'timestamp_device': 4149013, + 'timestamp_stream': 995.5848020762205, + 'transform': [array([ 1.27249980e+00, 1.57770996e+01, -1.97086323e-04]), + array([-0.06358906, -6.64954615, 0.02522871])]} +{'AngularVelocity': array([ 3.28552276e-02, -1.39672542e-03, 2.41653085e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.593994140625, + 'FR_Wheel_Angle': 4.054975509643555, + 'Location': array([ -2.33612657, -22.36664581, 0.1722365 ]), + 'Rotation': array([-3.10978498e-02, -8.86961594e+01, 6.01783320e-02]), + 'Velocity': array([ 1.14525937e-01, -2.09979725e+00, -7.31887820e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.52419853, 15.23823929, -0.21303731]), + 'camera_rotation': array([-7.02890635, -3.61418891, -0.44218245]), + 'current_gear_input': False, + 'focus_actor_dist': 4040.2802734375, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -602.15106201, -5331.49023438, 102.68145752]), + 'frame': 30807, + 'frame_number': 30807, + 'framesequence': 118360, + 'gaze_dir': array([ 0.99132538, -0.0224762 , 0.12771606]), + 'gaze_origin': array([-2.93953347, 0.01268005, -0.09353943]), + 'gaze_valid': True, + 'gaze_vergence': 135.67633056640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99205017, -0.00151062, 0.1257782 ]), + 'left_gaze_origin': array([-2.78082752, 2.87975168, -0.09430237]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.85894775390625, + 'left_pupil_posn': array([ 0.22454417, -0.09120023]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99060059, -0.04344177, 0.12965393]), + 'right_gaze_origin': array([-3.09823918, -2.85439157, -0.09277649]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7720947265625, + 'right_pupil_posn': array([-0.22987062, -0.18955064]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.3055466413497925, + 'timestamp': 995.6163950785995, + 'timestamp_carla': 995616, + 'timestamp_device': 4149046, + 'timestamp_stream': 995.6163950785995, + 'transform': [array([ 1.27377093e+00, 1.57556419e+01, -3.65638734e-05]), + array([-0.06365053, -6.64957619, 0.02495598])]} +{'AngularVelocity': array([ 0.00707539, -0.01290143, 3.68406081]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.746720790863037, + 'FR_Wheel_Angle': 6.55050802230835, + 'Location': array([ -2.30617309, -22.8366375 , 0.17214113]), + 'Rotation': array([-3.45744155e-02, -8.79784470e+01, 5.69864847e-02]), + 'Velocity': array([ 1.75031617e-01, -1.90336263e+00, 8.56018043e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.51645851, 15.24109459, -0.22299099]), + 'camera_rotation': array([-7.04174042, -3.60122085, -0.49047431]), + 'current_gear_input': False, + 'focus_actor_dist': 4026.13427734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -385.72671509, -5331.48974609, 156.67324829]), + 'frame': 30808, + 'frame_number': 30808, + 'framesequence': 118364, + 'gaze_dir': array([ 9.91432190e-01, -2.44140625e-04, 1.28883362e-01]), + 'gaze_origin': array([-2.95964146, -0.01245956, -0.08497772]), + 'gaze_valid': True, + 'gaze_vergence': 126.08937072753906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99250793, 0.01896667, 0.12065125]), + 'left_gaze_origin': array([-2.78473067, 2.84964609, -0.09316712]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.917724609375, + 'left_pupil_posn': array([ 0.2528218 , -0.08880961]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99035645, -0.01945496, 0.13711548]), + 'right_gaze_origin': array([-3.134552 , -2.87456536, -0.07678833]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.779876708984375, + 'right_pupil_posn': array([-0.20890146, -0.18772924]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.31348133087158203, + 'timestamp': 995.6494202762842, + 'timestamp_carla': 995649, + 'timestamp_device': 4149080, + 'timestamp_stream': 995.6494202762842, + 'transform': [array([ 1.27498353e+00, 1.57315893e+01, -2.21614828e-04]), + array([-0.06359589, -6.64917755, 0.02532752])]} +{'AngularVelocity': array([ 1.83558534e-03, -6.84970990e-03, 5.54229116e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.235669136047363, + 'FR_Wheel_Angle': 10.805296897888184, + 'Location': array([ -2.26494956, -23.23190308, 0.17207178]), + 'Rotation': array([-3.53667177e-02, -8.69494476e+01, 5.23754880e-02]), + 'Velocity': array([ 2.55362988e-01, -1.72150266e+00, -1.53136250e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.51462078, 15.23945904, -0.21965446]), + 'camera_rotation': array([-7.06645203, -3.5936873 , -0.4756799 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4022.506591796875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -295.64093018, -5331.49023438, 160.9210968 ]), + 'frame': 30809, + 'frame_number': 30809, + 'framesequence': 118368, + 'gaze_dir': array([9.91210938e-01, 9.15527344e-04, 1.30958557e-01]), + 'gaze_origin': array([-2.93687749, -0.01295242, -0.09207383]), + 'gaze_valid': True, + 'gaze_vergence': 138.2465057373047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99229431, 0.01750183, 0.12265015]), + 'left_gaze_origin': array([-2.75849152, 2.84941125, -0.10104676]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.912078857421875, + 'left_pupil_posn': array([ 0.25384533, -0.08841336]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99012756, -0.01567078, 0.13926697]), + 'right_gaze_origin': array([-3.11526346, -2.8753159 , -0.08310089]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8005523681640625, + 'right_pupil_posn': array([-0.20889062, -0.18764424]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.31348133087158203, + 'timestamp': 995.6829987764359, + 'timestamp_carla': 995682, + 'timestamp_device': 4149113, + 'timestamp_stream': 995.6829987764359, + 'transform': [array([ 1.28000283e+00, 1.57049789e+01, -4.72736341e-04]), + array([-0.06359589, -6.65607738, 0.0258208 ])]} +{'AngularVelocity': array([-1.39592774e-03, 1.58001669e-02, 6.67207050e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.220479011535645, + 'FR_Wheel_Angle': 14.319554328918457, + 'Location': array([ -2.21406198, -23.56061172, 0.17197034]), + 'Rotation': array([-3.55238132e-02, -8.56832123e+01, 5.22266440e-02]), + 'Velocity': array([ 3.16298991e-01, -1.56592584e+00, -1.05714797e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.51614952, 15.2394762 , -0.21011274]), + 'camera_rotation': array([-7.04631662, -3.60073328, -0.48952261]), + 'current_gear_input': False, + 'focus_actor_dist': 4020.09814453125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -290.19665527, -5331.48925781, 167.61454773]), + 'frame': 30810, + 'frame_number': 30810, + 'framesequence': 118372, + 'gaze_dir': array([0.99115753, 0.00104523, 0.13132477]), + 'gaze_origin': array([-2.93143773, -0.01293335, -0.09395066]), + 'gaze_valid': True, + 'gaze_vergence': 141.99893188476562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99212646, 0.01800537, 0.12391663]), + 'left_gaze_origin': array([-2.75493336, 2.84976053, -0.10236359]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.91204833984375, + 'left_pupil_posn': array([ 0.25347126, -0.08880961]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9901886 , -0.01591492, 0.13873291]), + 'right_gaze_origin': array([-3.10794234, -2.87562728, -0.08553772]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.810882568359375, + 'right_pupil_posn': array([-0.20850021, -0.18751025]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.31348133087158203, + 'timestamp': 995.716710075736, + 'timestamp_carla': 995716, + 'timestamp_device': 4149146, + 'timestamp_stream': 995.716710075736, + 'transform': [array([ 1.28094769e+00, 1.56772871e+01, -5.95836609e-04]), + array([-0.06346612, -6.65473604, 0.02606823])]} +{'AngularVelocity': array([-9.75506904e-04, 1.88587625e-02, 7.43070841e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.523759841918945, + 'FR_Wheel_Angle': 17.108888626098633, + 'Location': array([ -2.13200188, -23.95291901, 0.17182398]), + 'Rotation': array([-3.57970186e-02, -8.37492294e+01, 5.44274375e-02]), + 'Velocity': array([ 3.73422205e-01, -1.37585366e+00, -3.35283286e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.50039101, 15.2395668 , -0.20967263]), + 'camera_rotation': array([-6.99711847, -3.61201048, -0.46492204]), + 'current_gear_input': False, + 'focus_actor_dist': 4017.51123046875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -290.62411499, -5331.48974609, 170.5362854 ]), + 'frame': 30811, + 'frame_number': 30811, + 'framesequence': 118376, + 'gaze_dir': array([0.99114227, 0.00119019, 0.13159943]), + 'gaze_origin': array([-2.9283731 , -0.01313095, -0.09488831]), + 'gaze_valid': True, + 'gaze_vergence': 154.16917419433594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99195862, 0.01737976, 0.12535095]), + 'left_gaze_origin': array([-2.75370955, 2.84994197, -0.10236359]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.91204833984375, + 'left_pupil_posn': array([ 0.25364649, -0.08887112]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99032593, -0.01499939, 0.1378479 ]), + 'right_gaze_origin': array([-3.10303664, -2.87620401, -0.08741303]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8264617919921875, + 'right_pupil_posn': array([-0.20832652, -0.18738639]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.27775996923446655, + 'timestamp': 995.7499518766999, + 'timestamp_carla': 995749, + 'timestamp_device': 4149180, + 'timestamp_stream': 995.7499518766999, + 'transform': [array([ 1.28064942e+00, 1.56487780e+01, -6.09264360e-04]), + array([-0.06347294, -6.65086031, 0.02611087])]} +{'AngularVelocity': array([-1.84286467e-03, 1.83193590e-02, 7.33245182e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.645923614501953, + 'FR_Wheel_Angle': 18.37590980529785, + 'Location': array([ -2.05190825, -24.25744247, 0.17170072]), + 'Rotation': array([-3.60975489e-02, -8.19962082e+01, 5.77264354e-02]), + 'Velocity': array([ 3.93978298e-01, -1.23080313e+00, -8.49723801e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.50094032, 15.21941566, -0.20875572]), + 'camera_rotation': array([-6.95861673, -3.60441065, -0.46718258]), + 'current_gear_input': False, + 'focus_actor_dist': 4014.75927734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -290.33905029, -5331.48974609, 175.07907104]), + 'frame': 30812, + 'frame_number': 30812, + 'framesequence': 118380, + 'gaze_dir': array([ 0.99240112, -0.01945496, 0.11823273]), + 'gaze_origin': array([-2.97853327, 0.01123962, -0.07967148]), + 'gaze_valid': True, + 'gaze_vergence': 98.32560729980469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99189758, 0.00686646, 0.12684631]), + 'left_gaze_origin': array([-2.85080433, 2.87757897, -0.06972809]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.919891357421875, + 'left_pupil_posn': array([ 0.2261647 , -0.09483325]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99290466, -0.04577637, 0.10961914]), + 'right_gaze_origin': array([-3.10626245, -2.85509944, -0.08961488]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9182891845703125, + 'right_pupil_posn': array([-0.22645479, -0.18874562]), + 'right_pupil_posn_valid': True, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2658579349517822, + 'timestamp': 995.782936476171, + 'timestamp_carla': 995782, + 'timestamp_device': 4149213, + 'timestamp_stream': 995.782936476171, + 'transform': [array([ 1.28033674e+00, 1.56189594e+01, -6.77261327e-04]), + array([-0.06347294, -6.64682341, 0.02626363])]} +{'AngularVelocity': array([-7.98379595e-04, 1.08531099e-02, 6.83474731e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.70419692993164, + 'FR_Wheel_Angle': 18.427892684936523, + 'Location': array([ -1.98498476, -24.48225212, 0.17164396]), + 'Rotation': array([-3.63161154e-02, -8.06479568e+01, 6.06523976e-02]), + 'Velocity': array([ 3.91719252e-01, -1.12778652e+00, -6.26039517e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.50535202, 15.18684673, -0.19771571]), + 'camera_rotation': array([-6.84036589, -3.65630293, -0.42404205]), + 'current_gear_input': False, + 'focus_actor_dist': 4012.934814453125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -371.8727417 , -5331.49023438, 123.33975983]), + 'frame': 30813, + 'frame_number': 30813, + 'framesequence': 118384, + 'gaze_dir': array([ 0.97659302, -0.19564056, 0.08489227]), + 'gaze_origin': array([-2.98016214, 0.14710237, -0.11138231]), + 'gaze_valid': True, + 'gaze_vergence': 99.86934661865234, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98130798, -0.16925049, 0.09144592]), + 'left_gaze_origin': array([-2.85460234, 3.00326252, -0.09210206]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9071044921875, + 'left_pupil_posn': array([ 0.08153641, -0.12173712]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97187805, -0.22203064, 0.07833862]), + 'right_gaze_origin': array([-3.10572219, -2.70905781, -0.13066255]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.919525146484375, + 'right_pupil_posn': array([-0.39005637, -0.22914886]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0009704886469990015, + 'throttle_input': 0.26189059019088745, + 'timestamp': 995.8166367784142, + 'timestamp_carla': 995816, + 'timestamp_device': 4149246, + 'timestamp_stream': 995.8166367784142, + 'transform': [array([ 1.27996957e+00, 1.55870142e+01, -7.27062230e-04]), + array([-0.06352076, -6.64246893, 0.02636866])]} +{'AngularVelocity': array([2.76434381e-04, 4.60225949e-03, 6.29570627e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.740797996520996, + 'FR_Wheel_Angle': 18.479406356811523, + 'Location': array([ -1.9139868 , -24.70142555, 0.17147401]), + 'Rotation': array([-3.65278497e-02, -7.93204803e+01, 6.20725751e-02]), + 'Velocity': array([ 3.84537965e-01, -1.02784324e+00, -6.30779250e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.46779251, 15.13063622, -0.1947241 ]), + 'camera_rotation': array([-6.71263456, -4.02199602, -0.44812357]), + 'current_gear_input': False, + 'focus_actor_dist': 1914.907958984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -657.71142578, -3197.36035156, 71.01403809]), + 'frame': 30814, + 'frame_number': 30814, + 'framesequence': 118388, + 'gaze_dir': array([ 0.97010803, -0.23226166, 0.06788635]), + 'gaze_origin': array([-2.98539758, 0.1714119 , -0.11761094]), + 'gaze_valid': True, + 'gaze_vergence': 132.44186401367188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97291565, -0.21765137, 0.07775879]), + 'left_gaze_origin': array([-2.85775614, 3.02382994, -0.09815064]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6768341064453125, + 'left_pupil_posn': array([ 0.05941248, -0.13389707]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96730042, -0.24687195, 0.05801392]), + 'right_gaze_origin': array([-3.11303878, -2.68100595, -0.13707124]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9947662353515625, + 'right_pupil_posn': array([-0.427531 , -0.24047053]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00238044373691082, + 'throttle_input': 0.24998855590820312, + 'timestamp': 995.8489005789161, + 'timestamp_carla': 995848, + 'timestamp_device': 4149280, + 'timestamp_stream': 995.8489005789161, + 'transform': [array([ 1.27939987e+00, 1.55548725e+01, -8.64753732e-04]), + array([-0.06356857, -6.63773441, 0.02666902])]} +{'AngularVelocity': array([1.04737421e-03, 2.78416229e-03, 5.72253084e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.7655611038208, + 'FR_Wheel_Angle': 18.517555236816406, + 'Location': array([ -1.83336067, -24.93108559, 0.17138764]), + 'Rotation': array([-3.68352085e-02, -7.79145508e+01, 6.27361909e-02]), + 'Velocity': array([ 3.72189462e-01, -9.23473418e-01, -3.70335561e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.433671 , 14.99991512, -0.20093583]), + 'camera_rotation': array([-6.56238413, -4.71801758, -0.29918388]), + 'current_gear_input': False, + 'focus_actor_dist': 1125.9537353515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -546.44726562, -2416.66650391, 80.92727661]), + 'frame': 30815, + 'frame_number': 30815, + 'framesequence': 118392, + 'gaze_dir': array([ 0.97340393, -0.21819305, 0.06465149]), + 'gaze_origin': array([-2.98295522, 0.15977784, -0.12183992]), + 'gaze_valid': True, + 'gaze_vergence': 81.92981719970703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97653198, -0.19909668, 0.08195496]), + 'left_gaze_origin': array([-2.8563509 , 3.01611638, -0.10507049]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8298187255859375, + 'left_pupil_posn': array([ 0.0679518 , -0.14174926]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97027588, -0.23728943, 0.04734802]), + 'right_gaze_origin': array([-3.10955977, -2.69656086, -0.13860932]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.035369873046875, + 'right_pupil_posn': array([-0.40982044, -0.23916197]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004431287758052349, + 'throttle_input': 0.2222171425819397, + 'timestamp': 995.8852027766407, + 'timestamp_carla': 995885, + 'timestamp_device': 4149313, + 'timestamp_stream': 995.8852027766407, + 'transform': [array([ 1.27889371e+00, 1.55172729e+01, -8.47969030e-04]), + array([-0.06372566, -6.63257599, 0.02659905])]} +{'AngularVelocity': array([1.42311445e-03, 2.78893276e-03, 5.15083218e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.791399955749512, + 'FR_Wheel_Angle': 18.54743194580078, + 'Location': array([ -1.75530374, -25.13754845, 0.17127931]), + 'Rotation': array([-3.72928306e-02, -7.66370850e+01, 6.33166432e-02]), + 'Velocity': array([ 3.56740683e-01, -8.30151260e-01, -4.10337438e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.40704441, 14.8504715 , -0.20729125]), + 'camera_rotation': array([-6.65758324, -5.57025051, -0.03152832]), + 'current_gear_input': False, + 'focus_actor_dist': 1141.294189453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -547.29516602, -2435.50366211, 79.75775909]), + 'frame': 30816, + 'frame_number': 30816, + 'framesequence': 118397, + 'gaze_dir': array([ 0.9761734 , -0.20436859, 0.07006836]), + 'gaze_origin': array([-2.98273706, 0.15245821, -0.11960068]), + 'gaze_valid': True, + 'gaze_vergence': 136.15463256835938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97950745, -0.18617249, 0.07666016]), + 'left_gaze_origin': array([-2.85652494, 3.00989532, -0.10306703]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7397003173828125, + 'left_pupil_posn': array([ 0.07700562, -0.13450134]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97283936, -0.2225647 , 0.06347656]), + 'right_gaze_origin': array([-3.10894942, -2.70497918, -0.13613434]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0281829833984375, + 'right_pupil_posn': array([-0.3992328 , -0.23902833]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.007159642409533262, + 'throttle_input': 0.20236514508724213, + 'timestamp': 995.9187923781574, + 'timestamp_carla': 995918, + 'timestamp_device': 4149355, + 'timestamp_stream': 995.9187923781574, + 'transform': [array([ 1.28039300e+00, 1.54809313e+01, -7.17067684e-04]), + array([-0.06398521, -6.63165998, 0.0263743 ])]} +{'AngularVelocity': array([1.68149488e-03, 1.66711293e-03, 4.67777157e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.808147430419922, + 'FR_Wheel_Angle': 18.569936752319336, + 'Location': array([ -1.68242776, -25.31852531, 0.17117864]), + 'Rotation': array([-3.76889817e-02, -7.55057144e+01, 6.36570752e-02]), + 'Velocity': array([ 3.40217620e-01, -7.49633312e-01, -1.12056732e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.4021616 , 14.71151447, -0.23388293]), + 'camera_rotation': array([-6.94905472, -6.44454145, -0.24091972]), + 'current_gear_input': False, + 'focus_actor_dist': 1141.052490234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -547.45666504, -2439.2644043 , 84.86663818]), + 'frame': 30817, + 'frame_number': 30817, + 'framesequence': 118400, + 'gaze_dir': array([ 0.97800446, -0.19464874, 0.07192993]), + 'gaze_origin': array([-2.97912383, 0.14418183, -0.11695023]), + 'gaze_valid': True, + 'gaze_vergence': 120.37712097167969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9808197 , -0.17677307, 0.08200073]), + 'left_gaze_origin': array([-2.85794234, 3.0028367 , -0.09707337]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8058929443359375, + 'left_pupil_posn': array([ 0.0852946 , -0.13131011]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97518921, -0.21252441, 0.06185913]), + 'right_gaze_origin': array([-3.10030532, -2.71447301, -0.1368271 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9749298095703125, + 'right_pupil_posn': array([-0.38905102, -0.23573637]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01067537534981966, + 'throttle_input': 0.17856107652187347, + 'timestamp': 995.9508713781834, + 'timestamp_carla': 995950, + 'timestamp_device': 4149380, + 'timestamp_stream': 995.9508713781834, + 'transform': [array([ 1.28187144e+00, 1.54449663e+01, -6.40010810e-04]), + array([-0.06436087, -6.63089657, 0.02626786])]} +{'AngularVelocity': array([2.28355057e-03, 8.92054581e-04, 4.30038786e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.83264446258545, + 'FR_Wheel_Angle': 18.609630584716797, + 'Location': array([ -1.62111676, -25.46317291, 0.17111646]), + 'Rotation': array([-3.82080749e-02, -7.45928726e+01, 6.37000725e-02]), + 'Velocity': array([ 3.24256629e-01, -6.84831083e-01, -6.55574782e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.39436054, 14.58759689, -0.27035791]), + 'camera_rotation': array([-7.13424826, -7.33231544, -0.48127282]), + 'current_gear_input': False, + 'focus_actor_dist': 1113.181640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -546.63232422, -2414.18237305, 81.5556488 ]), + 'frame': 30818, + 'frame_number': 30818, + 'framesequence': 118404, + 'gaze_dir': array([ 0.98109436, -0.18057251, 0.0671463 ]), + 'gaze_origin': array([-2.98470545, 0.13635635, -0.11491471]), + 'gaze_valid': True, + 'gaze_vergence': 128.1815948486328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98294067, -0.16654968, 0.07792664]), + 'left_gaze_origin': array([-2.86497808, 2.99654555, -0.09434662]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8371734619140625, + 'left_pupil_posn': array([ 0.09576643, -0.13251328]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97924805, -0.19459534, 0.05636597]), + 'right_gaze_origin': array([-3.10443282, -2.72383285, -0.13548279]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8704681396484375, + 'right_pupil_posn': array([-0.37898546, -0.23674822]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014026307500898838, + 'throttle_input': 0.1745937317609787, + 'timestamp': 995.9845643788576, + 'timestamp_carla': 995984, + 'timestamp_device': 4149413, + 'timestamp_stream': 995.9845643788576, + 'transform': [array([ 1.28646922e+00, 1.54059362e+01, -3.29895003e-04]), + array([-0.06480483, -6.63614178, 0.0256728 ])]} +{'AngularVelocity': array([-0.01601523, -0.01488034, 2.73321366]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.853532791137695, + 'FR_Wheel_Angle': 18.62303352355957, + 'Location': array([ -1.55827236, -25.60474586, 0.17105341]), + 'Rotation': array([-4.02844548e-02, -7.36992493e+01, 6.47411421e-02]), + 'Velocity': array([ 2.80640990e-01, -5.70362687e-01, -3.34005337e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.38884735, 14.45981312, -0.25235119]), + 'camera_rotation': array([-7.07693624, -8.20008659, -0.46262047]), + 'current_gear_input': False, + 'focus_actor_dist': 1094.38525390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -543.31860352, -2398.71508789, 72.58366394]), + 'frame': 30819, + 'frame_number': 30819, + 'framesequence': 118408, + 'gaze_dir': array([ 0.98189545, -0.176651 , 0.06652069]), + 'gaze_origin': array([-2.99106693, 0.12909012, -0.11374512]), + 'gaze_valid': True, + 'gaze_vergence': 141.55453491210938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98320007, -0.1656189 , 0.07662964]), + 'left_gaze_origin': array([-2.88435531, 2.98904276, -0.08957825]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.86102294921875, + 'left_pupil_posn': array([ 0.10327196, -0.1329571 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98059082, -0.18768311, 0.05641174]), + 'right_gaze_origin': array([-3.09777856, -2.73086262, -0.13791199]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.822357177734375, + 'right_pupil_posn': array([-0.37372816, -0.23746014]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.016772974282503128, + 'throttle_input': 0.1745937317609787, + 'timestamp': 996.0166866779327, + 'timestamp_carla': 996016, + 'timestamp_device': 4149446, + 'timestamp_stream': 996.0166866779327, + 'transform': [array([1.29156566e+00, 1.53677816e+01, 1.00326533e-05]), + array([-0.06520781, -6.64264631, 0.02504332])]} +{'AngularVelocity': array([-0.03016873, -0.0380473 , 4.2413578 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.804976463317871, + 'FR_Wheel_Angle': 18.556550979614258, + 'Location': array([ -1.49057734, -25.75139999, 0.17091569]), + 'Rotation': array([-3.17057371e-02, -7.27536392e+01, 5.93720637e-02]), + 'Velocity': array([ 3.57781708e-01, -6.98404968e-01, -2.85263057e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.36794281, 14.33017921, -0.22096926]), + 'camera_rotation': array([-6.9895916 , -9.06070137, -0.49934161]), + 'current_gear_input': False, + 'focus_actor_dist': 1052.046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -544.07189941, -2358.68041992, 75.35456848]), + 'frame': 30820, + 'frame_number': 30820, + 'framesequence': 118412, + 'gaze_dir': array([ 0.98654938, -0.15001678, 0.06217957]), + 'gaze_origin': array([-3.09917617, 0.12400971, -0.08033981]), + 'gaze_valid': True, + 'gaze_vergence': 13.003966331481934, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98556519, -0.14888 , 0.08047485]), + 'left_gaze_origin': array([-3.10588384, 2.99150562, -0.01921539]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.71466064453125, + 'left_pupil_posn': array([ 0.11515415, -0.13159513]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98753357, -0.15115356, 0.04388428]), + 'right_gaze_origin': array([-3.09246826, -2.74348617, -0.14146425]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.83154296875, + 'right_pupil_posn': array([-0.35893732, -0.23741674]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01832941733300686, + 'throttle_input': 0.1745937317609787, + 'timestamp': 996.0515998788178, + 'timestamp_carla': 996051, + 'timestamp_device': 4149480, + 'timestamp_stream': 996.0515998788178, + 'transform': [array([1.29902220e+00, 1.53253241e+01, 4.53567482e-04]), + array([-0.06553566, -6.653512 , 0.02416491])]} +{'AngularVelocity': array([0.02407258, 0.02129866, 4.39283133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.547683715820312, + 'FR_Wheel_Angle': 18.081478118896484, + 'Location': array([ -1.40993929, -25.91856384, 0.17083475]), + 'Rotation': array([-3.49500775e-02, -7.16810913e+01, 6.02069199e-02]), + 'Velocity': array([ 3.68774027e-01, -6.90215230e-01, -3.20167543e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.34899235, 14.20128918, -0.19755356]), + 'camera_rotation': array([-6.89206362, -9.79881573, -0.58370876]), + 'current_gear_input': False, + 'focus_actor_dist': 1085.2138671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -540.08532715, -2397.4296875 , 70.01460266]), + 'frame': 30821, + 'frame_number': 30821, + 'framesequence': 118416, + 'gaze_dir': array([ 0.98784637, -0.13858032, 0.06575012]), + 'gaze_origin': array([-3.09397364, 0.11638947, -0.08390885]), + 'gaze_valid': True, + 'gaze_vergence': 22.161718368530273, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98548889, -0.14396667, 0.08973694]), + 'left_gaze_origin': array([-3.14798617, 2.98604441, -0.00842743]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7823486328125, + 'left_pupil_posn': array([ 0.12546885, -0.13309777]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99020386, -0.13319397, 0.04176331]), + 'right_gaze_origin': array([-3.03996134, -2.75326562, -0.15939027]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.86065673828125, + 'right_pupil_posn': array([-0.34973085, -0.23619807]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.020142216235399246, + 'throttle_input': 0.1745937317609787, + 'timestamp': 996.0843815766275, + 'timestamp_carla': 996084, + 'timestamp_device': 4149513, + 'timestamp_stream': 996.0843815766275, + 'transform': [array([1.30553317e+00, 1.52847271e+01, 8.12931044e-04]), + array([-0.06579521, -6.66282272, 0.02349608])]} +{'AngularVelocity': array([0.00799709, 0.00937549, 3.84188676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.802413940429688, + 'FR_Wheel_Angle': 16.99440574645996, + 'Location': array([ -1.32477427, -26.08873749, 0.17080343]), + 'Rotation': array([-3.98883037e-02, -7.06158295e+01, 6.26924932e-02]), + 'Velocity': array([ 3.40410620e-01, -6.21350348e-01, -2.87952425e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.35037708, 14.07302189, -0.17626081]), + 'camera_rotation': array([ -6.76291847, -10.47755241, -0.56035095]), + 'current_gear_input': False, + 'focus_actor_dist': 1093.9090576171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -543.90142822, -2409.90869141, 74.92417908]), + 'frame': 30822, + 'frame_number': 30822, + 'framesequence': 118420, + 'gaze_dir': array([ 0.98948669, -0.12638855, 0.06668091]), + 'gaze_origin': array([-3.09054494, 0.10898285, -0.08646011]), + 'gaze_valid': True, + 'gaze_vergence': 21.356359481811523, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98753357, -0.13050842, 0.08787537]), + 'left_gaze_origin': array([-3.15514398, 2.98040032, -0.00795136]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6865997314453125, + 'left_pupil_posn': array([ 0.13311112, -0.1325804 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99143982, -0.12226868, 0.04548645]), + 'right_gaze_origin': array([-3.02594614, -2.76243448, -0.16496888]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7806854248046875, + 'right_pupil_posn': array([-0.33853537, -0.2376585 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02146061696112156, + 'throttle_input': 0.19839780032634735, + 'timestamp': 996.1173302792013, + 'timestamp_carla': 996117, + 'timestamp_device': 4149546, + 'timestamp_stream': 996.1173302792013, + 'transform': [array([1.31306434e+00, 1.52432003e+01, 1.22167589e-03]), + array([-0.06597279, -6.67414236, 0.0227235 ])]} +{'AngularVelocity': array([-3.52533767e-04, 1.03180464e-02, 2.96157765e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.680241584777832, + 'FR_Wheel_Angle': 14.018754005432129, + 'Location': array([ -1.26234293, -26.21274376, 0.17073022]), + 'Rotation': array([-4.11382280e-02, -6.99163055e+01, 6.49684444e-02]), + 'Velocity': array([ 3.05296034e-01, -5.76530457e-01, 3.84998311e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.36347961, 13.95474243, -0.18053353]), + 'camera_rotation': array([ -6.62879372, -11.08772373, -0.62004578]), + 'current_gear_input': False, + 'focus_actor_dist': 1104.7528076171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -546.17858887, -2424.67919922, 77.80555725]), + 'frame': 30823, + 'frame_number': 30823, + 'framesequence': 118424, + 'gaze_dir': array([ 0.98983765, -0.12304688, 0.06863403]), + 'gaze_origin': array([-3.10472417, 0.10439759, -0.08331376]), + 'gaze_valid': True, + 'gaze_vergence': 21.201763153076172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98820496, -0.12606812, 0.08676147]), + 'left_gaze_origin': array([-3.16179061, 2.9752686 , -0.00816803]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7097320556640625, + 'left_pupil_posn': array([ 0.13748884, -0.13236654]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99147034, -0.12002563, 0.05050659]), + 'right_gaze_origin': array([-3.04765797, -2.76647353, -0.15845948]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8195648193359375, + 'right_pupil_posn': array([-0.33446807, -0.23777986]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.023273415863513947, + 'throttle_input': 0.21428243815898895, + 'timestamp': 996.1502145789564, + 'timestamp_carla': 996150, + 'timestamp_device': 4149580, + 'timestamp_stream': 996.1502145789564, + 'transform': [array([1.32112086e+00, 1.52009935e+01, 1.54886243e-03]), + array([-0.06614355, -6.68656635, 0.02210876])]} +{'AngularVelocity': array([-4.33421461e-04, 4.38891677e-03, 2.04540491e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.123711585998535, + 'FR_Wheel_Angle': 9.500226974487305, + 'Location': array([ -1.21344924, -26.31396675, 0.17066996]), + 'Rotation': array([-4.14729081e-02, -6.94730148e+01, 6.66549206e-02]), + 'Velocity': array([ 2.69187540e-01, -5.44123769e-01, -2.94136989e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.3322649 , 13.8579731 , -0.19400834]), + 'camera_rotation': array([ -6.51175833, -11.58492947, -0.77434146]), + 'current_gear_input': False, + 'focus_actor_dist': 1081.500732421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -548.20941162, -2404.40429688, 83.44377136]), + 'frame': 30824, + 'frame_number': 30824, + 'framesequence': 118428, + 'gaze_dir': array([ 0.98815155, -0.13230896, 0.07498932]), + 'gaze_origin': array([-2.957026 , 0.08849487, -0.13048935]), + 'gaze_valid': True, + 'gaze_vergence': 99.06021118164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9889679 , -0.11791992, 0.08959961]), + 'left_gaze_origin': array([-2.87436986, 2.95157933, -0.09870911]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.686676025390625, + 'left_pupil_posn': array([ 0.14223671, -0.13503742]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98733521, -0.146698 , 0.06037903]), + 'right_gaze_origin': array([-3.03968215, -2.77458978, -0.16226961]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.826995849609375, + 'right_pupil_posn': array([-0.32591081, -0.23797679]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.025873592123389244, + 'throttle_input': 0.21428243815898895, + 'timestamp': 996.1851260773838, + 'timestamp_carla': 996184, + 'timestamp_device': 4149613, + 'timestamp_stream': 996.1851260773838, + 'transform': [array([1.33125305e+00, 1.51552696e+01, 1.83984754e-03]), + array([-0.06634846, -6.70294571, 0.02153338])]} +{'AngularVelocity': array([ 0.00133876, -0.00303314, 1.11878955]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.386962890625, + 'FR_Wheel_Angle': 5.275545597076416, + 'Location': array([ -1.16521096, -26.42058945, 0.17061773]), + 'Rotation': array([-4.15685289e-02, -6.91647568e+01, 6.73194155e-02]), + 'Velocity': array([ 0.22988762, -0.51005816, -0.00093569]), + 'brake_input': 0.0, + 'camera_location': array([-8.31977272, 13.75920582, -0.21683796]), + 'camera_rotation': array([ -6.58284044, -11.97735214, -0.91346884]), + 'current_gear_input': False, + 'focus_actor_dist': 1028.936279296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -553.03582764, -2353.2722168 , 94.14331055]), + 'frame': 30825, + 'frame_number': 30825, + 'framesequence': 118432, + 'gaze_dir': array([ 0.98971558, -0.11989594, 0.07551575]), + 'gaze_origin': array([-2.96798658, 0.0875084 , -0.12518235]), + 'gaze_valid': True, + 'gaze_vergence': 88.45476531982422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98983765, -0.10914612, 0.0909729 ]), + 'left_gaze_origin': array([-2.89658689, 2.95108342, -0.08809509]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.678314208984375, + 'left_pupil_posn': array([ 0.14824975, -0.13212168]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98959351, -0.13064575, 0.06005859]), + 'right_gaze_origin': array([-3.03938603, -2.77606678, -0.16226961]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8274383544921875, + 'right_pupil_posn': array([-0.32180572, -0.23739672]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.028675192967057228, + 'throttle_input': 0.21824978291988373, + 'timestamp': 996.2170807793736, + 'timestamp_carla': 996216, + 'timestamp_device': 4149646, + 'timestamp_stream': 996.2170807793736, + 'transform': [array([1.34213066e+00, 1.51122351e+01, 1.89220428e-03]), + array([-0.06658068, -6.7211957 , 0.02147774])]} +{'AngularVelocity': array([ 0.00176571, -0.00616783, 0.41229132]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.923081874847412, + 'FR_Wheel_Angle': 1.6015557050704956, + 'Location': array([ -1.12365937, -26.51958847, 0.17055261]), + 'Rotation': array([-4.15685289e-02, -6.90209961e+01, 6.69667423e-02]), + 'Velocity': array([ 0.19584344, -0.47665671, -0.00097112]), + 'brake_input': 0.0, + 'camera_location': array([-8.32001591, 13.6814909 , -0.21789961]), + 'camera_rotation': array([ -6.75107479, -12.23899651, -0.97938961]), + 'current_gear_input': False, + 'focus_actor_dist': 1040.066650390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -550.76818848, -2369.8671875 , 92.63322449]), + 'frame': 30826, + 'frame_number': 30826, + 'framesequence': 118437, + 'gaze_dir': array([ 0.99008942, -0.11816406, 0.07348633]), + 'gaze_origin': array([-2.97241759, 0.0855568 , -0.12386017]), + 'gaze_valid': True, + 'gaze_vergence': 77.85652160644531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98997498, -0.10908508, 0.08958435]), + 'left_gaze_origin': array([-2.9063828 , 2.94884658, -0.08592224]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.705474853515625, + 'left_pupil_posn': array([ 0.15102971, -0.13347828]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99020386, -0.12724304, 0.05738831]), + 'right_gaze_origin': array([-3.03845239, -2.77773285, -0.1617981 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8347625732421875, + 'right_pupil_posn': array([-0.32061827, -0.23739672]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03178808093070984, + 'throttle_input': 0.2380865216255188, + 'timestamp': 996.2526106759906, + 'timestamp_carla': 996252, + 'timestamp_device': 4149688, + 'timestamp_stream': 996.2526106759906, + 'transform': [array([1.35665512e+00, 1.50633411e+01, 1.99947343e-03]), + array([-0.06687438, -6.74640942, 0.02125241])]} +{'AngularVelocity': array([ 4.54930495e-03, -1.48405079e-02, 8.15823569e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.08857834, -26.61008453, 0.1705232 ]), + 'Rotation': array([-4.13499624e-02, -6.90065308e+01, 6.57465383e-02]), + 'Velocity': array([ 1.69897646e-01, -4.43638295e-01, -1.25379564e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.31973553, 13.60149288, -0.20047444]), + 'camera_rotation': array([ -6.69695234, -12.41365814, -1.07919872]), + 'current_gear_input': False, + 'focus_actor_dist': 1022.46826171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -549.02758789, -2356.00805664, 88.15530396]), + 'frame': 30827, + 'frame_number': 30827, + 'framesequence': 118440, + 'gaze_dir': array([ 0.99018097, -0.11876678, 0.07152557]), + 'gaze_origin': array([-2.97079039, 0.08324204, -0.12499924]), + 'gaze_valid': True, + 'gaze_vergence': 61.22096633911133, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98976135, -0.11250305, 0.08772278]), + 'left_gaze_origin': array([-2.90189838, 2.94616556, -0.08966064]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6861724853515625, + 'left_pupil_posn': array([ 0.15354598, -0.13575923]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99060059, -0.12503052, 0.05532837]), + 'right_gaze_origin': array([-3.03968215, -2.77968168, -0.16033784]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8266448974609375, + 'right_pupil_posn': array([-0.3204962 , -0.23731196]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0349925234913826, + 'throttle_input': 0.269825279712677, + 'timestamp': 996.2837066762149, + 'timestamp_carla': 996283, + 'timestamp_device': 4149713, + 'timestamp_stream': 996.2837066762149, + 'transform': [array([1.36967635e+00, 1.50193539e+01, 1.83958048e-03]), + array([-0.06714758, -6.76923418, 0.02162675])]} +{'AngularVelocity': array([ 1.09217805e-03, -6.15198119e-03, 1.19438091e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.059618 , -26.68565559, 0.17049016]), + 'Rotation': array([-4.11109067e-02, -6.90065308e+01, 6.39604032e-02]), + 'Velocity': array([ 1.57976896e-01, -4.12323147e-01, 1.35755536e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.29773903, 13.54016304, -0.1907222 ]), + 'camera_rotation': array([ -6.55148315, -12.48971272, -1.24194789]), + 'current_gear_input': False, + 'focus_actor_dist': 1006.9774780273438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -548.73400879, -2344.62597656, 87.61762238]), + 'frame': 30828, + 'frame_number': 30828, + 'framesequence': 118444, + 'gaze_dir': array([ 0.98981476, -0.12049103, 0.07382202]), + 'gaze_origin': array([-2.96390319, 0.08123627, -0.12818529]), + 'gaze_valid': True, + 'gaze_vergence': 103.73377227783203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99002075, -0.11061096, 0.08720398]), + 'left_gaze_origin': array([-2.8853395 , 2.94339013, -0.09694367]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6650390625, + 'left_pupil_posn': array([ 0.15340948, -0.13574934]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98960876, -0.13037109, 0.06044006]), + 'right_gaze_origin': array([-3.04246688, -2.78091741, -0.15942688]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.821197509765625, + 'right_pupil_posn': array([-0.31901217, -0.23739672]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03808709979057312, + 'throttle_input': 0.2856946587562561, + 'timestamp': 996.3174819760025, + 'timestamp_carla': 996317, + 'timestamp_device': 4149746, + 'timestamp_stream': 996.3174819760025, + 'transform': [array([1.38649607e+00, 1.49702806e+01, 1.69073103e-03]), + array([-0.06740713, -6.79944611, 0.02192868])]} +{'AngularVelocity': array([-5.02069131e-04, -2.54846038e-03, 7.56505251e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.02920949, -26.76499367, 0.17044336]), + 'Rotation': array([-4.10767570e-02, -6.90065308e+01, 6.38334006e-02]), + 'Velocity': array([ 0.1454342 , -0.37948471, -0.0005976 ]), + 'brake_input': 0.0, + 'camera_location': array([-8.27211761, 13.4940834 , -0.17990154]), + 'camera_rotation': array([ -6.44176292, -12.53310394, -1.41062379]), + 'current_gear_input': False, + 'focus_actor_dist': 1007.64892578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -552.43963623, -2348.69555664, 92.09884644]), + 'frame': 30829, + 'frame_number': 30829, + 'framesequence': 118448, + 'gaze_dir': array([ 0.99002075, -0.12000275, 0.07180786]), + 'gaze_origin': array([-2.96543193, 0.08032075, -0.12871629]), + 'gaze_valid': True, + 'gaze_vergence': 108.93733978271484, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99038696, -0.10919189, 0.08488464]), + 'left_gaze_origin': array([-2.88137984, 2.94297504, -0.09826203]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6719818115234375, + 'left_pupil_posn': array([ 0.15351403, -0.13646901]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98965454, -0.1308136 , 0.05873108]), + 'right_gaze_origin': array([-3.04948449, -2.78233337, -0.15917054]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8125457763671875, + 'right_pupil_posn': array([-0.31765252, -0.23938036]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04099856689572334, + 'throttle_input': 0.3015792965888977, + 'timestamp': 996.3509867787361, + 'timestamp_carla': 996350, + 'timestamp_device': 4149780, + 'timestamp_stream': 996.3509867787361, + 'transform': [array([1.40467083e+00, 1.49202080e+01, 1.45675661e-03]), + array([-0.06763936, -6.83252621, 0.02240642])]} +{'AngularVelocity': array([ 1.01506589e-02, 3.01630422e-03, -2.54605802e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0807519406080246, + 'FR_Wheel_Angle': -0.07428959012031555, + 'Location': array([ -1.0123775 , -26.80889893, 0.17052855]), + 'Rotation': array([-5.83229810e-02, -6.90068054e+01, 6.37535080e-02]), + 'Velocity': array([ 8.44228089e-06, -5.26699569e-06, 7.84616685e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.24944115, 13.48976994, -0.1866726 ]), + 'camera_rotation': array([ -6.39303637, -12.45782471, -1.57123542]), + 'current_gear_input': False, + 'focus_actor_dist': 1003.282958984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST34', + 'focus_actor_pt': array([ -552.01196289, -2348.93920898, 91.82043457]), + 'frame': 30830, + 'frame_number': 30830, + 'framesequence': 118452, + 'gaze_dir': array([ 0.99105835, -0.082901 , 0.1031723 ]), + 'gaze_origin': array([-2.98513579, 0.05520172, -0.1015831 ]), + 'gaze_valid': True, + 'gaze_vergence': 133.92454528808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99098206, -0.07055664, 0.11381531]), + 'left_gaze_origin': array([-2.88873911, 2.9142611 , -0.07324219]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7357025146484375, + 'left_pupil_posn': array([ 0.18501163, -0.10959363]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99113464, -0.09524536, 0.0925293 ]), + 'right_gaze_origin': array([-3.08153248, -2.80385756, -0.12992401]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6719512939453125, + 'right_pupil_posn': array([-0.28913713, -0.21527267]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04339732229709625, + 'throttle_input': 0.3055466413497925, + 'timestamp': 996.3838464766741, + 'timestamp_carla': 996383, + 'timestamp_device': 4149813, + 'timestamp_stream': 996.3838464766741, + 'transform': [array([1.42439675e+00, 1.48695202e+01, 1.11877441e-03]), + array([-0.06778962, -6.86883974, 0.0230986 ])]} +{'AngularVelocity': array([-5.00918180e-02, -1.94919724e-02, 3.86485699e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011534701101481915, + 'FR_Wheel_Angle': 0.011535990051925182, + 'Location': array([ -1.01235247, -26.80896759, 0.17048426]), + 'Rotation': array([-4.80640382e-02, -6.90068970e+01, 6.36705235e-02]), + 'Velocity': array([-7.78366757e-06, 3.60283993e-05, 3.26628448e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.24096298, 13.48303795, -0.19647388]), + 'camera_rotation': array([ -6.38835764, -12.25448608, -1.5844022 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1862.4449462890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -727.07025146, -3197.17041016, 116.2455368 ]), + 'frame': 30831, + 'frame_number': 30831, + 'framesequence': 118456, + 'gaze_dir': array([ 0.99120331, -0.08185577, 0.10282135]), + 'gaze_origin': array([-2.9950068 , 0.0570427 , -0.09588395]), + 'gaze_valid': True, + 'gaze_vergence': 156.4822998046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99128723, -0.06985474, 0.11160278]), + 'left_gaze_origin': array([-2.90815139, 2.91737843, -0.06465454]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.744171142578125, + 'left_pupil_posn': array([ 0.18359423, -0.10699415]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99111938, -0.09385681, 0.09403992]), + 'right_gaze_origin': array([-3.08186197, -2.80329299, -0.12711334]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.67340087890625, + 'right_pupil_posn': array([-0.28925443, -0.21416628]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04533830285072327, + 'throttle_input': 0.30951398611068726, + 'timestamp': 996.4171793758869, + 'timestamp_carla': 996416, + 'timestamp_device': 4149846, + 'timestamp_stream': 996.4171793758869, + 'transform': [array([1.44621074e+00, 1.48164301e+01, 7.09762564e-04]), + array([-0.0678511 , -6.9093647 , 0.02392169])]} +{'AngularVelocity': array([-1.59647763e-02, -6.20186329e-03, 3.33581852e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.03332620486617088, + 'FR_Wheel_Angle': -0.025629183277487755, + 'Location': array([ -1.01233578, -26.80901146, 0.17043138]), + 'Rotation': array([-4.15343791e-02, -6.90068970e+01, 6.36397451e-02]), + 'Velocity': array([9.69884013e-07, 1.21432304e-05, 2.35468360e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.23497677, 13.4839468 , -0.19409762]), + 'camera_rotation': array([ -6.40719509, -12.07624245, -1.62400484]), + 'current_gear_input': False, + 'focus_actor_dist': 1855.6512451171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -718.1585083 , -3197.17041016, 115.8132782 ]), + 'frame': 30832, + 'frame_number': 30832, + 'framesequence': 118460, + 'gaze_dir': array([ 0.99147034, -0.08215332, 0.10011292]), + 'gaze_origin': array([-2.98521137, 0.05884476, -0.09941101]), + 'gaze_valid': True, + 'gaze_vergence': 151.24508666992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99136353, -0.07191467, 0.1096344 ]), + 'left_gaze_origin': array([-2.89588642, 2.92030811, -0.0699463 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.626190185546875, + 'left_pupil_posn': array([ 0.18193626, -0.10913658]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99157715, -0.09239197, 0.09059143]), + 'right_gaze_origin': array([-3.07453632, -2.8026185 , -0.12887575]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.67449951171875, + 'right_pupil_posn': array([-0.29039222, -0.21463358]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04748069867491722, + 'throttle_input': 0.31348133087158203, + 'timestamp': 996.4507928788662, + 'timestamp_carla': 996450, + 'timestamp_device': 4149880, + 'timestamp_stream': 996.4507928788662, + 'transform': [array([1.47010064e+00, 1.47611179e+01, 2.69908895e-04]), + array([-0.06789891, -6.95410633, 0.02480309])]} +{'AngularVelocity': array([-5.44780213e-03, -2.16103345e-03, -7.78841422e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.017944881692528725, + 'FR_Wheel_Angle': -0.01794176548719406, + 'Location': array([ -1.01233101, -26.8090229 , 0.17042115]), + 'Rotation': array([-3.97038870e-02, -6.90068893e+01, 6.36302158e-02]), + 'Velocity': array([ 3.44652199e-06, 4.78001493e-06, -2.24639996e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.19919586, 13.48861313, -0.19199227]), + 'camera_rotation': array([ -6.35410404, -11.89328957, -1.62623954]), + 'current_gear_input': False, + 'focus_actor_dist': 1849.5654296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -712.75488281, -3197.16821289, 110.13349915]), + 'frame': 30833, + 'frame_number': 30833, + 'framesequence': 118464, + 'gaze_dir': array([ 0.99115753, -0.08351135, 0.10205078]), + 'gaze_origin': array([-2.97709584, 0.05958176, -0.10254975]), + 'gaze_valid': True, + 'gaze_vergence': 161.5033721923828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99130249, -0.07154846, 0.11044312]), + 'left_gaze_origin': array([-2.89096856, 2.92127395, -0.07264863]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6981658935546875, + 'left_pupil_posn': array([ 0.18022084, -0.10913658]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99101257, -0.09547424, 0.09365845]), + 'right_gaze_origin': array([-3.06322336, -2.80211043, -0.13245086]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.677276611328125, + 'right_pupil_posn': array([-0.29052854, -0.21461201]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.048780787736177444, + 'throttle_input': 0.31348133087158203, + 'timestamp': 996.4835913777351, + 'timestamp_carla': 996483, + 'timestamp_device': 4149913, + 'timestamp_stream': 996.4835913777351, + 'transform': [array([ 1.49529862e+00, 1.47053118e+01, -1.84726712e-04]), + array([-0.06787842, -7.00159645, 0.02572878])]} +{'AngularVelocity': array([-1.61119725e-03, -6.89084700e-04, -1.21802850e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.017944883555173874, + 'FR_Wheel_Angle': -0.01794176548719406, + 'Location': array([ -1.01232946, -26.80902863, 0.17041139]), + 'Rotation': array([-3.94579992e-02, -6.90068893e+01, 6.36297464e-02]), + 'Velocity': array([ 4.07964899e-06, 2.10360918e-06, -5.28343662e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.16078568, 13.49503517, -0.18331495]), + 'camera_rotation': array([ -6.36396027, -11.79456139, -1.76701105]), + 'current_gear_input': False, + 'focus_actor_dist': 1843.651123046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -709.4342041 , -3197.1706543 , 115.47026825]), + 'frame': 30834, + 'frame_number': 30834, + 'framesequence': 118468, + 'gaze_dir': array([ 0.99087524, -0.08646393, 0.1020813 ]), + 'gaze_origin': array([-2.97423482, 0.06035614, -0.10301972]), + 'gaze_valid': True, + 'gaze_vergence': 151.2671356201172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99111938, -0.07331848, 0.11090088]), + 'left_gaze_origin': array([-2.88900018, 2.92235422, -0.07228394]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6988677978515625, + 'left_pupil_posn': array([ 0.17805624, -0.10870183]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9906311 , -0.09960938, 0.09326172]), + 'right_gaze_origin': array([-3.0594697 , -2.80164194, -0.13375551]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6782379150390625, + 'right_pupil_posn': array([-0.29144335, -0.21461201]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.049549851566553116, + 'throttle_input': 0.3174487054347992, + 'timestamp': 996.518059976399, + 'timestamp_carla': 996517, + 'timestamp_device': 4149946, + 'timestamp_stream': 996.518059976399, + 'transform': [array([ 1.52314401e+00, 1.46448593e+01, -6.10122690e-04]), + array([-0.0677828 , -7.05430365, 0.02657209])]} +{'AngularVelocity': array([-4.97010129e-04, -2.02642623e-04, -1.24014568e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.017944883555173874, + 'FR_Wheel_Angle': -0.01794176548719406, + 'Location': array([ -1.01232886, -26.80902863, 0.17042044]), + 'Rotation': array([-3.94579992e-02, -6.90068893e+01, 6.36297464e-02]), + 'Velocity': array([5.11518647e-06, 1.30940782e-06, 3.84792338e-06]), + 'brake_input': 0.0, + 'camera_location': array([-8.14744282, 13.51301289, -0.19520196]), + 'camera_rotation': array([ -6.45290279, -11.69529438, -1.77076197]), + 'current_gear_input': False, + 'focus_actor_dist': 1839.2813720703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -712.39465332, -3197.17016602, 114.79969025]), + 'frame': 30835, + 'frame_number': 30835, + 'framesequence': 118472, + 'gaze_dir': array([ 0.99058533, -0.09061432, 0.10137939]), + 'gaze_origin': array([-2.97207665, 0.06156922, -0.10334321]), + 'gaze_valid': True, + 'gaze_vergence': 145.45645141601562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99066162, -0.07881165, 0.11112976]), + 'left_gaze_origin': array([-2.88959217, 2.92320132, -0.07136994]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6631927490234375, + 'left_pupil_posn': array([ 0.17650282, -0.10870183]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99050903, -0.10241699, 0.09162903]), + 'right_gaze_origin': array([-3.0545609 , -2.80006266, -0.13531648]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6614532470703125, + 'right_pupil_posn': array([-0.29442352, -0.21461201]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05015411972999573, + 'throttle_input': 0.3174487054347992, + 'timestamp': 996.550927978009, + 'timestamp_carla': 996550, + 'timestamp_device': 4149980, + 'timestamp_stream': 996.550927978009, + 'transform': [array([ 1.55120444e+00, 1.45853300e+01, -1.02216715e-03]), + array([-0.06764619, -7.10761595, 0.02742224])]} +{'AngularVelocity': array([-1.37662442e-04, -6.79894365e-05, -1.27733774e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.01232839, -26.80902863, 0.17041494]), + 'Rotation': array([-3.94579992e-02, -6.90068893e+01, 6.36297464e-02]), + 'Velocity': array([5.26842177e-06, 1.04604669e-06, 8.89923103e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.13282585, 13.5284338 , -0.2176895 ]), + 'camera_rotation': array([ -6.51319981, -11.62369728, -1.66128147]), + 'current_gear_input': False, + 'focus_actor_dist': 1835.018310546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -717.15960693, -3197.16796875, 110.56684875]), + 'frame': 30836, + 'frame_number': 30836, + 'framesequence': 118476, + 'gaze_dir': array([ 0.99021912, -0.09214783, 0.10353851]), + 'gaze_origin': array([-2.99456191, 0.06528931, -0.09450608]), + 'gaze_valid': True, + 'gaze_vergence': 138.86953735351562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99021912, -0.08047485, 0.11390686]), + 'left_gaze_origin': array([-2.93456268, 2.92968154, -0.05369568]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.51129150390625, + 'left_pupil_posn': array([ 0.17197275, -0.1044873 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99021912, -0.1038208 , 0.09317017]), + 'right_gaze_origin': array([-3.0545609 , -2.79910278, -0.13531648]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6402130126953125, + 'right_pupil_posn': array([-0.2956515 , -0.21357906]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.050245676189661026, + 'throttle_input': 0.3174487054347992, + 'timestamp': 996.584773376584, + 'timestamp_carla': 996584, + 'timestamp_device': 4150013, + 'timestamp_stream': 996.584773376584, + 'transform': [array([ 1.58125150e+00, 1.45221891e+01, -1.40279764e-03]), + array([-0.06746177, -7.16486216, 0.02819396])]} +{'AngularVelocity': array([-3.11484837e-05, 4.64322784e-06, -1.21580142e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.01232767, -26.80903053, 0.17042306]), + 'Rotation': array([-3.94579992e-02, -6.90068893e+01, 6.36297464e-02]), + 'Velocity': array([5.70802013e-06, 9.57812404e-07, 3.72953771e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.12175846, 13.56018639, -0.22490695]), + 'camera_rotation': array([ -6.600667 , -11.51578045, -1.65692163]), + 'current_gear_input': False, + 'focus_actor_dist': 1829.770263671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -717.67919922, -3197.16845703, 112.98171234]), + 'frame': 30837, + 'frame_number': 30837, + 'framesequence': 118480, + 'gaze_dir': array([ 0.99047852, -0.09238434, 0.10088348]), + 'gaze_origin': array([-2.99470472, 0.06589966, -0.09322587]), + 'gaze_valid': True, + 'gaze_vergence': 141.9418487548828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99046326, -0.08137512, 0.11106873]), + 'left_gaze_origin': array([-2.93447733, 2.92995167, -0.05382385]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5499725341796875, + 'left_pupil_posn': array([ 0.17197275, -0.10549152]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99049377, -0.10339355, 0.09069824]), + 'right_gaze_origin': array([-3.05493164, -2.79815245, -0.13262787]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6302947998046875, + 'right_pupil_posn': array([-0.29660112, -0.21279979]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.050245676189661026, + 'throttle_input': 0.3174487054347992, + 'timestamp': 996.6177544780076, + 'timestamp_carla': 996617, + 'timestamp_device': 4150046, + 'timestamp_stream': 996.6177544780076, + 'transform': [array([ 1.61161268e+00, 1.44588022e+01, -1.75989151e-03]), + array([-0.0672637 , -7.22284937, 0.0289358 ])]} +{'AngularVelocity': array([0.01277482, 0.00866606, 0.31899577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.017943905666470528, + 'FR_Wheel_Angle': -0.017940480262041092, + 'Location': array([ -1.01229036, -26.80926704, 0.17040105]), + 'Rotation': array([-3.91847938e-02, -6.89993896e+01, 6.36621639e-02]), + 'Velocity': array([-0.00158104, 0.00239254, -0.00028141]), + 'brake_input': 0.0, + 'camera_location': array([-8.09483433, 13.60134315, -0.22017804]), + 'camera_rotation': array([ -6.60833073, -11.4005785 , -1.59321821]), + 'current_gear_input': False, + 'focus_actor_dist': 1823.459228515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -714.6784668 , -3197.16796875, 105.44229889]), + 'frame': 30838, + 'frame_number': 30838, + 'framesequence': 118484, + 'gaze_dir': array([ 0.99001312, -0.09587097, 0.102005 ]), + 'gaze_origin': array([-2.99496698, 0.06629182, -0.09312897]), + 'gaze_valid': True, + 'gaze_vergence': 143.00686645507812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99020386, -0.08338928, 0.11184692]), + 'left_gaze_origin': array([-2.93447733, 2.92999125, -0.05382385]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5511016845703125, + 'left_pupil_posn': array([ 0.17022812, -0.10502899]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98982239, -0.10835266, 0.09216309]), + 'right_gaze_origin': array([-3.05545664, -2.79740763, -0.1324341 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.610137939453125, + 'right_pupil_posn': array([-0.29782701, -0.21245897]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.050245676189661026, + 'throttle_input': 0.3174487054347992, + 'timestamp': 996.6505171768367, + 'timestamp_carla': 996650, + 'timestamp_device': 4150080, + 'timestamp_stream': 996.6505171768367, + 'transform': [array([ 1.64290905e+00, 1.43939753e+01, -2.10018153e-03]), + array([-0.06707245, -7.28276062, 0.02964494])]} +{'AngularVelocity': array([0.00732062, 0.00279222, 0.00295797]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.017942631617188454, + 'FR_Wheel_Angle': -0.017941562458872795, + 'Location': array([ -1.01236129, -26.80912971, 0.17042401]), + 'Rotation': array([-3.94853204e-02, -6.89956970e+01, 6.36039153e-02]), + 'Velocity': array([-2.16090702e-03, 6.12922106e-03, 8.76760460e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.07440853, 13.66124725, -0.24084932]), + 'camera_rotation': array([ -6.6589694 , -11.23859596, -1.56337905]), + 'current_gear_input': False, + 'focus_actor_dist': 1818.432861328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -717.57385254, -3197.16748047, 107.44998169]), + 'frame': 30839, + 'frame_number': 30839, + 'framesequence': 118488, + 'gaze_dir': array([ 0.9908371 , -0.09540558, 0.09343719]), + 'gaze_origin': array([-3.05935001, 0.07398148, -0.07425766]), + 'gaze_valid': True, + 'gaze_vergence': 54.54442596435547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98977661, -0.08839417, 0.11183167]), + 'left_gaze_origin': array([-3.06376815, 2.94517064, -0.0163208 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5863189697265625, + 'left_pupil_posn': array([ 0.16324604, -0.11013174]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99189758, -0.10241699, 0.07504272]), + 'right_gaze_origin': array([-3.05493164, -2.79720783, -0.13219452]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.59503173828125, + 'right_pupil_posn': array([-0.29971963, -0.21218061]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05048372223973274, + 'throttle_input': 0.3174487054347992, + 'timestamp': 996.6838215775788, + 'timestamp_carla': 996683, + 'timestamp_device': 4150113, + 'timestamp_stream': 996.6838215775788, + 'transform': [array([ 1.67580557e+00, 1.43262339e+01, -2.39372253e-03]), + array([-0.06694268, -7.34590149, 0.03025248])]} +{'AngularVelocity': array([-0.00547351, -0.00193911, 0.00027316]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.023069866001605988, + 'FR_Wheel_Angle': -0.02306111715734005, + 'Location': array([ -1.01270187, -26.80815125, 0.17041875]), + 'Rotation': array([-3.94853204e-02, -6.89956970e+01, 6.36039153e-02]), + 'Velocity': array([-0.00151646, 0.00443566, 0.00023624]), + 'brake_input': 0.0, + 'camera_location': array([-8.0549612 , 13.73235703, -0.25380838]), + 'camera_rotation': array([ -6.7682662 , -11.01395893, -1.54256916]), + 'current_gear_input': False, + 'focus_actor_dist': 1811.4378662109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -711.19042969, -3197.16772461, 90.51155853]), + 'frame': 30840, + 'frame_number': 30840, + 'framesequence': 118493, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5094678401947021, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.07621169, -2.87910628, -0.21967469]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.051069676876068115, + 'throttle_input': 0.3174487054347992, + 'timestamp': 996.7172842770815, + 'timestamp_carla': 996717, + 'timestamp_device': 4150155, + 'timestamp_stream': 996.7172842770815, + 'transform': [array([ 1.71008050e+00, 1.42563038e+01, -2.64259335e-03]), + array([-0.06689487, -7.41187859, 0.03077188])]} +{'AngularVelocity': array([5.95301716e-03, 2.23870645e-03, 4.57764181e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02306387759745121, + 'FR_Wheel_Angle': -0.02306179329752922, + 'Location': array([ -1.01357317, -26.80577087, 0.17041628]), + 'Rotation': array([-3.94853204e-02, -6.89956970e+01, 6.36039153e-02]), + 'Velocity': array([-0.006665 , 0.01793065, 0.00034374]), + 'brake_input': 0.0, + 'camera_location': array([-8.03929424, 13.79765034, -0.24919249]), + 'camera_rotation': array([ -6.79584646, -10.8080492 , -1.43519104]), + 'current_gear_input': False, + 'focus_actor_dist': 994.0076293945312, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -412.63989258, -2427.10839844, 17.1984024 ]), + 'frame': 30841, + 'frame_number': 30841, + 'framesequence': 118497, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.051948610693216324, + 'throttle_input': 0.32538339495658875, + 'timestamp': 996.7502847760916, + 'timestamp_carla': 996750, + 'timestamp_device': 4150188, + 'timestamp_stream': 996.7502847760916, + 'transform': [array([ 1.74541664e+00, 1.41854124e+01, -2.87427893e-03]), + array([-0.06694951, -7.48014545, 0.031266 ])]} +{'AngularVelocity': array([0.0070095 , 0.00243361, 0.0017791 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1575888991355896, + 'FR_Wheel_Angle': -0.22375623881816864, + 'Location': array([ -1.01468122, -26.80278969, 0.17041612]), + 'Rotation': array([-3.94853204e-02, -6.89956970e+01, 6.36039153e-02]), + 'Velocity': array([-0.00844291, 0.02271443, -0.00036703]), + 'brake_input': 0.0, + 'camera_location': array([-8.01829624, 13.87512684, -0.24936987]), + 'camera_rotation': array([ -6.81490278, -10.51913071, -1.21926522]), + 'current_gear_input': False, + 'focus_actor_dist': 990.0972290039062, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -409.51776123, -2430.05810547, 17.19501495]), + 'frame': 30842, + 'frame_number': 30842, + 'framesequence': 118501, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.09901046007871628, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([-3.08791518, -3.00805974, -0.07412262]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05291909724473953, + 'throttle_input': 0.32538339495658875, + 'timestamp': 996.7835882790387, + 'timestamp_carla': 996783, + 'timestamp_device': 4150221, + 'timestamp_stream': 996.7835882790387, + 'transform': [array([ 1.78273070e+00, 1.41119223e+01, -3.08340066e-03]), + array([-0.06706563, -7.55251265, 0.03171054])]} +{'AngularVelocity': array([-0.1093499 , -0.04198821, 0.00018921]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.01065218, -26.81321144, 0.17034605]), + 'Rotation': array([-2.83247922e-02, -6.89956894e+01, 6.36311397e-02]), + 'Velocity': array([ 0.0937471 , -0.24433723, -0.00040429]), + 'brake_input': 0.0, + 'camera_location': array([-7.98787975, 13.98019218, -0.2406286 ]), + 'camera_rotation': array([ -6.76842356, -10.06303883, -1.03010321]), + 'current_gear_input': False, + 'focus_actor_dist': 987.40283203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -405.21380615, -2434.48461914, 17.19033813]), + 'frame': 30843, + 'frame_number': 30843, + 'framesequence': 118504, + 'gaze_dir': array([ 0., -0., 0.]), + 'gaze_origin': array([-3.01317692, -0.12666856, -0.06406632]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.3077539801597595, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([-2.94169784, 2.73105478, -0.04391175]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.5806843638420105, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.08465576, -2.98439193, -0.08422089]), + 'right_gaze_valid': True, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05363323166966438, + 'throttle_input': 0.32538339495658875, + 'timestamp': 996.8172244764864, + 'timestamp_carla': 996817, + 'timestamp_device': 4150246, + 'timestamp_stream': 996.8172244764864, + 'transform': [array([ 1.82196367e+00, 1.40357494e+01, -3.27049242e-03]), + array([-0.06720906, -7.62886047, 0.03210943])]} +{'AngularVelocity': array([ 0.10659832, 0.03593931, -0.05850054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1048784255981445, + 'FR_Wheel_Angle': -1.132108211517334, + 'Location': array([ -0.98969626, -26.86827278, 0.17036687]), + 'Rotation': array([-3.50115485e-02, -6.90028687e+01, 6.39619455e-02]), + 'Velocity': array([ 7.22111836e-02, -1.93402112e-01, -1.54132838e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.97803593, 14.09359932, -0.2503677 ]), + 'camera_rotation': array([-6.80472565, -9.50665665, -0.96029103]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ -268.16207886, -1467.37365723, 134.11073303]), + 'frame': 30844, + 'frame_number': 30844, + 'framesequence': 118508, + 'gaze_dir': array([ 0., -0., 0.]), + 'gaze_origin': array([-3.0120523 , -0.12203904, -0.07005234]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.5813822746276855, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0., -0., 0.]), + 'left_gaze_origin': array([-2.9401567 , 2.73418593, -0.05025483]), + 'left_gaze_valid': True, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.8358910083770752, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0., -0., 0.]), + 'right_gaze_origin': array([-3.0839479 , -2.97826409, -0.08984986]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.39166259765625, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05385296419262886, + 'throttle_input': 0.3293507397174835, + 'timestamp': 996.8497295789421, + 'timestamp_carla': 996849, + 'timestamp_device': 4150279, + 'timestamp_stream': 996.8497295789421, + 'transform': [array([ 1.86129248e+00, 1.39602032e+01, -3.46422195e-03]), + array([-0.06729102, -7.70564413, 0.03254075])]} +{'AngularVelocity': array([ 0.00558163, 0.00477057, -0.05000461]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.3418267965316772, + 'FR_Wheel_Angle': -1.3250190019607544, + 'Location': array([ -0.98071641, -26.89235306, 0.17042235]), + 'Rotation': array([-4.48606797e-02, -6.90135193e+01, 6.35880381e-02]), + 'Velocity': array([ 0.02309599, -0.06370878, 0.00022772]), + 'brake_input': 0.0, + 'camera_location': array([-7.9572773 , 14.20008087, -0.24527752]), + 'camera_rotation': array([-6.7625289 , -8.92289734, -0.85387844]), + 'current_gear_input': False, + 'focus_actor_dist': 100000.0, + 'focus_actor_name': 'None', + 'focus_actor_pt': array([ -267.98483276, -1474.39648438, 134.09866333]), + 'frame': 30845, + 'frame_number': 30845, + 'framesequence': 118512, + 'gaze_dir': array([0.98408508, 0.14672852, 0.09853363]), + 'gaze_origin': array([-2.99199986, -0.11526414, -0.08256532]), + 'gaze_valid': True, + 'gaze_vergence': 157.1637420654297, + 'handbrake_input': False, + 'left_eye_openness': 0.7091627717018127, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98197937, 0.16357422, 0.09448242]), + 'left_gaze_origin': array([-2.89755249, 2.74167967, -0.07104645]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.77630615234375, + 'left_pupil_posn': array([ 0.37981939, -0.10755765]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9283067584037781, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9861908 , 0.12988281, 0.10258484]), + 'right_gaze_origin': array([-3.08644724, -2.97220778, -0.09408417]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5439453125, + 'right_pupil_posn': array([-0.09182739, -0.20107377]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0538712777197361, + 'throttle_input': 0.3293507397174835, + 'timestamp': 996.8837121762335, + 'timestamp_carla': 996883, + 'timestamp_device': 4150313, + 'timestamp_stream': 996.8837121762335, + 'transform': [array([ 1.90347183e+00, 1.38793383e+01, -3.61188874e-03]), + array([-0.06732517, -7.78822851, 0.03285863])]} +{'AngularVelocity': array([-0.03490407, -0.01253865, 0.00010761]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.964746 , -26.9341011 , 0.17026636]), + 'Rotation': array([-2.80789062e-02, -6.90148468e+01, 6.34953752e-02]), + 'Velocity': array([ 1.39233947e-01, -3.63364249e-01, 2.81519897e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.95458603, 14.31051064, -0.2512399 ]), + 'camera_rotation': array([-6.67573786, -8.30860901, -0.79146218]), + 'current_gear_input': False, + 'focus_actor_dist': 3524.42138671875, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ -161.79008484, -5003.77880859, 79.43650818]), + 'frame': 30846, + 'frame_number': 30846, + 'framesequence': 118516, + 'gaze_dir': array([0.98422241, 0.14427948, 0.10028076]), + 'gaze_origin': array([-2.94445372, -0.11064453, -0.09993439]), + 'gaze_valid': True, + 'gaze_vergence': 117.36729431152344, + 'handbrake_input': False, + 'left_eye_openness': 0.8380004167556763, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9828186 , 0.16146851, 0.08934021]), + 'left_gaze_origin': array([-2.79933167, 2.74653482, -0.10561524]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8209991455078125, + 'left_pupil_posn': array([ 0.37277114, -0.10932958]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9677374958992004, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98562622, 0.12709045, 0.11122131]), + 'right_gaze_origin': array([-3.08957529, -2.96782374, -0.09425355]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5588226318359375, + 'right_pupil_posn': array([-0.0955646 , -0.20348132]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0538712777197361, + 'throttle_input': 0.3293507397174835, + 'timestamp': 996.9163091778755, + 'timestamp_carla': 996916, + 'timestamp_device': 4150346, + 'timestamp_stream': 996.9163091778755, + 'transform': [array([ 1.94494760e+00, 1.37998848e+01, -3.76527780e-03]), + array([-0.06733883, -7.86964369, 0.03321387])]} +{'AngularVelocity': array([3.66321504e-02, 1.44500565e-02, 3.81603822e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.93829089, -27.00315094, 0.17029428]), + 'Rotation': array([-3.19243036e-02, -6.90148544e+01, 6.35602698e-02]), + 'Velocity': array([ 0.15040946, -0.39257607, -0.0004965 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.96882439, 14.41686821, -0.2429173 ]), + 'camera_rotation': array([-6.73175192, -7.74357367, -0.70412779]), + 'current_gear_input': False, + 'focus_actor_dist': 3845.57373046875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -125.47172546, -5331.49023438, 86.04385376]), + 'frame': 30847, + 'frame_number': 30847, + 'framesequence': 118520, + 'gaze_dir': array([0.98338318, 0.14367676, 0.10876465]), + 'gaze_origin': array([-2.8736856 , -0.10446701, -0.12471086]), + 'gaze_valid': True, + 'gaze_vergence': 54.00122833251953, + 'handbrake_input': False, + 'left_eye_openness': 0.9166203737258911, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98432922, 0.15235901, 0.08874512]), + 'left_gaze_origin': array([-2.64102173, 2.75630975, -0.16016541]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.94830322265625, + 'left_pupil_posn': array([ 0.36480927, -0.11043382]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9769136905670166, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98243713, 0.13499451, 0.12878418]), + 'right_gaze_origin': array([-3.10634923, -2.96524382, -0.08925629]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.613739013671875, + 'right_pupil_posn': array([-0.10043877, -0.20347452]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0538712777197361, + 'throttle_input': 0.3293507397174835, + 'timestamp': 996.9496602788568, + 'timestamp_carla': 996949, + 'timestamp_device': 4150379, + 'timestamp_stream': 996.9496602788568, + 'transform': [array([ 1.98845232e+00, 1.37167120e+01, -3.90754687e-03]), + array([-0.06733883, -7.95528412, 0.03353339])]} +{'AngularVelocity': array([1.72562711e-02, 6.68705115e-03, 5.73502512e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.90957814, -27.07809448, 0.17026483]), + 'Rotation': array([-3.76548320e-02, -6.90148239e+01, 6.35877103e-02]), + 'Velocity': array([ 1.41060382e-01, -3.68158519e-01, 1.03201863e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.99494553, 14.51268959, -0.24362886]), + 'camera_rotation': array([-6.78442669, -7.22644377, -0.58376789]), + 'current_gear_input': False, + 'focus_actor_dist': 4006.90283203125, + 'focus_actor_name': 'SM_Shop_69', + 'focus_actor_pt': array([ -87.78565979, -5499.00097656, 113.37423706]), + 'frame': 30848, + 'frame_number': 30848, + 'framesequence': 118524, + 'gaze_dir': array([0.98714447, 0.12301636, 0.09967041]), + 'gaze_origin': array([-2.99987197, -0.10084534, -0.08396301]), + 'gaze_valid': True, + 'gaze_vergence': 70.05523681640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98762512, 0.13398743, 0.08131409]), + 'left_gaze_origin': array([-2.77490997, 2.75914168, -0.11512604]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.889801025390625, + 'left_pupil_posn': array([ 0.35835552, -0.10866117]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98666382, 0.11204529, 0.11802673]), + 'right_gaze_origin': array([-3.22483373, -2.96083236, -0.05279999]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5162200927734375, + 'right_pupil_posn': array([-0.1090039 , -0.20366538]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0538712777197361, + 'throttle_input': 0.3293507397174835, + 'timestamp': 996.9823734760284, + 'timestamp_carla': 996982, + 'timestamp_device': 4150413, + 'timestamp_stream': 996.9823734760284, + 'transform': [array([ 2.03209138e+00, 1.36332664e+01, -4.04176721e-03]), + array([-0.06735249, -8.04143238, 0.03384835])]} +{'AngularVelocity': array([4.16956935e-03, 1.63172535e-03, 7.88792313e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.87940305, -27.156847 , 0.17023675]), + 'Rotation': array([-3.98883037e-02, -6.90148239e+01, 6.35990798e-02]), + 'Velocity': array([ 0.12882712, -0.33620682, 0.00039844]), + 'brake_input': 0.0, + 'camera_location': array([-8.01976395, 14.5912981 , -0.24878493]), + 'camera_rotation': array([-6.84281778, -6.74318504, -0.54284066]), + 'current_gear_input': False, + 'focus_actor_dist': 3830.271728515625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -145.30116272, -5331.49023438, 72.69801331]), + 'frame': 30849, + 'frame_number': 30849, + 'framesequence': 118528, + 'gaze_dir': array([0.98732758, 0.11724854, 0.1055603 ]), + 'gaze_origin': array([-2.97108841, -0.09442292, -0.09216767]), + 'gaze_valid': True, + 'gaze_vergence': 115.3460922241211, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98731995, 0.12854004, 0.09306335]), + 'left_gaze_origin': array([-2.73743153, 2.76604176, -0.12639619]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7733154296875, + 'left_pupil_posn': array([ 0.35070896, -0.10895038]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98733521, 0.10595703, 0.11805725]), + 'right_gaze_origin': array([-3.20474577, -2.95488763, -0.05793915]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5065155029296875, + 'right_pupil_posn': array([-0.11499161, -0.19878781]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0538712777197361, + 'throttle_input': 0.3293507397174835, + 'timestamp': 997.0160638764501, + 'timestamp_carla': 997015, + 'timestamp_device': 4150446, + 'timestamp_stream': 997.0160638764501, + 'transform': [array([ 2.07794571e+00, 1.35454807e+01, -4.14586999e-03]), + array([-0.06738664, -8.1321888 , 0.03408956])]} +{'AngularVelocity': array([ 0.00035176, 0.00014924, -0.00034511]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.85173595, -27.22904778, 0.17022203]), + 'Rotation': array([-3.98883037e-02, -6.90148239e+01, 6.35990798e-02]), + 'Velocity': array([ 1.17445610e-01, -3.06477249e-01, -3.16238402e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.04407692, 14.66884327, -0.24809292]), + 'camera_rotation': array([-6.8426609 , -6.33680391, -0.48048875]), + 'current_gear_input': False, + 'focus_actor_dist': 3822.522705078125, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -141.15087891, -5331.49023438, 90.69447327]), + 'frame': 30850, + 'frame_number': 30850, + 'framesequence': 118532, + 'gaze_dir': array([0.98809814, 0.11386871, 0.10041046]), + 'gaze_origin': array([-2.95341659, -0.08926544, -0.09886475]), + 'gaze_valid': True, + 'gaze_vergence': 24.547136306762695, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99000549, 0.11854553, 0.07633972]), + 'left_gaze_origin': array([-2.70000315, 2.77234364, -0.13983765]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8468017578125, + 'left_pupil_posn': array([ 0.34670532, -0.10878098]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9861908 , 0.10919189, 0.1244812 ]), + 'right_gaze_origin': array([-3.20683002, -2.95087457, -0.05789185]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6049957275390625, + 'right_pupil_posn': array([-0.12154275, -0.20528615]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.053614918142557144, + 'throttle_input': 0.3333180844783783, + 'timestamp': 997.0500636771321, + 'timestamp_carla': 997049, + 'timestamp_device': 4150479, + 'timestamp_stream': 997.0500636771321, + 'transform': [array([ 2.12486863e+00, 1.34550543e+01, -4.22262168e-03]), + array([-0.06740031, -8.22533131, 0.03427951])]} +{'AngularVelocity': array([-0.00049542, -0.00014143, -0.02677333]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.82918316, -27.2878933 , 0.17019384]), + 'Rotation': array([-3.98883037e-02, -6.90148239e+01, 6.35990798e-02]), + 'Velocity': array([ 1.08177274e-01, -2.82267749e-01, -6.81114179e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.07367802, 14.70611191, -0.23894784]), + 'camera_rotation': array([-6.78974056, -5.99740267, -0.39951679]), + 'current_gear_input': False, + 'focus_actor_dist': 3815.084228515625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -132.59719849, -5331.49023438, 70.32304382]), + 'frame': 30851, + 'frame_number': 30851, + 'framesequence': 118536, + 'gaze_dir': array([0.98828888, 0.11394501, 0.09890747]), + 'gaze_origin': array([-2.95556879, -0.08789139, -0.09886169]), + 'gaze_valid': True, + 'gaze_vergence': 38.815616607666016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98970032, 0.12016296, 0.07765198]), + 'left_gaze_origin': array([-2.69076252, 2.77342844, -0.14382935]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8006591796875, + 'left_pupil_posn': array([ 0.34525239, -0.11107039]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98687744, 0.10772705, 0.12016296]), + 'right_gaze_origin': array([-3.2203753 , -2.94921112, -0.05389405]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5763702392578125, + 'right_pupil_posn': array([-0.12202036, -0.20473647]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05335856229066849, + 'throttle_input': 0.3333180844783783, + 'timestamp': 997.0835056789219, + 'timestamp_carla': 997083, + 'timestamp_device': 4150513, + 'timestamp_stream': 997.0835056789219, + 'transform': [array([ 2.17176604e+00, 1.33642550e+01, -4.29887744e-03]), + array([-0.06740713, -8.31868362, 0.03448206])]} +{'AngularVelocity': array([0.02953994, 0.00959836, 0.00017703]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.80711961, -27.34547234, 0.17020085]), + 'Rotation': array([-4.36995476e-02, -6.90166245e+01, 6.36497959e-02]), + 'Velocity': array([ 6.43104389e-02, -1.68262824e-01, -2.01089006e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.09945107, 14.72245979, -0.24456973]), + 'camera_rotation': array([-6.74644375, -5.74770451, -0.38425791]), + 'current_gear_input': False, + 'focus_actor_dist': 3997.756103515625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -108.04049683, -5521.52490234, 64.24069977]), + 'frame': 30852, + 'frame_number': 30852, + 'framesequence': 118540, + 'gaze_dir': array([0.98815155, 0.1129303 , 0.1018219 ]), + 'gaze_origin': array([-2.93908024, -0.08441315, -0.10398026]), + 'gaze_valid': True, + 'gaze_vergence': 52.167236328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98928833, 0.12026978, 0.08262634]), + 'left_gaze_origin': array([-2.68096781, 2.77455449, -0.14702912]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8000335693359375, + 'left_pupil_posn': array([ 0.34354341, -0.11096489]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98701477, 0.10559082, 0.12101746]), + 'right_gaze_origin': array([-3.19719243, -2.94338083, -0.0609314 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.55169677734375, + 'right_pupil_posn': array([-0.12606657, -0.20315516]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05264442786574364, + 'throttle_input': 0.33728542923927307, + 'timestamp': 997.1162256784737, + 'timestamp_carla': 997116, + 'timestamp_device': 4150546, + 'timestamp_stream': 997.1162256784737, + 'transform': [array([ 2.21825361e+00, 1.32736120e+01, -4.37282538e-03]), + array([-0.06730468, -8.41146374, 0.03469211])]} +{'AngularVelocity': array([-0.0094968 , -0.00363047, 0.00294838]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.79083043, -27.38806534, 0.17015192]), + 'Rotation': array([-4.06806059e-02, -6.90168457e+01, 6.36008754e-02]), + 'Velocity': array([ 5.75020239e-02, -1.50329977e-01, -5.46130286e-06]), + 'brake_input': 0.0, + 'camera_location': array([-8.13046455, 14.7410717 , -0.25446862]), + 'camera_rotation': array([-6.77709103, -5.51499462, -0.50285673]), + 'current_gear_input': False, + 'focus_actor_dist': 3976.04931640625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -102.10021973, -5508.07080078, 79.02140808]), + 'frame': 30853, + 'frame_number': 30853, + 'framesequence': 118544, + 'gaze_dir': array([0.9882431 , 0.11051178, 0.10394287]), + 'gaze_origin': array([-2.93093443, -0.08313675, -0.10612793]), + 'gaze_valid': True, + 'gaze_vergence': 45.692298889160156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98953247, 0.11552429, 0.08636475]), + 'left_gaze_origin': array([-2.6832397 , 2.77547026, -0.14582978]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.79949951171875, + 'left_pupil_posn': array([ 0.34294522, -0.11046672]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98695374, 0.10549927, 0.121521 ]), + 'right_gaze_origin': array([-3.17862844, -2.94174361, -0.06642609]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5219879150390625, + 'right_pupil_posn': array([-0.1289258 , -0.20183218]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05123447626829147, + 'throttle_input': 0.33728542923927307, + 'timestamp': 997.1492716781795, + 'timestamp_carla': 997149, + 'timestamp_device': 4150579, + 'timestamp_stream': 997.1492716781795, + 'transform': [array([ 2.26521969e+00, 1.31803608e+01, -4.41726670e-03]), + array([-0.06703147, -8.50538731, 0.03483905])]} +{'AngularVelocity': array([-0.003225 , -0.00124841, 0.00124518]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': -0.994631826877594, + 'Location': array([ -0.77981645, -27.41685677, 0.17013948]), + 'Rotation': array([-3.94579992e-02, -6.90168076e+01, 6.35978431e-02]), + 'Velocity': array([ 5.31288385e-02, -1.38795614e-01, -5.11842954e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.15541267, 14.72983074, -0.23984335]), + 'camera_rotation': array([-6.76243353, -5.31363106, -0.46939886]), + 'current_gear_input': False, + 'focus_actor_dist': 3966.93359375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -103.37606812, -5507.34423828, 86.18423462]), + 'frame': 30854, + 'frame_number': 30854, + 'framesequence': 118548, + 'gaze_dir': array([0.98867798, 0.10850525, 0.10227203]), + 'gaze_origin': array([-2.93782973, -0.08255845, -0.10246125]), + 'gaze_valid': True, + 'gaze_vergence': 71.63072967529297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98953247, 0.11491394, 0.08724976]), + 'left_gaze_origin': array([-2.68376637, 2.77676392, -0.14398958]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7765350341796875, + 'left_pupil_posn': array([ 0.34092438, -0.11066628]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98782349, 0.10209656, 0.11729431]), + 'right_gaze_origin': array([-3.1918931 , -2.94188094, -0.06093293]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4713897705078125, + 'right_pupil_posn': array([-0.12892371, -0.20027399]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.049513231962919235, + 'throttle_input': 0.33728542923927307, + 'timestamp': 997.1828923784196, + 'timestamp_carla': 997182, + 'timestamp_device': 4150613, + 'timestamp_stream': 997.1828923784196, + 'transform': [array([ 2.31237245e+00, 1.30838804e+01, -4.42707073e-03]), + array([-0.06662849, -8.59987259, 0.03491338])]} +{'AngularVelocity': array([0.04145285, 0.01135643, 0.52625436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0047621726989746, + 'FR_Wheel_Angle': -0.9951694011688232, + 'Location': array([ -0.77292204, -27.43534279, 0.1701425 ]), + 'Rotation': array([-4.18417379e-02, -6.90259705e+01, 6.36261553e-02]), + 'Velocity': array([ 1.51948174e-02, -4.07556482e-02, -9.01889798e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.15761662, 14.71010208, -0.23162976]), + 'camera_rotation': array([-6.69292927, -5.1762228 , -0.56319964]), + 'current_gear_input': False, + 'focus_actor_dist': 3961.369140625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -103.92640686, -5510.20654297, 80.19567871]), + 'frame': 30855, + 'frame_number': 30855, + 'framesequence': 118552, + 'gaze_dir': array([0.98866272, 0.10713196, 0.10358429]), + 'gaze_origin': array([-2.93620229, -0.0824028 , -0.10326996]), + 'gaze_valid': True, + 'gaze_vergence': 70.62907409667969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98953247, 0.11491394, 0.08726501]), + 'left_gaze_origin': array([-2.683043 , 2.77696562, -0.14474641]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.75860595703125, + 'left_pupil_posn': array([ 0.33983672, -0.11008668]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98779297, 0.09934998, 0.11990356]), + 'right_gaze_origin': array([-3.18936181, -2.94177103, -0.06179352]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.426788330078125, + 'right_pupil_posn': array([-0.12898374, -0.20025444]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04773705452680588, + 'throttle_input': 0.33728542923927307, + 'timestamp': 997.2162380777299, + 'timestamp_carla': 997216, + 'timestamp_device': 4150646, + 'timestamp_stream': 997.2162380777299, + 'transform': [array([ 2.35835147e+00, 1.29866161e+01, -4.41995589e-03]), + array([-0.06616404, -8.69216537, 0.03496387])]} +{'AngularVelocity': array([0.03590906, 0.00947474, 0.56071305]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0055533647537231, + 'FR_Wheel_Angle': -0.9959009885787964, + 'Location': array([ -0.76966012, -27.44408417, 0.17013299]), + 'Rotation': array([-4.11109067e-02, -6.90335312e+01, 6.35403022e-02]), + 'Velocity': array([-0.00077048, 0.00244525, -0.00012366]), + 'brake_input': 0.0, + 'camera_location': array([-8.16789722, 14.69555664, -0.22154668]), + 'camera_rotation': array([-6.63399839, -5.10282898, -0.78784937]), + 'current_gear_input': False, + 'focus_actor_dist': 3444.498046875, + 'focus_actor_name': 'BP_RepSpline20_12', + 'focus_actor_pt': array([ -128.06430054, -5002.87841797, 96.44348145]), + 'frame': 30856, + 'frame_number': 30856, + 'framesequence': 118556, + 'gaze_dir': array([0.98846436, 0.10641479, 0.1059494 ]), + 'gaze_origin': array([-2.9353745 , -0.08241425, -0.10354157]), + 'gaze_valid': True, + 'gaze_vergence': 68.96385192871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98937988, 0.11497498, 0.08879089]), + 'left_gaze_origin': array([-2.68100905, 2.77693796, -0.14495544]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6725921630859375, + 'left_pupil_posn': array([ 0.33931386, -0.10859191]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98754883, 0.09785461, 0.12310791]), + 'right_gaze_origin': array([-3.18973994, -2.9417665 , -0.06212769]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.426971435546875, + 'right_pupil_posn': array([-0.1289376, -0.1999718]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04652852192521095, + 'throttle_input': 0.33728542923927307, + 'timestamp': 997.2502433769405, + 'timestamp_carla': 997250, + 'timestamp_device': 4150679, + 'timestamp_stream': 997.2502433769405, + 'transform': [array([ 2.40462279e+00, 1.28858213e+01, -4.38484177e-03]), + array([-0.06582253, -8.78523922, 0.03495202])]} +{'AngularVelocity': array([0.04009392, 0.0105289 , 0.66189569]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0048322677612305, + 'FR_Wheel_Angle': -0.9945216774940491, + 'Location': array([ -0.76953948, -27.44445229, 0.17009915]), + 'Rotation': array([-4.02844548e-02, -6.90346603e+01, 6.35225102e-02]), + 'Velocity': array([-0.01227386, 0.03377303, -0.00066906]), + 'brake_input': 0.0, + 'camera_location': array([-8.17773151, 14.67003536, -0.2204949 ]), + 'camera_rotation': array([-6.62921715, -5.03523874, -0.78239781]), + 'current_gear_input': False, + 'focus_actor_dist': 3947.563232421875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -113.66996765, -5514.78173828, 105.95300293]), + 'frame': 30857, + 'frame_number': 30857, + 'framesequence': 118560, + 'gaze_dir': array([0.98854828, 0.10611725, 0.10558319]), + 'gaze_origin': array([-2.93450785, -0.08262101, -0.10362549]), + 'gaze_valid': True, + 'gaze_vergence': 76.66825103759766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98933411, 0.11483765, 0.08946228]), + 'left_gaze_origin': array([-2.67740798, 2.77655649, -0.14537659]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6170806884765625, + 'left_pupil_posn': array([ 0.33932447, -0.10859191]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98776245, 0.09739685, 0.1217041 ]), + 'right_gaze_origin': array([-3.19160771, -2.94179869, -0.06187439]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3872528076171875, + 'right_pupil_posn': array([-0.1289376 , -0.19986355]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.044862210750579834, + 'throttle_input': 0.33728542923927307, + 'timestamp': 997.2832365781069, + 'timestamp_carla': 997283, + 'timestamp_device': 4150713, + 'timestamp_stream': 997.2832365781069, + 'transform': [array([ 2.44886780e+00, 1.27864580e+01, -4.34696209e-03]), + array([-0.06556299, -8.8744154 , 0.03495423])]} +{'AngularVelocity': array([ 0.0378723 , 0.01513862, -0.30479649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.000264048576355, + 'FR_Wheel_Angle': -0.9909350872039795, + 'Location': array([ -0.78351116, -27.40615463, 0.17019254]), + 'Rotation': array([-4.79752459e-02, -6.90576782e+01, 6.31591454e-02]), + 'Velocity': array([-1.02011010e-01, 2.76630253e-01, -9.66072039e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.17968369, 14.66297626, -0.21749511]), + 'camera_rotation': array([-6.66046524, -5.00744247, -0.7806896 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3942.963134765625, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -116.78894043, -5519.53710938, 104.78892517]), + 'frame': 30858, + 'frame_number': 30858, + 'framesequence': 118564, + 'gaze_dir': array([0.98836517, 0.10497284, 0.10820007]), + 'gaze_origin': array([-2.93444085, -0.08411408, -0.10372543]), + 'gaze_valid': True, + 'gaze_vergence': 76.591064453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.989151 , 0.11499023, 0.09132385]), + 'left_gaze_origin': array([-2.67616725, 2.77458644, -0.1459015 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5616912841796875, + 'left_pupil_posn': array([ 0.33978045, -0.10737991]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98757935, 0.09495544, 0.12507629]), + 'right_gaze_origin': array([-3.19271421, -2.94281483, -0.06154938]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.36083984375, + 'right_pupil_posn': array([-0.12813294, -0.19912267]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.043195899575948715, + 'throttle_input': 0.33728542923927307, + 'timestamp': 997.3168874792755, + 'timestamp_carla': 997316, + 'timestamp_device': 4150746, + 'timestamp_stream': 997.3168874792755, + 'transform': [array([ 2.49314570e+00, 1.26835899e+01, -4.29710373e-03]), + array([-0.06530344, -8.96383095, 0.034923 ])]} +{'AngularVelocity': array([-0.00940465, -0.00351773, 0.63039565]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0387071371078491, + 'FR_Wheel_Angle': -1.1257370710372925, + 'Location': array([ -0.81303394, -27.32644272, 0.17022333]), + 'Rotation': array([-4.77566794e-02, -6.90395203e+01, 6.32846579e-02]), + 'Velocity': array([-1.52787402e-01, 4.13633972e-01, 2.92282086e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.19132519, 14.66369247, -0.21560034]), + 'camera_rotation': array([-6.71102953, -4.95586967, -0.82664782]), + 'current_gear_input': False, + 'focus_actor_dist': 3745.263427734375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -132.81063843, -5331.48974609, 113.98760223]), + 'frame': 30859, + 'frame_number': 30859, + 'framesequence': 118569, + 'gaze_dir': array([0.98804474, 0.10106659, 0.11433411]), + 'gaze_origin': array([-2.93824792, -0.08165818, -0.10194702]), + 'gaze_valid': True, + 'gaze_vergence': 69.36492156982422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98908997, 0.11166382, 0.09594727]), + 'left_gaze_origin': array([-2.68136764, 2.77703881, -0.14331666]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.540496826171875, + 'left_pupil_posn': array([ 0.33673573, -0.10398877]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98699951, 0.09046936, 0.13272095]), + 'right_gaze_origin': array([-3.19512796, -2.94035506, -0.06057739]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.2709503173828125, + 'right_pupil_posn': array([-0.13088262, -0.19704211]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041254922747612, + 'throttle_input': 0.2856946587562561, + 'timestamp': 997.3525316789746, + 'timestamp_carla': 997352, + 'timestamp_device': 4150788, + 'timestamp_stream': 997.3525316789746, + 'transform': [array([ 2.53848028e+00, 1.25732040e+01, -4.16088104e-03]), + array([-0.0650234 , -9.05558968, 0.03469946])]} +{'AngularVelocity': array([-0.02953218, -0.02596124, 1.70405078]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.442157030105591, + 'FR_Wheel_Angle': -3.8820693492889404, + 'Location': array([ -0.85270101, -27.21867371, 0.1702577 ]), + 'Rotation': array([-4.48333584e-02, -6.89761124e+01, 6.22397475e-02]), + 'Velocity': array([-0.17318809, 0.49468604, 0.00053486]), + 'brake_input': 0.0, + 'camera_location': array([-8.18752098, 14.66097069, -0.21722184]), + 'camera_rotation': array([-6.67409849, -4.85407972, -0.73331332]), + 'current_gear_input': False, + 'focus_actor_dist': 3735.13818359375, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -150.9743042 , -5331.49023438, 133.78469849]), + 'frame': 30860, + 'frame_number': 30860, + 'framesequence': 118572, + 'gaze_dir': array([ 0.99352264, -0.06253815, 0.09041595]), + 'gaze_origin': array([-2.99822855, 0.03892365, -0.09660416]), + 'gaze_valid': True, + 'gaze_vergence': 80.18671417236328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99336243, -0.0400238 , 0.10778809]), + 'left_gaze_origin': array([-2.9088335 , 2.89997125, -0.06923065]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.4662933349609375, + 'left_pupil_posn': array([ 0.19818413, -0.11676204]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99368286, -0.08505249, 0.07304382]), + 'right_gaze_origin': array([-3.08762383, -2.82212377, -0.12397768]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.43780517578125, + 'right_pupil_posn': array([-0.2659111 , -0.21401036]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03896603360772133, + 'throttle_input': 0.2063324898481369, + 'timestamp': 997.3847520761192, + 'timestamp_carla': 997384, + 'timestamp_device': 4150813, + 'timestamp_stream': 997.3847520761192, + 'transform': [array([ 2.57803392e+00, 1.24722738e+01, -3.93905630e-03]), + array([-0.0647297 , -9.13578606, 0.03436957])]} +{'AngularVelocity': array([-0.01194954, 0.00496325, 2.16420412]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.9041428565979, + 'FR_Wheel_Angle': -6.743978977203369, + 'Location': array([ -0.89154458, -27.10497475, 0.17026682]), + 'Rotation': array([-4.00727168e-02, -6.87918701e+01, 6.12682961e-02]), + 'Velocity': array([-1.56407356e-01, 4.89361912e-01, 3.92036425e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.2017374 , 14.65489674, -0.24552004]), + 'camera_rotation': array([-6.79848289, -4.69035864, -0.71431041]), + 'current_gear_input': False, + 'focus_actor_dist': 2426.27734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST40', + 'focus_actor_pt': array([ -586.71948242, -4012.67675781, 71.29032898]), + 'frame': 30861, + 'frame_number': 30861, + 'framesequence': 118576, + 'gaze_dir': array([ 0.9853363 , -0.14022827, 0.09472656]), + 'gaze_origin': array([-2.95160007, 0.09149781, -0.11137238]), + 'gaze_valid': True, + 'gaze_vergence': 117.0772705078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98704529, -0.12135315, 0.10491943]), + 'left_gaze_origin': array([-2.83333898, 2.94356251, -0.09242707]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3416290283203125, + 'left_pupil_posn': array([ 0.14252102, -0.11415446]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98362732, -0.15910339, 0.08453369]), + 'right_gaze_origin': array([-3.06986094, -2.76056671, -0.1303177 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5037841796875, + 'right_pupil_posn': array([-0.33678418, -0.21580064]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.036805324256420135, + 'throttle_input': 0.15078964829444885, + 'timestamp': 997.4158595763147, + 'timestamp_carla': 997415, + 'timestamp_device': 4150846, + 'timestamp_stream': 997.4158595763147, + 'transform': [array([ 2.61492276e+00, 1.23740292e+01, -3.57511523e-03]), + array([-0.06442234, -9.21068382, 0.03376117])]} +{'AngularVelocity': array([-1.06589021e-02, -2.20643613e-03, 2.85692501e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.573029518127441, + 'FR_Wheel_Angle': -8.991666793823242, + 'Location': array([ -0.930121 , -26.98524284, 0.1703269 ]), + 'Rotation': array([-4.27843034e-02, -6.84744339e+01, 6.03049323e-02]), + 'Velocity': array([-1.63195804e-01, 5.57336330e-01, 3.89389985e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.21606064, 14.64987659, -0.2826744 ]), + 'camera_rotation': array([-6.9694972 , -4.53456068, -0.83891594]), + 'current_gear_input': False, + 'focus_actor_dist': 1615.2935791015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -602.0567627 , -3197.50634766, 95.85923004]), + 'frame': 30862, + 'frame_number': 30862, + 'framesequence': 118580, + 'gaze_dir': array([ 0.9861908 , -0.13611603, 0.09242249]), + 'gaze_origin': array([-2.99934793, 0.09596863, -0.09266815]), + 'gaze_valid': True, + 'gaze_vergence': 135.93438720703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98757935, -0.12002563, 0.10131836]), + 'left_gaze_origin': array([-2.86147165, 2.94984293, -0.08024751]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2639312744140625, + 'left_pupil_posn': array([ 0.14093852, -0.11163127]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98480225, -0.15220642, 0.08352661]), + 'right_gaze_origin': array([-3.13722372, -2.75790572, -0.10508881]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4150543212890625, + 'right_pupil_posn': array([-0.33884549, -0.21286118]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03405865654349327, + 'throttle_input': 0.11506828665733337, + 'timestamp': 997.4491954781115, + 'timestamp_carla': 997449, + 'timestamp_device': 4150879, + 'timestamp_stream': 997.4491954781115, + 'transform': [array([ 2.65213323e+00, 1.22684755e+01, -2.93025956e-03]), + array([-0.06406034, -9.28633881, 0.03256564])]} +{'AngularVelocity': array([ 0.01348976, -0.01716417, 2.81638837]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.575345039367676, + 'FR_Wheel_Angle': -10.726009368896484, + 'Location': array([ -0.9736616 , -26.84314346, 0.17034623]), + 'Rotation': array([-3.93350571e-02, -6.79793777e+01, 6.19885139e-02]), + 'Velocity': array([-1.45289347e-01, 5.27006209e-01, 1.70345302e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.1990509 , 14.62545109, -0.26795509]), + 'camera_rotation': array([-6.80978012, -4.47008991, -0.9655934 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1610.910888671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -592.68530273, -3203.83569336, 86.93245697]), + 'frame': 30863, + 'frame_number': 30863, + 'framesequence': 118584, + 'gaze_dir': array([ 0.98578644, -0.14363098, 0.08598328]), + 'gaze_origin': array([-3.00735712, 0.0980156 , -0.0965973 ]), + 'gaze_valid': True, + 'gaze_vergence': 209.0583038330078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98786926, -0.13046265, 0.08416748]), + 'left_gaze_origin': array([-2.88340759, 2.95510578, -0.08125153]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2892913818359375, + 'left_pupil_posn': array([ 0.13596892, -0.11502886]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98370361, -0.15679932, 0.08779907]), + 'right_gaze_origin': array([-3.13130665, -2.75907469, -0.11194307]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3220672607421875, + 'right_pupil_posn': array([-0.34191269, -0.22228932]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03175146132707596, + 'throttle_input': 0.09126421064138412, + 'timestamp': 997.4839189760387, + 'timestamp_carla': 997483, + 'timestamp_device': 4150913, + 'timestamp_stream': 997.4839189760387, + 'transform': [array([ 2.68788958e+00, 1.21587925e+01, -1.95556646e-03]), + array([-0.06375981, -9.3591547 , 0.03071083])]} +{'AngularVelocity': array([-0.0484839 , 0.03444527, 2.95566463]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.860549926757812, + 'FR_Wheel_Angle': -12.469019889831543, + 'Location': array([ -1.01685119, -26.69786644, 0.17044885]), + 'Rotation': array([-4.74493206e-02, -6.73606110e+01, 5.89533821e-02]), + 'Velocity': array([-1.88738987e-01, 6.95395410e-01, 4.21929348e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.1977396 , 14.58056259, -0.25294632]), + 'camera_rotation': array([-6.68692541, -4.45307207, -1.03681195]), + 'current_gear_input': False, + 'focus_actor_dist': 1597.7225341796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -602.40368652, -3197.99780273, 80.89383698]), + 'frame': 30864, + 'frame_number': 30864, + 'framesequence': 118588, + 'gaze_dir': array([ 0.98728943, -0.13297272, 0.0853653 ]), + 'gaze_origin': array([-3.06294656, 0.10246812, -0.0747345 ]), + 'gaze_valid': True, + 'gaze_vergence': 91.24667358398438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98721313, -0.12442017, 0.09953308]), + 'left_gaze_origin': array([-3.00547028, 2.96404123, -0.03746338]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.22674560546875, + 'left_pupil_posn': array([ 0.13605809, -0.11420679]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98736572, -0.14152527, 0.07119751]), + 'right_gaze_origin': array([-3.1204226 , -2.75910497, -0.11200563]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.513153076171875, + 'right_pupil_posn': array([-0.33941388, -0.21519458]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029114659875631332, + 'throttle_input': 0.0476234070956707, + 'timestamp': 997.5165484771132, + 'timestamp_carla': 997516, + 'timestamp_device': 4150946, + 'timestamp_stream': 997.5165484771132, + 'transform': [array([ 2.71883845e+00, 1.20562305e+01, -8.46042589e-04]), + array([-0.06352758, -9.42226028, 0.02863124])]} +{'AngularVelocity': array([-0.0193819 , 0.04118603, 3.3744905 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.59253215789795, + 'FR_Wheel_Angle': -13.75133228302002, + 'Location': array([ -1.06339836, -26.5386219 , 0.17047316]), + 'Rotation': array([-4.30848300e-02, -6.65764313e+01, 6.11277893e-02]), + 'Velocity': array([-1.87211543e-01, 6.92605495e-01, 4.78372560e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.22690392, 14.53008556, -0.277024 ]), + 'camera_rotation': array([-6.93420553, -4.55707359, -1.15849137]), + 'current_gear_input': False, + 'focus_actor_dist': 1590.01025390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -585.80969238, -3203.92993164, 83.25505066]), + 'frame': 30865, + 'frame_number': 30865, + 'framesequence': 118592, + 'gaze_dir': array([ 0.98913574, -0.11992645, 0.08267212]), + 'gaze_origin': array([-3.16559529, 0.10683595, -0.04040451]), + 'gaze_valid': True, + 'gaze_vergence': 11.6412992477417, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98765564, -0.11885071, 0.10198975]), + 'left_gaze_origin': array([-3.19888926, 2.97477889, 0.02421417]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.1964111328125, + 'left_pupil_posn': array([ 0.13723755, -0.1118809 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99061584, -0.1210022 , 0.06335449]), + 'right_gaze_origin': array([-3.13230157, -2.76110697, -0.1050232 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.322052001953125, + 'right_pupil_posn': array([-0.3361522 , -0.21153498]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02693563885986805, + 'throttle_input': 0.0, + 'timestamp': 997.5494261756539, + 'timestamp_carla': 997549, + 'timestamp_device': 4150979, + 'timestamp_stream': 997.5494261756539, + 'transform': [array([2.74760818e+00, 1.19535398e+01, 3.44943983e-04]), + array([-0.06336366, -9.48100853, 0.02638271])]} +{'AngularVelocity': array([-3.72681348e-03, 3.95797044e-02, 4.02246237e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.43265151977539, + 'FR_Wheel_Angle': -15.096736907958984, + 'Location': array([ -1.11261857, -26.37175179, 0.17053065]), + 'Rotation': array([-4.48333584e-02, -6.56637802e+01, 6.03607744e-02]), + 'Velocity': array([-2.02712417e-01, 7.50924885e-01, 5.20925503e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.21917915, 14.4569149 , -0.27437663]), + 'camera_rotation': array([-6.9219389 , -4.77271938, -1.21391559]), + 'current_gear_input': False, + 'focus_actor_dist': 1572.67431640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -566.82556152, -3199.19189453, 72.45973206]), + 'frame': 30866, + 'frame_number': 30866, + 'framesequence': 118596, + 'gaze_dir': array([ 0.98926544, -0.12085724, 0.07965851]), + 'gaze_origin': array([-3.16927147, 0.10367051, -0.04197083]), + 'gaze_valid': True, + 'gaze_vergence': 20.38759422302246, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98735046, -0.1240387 , 0.09864807]), + 'left_gaze_origin': array([-3.22369862, 2.97390914, 0.03134918]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.1950836181640625, + 'left_pupil_posn': array([ 0.13918936, -0.11272001]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99118042, -0.11767578, 0.06066895]), + 'right_gaze_origin': array([-3.11484385, -2.76656818, -0.11529084]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3677215576171875, + 'right_pupil_posn': array([-0.33420187, -0.21619248]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.024793237447738647, + 'throttle_input': 0.0, + 'timestamp': 997.582892678678, + 'timestamp_carla': 997582, + 'timestamp_device': 4151013, + 'timestamp_stream': 997.582892678678, + 'transform': [array([2.77478385e+00, 1.18499718e+01, 1.65399548e-03]), + array([-0.0632817 , -9.53654289, 0.02389215])]} +{'AngularVelocity': array([-0.01478724, 0.04269874, 4.84388685]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.66020393371582, + 'FR_Wheel_Angle': -16.02937126159668, + 'Location': array([ -1.16818988, -26.18804359, 0.17061467]), + 'Rotation': array([-4.81801517e-02, -6.45737152e+01, 5.91527149e-02]), + 'Velocity': array([-2.35377148e-01, 8.48069072e-01, 1.94511405e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.20785141, 14.39437962, -0.24915896]), + 'camera_rotation': array([-6.72302294, -5.04891253, -1.38303638]), + 'current_gear_input': False, + 'focus_actor_dist': 1564.82080078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -574.25402832, -3199.28735352, 68.13296509]), + 'frame': 30867, + 'frame_number': 30867, + 'framesequence': 118600, + 'gaze_dir': array([ 0.98981476, -0.11968994, 0.07563782]), + 'gaze_origin': array([-3.17771697, 0.10168229, -0.03883667]), + 'gaze_valid': True, + 'gaze_vergence': 28.673423767089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98849487, -0.12194824, 0.08934021]), + 'left_gaze_origin': array([-3.20679474, 2.97245812, 0.02421417]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2004547119140625, + 'left_pupil_posn': array([ 0.14016104, -0.11388206]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99113464, -0.11743164, 0.06193542]), + 'right_gaze_origin': array([-3.1486392 , -2.76909351, -0.10188752]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3013763427734375, + 'right_pupil_posn': array([-0.33201867, -0.21697438]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02303536981344223, + 'throttle_input': 0.0, + 'timestamp': 997.6158933788538, + 'timestamp_carla': 997615, + 'timestamp_device': 4151046, + 'timestamp_stream': 997.6158933788538, + 'transform': [array([2.79936051e+00, 1.17490721e+01, 2.99821841e-03]), + array([-0.06331585, -9.58683777, 0.02133893])]} +{'AngularVelocity': array([-0.0194478 , 0.04242661, 5.49852943]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.85527801513672, + 'FR_Wheel_Angle': -16.779098510742188, + 'Location': array([ -1.23178756, -25.98570061, 0.17068246]), + 'Rotation': array([-4.84875105e-02, -6.32829704e+01, 5.95484488e-02]), + 'Velocity': array([-2.61493891e-01, 9.04448807e-01, 6.24609005e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.22607613, 14.32190037, -0.27707765]), + 'camera_rotation': array([-6.80695248, -5.24981308, -1.26230192]), + 'current_gear_input': False, + 'focus_actor_dist': 1558.777587890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -580.39624023, -3201.6784668 , 66.88142395]), + 'frame': 30868, + 'frame_number': 30868, + 'framesequence': 118604, + 'gaze_dir': array([ 0.98770905, -0.13077545, 0.08427429]), + 'gaze_origin': array([-3.03264022, 0.08906632, -0.08402787]), + 'gaze_valid': True, + 'gaze_vergence': 196.685546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98937988, -0.11671448, 0.08654785]), + 'left_gaze_origin': array([-2.91854858, 2.94967055, -0.06807404]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2143096923828125, + 'left_pupil_posn': array([ 0.14397192, -0.11461461]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98603821, -0.14483643, 0.08200073]), + 'right_gaze_origin': array([-3.14673185, -2.77153802, -0.0999817 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.2848052978515625, + 'right_pupil_posn': array([-0.32841492, -0.21621227]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02157048135995865, + 'throttle_input': 0.0, + 'timestamp': 997.649268578738, + 'timestamp_carla': 997649, + 'timestamp_device': 4151079, + 'timestamp_stream': 997.649268578738, + 'transform': [array([2.82232118e+00, 1.16483593e+01, 4.33197012e-03]), + array([-0.06345928, -9.63391685, 0.01879802])]} +{'AngularVelocity': array([-0.01099953, 0.04131008, 6.25676394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.666805267333984, + 'FR_Wheel_Angle': -17.516111373901367, + 'Location': array([ -1.30431831, -25.76856804, 0.17076612]), + 'Rotation': array([-5.02087176e-02, -6.18434525e+01, 5.93425743e-02]), + 'Velocity': array([-3.02613884e-01, 9.79403675e-01, 1.65042875e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.26537704, 14.26472855, -0.31871369]), + 'camera_rotation': array([-7.00950861, -5.51798916, -1.43746316]), + 'current_gear_input': False, + 'focus_actor_dist': 1548.59765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -602.13818359, -3196.87939453, 78.6295166 ]), + 'frame': 30869, + 'frame_number': 30869, + 'framesequence': 118608, + 'gaze_dir': array([ 0.97730255, -0.19345856, 0.0840683 ]), + 'gaze_origin': array([-3.08117914, 0.14134979, -0.06526718]), + 'gaze_valid': True, + 'gaze_vergence': 101.35315704345703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9786377 , -0.18057251, 0.09825134]), + 'left_gaze_origin': array([-3.00843668, 2.9991076 , -0.03144226]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2984466552734375, + 'left_pupil_posn': array([ 0.08972406, -0.11209309]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97596741, -0.2063446 , 0.06988525]), + 'right_gaze_origin': array([-3.1539216 , -2.71640801, -0.0990921 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.451141357421875, + 'right_pupil_posn': array([-0.38971215, -0.21349216]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01988586224615574, + 'throttle_input': 0.0, + 'timestamp': 997.6823343783617, + 'timestamp_carla': 997682, + 'timestamp_device': 4151113, + 'timestamp_stream': 997.6823343783617, + 'transform': [array([2.83081913e+00, 1.15523911e+01, 5.87099046e-03]), + array([-0.06073404, -9.65085411, 0.01589035])]} +{'AngularVelocity': array([-4.99501918e-03, 3.82439867e-02, 7.46741295e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.187286376953125, + 'FR_Wheel_Angle': -19.39765739440918, + 'Location': array([ -1.38548195, -25.53671837, 0.17086759]), + 'Rotation': array([-5.13561890e-02, -6.01744003e+01, 5.74212447e-02]), + 'Velocity': array([-3.30773771e-01, 1.04705667e+00, 4.42285527e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.28728294, 14.22221184, -0.3178671 ]), + 'camera_rotation': array([-7.01338148, -5.74326181, -1.61799216]), + 'current_gear_input': False, + 'focus_actor_dist': 1567.154052734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -711.32104492, -3197.16796875, 71.11004639]), + 'frame': 30870, + 'frame_number': 30870, + 'framesequence': 118613, + 'gaze_dir': array([ 0.97679138, -0.19526672, 0.08672333]), + 'gaze_origin': array([-3.08192682, 0.14639512, -0.0676384 ]), + 'gaze_valid': True, + 'gaze_vergence': 123.3332748413086, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97753906, -0.1864624 , 0.09809875]), + 'left_gaze_origin': array([-3.01128101, 3.00352025, -0.03401642]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.296112060546875, + 'left_pupil_posn': array([ 0.08751094, -0.11241293]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9760437 , -0.20407104, 0.0753479 ]), + 'right_gaze_origin': array([-3.15257263, -2.71073008, -0.10126038]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.477630615234375, + 'right_pupil_posn': array([-0.39582074, -0.21489096]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.018439285457134247, + 'throttle_input': 0.0, + 'timestamp': 997.7171159759164, + 'timestamp_carla': 997717, + 'timestamp_device': 4151154, + 'timestamp_stream': 997.7171159759164, + 'transform': [array([2.83283329e+00, 1.14540329e+01, 7.24737160e-03]), + array([-0.05905381, -9.65405273, 0.01326331])]} +{'AngularVelocity': array([-0.02019463, 0.05315544, 8.84136009]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.776371002197266, + 'FR_Wheel_Angle': -20.926593780517578, + 'Location': array([ -1.4618963 , -25.32476044, 0.1709633 ]), + 'Rotation': array([-5.33096232e-02, -5.84621048e+01, 5.58323637e-02]), + 'Velocity': array([-3.60489607e-01, 1.11390305e+00, 3.91721725e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.28845978, 14.17617989, -0.26466438]), + 'camera_rotation': array([-6.7043767 , -5.96922207, -1.5720408 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1560.170166015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -718.92114258, -3197.16796875, 74.39207458]), + 'frame': 30871, + 'frame_number': 30871, + 'framesequence': 118617, + 'gaze_dir': array([ 0.97566223, -0.19952393, 0.08903503]), + 'gaze_origin': array([-3.08036351, 0.14515992, -0.07117233]), + 'gaze_valid': True, + 'gaze_vergence': 69.96089172363281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9757843 , -0.19163513, 0.10542297]), + 'left_gaze_origin': array([-3.01151156, 3.00352025, -0.03518524]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2886199951171875, + 'left_pupil_posn': array([ 0.08635342, -0.11424589]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97554016, -0.20741272, 0.07264709]), + 'right_gaze_origin': array([-3.14921594, -2.71320057, -0.10715943]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.472900390625, + 'right_pupil_posn': array([-0.39596373, -0.21582425]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01679128408432007, + 'throttle_input': 0.0, + 'timestamp': 997.75388847664, + 'timestamp_carla': 997753, + 'timestamp_device': 4151188, + 'timestamp_stream': 997.75388847664, + 'transform': [array([2.83403134e+00, 1.13516464e+01, 8.35088734e-03]), + array([-0.05904015, -9.65539169, 0.01113185])]} +{'AngularVelocity': array([-0.040032 , 0.05925322, 9.60222054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.86441993713379, + 'FR_Wheel_Angle': -20.907936096191406, + 'Location': array([ -1.56393242, -25.06185913, 0.17108603]), + 'Rotation': array([-5.58436252e-02, -5.62046280e+01, 5.78313433e-02]), + 'Velocity': array([-4.25751537e-01, 1.17476809e+00, 3.97176744e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.30204964, 14.14177799, -0.2202832 ]), + 'camera_rotation': array([-6.45586729, -6.16936159, -1.73647261]), + 'current_gear_input': False, + 'focus_actor_dist': 1553.4459228515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -729.4072876 , -3197.16772461, 86.65975952]), + 'frame': 30872, + 'frame_number': 30872, + 'framesequence': 118620, + 'gaze_dir': array([ 0.97588348, -0.19836426, 0.08872223]), + 'gaze_origin': array([-3.07842493, 0.1451378 , -0.07355957]), + 'gaze_valid': True, + 'gaze_vergence': 66.95812225341797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97618103, -0.188797 , 0.10681152]), + 'left_gaze_origin': array([-3.01205921, 3.00376129, -0.03578186]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2863006591796875, + 'left_pupil_posn': array([ 0.08600605, -0.11543703]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97558594, -0.20793152, 0.07063293]), + 'right_gaze_origin': array([-3.14479089, -2.71348572, -0.11133729]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4125518798828125, + 'right_pupil_posn': array([-0.39475036, -0.21714914]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.015106662176549435, + 'throttle_input': 0.0, + 'timestamp': 997.7829885780811, + 'timestamp_carla': 997782, + 'timestamp_device': 4151213, + 'timestamp_stream': 997.7829885780811, + 'transform': [array([2.83227038e+00, 1.12721529e+01, 9.03224945e-03]), + array([-0.05962755, -9.65103245, 0.00980056])]} +{'AngularVelocity': array([-0.04886532, 0.05077861, 10.03999615]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.857391357421875, + 'FR_Wheel_Angle': -20.912139892578125, + 'Location': array([ -1.68213761, -24.79005051, 0.1712328 ]), + 'Rotation': array([ -0.05682717, -53.82659531, 0.05944608]), + 'Velocity': array([-4.91696239e-01, 1.19925416e+00, 6.30254741e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.30799294, 14.13189697, -0.19555716]), + 'camera_rotation': array([-6.25931501, -6.33349657, -1.95264661]), + 'current_gear_input': False, + 'focus_actor_dist': 1543.82080078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -730.32507324, -3197.16748047, 92.13176727]), + 'frame': 30873, + 'frame_number': 30873, + 'framesequence': 118624, + 'gaze_dir': array([ 0.97587585, -0.19855499, 0.08744049]), + 'gaze_origin': array([-3.07827306, 0.14602052, -0.07491989]), + 'gaze_valid': True, + 'gaze_vergence': 55.67494583129883, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97618103, -0.18766785, 0.10877991]), + 'left_gaze_origin': array([-3.01256895, 3.00414896, -0.03609162]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2924652099609375, + 'left_pupil_posn': array([ 0.08523083, -0.11733186]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97557068, -0.20944214, 0.06610107]), + 'right_gaze_origin': array([-3.1439774 , -2.7121079 , -0.11374818]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.442108154296875, + 'right_pupil_posn': array([-0.39532566, -0.21788681]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.013879818841814995, + 'throttle_input': 0.0, + 'timestamp': 997.815985776484, + 'timestamp_carla': 997815, + 'timestamp_device': 4151246, + 'timestamp_stream': 997.815985776484, + 'transform': [array([2.83315229e+00, 1.11825876e+01, 9.72948037e-03]), + array([-6.04471713e-02, -9.65182304e+00, 8.55202321e-03])]} +{'AngularVelocity': array([-7.93960914e-02, 1.81220530e-03, 1.05206966e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.795917510986328, + 'FR_Wheel_Angle': -21.55644989013672, + 'Location': array([ -1.81589758, -24.51464272, 0.17138135]), + 'Rotation': array([ -0.057558 , -51.3570137 , 0.05890836]), + 'Velocity': array([-5.31578004e-01, 1.18131244e+00, 4.75740409e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.3115015 , 14.10788345, -0.17074735]), + 'camera_rotation': array([-6.09786272, -6.51127052, -1.9403764 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1536.9732666015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -733.03198242, -3197.16748047, 94.33938599]), + 'frame': 30874, + 'frame_number': 30874, + 'framesequence': 118628, + 'gaze_dir': array([ 0.97580719, -0.20329285, 0.07859802]), + 'gaze_origin': array([-3.08175993, 0.14853822, -0.07547837]), + 'gaze_valid': True, + 'gaze_vergence': 131.94712829589844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97753906, -0.19085693, 0.08934021]), + 'left_gaze_origin': array([-3.01440144, 3.00869012, -0.04348145]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.2940216064453125, + 'left_pupil_posn': array([ 0.07994187, -0.1221478 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97407532, -0.21572876, 0.06785583]), + 'right_gaze_origin': array([-3.14911819, -2.71161366, -0.10747529]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3955078125, + 'right_pupil_posn': array([-0.3969115 , -0.22145641]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.012323373928666115, + 'throttle_input': 0.0, + 'timestamp': 997.8503296785057, + 'timestamp_carla': 997850, + 'timestamp_device': 4151279, + 'timestamp_stream': 997.8503296785057, + 'transform': [array([2.83359957e+00, 1.10907526e+01, 1.03217317e-02]), + array([-6.13282658e-02, -9.65170288e+00, 7.46691553e-03])]} +{'AngularVelocity': array([-0.02628312, -0.01174152, 7.5949111 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.98896598815918, + 'FR_Wheel_Angle': -21.671947479248047, + 'Location': array([ -1.93411112, -24.29128075, 0.17144048]), + 'Rotation': array([-4.39727567e-02, -4.92576523e+01, 6.78810999e-02]), + 'Velocity': array([-4.06505853e-01, 8.27012777e-01, 7.35387788e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.32032204, 14.07669449, -0.16191192]), + 'camera_rotation': array([-6.08171606, -6.76446629, -1.87766826]), + 'current_gear_input': False, + 'focus_actor_dist': 1531.6192626953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -742.4317627 , -3197.16796875, 85.08587646]), + 'frame': 30875, + 'frame_number': 30875, + 'framesequence': 118632, + 'gaze_dir': array([ 0.97658539, -0.20078278, 0.07497406]), + 'gaze_origin': array([-3.08078313, 0.1551674 , -0.07229004]), + 'gaze_valid': True, + 'gaze_vergence': 65.51312255859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9768219 , -0.19343567, 0.09153748]), + 'left_gaze_origin': array([-3.01378036, 3.01525283, -0.04274597]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3131256103515625, + 'left_pupil_posn': array([ 0.07821143, -0.124663 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97634888, -0.20812988, 0.05841064]), + 'right_gaze_origin': array([-3.14778614, -2.70491791, -0.10183412]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3946533203125, + 'right_pupil_posn': array([-0.40238118, -0.21659076]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.010510575026273727, + 'throttle_input': 0.0, + 'timestamp': 997.8819361776114, + 'timestamp_carla': 997881, + 'timestamp_device': 4151313, + 'timestamp_stream': 997.8819361776114, + 'transform': [array([2.83426499e+00, 1.10073366e+01, 1.07969278e-02]), + array([-6.20590970e-02, -9.65209770e+00, 6.63543865e-03])]} +{'AngularVelocity': array([ 0.02790918, -0.01007305, 5.17432833]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.410696029663086, + 'FR_Wheel_Angle': -22.05596923828125, + 'Location': array([ -2.02562213, -24.13068962, 0.17151025]), + 'Rotation': array([-4.36107554e-02, -4.77103958e+01, 6.46471307e-02]), + 'Velocity': array([-2.86123574e-01, 5.47142804e-01, -1.09710694e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.33397865, 14.03539085, -0.1535611 ]), + 'camera_rotation': array([-6.0581522 , -7.17701054, -2.31387854]), + 'current_gear_input': False, + 'focus_actor_dist': 1522.9527587890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -742.09069824, -3197.16772461, 80.63038635]), + 'frame': 30876, + 'frame_number': 30876, + 'framesequence': 118636, + 'gaze_dir': array([ 0.97818756, -0.19273376, 0.07411194]), + 'gaze_origin': array([-3.08086324, 0.15718003, -0.06951981]), + 'gaze_valid': True, + 'gaze_vergence': 55.436248779296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97848511, -0.18345642, 0.09422302]), + 'left_gaze_origin': array([-3.01528645, 3.0184052 , -0.03757782]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.284332275390625, + 'left_pupil_posn': array([ 0.07824671, -0.12291098]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97789001, -0.20201111, 0.05400085]), + 'right_gaze_origin': array([-3.14644027, -2.7040453 , -0.1014618 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.46124267578125, + 'right_pupil_posn': array([-0.39928609, -0.21507955]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00875270925462246, + 'throttle_input': 0.0, + 'timestamp': 997.9169072769582, + 'timestamp_carla': 997916, + 'timestamp_device': 4151346, + 'timestamp_stream': 997.9169072769582, + 'transform': [array([ 2.83458805, 10.91640091, 0.01119474]), + array([-6.27626032e-02, -9.65175819e+00, 5.89217478e-03])]} +{'AngularVelocity': array([ 2.68260520e-02, -1.71438826e-03, 3.63840866e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.036216735839844, + 'FR_Wheel_Angle': -22.353439331054688, + 'Location': array([ -2.08501005, -24.03058624, 0.17163019]), + 'Rotation': array([ -0.04757227, -46.71111298, 0.05925515]), + 'Velocity': array([-2.01055393e-01, 3.74025106e-01, 2.24781033e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.3673954 , 13.90563774, -0.09976748]), + 'camera_rotation': array([-5.74651098, -8.2255106 , -3.09799266]), + 'current_gear_input': False, + 'focus_actor_dist': 1514.041748046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -738.55786133, -3197.16772461, 78.15053558]), + 'frame': 30877, + 'frame_number': 30877, + 'framesequence': 118640, + 'gaze_dir': array([ 0.98036957, -0.17880249, 0.08138275]), + 'gaze_origin': array([-3.06528163, 0.1439438 , -0.08303833]), + 'gaze_valid': True, + 'gaze_vergence': 63.427040100097656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98013306, -0.17318726, 0.09661865]), + 'left_gaze_origin': array([-3.02582717, 3.00651097, -0.03959503]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.322418212890625, + 'left_pupil_posn': array([ 0.09248912, -0.12188864]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98060608, -0.18441772, 0.06614685]), + 'right_gaze_origin': array([-3.10473657, -2.71862364, -0.12648164]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.46038818359375, + 'right_pupil_posn': array([-0.38498735, -0.22319317]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0070497761480510235, + 'throttle_input': 0.0, + 'timestamp': 997.949708878994, + 'timestamp_carla': 997949, + 'timestamp_device': 4151379, + 'timestamp_stream': 997.949708878994, + 'transform': [array([ 2.83513522, 10.83226299, 0.01151435]), + array([-6.33226782e-02, -9.65190983e+00, 5.33898873e-03])]} +{'AngularVelocity': array([ 0.06650811, -0.05882482, 2.45493674]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.427492141723633, + 'FR_Wheel_Angle': -22.653806686401367, + 'Location': array([ -2.12441182, -23.96541214, 0.17167349]), + 'Rotation': array([ -0.04906807, -46.0470314 , 0.05648367]), + 'Velocity': array([-0.10213587, 0.20983873, 0.00028534]), + 'brake_input': 0.0, + 'camera_location': array([-8.37702370e+00, 1.36945143e+01, -1.12563614e-02]), + 'camera_rotation': array([-5.25593281, -9.65493679, -3.39173055]), + 'current_gear_input': False, + 'focus_actor_dist': 1506.620849609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -744.05871582, -3197.16748047, 94.14395142]), + 'frame': 30878, + 'frame_number': 30878, + 'framesequence': 118644, + 'gaze_dir': array([ 0.98349762, -0.1667099 , 0.06754303]), + 'gaze_origin': array([-3.10757685, 0.13170929, -0.07624588]), + 'gaze_valid': True, + 'gaze_vergence': 50.18752670288086, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98324585, -0.16099548, 0.08529663]), + 'left_gaze_origin': array([-3.1182878 , 2.99677896, -0.01490936]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3250579833984375, + 'left_pupil_posn': array([ 0.10371542, -0.12848318]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98374939, -0.17242432, 0.04978943]), + 'right_gaze_origin': array([-3.09686613, -2.73336053, -0.13758241]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.507476806640625, + 'right_pupil_posn': array([-0.37048608, -0.23306072]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.005639820825308561, + 'throttle_input': 0.0, + 'timestamp': 997.9824548773468, + 'timestamp_carla': 997982, + 'timestamp_device': 4151413, + 'timestamp_stream': 997.9824548773468, + 'transform': [array([ 2.83562088, 10.7494297 , 0.01175903]), + array([-6.37803003e-02, -9.65197086e+00, 4.92396858e-03])]} +{'AngularVelocity': array([ 0.08792605, -0.05690092, 1.38415146]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.87000846862793, + 'FR_Wheel_Angle': -22.919782638549805, + 'Location': array([ -2.14267635, -23.93499756, 0.17171164]), + 'Rotation': array([ -0.05218264, -45.72950363, 0.05350939]), + 'Velocity': array([-0.0431167 , 0.09993613, 0.00016151]), + 'brake_input': 0.0, + 'camera_location': array([-8.39607048, 13.4561739 , 0.05253715]), + 'camera_rotation': array([ -4.90693045, -11.1404829 , -3.47283745]), + 'current_gear_input': False, + 'focus_actor_dist': 1504.30810546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -760.79626465, -3197.16748047, 85.48432159]), + 'frame': 30879, + 'frame_number': 30879, + 'framesequence': 118648, + 'gaze_dir': array([ 0.98690033, -0.14868164, 0.05921173]), + 'gaze_origin': array([-3.13557673, 0.11366653, -0.07344742]), + 'gaze_valid': True, + 'gaze_vergence': 1.6697450876235962, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.985672 , -0.14888 , 0.07923889]), + 'left_gaze_origin': array([-3.14311695, 2.98119664, -0.01199799]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3732147216796875, + 'left_pupil_posn': array([ 0.12290335, -0.13464808]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98812866, -0.14848328, 0.03918457]), + 'right_gaze_origin': array([-3.1280365 , -2.75386357, -0.13489686]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5022125244140625, + 'right_pupil_posn': array([-0.3523891 , -0.23966861]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0049073765985667706, + 'throttle_input': 0.0, + 'timestamp': 998.0161339789629, + 'timestamp_carla': 998016, + 'timestamp_device': 4151446, + 'timestamp_stream': 998.0161339789629, + 'transform': [array([ 2.83604598, 10.6654377 , 0.0119526 ]), + array([-6.41627908e-02, -9.65187836e+00, 4.59010154e-03])]} +{'AngularVelocity': array([ 0.08073049, -0.05761877, 1.11373425]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.923978805541992, + 'FR_Wheel_Angle': -22.925376892089844, + 'Location': array([ -2.15258503, -23.91865921, 0.17175531]), + 'Rotation': array([ -0.05690913, -45.5579071 , 0.04944313]), + 'Velocity': array([-2.98372377e-02, 7.42208809e-02, 3.17573540e-06]), + 'brake_input': 0.0, + 'camera_location': array([-8.45185661, 13.27205563, 0.04028936]), + 'camera_rotation': array([ -4.90764761, -12.45043945, -3.57898021]), + 'current_gear_input': False, + 'focus_actor_dist': 1499.47412109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -769.58435059, -3197.16796875, 83.10112762]), + 'frame': 30880, + 'frame_number': 30880, + 'framesequence': 118652, + 'gaze_dir': array([ 0.98603821, -0.15272522, 0.06511688]), + 'gaze_origin': array([-2.97886205, 0.0885788 , -0.12243729]), + 'gaze_valid': True, + 'gaze_vergence': 169.8851318359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98672485, -0.14466858, 0.07359314]), + 'left_gaze_origin': array([-2.86136341, 2.94898248, -0.09910432]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.38531494140625, + 'left_pupil_posn': array([ 0.1389091 , -0.13401473]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98535156, -0.16078186, 0.05664062]), + 'right_gaze_origin': array([-3.09636092, -2.77182484, -0.14577027]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.466766357421875, + 'right_pupil_posn': array([-0.33814692, -0.24284995]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.0497474782169, + 'timestamp_carla': 998049, + 'timestamp_device': 4151479, + 'timestamp_stream': 998.0497474782169, + 'transform': [array([ 2.83647633, 10.58278179, 0.01209133]), + array([-6.44838139e-02, -9.65182209e+00, 4.36681230e-03])]} +{'AngularVelocity': array([1.73358306e-01, 1.54449648e-04, 3.76087832e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.74430274963379, + 'FR_Wheel_Angle': -22.801618576049805, + 'Location': array([ -2.17049789, -23.88988686, 0.17185144]), + 'Rotation': array([-7.01938495e-02, -4.52794037e+01, 3.77737172e-02]), + 'Velocity': array([-0.17943038, 0.31630555, 0.00034251]), + 'brake_input': 0.0, + 'camera_location': array([-8.52085972e+00, 1.31430864e+01, -1.25908200e-02]), + 'camera_rotation': array([ -5.14756489, -13.43079662, -3.46577692]), + 'current_gear_input': False, + 'focus_actor_dist': 1505.3482666015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -810.36413574, -3197.14746094, 91.00286865]), + 'frame': 30881, + 'frame_number': 30881, + 'framesequence': 118656, + 'gaze_dir': array([ 0.98717499, -0.14505005, 0.06515503]), + 'gaze_origin': array([-2.94996881, 0.0737587 , -0.12976074]), + 'gaze_valid': True, + 'gaze_vergence': 67.61369323730469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98693848, -0.14093018, 0.07792664]), + 'left_gaze_origin': array([-2.85874796, 2.93513823, -0.09739991]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.480621337890625, + 'left_pupil_posn': array([ 0.15212166, -0.13361776]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9874115 , -0.14916992, 0.05238342]), + 'right_gaze_origin': array([-3.04118967, -2.78762078, -0.16212159]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4606170654296875, + 'right_pupil_posn': array([-0.32534814, -0.24170291]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.0839348770678, + 'timestamp_carla': 998083, + 'timestamp_device': 4151513, + 'timestamp_stream': 998.0839348770678, + 'transform': [array([ 2.83684373, 10.49992085, 0.01218431]), + array([-6.47433624e-02, -9.65164185e+00, 4.22658212e-03])]} +{'AngularVelocity': array([-0.01355458, -0.05764886, 5.89068651]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.649599075317383, + 'FR_Wheel_Angle': -22.748716354370117, + 'Location': array([ -2.2488215, -23.7687664, 0.1719436]), + 'Rotation': array([-7.30830207e-02, -4.39969635e+01, 3.61245275e-02]), + 'Velocity': array([-3.01761270e-01, 5.38699269e-01, -1.68132774e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.56348038, 13.07219505, -0.05947941]), + 'camera_rotation': array([ -5.41601181, -14.06169891, -3.19601536]), + 'current_gear_input': False, + 'focus_actor_dist': 1502.680419921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -822.36157227, -3197.67553711, 85.89111328]), + 'frame': 30882, + 'frame_number': 30882, + 'framesequence': 118660, + 'gaze_dir': array([ 0.98558807, -0.13555145, 0.09928894]), + 'gaze_origin': array([-3.03484201, 0.07532959, -0.08567505]), + 'gaze_valid': True, + 'gaze_vergence': 110.88177490234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98625183, -0.1212616 , 0.11222839]), + 'left_gaze_origin': array([-2.92208886, 2.93598485, -0.0617981 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.4095611572265625, + 'left_pupil_posn': array([ 0.15160918, -0.11006713]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98492432, -0.14984131, 0.08634949]), + 'right_gaze_origin': array([-3.14759541, -2.78532577, -0.10955201]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4685211181640625, + 'right_pupil_posn': array([-0.32047004, -0.21437061]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.1172105781734, + 'timestamp_carla': 998117, + 'timestamp_device': 4151546, + 'timestamp_stream': 998.1172105781734, + 'transform': [array([ 2.8373456 , 10.42037296, 0.01225892]), + array([-6.49482682e-02, -9.65175819e+00, 4.13852138e-03])]} +{'AngularVelocity': array([ 0.02357677, -0.03999519, 5.90087652]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.63455581665039, + 'FR_Wheel_Angle': -22.731122970581055, + 'Location': array([ -2.31597257, -23.66802406, 0.17199537]), + 'Rotation': array([-6.68948665e-02, -4.29127884e+01, 4.21901383e-02]), + 'Velocity': array([-0.32167837, 0.54148901, 0.00082499]), + 'brake_input': 0.0, + 'camera_location': array([-8.57670689, 13.04861546, -0.09430426]), + 'camera_rotation': array([ -5.62423706, -14.27801704, -3.03872299]), + 'current_gear_input': False, + 'focus_actor_dist': 1495.0711669921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -823.95294189, -3197.85546875, 132.0214386 ]), + 'frame': 30883, + 'frame_number': 30883, + 'framesequence': 118664, + 'gaze_dir': array([ 0.98603058, -0.13454437, 0.09670258]), + 'gaze_origin': array([-3.03891158, 0.07589264, -0.07997894]), + 'gaze_valid': True, + 'gaze_vergence': 120.34270477294922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9864502 , -0.12286377, 0.10868835]), + 'left_gaze_origin': array([-2.92978525, 2.93540835, -0.05581208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3813934326171875, + 'left_pupil_posn': array([ 0.15327823, -0.10795093]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98561096, -0.14622498, 0.0847168 ]), + 'right_gaze_origin': array([-3.14803791, -2.78362298, -0.10414582]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4335174560546875, + 'right_pupil_posn': array([-0.32219714, -0.21194768]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.1489013768733, + 'timestamp_carla': 998148, + 'timestamp_device': 4151579, + 'timestamp_stream': 998.1489013768733, + 'transform': [array([ 2.83786559, 10.34562874, 0.01231419]), + array([-6.50985315e-02, -9.65196991e+00, 4.10379842e-03])]} +{'AngularVelocity': array([ 0.07838537, -0.03663633, 8.19235229]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.517038345336914, + 'FR_Wheel_Angle': -22.656591415405273, + 'Location': array([ -2.42940068, -23.50837326, 0.17215452]), + 'Rotation': array([-7.39094764e-02, -4.11758461e+01, 3.71092409e-02]), + 'Velocity': array([-4.78410095e-01, 7.39776075e-01, 3.74479278e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.60260391, 13.05374432, -0.09084436]), + 'camera_rotation': array([ -5.70753098, -14.29913712, -3.07148528]), + 'current_gear_input': False, + 'focus_actor_dist': 1487.274169921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -824.2824707 , -3197.20800781, 123.43402863]), + 'frame': 30884, + 'frame_number': 30884, + 'framesequence': 118668, + 'gaze_dir': array([ 0.98547363, -0.13686371, 0.09855652]), + 'gaze_origin': array([-3.02705097, 0.07662202, -0.08366318]), + 'gaze_valid': True, + 'gaze_vergence': 91.742431640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98558044, -0.12507629, 0.11383057]), + 'left_gaze_origin': array([-2.93016982, 2.93697524, -0.05540162]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.30426025390625, + 'left_pupil_posn': array([ 0.15139604, -0.10826945]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98536682, -0.14865112, 0.08328247]), + 'right_gaze_origin': array([-3.12393188, -2.78373122, -0.11192475]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4381256103515625, + 'right_pupil_posn': array([-0.32264817, -0.2107929 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.1828546784818, + 'timestamp_carla': 998182, + 'timestamp_device': 4151613, + 'timestamp_stream': 998.1828546784818, + 'transform': [array([ 2.83824086, 10.26669407, 0.01233461]), + array([-6.52419627e-02, -9.65184402e+00, 4.09717392e-03])]} +{'AngularVelocity': array([-2.97885612e-02, -1.43334328e-03, 9.64989567e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.453445434570312, + 'FR_Wheel_Angle': -22.6163387298584, + 'Location': array([ -2.54221249, -23.35974884, 0.17228791]), + 'Rotation': array([-7.47086033e-02, -3.95323219e+01, 3.84817570e-02]), + 'Velocity': array([-5.76057017e-01, 8.17298472e-01, 5.17816516e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.59092617, 13.08293629, -0.07207633]), + 'camera_rotation': array([ -5.61605453, -14.09521866, -3.1596694 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1480.9522705078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -825.81542969, -3197.21044922, 123.86973572]), + 'frame': 30885, + 'frame_number': 30885, + 'framesequence': 118672, + 'gaze_dir': array([ 0.98712921, -0.13037109, 0.09141541]), + 'gaze_origin': array([-3.17117381, 0.09540787, -0.04044342]), + 'gaze_valid': True, + 'gaze_vergence': 13.188582420349121, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98562622, -0.13172913, 0.10571289]), + 'left_gaze_origin': array([-3.22513437, 2.96538854, 0.03409882]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.345489501953125, + 'left_pupil_posn': array([ 0.141011 , -0.10551131]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9886322 , -0.12901306, 0.07711792]), + 'right_gaze_origin': array([-3.11721349, -2.77457285, -0.11498566]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5070953369140625, + 'right_pupil_posn': array([-0.33130383, -0.21464777]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.2157969772816, + 'timestamp_carla': 998215, + 'timestamp_device': 4151646, + 'timestamp_stream': 998.2157969772816, + 'transform': [array([ 2.83868337, 10.19116688, 0.01235224]), + array([-6.53444156e-02, -9.65187931e+00, 4.11572726e-03])]} +{'AngularVelocity': array([-7.66033446e-03, 6.68395078e-03, 1.05744381e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.393770217895508, + 'FR_Wheel_Angle': -22.610258102416992, + 'Location': array([ -2.69588566, -23.17080688, 0.17245886]), + 'Rotation': array([ -0.07397778, -37.38124084, 0.03880098]), + 'Velocity': array([-6.76259577e-01, 8.86860132e-01, 5.41839574e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.56313705, 13.11767483, -0.04594691]), + 'camera_rotation': array([ -5.43652296, -13.72635937, -3.25216174]), + 'current_gear_input': False, + 'focus_actor_dist': 1466.508544921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -806.12835693, -3197.17480469, 115.90553284]), + 'frame': 30886, + 'frame_number': 30886, + 'framesequence': 118676, + 'gaze_dir': array([ 0.98662567, -0.13974762, 0.08149719]), + 'gaze_origin': array([-3.16036391, 0.10726547, -0.0458046 ]), + 'gaze_valid': True, + 'gaze_vergence': 31.6539306640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98439026, -0.14450073, 0.10038757]), + 'left_gaze_origin': array([-3.20568419, 2.97627735, 0.02644196]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3134918212890625, + 'left_pupil_posn': array([ 0.13138962, -0.11228704]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98886108, -0.13499451, 0.06260681]), + 'right_gaze_origin': array([-3.11504388, -2.76174641, -0.11805116]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.398651123046875, + 'right_pupil_posn': array([-0.34481519, -0.2179023 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.2501644790173, + 'timestamp_carla': 998250, + 'timestamp_device': 4151679, + 'timestamp_stream': 998.2501644790173, + 'transform': [array([ 2.83900928, 10.11350822, 0.01234486]), + array([-6.54332116e-02, -9.65166664e+00, 4.16166475e-03])]} +{'AngularVelocity': array([ 0.09034736, -0.51430625, 12.30762005]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.729642868041992, + 'FR_Wheel_Angle': -23.49456214904785, + 'Location': array([ -2.91526079, -22.92211151, 0.1731898 ]), + 'Rotation': array([ -0.08911347, -34.39881134, 0.04112495]), + 'Velocity': array([-0.87747025, 1.0522927 , -0.0070261 ]), + 'brake_input': 0.0, + 'camera_location': array([-8.52207661, 13.17759037, -0.02939908]), + 'camera_rotation': array([ -5.35469055, -13.35127068, -3.40849566]), + 'current_gear_input': False, + 'focus_actor_dist': 1460.0006103515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -807.17346191, -3197.13134766, 105.12133026]), + 'frame': 30887, + 'frame_number': 30887, + 'framesequence': 118680, + 'gaze_dir': array([ 0.9855957 , -0.1490097 , 0.07772827]), + 'gaze_origin': array([-3.14540577, 0.11391298, -0.0524086 ]), + 'gaze_valid': True, + 'gaze_vergence': 37.7885856628418, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98345947, -0.15396118, 0.09535217]), + 'left_gaze_origin': array([-3.19245934, 2.98294997, 0.01941223]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3800811767578125, + 'left_pupil_posn': array([ 0.12358761, -0.11563635]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98773193, -0.14405823, 0.06010437]), + 'right_gaze_origin': array([-3.09835219, -2.75512409, -0.12422943]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4962921142578125, + 'right_pupil_posn': array([-0.35258925, -0.22091627]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.2832494787872, + 'timestamp_carla': 998283, + 'timestamp_device': 4151713, + 'timestamp_stream': 998.2832494787872, + 'transform': [array([ 2.8394208 , 10.03977776, 0.01237396]), + array([-6.54332116e-02, -9.65166664e+00, 4.16166475e-03])]} +{'AngularVelocity': array([-1.54469823e-02, 7.64146540e-03, 1.34239082e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.79521369934082, + 'FR_Wheel_Angle': -23.483837127685547, + 'Location': array([ -3.13194203, -22.69699478, 0.17289737]), + 'Rotation': array([ -0.07602 , -31.53526115, 0.03406934]), + 'Velocity': array([-0.996786 , 1.09902191, 0.00111796]), + 'brake_input': 0.0, + 'camera_location': array([-8.49478245, 13.21001053, -0.02252281]), + 'camera_rotation': array([ -5.39014578, -13.06357765, -3.35016966]), + 'current_gear_input': False, + 'focus_actor_dist': 1453.27587890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -808.33129883, -3197.10693359, 100.65179443]), + 'frame': 30888, + 'frame_number': 30888, + 'framesequence': 118684, + 'gaze_dir': array([ 0.9850769 , -0.15322113, 0.07596588]), + 'gaze_origin': array([-3.15769768, 0.12017747, -0.04777069]), + 'gaze_valid': True, + 'gaze_vergence': 55.23057556152344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98260498, -0.16055298, 0.0932312 ]), + 'left_gaze_origin': array([-3.19102621, 2.98845983, 0.02015686]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.3549652099609375, + 'left_pupil_posn': array([ 0.11912799, -0.11529744]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98754883, -0.14588928, 0.05870056]), + 'right_gaze_origin': array([-3.12436843, -2.74810505, -0.11569825]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.509613037109375, + 'right_pupil_posn': array([-0.36011553, -0.22094774]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.3174061775208, + 'timestamp_carla': 998317, + 'timestamp_device': 4151746, + 'timestamp_stream': 998.3174061775208, + 'transform': [array([2.83974481, 9.96474457, 0.01234171]), + array([-6.54741898e-02, -9.65149117e+00, 4.26320545e-03])]} +{'AngularVelocity': array([3.18466239e-02, 1.26958461e-02, 1.47566147e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.705350875854492, + 'FR_Wheel_Angle': -23.41988182067871, + 'Location': array([ -3.35550308, -22.48636627, 0.1732164 ]), + 'Rotation': array([ -0.07961951, -28.72179794, 0.03397391]), + 'Velocity': array([-1.15625441, 1.15330422, 0.00163757]), + 'brake_input': 0.0, + 'camera_location': array([-8.47197723, 13.21850777, -0.05196161]), + 'camera_rotation': array([ -5.51922989, -12.8744545 , -3.35864401]), + 'current_gear_input': False, + 'focus_actor_dist': 1444.8804931640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -803.87158203, -3197.11914062, 97.38894653]), + 'frame': 30889, + 'frame_number': 30889, + 'framesequence': 118688, + 'gaze_dir': array([ 0.98423004, -0.15926361, 0.07424164]), + 'gaze_origin': array([-3.14422321, 0.12174683, -0.0516037 ]), + 'gaze_valid': True, + 'gaze_vergence': 43.95802688598633, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98171997, -0.16600037, 0.09306335]), + 'left_gaze_origin': array([-3.19112253, 2.98995996, 0.02051544]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.392730712890625, + 'left_pupil_posn': array([ 0.11578262, -0.11633885]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98674011, -0.15252686, 0.05541992]), + 'right_gaze_origin': array([-3.09732366, -2.74646616, -0.12372284]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.49951171875, + 'right_pupil_posn': array([-0.36282134, -0.22143865]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.3489079773426, + 'timestamp_carla': 998348, + 'timestamp_device': 4151779, + 'timestamp_stream': 998.3489079773426, + 'transform': [array([2.84028077, 9.89644718, 0.01233002]), + array([-6.55083433e-02, -9.65178680e+00, 4.36171005e-03])]} +{'AngularVelocity': array([-4.92632836e-02, -5.30082826e-03, 1.59728594e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.65694236755371, + 'FR_Wheel_Angle': -23.43624496459961, + 'Location': array([ -3.5995996 , -22.27854919, 0.17356266]), + 'Rotation': array([ -0.08258381, -25.79337502, 0.03339872]), + 'Velocity': array([-1.32071459, 1.18823087, 0.00144364]), + 'brake_input': 0.0, + 'camera_location': array([-8.44994736, 13.23929691, -0.07812519]), + 'camera_rotation': array([ -5.64769173, -12.71302223, -3.37349868]), + 'current_gear_input': False, + 'focus_actor_dist': 1438.55615234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -805.08874512, -3197.15966797, 91.44411469]), + 'frame': 30890, + 'frame_number': 30890, + 'framesequence': 118692, + 'gaze_dir': array([ 0.99024963, -0.06267548, 0.12240601]), + 'gaze_origin': array([-2.95389175, 0.01987152, -0.08781663]), + 'gaze_valid': True, + 'gaze_vergence': 122.24581146240234, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99046326, -0.04283142, 0.13082886]), + 'left_gaze_origin': array([-2.81310892, 2.87724328, -0.07609101]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.585113525390625, + 'left_pupil_posn': array([ 0.21310294, -0.08982909]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99003601, -0.08251953, 0.11398315]), + 'right_gaze_origin': array([-3.09467483, -2.8375001 , -0.09954224]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.578826904296875, + 'right_pupil_posn': array([-0.25598222, -0.19074082]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.3821826763451, + 'timestamp_carla': 998382, + 'timestamp_device': 4151812, + 'timestamp_stream': 998.3821826763451, + 'transform': [array([2.84067678, 9.82532215, 0.01230095]), + array([-6.55356646e-02, -9.65178680e+00, 4.45920834e-03])]} +{'AngularVelocity': array([-0.02715953, -0.03721192, 15.39760876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.23079490661621, + 'FR_Wheel_Angle': -24.56553840637207, + 'Location': array([ -3.87598348, -22.06576347, 0.17377517]), + 'Rotation': array([ -0.07140962, -22.54734612, 0.04043727]), + 'Velocity': array([-1.25405014, 1.03151071, 0.00176196]), + 'brake_input': 0.0, + 'camera_location': array([-8.41640091, 13.25518703, -0.08955434]), + 'camera_rotation': array([ -5.67600298, -12.55295372, -3.35778594]), + 'current_gear_input': False, + 'focus_actor_dist': 1386.5528564453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -658.64782715, -3200.43066406, 163.03051758]), + 'frame': 30891, + 'frame_number': 30891, + 'framesequence': 118696, + 'gaze_dir': array([ 0.9907608 , -0.03250885, 0.13097382]), + 'gaze_origin': array([-2.98613524e+00, -2.94570951e-03, -6.96739256e-02]), + 'gaze_valid': True, + 'gaze_vergence': 225.81427001953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99092102, -0.0201416 , 0.1328125 ]), + 'left_gaze_origin': array([-2.79323149, 2.85019231, -0.07652435]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.6004180908203125, + 'left_pupil_posn': array([ 0.24371386, -0.08122921]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99060059, -0.0448761 , 0.12913513]), + 'right_gaze_origin': array([-3.179039 , -2.85608387, -0.06282349]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.427276611328125, + 'right_pupil_posn': array([-0.23531675, -0.18159866]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.4165157787502, + 'timestamp_carla': 998416, + 'timestamp_device': 4151846, + 'timestamp_stream': 998.4165157787502, + 'transform': [array([2.84096622, 9.75299454, 0.01225061]), + array([-6.55561537e-02, -9.65157318e+00, 4.58572619e-03])]} +{'AngularVelocity': array([-0.0446841 , -0.04638033, 12.86236095]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.39229202270508, + 'FR_Wheel_Angle': -25.926103591918945, + 'Location': array([ -4.09003305, -21.91312218, 0.17391174]), + 'Rotation': array([ -0.05810441, -19.92041016, 0.04727882]), + 'Velocity': array([-0.99906331, 0.77986801, 0.00199726]), + 'brake_input': 0.0, + 'camera_location': array([-8.38253784, 13.2750349 , -0.09000487]), + 'camera_rotation': array([ -5.67126274, -12.39192104, -3.407511 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1372.4410400390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -611.56347656, -3205.54370117, 176.07432556]), + 'frame': 30892, + 'frame_number': 30892, + 'framesequence': 118700, + 'gaze_dir': array([ 0.9907608 , -0.03448486, 0.13031006]), + 'gaze_origin': array([-2.98456287, -0.00381699, -0.06737214]), + 'gaze_valid': True, + 'gaze_vergence': 186.5458984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9907074 , -0.02041626, 0.13444519]), + 'left_gaze_origin': array([-2.79274297, 2.85108972, -0.07572937]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.5985260009765625, + 'left_pupil_posn': array([ 0.24188304, -0.08172405]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99081421, -0.04855347, 0.12617493]), + 'right_gaze_origin': array([-3.17638254, -2.8587234 , -0.0590149 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5806427001953125, + 'right_pupil_posn': array([-0.23352402, -0.17800283]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004742576740682125, + 'throttle_input': 0.0, + 'timestamp': 998.4497713781893, + 'timestamp_carla': 998449, + 'timestamp_device': 4151879, + 'timestamp_stream': 998.4497713781893, + 'transform': [array([2.84136581, 9.68389702, 0.0122122 ]), + array([-6.55561537e-02, -9.65160370e+00, 4.71142307e-03])]} +{'AngularVelocity': array([ 0.01631957, -0.01169949, 10.23022652]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.33818435668945, + 'FR_Wheel_Angle': -27.12654685974121, + 'Location': array([ -4.24967813, -21.80534363, 0.17407227]), + 'Rotation': array([ -0.05288615, -17.87034225, 0.04709262]), + 'Velocity': array([-7.61668086e-01, 5.71994543e-01, 3.50484828e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.34370708, 13.27854156, -0.0593162 ]), + 'camera_rotation': array([ -5.48753738, -12.13948631, -3.48078227]), + 'current_gear_input': False, + 'focus_actor_dist': 1364.48974609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -608.5178833 , -3205.40722656, 174.84410095]), + 'frame': 30893, + 'frame_number': 30893, + 'framesequence': 118704, + 'gaze_dir': array([ 0.99226379, -0.03710938, 0.11781311]), + 'gaze_origin': array([-2.97997212e+00, 1.37481699e-03, -7.40455613e-02]), + 'gaze_valid': True, + 'gaze_vergence': 225.83364868164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99224854, -0.02566528, 0.12153625]), + 'left_gaze_origin': array([-2.80690002, 2.85909891, -0.07343903]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.648712158203125, + 'left_pupil_posn': array([ 0.23679495, -0.08697331]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99227905, -0.04855347, 0.11408997]), + 'right_gaze_origin': array([-3.15304446, -2.85634947, -0.07465211]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3947906494140625, + 'right_pupil_posn': array([-0.23713988, -0.18830633]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.004651021212339401, + 'throttle_input': 0.0, + 'timestamp': 998.4839727766812, + 'timestamp_carla': 998483, + 'timestamp_device': 4151912, + 'timestamp_stream': 998.4839727766812, + 'transform': [array([2.84165001, 9.61387062, 0.01215127]), + array([-6.55561537e-02, -9.65139198e+00, 4.86634485e-03])]} +{'AngularVelocity': array([0.03264504, 0.00854698, 7.46490192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.26228713989258, + 'FR_Wheel_Angle': -28.227054595947266, + 'Location': array([ -4.39777279, -21.70965576, 0.17419551]), + 'Rotation': array([ -0.05490106, -15.88041782, 0.0406279 ]), + 'Velocity': array([-0.53395939, 0.38672766, 0.0010897 ]), + 'brake_input': 0.0, + 'camera_location': array([-8.28422928, 13.33609009, -0.0188557 ]), + 'camera_rotation': array([ -5.33230782, -11.73277569, -3.72509623]), + 'current_gear_input': False, + 'focus_actor_dist': 1353.951171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -602.81542969, -3203.26879883, 161.58627319]), + 'frame': 30894, + 'frame_number': 30894, + 'framesequence': 118708, + 'gaze_dir': array([ 0.99121094, -0.04231262, 0.12459564]), + 'gaze_origin': array([-2.98012614, 0.00567398, -0.07256699]), + 'gaze_valid': True, + 'gaze_vergence': 211.92967224121094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99197388, -0.02900696, 0.12303162]), + 'left_gaze_origin': array([-2.79698491, 2.86339736, -0.07578431]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.56024169921875, + 'left_pupil_posn': array([ 0.23134768, -0.0826267 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.990448 , -0.05561829, 0.12615967]), + 'right_gaze_origin': array([-3.16326761, -2.85204935, -0.06934967]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4788818359375, + 'right_pupil_posn': array([-0.24126905, -0.18641603]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0040467544458806515, + 'throttle_input': 0.0, + 'timestamp': 998.5163552761078, + 'timestamp_carla': 998516, + 'timestamp_device': 4151946, + 'timestamp_stream': 998.5163552761078, + 'transform': [array([2.84215569, 9.54843807, 0.01212082]), + array([-6.55561537e-02, -9.65166759e+00, 4.98983450e-03])]} +{'AngularVelocity': array([0.03129927, 0.00967054, 5.20270872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.65140914916992, + 'FR_Wheel_Angle': -28.42630386352539, + 'Location': array([ -4.50260735, -21.64510918, 0.17434952]), + 'Rotation': array([ -0.05910845, -14.44862556, 0.03414871]), + 'Velocity': array([-0.37427074, 0.2586686 , 0.00048503]), + 'brake_input': 0.0, + 'camera_location': array([-8.23540592, 13.40588474, -0.01972502]), + 'camera_rotation': array([ -5.36925936, -11.18440628, -3.67010808]), + 'current_gear_input': False, + 'focus_actor_dist': 1348.9718017578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -600.16467285, -3205.53710938, 173.69036865]), + 'frame': 30895, + 'frame_number': 30895, + 'framesequence': 118712, + 'gaze_dir': array([ 0.99052429, -0.05077362, 0.12696838]), + 'gaze_origin': array([-2.96349883, 0.01481934, -0.07947388]), + 'gaze_valid': True, + 'gaze_vergence': 222.07904052734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99055481, -0.03948975, 0.13122559]), + 'left_gaze_origin': array([-2.80889153, 2.87468433, -0.07298432]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.58477783203125, + 'left_pupil_posn': array([ 0.22175527, -0.08399105]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99049377, -0.0620575 , 0.12271118]), + 'right_gaze_origin': array([-3.11810613, -2.84504557, -0.08596344]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4727935791015625, + 'right_pupil_posn': array([-0.24962538, -0.18604517]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.002984710270538926, + 'throttle_input': 0.0, + 'timestamp': 998.5498318783939, + 'timestamp_carla': 998549, + 'timestamp_device': 4151979, + 'timestamp_stream': 998.5498318783939, + 'transform': [array([2.84249258, 9.48176003, 0.01206325]), + array([-6.55424893e-02, -9.65160465e+00, 5.14326245e-03])]} +{'AngularVelocity': array([0.0249119 , 0.00778401, 3.73270845]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.925262451171875, + 'FR_Wheel_Angle': -28.554670333862305, + 'Location': array([ -4.57035494, -21.60510445, 0.17442107]), + 'Rotation': array([ -0.06231181, -13.526021 , 0.02880197]), + 'Velocity': array([-0.26918295, 0.18055463, 0.00093191]), + 'brake_input': 0.0, + 'camera_location': array([-8.19957733e+00, 1.34739237e+01, -2.20686337e-03]), + 'camera_rotation': array([ -5.36175966, -10.69792747, -3.57411289]), + 'current_gear_input': False, + 'focus_actor_dist': 1342.188232421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -597.0045166 , -3205.86914062, 175.21694946]), + 'frame': 30896, + 'frame_number': 30896, + 'framesequence': 118716, + 'gaze_dir': array([ 0.98957062, -0.06119537, 0.12966156]), + 'gaze_origin': array([-2.95494485, 0.0206398 , -0.08110733]), + 'gaze_valid': True, + 'gaze_vergence': 205.06478881835938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98986816, -0.04837036, 0.13348389]), + 'left_gaze_origin': array([-2.81423497, 2.88059092, -0.07127533]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.572235107421875, + 'left_pupil_posn': array([ 0.2137537 , -0.08276594]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98927307, -0.07402039, 0.12583923]), + 'right_gaze_origin': array([-3.09565449, -2.83931136, -0.09093934]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.537750244140625, + 'right_pupil_posn': array([-0.25656629, -0.1844821 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0017578662373125553, + 'throttle_input': 0.01190203707665205, + 'timestamp': 998.5819968767464, + 'timestamp_carla': 998582, + 'timestamp_device': 4152012, + 'timestamp_stream': 998.5819968767464, + 'transform': [array([2.84292412, 9.41855526, 0.01203042]), + array([-6.55356646e-02, -9.65175915e+00, 5.26558328e-03])]} +{'AngularVelocity': array([0.01954343, 0.00588305, 2.66425371]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.98770523071289, + 'FR_Wheel_Angle': -28.589981079101562, + 'Location': array([ -4.61950159, -21.57692337, 0.17447785]), + 'Rotation': array([ -0.06482532, -12.85909081, 0.02467769]), + 'Velocity': array([-0.19261684, 0.12634516, 0.00074206]), + 'brake_input': 0.0, + 'camera_location': array([-8.18083858, 13.52997017, -0.02864029]), + 'camera_rotation': array([ -5.49826097, -10.2749815 , -3.40023398]), + 'current_gear_input': False, + 'focus_actor_dist': 1336.409423828125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -597.93817139, -3206.25585938, 178.2021637 ]), + 'frame': 30897, + 'frame_number': 30897, + 'framesequence': 118720, + 'gaze_dir': array([ 0.98907471, -0.06655121, 0.13097382]), + 'gaze_origin': array([-2.9407258 , 0.02782135, -0.08199769]), + 'gaze_valid': True, + 'gaze_vergence': 247.41744995117188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98959351, -0.05526733, 0.13276672]), + 'left_gaze_origin': array([-2.81891799, 2.88832116, -0.06762085]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.587127685546875, + 'left_pupil_posn': array([ 0.20735645, -0.08014071]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98855591, -0.07783508, 0.12918091]), + 'right_gaze_origin': array([-3.06253386, -2.83267832, -0.09637452]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.518646240234375, + 'right_pupil_posn': array([-0.26331896, -0.18201709]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0008423108956776559, + 'throttle_input': 0.043656062334775925, + 'timestamp': 998.6171017773449, + 'timestamp_carla': 998617, + 'timestamp_device': 4152046, + 'timestamp_stream': 998.6171017773449, + 'transform': [array([2.84304905, 9.3510952 , 0.01222542]), + array([-6.57132491e-02, -9.65130138e+00, 4.89304401e-03])]} +{'AngularVelocity': array([0.01456145, 0.00464261, 1.89369071]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.03706359863281, + 'FR_Wheel_Angle': -28.618772506713867, + 'Location': array([ -4.65407658, -21.55757332, 0.17450866]), + 'Rotation': array([ -0.06661483, -12.39326859, 0.02183554]), + 'Velocity': array([-0.13834694, 0.08884993, -0.00050908]), + 'brake_input': 0.0, + 'camera_location': array([-8.1496315 , 13.5649538 , -0.06540231]), + 'camera_rotation': array([ -5.65234327, -10.00158691, -3.24453783]), + 'current_gear_input': False, + 'focus_actor_dist': 1328.9503173828125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -593.04138184, -3206.1875 , 176.43360901]), + 'frame': 30898, + 'frame_number': 30898, + 'framesequence': 118724, + 'gaze_dir': array([ 0.98960876, -0.07216644, 0.12347412]), + 'gaze_origin': array([-2.97521615, 0.03158265, -0.06875382]), + 'gaze_valid': True, + 'gaze_vergence': 185.3479766845703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98980713, -0.05940247, 0.12936401]), + 'left_gaze_origin': array([-2.85870528, 2.89236617, -0.05141144]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.593902587890625, + 'left_pupil_posn': array([ 0.20273876, -0.08078051]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9894104 , -0.08493042, 0.11758423]), + 'right_gaze_origin': array([-3.09172678, -2.82920098, -0.0860962 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4627685546875, + 'right_pupil_posn': array([-0.26729983, -0.18156898]), + 'right_pupil_posn_valid': True, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0476234070956707, + 'timestamp': 998.648604478687, + 'timestamp_carla': 998648, + 'timestamp_device': 4152079, + 'timestamp_stream': 998.648604478687, + 'transform': [array([2.84363794, 9.29170036, 0.01247476]), + array([-6.58088699e-02, -9.65184402e+00, 4.47677169e-03])]} +{'AngularVelocity': array([-0.00583478, -0.02595176, 1.31418729]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.08134078979492, + 'FR_Wheel_Angle': -28.660131454467773, + 'Location': array([ -4.67882633, -21.54353523, 0.17454429]), + 'Rotation': array([ -0.06656019, -12.07381058, 0.02091849]), + 'Velocity': array([-0.03552334, 0.03029731, -0.00070619]), + 'brake_input': 0.0, + 'camera_location': array([-8.09885216, 13.58472729, -0.07992397]), + 'camera_rotation': array([-5.7229948 , -9.89203358, -3.24514127]), + 'current_gear_input': False, + 'focus_actor_dist': 1319.0633544921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -590.72937012, -3203.68261719, 162.51445007]), + 'frame': 30899, + 'frame_number': 30899, + 'framesequence': 118728, + 'gaze_dir': array([ 0.99095917, -0.04387665, 0.1257782 ]), + 'gaze_origin': array([-2.95340586, 0.0087059 , -0.07706451]), + 'gaze_valid': True, + 'gaze_vergence': 175.71388244628906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99092102, -0.02955627, 0.13108826]), + 'left_gaze_origin': array([-2.79563165, 2.87107396, -0.07396851]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.55731201171875, + 'left_pupil_posn': array([ 0.22529829, -0.0828954 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99099731, -0.05819702, 0.12046814]), + 'right_gaze_origin': array([-3.11118031, -2.85366225, -0.08016053]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.393585205078125, + 'right_pupil_posn': array([-0.24009585, -0.18069863]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00018311107123736292, + 'throttle_input': 0.05555810034275055, + 'timestamp': 998.6835361793637, + 'timestamp_carla': 998683, + 'timestamp_device': 4152112, + 'timestamp_stream': 998.6835361793637, + 'transform': [array([2.84391069, 9.22720051, 0.01271208]), + array([-6.63279667e-02, -9.65166664e+00, 4.01101448e-03])]} +{'AngularVelocity': array([0.03007275, 0.03586941, 0.00076274]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.11930465698242, + 'FR_Wheel_Angle': -28.66522979736328, + 'Location': array([ -4.68674469, -21.53898239, 0.17461219]), + 'Rotation': array([ -0.06863657, -11.98073006, 0.01863995]), + 'Velocity': array([-0.05708155, 0.03125599, 0.00011675]), + 'brake_input': 0.0, + 'camera_location': array([-8.06493282, 13.59543896, -0.078402 ]), + 'camera_rotation': array([-5.78301144, -9.84893322, -3.16099811]), + 'current_gear_input': False, + 'focus_actor_dist': 1301.4410400390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -548.28527832, -3201.55322266, 165.34423828]), + 'frame': 30900, + 'frame_number': 30900, + 'framesequence': 118732, + 'gaze_dir': array([0.99085999, 0.05034637, 0.12364197]), + 'gaze_origin': array([-2.97915578, -0.05810013, -0.06946106]), + 'gaze_valid': True, + 'gaze_vergence': 144.50283813476562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99069214, 0.06817627, 0.11776733]), + 'left_gaze_origin': array([-2.80163121, 2.79783344, -0.07808838]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7273101806640625, + 'left_pupil_posn': array([ 0.30540287, -0.08428288]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99102783, 0.03251648, 0.1295166 ]), + 'right_gaze_origin': array([-3.15668058, -2.91403365, -0.06083374]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4581146240234375, + 'right_pupil_posn': array([-0.16427398, -0.18167329]), + 'right_pupil_posn_valid': True, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.08332952111959457, + 'timestamp': 998.7149431779981, + 'timestamp_carla': 998714, + 'timestamp_device': 4152146, + 'timestamp_stream': 998.7149431779981, + 'transform': [array([2.84424734, 9.17005062, 0.01288342]), + array([-6.66421503e-02, -9.65169716e+00, 3.72547447e-03])]} +{'AngularVelocity': array([ 0.02436224, 0.03263179, -0.0091214 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.118045806884766, + 'FR_Wheel_Angle': -28.664215087890625, + 'Location': array([ -4.69605017, -21.5337944 , 0.1746268 ]), + 'Rotation': array([ -0.07055585, -11.85853958, 0.01638932]), + 'Velocity': array([-0.05670489, 0.03009316, -0.00027962]), + 'brake_input': 0.0, + 'camera_location': array([-8.03453255, 13.61686897, -0.08885676]), + 'camera_rotation': array([-5.8696661 , -9.87364388, -3.06438041]), + 'current_gear_input': False, + 'focus_actor_dist': 3420.578125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -684.67675781, -5331.49121094, 222.52593994]), + 'frame': 30901, + 'frame_number': 30901, + 'framesequence': 118736, + 'gaze_dir': array([0.99160004, 0.04686737, 0.11975098]), + 'gaze_origin': array([-2.98396158, -0.05942994, -0.06595077]), + 'gaze_valid': True, + 'gaze_vergence': 198.72186279296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99169922, 0.05871582, 0.11425781]), + 'left_gaze_origin': array([-2.8107698 , 2.79598546, -0.07395173]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7419586181640625, + 'left_pupil_posn': array([ 0.30778551, -0.08468544]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99150085, 0.03501892, 0.12524414]), + 'right_gaze_origin': array([-3.15715337, -2.91484547, -0.05794983]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.3610992431640625, + 'right_pupil_posn': array([-0.16711181, -0.18123043]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.1428549587726593, + 'timestamp': 998.7492753788829, + 'timestamp_carla': 998749, + 'timestamp_device': 4152179, + 'timestamp_stream': 998.7492753788829, + 'transform': [array([2.84458852, 9.10842514, 0.01300587]), + array([-6.67992458e-02, -9.65169716e+00, 3.47259222e-03])]} +{'AngularVelocity': array([0.09529646, 0.06775327, 1.04686105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.042659759521484, + 'FR_Wheel_Angle': -28.582130432128906, + 'Location': array([ -4.71070623, -21.52609253, 0.17466758]), + 'Rotation': array([-7.45856613e-02, -1.16611509e+01, 1.14029869e-02]), + 'Velocity': array([-1.43690363e-01, 8.11023563e-02, -1.70326221e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.00557232, 13.64142895, -0.10190013]), + 'camera_rotation': array([-5.91740942, -9.78635502, -3.04674435]), + 'current_gear_input': False, + 'focus_actor_dist': 3415.836669921875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -695.97662354, -5331.49072266, 202.89089966]), + 'frame': 30902, + 'frame_number': 30902, + 'framesequence': 118740, + 'gaze_dir': array([0.99100494, 0.0486145 , 0.12406158]), + 'gaze_origin': array([-2.96286178, -0.05879288, -0.07330856]), + 'gaze_valid': True, + 'gaze_vergence': 209.0420684814453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99130249, 0.05834961, 0.11782837]), + 'left_gaze_origin': array([-2.77033234, 2.79737425, -0.08773346]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7529296875, + 'left_pupil_posn': array([ 0.30735886, -0.08473957]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9907074 , 0.03887939, 0.1302948 ]), + 'right_gaze_origin': array([-3.15539098, -2.91495991, -0.05888367]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.397796630859375, + 'right_pupil_posn': array([-0.16712165, -0.18012679]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.17062638700008392, + 'timestamp': 998.7818099781871, + 'timestamp_carla': 998781, + 'timestamp_device': 4152212, + 'timestamp_stream': 998.7818099781871, + 'transform': [array([2.84501958, 9.0505085 , 0.01298006]), + array([-6.68265671e-02, -9.65190983e+00, 3.53995292e-03])]} +{'AngularVelocity': array([-1.34618755e-03, 3.86350937e-02, 6.87865305e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.78038787841797, + 'FR_Wheel_Angle': -28.44025421142578, + 'Location': array([ -4.78732729, -21.48660088, 0.17483643]), + 'Rotation': array([-8.69756266e-02, -1.06260824e+01, -3.41796898e-03]), + 'Velocity': array([-0.49810916, 0.29017571, 0.00130834]), + 'brake_input': 0.0, + 'camera_location': array([-7.95627689, 13.68609047, -0.10977273]), + 'camera_rotation': array([-6.01054573, -9.65804958, -3.1336751 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3408.52734375, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -684.53961182, -5331.49023438, 214.93354797]), + 'frame': 30903, + 'frame_number': 30903, + 'framesequence': 118745, + 'gaze_dir': array([0.99095917, 0.04940033, 0.12417603]), + 'gaze_origin': array([-2.96555042, -0.05661698, -0.07200928]), + 'gaze_valid': True, + 'gaze_vergence': 195.45999145507812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99142456, 0.0582428 , 0.11697388]), + 'left_gaze_origin': array([-2.76489139, 2.79870152, -0.08963165]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.759765625, + 'left_pupil_posn': array([ 0.30693209, -0.08462048]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99049377, 0.04055786, 0.13137817]), + 'right_gaze_origin': array([-3.16620946, -2.91193557, -0.0543869 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4238739013671875, + 'right_pupil_posn': array([-0.16919208, -0.17944217]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.17856107652187347, + 'timestamp': 998.8222028762102, + 'timestamp_carla': 998822, + 'timestamp_device': 4152254, + 'timestamp_stream': 998.8222028762102, + 'transform': [array([2.84861088, 8.9783287 , 0.01270825]), + array([-6.67446032e-02, -9.65825367e+00, 4.08412609e-03])]} +{'AngularVelocity': array([ 0.00928033, -0.04927208, 7.84653902]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.33330535888672, + 'FR_Wheel_Angle': -27.875219345092773, + 'Location': array([ -4.91726303, -21.42197227, 0.17489952]), + 'Rotation': array([-7.90389478e-02, -8.95048237e+00, 6.21435558e-03]), + 'Velocity': array([-0.55514622, 0.32695523, 0.00069324]), + 'brake_input': 0.0, + 'camera_location': array([-7.91939735, 13.73685265, -0.12738955]), + 'camera_rotation': array([-6.21250057, -9.45413971, -3.06808257]), + 'current_gear_input': False, + 'focus_actor_dist': 3401.366455078125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -674.08764648, -5331.49023438, 209.99569702]), + 'frame': 30904, + 'frame_number': 30904, + 'framesequence': 118749, + 'gaze_dir': array([0.99110413, 0.04798889, 0.12355804]), + 'gaze_origin': array([-2.96806741, -0.05529252, -0.07007141]), + 'gaze_valid': True, + 'gaze_vergence': 199.1183624267578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99159241, 0.0562439 , 0.1164093 ]), + 'left_gaze_origin': array([-2.77390909, 2.80042601, -0.08637543]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.764678955078125, + 'left_pupil_posn': array([ 0.30568027, -0.08436131]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99061584, 0.03973389, 0.13070679]), + 'right_gaze_origin': array([-3.16222525, -2.91101098, -0.0537674 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4268035888671875, + 'right_pupil_posn': array([-0.17052794, -0.17841065]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.18252842128276825, + 'timestamp': 998.853142477572, + 'timestamp_carla': 998853, + 'timestamp_device': 4152287, + 'timestamp_stream': 998.853142477572, + 'transform': [array([2.84896469, 8.92341614, 0.01234964]), + array([-6.66216612e-02, -9.65835190e+00, 4.80612507e-03])]} +{'AngularVelocity': array([ 0.03552576, -0.01994706, 6.70242691]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.96122169494629, + 'FR_Wheel_Angle': -22.799129486083984, + 'Location': array([ -5.03282547, -21.3706131 , 0.17497413]), + 'Rotation': array([-0.07477008, -7.57559824, 0.01695445]), + 'Velocity': array([-5.80457926e-01, 2.82100439e-01, 3.44219210e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.87558699, 13.77945232, -0.14996831]), + 'camera_rotation': array([-6.36583138, -9.29054546, -2.89357138]), + 'current_gear_input': False, + 'focus_actor_dist': 3392.937744140625, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -665.59448242, -5331.49023438, 195.32800293]), + 'frame': 30905, + 'frame_number': 30905, + 'framesequence': 118752, + 'gaze_dir': array([0.99183655, 0.04360962, 0.11923218]), + 'gaze_origin': array([-2.9790659 , -0.05440979, -0.06336289]), + 'gaze_valid': True, + 'gaze_vergence': 250.12596130371094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99156189, 0.05471802, 0.11743164]), + 'left_gaze_origin': array([-2.79943252, 2.80140853, -0.07246247]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7921295166015625, + 'left_pupil_posn': array([ 0.30304623, -0.08314991]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99211121, 0.03250122, 0.12103271]), + 'right_gaze_origin': array([-3.15869927, -2.91022801, -0.0542633 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4437408447265625, + 'right_pupil_posn': array([-0.17160779, -0.17775297]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.18252842128276825, + 'timestamp': 998.8838770762086, + 'timestamp_carla': 998883, + 'timestamp_device': 4152312, + 'timestamp_stream': 998.8838770762086, + 'transform': [array([2.84932733, 8.8686676 , 0.01191061]), + array([-6.64713979e-02, -9.65847397e+00, 5.67779085e-03])]} +{'AngularVelocity': array([ 0.06106482, -0.00669868, 5.31571293]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.955751419067383, + 'FR_Wheel_Angle': -18.40253448486328, + 'Location': array([ -5.17629147, -21.32076454, 0.1751084 ]), + 'Rotation': array([-0.07428513, -6.28494692, 0.02084516]), + 'Velocity': array([-0.62979507, 0.23169102, 0.00065506]), + 'brake_input': 0.0, + 'camera_location': array([-7.83591557, 13.82496166, -0.16404136]), + 'camera_rotation': array([-6.43823147, -9.07261944, -2.75003815]), + 'current_gear_input': False, + 'focus_actor_dist': 3387.395751953125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -668.06616211, -5331.48974609, 170.22142029]), + 'frame': 30906, + 'frame_number': 30906, + 'framesequence': 118756, + 'gaze_dir': array([0.99157715, 0.03716278, 0.1235199 ]), + 'gaze_origin': array([-2.98136234, -0.05384369, -0.06221161]), + 'gaze_valid': True, + 'gaze_vergence': 254.75564575195312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99136353, 0.04814148, 0.12197876]), + 'left_gaze_origin': array([-2.80132461, 2.8024447 , -0.07133942]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7960357666015625, + 'left_pupil_posn': array([ 0.30022097, -0.08138561]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99179077, 0.02618408, 0.12506104]), + 'right_gaze_origin': array([-3.16139984, -2.91013193, -0.0530838 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.541473388671875, + 'right_pupil_posn': array([-0.17398971, -0.17607009]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.18252842128276825, + 'timestamp': 998.9167012758553, + 'timestamp_carla': 998916, + 'timestamp_device': 4152346, + 'timestamp_stream': 998.9167012758553, + 'transform': [array([2.84974051, 8.81000996, 0.01148426]), + array([-6.63211346e-02, -9.65865993e+00, 6.48888620e-03])]} +{'AngularVelocity': array([4.34761569e-02, 1.99280051e-03, 4.22277164e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.788545608520508, + 'FR_Wheel_Angle': -13.76292610168457, + 'Location': array([ -5.32866001, -21.27952194, 0.17526466]), + 'Rotation': array([-0.07458566, -5.25635004, 0.02075261]), + 'Velocity': array([-0.68084514, 0.1913393 , 0.00089933]), + 'brake_input': 0.0, + 'camera_location': array([-7.78440428, 13.89326191, -0.18766433]), + 'camera_rotation': array([-6.50601435, -8.78752995, -2.65151691]), + 'current_gear_input': False, + 'focus_actor_dist': 3382.990478515625, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -675.99926758, -5331.49023438, 179.09571838]), + 'frame': 30907, + 'frame_number': 30907, + 'framesequence': 118760, + 'gaze_dir': array([0.98122406, 0.14912415, 0.11935425]), + 'gaze_origin': array([-2.94698191, -0.13658983, -0.0851265 ]), + 'gaze_valid': True, + 'gaze_vergence': 81.16959381103516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98031616, 0.16908264, 0.10188293]), + 'left_gaze_origin': array([-2.7320056 , 2.71695566, -0.1101471 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.933502197265625, + 'left_pupil_posn': array([ 0.39134479, -0.09159625]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98213196, 0.12916565, 0.13682556]), + 'right_gaze_origin': array([-3.16195869, -2.99013543, -0.0601059 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.4954376220703125, + 'right_pupil_posn': array([-0.07663161, -0.18980634]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.18252842128276825, + 'timestamp': 998.9477427788079, + 'timestamp_carla': 998947, + 'timestamp_device': 4152379, + 'timestamp_stream': 998.9477427788079, + 'transform': [array([2.85010624, 8.75424385, 0.01110496]), + array([-6.61913604e-02, -9.65878296e+00, 7.24020787e-03])]} +{'AngularVelocity': array([0.03954361, 0.06240252, 3.03161311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.262988090515137, + 'FR_Wheel_Angle': -7.57825231552124, + 'Location': array([ -5.53511953, -21.23993683, 0.17552836]), + 'Rotation': array([-0.083984 , -4.37948751, 0.02011393]), + 'Velocity': array([-9.67476726e-01, 1.68677256e-01, 9.61904530e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.73748207, 13.98813629, -0.19956262]), + 'camera_rotation': array([-6.66917372, -8.2961483 , -2.46993279]), + 'current_gear_input': False, + 'focus_actor_dist': 3352.313232421875, + 'focus_actor_name': 'SM_Shop_72', + 'focus_actor_pt': array([ -278.49572754, -5331.48974609, 181.42318726]), + 'frame': 30908, + 'frame_number': 30908, + 'framesequence': 118764, + 'gaze_dir': array([0.93849182, 0.33628082, 0.07623291]), + 'gaze_origin': array([-3.01891351, -0.28520584, -0.10318909]), + 'gaze_valid': True, + 'gaze_vergence': 91.92825317382812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93588257, 0.3467865 , 0.06196594]), + 'left_gaze_origin': array([-2.84616113, 2.54713607, -0.11605836]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2258453369140625, + 'left_pupil_posn': array([ 0.58547091, -0.13774395]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94110107, 0.32577515, 0.09049988]), + 'right_gaze_origin': array([-3.19166589, -3.11754775, -0.09031983]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7193450927734375, + 'right_pupil_posn': array([ 0.07405412, -0.23656225]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.18252842128276825, + 'timestamp': 998.9807506762445, + 'timestamp_carla': 998980, + 'timestamp_device': 4152412, + 'timestamp_stream': 998.9807506762445, + 'transform': [array([2.85050964, 8.69466019, 0.01078623]), + array([-6.60820752e-02, -9.65893459e+00, 7.84093980e-03])]} +{'AngularVelocity': array([-0.00334864, -0.04550961, 0.48101759]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.408596158027649, + 'FR_Wheel_Angle': -0.3920787572860718, + 'Location': array([ -5.75345135, -21.21415329, 0.17568836]), + 'Rotation': array([-0.07422366, -3.99691892, 0.02553088]), + 'Velocity': array([-0.89208609, 0.07980049, 0.00094136]), + 'brake_input': 0.0, + 'camera_location': array([-7.68513393, 14.11401749, -0.22028162]), + 'camera_rotation': array([-6.85318613, -7.40297461, -2.23762274]), + 'current_gear_input': False, + 'focus_actor_dist': 3415.41845703125, + 'focus_actor_name': 'SM_Shop_68', + 'focus_actor_pt': array([ 412.62039185, -5331.48974609, 68.5122757 ]), + 'frame': 30909, + 'frame_number': 30909, + 'framesequence': 118768, + 'gaze_dir': array([0.89201355, 0.44875336, 0.05255127]), + 'gaze_origin': array([-3.05988097, -0.37309191, -0.12276078]), + 'gaze_valid': True, + 'gaze_vergence': 148.77862548828125, + 'handbrake_input': False, + 'left_eye_openness': 0.6905624866485596, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.88851929, 0.45669556, 0.04405212]), + 'left_gaze_origin': array([-2.8927722 , 2.44759369, -0.13797608]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30718994140625, + 'left_pupil_posn': array([ 0.71159267, -0.17814672]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.89550781, 0.44081116, 0.06105042]), + 'right_gaze_origin': array([-3.22698998, -3.1937778 , -0.10754547]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.69482421875, + 'right_pupil_posn': array([ 0.16794574, -0.26745331]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.18252842128276825, + 'timestamp': 999.0161392763257, + 'timestamp_carla': 999016, + 'timestamp_device': 4152446, + 'timestamp_stream': 999.0161392763257, + 'transform': [array([2.85097289, 8.63058567, 0.010592 ]), + array([-6.60206079e-02, -9.65914726e+00, 8.17051344e-03])]} +{'AngularVelocity': array([ 0.02707127, -0.0189299 , 0.0320088 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.11373743414878845, + 'FR_Wheel_Angle': -0.04043666273355484, + 'Location': array([ -5.94792938, -21.20031166, 0.1758786 ]), + 'Rotation': array([-0.06796038, -4.00015354, 0.01938498]), + 'Velocity': array([-0.77135003, 0.05512432, 0.00132341]), + 'brake_input': 0.0, + 'camera_location': array([-7.65752649, 14.35206509, -0.2595264 ]), + 'camera_rotation': array([-7.10543871, -5.72192574, -2.14042687]), + 'current_gear_input': False, + 'focus_actor_dist': 3163.48583984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 786.46179199, -4971.54199219, 16.07819366]), + 'frame': 30910, + 'frame_number': 30910, + 'framesequence': 118772, + 'gaze_dir': array([0.89765167, 0.43859863, 0.04190826]), + 'gaze_origin': array([-3.04920602, -0.35239947, -0.11772004]), + 'gaze_valid': True, + 'gaze_vergence': 251.291748046875, + 'handbrake_input': False, + 'left_eye_openness': 0.705367922782898, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.90126038, 0.43157959, 0.03816223]), + 'left_gaze_origin': array([-2.88123012, 2.47510076, -0.13459931]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1185150146484375, + 'left_pupil_posn': array([ 0.69073117, -0.17869985]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.89404297, 0.44561768, 0.0456543 ]), + 'right_gaze_origin': array([-3.21718168, -3.17989969, -0.10084077]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6275787353515625, + 'right_pupil_posn': array([ 0.14868784, -0.2614783 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 999.0476768761873, + 'timestamp_carla': 999047, + 'timestamp_device': 4152479, + 'timestamp_stream': 999.0476768761873, + 'transform': [array([2.85124564, 8.57309628, 0.01042433]), + array([-6.59386441e-02, -9.65906143e+00, 8.52826517e-03])]} +{'AngularVelocity': array([ 0.00953064, -0.00055655, -0.06712282]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04680459946393967, + 'FR_Wheel_Angle': 0.04429832845926285, + 'Location': array([ -6.07846165, -21.19112968, 0.17601395]), + 'Rotation': array([-0.06753691, -4.0016799 , 0.01674438]), + 'Velocity': array([-0.70564336, 0.04939089, 0.00096076]), + 'brake_input': 0.0, + 'camera_location': array([-7.63529396, 14.65791893, -0.31141782]), + 'camera_rotation': array([-7.33705044, -3.53927422, -2.32918715]), + 'current_gear_input': False, + 'focus_actor_dist': 2197.9970703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 503.56945801, -4052.58789062, 16.22867584]), + 'frame': 30911, + 'frame_number': 30911, + 'framesequence': 118776, + 'gaze_dir': array([0.91873169, 0.39234924, 0.04231262]), + 'gaze_origin': array([-3.03517795, -0.32911378, -0.11354447]), + 'gaze_valid': True, + 'gaze_vergence': 178.2305450439453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92385864, 0.3808136 , 0.03799438]), + 'left_gaze_origin': array([-2.86504388, 2.50364542, -0.13062134]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2205352783203125, + 'left_pupil_posn': array([ 0.65001118, -0.17014921]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91360474, 0.40388489, 0.04663086]), + 'right_gaze_origin': array([-3.20531178, -3.16187286, -0.0964676 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.52886962890625, + 'right_pupil_posn': array([ 0.11731517, -0.2535367 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0007507553673349321, + 'throttle_input': 0.1904631108045578, + 'timestamp': 999.0825524777174, + 'timestamp_carla': 999082, + 'timestamp_device': 4152512, + 'timestamp_stream': 999.0825524777174, + 'transform': [array([2.85127616, 8.50923824, 0.01032497]), + array([-6.58225268e-02, -9.65838242e+00, 8.69423617e-03])]} +{'AngularVelocity': array([0.00228417, 0.00844845, 0.0115491 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0050660730339586735, + 'FR_Wheel_Angle': -0.005066477227956057, + 'Location': array([ -6.21519089, -21.18151093, 0.17614311]), + 'Rotation': array([-0.06882098, -4.00033712, 0.01569675]), + 'Velocity': array([-6.63317800e-01, 4.68386672e-02, 5.55109989e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.59584713, 14.95928669, -0.35674849]), + 'camera_rotation': array([-7.44141579, -1.53329182, -2.65903521]), + 'current_gear_input': False, + 'focus_actor_dist': 1963.3294677734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 397.72155762, -3846.96826172, 16.33872986]), + 'frame': 30912, + 'frame_number': 30912, + 'framesequence': 118780, + 'gaze_dir': array([0.92316437, 0.37970734, 0.05901337]), + 'gaze_origin': array([-3.03137922, -0.31471023, -0.11081925]), + 'gaze_valid': True, + 'gaze_vergence': 25.85297966003418, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92408752, 0.37886047, 0.05007935]), + 'left_gaze_origin': array([-2.85935831, 2.52204442, -0.12698059]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1371612548828125, + 'left_pupil_posn': array([ 0.626369 , -0.15785611]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92224121, 0.3805542 , 0.06794739]), + 'right_gaze_origin': array([-3.2033999 , -3.15146494, -0.09465791]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.773773193359375, + 'right_pupil_posn': array([ 0.10926139, -0.24764132]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00139164412394166, + 'throttle_input': 0.1904631108045578, + 'timestamp': 999.1150113791227, + 'timestamp_carla': 999115, + 'timestamp_device': 4152546, + 'timestamp_stream': 999.1150113791227, + 'transform': [array([2.85088491, 8.4494257 , 0.01025404]), + array([-6.56859279e-02, -9.65686131e+00, 8.85568094e-03])]} +{'AngularVelocity': array([0.00011193, 0.0134755 , 0.0342681 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.015204165130853653, + 'FR_Wheel_Angle': -0.015201105736196041, + 'Location': array([ -6.34515476, -21.17226982, 0.17625949]), + 'Rotation': array([-0.07009823, -4.00344944, 0.01565653]), + 'Velocity': array([-6.39477491e-01, 4.52142507e-02, 5.12361512e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.56363344, 15.298563 , -0.38145965]), + 'camera_rotation': array([-7.52595282, 0.37343681, -2.84899545]), + 'current_gear_input': False, + 'focus_actor_dist': 2676.840087890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 689.73815918, -4507.13183594, 16.10224915]), + 'frame': 30913, + 'frame_number': 30913, + 'framesequence': 118784, + 'gaze_dir': array([0.93574524, 0.34947205, 0.04456329]), + 'gaze_origin': array([-3.01932907, -0.28828508, -0.10458833]), + 'gaze_valid': True, + 'gaze_vergence': 85.41851043701172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93363953, 0.35684204, 0.03097534]), + 'left_gaze_origin': array([-2.84552026, 2.55084538, -0.12187805]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0897216796875, + 'left_pupil_posn': array([ 0.58911026, -0.15326142]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93785095, 0.34210205, 0.05815125]), + 'right_gaze_origin': array([-3.19313812, -3.12741542, -0.08729859]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6811370849609375, + 'right_pupil_posn': array([ 0.08415961, -0.24632502]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.19839780032634735, + 'timestamp': 999.1495723761618, + 'timestamp_carla': 999149, + 'timestamp_device': 4152579, + 'timestamp_stream': 999.1495723761618, + 'transform': [array([2.84969664, 8.38546467, 0.01026466]), + array([-6.54946789e-02, -9.65362167e+00, 8.82028230e-03])]} +{'AngularVelocity': array([-1.73027554e-04, 3.80883887e-02, 9.74026322e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.017712492495775223, + 'FR_Wheel_Angle': -0.017714111134409904, + 'Location': array([ -6.487391 , -21.16223335, 0.17698017]), + 'Rotation': array([-0.09643544, -4.00302315, -0.01721191]), + 'Velocity': array([-0.7248463 , 0.05118675, 0.00274671]), + 'brake_input': 0.0, + 'camera_location': array([-7.58235741, 15.65259647, -0.40617722]), + 'camera_rotation': array([-7.71262169, 2.44347024, -2.83744502]), + 'current_gear_input': False, + 'focus_actor_dist': 1910.2205810546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 418.63232422, -3795.09814453, 16.31755066]), + 'frame': 30914, + 'frame_number': 30914, + 'framesequence': 118788, + 'gaze_dir': array([0.94245911, 0.3298111 , 0.05348206]), + 'gaze_origin': array([-3.01290131, -0.26882631, -0.09718858]), + 'gaze_valid': True, + 'gaze_vergence': 35.593997955322266, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94258118, 0.3311615 , 0.04290771]), + 'left_gaze_origin': array([-2.83853173, 2.57432723, -0.11429902]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.049530029296875, + 'left_pupil_posn': array([ 0.56637788, -0.14432275]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94233704, 0.32846069, 0.0640564 ]), + 'right_gaze_origin': array([-3.18727112, -3.11197972, -0.08007813]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.63726806640625, + 'right_pupil_posn': array([ 0.06421125, -0.23490381]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004614398814737797, + 'throttle_input': 0.20236514508724213, + 'timestamp': 999.1816292777658, + 'timestamp_carla': 999181, + 'timestamp_device': 4152612, + 'timestamp_stream': 999.1816292777658, + 'transform': [array([2.84753966, 8.32580185, 0.01025909]), + array([-6.52078092e-02, -9.64837551e+00, 8.86285026e-03])]} +{'AngularVelocity': array([-0.02008434, 0.00108556, -0.89000136]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.021501893177628517, + 'FR_Wheel_Angle': -0.021476849913597107, + 'Location': array([ -6.65284061, -21.15041161, 0.17716652]), + 'Rotation': array([-0.09310913, -4.01425314, -0.01281738]), + 'Velocity': array([-7.37096846e-01, 5.19839451e-02, 3.81426798e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.59220886, 16.00314713, -0.39764416]), + 'camera_rotation': array([-7.76590395, 4.38285971, -2.73606873]), + 'current_gear_input': False, + 'focus_actor_dist': 2038.0135498046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 492.80651855, -3910.03198242, 16.24060059]), + 'frame': 30915, + 'frame_number': 30915, + 'framesequence': 118792, + 'gaze_dir': array([0.9515686 , 0.30032349, 0.06561279]), + 'gaze_origin': array([-3.00775909, -0.25008929, -0.0953064 ]), + 'gaze_valid': True, + 'gaze_vergence': 1268.19970703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9521637 , 0.29855347, 0.06498718]), + 'left_gaze_origin': array([-2.83326578, 2.59458947, -0.11343995]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1026153564453125, + 'left_pupil_posn': array([ 0.54166198, -0.14083672]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95097351, 0.30209351, 0.0662384 ]), + 'right_gaze_origin': array([-3.18225241, -3.09476805, -0.07717286]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5791778564453125, + 'right_pupil_posn': array([ 0.04094911, -0.22264433]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005951109807938337, + 'throttle_input': 0.21031509339809418, + 'timestamp': 999.2143811769783, + 'timestamp_carla': 999214, + 'timestamp_device': 4152646, + 'timestamp_stream': 999.2143811769783, + 'transform': [array([2.84438205, 8.26446056, 0.01027439]), + array([-6.49209470e-02, -9.64099216e+00, 8.84476863e-03])]} +{'AngularVelocity': array([-0.0129642 , 0.01944039, 0.89696771]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.022703902795910835, + 'FR_Wheel_Angle': -0.023951997980475426, + 'Location': array([ -6.83338737, -21.13764763, 0.17726241]), + 'Rotation': array([-0.09442736, -4.0021677 , -0.0090332 ]), + 'Velocity': array([-8.71238708e-01, 6.23229221e-02, 8.01057788e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.55631638, 16.33779907, -0.33420789]), + 'camera_rotation': array([-7.4935503 , 6.04872704, -2.59791946]), + 'current_gear_input': False, + 'focus_actor_dist': 2362.620849609375, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 619.27050781, -4215.69726562, 16.22583771]), + 'frame': 30916, + 'frame_number': 30916, + 'framesequence': 118798, + 'gaze_dir': array([0.96522522, 0.25380707, 0.06136322]), + 'gaze_origin': array([-2.99902892, -0.22425155, -0.10021592]), + 'gaze_valid': True, + 'gaze_vergence': 173.15020751953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96343994, 0.26252747, 0.05342102]), + 'left_gaze_origin': array([-2.823282 , 2.62094593, -0.11923981]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.06402587890625, + 'left_pupil_posn': array([ 0.50164378, -0.14012074]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9670105 , 0.24508667, 0.06930542]), + 'right_gaze_origin': array([-3.17477584, -3.06944895, -0.08119202]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6131591796875, + 'right_pupil_posn': array([ 0.01030552, -0.22687137]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.007397687062621117, + 'throttle_input': 0.2222171425819397, + 'timestamp': 999.260716278106, + 'timestamp_carla': 999260, + 'timestamp_device': 4152696, + 'timestamp_stream': 999.260716278106, + 'transform': [array([2.8343389 , 8.17811775, 0.01049665]), + array([-6.46955520e-02, -9.61926270e+00, 8.33943207e-03])]} +{'AngularVelocity': array([-0.02127277, -0.01089907, 1.0394572 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.025167595595121384, + 'FR_Wheel_Angle': -0.025150539353489876, + 'Location': array([ -7.05194616, -21.12216949, 0.17740981]), + 'Rotation': array([-0.09383997, -3.9983542 , -0.00518799]), + 'Velocity': array([-1.00197375e+00, 7.09612370e-02, 5.30405028e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.56637001, 17.01780701, -0.32293433]), + 'camera_rotation': array([-7.28436899, 9.4951458 , -2.49015045]), + 'current_gear_input': False, + 'focus_actor_dist': 2178.619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 512.63525391, -4066.05322266, 16.21928406]), + 'frame': 30917, + 'frame_number': 30917, + 'framesequence': 118801, + 'gaze_dir': array([0.97048187, 0.23339844, 0.05932617]), + 'gaze_origin': array([-2.99313688, -0.21207428, -0.09658814]), + 'gaze_valid': True, + 'gaze_vergence': 166.9989013671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96879578, 0.24252319, 0.05104065]), + 'left_gaze_origin': array([-2.81420755, 2.63635421, -0.11547394]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0208587646484375, + 'left_pupil_posn': array([ 0.48294163, -0.13590968]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97216797, 0.22427368, 0.06761169]), + 'right_gaze_origin': array([-3.17206597, -3.06050277, -0.07770234]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.654815673828125, + 'right_pupil_posn': array([-0.00307983, -0.2242769 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00867946445941925, + 'throttle_input': 0.23015183210372925, + 'timestamp': 999.2883596792817, + 'timestamp_carla': 999288, + 'timestamp_device': 4152721, + 'timestamp_stream': 999.2883596792817, + 'transform': [array([2.83414054, 8.12518311, 0.01067028]), + array([-6.46135882e-02, -9.61767101e+00, 7.98445754e-03])]} +{'AngularVelocity': array([-0.01990515, 0.00478356, 0.8280682 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.025133034214377403, + 'FR_Wheel_Angle': -0.0251181460916996, + 'Location': array([ -7.29368925, -21.10509682, 0.17758873]), + 'Rotation': array([-8.92364159e-02, -3.99408054e+00, -1.12914992e-03]), + 'Velocity': array([-1.08082819, 0.07642009, 0.00123946]), + 'brake_input': 0.0, + 'camera_location': array([-7.5662632 , 17.01783562, -0.32294405]), + 'camera_rotation': array([-7.28436899, 9.4951458 , -2.49015045]), + 'current_gear_input': False, + 'focus_actor_dist': 2158.05517578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 585.19055176, -4023.49658203, 16.14495087]), + 'frame': 30918, + 'frame_number': 30918, + 'framesequence': 118805, + 'gaze_dir': array([0.96791077, 0.24299622, 0.06182098]), + 'gaze_origin': array([-2.99399662, -0.21418841, -0.09993897]), + 'gaze_valid': True, + 'gaze_vergence': 159.87265014648438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96458435, 0.25767517, 0.0561676 ]), + 'left_gaze_origin': array([-2.8139801 , 2.63496256, -0.11855927]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9085693359375, + 'left_pupil_posn': array([ 0.48531282, -0.13776696]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97123718, 0.22831726, 0.06747437]), + 'right_gaze_origin': array([-3.1740129 , -3.06333947, -0.08131867]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.70086669921875, + 'right_pupil_posn': array([ 0.00427771, -0.2258147 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.009411908686161041, + 'throttle_input': 0.23015183210372925, + 'timestamp': 999.325974676758, + 'timestamp_carla': 999326, + 'timestamp_device': 4152754, + 'timestamp_stream': 999.325974676758, + 'transform': [array([2.82757497, 8.05376244, 0.01090269]), + array([-6.45521134e-02, -9.60289669e+00, 7.50960084e-03])]} +{'AngularVelocity': array([-0.02226783, -0.00336182, 0.89863044]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.025070827454328537, + 'FR_Wheel_Angle': -0.025056930258870125, + 'Location': array([ -7.55976439, -21.08625221, 0.17778492]), + 'Rotation': array([-8.84441137e-02, -3.99536252e+00, 3.28955450e-03]), + 'Velocity': array([-1.20548320e+00, 8.53917673e-02, 9.06524656e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.58491707, 17.74578476, -0.31518823]), + 'camera_rotation': array([-7.15417862, 13.18362999, -2.58930135]), + 'current_gear_input': False, + 'focus_actor_dist': 2293.1201171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 659.11083984, -4144.16845703, 16.07985687]), + 'frame': 30919, + 'frame_number': 30919, + 'framesequence': 118809, + 'gaze_dir': array([0.92723846, 0.37141418, 0.04660797]), + 'gaze_origin': array([-3.02237177, -0.29914096, -0.11133576]), + 'gaze_valid': True, + 'gaze_vergence': 12.725564956665039, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92758179, 0.37173462, 0.03729248]), + 'left_gaze_origin': array([-2.84678364, 2.53868127, -0.12652132]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09002685546875, + 'left_pupil_posn': array([ 0.609285 , -0.15858591]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92689514, 0.37109375, 0.05592346]), + 'right_gaze_origin': array([-3.19796014, -3.13696313, -0.09615021]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5284271240234375, + 'right_pupil_posn': array([ 0.09616542, -0.2519381 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.010364086367189884, + 'throttle_input': 0.23411917686462402, + 'timestamp': 999.3555560782552, + 'timestamp_carla': 999355, + 'timestamp_device': 4152787, + 'timestamp_stream': 999.3555560782552, + 'transform': [array([2.81716037, 7.99813223, 0.01110891]), + array([-6.45452812e-02, -9.58074570e+00, 7.07421452e-03])]} +{'AngularVelocity': array([-0.02408648, -0.01382403, 0.80195296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0250205360352993, + 'FR_Wheel_Angle': -0.025014745071530342, + 'Location': array([ -7.85613823, -21.0653038 , 0.17800994]), + 'Rotation': array([-0.08566423, -3.99292159, 0.00822632]), + 'Velocity': array([-1.3233006 , 0.0936949 , 0.00144488]), + 'brake_input': 0.0, + 'camera_location': array([-7.58491707, 17.74578476, -0.31518823]), + 'camera_rotation': array([-7.15417862, 13.18362999, -2.58930135]), + 'current_gear_input': False, + 'focus_actor_dist': 2220.822021484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1016.2409668 , -3866.72167969, 15.71404266]), + 'frame': 30920, + 'frame_number': 30920, + 'framesequence': 118814, + 'gaze_dir': array([0.9168396 , 0.39691162, 0.04291534]), + 'gaze_origin': array([-3.02993417, -0.31966326, -0.11142579]), + 'gaze_valid': True, + 'gaze_vergence': 981.5170288085938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.91600037, 0.3989563 , 0.04197693]), + 'left_gaze_origin': array([-2.85502338, 2.51328897, -0.12969819]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0090789794921875, + 'left_pupil_posn': array([ 0.63839126, -0.16766703]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.91767883, 0.39486694, 0.04385376]), + 'right_gaze_origin': array([-3.20484495, -3.15261555, -0.09315339]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6750030517578125, + 'right_pupil_posn': array([ 0.11736131, -0.25066805]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01073030848056078, + 'throttle_input': 0.24205386638641357, + 'timestamp': 999.3936250768602, + 'timestamp_carla': 999393, + 'timestamp_device': 4152829, + 'timestamp_stream': 999.3936250768602, + 'transform': [array([2.80928731, 7.92484093, 0.01131741]), + array([-6.45726025e-02, -9.56310368e+00, 6.67581335e-03])]} +{'AngularVelocity': array([-7.88940160e-05, -4.29068543e-02, 1.71250045e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.99046612, -21.05567169, 0.17778225]), + 'Rotation': array([-0.02044276, -4.00698948, 0.01375289]), + 'Velocity': array([ 0.22878692, -0.01621816, -0.00038661]), + 'brake_input': 0.0, + 'camera_location': array([-7.64566612, 18.47642899, -0.32553318]), + 'camera_rotation': array([-7.25345564, 16.89203453, -2.31359816]), + 'current_gear_input': False, + 'focus_actor_dist': 2170.467041015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1036.54272461, -3795.35595703, 15.68602753]), + 'frame': 30921, + 'frame_number': 30921, + 'framesequence': 118817, + 'gaze_dir': array([0.92217255, 0.38408661, 0.04316711]), + 'gaze_origin': array([-3.02377868, -0.30241549, -0.10818864]), + 'gaze_valid': True, + 'gaze_vergence': 2.083735227584839, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92294312, 0.38380432, 0.02919006]), + 'left_gaze_origin': array([-2.84929657, 2.53435683, -0.12653047]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.018768310546875, + 'left_pupil_posn': array([ 0.61802244, -0.15944171]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92140198, 0.3843689 , 0.05714417]), + 'right_gaze_origin': array([-3.19826078, -3.13918781, -0.0898468 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.74945068359375, + 'right_pupil_posn': array([ 0.10200727, -0.25111318]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011096530593931675, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.4239845760167, + 'timestamp_carla': 999424, + 'timestamp_device': 4152854, + 'timestamp_stream': 999.4239845760167, + 'transform': [array([2.80274129, 7.8653512 , 0.0112401 ]), + array([-6.45111352e-02, -9.54839134e+00, 6.94339070e-03])]} +{'AngularVelocity': array([7.79897999e-03, 9.81857851e-02, 1.75256773e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.023071974515914917, + 'FR_Wheel_Angle': -0.023066828027367592, + 'Location': array([ -7.95339584, -21.05832672, 0.17805476]), + 'Rotation': array([-0.07183993, -3.99939108, 0.01320832]), + 'Velocity': array([ 6.80896919e-05, -2.97458541e-06, 9.05419947e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.64566612, 18.47642899, -0.32553318]), + 'camera_rotation': array([-7.25345564, 16.89203453, -2.31359816]), + 'current_gear_input': False, + 'focus_actor_dist': 2006.11572265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1019.35974121, -3607.13598633, 15.7011795 ]), + 'frame': 30922, + 'frame_number': 30922, + 'framesequence': 118821, + 'gaze_dir': array([0.93590546, 0.34902954, 0.04473114]), + 'gaze_origin': array([-3.01510859, -0.28300476, -0.10512848]), + 'gaze_valid': True, + 'gaze_vergence': 17.748857498168945, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93722534, 0.34741211, 0.02975464]), + 'left_gaze_origin': array([-2.83984232, 2.55679011, -0.12539826]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0589447021484375, + 'left_pupil_posn': array([ 0.58777237, -0.15421903]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93458557, 0.35064697, 0.05970764]), + 'right_gaze_origin': array([-3.19037485, -3.12279987, -0.08485871]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.745758056640625, + 'right_pupil_posn': array([ 0.07737553, -0.2442528 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011297952383756638, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.4586307778955, + 'timestamp_carla': 999458, + 'timestamp_device': 4152887, + 'timestamp_stream': 999.4586307778955, + 'transform': [array([2.79491377, 7.79650879, 0.01113998]), + array([-6.44838139e-02, -9.53082085e+00, 7.15667708e-03])]} +{'AngularVelocity': array([6.50128524e-04, 7.37398164e-03, 2.34174931e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02307199127972126, + 'FR_Wheel_Angle': -0.023066837340593338, + 'Location': array([ -7.95344782, -21.05832291, 0.17809944]), + 'Rotation': array([-0.07946925, -3.99939132, 0.01309332]), + 'Velocity': array([ 6.90515617e-06, 7.30694956e-06, -1.09901586e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.67056274, 19.08839417, -0.37061569]), + 'camera_rotation': array([-7.29431391, 19.66751099, -2.13833117]), + 'current_gear_input': False, + 'focus_actor_dist': 1953.2933349609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 928.6050415 , -3618.32128906, 15.79440308]), + 'frame': 30923, + 'frame_number': 30923, + 'framesequence': 118825, + 'gaze_dir': array([0.93901825, 0.34072113, 0.04232788]), + 'gaze_origin': array([-3.0114572 , -0.27125627, -0.10407867]), + 'gaze_valid': True, + 'gaze_vergence': 8.985346794128418, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94032288, 0.3394165 , 0.02388 ]), + 'left_gaze_origin': array([-2.8358109 , 2.57138681, -0.12520753]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.141021728515625, + 'left_pupil_posn': array([ 0.5736177 , -0.15268481]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93771362, 0.34202576, 0.06077576]), + 'right_gaze_origin': array([-3.18710351, -3.11389947, -0.08294983]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.75299072265625, + 'right_pupil_posn': array([ 0.06834137, -0.24391472]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011426130309700966, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.4886957779527, + 'timestamp_carla': 999488, + 'timestamp_device': 4152921, + 'timestamp_stream': 999.4886957779527, + 'transform': [array([2.78791428, 7.73572969, 0.01098858]), + array([-6.44496605e-02, -9.51506996e+00, 7.52239395e-03])]} +{'AngularVelocity': array([1.73762150e-04, 2.02096021e-03, 2.34836716e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02307199127972126, + 'FR_Wheel_Angle': -0.023066837340593338, + 'Location': array([ -7.95345402, -21.05832291, 0.17809066]), + 'Rotation': array([-0.08016592, -3.99939132, 0.01307631]), + 'Velocity': array([ 3.28646502e-06, 7.84588883e-06, -4.95325257e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.67056274, 19.08839417, -0.37061569]), + 'camera_rotation': array([-7.29431391, 19.66751099, -2.13833117]), + 'current_gear_input': False, + 'focus_actor_dist': 1807.6993408203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 896.64038086, -3464.36572266, 15.82818604]), + 'frame': 30924, + 'frame_number': 30924, + 'framesequence': 118829, + 'gaze_dir': array([0.94347382, 0.32566071, 0.0585556 ]), + 'gaze_origin': array([-3.00766158, -0.25591663, -0.10084 ]), + 'gaze_valid': True, + 'gaze_vergence': 9.883394241333008, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9442749 , 0.32669067, 0.03988647]), + 'left_gaze_origin': array([-2.83179951, 2.5872376 , -0.12175904]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0277252197265625, + 'left_pupil_posn': array([ 0.55542696, -0.14302075]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94267273, 0.32463074, 0.07722473]), + 'right_gaze_origin': array([-3.18352365, -3.09907079, -0.07992096]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6639404296875, + 'right_pupil_posn': array([ 0.0536629, -0.2348218]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01144444104284048, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.5251741781831, + 'timestamp_carla': 999525, + 'timestamp_device': 4152954, + 'timestamp_stream': 999.5251741781831, + 'transform': [array([2.77929187, 7.66108608, 0.01101704]), + array([-6.45521134e-02, -9.49562740e+00, 7.41558243e-03])]} +{'AngularVelocity': array([ 2.22810704e-05, 4.85057273e-04, -9.27405324e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02307199127972126, + 'FR_Wheel_Angle': -0.023066839203238487, + 'Location': array([ -7.95345545, -21.05832291, 0.17809577]), + 'Rotation': array([-0.08016592, -3.99939132, 0.01307631]), + 'Velocity': array([1.85884994e-06, 3.39299731e-07, 3.78310971e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.70752525, 19.55284882, -0.40467706]), + 'camera_rotation': array([-7.45041084, 21.53014565, -1.73894274]), + 'current_gear_input': False, + 'focus_actor_dist': 2350.335205078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1215.91040039, -3911.85546875, 15.53736877]), + 'frame': 30925, + 'frame_number': 30925, + 'framesequence': 118833, + 'gaze_dir': array([0.94846344, 0.31196594, 0.05528259]), + 'gaze_origin': array([-3.00434947, -0.24800417, -0.0986763 ]), + 'gaze_valid': True, + 'gaze_vergence': 588.3099975585938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94955444, 0.309021 , 0.05328369]), + 'left_gaze_origin': array([-2.82711792, 2.59674835, -0.1215027 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0551910400390625, + 'left_pupil_posn': array([ 0.54465497, -0.14853799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94737244, 0.31491089, 0.05728149]), + 'right_gaze_origin': array([-3.18158126, -3.09275675, -0.07584992]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.5795135498046875, + 'right_pupil_posn': array([ 0.04322231, -0.22607183]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01146275270730257, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.5551725775003, + 'timestamp_carla': 999555, + 'timestamp_device': 4152987, + 'timestamp_stream': 999.5551725775003, + 'transform': [array([2.77677631, 7.59836388, 0.01124662]), + array([-6.47296980e-02, -9.48864365e+00, 6.88865175e-03])]} +{'AngularVelocity': array([-1.98192038e-06, 1.18816242e-04, -3.19073388e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02307199314236641, + 'FR_Wheel_Angle': -0.023066839203238487, + 'Location': array([ -7.9534564 , -21.05832291, 0.17810379]), + 'Rotation': array([-0.08016592, -3.99939132, 0.01307631]), + 'Velocity': array([ 1.26701309e-06, 3.30727772e-07, -3.93415045e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.70752525, 19.55284882, -0.40467706]), + 'camera_rotation': array([-7.45041084, 21.53014565, -1.73894274]), + 'current_gear_input': False, + 'focus_actor_dist': 1987.2730712890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1016.6159668 , -3612.92993164, 15.70399475]), + 'frame': 30926, + 'frame_number': 30926, + 'framesequence': 118837, + 'gaze_dir': array([0.95101166, 0.30493164, 0.05046844]), + 'gaze_origin': array([-3.00214624, -0.24287416, -0.09564362]), + 'gaze_valid': True, + 'gaze_vergence': 5.768585681915283, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95077515, 0.30500793, 0.05441284]), + 'left_gaze_origin': array([-2.82350779, 2.60297704, -0.11779328]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9744415283203125, + 'left_pupil_posn': array([ 0.53625107, -0.14858425]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95124817, 0.30485535, 0.04652405]), + 'right_gaze_origin': array([-3.1807847 , -3.08872533, -0.07349396]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.544586181640625, + 'right_pupil_posn': array([ 0.0390563, -0.2236917]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011572618968784809, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.5928237773478, + 'timestamp_carla': 999592, + 'timestamp_device': 4153021, + 'timestamp_stream': 999.5928237773478, + 'transform': [array([2.76754642, 7.51984596, 0.01159018]), + array([-6.49209470e-02, -9.46777344e+00, 6.21002913e-03])]} +{'AngularVelocity': array([ 1.89307320e-05, -1.22630945e-05, -3.08474182e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.9534564 , -21.05832291, 0.17809406]), + 'Rotation': array([-0.08016592, -3.99939132, 0.01307631]), + 'Velocity': array([ 1.19443985e-06, 2.43932305e-07, -3.28479597e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.7219162 , 19.84762383, -0.42515075]), + 'camera_rotation': array([-7.51489496, 22.37668991, -1.57101703]), + 'current_gear_input': False, + 'focus_actor_dist': 1822.627197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 900.59814453, -3501.35058594, 15.8239212 ]), + 'frame': 30927, + 'frame_number': 30927, + 'framesequence': 118841, + 'gaze_dir': array([0.95249176, 0.2985611 , 0.05953979]), + 'gaze_origin': array([-3.00213337, -0.240403 , -0.09582292]), + 'gaze_valid': True, + 'gaze_vergence': 187.7309112548828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95161438, 0.30270386, 0.05284119]), + 'left_gaze_origin': array([-2.82353687, 2.60737014, -0.11797181]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.106842041015625, + 'left_pupil_posn': array([ 0.52928257, -0.1417712 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95336914, 0.29441833, 0.0662384 ]), + 'right_gaze_origin': array([-3.18072987, -3.08817601, -0.07367402]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.6424407958984375, + 'right_pupil_posn': array([ 0.03775251, -0.22436261]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.011938841082155704, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.623377777636, + 'timestamp_carla': 999623, + 'timestamp_device': 4153054, + 'timestamp_stream': 999.623377777636, + 'transform': [array([2.75975275, 7.45500708, 0.01165756]), + array([-6.49209470e-02, -9.45012856e+00, 6.17947103e-03])]} +{'AngularVelocity': array([-2.03649251e-05, 6.64268964e-06, -2.95152199e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.9534564 , -21.05832291, 0.17809814]), + 'Rotation': array([-0.08016592, -3.99939132, 0.01307631]), + 'Velocity': array([ 1.21491962e-06, 2.78718346e-07, -3.43166670e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.7219162 , 19.84762383, -0.42515075]), + 'camera_rotation': array([-7.51489496, 22.37668991, -1.57101703]), + 'current_gear_input': False, + 'focus_actor_dist': 2033.2010498046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1048.65771484, -3660.88720703, 15.67073822]), + 'frame': 30928, + 'frame_number': 30928, + 'framesequence': 118845, + 'gaze_dir': array([0.98524475, 0.15740967, 0.06363678]), + 'gaze_origin': array([-2.94901133, -0.13051605, -0.10248795]), + 'gaze_valid': True, + 'gaze_vergence': 70.04393005371094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98472595, 0.16798401, 0.04551697]), + 'left_gaze_origin': array([-2.69376397, 2.72684646, -0.14511719]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.99053955078125, + 'left_pupil_posn': array([ 0.3897965 , -0.12630236]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98576355, 0.14683533, 0.08175659]), + 'right_gaze_origin': array([-3.20425892, -2.98787856, -0.0598587 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.754241943359375, + 'right_pupil_posn': array([-0.07904905, -0.21834493]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.012891018763184547, + 'throttle_input': 0.2539559006690979, + 'timestamp': 999.658648878336, + 'timestamp_carla': 999658, + 'timestamp_device': 4153087, + 'timestamp_stream': 999.658648878336, + 'transform': [array([2.75009942, 7.37920904, 0.01180523]), + array([-6.48663044e-02, -9.42830753e+00, 5.89114334e-03])]} +{'AngularVelocity': array([0.00140103, 0.01136103, 0.00295951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22549180686473846, + 'FR_Wheel_Angle': -0.2428635060787201, + 'Location': array([ -7.95173216, -21.05844688, 0.17806652]), + 'Rotation': array([-0.07934631, -3.99942255, 0.01307516]), + 'Velocity': array([ 0.01748603, -0.00116824, -0.00031777]), + 'brake_input': 0.0, + 'camera_location': array([-7.77059078, 19.99064636, -0.44924101]), + 'camera_rotation': array([-7.87759161, 22.45919418, -1.30719769]), + 'current_gear_input': False, + 'focus_actor_dist': 1899.0146484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 740.10083008, -3726.47900391, 15.98751068]), + 'frame': 30929, + 'frame_number': 30929, + 'framesequence': 118849, + 'gaze_dir': array([0.99465179, 0.07062531, 0.07466888]), + 'gaze_origin': array([-2.95094228, -0.05661927, -0.10135499]), + 'gaze_valid': True, + 'gaze_vergence': 281.4443664550781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99432373, 0.07914734, 0.07096863]), + 'left_gaze_origin': array([-2.75035405, 2.79748988, -0.12049561]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9897918701171875, + 'left_pupil_posn': array([ 0.31479967, -0.12045133]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99497986, 0.06210327, 0.07836914]), + 'right_gaze_origin': array([-3.15153074, -2.91072845, -0.08221436]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.640838623046875, + 'right_pupil_posn': array([-0.16341734, -0.21245527]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0142277292907238, + 'throttle_input': 0.23015183210372925, + 'timestamp': 999.6882647760212, + 'timestamp_carla': 999688, + 'timestamp_device': 4153121, + 'timestamp_stream': 999.6882647760212, + 'transform': [array([2.73679566, 7.31590319, 0.01212769]), + array([-6.48116618e-02, -9.39953041e+00, 5.20012993e-03])]} +{'AngularVelocity': array([0.00171085, 0.01291137, 0.00426197]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.29985594749450684, + 'FR_Wheel_Angle': -0.2989996373653412, + 'Location': array([ -7.94802046, -21.0587101 , 0.17811169]), + 'Rotation': array([-0.08044596, -3.9996357 , 0.01306472]), + 'Velocity': array([ 0.0066098 , -0.00036697, 0.00024125]), + 'brake_input': 0.0, + 'camera_location': array([-7.77059078, 19.99064636, -0.44924101]), + 'camera_rotation': array([-7.87759161, 22.45919418, -1.30719769]), + 'current_gear_input': False, + 'focus_actor_dist': 1920.3177490234375, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 608.76342773, -3833.00341797, 16.22582245]), + 'frame': 30930, + 'frame_number': 30930, + 'framesequence': 118853, + 'gaze_dir': array([0.99526978, 0.06482697, 0.07178497]), + 'gaze_origin': array([-2.95272446, -0.05961151, -0.09735642]), + 'gaze_valid': True, + 'gaze_vergence': 331.2620849609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99485779, 0.07304382, 0.0700531 ]), + 'left_gaze_origin': array([-2.77744603, 2.79664183, -0.1074173 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9241180419921875, + 'left_pupil_posn': array([ 0.31413615, -0.11859965]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99568176, 0.05661011, 0.07351685]), + 'right_gaze_origin': array([-3.12800288, -2.91586471, -0.08729554]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7190399169921875, + 'right_pupil_posn': array([-0.16213959, -0.21178818]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015527818351984024, + 'throttle_input': 0.18649576604366302, + 'timestamp': 999.7256614789367, + 'timestamp_carla': 999725, + 'timestamp_device': 4153154, + 'timestamp_stream': 999.7256614789367, + 'transform': [array([2.72437882, 7.23439932, 0.01264545]), + array([-6.47023767e-02, -9.37164402e+00, 4.18849383e-03])]} +{'AngularVelocity': array([0.00168901, 0.01194156, 0.0060501 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.2999354600906372, + 'FR_Wheel_Angle': -0.29904672503471375, + 'Location': array([ -7.94698572, -21.05878067, 0.17810684]), + 'Rotation': array([-0.08044596, -3.9996357 , 0.01306472]), + 'Velocity': array([-7.83616304e-03, 6.97428652e-04, 3.74793999e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.75758076, 19.9815712 , -0.46840164]), + 'camera_rotation': array([-7.83681536, 21.78417397, -1.05062139]), + 'current_gear_input': False, + 'focus_actor_dist': 1829.542236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 559.0501709 , -3762.87158203, 16.17340851]), + 'frame': 30931, + 'frame_number': 30931, + 'framesequence': 118857, + 'gaze_dir': array([0.99514771, 0.06658936, 0.07119751]), + 'gaze_origin': array([-2.96613336, -0.06446152, -0.09493104]), + 'gaze_valid': True, + 'gaze_vergence': 226.8968505859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99420166, 0.07875061, 0.07305908]), + 'left_gaze_origin': array([-2.79413772, 2.79156804, -0.10389253]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9291534423828125, + 'left_pupil_posn': array([ 0.31709278, -0.12077105]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99609375, 0.0544281 , 0.06933594]), + 'right_gaze_origin': array([-3.13812876, -2.92049122, -0.08596955]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7596282958984375, + 'right_pupil_posn': array([-0.15694612, -0.21192896]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.017688529565930367, + 'throttle_input': 0.13888761401176453, + 'timestamp': 999.754996675998, + 'timestamp_carla': 999755, + 'timestamp_device': 4153187, + 'timestamp_stream': 999.754996675998, + 'transform': [array([2.71767378, 7.16947746, 0.01316891]), + array([-6.45794347e-02, -9.35557556e+00, 3.14491475e-03])]} +{'AngularVelocity': array([0.00169446, 0.01028867, 0.00790315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.29983067512512207, + 'FR_Wheel_Angle': -0.29895344376564026, + 'Location': array([ -7.95001936, -21.05855751, 0.17810665]), + 'Rotation': array([-0.08044596, -3.9996357 , 0.01306472]), + 'Velocity': array([-0.02656771, 0.00207298, 0.00023973]), + 'brake_input': 0.0, + 'camera_location': array([-7.75758076, 19.9815712 , -0.46840164]), + 'camera_rotation': array([-7.83681536, 21.78417397, -1.05062139]), + 'current_gear_input': False, + 'focus_actor_dist': 1825.8343505859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 542.56433105, -3775.39990234, 16.19026947]), + 'frame': 30932, + 'frame_number': 30932, + 'framesequence': 118861, + 'gaze_dir': array([0.99459076, 0.07579803, 0.06877899]), + 'gaze_origin': array([-2.94759679, -0.06664353, -0.10063095]), + 'gaze_valid': True, + 'gaze_vergence': 150.6528778076172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99391174, 0.09135437, 0.06150818]), + 'left_gaze_origin': array([-2.73538065, 2.79156947, -0.12528992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9531402587890625, + 'left_pupil_posn': array([ 0.31788599, -0.12178326]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99526978, 0.0602417 , 0.0760498 ]), + 'right_gaze_origin': array([-3.15981317, -2.92485666, -0.07597199]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7430877685546875, + 'right_pupil_posn': array([-0.14949858, -0.213503 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.019391462206840515, + 'throttle_input': 0.09919890016317368, + 'timestamp': 999.7917454764247, + 'timestamp_carla': 999791, + 'timestamp_device': 4153221, + 'timestamp_stream': 999.7917454764247, + 'transform': [array([2.70213747, 7.08895731, 0.01394553]), + array([-6.44291714e-02, -9.32099819e+00, 1.66156248e-03])]} +{'AngularVelocity': array([0.00145287, 0.00903014, 0.00979533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.29973411560058594, + 'FR_Wheel_Angle': -0.2988545894622803, + 'Location': array([ -7.95712852, -21.0580368 , 0.17809276]), + 'Rotation': array([-0.08032302, -3.99911737, 0.01307033]), + 'Velocity': array([-4.20825742e-02, 3.22176469e-03, -4.24766513e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.72969055, 19.92254066, -0.45915174]), + 'camera_rotation': array([-7.80553961, 20.77252388, -0.99812335]), + 'current_gear_input': False, + 'focus_actor_dist': 1765.905517578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 531.35345459, -3720.63378906, 16.20211792]), + 'frame': 30933, + 'frame_number': 30933, + 'framesequence': 118865, + 'gaze_dir': array([0.99441528, 0.07839203, 0.06964874]), + 'gaze_origin': array([-2.94458723, -0.07098771, -0.10290605]), + 'gaze_valid': True, + 'gaze_vergence': 244.5973663330078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99365234, 0.08969116, 0.06782532]), + 'left_gaze_origin': array([-2.71427917, 2.78775811, -0.13440552]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8916778564453125, + 'left_pupil_posn': array([ 0.32230651, -0.12532902]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99517822, 0.0670929 , 0.07147217]), + 'right_gaze_origin': array([-3.17489505, -2.92973351, -0.07140656]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7199554443359375, + 'right_pupil_posn': array([-0.1466037 , -0.21107495]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.021185949444770813, + 'throttle_input': 0.0634927898645401, + 'timestamp': 999.8201161772013, + 'timestamp_carla': 999820, + 'timestamp_device': 4153254, + 'timestamp_stream': 999.8201161772013, + 'transform': [array([2.68500233, 7.02757549, 0.01467996]), + array([-6.43950179e-02, -9.28390980e+00, 2.29993762e-04])]} +{'AngularVelocity': array([ 0.00628892, -0.00557044, -0.86376327]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.3041345477104187, + 'FR_Wheel_Angle': -0.3029401898384094, + 'Location': array([ -7.87889338, -21.06376266, 0.17788269]), + 'Rotation': array([-0.04889732, -3.99731541, 0.01319163]), + 'Velocity': array([ 7.61394322e-01, -5.47025129e-02, 7.67564779e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.72969055, 19.92254066, -0.45915174]), + 'camera_rotation': array([-7.80553961, 20.77252388, -0.99812335]), + 'current_gear_input': False, + 'focus_actor_dist': 1803.92529296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 525.38562012, -3774.54931641, 16.20793152]), + 'frame': 30934, + 'frame_number': 30934, + 'framesequence': 118869, + 'gaze_dir': array([0.99417877, 0.0850296 , 0.06326294]), + 'gaze_origin': array([-2.95778513, -0.07709503, -0.0989441 ]), + 'gaze_valid': True, + 'gaze_vergence': 107.20807647705078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99389648, 0.09840393, 0.04977417]), + 'left_gaze_origin': array([-2.71702433, 2.78305817, -0.13722688]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.037353515625, + 'left_pupil_posn': array([ 0.32706296, -0.12625778]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99446106, 0.07165527, 0.07675171]), + 'right_gaze_origin': array([-3.19854617, -2.93724823, -0.06066132]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7675018310546875, + 'right_pupil_posn': array([-0.13838685, -0.21493053]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.022632528096437454, + 'throttle_input': 0.051590751856565475, + 'timestamp': 999.8591640777886, + 'timestamp_carla': 999859, + 'timestamp_device': 4153287, + 'timestamp_stream': 999.8591640777886, + 'transform': [array([2.66541243, 6.94262934, 0.01589764]), + array([-6.45179600e-02, -9.24048710e+00, -2.16585863e-03])]} diff --git a/PythonAPI/data/trials/trial6.txt b/PythonAPI/data/trials/trial6.txt new file mode 100644 index 0000000..0c0c636 --- /dev/null +++ b/PythonAPI/data/trials/trial6.txt @@ -0,0 +1,7614 @@ +{'AngularVelocity': array([-4.97397734e-04, -1.99196475e-05, -7.02933767e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.68211842, -13.66109943, 0.17034112]), + 'Rotation': array([ 2.32226419e-04, -8.84361954e+01, 6.68856949e-02]), + 'Velocity': array([ 5.18086335e-06, 1.15592263e-06, -1.41118668e-04]), + 'brake_input': 0.0, + 'camera_location': array([-10.51125336, 16.26244926, 0.82592756]), + 'camera_rotation': array([-1.30593896, -4.45663118, -0.71348506]), + 'current_gear_input': False, + 'focus_actor_dist': 3975.794921875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -596.3928833 , -5331.49072266, 265.6333313 ]), + 'frame': 34622, + 'frame_number': 34622, + 'framesequence': 132464, + 'gaze_dir': array([ 0.99784851, -0.02418518, 0.05647278]), + 'gaze_origin': array([-2.95171356, 0.0209343 , -0.12997895]), + 'gaze_valid': True, + 'gaze_vergence': 116.57189178466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99781799, -0.00382996, 0.0657959 ]), + 'left_gaze_origin': array([-2.85061646, 2.88516092, -0.11439514]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.95733642578125, + 'left_pupil_posn': array([ 0.22169971, -0.1455543 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99787903, -0.04454041, 0.04714966]), + 'right_gaze_origin': array([-3.05281067, -2.84329247, -0.14556275]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9016876220703125, + 'right_pupil_posn': array([-0.23905593, -0.23780215]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.1257220767438, + 'timestamp_carla': 1113129, + 'timestamp_device': 4266554, + 'timestamp_stream': 1113.1257220767438, + 'transform': [array([1.94244194e+00, 1.49946203e+01, 7.08242413e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([-1.44710924e-04, 9.06331406e-05, -7.39018787e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': -0.01664409041404724, + 'Location': array([ -2.68211842, -13.66110039, 0.17034021]), + 'Rotation': array([ 2.32226419e-04, -8.84361954e+01, 6.68856949e-02]), + 'Velocity': array([ 5.12083989e-06, 8.62497814e-07, -2.74918042e-04]), + 'brake_input': 0.0, + 'camera_location': array([-10.46982765, 16.24117279, 0.79839098]), + 'camera_rotation': array([-1.39968324, -4.52427435, -0.71169615]), + 'current_gear_input': False, + 'focus_actor_dist': 3975.631591796875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -593.63220215, -5331.49023438, 268.18414307]), + 'frame': 34623, + 'frame_number': 34623, + 'framesequence': 132468, + 'gaze_dir': array([ 0.99784851, -0.02144623, 0.05651855]), + 'gaze_origin': array([-2.95091724, 0.01998901, -0.12897111]), + 'gaze_valid': True, + 'gaze_vergence': 107.77555847167969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99783325, 0.00163269, 0.06555176]), + 'left_gaze_origin': array([-2.84521198, 2.88399673, -0.11504669]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.970611572265625, + 'left_pupil_posn': array([ 0.22242022, -0.14488912]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99786377, -0.04452515, 0.04748535]), + 'right_gaze_origin': array([-3.05662251, -2.8440187 , -0.1428955 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.906951904296875, + 'right_pupil_posn': array([-0.23665178, -0.23684216]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.1580217778683, + 'timestamp_carla': 1113162, + 'timestamp_device': 4266588, + 'timestamp_stream': 1113.1580217778683, + 'transform': [array([1.94244194e+00, 1.49946203e+01, 7.09318137e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([ 0.07373849, 0.00205662, -0.00078882]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.01664598286151886, + 'FR_Wheel_Angle': -0.01664488948881626, + 'Location': array([ -2.68200469, -13.66389465, 0.17034963]), + 'Rotation': array([ 4.43962286e-04, -8.84362106e+01, 6.68690652e-02]), + 'Velocity': array([-5.11443825e-04, 2.69267634e-02, -7.20691678e-05]), + 'brake_input': 0.0, + 'camera_location': array([-10.42928696, 16.22769928, 0.76993263]), + 'camera_rotation': array([-1.46999323, -4.5684576 , -0.77787429]), + 'current_gear_input': False, + 'focus_actor_dist': 3974.922607421875, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -587.42834473, -5331.49023438, 261.96032715]), + 'frame': 34624, + 'frame_number': 34624, + 'framesequence': 132472, + 'gaze_dir': array([ 0.99775696, -0.01880646, 0.0586319 ]), + 'gaze_origin': array([-2.95267344, 0.01903534, -0.12765886]), + 'gaze_valid': True, + 'gaze_vergence': 102.60796356201172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99766541, 0.0055542 , 0.06797791]), + 'left_gaze_origin': array([-2.84227157, 2.88307524, -0.11504669]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0152435302734375, + 'left_pupil_posn': array([ 0.22347593, -0.14380884]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99784851, -0.04316711, 0.04928589]), + 'right_gaze_origin': array([-3.06307554, -2.84500432, -0.14027099]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9155731201171875, + 'right_pupil_posn': array([-0.23460406, -0.2355144 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.191775277257, + 'timestamp_carla': 1113195, + 'timestamp_device': 4266621, + 'timestamp_stream': 1113.191775277257, + 'transform': [array([1.94244194e+00, 1.49946203e+01, 7.08883256e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([-0.02291277, -0.00044344, 0.01159113]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.01662675105035305, + 'FR_Wheel_Angle': -0.016598807647824287, + 'Location': array([ -2.68166304, -13.67450333, 0.17033426]), + 'Rotation': array([ 4.38498100e-03, -8.84366455e+01, 6.68760091e-02]), + 'Velocity': array([ 0.00316333, -0.11093913, 0.00033983]), + 'brake_input': 0.0, + 'camera_location': array([-10.38717651, 16.21809006, 0.74936765]), + 'camera_rotation': array([-1.57778049, -4.60769653, -0.83501101]), + 'current_gear_input': False, + 'focus_actor_dist': 3974.4833984375, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -580.35644531, -5331.49072266, 265.49334717]), + 'frame': 34625, + 'frame_number': 34625, + 'framesequence': 132476, + 'gaze_dir': array([ 0.99787903, -0.01873016, 0.05709076]), + 'gaze_origin': array([-2.95962763, 0.01819229, -0.12421494]), + 'gaze_valid': True, + 'gaze_vergence': 109.52195739746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99787903, 0.00488281, 0.06486511]), + 'left_gaze_origin': array([-2.83958769, 2.88267374, -0.11523438]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.02166748046875, + 'left_pupil_posn': array([ 0.22398853, -0.14341533]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99787903, -0.04234314, 0.04931641]), + 'right_gaze_origin': array([-3.07966781, -2.84628916, -0.13319549]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9298095703125, + 'right_pupil_posn': array([-0.23400176, -0.23504794]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.2233765758574, + 'timestamp_carla': 1113227, + 'timestamp_device': 4266654, + 'timestamp_stream': 1113.2233765758574, + 'transform': [array([1.94244194e+00, 1.49946184e+01, 7.10142124e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([0.00606497, 0.00287589, 0.20688954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0165119431912899, + 'FR_Wheel_Angle': -0.01649399846792221, + 'Location': array([ -2.67936945, -13.75452709, 0.17029001]), + 'Rotation': array([ 1.66041888e-02, -8.84476700e+01, 6.68362752e-02]), + 'Velocity': array([ 1.38485543e-02, -5.04181504e-01, -3.35121149e-05]), + 'brake_input': 0.0, + 'camera_location': array([-10.34565544, 16.195755 , 0.73411316]), + 'camera_rotation': array([-1.70930934, -4.62116051, -0.88416302]), + 'current_gear_input': False, + 'focus_actor_dist': 3974.206298828125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -582.9329834 , -5331.49023438, 251.79003906]), + 'frame': 34626, + 'frame_number': 34626, + 'framesequence': 132480, + 'gaze_dir': array([ 0.9979248 , -0.02082825, 0.05606842]), + 'gaze_origin': array([-2.95727396, 0.01626663, -0.12267379]), + 'gaze_valid': True, + 'gaze_vergence': 114.35807037353516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99790955, 0.00106812, 0.06440735]), + 'left_gaze_origin': array([-2.83011484, 2.88169098, -0.11547089]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0456390380859375, + 'left_pupil_posn': array([ 0.22440159, -0.14236867]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99794006, -0.04272461, 0.04772949]), + 'right_gaze_origin': array([-3.08443308, -2.84915781, -0.12987672]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9655303955078125, + 'right_pupil_posn': array([-0.23336655, -0.2339735 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.2591698765755, + 'timestamp_carla': 1113263, + 'timestamp_device': 4266688, + 'timestamp_stream': 1113.2591698765755, + 'transform': [array([1.94244194e+00, 1.49946184e+01, 7.07624434e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([-0.06290815, -0.0031425 , -0.02361544]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016414538025856018, + 'FR_Wheel_Angle': -0.01639874465763569, + 'Location': array([ -2.67496943, -13.91605473, 0.17031808]), + 'Rotation': array([ 1.90562271e-02, -8.84588623e+01, 6.69717565e-02]), + 'Velocity': array([ 2.37096716e-02, -8.93149555e-01, 4.99105430e-04]), + 'brake_input': 0.0, + 'camera_location': array([-10.29375648, 16.18239212, 0.71488655]), + 'camera_rotation': array([-1.87350035, -4.59683752, -0.91805184]), + 'current_gear_input': False, + 'focus_actor_dist': 3974.486572265625, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -592.38989258, -5331.48925781, 238.41830444]), + 'frame': 34627, + 'frame_number': 34627, + 'framesequence': 132484, + 'gaze_dir': array([ 0.99799347, -0.01843262, 0.05597687]), + 'gaze_origin': array([-2.95678329, 0.01613769, -0.12132493]), + 'gaze_valid': True, + 'gaze_vergence': 115.80431365966797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99787903, 0.00244141, 0.06497192]), + 'left_gaze_origin': array([-2.82448149, 2.88155365, -0.11571809]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0833740234375, + 'left_pupil_posn': array([ 0.22558153, -0.14176238]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99810791, -0.03930664, 0.04698181]), + 'right_gaze_origin': array([-3.08908558, -2.84927845, -0.12693177]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9658660888671875, + 'right_pupil_posn': array([-0.23279071, -0.23268008]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.290848478675, + 'timestamp_carla': 1113294, + 'timestamp_device': 4266721, + 'timestamp_stream': 1113.290848478675, + 'transform': [array([1.94244194e+00, 1.49946184e+01, 7.09363911e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([-0.05937411, -0.0015585 , -0.00801677]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016297781839966774, + 'FR_Wheel_Angle': -0.016277262941002846, + 'Location': array([ -2.66833615, -14.1654892 , 0.1703629 ]), + 'Rotation': array([ 2.18702648e-02, -8.84628601e+01, 6.69075921e-02]), + 'Velocity': array([ 3.39637138e-02, -1.28403425e+00, 5.05266187e-04]), + 'brake_input': 0.0, + 'camera_location': array([-10.2417841 , 16.1672802 , 0.67811018]), + 'camera_rotation': array([-2.08400679, -4.58307314, -0.90823531]), + 'current_gear_input': False, + 'focus_actor_dist': 3973.32958984375, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -581.29089355, -5331.49023438, 226.71118164]), + 'frame': 34628, + 'frame_number': 34628, + 'framesequence': 132488, + 'gaze_dir': array([ 0.99790955, -0.02239227, 0.05574799]), + 'gaze_origin': array([-2.96994495, 0.01343689, -0.11287003]), + 'gaze_valid': True, + 'gaze_vergence': 119.52210235595703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([9.98123169e-01, 3.20434570e-04, 6.10809326e-02]), + 'left_gaze_origin': array([-2.81577015, 2.87820458, -0.11710968]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1033782958984375, + 'left_pupil_posn': array([ 0.22574353, -0.13995099]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99769592, -0.04510498, 0.05041504]), + 'right_gaze_origin': array([-3.12411976, -2.85133076, -0.10863037]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.994781494140625, + 'right_pupil_posn': array([-0.23213798, -0.22845781]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.3255655765533, + 'timestamp_carla': 1113329, + 'timestamp_device': 4266754, + 'timestamp_stream': 1113.3255655765533, + 'transform': [array([1.94244194e+00, 1.49946184e+01, 7.08150864e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([-0.04081496, 0.00386645, -0.12030222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.2277947962284088, + 'FR_Wheel_Angle': -0.339584082365036, + 'Location': array([ -2.65936875, -14.51002312, 0.17044595]), + 'Rotation': array([ 2.29562651e-02, -8.84711227e+01, 6.73099384e-02]), + 'Velocity': array([ 4.07643691e-02, -1.66803527e+00, -1.31883615e-04]), + 'brake_input': 0.0, + 'camera_location': array([-10.19124222, 16.1622963 , 0.65257621]), + 'camera_rotation': array([-2.27579832, -4.52129936, -0.877092 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3974.0517578125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -596.09094238, -5331.48974609, 211.0032196 ]), + 'frame': 34629, + 'frame_number': 34629, + 'framesequence': 132492, + 'gaze_dir': array([ 0.9912796 , -0.12688446, 0.02047729]), + 'gaze_origin': array([-3.0456903 , 0.09929048, -0.10845795]), + 'gaze_valid': True, + 'gaze_vergence': 87.04823303222656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99415588, -0.10211182, 0.03468323]), + 'left_gaze_origin': array([-3.01959848, 2.96551371, -0.06208343]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.06781005859375, + 'left_pupil_posn': array([ 0.13267517, -0.15774751]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98840332, -0.1516571 , 0.00627136]), + 'right_gaze_origin': array([-3.07178211, -2.76693273, -0.15483247]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1224517822265625, + 'right_pupil_posn': array([-0.32622468, -0.25892162]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.0, + 'timestamp': 1113.358466476202, + 'timestamp_carla': 1113362, + 'timestamp_device': 4266787, + 'timestamp_stream': 1113.358466476202, + 'transform': [array([1.94244194e+00, 1.49946184e+01, 7.08871847e-03]), + array([-0.06582936, -8.43625069, 0.01184333])]} +{'AngularVelocity': array([-0.01233481, 0.00907783, -0.73573387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1815063953399658, + 'FR_Wheel_Angle': -1.278861403465271, + 'Location': array([ -2.65086198, -14.92573547, 0.1706001 ]), + 'Rotation': array([ 1.92269813e-02, -8.85686340e+01, 6.95182905e-02]), + 'Velocity': array([ 2.65821759e-02, -1.92764604e+00, 4.53023909e-04]), + 'brake_input': 0.0, + 'camera_location': array([-10.13510036, 16.16111755, 0.63647658]), + 'camera_rotation': array([-2.44974279, -4.42649746, -0.86705452]), + 'current_gear_input': False, + 'focus_actor_dist': 1857.8658447265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -625.66125488, -3197.31616211, 96.43952179]), + 'frame': 34630, + 'frame_number': 34630, + 'framesequence': 132496, + 'gaze_dir': array([ 0.98574066, -0.16387939, 0.01774597]), + 'gaze_origin': array([-3.01966333, 0.12313691, -0.12140961]), + 'gaze_valid': True, + 'gaze_vergence': 78.54553985595703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99061584, -0.13320923, 0.03038025]), + 'left_gaze_origin': array([-2.86169767, 2.97706318, -0.1183487 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.16241455078125, + 'left_pupil_posn': array([ 0.10937464, -0.16604269]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98086548, -0.19454956, 0.00511169]), + 'right_gaze_origin': array([-3.17762947, -2.73078918, -0.12447053]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0002288818359375, + 'right_pupil_posn': array([-0.36358941, -0.26029825]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1113.3905130773783, + 'timestamp_carla': 1113394, + 'timestamp_device': 4266821, + 'timestamp_stream': 1113.3905130773783, + 'transform': [array([1.94246268e+00, 1.49940948e+01, 6.90139737e-03]), + array([-0.0657474 , -8.43625069, 0.01223008])]} +{'AngularVelocity': array([-0.01761805, 0.01250776, -1.38112879]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.3289830684661865, + 'FR_Wheel_Angle': -2.486154794692993, + 'Location': array([ -2.64652348, -15.32197857, 0.17073785]), + 'Rotation': array([ 1.39472457e-02, -8.87774658e+01, 7.10843801e-02]), + 'Velocity': array([ 3.21504800e-03, -2.03668571e+00, 4.38890449e-04]), + 'brake_input': 0.0, + 'camera_location': array([-10.0764637 , 16.15729713, 0.60388225]), + 'camera_rotation': array([-2.6630702 , -4.37972498, -0.88857794]), + 'current_gear_input': False, + 'focus_actor_dist': 1871.2186279296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -693.58996582, -3197.16845703, 84.90955353]), + 'frame': 34631, + 'frame_number': 34631, + 'framesequence': 132500, + 'gaze_dir': array([ 0.98517609, -0.16628265, 0.02639771]), + 'gaze_origin': array([-2.95846343, 0.12424546, -0.14202347]), + 'gaze_valid': True, + 'gaze_vergence': 68.5448989868164, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98886108, -0.14118958, 0.04676819]), + 'left_gaze_origin': array([-2.8637805 , 2.98117375, -0.1156952 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.257843017578125, + 'left_pupil_posn': array([ 0.10776961, -0.16439831]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98149109, -0.19137573, 0.00602722]), + 'right_gaze_origin': array([-3.05314636, -2.73268294, -0.16835175]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.097198486328125, + 'right_pupil_posn': array([-0.36358941, -0.26029825]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.1111009418964386, + 'timestamp': 1113.4231981784105, + 'timestamp_carla': 1113427, + 'timestamp_device': 4266854, + 'timestamp_stream': 1113.4231981784105, + 'transform': [array([1.94248223e+00, 1.49936152e+01, 6.90254197e-03]), + array([-0.0657474 , -8.43625069, 0.01223008])]} +{'AngularVelocity': array([ 7.13921501e-04, 5.72709087e-03, -2.31139135e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6915271282196045, + 'FR_Wheel_Angle': -3.6736724376678467, + 'Location': array([ -2.64850307, -15.79111576, 0.17095137]), + 'Rotation': array([ 6.72773598e-03, -8.92194672e+01, 7.25941584e-02]), + 'Velocity': array([-4.03036438e-02, -2.01328397e+00, 1.27505779e-03]), + 'brake_input': 0.0, + 'camera_location': array([-10.01269341, 16.14946938, 0.53464323]), + 'camera_rotation': array([-2.98968983, -4.35409498, -0.88296705]), + 'current_gear_input': False, + 'focus_actor_dist': 1871.5338134765625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -696.87719727, -3197.16845703, 94.05027771]), + 'frame': 34632, + 'frame_number': 34632, + 'framesequence': 132504, + 'gaze_dir': array([ 0.98535919, -0.16516113, 0.03178406]), + 'gaze_origin': array([-2.95264673, 0.12528686, -0.1370392 ]), + 'gaze_valid': True, + 'gaze_vergence': 80.84652709960938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98832703, -0.14408875, 0.0491333 ]), + 'left_gaze_origin': array([-2.86765909, 2.98419499, -0.10947113]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1513824462890625, + 'left_pupil_posn': array([ 0.10742569, -0.15792799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98239136, -0.18623352, 0.01443481]), + 'right_gaze_origin': array([-3.03763437, -2.73362136, -0.16460724]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1708526611328125, + 'right_pupil_posn': array([-0.36342651, -0.25405288]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.13888761401176453, + 'timestamp': 1113.4596876762807, + 'timestamp_carla': 1113463, + 'timestamp_device': 4266887, + 'timestamp_stream': 1113.4596876762807, + 'transform': [array([1.94250572e+00, 1.49930296e+01, 6.87210076e-03]), + array([-0.0657474 , -8.43625069, 0.01223008])]} +{'AngularVelocity': array([ 0.00754711, -0.01066034, -2.4550097 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.032340049743652, + 'FR_Wheel_Angle': -3.8824853897094727, + 'Location': array([ -2.65797901, -16.23675346, 0.17115812]), + 'Rotation': array([ 3.62000021e-04, -8.97854919e+01, 7.08889291e-02]), + 'Velocity': array([-6.59635141e-02, -1.86078811e+00, 6.74896233e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.95592499, 16.14004517, 0.48250756]), + 'camera_rotation': array([-3.3126142 , -4.43702126, -0.85330445]), + 'current_gear_input': False, + 'focus_actor_dist': 1870.794189453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -693.9296875 , -3197.16845703, 93.62176514]), + 'frame': 34633, + 'frame_number': 34633, + 'framesequence': 132508, + 'gaze_dir': array([ 0.98583221, -0.16334534, 0.0296402 ]), + 'gaze_origin': array([-2.96990657, 0.1257599 , -0.12895203]), + 'gaze_valid': True, + 'gaze_vergence': 102.8084945678711, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98875427, -0.14343262, 0.04205322]), + 'left_gaze_origin': array([-2.8695848 , 2.98517466, -0.10699616]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1725311279296875, + 'left_pupil_posn': array([ 0.10781217, -0.15568125]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98291016, -0.18325806, 0.01722717]), + 'right_gaze_origin': array([-3.07022882, -2.73365498, -0.1509079 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2081756591796875, + 'right_pupil_posn': array([-0.36361384, -0.25351381]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.14682230353355408, + 'timestamp': 1113.4900377765298, + 'timestamp_carla': 1113494, + 'timestamp_device': 4266921, + 'timestamp_stream': 1113.4900377765298, + 'transform': [array([1.94252777e+00, 1.49927073e+01, 6.99317921e-03]), + array([-0.06578155, -8.43627167, 0.01204896])]} +{'AngularVelocity': array([ 0.00482222, -0.00659454, -2.20372081]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.005914211273193, + 'FR_Wheel_Angle': -3.8581619262695312, + 'Location': array([ -2.67371821, -16.70890427, 0.17136171]), + 'Rotation': array([-2.11052829e-03, -9.04073715e+01, 6.82697147e-02]), + 'Velocity': array([-7.76139796e-02, -1.67859399e+00, 9.69657849e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.87991428, 16.1288929 , 0.45989493]), + 'camera_rotation': array([-3.4634316 , -4.55075216, -0.89315712]), + 'current_gear_input': False, + 'focus_actor_dist': 1870.8880615234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -693.10778809, -3197.16845703, 79.35351562]), + 'frame': 34634, + 'frame_number': 34634, + 'framesequence': 132512, + 'gaze_dir': array([ 0.98581696, -0.16313171, 0.03046417]), + 'gaze_origin': array([-2.97541142, 0.12482759, -0.12640229]), + 'gaze_valid': True, + 'gaze_vergence': 95.75470733642578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98873901, -0.14289856, 0.04434204]), + 'left_gaze_origin': array([-2.87354755, 2.98523569, -0.10431214]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.123260498046875, + 'left_pupil_posn': array([ 0.10770321, -0.1548053 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9828949 , -0.18336487, 0.0165863 ]), + 'right_gaze_origin': array([-3.07727528, -2.73558044, -0.14849244]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16473388671875, + 'right_pupil_posn': array([-0.36219424, -0.25250864]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.14682230353355408, + 'timestamp': 1113.523589976132, + 'timestamp_carla': 1113527, + 'timestamp_device': 4266954, + 'timestamp_stream': 1113.523589976132, + 'transform': [array([1.94254661e+00, 1.49922686e+01, 6.98924996e-03]), + array([-0.06578155, -8.43627167, 0.01204896])]} +{'AngularVelocity': array([-0.00269046, -0.00280434, -2.00651097]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.016353607177734, + 'FR_Wheel_Angle': -3.8677279949188232, + 'Location': array([ -2.68970394, -17.08075714, 0.17151159]), + 'Rotation': array([-2.28811335e-03, -9.08952026e+01, 6.72188997e-02]), + 'Velocity': array([-8.35774317e-02, -1.52113700e+00, 6.69536588e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.81376934, 16.10491371, 0.44274604]), + 'camera_rotation': array([-3.50717211, -4.74388552, -0.99801749]), + 'current_gear_input': False, + 'focus_actor_dist': 1871.6343994140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -696.56665039, -3197.16845703, 75.79598999]), + 'frame': 34635, + 'frame_number': 34635, + 'framesequence': 132516, + 'gaze_dir': array([ 0.985466 , -0.16426849, 0.03650665]), + 'gaze_origin': array([-2.97559595, 0.12421189, -0.12671509]), + 'gaze_valid': True, + 'gaze_vergence': 103.1490249633789, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98815918, -0.14526367, 0.04931641]), + 'left_gaze_origin': array([-2.87786865, 2.98523569, -0.10266114]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.099029541015625, + 'left_pupil_posn': array([ 0.10770321, -0.15204537]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98277283, -0.18327332, 0.0236969 ]), + 'right_gaze_origin': array([-3.07332325, -2.73681188, -0.15076905]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1417388916015625, + 'right_pupil_posn': array([-0.36211687, -0.25154257]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.14682230353355408, + 'timestamp': 1113.5571349784732, + 'timestamp_carla': 1113561, + 'timestamp_device': 4266987, + 'timestamp_stream': 1113.5571349784732, + 'transform': [array([1.94256556e+00, 1.49918194e+01, 6.98711397e-03]), + array([-0.06578155, -8.43627167, 0.01204896])]} +{'AngularVelocity': array([-0.00461636, -0.00185754, -1.85306394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.0270466804504395, + 'FR_Wheel_Angle': -3.87923264503479, + 'Location': array([ -2.70447874, -17.3718853 , 0.171624 ]), + 'Rotation': array([-1.55728310e-03, -9.12783279e+01, 6.66566491e-02]), + 'Velocity': array([-8.63754898e-02, -1.39742076e+00, 8.41612811e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.76441956, 16.0876503 , 0.42516264]), + 'camera_rotation': array([-3.65400076, -4.90169191, -0.89695799]), + 'current_gear_input': False, + 'focus_actor_dist': 1873.1851806640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -705.46008301, -3197.16796875, 85.07672119]), + 'frame': 34636, + 'frame_number': 34636, + 'framesequence': 132520, + 'gaze_dir': array([ 0.98562622, -0.16304016, 0.03829956]), + 'gaze_origin': array([-2.97423649, 0.12078476, -0.12734833]), + 'gaze_valid': True, + 'gaze_vergence': 107.74468994140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98815918, -0.14483643, 0.05059814]), + 'left_gaze_origin': array([-2.88828135, 2.98523569, -0.09928741]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0822906494140625, + 'left_pupil_posn': array([ 0.10840821, -0.15092802]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98309326, -0.1812439 , 0.02600098]), + 'right_gaze_origin': array([-3.06019139, -2.74366617, -0.15540925]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.113800048828125, + 'right_pupil_posn': array([-0.35705829, -0.25163889]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.14682230353355408, + 'timestamp': 1113.5918177776039, + 'timestamp_carla': 1113596, + 'timestamp_device': 4267021, + 'timestamp_stream': 1113.5918177776039, + 'transform': [array([1.94258690e+00, 1.49913006e+01, 6.97685219e-03]), + array([-0.06578155, -8.43627167, 0.01204896])]} +{'AngularVelocity': array([-0.02764742, 0.01029063, -1.64149034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.8904623985290527, + 'FR_Wheel_Angle': -3.660433053970337, + 'Location': array([ -2.72177386, -17.67303467, 0.17174211]), + 'Rotation': array([-2.47252826e-03, -9.16772461e+01, 6.57967925e-02]), + 'Velocity': array([-8.38022530e-02, -1.21350169e+00, 2.32820501e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.72109318, 16.06443596, 0.39097077]), + 'camera_rotation': array([-3.87124181, -5.0602417 , -0.90034652]), + 'current_gear_input': False, + 'focus_actor_dist': 1873.7305908203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -708.27850342, -3197.16748047, 84.2354126 ]), + 'frame': 34637, + 'frame_number': 34637, + 'framesequence': 132524, + 'gaze_dir': array([ 0.985466 , -0.16264343, 0.04288483]), + 'gaze_origin': array([-2.97977543, 0.1203003 , -0.12593842]), + 'gaze_valid': True, + 'gaze_vergence': 94.25234985351562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98770142, -0.1451416 , 0.05795288]), + 'left_gaze_origin': array([-2.89742446, 2.98505402, -0.0971695 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.039154052734375, + 'left_pupil_posn': array([ 0.10890865, -0.1505754 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98323059, -0.18014526, 0.02781677]), + 'right_gaze_origin': array([-3.06212616, -2.74445367, -0.15470734]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1009368896484375, + 'right_pupil_posn': array([-0.35660344, -0.24894655]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.14682230353355408, + 'timestamp': 1113.6230727769434, + 'timestamp_carla': 1113627, + 'timestamp_device': 4267054, + 'timestamp_stream': 1113.6230727769434, + 'transform': [array([1.94260550e+00, 1.49908628e+01, 6.99584931e-03]), + array([-0.06578155, -8.43627167, 0.01204896])]} +{'AngularVelocity': array([-0.06961899, 0.00570121, -1.3012054 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.4603893756866455, + 'FR_Wheel_Angle': -2.1418673992156982, + 'Location': array([ -2.74071813, -17.99038506, 0.17180857]), + 'Rotation': array([ 1.13449432e-02, -9.20350418e+01, 6.50743395e-02]), + 'Velocity': array([-8.82026628e-02, -1.39465892e+00, 5.38187043e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.70378494, 16.04984856, 0.34684041]), + 'camera_rotation': array([-4.06237078, -5.22437429, -0.94540912]), + 'current_gear_input': False, + 'focus_actor_dist': 1874.63720703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -712.96032715, -3197.16748047, 85.77412415]), + 'frame': 34638, + 'frame_number': 34638, + 'framesequence': 132528, + 'gaze_dir': array([ 0.98571777, -0.16077423, 0.04497528]), + 'gaze_origin': array([-2.98326826, 0.11982117, -0.12459413]), + 'gaze_valid': True, + 'gaze_vergence': 101.73870849609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98776245, -0.1443634 , 0.05891418]), + 'left_gaze_origin': array([-2.90902734, 2.98452473, -0.09307862]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0187225341796875, + 'left_pupil_posn': array([ 0.11028278, -0.14884937]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9836731 , -0.17718506, 0.03103638]), + 'right_gaze_origin': array([-3.05750895, -2.74488235, -0.15610963]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0992431640625, + 'right_pupil_posn': array([-0.35597032, -0.24865937]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.14682230353355408, + 'timestamp': 1113.6576704792678, + 'timestamp_carla': 1113661, + 'timestamp_device': 4267087, + 'timestamp_stream': 1113.6576704792678, + 'transform': [array([1.94262993e+00, 1.49902086e+01, 6.98223105e-03]), + array([-0.06578155, -8.43627167, 0.01204896])]} +{'AngularVelocity': array([-4.40251715e-02, -1.28600892e-04, -6.15071058e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.75238037109375, + 'FR_Wheel_Angle': -0.5626813769340515, + 'Location': array([ -2.75948763, -18.35164642, 0.17187418]), + 'Rotation': array([ 2.41310578e-02, -9.22456589e+01, 6.33215830e-02]), + 'Velocity': array([-8.88687521e-02, -1.78572536e+00, 5.27772878e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.67050171, 16.03899384, 0.31539434]), + 'camera_rotation': array([-4.14319944, -5.30938864, -0.90524077]), + 'current_gear_input': False, + 'focus_actor_dist': 1875.0892333984375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -714.94604492, -3197.16796875, 83.26152039]), + 'frame': 34639, + 'frame_number': 34639, + 'framesequence': 132532, + 'gaze_dir': array([ 0.98632812, -0.15727997, 0.04670715]), + 'gaze_origin': array([-2.98340774, 0.11913682, -0.12183992]), + 'gaze_valid': True, + 'gaze_vergence': 168.5334014892578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98797607, -0.14476013, 0.05415344]), + 'left_gaze_origin': array([-2.92110467, 2.98437214, -0.08759156]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9969329833984375, + 'left_pupil_posn': array([ 0.11292326, -0.14453518]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98468018, -0.1697998 , 0.03926086]), + 'right_gaze_origin': array([-3.04571104, -2.74609852, -0.15608826]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0988006591796875, + 'right_pupil_posn': array([-0.35507357, -0.24799037]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.15475699305534363, + 'timestamp': 1113.6905591785908, + 'timestamp_carla': 1113694, + 'timestamp_device': 4267121, + 'timestamp_stream': 1113.6905591785908, + 'transform': [array([1.94265497e+00, 1.49895382e+01, 6.98749535e-03]), + array([-0.06578155, -8.43627167, 0.01204896])]} +{'AngularVelocity': array([-0.03404271, 0.00210624, 0.13557452]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2608390152454376, + 'FR_Wheel_Angle': 0.30277687311172485, + 'Location': array([ -2.77961946, -18.82463646, 0.1720167 ]), + 'Rotation': array([ 3.18969823e-02, -9.22891312e+01, 6.20216355e-02]), + 'Velocity': array([-8.85922685e-02, -2.28852797e+00, 1.08113769e-03]), + 'brake_input': 0.0, + 'camera_location': array([-9.64541817, 16.04091644, 0.27966031]), + 'camera_rotation': array([-4.23504496, -5.34302855, -0.88513291]), + 'current_gear_input': False, + 'focus_actor_dist': 1874.069091796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -710.92346191, -3197.16796875, 84.12776947]), + 'frame': 34640, + 'frame_number': 34640, + 'framesequence': 132536, + 'gaze_dir': array([ 0.99230957, -0.1088562 , 0.05562592]), + 'gaze_origin': array([-3.09783173, 0.09677048, -0.08231964]), + 'gaze_valid': True, + 'gaze_vergence': 51.97677230834961, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99195862, -0.10296631, 0.07341003]), + 'left_gaze_origin': array([-3.15802169, 2.97235727, -0.00952911]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9796600341796875, + 'left_pupil_posn': array([ 0.14152873, -0.13738358]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99266052, -0.11474609, 0.0378418 ]), + 'right_gaze_origin': array([-3.03764224, -2.77881646, -0.15511018]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0203857421875, + 'right_pupil_posn': array([-0.31769174, -0.238855 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.18252842128276825, + 'timestamp': 1113.724147476256, + 'timestamp_carla': 1113728, + 'timestamp_device': 4267154, + 'timestamp_stream': 1113.724147476256, + 'transform': [array([1.94270408e+00, 1.49886951e+01, 6.90649031e-03]), + array([-0.0657474 , -8.43630219, 0.01220409])]} +{'AngularVelocity': array([-0.00119577, 0.00738091, 0.74254876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.9406958818435669, + 'FR_Wheel_Angle': 1.0689955949783325, + 'Location': array([ -2.80152607, -19.42757225, 0.17219995]), + 'Rotation': array([ 3.65756601e-02, -9.21981354e+01, 6.29465878e-02]), + 'Velocity': array([-9.05091390e-02, -2.87474918e+00, 8.59117485e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.61301804, 16.04274368, 0.25266588]), + 'camera_rotation': array([-4.32467079, -5.32863474, -0.81647474]), + 'current_gear_input': False, + 'focus_actor_dist': 1855.385498046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -619.23706055, -3197.02050781, 98.7766571 ]), + 'frame': 34641, + 'frame_number': 34641, + 'framesequence': 132540, + 'gaze_dir': array([ 0.99441528, -0.08287048, 0.06078339]), + 'gaze_origin': array([-2.94651437, 0.04744416, -0.12216874]), + 'gaze_valid': True, + 'gaze_vergence': 120.70003509521484, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9962616 , -0.05935669, 0.06259155]), + 'left_gaze_origin': array([-2.82359028, 2.90970922, -0.10792085]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1651458740234375, + 'left_pupil_posn': array([ 0.1840266 , -0.13282549]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99256897, -0.10638428, 0.05897522]), + 'right_gaze_origin': array([-3.06943822, -2.814821 , -0.13641664]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.94403076171875, + 'right_pupil_posn': array([-0.27798629, -0.23611617]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.2222171425819397, + 'timestamp': 1113.7574089765549, + 'timestamp_carla': 1113761, + 'timestamp_device': 4267187, + 'timestamp_stream': 1113.7574089765549, + 'transform': [array([1.94274199e+00, 1.49874249e+01, 6.64999010e-03]), + array([-0.06566544, -8.43630219, 0.01270903])]} +{'AngularVelocity': array([ 0.0876406 , -0.04222741, 2.16685057]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.362380027770996, + 'FR_Wheel_Angle': 2.945018768310547, + 'Location': array([ -2.82073355, -20.14383316, 0.17223355]), + 'Rotation': array([ 2.64260005e-02, -9.18883743e+01, 5.90021275e-02]), + 'Velocity': array([-5.23287654e-02, -3.34615493e+00, -3.41396313e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.57940292, 16.05739784, 0.22368576]), + 'camera_rotation': array([-4.42017698, -5.30727291, -0.82813251]), + 'current_gear_input': False, + 'focus_actor_dist': 1848.1328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -569.97839355, -3198.15820312, 106.05201721]), + 'frame': 34642, + 'frame_number': 34642, + 'framesequence': 132544, + 'gaze_dir': array([ 0.99486542, -0.07626343, 0.06279755]), + 'gaze_origin': array([-2.93788695, 0.04834137, -0.12445984]), + 'gaze_valid': True, + 'gaze_vergence': 118.79967498779297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99571228, -0.05709839, 0.07258606]), + 'left_gaze_origin': array([-2.81933308, 2.91130233, -0.10940857]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1847076416015625, + 'left_pupil_posn': array([ 0.18663549, -0.13490665]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99401855, -0.09542847, 0.05300903]), + 'right_gaze_origin': array([-3.05644083, -2.81461954, -0.13951112]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9740447998046875, + 'right_pupil_posn': array([-0.27710837, -0.23196292]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1113.7916636765003, + 'timestamp_carla': 1113795, + 'timestamp_device': 4267221, + 'timestamp_stream': 1113.7916636765003, + 'transform': [array([1.94311643e+00, 1.49844408e+01, 5.54670300e-03]), + array([-0.06528294, -8.43688679, 0.01485464])]} +{'AngularVelocity': array([ 0.12782201, -0.03538629, 6.07824421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.493201732635498, + 'FR_Wheel_Angle': 6.0671067237854, + 'Location': array([ -2.81843734, -21.04572296, 0.17245764]), + 'Rotation': array([-7.50637753e-03, -9.07533569e+01, 4.44467217e-02]), + 'Velocity': array([ 1.24380365e-01, -3.30301404e+00, -1.72977438e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.54523945, 16.07077599, 0.19635352]), + 'camera_rotation': array([-4.54614639, -5.22521973, -0.79363889]), + 'current_gear_input': False, + 'focus_actor_dist': 1845.959228515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -556.91583252, -3198.05957031, 106.78395844]), + 'frame': 34643, + 'frame_number': 34643, + 'framesequence': 132548, + 'gaze_dir': array([ 0.99473572, -0.07643127, 0.06480408]), + 'gaze_origin': array([-2.9399004 , 0.04857025, -0.12334596]), + 'gaze_valid': True, + 'gaze_vergence': 123.39148712158203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99560547, -0.05747986, 0.07383728]), + 'left_gaze_origin': array([-2.82079935, 2.9116838 , -0.10897675]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.156280517578125, + 'left_pupil_posn': array([ 0.18638599, -0.13393211]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99386597, -0.09538269, 0.05577087]), + 'right_gaze_origin': array([-3.05900121, -2.81454325, -0.13771516]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9730377197265625, + 'right_pupil_posn': array([-0.2772882 , -0.23081744]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3055466413497925, + 'timestamp': 1113.8236889764667, + 'timestamp_carla': 1113827, + 'timestamp_device': 4267254, + 'timestamp_stream': 1113.8236889764667, + 'transform': [array([1.94312680e+00, 1.49811659e+01, 5.00946026e-03]), + array([-0.06509853, -8.43671513, 0.01593132])]} +{'AngularVelocity': array([ 0.0869686 , -0.01206828, 8.02117157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.199748039245605, + 'FR_Wheel_Angle': 9.677518844604492, + 'Location': array([ -2.78813887, -21.67728996, 0.17259577]), + 'Rotation': array([-2.89326794e-02, -8.93482285e+01, 4.08948399e-02]), + 'Velocity': array([ 2.60046750e-01, -3.04638124e+00, -7.86209057e-05]), + 'brake_input': 0.0, + 'camera_location': array([-9.50956726, 16.08747864, 0.16855316]), + 'camera_rotation': array([-4.68686199, -5.15206051, -0.78778464]), + 'current_gear_input': False, + 'focus_actor_dist': 1845.234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -554.4854126 , -3197.98925781, 106.5873642 ]), + 'frame': 34644, + 'frame_number': 34644, + 'framesequence': 132553, + 'gaze_dir': array([ 0.99443817, -0.07723999, 0.06825256]), + 'gaze_origin': array([-2.93849039, 0.04955902, -0.12381975]), + 'gaze_valid': True, + 'gaze_vergence': 122.47346496582031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99530029, -0.05810547, 0.07733154]), + 'left_gaze_origin': array([-2.82126188, 2.91333485, -0.10812837]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1504974365234375, + 'left_pupil_posn': array([ 0.18493259, -0.13225865]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99357605, -0.09637451, 0.05917358]), + 'right_gaze_origin': array([-3.05571914, -2.81421661, -0.13951112]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.975860595703125, + 'right_pupil_posn': array([-0.27770418, -0.23018384]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.30951398611068726, + 'timestamp': 1113.8608712777495, + 'timestamp_carla': 1113865, + 'timestamp_device': 4267296, + 'timestamp_stream': 1113.8608712777495, + 'transform': [array([1.93816459e+00, 1.49751244e+01, 3.31703178e-03]), + array([-0.06453846, -8.42654705, 0.01917608])]} +{'AngularVelocity': array([ 0.02048895, 0.0129538 , 11.45461464]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.046382904052734, + 'FR_Wheel_Angle': 14.042353630065918, + 'Location': array([ -2.70272946, -22.44156837, 0.1726235 ]), + 'Rotation': array([-4.39112820e-02, -8.66827698e+01, 3.38244475e-02]), + 'Velocity': array([ 4.83312458e-01, -2.68465090e+00, -5.06458280e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.54870129, 16.12573814, 0.06064842]), + 'camera_rotation': array([-4.7980504 , -5.09632015, -0.72229552]), + 'current_gear_input': False, + 'focus_actor_dist': 1844.670166015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -553.60131836, -3197.93212891, 108.47277832]), + 'frame': 34645, + 'frame_number': 34645, + 'framesequence': 132558, + 'gaze_dir': array([ 0.99472046, -0.07655334, 0.06520844]), + 'gaze_origin': array([-2.93241453, 0.05076142, -0.12311173]), + 'gaze_valid': True, + 'gaze_vergence': 135.87586975097656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99578857, -0.05740356, 0.07131958]), + 'left_gaze_origin': array([-2.8232851 , 2.91521931, -0.1066742 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.12469482421875, + 'left_pupil_posn': array([ 0.18390512, -0.13164079]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99365234, -0.09570312, 0.05909729]), + 'right_gaze_origin': array([-3.04154372, -2.81369638, -0.13954926]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9709930419921875, + 'right_pupil_posn': array([-0.27770418, -0.22952414]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.30951398611068726, + 'timestamp': 1113.9016407765448, + 'timestamp_carla': 1113905, + 'timestamp_device': 4267337, + 'timestamp_stream': 1113.9016407765448, + 'transform': [array([1.93892026e+00, 1.49651318e+01, 2.00843811e-03]), + array([-0.06410132, -8.42750263, 0.02178329])]} +{'AngularVelocity': array([1.13736996e-02, 1.15970932e-02, 1.24438620e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.9310302734375, + 'FR_Wheel_Angle': 16.394468307495117, + 'Location': array([ -2.58602595, -23.04543495, 0.17241323]), + 'Rotation': array([-4.58715484e-02, -8.37841644e+01, 3.88255529e-02]), + 'Velocity': array([ 6.12614036e-01, -2.36084890e+00, -1.03940966e-03]), + 'brake_input': 0.0, + 'camera_location': array([-9.39647388, 16.12893677, 0.05736398]), + 'camera_rotation': array([-5.14241505, -5.06305265, -0.62390912]), + 'current_gear_input': False, + 'focus_actor_dist': 1843.8037109375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -549.85906982, -3198.07861328, 99.45465088]), + 'frame': 34646, + 'frame_number': 34646, + 'framesequence': 132560, + 'gaze_dir': array([ 0.99446106, -0.07737732, 0.06784058]), + 'gaze_origin': array([-2.93429112, 0.05118485, -0.12216949]), + 'gaze_valid': True, + 'gaze_vergence': 131.9057159423828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99560547, -0.05741882, 0.0737915 ]), + 'left_gaze_origin': array([-2.82885909, 2.91601562, -0.10471191]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.112701416015625, + 'left_pupil_posn': array([ 0.18285692, -0.13044441]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99331665, -0.09733582, 0.06188965]), + 'right_gaze_origin': array([-3.03972316, -2.81364608, -0.13962708]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.97235107421875, + 'right_pupil_posn': array([-0.27770996, -0.22836149]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.2856946587562561, + 'timestamp': 1113.926169577986, + 'timestamp_carla': 1113930, + 'timestamp_device': 4267354, + 'timestamp_stream': 1113.926169577986, + 'transform': [array([1.93766439e+00, 1.49579992e+01, 1.23834610e-03]), + array([-0.0639374 , -8.42466545, 0.02330675])]} +{'AngularVelocity': array([-0.02783951, -0.02334046, 12.17166615]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.718545913696289, + 'FR_Wheel_Angle': 17.095874786376953, + 'Location': array([ -2.45405912, -23.55448151, 0.1721929 ]), + 'Rotation': array([-4.42801155e-02, -8.10067596e+01, 4.45081852e-02]), + 'Velocity': array([ 6.90203786e-01, -2.13273096e+00, -1.31756777e-03]), + 'brake_input': 0.0, + 'camera_location': array([-9.39647388, 16.12893677, 0.05736398]), + 'camera_rotation': array([-5.14241505, -5.06305265, -0.62390912]), + 'current_gear_input': False, + 'focus_actor_dist': 1843.08447265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -550.05810547, -3198.33496094, 93.62922668]), + 'frame': 34647, + 'frame_number': 34647, + 'framesequence': 132565, + 'gaze_dir': array([ 0.99423218, -0.07736206, 0.07095337]), + 'gaze_origin': array([-2.9404664 , 0.05172501, -0.11922684]), + 'gaze_valid': True, + 'gaze_vergence': 125.09266662597656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99530029, -0.05697632, 0.07817078]), + 'left_gaze_origin': array([-2.84120965, 2.91675591, -0.09882661]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.093170166015625, + 'left_pupil_posn': array([ 0.18234491, -0.12824118]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99316406, -0.0977478 , 0.06373596]), + 'right_gaze_origin': array([-3.03972316, -2.81330562, -0.13962708]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9888458251953125, + 'right_pupil_posn': array([-0.27775973, -0.22689211]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.2856946587562561, + 'timestamp': 1113.9626851789653, + 'timestamp_carla': 1113966, + 'timestamp_device': 4267396, + 'timestamp_stream': 1113.9626851789653, + 'transform': [array([1.94244528e+00, 1.49447784e+01, 4.83322132e-04]), + array([-0.06350709, -8.43342304, 0.02474355])]} +{'AngularVelocity': array([-0.03196678, 0.020068 , 11.9206152 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.713981628417969, + 'FR_Wheel_Angle': 17.085880279541016, + 'Location': array([ -2.29550147, -24.05712509, 0.17191786]), + 'Rotation': array([-3.57970186e-02, -7.81806641e+01, 4.55230437e-02]), + 'Velocity': array([ 7.94756174e-01, -2.12018442e+00, -8.32290621e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.35867786, 16.13777924, 0.03728621]), + 'camera_rotation': array([-5.27023506, -5.04530764, -0.52731419]), + 'current_gear_input': False, + 'focus_actor_dist': 1841.960693359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -549.83081055, -3198.07788086, 99.45628357]), + 'frame': 34648, + 'frame_number': 34648, + 'framesequence': 132569, + 'gaze_dir': array([ 0.99372864, -0.07802582, 0.07683563]), + 'gaze_origin': array([-2.95076156, 0.05250015, -0.11383286]), + 'gaze_valid': True, + 'gaze_vergence': 114.7457275390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99452209, -0.05801392, 0.0868988 ]), + 'left_gaze_origin': array([-2.86137414, 2.91812301, -0.08982086]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0798187255859375, + 'left_pupil_posn': array([ 0.18150282, -0.12496245]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99293518, -0.09803772, 0.06677246]), + 'right_gaze_origin': array([-3.04014897, -2.81312251, -0.13784486]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.011962890625, + 'right_pupil_posn': array([-0.27817404, -0.22277713]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1113.9929357767105, + 'timestamp_carla': 1113997, + 'timestamp_device': 4267429, + 'timestamp_stream': 1113.9929357767105, + 'transform': [array([ 1.94420958e+00, 1.49322186e+01, -2.60753615e-04]), + array([-0.06318608, -8.43620014, 0.02626873])]} +{'AngularVelocity': array([ 0.01419997, 0.03600594, 11.96759701]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.720641136169434, + 'FR_Wheel_Angle': 17.10137939453125, + 'Location': array([ -2.11266303, -24.55007744, 0.17165589]), + 'Rotation': array([-3.50661911e-02, -7.53634644e+01, 4.42708433e-02]), + 'Velocity': array([ 0.90449804, -2.08374214, -0.00226264]), + 'brake_input': 0.0, + 'camera_location': array([-9.30065536, 16.15335274, 0.02326297]), + 'camera_rotation': array([-5.35779142, -5.01378441, -0.46167681]), + 'current_gear_input': False, + 'focus_actor_dist': 1840.4544677734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -550.38574219, -3197.86572266, 106.52637482]), + 'frame': 34649, + 'frame_number': 34649, + 'framesequence': 132572, + 'gaze_dir': array([0.99679565, 0.01748657, 0.0736618 ]), + 'gaze_origin': array([-2.95558023, -0.00992279, -0.11232986]), + 'gaze_valid': True, + 'gaze_vergence': 97.41170501708984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99739075, 0.03907776, 0.06048584]), + 'left_gaze_origin': array([-2.73185444, 2.85749221, -0.13762666]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.276275634765625, + 'left_pupil_posn': array([ 0.25226629, -0.12588298]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99620056, -0.00410461, 0.08683777]), + 'right_gaze_origin': array([-3.17930627, -2.87733793, -0.08703309]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.924835205078125, + 'right_pupil_posn': array([-0.20071274, -0.225034 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1114.0246554762125, + 'timestamp_carla': 1114028, + 'timestamp_device': 4267454, + 'timestamp_stream': 1114.0246554762125, + 'transform': [array([ 1.94795585e+00, 1.49174309e+01, -6.55822747e-04]), + array([-0.06301532, -8.44279861, 0.02706894])]} +{'AngularVelocity': array([ 0.02954606, 0.02501775, 11.40242577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.798726081848145, + 'FR_Wheel_Angle': 17.22752571105957, + 'Location': array([ -1.93635476, -24.9640255 , 0.17149805]), + 'Rotation': array([-4.24496233e-02, -7.29490738e+01, 4.69288416e-02]), + 'Velocity': array([ 9.34177756e-01, -1.90858793e+00, -5.97963342e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.25399494, 16.17606354, 0.01715752]), + 'camera_rotation': array([-5.49306345, -4.94817495, -0.44749424]), + 'current_gear_input': False, + 'focus_actor_dist': 3959.147705078125, + 'focus_actor_name': 'SM_Shop_70', + 'focus_actor_pt': array([ -465.85614014, -5331.49023438, 57.98439789]), + 'frame': 34650, + 'frame_number': 34650, + 'framesequence': 132576, + 'gaze_dir': array([0.9696579 , 0.23503113, 0.06065369]), + 'gaze_origin': array([-2.97968602, -0.17902146, -0.10852814]), + 'gaze_valid': True, + 'gaze_vergence': 92.18551635742188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96354675, 0.26216125, 0.05319214]), + 'left_gaze_origin': array([-2.86329508, 2.66575933, -0.10771942]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2357635498046875, + 'left_pupil_posn': array([ 0.45848095, -0.13979983]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97576904, 0.207901 , 0.06811523]), + 'right_gaze_origin': array([-3.09607697, -3.02380228, -0.10933686]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9780426025390625, + 'right_pupil_posn': array([-0.02285433, -0.23118865]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1114.0580853782594, + 'timestamp_carla': 1114062, + 'timestamp_device': 4267487, + 'timestamp_stream': 1114.0580853782594, + 'transform': [array([ 1.95093071e+00, 1.49002180e+01, -1.11312862e-03]), + array([-0.06294019, -8.44774437, 0.02795799])]} +{'AngularVelocity': array([5.51561359e-03, 3.48197892e-02, 1.03275614e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.992027282714844, + 'FR_Wheel_Angle': 17.516386032104492, + 'Location': array([ -1.73131573, -25.39086151, 0.17122629]), + 'Rotation': array([-4.79479246e-02, -7.03903427e+01, 5.06853350e-02]), + 'Velocity': array([ 0.9255448 , -1.69061685, -0.0018245 ]), + 'brake_input': 0.0, + 'camera_location': array([-9.20834637e+00, 1.61949368e+01, -1.13225384e-02]), + 'camera_rotation': array([-5.67376947, -4.90194988, -0.41041723]), + 'current_gear_input': False, + 'focus_actor_dist': 3857.05712890625, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 387.19528198, -5172.73876953, 16.47200775]), + 'frame': 34651, + 'frame_number': 34651, + 'framesequence': 132580, + 'gaze_dir': array([0.96034241, 0.27185059, 0.05960083]), + 'gaze_origin': array([-2.98728657, -0.2085579 , -0.11080781]), + 'gaze_valid': True, + 'gaze_vergence': 142.61048889160156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95713806, 0.28507996, 0.05090332]), + 'left_gaze_origin': array([-2.87286997, 2.63181639, -0.11127625]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.37188720703125, + 'left_pupil_posn': array([ 0.50103724, -0.14574182]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96354675, 0.25862122, 0.06829834]), + 'right_gaze_origin': array([-3.10170293, -3.04893208, -0.11033936]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.94482421875, + 'right_pupil_posn': array([ 0.00251532, -0.23452687]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1114.0913039781153, + 'timestamp_carla': 1114095, + 'timestamp_device': 4267521, + 'timestamp_stream': 1114.0913039781153, + 'transform': [array([ 1.95500851e+00, 1.48813105e+01, -1.53453823e-03]), + array([-0.06287189, -8.45481396, 0.02878541])]} +{'AngularVelocity': array([2.50280928e-03, 1.47196921e-02, 9.67883205e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.366758346557617, + 'FR_Wheel_Angle': 17.98931121826172, + 'Location': array([ -1.52557981, -25.77253532, 0.17100984]), + 'Rotation': array([-5.04136235e-02, -6.79941406e+01, 5.17807901e-02]), + 'Velocity': array([ 9.10540700e-01, -1.48956788e+00, -7.52449036e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.16433907, 16.20667076, -0.04611004]), + 'camera_rotation': array([-5.84861565, -4.83060312, -0.37403095]), + 'current_gear_input': False, + 'focus_actor_dist': 3504.2958984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 458.11184692, -4800.44384766, 16.35527802]), + 'frame': 34652, + 'frame_number': 34652, + 'framesequence': 132584, + 'gaze_dir': array([0.95983887, 0.27310181, 0.06268311]), + 'gaze_origin': array([-2.98658848, -0.20815735, -0.10888519]), + 'gaze_valid': True, + 'gaze_vergence': 194.0470428466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95658875, 0.28544617, 0.0586853 ]), + 'left_gaze_origin': array([-2.87061477, 2.63534713, -0.11023103]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.292022705078125, + 'left_pupil_posn': array([ 0.4992336 , -0.14480245]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96308899, 0.26075745, 0.06668091]), + 'right_gaze_origin': array([-3.10256195, -3.05166197, -0.10753938]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9417572021484375, + 'right_pupil_posn': array([ 0.00462067, -0.23007703]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1114.1245526783168, + 'timestamp_carla': 1114128, + 'timestamp_device': 4267554, + 'timestamp_stream': 1114.1245526783168, + 'transform': [array([ 1.95999444e+00, 1.48604021e+01, -1.83494564e-03]), + array([-0.06273528, -8.46358109, 0.02937957])]} +{'AngularVelocity': array([2.66867829e-03, 2.54218373e-03, 8.97332668e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.661625862121582, + 'FR_Wheel_Angle': 18.457176208496094, + 'Location': array([ -1.30690539, -26.13723373, 0.17079012]), + 'Rotation': array([-5.16703799e-02, -6.55857315e+01, 5.31820171e-02]), + 'Velocity': array([ 8.79840434e-01, -1.29749978e+00, -9.06496018e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.11379623, 16.22476578, -0.07926384]), + 'camera_rotation': array([-5.99114799, -4.74572659, -0.3312985 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3507.14404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 467.10113525, -4803.26171875, 16.347435 ]), + 'frame': 34653, + 'frame_number': 34653, + 'framesequence': 132588, + 'gaze_dir': array([0.96087646, 0.26876068, 0.06505585]), + 'gaze_origin': array([-2.98649836, -0.20850755, -0.10827331]), + 'gaze_valid': True, + 'gaze_vergence': 175.03805541992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95706177, 0.28315735, 0.06196594]), + 'left_gaze_origin': array([-2.87022114, 2.63555455, -0.10971375]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.293487548828125, + 'left_pupil_posn': array([ 0.49673033, -0.14371121]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96469116, 0.25436401, 0.06814575]), + 'right_gaze_origin': array([-3.10277557, -3.05256963, -0.10683288]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9613494873046875, + 'right_pupil_posn': array([ 0.00443161, -0.22849369]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1114.1570812761784, + 'timestamp_carla': 1114161, + 'timestamp_device': 4267587, + 'timestamp_stream': 1114.1570812761784, + 'transform': [array([ 1.96131647e+00, 1.48387737e+01, -2.14721682e-03]), + array([-0.06261234, -8.46501541, 0.03000938])]} +{'AngularVelocity': array([1.57090172e-03, 6.46358298e-04, 8.41975975e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.8424654006958, + 'FR_Wheel_Angle': 18.553237915039062, + 'Location': array([ -1.14074159, -26.39069748, 0.17058179]), + 'Rotation': array([-5.23055866e-02, -6.38269806e+01, 5.40958792e-02]), + 'Velocity': array([ 8.49066973e-01, -1.16458976e+00, -1.06848718e-03]), + 'brake_input': 0.0, + 'camera_location': array([-9.0587759 , 16.25183487, -0.09969044]), + 'camera_rotation': array([-6.11661148, -4.5993309 , -0.29729414]), + 'current_gear_input': False, + 'focus_actor_dist': 3469.414306640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 448.35189819, -4770.82470703, 16.36010742]), + 'frame': 34654, + 'frame_number': 34654, + 'framesequence': 132592, + 'gaze_dir': array([0.96129608, 0.2660675 , 0.06926727]), + 'gaze_origin': array([-2.98596215, -0.20809861, -0.10712586]), + 'gaze_valid': True, + 'gaze_vergence': 145.60052490234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95758057, 0.28131104, 0.06228638]), + 'left_gaze_origin': array([-2.86946273, 2.63653731, -0.1087082 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30194091796875, + 'left_pupil_posn': array([ 0.49472773, -0.14002764]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9650116 , 0.25082397, 0.07624817]), + 'right_gaze_origin': array([-3.10246134, -3.05273461, -0.10554352]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9259185791015625, + 'right_pupil_posn': array([ 0.00394011, -0.22730184]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1114.1902490779757, + 'timestamp_carla': 1114194, + 'timestamp_device': 4267621, + 'timestamp_stream': 1114.1902490779757, + 'transform': [array([ 1.95564449e+00, 1.48164940e+01, -2.23484030e-03]), + array([-0.06263966, -8.45258808, 0.03018738])]} +{'AngularVelocity': array([-4.43668384e-03, 1.05509171e-02, 6.94499731e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.752361297607422, + 'FR_Wheel_Angle': 16.87321662902832, + 'Location': array([ -0.93593413, -26.68333626, 0.17036863]), + 'Rotation': array([-5.27905300e-02, -6.18052368e+01, 5.77437505e-02]), + 'Velocity': array([ 7.84581482e-01, -1.02766955e+00, -8.14819301e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.99866199, 16.27845764, -0.11948775]), + 'camera_rotation': array([-6.23866034, -4.41586304, -0.27118656]), + 'current_gear_input': False, + 'focus_actor_dist': 3671.945068359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 490.92459106, -4971.16796875, 16.34893036]), + 'frame': 34655, + 'frame_number': 34655, + 'framesequence': 132596, + 'gaze_dir': array([0.96224976, 0.26065063, 0.07527161]), + 'gaze_origin': array([-2.98491597, -0.20467834, -0.10457078]), + 'gaze_valid': True, + 'gaze_vergence': 121.4022216796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95756531, 0.2800293 , 0.06802368]), + 'left_gaze_origin': array([-2.86744547, 2.64321303, -0.10519257]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.290985107421875, + 'left_pupil_posn': array([ 0.48646367, -0.1348772 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9669342 , 0.24127197, 0.08251953]), + 'right_gaze_origin': array([-3.10238647, -3.05256963, -0.10394897]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.892730712890625, + 'right_pupil_posn': array([ 0.00349069, -0.22410297]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3015792965888977, + 'timestamp': 1114.2231068760157, + 'timestamp_carla': 1114227, + 'timestamp_device': 4267654, + 'timestamp_stream': 1114.2231068760157, + 'transform': [array([ 1.95503354e+00, 1.47923975e+01, -2.08339677e-03]), + array([-0.0626943 , -8.45008945, 0.02990529])]} +{'AngularVelocity': array([-4.91048209e-03, 9.71569493e-03, 5.47393560e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.391725540161133, + 'FR_Wheel_Angle': 13.492704391479492, + 'Location': array([ -0.78981137, -26.88632965, 0.17020594]), + 'Rotation': array([-5.29134721e-02, -6.05510445e+01, 6.07734844e-02]), + 'Velocity': array([ 7.21902728e-01, -9.47419465e-01, 1.18269920e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.95797348, 16.31247711, -0.14317194]), + 'camera_rotation': array([-6.44515038, -4.20884418, -0.24587983]), + 'current_gear_input': False, + 'focus_actor_dist': 4146.68701171875, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 583.69897461, -5439.46630859, 16.32902527]), + 'frame': 34656, + 'frame_number': 34656, + 'framesequence': 132600, + 'gaze_dir': array([0.96269226, 0.2585144 , 0.07801056]), + 'gaze_origin': array([-2.9846971 , -0.20371629, -0.10430908]), + 'gaze_valid': True, + 'gaze_vergence': 156.5006866455078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95857239, 0.27484131, 0.07476807]), + 'left_gaze_origin': array([-2.86701369, 2.64492059, -0.10500336]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3337554931640625, + 'left_pupil_posn': array([ 0.48556888, -0.13518476]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96681213, 0.2421875 , 0.08125305]), + 'right_gaze_origin': array([-3.10238051, -3.05235314, -0.10361481]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.84564208984375, + 'right_pupil_posn': array([ 0.00165391, -0.2212317 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.30951398611068726, + 'timestamp': 1114.25711767748, + 'timestamp_carla': 1114261, + 'timestamp_device': 4267687, + 'timestamp_stream': 1114.25711767748, + 'transform': [array([ 1.95836294e+00, 1.47650928e+01, -2.15576170e-03]), + array([-0.06272846, -8.45527935, 0.03004395])]} +{'AngularVelocity': array([ 2.50273943e-03, -4.60884161e-03, 4.02960587e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.333703994750977, + 'FR_Wheel_Angle': 9.701594352722168, + 'Location': array([ -0.63315117, -27.10615158, 0.16998327]), + 'Rotation': array([-5.28861508e-02, -5.94809456e+01, 6.30598590e-02]), + 'Velocity': array([ 0.6415022 , -0.8707183 , -0.00091266]), + 'brake_input': 0.0, + 'camera_location': array([-8.92089176, 16.35152817, -0.16499668]), + 'camera_rotation': array([-6.63015985, -4.02290535, -0.18656223]), + 'current_gear_input': False, + 'focus_actor_dist': 4014.32666015625, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 561.43249512, -5311.29150391, 16.331604 ]), + 'frame': 34657, + 'frame_number': 34657, + 'framesequence': 132604, + 'gaze_dir': array([0.96283722, 0.25735474, 0.0799408 ]), + 'gaze_origin': array([-2.98453617, -0.20253067, -0.10368653]), + 'gaze_valid': True, + 'gaze_vergence': 150.29019165039062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95878601, 0.27391052, 0.07545471]), + 'left_gaze_origin': array([-2.86680603, 2.64625716, -0.10496674]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.335723876953125, + 'left_pupil_posn': array([ 0.48412609, -0.13402247]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96688843, 0.24079895, 0.08442688]), + 'right_gaze_origin': array([-3.10226607, -3.05131841, -0.10240632]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8072052001953125, + 'right_pupil_posn': array([ 0.00068235, -0.22003925]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.2890822775662, + 'timestamp_carla': 1114293, + 'timestamp_device': 4267721, + 'timestamp_stream': 1114.2890822775662, + 'transform': [array([ 1.96092641e+00, 1.47377758e+01, -2.31832499e-03]), + array([-0.06264649, -8.45893669, 0.0303963 ])]} +{'AngularVelocity': array([ 2.38816901e-05, -2.04789266e-03, 2.09307408e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.199982643127441, + 'FR_Wheel_Angle': 6.035367488861084, + 'Location': array([ -0.49076658, -27.31170082, 0.16982999]), + 'Rotation': array([-5.27632087e-02, -5.87908783e+01, 6.38436452e-02]), + 'Velocity': array([ 0.55948693, -0.80286723, -0.00231805]), + 'brake_input': 0.0, + 'camera_location': array([-8.87375355, 16.39026642, -0.19195612]), + 'camera_rotation': array([-6.79652977, -3.85461617, -0.20104066]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.23388671875, + 'focus_actor_name': 'Road_Grass_Town05_131', + 'focus_actor_pt': array([ 527.75952148, -5122.62744141, 16.33622742]), + 'frame': 34658, + 'frame_number': 34658, + 'framesequence': 132608, + 'gaze_dir': array([0.96324921, 0.25567627, 0.08081055]), + 'gaze_origin': array([-2.98437214, -0.20169069, -0.10330124]), + 'gaze_valid': True, + 'gaze_vergence': 172.60939025878906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95988464, 0.26979065, 0.07632446]), + 'left_gaze_origin': array([-2.86647797, 2.64768219, -0.1048584 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3224029541015625, + 'left_pupil_posn': array([ 0.48339665, -0.13359725]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96661377, 0.24156189, 0.08529663]), + 'right_gaze_origin': array([-3.10226607, -3.05106354, -0.10174408]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.840240478515625, + 'right_pupil_posn': array([-0.00098574, -0.21923792]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.3233875781298, + 'timestamp_carla': 1114327, + 'timestamp_device': 4267754, + 'timestamp_stream': 1114.3233875781298, + 'transform': [array([ 1.96280730e+00, 1.47068787e+01, -2.45605456e-03]), + array([-0.06257136, -8.46105003, 0.03066002])]} +{'AngularVelocity': array([ 0.00236811, -0.00734972, 0.80046988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.3287289142608643, + 'FR_Wheel_Angle': 1.7484310865402222, + 'Location': array([ -0.37119547, -27.49349213, 0.16972338]), + 'Rotation': array([-5.23670577e-02, -5.84847679e+01, 6.43269867e-02]), + 'Velocity': array([ 4.82236654e-01, -7.46621311e-01, -6.39419537e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.8408041 , 16.41226006, -0.23533458]), + 'camera_rotation': array([-6.87995338, -3.70318055, -0.13334012]), + 'current_gear_input': False, + 'focus_actor_dist': 3594.943115234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 483.27401733, -4904.38623047, 16.34666443]), + 'frame': 34659, + 'frame_number': 34659, + 'framesequence': 132612, + 'gaze_dir': array([0.96391296, 0.25296783, 0.08105469]), + 'gaze_origin': array([-2.98252892, -0.19577867, -0.10222168]), + 'gaze_valid': True, + 'gaze_vergence': 157.31871032714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9598999 , 0.26927185, 0.07780457]), + 'left_gaze_origin': array([-2.86326313, 2.65547943, -0.10460969]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.253509521484375, + 'left_pupil_posn': array([ 0.4760536, -0.1328181]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96792603, 0.23666382, 0.08430481]), + 'right_gaze_origin': array([-3.10179472, -3.04703689, -0.09983368]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.920623779296875, + 'right_pupil_posn': array([-0.00396621, -0.21738505]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.3556314781308, + 'timestamp_carla': 1114359, + 'timestamp_device': 4267787, + 'timestamp_stream': 1114.3556314781308, + 'transform': [array([ 1.96405661e+00, 1.46761150e+01, -2.66092294e-03]), + array([-0.06247574, -8.4618988 , 0.03109503])]} +{'AngularVelocity': array([ 0.01001927, -0.02951971, 0.07548929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.26820704, -27.66035652, 0.16963804]), + 'Rotation': array([-5.12400754e-02, -5.84633827e+01, 6.07043691e-02]), + 'Velocity': array([ 4.21695501e-01, -6.88115656e-01, -2.82297115e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.80988693, 16.43155861, -0.25925994]), + 'camera_rotation': array([-6.97436714, -3.65086579, -0.14503869]), + 'current_gear_input': False, + 'focus_actor_dist': 3431.5322265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 447.7543335 , -4747.91845703, 16.35745239]), + 'frame': 34660, + 'frame_number': 34660, + 'framesequence': 132616, + 'gaze_dir': array([0.99325562, 0.06281281, 0.09083557]), + 'gaze_origin': array([-3.00851607, -0.04296494, -0.08165131]), + 'gaze_valid': True, + 'gaze_vergence': 79.7997055053711, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99165344, 0.09736633, 0.08442688]), + 'left_gaze_origin': array([-2.85342121, 2.82297373, -0.08777314]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.06719970703125, + 'left_pupil_posn': array([ 0.28817248, -0.11190677]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99485779, 0.02825928, 0.09724426]), + 'right_gaze_origin': array([-3.16361117, -2.90890384, -0.07552948]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9385986328125, + 'right_pupil_posn': array([-0.15823501, -0.20625126]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.389623977244, + 'timestamp_carla': 1114393, + 'timestamp_device': 4267821, + 'timestamp_stream': 1114.389623977244, + 'transform': [array([ 1.96505487e+00, 1.46418953e+01, -2.86840438e-03]), + array([-0.06240061, -8.46208096, 0.0315042 ])]} +{'AngularVelocity': array([0.0012968 , 0.00983382, 0.09261296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.17465359, -27.81290436, 0.16952616]), + 'Rotation': array([-5.11171333e-02, -5.84630814e+01, 5.91476075e-02]), + 'Velocity': array([ 0.38310257, -0.62446105, -0.0009626 ]), + 'brake_input': 0.0, + 'camera_location': array([-8.77640152, 16.43476868, -0.27162647]), + 'camera_rotation': array([-7.08428526, -3.6402328 , -0.09271023]), + 'current_gear_input': False, + 'focus_actor_dist': 3907.72314453125, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -192.80014038, -5307.27929688, 17.02215576]), + 'frame': 34661, + 'frame_number': 34661, + 'framesequence': 132620, + 'gaze_dir': array([ 0.9882431 , -0.11885834, 0.0931015 ]), + 'gaze_origin': array([-2.99169254, 0.0899025 , -0.09323655]), + 'gaze_valid': True, + 'gaze_vergence': 108.86092376708984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98983765, -0.09757996, 0.1033783 ]), + 'left_gaze_origin': array([-2.86659861, 2.94521332, -0.08105011]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.95361328125, + 'left_pupil_posn': array([ 0.14894652, -0.11486721]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98664856, -0.14013672, 0.08282471]), + 'right_gaze_origin': array([-3.11678624, -2.76540852, -0.10542298]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0789794921875, + 'right_pupil_posn': array([-0.32516462, -0.2096498 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.4233392775059, + 'timestamp_carla': 1114427, + 'timestamp_device': 4267854, + 'timestamp_stream': 1114.4233392775059, + 'transform': [array([ 1.96611810e+00, 1.46060247e+01, -3.08345794e-03]), + array([-0.06231181, -8.46230125, 0.03194047])]} +{'AngularVelocity': array([-1.09166883e-01, -6.95387274e-02, 9.83740974e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1589401364326477, + 'FR_Wheel_Angle': -0.15869595110416412, + 'Location': array([ -0.15494016, -27.84486198, 0.16962239]), + 'Rotation': array([ -0.07302155, -58.47710037, 0.05858334]), + 'Velocity': array([-4.25430517e-05, 7.82480056e-05, -1.48515828e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.73843575, 16.4365387 , -0.26006651]), + 'camera_rotation': array([-7.12518454, -3.71849084, -0.0770136 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1816.152099609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -575.50378418, -3199.38964844, 81.1661377 ]), + 'frame': 34662, + 'frame_number': 34662, + 'framesequence': 132624, + 'gaze_dir': array([ 0.98547363, -0.13954163, 0.09410095]), + 'gaze_origin': array([-2.97188282, 0.10577012, -0.10456315]), + 'gaze_valid': True, + 'gaze_vergence': 74.13215637207031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98550415, -0.1270752 , 0.11224365]), + 'left_gaze_origin': array([-2.86686277, 2.96070266, -0.08593751]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9905242919921875, + 'left_pupil_posn': array([ 0.13451457, -0.12051177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98544312, -0.15200806, 0.07595825]), + 'right_gaze_origin': array([-3.07690287, -2.74916244, -0.12318879]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.04058837890625, + 'right_pupil_posn': array([-0.34646177, -0.21116292]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.4561525769532, + 'timestamp_carla': 1114460, + 'timestamp_device': 4267887, + 'timestamp_stream': 1114.4561525769532, + 'transform': [array([ 1.96719933e+00, 1.45691986e+01, -3.30778118e-03]), + array([-0.06222302, -8.46250725, 0.03241078])]} +{'AngularVelocity': array([-3.56320329e-02, -2.24889629e-02, 2.25690528e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.15894031524658203, + 'FR_Wheel_Angle': -0.15614038705825806, + 'Location': array([ -0.15487224, -27.84498024, 0.16951482]), + 'Rotation': array([-5.38287163e-02, -5.84769135e+01, 5.83048984e-02]), + 'Velocity': array([-1.06279504e-05, 2.64033151e-05, 4.18927921e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.69607449, 16.42016602, -0.2622112 ]), + 'camera_rotation': array([-7.17051649, -3.88622379, -0.03422395]), + 'current_gear_input': False, + 'focus_actor_dist': 1818.1663818359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -615.50915527, -3198.33642578, 82.31628418]), + 'frame': 34663, + 'frame_number': 34663, + 'framesequence': 132628, + 'gaze_dir': array([ 0.98577118, -0.13738251, 0.09481812]), + 'gaze_origin': array([-2.97067046, 0.10405274, -0.10650788]), + 'gaze_valid': True, + 'gaze_vergence': 94.92061614990234, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98600769, -0.12542725, 0.10966492]), + 'left_gaze_origin': array([-2.87163115, 2.9626925 , -0.08604584]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.989837646484375, + 'left_pupil_posn': array([ 0.13408375, -0.12003422]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98553467, -0.14933777, 0.07997131]), + 'right_gaze_origin': array([-3.06971002, -2.75458694, -0.12696992]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1004180908203125, + 'right_pupil_posn': array([-0.34205657, -0.21339083]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.4904445782304, + 'timestamp_carla': 1114494, + 'timestamp_device': 4267921, + 'timestamp_stream': 1114.4904445782304, + 'transform': [array([ 1.96837187e+00, 1.45287895e+01, -3.48962774e-03]), + array([-0.06215472, -8.46272182, 0.03277344])]} +{'AngularVelocity': array([-8.65186751e-03, -5.57336258e-03, -6.06010417e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.13330481946468353, + 'FR_Wheel_Angle': -0.13313299417495728, + 'Location': array([ -0.15485314, -27.84501076, 0.16947283]), + 'Rotation': array([-4.86514345e-02, -5.84766350e+01, 5.82248122e-02]), + 'Velocity': array([ 6.18444744e-07, 7.38961853e-06, -1.42000106e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.67792416, 16.38916779, -0.27910593]), + 'camera_rotation': array([-7.2196188 , -4.06447172, -0.05290147]), + 'current_gear_input': False, + 'focus_actor_dist': 1814.6890869140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -615.99987793, -3198.42407227, 82.42784882]), + 'frame': 34664, + 'frame_number': 34664, + 'framesequence': 132632, + 'gaze_dir': array([ 0.98600006, -0.13653564, 0.09378052]), + 'gaze_origin': array([-2.98322916, 0.10380403, -0.10299149]), + 'gaze_valid': True, + 'gaze_vergence': 98.16777801513672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98625183, -0.12484741, 0.1081543 ]), + 'left_gaze_origin': array([-2.87696838, 2.96347213, -0.08529663]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.97265625, + 'left_pupil_posn': array([ 0.13396549, -0.12069476]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98574829, -0.14822388, 0.07940674]), + 'right_gaze_origin': array([-3.08948994, -2.75586414, -0.12068634]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0855255126953125, + 'right_pupil_posn': array([-0.34121978, -0.21339083]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.5234128758311, + 'timestamp_carla': 1114527, + 'timestamp_device': 4267954, + 'timestamp_stream': 1114.5234128758311, + 'transform': [array([ 1.96956170e+00, 1.44880114e+01, -3.66811734e-03]), + array([-0.06209325, -8.46294212, 0.03315644])]} +{'AngularVelocity': array([-2.45841639e-03, -1.67230179e-03, 1.92470338e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.15484384, -27.84502411, 0.16947442]), + 'Rotation': array([-4.73332070e-02, -5.84764214e+01, 5.82029484e-02]), + 'Velocity': array([ 0.00022074, -0.00035189, -0.00020843]), + 'brake_input': 0.0, + 'camera_location': array([-8.66718197, 16.36434937, -0.29627737]), + 'camera_rotation': array([-7.2922101 , -4.25762224, -0.08794023]), + 'current_gear_input': False, + 'focus_actor_dist': 1810.076904296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -619.16540527, -3197.08642578, 79.03578949]), + 'frame': 34665, + 'frame_number': 34665, + 'framesequence': 132636, + 'gaze_dir': array([ 0.98642731, -0.13355255, 0.0934906 ]), + 'gaze_origin': array([-2.99290633, 0.10392991, -0.09995423]), + 'gaze_valid': True, + 'gaze_vergence': 100.4621810913086, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98675537, -0.12117004, 0.10769653]), + 'left_gaze_origin': array([-2.88514113, 2.96427155, -0.08287201]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.969940185546875, + 'left_pupil_posn': array([ 0.13424897, -0.12059295]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98609924, -0.14593506, 0.07928467]), + 'right_gaze_origin': array([-3.10067153, -2.75641203, -0.11703645]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0717315673828125, + 'right_pupil_posn': array([-0.33967668, -0.21319318]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.555452477187, + 'timestamp_carla': 1114559, + 'timestamp_device': 4267987, + 'timestamp_stream': 1114.555452477187, + 'transform': [array([ 1.97078001e+00, 1.44464989e+01, -3.85614391e-03]), + array([-0.06201812, -8.46317863, 0.0335663 ])]} +{'AngularVelocity': array([-3.98839533e-04, -2.40605121e-04, -1.47082228e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -0.15476298, -27.84515381, 0.16946565]), + 'Rotation': array([-4.72444147e-02, -5.84764023e+01, 5.82028665e-02]), + 'Velocity': array([ 4.16501416e-06, 1.57583554e-06, -2.21173585e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.65126324, 16.33239174, -0.30570382]), + 'camera_rotation': array([-7.34002161, -4.45048904, -0.08945846]), + 'current_gear_input': False, + 'focus_actor_dist': 1807.154541015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -619.29089355, -3198.05957031, 76.10260773]), + 'frame': 34666, + 'frame_number': 34666, + 'framesequence': 132640, + 'gaze_dir': array([ 0.98670197, -0.13105011, 0.09400177]), + 'gaze_origin': array([-2.9912715 , 0.10437699, -0.10052796]), + 'gaze_valid': True, + 'gaze_vergence': 88.11223602294922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98678589, -0.11911011, 0.10978699]), + 'left_gaze_origin': array([-2.90024281, 2.96538091, -0.07804261]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.966033935546875, + 'left_pupil_posn': array([ 0.13461876, -0.12057316]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98661804, -0.14299011, 0.07821655]), + 'right_gaze_origin': array([-3.08229995, -2.75662708, -0.12301331]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0772552490234375, + 'right_pupil_posn': array([-0.3385852 , -0.21300495]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00023804437660146505, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.5909999758005, + 'timestamp_carla': 1114595, + 'timestamp_device': 4268021, + 'timestamp_stream': 1114.5909999758005, + 'transform': [array([ 1.97217524e+00, 1.43985529e+01, -3.93957132e-03]), + array([-0.06199079, -8.46342945, 0.03371362])]} +{'AngularVelocity': array([-0.00809752, -0.00226701, -0.01355023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6856989860534668, + 'FR_Wheel_Angle': -0.6988769769668579, + 'Location': array([ -0.15471956, -27.84520721, 0.16946317]), + 'Rotation': array([-4.72444147e-02, -5.84764023e+01, 5.82028665e-02]), + 'Velocity': array([ 2.37208023e-03, -4.11030184e-03, -6.46686531e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.64697552, 16.29446793, -0.30316466]), + 'camera_rotation': array([-7.34153748, -4.60286522, -0.11670087]), + 'current_gear_input': False, + 'focus_actor_dist': 1803.35986328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -620.02111816, -3198.19921875, 75.5932312 ]), + 'frame': 34667, + 'frame_number': 34667, + 'framesequence': 132644, + 'gaze_dir': array([ 0.98730469, -0.12838745, 0.09140015]), + 'gaze_origin': array([-3.02031326, 0.10444565, -0.0906807 ]), + 'gaze_valid': True, + 'gaze_vergence': 45.092063903808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98632812, -0.12261963, 0.11004639]), + 'left_gaze_origin': array([-2.98385787, 2.96951008, -0.05127716]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9532470703125, + 'left_pupil_posn': array([ 0.13542187, -0.12023962]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98828125, -0.13415527, 0.07275391]), + 'right_gaze_origin': array([-3.05676889, -2.76061869, -0.13008423]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0679473876953125, + 'right_pupil_posn': array([-0.33676893, -0.21279979]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0003295999194961041, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.6260429769754, + 'timestamp_carla': 1114630, + 'timestamp_device': 4268054, + 'timestamp_stream': 1114.6260429769754, + 'transform': [array([ 1.97364044e+00, 1.43492918e+01, -3.97130940e-03]), + array([-0.06198396, -8.46376324, 0.03378892])]} +{'AngularVelocity': array([-0.008184 , -0.00107016, -0.01651642]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.9214645028114319, + 'FR_Wheel_Angle': -0.9384756088256836, + 'Location': array([ -0.15488522, -27.84485626, 0.16947156]), + 'Rotation': array([-4.72444147e-02, -5.84764023e+01, 5.82028665e-02]), + 'Velocity': array([ 2.35214524e-04, -7.26956117e-04, -5.11360158e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.64054585, 16.25099564, -0.31165788]), + 'camera_rotation': array([-7.33537006, -4.76039505, -0.09555471]), + 'current_gear_input': False, + 'focus_actor_dist': 1801.043212890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -619.52478027, -3200.51904297, 70.7525177 ]), + 'frame': 34668, + 'frame_number': 34668, + 'framesequence': 132649, + 'gaze_dir': array([ 0.98851776, -0.12156677, 0.08609009]), + 'gaze_origin': array([-3.10511637, 0.10763092, -0.06358795]), + 'gaze_valid': True, + 'gaze_vergence': 4.128497123718262, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98640442, -0.12129211, 0.11074829]), + 'left_gaze_origin': array([-3.15346384e+00, 2.97647095e+00, 2.90832529e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.918365478515625, + 'left_pupil_posn': array([ 0.13608968, -0.11977637]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9906311 , -0.12184143, 0.06143188]), + 'right_gaze_origin': array([-3.05676889, -2.76120925, -0.13008423]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0680084228515625, + 'right_pupil_posn': array([-0.33589244, -0.21255589]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0005859553930349648, + 'throttle_input': 0.3174487054347992, + 'timestamp': 1114.661192279309, + 'timestamp_carla': 1114665, + 'timestamp_device': 4268096, + 'timestamp_stream': 1114.661192279309, + 'transform': [array([ 1.97529817e+00, 1.42978535e+01, -3.99417849e-03]), + array([-0.06199762, -8.46437645, 0.03385398])]} +{'AngularVelocity': array([-0.00720558, -0.00040625, -0.01402974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0148296356201172, + 'FR_Wheel_Angle': -1.0099372863769531, + 'Location': array([ -0.15586795, -27.84314728, 0.16947393]), + 'Rotation': array([-4.73946817e-02, -5.84759445e+01, 5.81980050e-02]), + 'Velocity': array([-5.33032650e-03, 8.48699640e-03, 8.65077964e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.63235283, 16.1938858 , -0.30363926]), + 'camera_rotation': array([-7.31421709, -4.89490986, -0.10900667]), + 'current_gear_input': False, + 'focus_actor_dist': 1796.0531005859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -611.17437744, -3201.44238281, 61.5004425 ]), + 'frame': 34669, + 'frame_number': 34669, + 'framesequence': 132652, + 'gaze_dir': array([ 0.98886871, -0.11986542, 0.08542633]), + 'gaze_origin': array([-3.11358881, 0.10695191, -0.06056595]), + 'gaze_valid': True, + 'gaze_vergence': 5.193026542663574, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98687744, -0.12121582, 0.10662842]), + 'left_gaze_origin': array([-3.16491723, 2.97647095, 0.00575562]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9209136962890625, + 'left_pupil_posn': array([ 0.13732231, -0.11905479]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99085999, -0.11851501, 0.06422424]), + 'right_gaze_origin': array([-3.06226063, -2.76256728, -0.12688752]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0406494140625, + 'right_pupil_posn': array([-0.33499587, -0.21280754]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00119022186845541, + 'throttle_input': 0.29761195182800293, + 'timestamp': 1114.6918107792735, + 'timestamp_carla': 1114695, + 'timestamp_device': 4268121, + 'timestamp_stream': 1114.6918107792735, + 'transform': [array([ 1.97703397e+00, 1.42511473e+01, -4.11880482e-03]), + array([-0.06199762, -8.46540642, 0.03418129])]} +{'AngularVelocity': array([-0.00895401, 0.00041137, -0.01228785]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.5178309679031372, + 'FR_Wheel_Angle': -1.6200097799301147, + 'Location': array([ -0.15827778, -27.83907127, 0.16947168]), + 'Rotation': array([-4.78864536e-02, -5.84739838e+01, 5.81724830e-02]), + 'Velocity': array([-0.01465707, 0.02392741, -0.00041877]), + 'brake_input': 0.0, + 'camera_location': array([-8.6336832 , 16.13240051, -0.30883205]), + 'camera_rotation': array([-7.30682659, -5.04102278, -0.20001128]), + 'current_gear_input': False, + 'focus_actor_dist': 1791.0069580078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -611.3392334 , -3201.38769531, 61.07727814]), + 'frame': 34670, + 'frame_number': 34670, + 'framesequence': 132656, + 'gaze_dir': array([ 0.98944855, -0.11514282, 0.08511353]), + 'gaze_origin': array([-3.11532688, 0.10630875, -0.06014558]), + 'gaze_valid': True, + 'gaze_vergence': 15.413501739501953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98722839, -0.11825562, 0.10668945]), + 'left_gaze_origin': array([-3.16491723, 2.97631836, 0.00575562]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.920196533203125, + 'left_pupil_posn': array([ 0.13969529, -0.11923099]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9916687 , -0.11203003, 0.0635376 ]), + 'right_gaze_origin': array([-3.06573653, -2.76370096, -0.12604676]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0287017822265625, + 'right_pupil_posn': array([-0.33321029, -0.2128793 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.002142399549484253, + 'throttle_input': 0.2896620035171509, + 'timestamp': 1114.7232811786234, + 'timestamp_carla': 1114727, + 'timestamp_device': 4268154, + 'timestamp_stream': 1114.7232811786234, + 'transform': [array([ 1.97929716e+00, 1.42013769e+01, -4.23116656e-03]), + array([-0.06208641, -8.46739769, 0.03445138])]} +{'AngularVelocity': array([-0.0132761 , 0.00224307, -0.00865855]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.851909637451172, + 'FR_Wheel_Angle': -3.0595076084136963, + 'Location': array([ -0.16309091, -27.8308506 , 0.16948777]), + 'Rotation': array([-4.77293581e-02, -5.84675102e+01, 5.81292771e-02]), + 'Velocity': array([-2.13400368e-02, 3.53581645e-02, 5.31482692e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.65541267, 16.07151794, -0.33328199]), + 'camera_rotation': array([-7.36365366, -5.24179554, -0.29502398]), + 'current_gear_input': False, + 'focus_actor_dist': 1785.7060546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -606.71606445, -3201.45483398, 60.53197479]), + 'frame': 34671, + 'frame_number': 34671, + 'framesequence': 132660, + 'gaze_dir': array([ 0.9899826 , -0.11283112, 0.08234406]), + 'gaze_origin': array([-3.11665368, 0.10504913, -0.05860291]), + 'gaze_valid': True, + 'gaze_vergence': 23.60853385925293, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98791504, -0.11662292, 0.10198975]), + 'left_gaze_origin': array([-3.16116524, 2.97502756, 0.00433197]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9247894287109375, + 'left_pupil_posn': array([ 0.14160919, -0.11977637]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99205017, -0.10903931, 0.06269836]), + 'right_gaze_origin': array([-3.07214212, -2.76492929, -0.12153778]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0279541015625, + 'right_pupil_posn': array([-0.3318451 , -0.21263492]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0033509323839098215, + 'throttle_input': 0.2856946587562561, + 'timestamp': 1114.7591731771827, + 'timestamp_carla': 1114763, + 'timestamp_device': 4268187, + 'timestamp_stream': 1114.7591731771827, + 'transform': [array([ 1.98266232e+00, 1.41428032e+01, -4.16357024e-03]), + array([-0.06230498, -8.47120953, 0.03429581])]} +{'AngularVelocity': array([-0.0152486 , 0.0111432 , -0.00098878]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.905231475830078, + 'FR_Wheel_Angle': -5.973855495452881, + 'Location': array([ -0.16870444, -27.82092285, 0.16949449]), + 'Rotation': array([-4.74834740e-02, -5.84520454e+01, 5.80283888e-02]), + 'Velocity': array([-0.02503556, 0.0424451 , 0.00019989]), + 'brake_input': 0.0, + 'camera_location': array([-8.67470837, 15.99667645, -0.34395826]), + 'camera_rotation': array([-7.3730588 , -5.44641399, -0.35172158]), + 'current_gear_input': False, + 'focus_actor_dist': 1780.0986328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -607.97351074, -3200.15234375, 53.67802429]), + 'frame': 34672, + 'frame_number': 34672, + 'framesequence': 132664, + 'gaze_dir': array([ 0.9885025 , -0.12313843, 0.08563995]), + 'gaze_origin': array([-3.02035618, 0.09753037, -0.08718262]), + 'gaze_valid': True, + 'gaze_vergence': 54.90210723876953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98779297, -0.11671448, 0.1030426 ]), + 'left_gaze_origin': array([-2.9622407 , 2.9614563 , -0.05443573]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.992706298828125, + 'left_pupil_posn': array([ 0.14235544, -0.11986506]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98921204, -0.12956238, 0.0682373 ]), + 'right_gaze_origin': array([-3.07847142, -2.76639581, -0.11992951]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0252532958984375, + 'right_pupil_posn': array([-0.33093888, -0.21240377]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.005017243325710297, + 'throttle_input': 0.28172731399536133, + 'timestamp': 1114.7904714792967, + 'timestamp_carla': 1114794, + 'timestamp_device': 4268221, + 'timestamp_stream': 1114.7904714792967, + 'transform': [array([ 1.98650753e+00, 1.40899391e+01, -4.11012629e-03]), + array([-0.06254404, -8.47637367, 0.03425538])]} +{'AngularVelocity': array([0.1690432 , 0.06324934, 2.55776954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.406986236572266, + 'FR_Wheel_Angle': -8.02200698852539, + 'Location': array([ -0.18926302, -27.78285408, 0.16963938]), + 'Rotation': array([-6.85409456e-02, -5.83293610e+01, 5.24256192e-02]), + 'Velocity': array([-0.26619658, 0.51537061, 0.0006988 ]), + 'brake_input': 0.0, + 'camera_location': array([-8.70137501, 15.91979122, -0.34586275]), + 'camera_rotation': array([-7.31557608, -5.68836737, -0.24703322]), + 'current_gear_input': False, + 'focus_actor_dist': 1778.9307861328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -632.3885498 , -3200.51904297, 59.25827026]), + 'frame': 34673, + 'frame_number': 34673, + 'framesequence': 132668, + 'gaze_dir': array([ 0.98861694, -0.12163544, 0.08636475]), + 'gaze_origin': array([-3.02326536, 0.0959961 , -0.08642273]), + 'gaze_valid': True, + 'gaze_vergence': 56.82820510864258, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9879303 , -0.11477661, 0.10388184]), + 'left_gaze_origin': array([-2.9593966 , 2.96011972, -0.05552521]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0084228515625, + 'left_pupil_posn': array([ 0.14361048, -0.11986506]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98930359, -0.12849426, 0.06884766]), + 'right_gaze_origin': array([-3.08713388, -2.76812768, -0.11732025]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0153656005859375, + 'right_pupil_posn': array([-0.32914996, -0.21199894]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.006701864767819643, + 'throttle_input': 0.2737926244735718, + 'timestamp': 1114.8234411776066, + 'timestamp_carla': 1114827, + 'timestamp_device': 4268254, + 'timestamp_stream': 1114.8234411776066, + 'transform': [array([ 1.99168968e+00, 1.40325537e+01, -4.01433930e-03]), + array([-0.06285822, -8.4840889 , 0.03409645])]} +{'AngularVelocity': array([ 0.00466855, -0.00582265, 2.13152719]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.616432189941406, + 'FR_Wheel_Angle': -8.836712837219238, + 'Location': array([ -0.26397336, -27.64087296, 0.16968954]), + 'Rotation': array([-5.86849824e-02, -5.78582497e+01, 5.20430170e-02]), + 'Velocity': array([-3.05383861e-01, 6.12240791e-01, 2.93779362e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.72624397, 15.83956432, -0.33613503]), + 'camera_rotation': array([-7.26942444, -5.93077898, -0.30126736]), + 'current_gear_input': False, + 'focus_actor_dist': 1771.04345703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -635.41796875, -3197.2409668 , 63.00936127]), + 'frame': 34674, + 'frame_number': 34674, + 'framesequence': 132672, + 'gaze_dir': array([ 0.98936462, -0.11714172, 0.08448029]), + 'gaze_origin': array([-3.02208877, 0.092939 , -0.08638611]), + 'gaze_valid': True, + 'gaze_vergence': 99.52263641357422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98931885, -0.10775757, 0.0980835 ]), + 'left_gaze_origin': array([-2.93677831, 2.9566164 , -0.06346436]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.015167236328125, + 'left_pupil_posn': array([ 0.14648557, -0.12021732]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9894104 , -0.12652588, 0.07087708]), + 'right_gaze_origin': array([-3.10739923, -2.77073836, -0.10930786]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.02996826171875, + 'right_pupil_posn': array([-0.32508385, -0.21247315]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00873439759016037, + 'throttle_input': 0.2380865216255188, + 'timestamp': 1114.8575654774904, + 'timestamp_carla': 1114861, + 'timestamp_device': 4268287, + 'timestamp_stream': 1114.8575654774904, + 'transform': [array([ 1.99840355e+00, 1.39714632e+01, -3.82747641e-03]), + array([-0.06326121, -8.49485397, 0.03374308])]} +{'AngularVelocity': array([0.00977872, 0.00720664, 2.42809677]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.541692733764648, + 'FR_Wheel_Angle': -8.644953727722168, + 'Location': array([ -0.36099064, -27.45897865, 0.16979857]), + 'Rotation': array([-6.62869811e-02, -5.72314796e+01, 5.36917187e-02]), + 'Velocity': array([-4.89988863e-01, 9.45437312e-01, 5.20381902e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.73145008, 15.75724125, -0.31410903]), + 'camera_rotation': array([-7.13099718, -6.19360685, -0.40540656]), + 'current_gear_input': False, + 'focus_actor_dist': 1766.3641357421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -634.27642822, -3198.24853516, 60.98562622]), + 'frame': 34675, + 'frame_number': 34675, + 'framesequence': 132676, + 'gaze_dir': array([ 0.99006653, -0.11473083, 0.08011627]), + 'gaze_origin': array([-3.00800943, 0.08669892, -0.09303742]), + 'gaze_valid': True, + 'gaze_vergence': 151.17547607421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99029541, -0.10606384, 0.08966064]), + 'left_gaze_origin': array([-2.93527389, 2.95414901, -0.06474762]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.030181884765625, + 'left_pupil_posn': array([ 0.14922452, -0.12090123]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98983765, -0.12339783, 0.0705719 ]), + 'right_gaze_origin': array([-3.08074498, -2.78075123, -0.12132721]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0580291748046875, + 'right_pupil_posn': array([-0.31742322, -0.2185477 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.011023285798728466, + 'throttle_input': 0.21428243815898895, + 'timestamp': 1114.8913704790175, + 'timestamp_carla': 1114895, + 'timestamp_device': 4268321, + 'timestamp_stream': 1114.8913704790175, + 'transform': [array([ 2.00660205e+00, 1.39093580e+01, -3.54719162e-03]), + array([-0.063712 , -8.50871754, 0.03322012])]} +{'AngularVelocity': array([-0.0747419 , -0.00915706, 1.79310215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.539992332458496, + 'FR_Wheel_Angle': -6.599796772003174, + 'Location': array([ -0.49195352, -27.22403717, 0.16988526]), + 'Rotation': array([ -0.05837762, -56.47047043, 0.05922046]), + 'Velocity': array([-5.60040593e-01, 1.00551510e+00, 8.16917396e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.73709869, 15.67977142, -0.3093392 ]), + 'camera_rotation': array([-6.99545193, -6.40381908, -0.51556462]), + 'current_gear_input': False, + 'focus_actor_dist': 1760.197021484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -637.26074219, -3197.22021484, 57.34511566]), + 'frame': 34676, + 'frame_number': 34676, + 'framesequence': 132680, + 'gaze_dir': array([ 0.99029541, -0.10932159, 0.08525848]), + 'gaze_origin': array([-3.01591969, 0.08290024, -0.09354477]), + 'gaze_valid': True, + 'gaze_vergence': 220.19039916992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99032593, -0.10398865, 0.09172058]), + 'left_gaze_origin': array([-2.94797826, 2.94794488, -0.06539002]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.07147216796875, + 'left_pupil_posn': array([ 0.15648854, -0.12088335]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99026489, -0.11465454, 0.07879639]), + 'right_gaze_origin': array([-3.08386087, -2.78214431, -0.12169953]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1058197021484375, + 'right_pupil_posn': array([-0.31576121, -0.21877885]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.013165686279535294, + 'throttle_input': 0.20236514508724213, + 'timestamp': 1114.9242553785443, + 'timestamp_carla': 1114928, + 'timestamp_device': 4268354, + 'timestamp_stream': 1114.9242553785443, + 'transform': [array([ 2.01609039e+00, 1.38475256e+01, -3.21329106e-03]), + array([-0.06417646, -8.52535343, 0.03260824])]} +{'AngularVelocity': array([-0.05659376, -0.02160122, 0.23171906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.4093387126922607, + 'FR_Wheel_Angle': -2.7405219078063965, + 'Location': array([ -0.59978819, -27.04402542, 0.1699357 ]), + 'Rotation': array([-4.51065674e-02, -5.60763321e+01, 6.47106841e-02]), + 'Velocity': array([-4.99767244e-01, 8.17553461e-01, 7.75656663e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.76706982, 15.61440945, -0.30000052]), + 'camera_rotation': array([-7.05225182, -6.59397936, -0.55204231]), + 'current_gear_input': False, + 'focus_actor_dist': 1753.412841796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -633.5958252 , -3197.62792969, 70.34233093]), + 'frame': 34677, + 'frame_number': 34677, + 'framesequence': 132684, + 'gaze_dir': array([ 0.99023438, -0.11077118, 0.08412933]), + 'gaze_origin': array([-3.00755239, 0.080439 , -0.09676743]), + 'gaze_valid': True, + 'gaze_vergence': 202.2777862548828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9901886 , -0.10609436, 0.09085083]), + 'left_gaze_origin': array([-2.93160725, 2.94528508, -0.07144775]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0304107666015625, + 'left_pupil_posn': array([ 0.15789175, -0.12236071]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99028015, -0.115448 , 0.07740784]), + 'right_gaze_origin': array([-3.08349776, -2.78440714, -0.1220871 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1298065185546875, + 'right_pupil_posn': array([-0.3149479 , -0.21931458]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.015326395630836487, + 'throttle_input': 0.19839780032634735, + 'timestamp': 1114.956910379231, + 'timestamp_carla': 1114961, + 'timestamp_device': 4268387, + 'timestamp_stream': 1114.956910379231, + 'transform': [array([ 2.02703834e+00, 1.37848644e+01, -2.82356259e-03]), + array([-0.06464091, -8.54505444, 0.03188635])]} +{'AngularVelocity': array([ 0.00502434, -0.01797611, -0.93336964]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7367698550224304, + 'FR_Wheel_Angle': -0.7319124341011047, + 'Location': array([ -0.70477283, -26.88157463, 0.17000063]), + 'Rotation': array([-3.86383794e-02, -5.59444313e+01, 6.33539259e-02]), + 'Velocity': array([-3.91431838e-01, 5.89839637e-01, 2.11305611e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.79258633, 15.56810379, -0.30187762]), + 'camera_rotation': array([-7.12928295, -6.64471388, -0.60132122]), + 'current_gear_input': False, + 'focus_actor_dist': 1756.091552734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -642.84558105, -3204.35986328, 66.4173584 ]), + 'frame': 34678, + 'frame_number': 34678, + 'framesequence': 132688, + 'gaze_dir': array([ 0.98954773, -0.12106323, 0.07541656]), + 'gaze_origin': array([-2.96886086, 0.08765946, -0.11426316]), + 'gaze_valid': True, + 'gaze_vergence': 112.37295532226562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99069214, -0.10409546, 0.08755493]), + 'left_gaze_origin': array([-2.91780114, 2.95169067, -0.07998505]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1337127685546875, + 'left_pupil_posn': array([ 0.14575791, -0.13040447]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98840332, -0.13803101, 0.0632782 ]), + 'right_gaze_origin': array([-3.01992059, -2.77637196, -0.14854127]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1862335205078125, + 'right_pupil_posn': array([-0.31930906, -0.22599041]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01746879518032074, + 'throttle_input': 0.19839780032634735, + 'timestamp': 1114.9905528761446, + 'timestamp_carla': 1114994, + 'timestamp_device': 4268420, + 'timestamp_stream': 1114.9905528761446, + 'transform': [array([ 2.03991914e+00, 1.37191582e+01, -2.36150739e-03]), + array([-0.06511902, -8.56871223, 0.03100666])]} +{'AngularVelocity': array([ 0.01106203, -0.00402935, -1.00507665]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0042614936828613, + 'FR_Wheel_Angle': -1.010010838508606, + 'Location': array([ -0.78394192, -26.76260757, 0.17010103]), + 'Rotation': array([-4.01546806e-02, -5.59066315e+01, 5.84887080e-02]), + 'Velocity': array([-0.29618371, 0.4471266 , 0.00072224]), + 'brake_input': 0.0, + 'camera_location': array([-8.79697895, 15.54298878, -0.29839522]), + 'camera_rotation': array([-7.06912231, -6.60308647, -0.72496641]), + 'current_gear_input': False, + 'focus_actor_dist': 2395.34619140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -797.60015869, -3829.578125 , 17.5675354 ]), + 'frame': 34679, + 'frame_number': 34679, + 'framesequence': 132692, + 'gaze_dir': array([ 0.98884583, -0.1217041 , 0.082901 ]), + 'gaze_origin': array([-2.95289326, 0.08591919, -0.12495957]), + 'gaze_valid': True, + 'gaze_vergence': 66.1503677368164, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98857117, -0.11096191, 0.10189819]), + 'left_gaze_origin': array([-2.91230035, 2.95023966, -0.08481751]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0773162841796875, + 'left_pupil_posn': array([ 0.14859223, -0.13229799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98912048, -0.13244629, 0.06390381]), + 'right_gaze_origin': array([-2.99348617, -2.77840114, -0.16510163]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2064361572265625, + 'right_pupil_posn': array([-0.32007408, -0.22742271]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.019153418019413948, + 'throttle_input': 0.1904631108045578, + 'timestamp': 1115.024404078722, + 'timestamp_carla': 1115028, + 'timestamp_device': 4268454, + 'timestamp_stream': 1115.024404078722, + 'transform': [array([ 2.05426335e+00, 1.36520100e+01, -1.86044688e-03]), + array([-0.06553566, -8.59544945, 0.03005314])]} +{'AngularVelocity': array([ 0.00876264, 0.00227387, -1.08277297]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.37554931640625, + 'FR_Wheel_Angle': -1.5819857120513916, + 'Location': array([ -0.84497702, -26.67065811, 0.17018591]), + 'Rotation': array([-4.29413952e-02, -5.58675613e+01, 5.68160713e-02]), + 'Velocity': array([-2.33257920e-01, 3.53978992e-01, 3.00149899e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.80278778, 15.52298546, -0.30673185]), + 'camera_rotation': array([-6.9749341 , -6.49676657, -0.8872447 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1740.7745361328125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -660.39331055, -3197.35791016, 63.78565979]), + 'frame': 34680, + 'frame_number': 34680, + 'framesequence': 132696, + 'gaze_dir': array([ 0.98810577, -0.1257019 , 0.08625031]), + 'gaze_origin': array([-2.95292139, 0.0880928 , -0.12472153]), + 'gaze_valid': True, + 'gaze_vergence': 65.97657775878906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98768616, -0.116745 , 0.10409546]), + 'left_gaze_origin': array([-2.90781569, 2.95159173, -0.08600616]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0343780517578125, + 'left_pupil_posn': array([ 0.14688635, -0.13076365]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98852539, -0.13465881, 0.06840515]), + 'right_gaze_origin': array([-2.99802732, -2.77540612, -0.1634369 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1879119873046875, + 'right_pupil_posn': array([-0.32417035, -0.22648191]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.020966216921806335, + 'throttle_input': 0.1904631108045578, + 'timestamp': 1115.0581210777164, + 'timestamp_carla': 1115062, + 'timestamp_device': 4268487, + 'timestamp_stream': 1115.0581210777164, + 'transform': [array([ 2.06992006e+00, 1.35841513e+01, -1.36251445e-03]), + array([-0.06590449, -8.62499428, 0.02911266])]} +{'AngularVelocity': array([0.00528023, 0.01087782, 0.04908152]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.2153677940368652, + 'FR_Wheel_Angle': -3.424743890762329, + 'Location': array([ -0.89654845, -26.59153938, 0.17027551]), + 'Rotation': array([-4.82143015e-02, -5.58151741e+01, 5.55052198e-02]), + 'Velocity': array([-0.22201915, 0.34657568, 0.00039124]), + 'brake_input': 0.0, + 'camera_location': array([-8.81703854, 15.51741886, -0.31881028]), + 'camera_rotation': array([-6.97612953, -6.36948395, -0.98747015]), + 'current_gear_input': False, + 'focus_actor_dist': 1734.867431640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -664.03857422, -3197.29736328, 72.03935242]), + 'frame': 34681, + 'frame_number': 34681, + 'framesequence': 132700, + 'gaze_dir': array([ 0.98919678, -0.12197876, 0.07892609]), + 'gaze_origin': array([-2.98901081, 0.09112702, -0.11081391]), + 'gaze_valid': True, + 'gaze_vergence': 127.20454406738281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99032593, -0.10614014, 0.08926392]), + 'left_gaze_origin': array([-2.90987253, 2.95279717, -0.08539887]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.067718505859375, + 'left_pupil_posn': array([ 0.14504373, -0.13077617]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98806763, -0.13781738, 0.06858826]), + 'right_gaze_origin': array([-3.06814885, -2.7705431 , -0.13622895]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1748199462890625, + 'right_pupil_posn': array([-0.32449704, -0.22656596]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02288888208568096, + 'throttle_input': 0.18649576604366302, + 'timestamp': 1115.0906768776476, + 'timestamp_carla': 1115094, + 'timestamp_device': 4268520, + 'timestamp_stream': 1115.0906768776476, + 'transform': [array([ 2.08639073e+00, 1.35177011e+01, -9.30976821e-04]), + array([-0.066246 , -8.65638733, 0.02831955])]} +{'AngularVelocity': array([-0.01747769, -0.00683028, 0.40517396]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.572075366973877, + 'FR_Wheel_Angle': -5.536761283874512, + 'Location': array([ -0.94788903, -26.51085091, 0.17034498]), + 'Rotation': array([-5.09668700e-02, -5.56646500e+01, 5.44034652e-02]), + 'Velocity': array([-2.17409700e-01, 3.57353657e-01, 2.49938952e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.83998299, 15.50046062, -0.31149986]), + 'camera_rotation': array([-7.00486422, -6.3142643 , -0.98692918]), + 'current_gear_input': False, + 'focus_actor_dist': 1726.7674560546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -653.01257324, -3197.34033203, 59.20944214]), + 'frame': 34682, + 'frame_number': 34682, + 'framesequence': 132704, + 'gaze_dir': array([ 0.98992157, -0.11828613, 0.07610321]), + 'gaze_origin': array([-2.98955154, 0.09367219, -0.10927278]), + 'gaze_valid': True, + 'gaze_vergence': 127.77571105957031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99038696, -0.10707092, 0.0874176 ]), + 'left_gaze_origin': array([-2.91450977, 2.95750284, -0.08227997]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.009735107421875, + 'left_pupil_posn': array([ 0.14476287, -0.13075101]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98945618, -0.12950134, 0.06478882]), + 'right_gaze_origin': array([-3.06459379, -2.77015853, -0.13626556]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.175018310546875, + 'right_pupil_posn': array([-0.32504362, -0.22656596]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.025067904964089394, + 'throttle_input': 0.17856107652187347, + 'timestamp': 1115.1228687763214, + 'timestamp_carla': 1115127, + 'timestamp_device': 4268554, + 'timestamp_stream': 1115.1228687763214, + 'transform': [array([ 2.10420656e+00, 1.34510860e+01, -5.48000331e-04]), + array([-0.066608 , -8.69069099, 0.0276191 ])]} +{'AngularVelocity': array([-0.01103288, 0.00195616, 0.09427197]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.748164176940918, + 'FR_Wheel_Angle': -6.475322246551514, + 'Location': array([ -1.00678194, -26.41549683, 0.17042276]), + 'Rotation': array([-5.37126064e-02, -5.54424210e+01, 5.43781072e-02]), + 'Velocity': array([-2.59863049e-01, 4.32140648e-01, 3.60002508e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.84799862, 15.48057365, -0.2827374 ]), + 'camera_rotation': array([-6.89449501, -6.43734169, -0.99871641]), + 'current_gear_input': False, + 'focus_actor_dist': 2495.6318359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -803.57513428, -3956.58837891, 17.57290649]), + 'frame': 34683, + 'frame_number': 34683, + 'framesequence': 132708, + 'gaze_dir': array([ 0.99008179, -0.11600494, 0.07434082]), + 'gaze_origin': array([-3.06826568, 0.09846726, -0.09080125]), + 'gaze_valid': True, + 'gaze_vergence': 8.998702049255371, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98823547, -0.11444092, 0.10144043]), + 'left_gaze_origin': array([-3.14181066, 2.97134399, -0.01578827]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2192840576171875, + 'left_pupil_posn': array([ 0.14119136, -0.13547993]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9919281 , -0.11756897, 0.04724121]), + 'right_gaze_origin': array([-2.9947207 , -2.77440953, -0.16581422]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1232147216796875, + 'right_pupil_posn': array([-0.32412547, -0.22840106]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0278328824788332, + 'throttle_input': 0.17062638700008392, + 'timestamp': 1115.1573123782873, + 'timestamp_carla': 1115161, + 'timestamp_device': 4268587, + 'timestamp_stream': 1115.1573123782873, + 'transform': [array([ 2.12521338e+00, 1.33789415e+01, -1.46026607e-04]), + array([-0.06705196, -8.73155212, 0.02684488])]} +{'AngularVelocity': array([-0.03980182, 0.01131197, 1.52115774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.721390247344971, + 'FR_Wheel_Angle': -7.280092239379883, + 'Location': array([ -1.07460725, -26.3045063 , 0.17051329]), + 'Rotation': array([-5.67315482e-02, -5.51319160e+01, 5.34230024e-02]), + 'Velocity': array([-3.11584592e-01, 5.24530947e-01, 2.73523328e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.87013531, 15.45203686, -0.25394434]), + 'camera_rotation': array([-6.69701385, -6.53846502, -0.95230108]), + 'current_gear_input': False, + 'focus_actor_dist': 1718.4105224609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -644.85620117, -3202.88867188, 54.12953186]), + 'frame': 34684, + 'frame_number': 34684, + 'framesequence': 132712, + 'gaze_dir': array([ 0.98797607, -0.12882233, 0.08252716]), + 'gaze_origin': array([-2.9426043 , 0.09115983, -0.13271028]), + 'gaze_valid': True, + 'gaze_vergence': 59.11397933959961, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98757935, -0.11930847, 0.1020813 ]), + 'left_gaze_origin': array([-2.89680648, 2.95622563, -0.09534913]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1297760009765625, + 'left_pupil_posn': array([ 0.14255071, -0.13697445]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9883728 , -0.13833618, 0.06297302]), + 'right_gaze_origin': array([-2.98840189, -2.77390599, -0.17007142]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1888427734375, + 'right_pupil_posn': array([-0.32605559, -0.22980845]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.031165504828095436, + 'throttle_input': 0.15078964829444885, + 'timestamp': 1115.191882777959, + 'timestamp_carla': 1115195, + 'timestamp_device': 4268620, + 'timestamp_stream': 1115.191882777959, + 'transform': [array([2.14862800e+00, 1.33056431e+01, 2.56481173e-04]), + array([-0.06757789, -8.77755165, 0.02607909])]} +{'AngularVelocity': array([0.04689901, 0.0260944 , 2.08024168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.6952409744262695, + 'FR_Wheel_Angle': -6.944544792175293, + 'Location': array([ -1.15519297, -26.17271996, 0.17063615]), + 'Rotation': array([-6.10072464e-02, -5.47235641e+01, 5.28980345e-02]), + 'Velocity': array([-4.15109277e-01, 6.94117665e-01, 6.69703470e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.89596844, 15.43887424, -0.24876092]), + 'camera_rotation': array([-6.66789007, -6.64457941, -0.99397445]), + 'current_gear_input': False, + 'focus_actor_dist': 1710.4541015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -669.08666992, -3197.24829102, 74.45573425]), + 'frame': 34685, + 'frame_number': 34685, + 'framesequence': 132716, + 'gaze_dir': array([ 0.98822784, -0.12921143, 0.07913971]), + 'gaze_origin': array([-2.9431076 , 0.09120025, -0.13232194]), + 'gaze_valid': True, + 'gaze_vergence': 67.8249282836914, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98805237, -0.11947632, 0.09719849]), + 'left_gaze_origin': array([-2.89708424, 2.95624709, -0.09518586]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.128448486328125, + 'left_pupil_posn': array([ 0.14231813, -0.13755274]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98840332, -0.13894653, 0.06108093]), + 'right_gaze_origin': array([-2.98913145, -2.77384639, -0.16945802]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2052459716796875, + 'right_pupil_posn': array([-0.3261795 , -0.23123765]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.034516435116529465, + 'throttle_input': 0.1269855797290802, + 'timestamp': 1115.2238070778549, + 'timestamp_carla': 1115227, + 'timestamp_device': 4268654, + 'timestamp_stream': 1115.2238070778549, + 'transform': [array([2.17250729e+00, 1.32371197e+01, 6.04038243e-04]), + array([-0.06810381, -8.82484245, 0.02546354])]} +{'AngularVelocity': array([-0.0360298 , -0.01852196, 1.39189744]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.38541316986084, + 'FR_Wheel_Angle': -6.0173821449279785, + 'Location': array([ -1.2481885 , -26.02495766, 0.1706737 ]), + 'Rotation': array([-5.12400754e-02, -5.43238106e+01, 5.65194450e-02]), + 'Velocity': array([-3.61782521e-01, 5.79819500e-01, 3.52563860e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.93364716, 15.42998791, -0.24319257]), + 'camera_rotation': array([-6.6175375 , -6.73155499, -0.90388584]), + 'current_gear_input': False, + 'focus_actor_dist': 1704.724853515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -672.83459473, -3197.22290039, 69.54737854]), + 'frame': 34686, + 'frame_number': 34686, + 'framesequence': 132720, + 'gaze_dir': array([ 0.98825836, -0.12928009, 0.07861328]), + 'gaze_origin': array([-2.94270802, 0.09116516, -0.13262787]), + 'gaze_valid': True, + 'gaze_vergence': 65.33930969238281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98805237, -0.11962891, 0.09706116]), + 'left_gaze_origin': array([-2.89708424, 2.95624709, -0.09518586]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.128997802734375, + 'left_pupil_posn': array([ 0.14233136, -0.13785672]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98846436, -0.13893127, 0.06016541]), + 'right_gaze_origin': array([-2.98833179, -2.77391672, -0.1700699 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2059326171875, + 'right_pupil_posn': array([-0.3261795 , -0.23156428]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.037757501006126404, + 'throttle_input': 0.1111009418964386, + 'timestamp': 1115.2570406794548, + 'timestamp_carla': 1115261, + 'timestamp_device': 4268687, + 'timestamp_stream': 1115.2570406794548, + 'transform': [array([2.19970942e+00, 1.31650839e+01, 1.00448611e-03]), + array([-0.06860241, -8.87913322, 0.02471844])]} +{'AngularVelocity': array([-0.0133659 , -0.00978929, 1.01356649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.630970478057861, + 'FR_Wheel_Angle': -6.439634323120117, + 'Location': array([ -1.32471216, -25.90639114, 0.17072508]), + 'Rotation': array([-4.57759239e-02, -5.40287170e+01, 5.63983247e-02]), + 'Velocity': array([-0.28240725, 0.44749999, 0.00064052]), + 'brake_input': 0.0, + 'camera_location': array([-8.96112156, 15.4189949 , -0.22309029]), + 'camera_rotation': array([-6.45886564, -6.7968955 , -0.91480178]), + 'current_gear_input': False, + 'focus_actor_dist': 1698.9901123046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -675.31488037, -3197.19921875, 70.6856842 ]), + 'frame': 34687, + 'frame_number': 34687, + 'framesequence': 132724, + 'gaze_dir': array([ 0.98839569, -0.12947083, 0.07649231]), + 'gaze_origin': array([-2.9428103 , 0.0911705 , -0.13254701]), + 'gaze_valid': True, + 'gaze_vergence': 62.58399200439453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98817444, -0.12001038, 0.09532166]), + 'left_gaze_origin': array([-2.89736032, 2.95626831, -0.09502259]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1586456298828125, + 'left_pupil_posn': array([ 0.14234591, -0.13870311]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98861694, -0.13893127, 0.05766296]), + 'right_gaze_origin': array([-2.98826003, -2.77392745, -0.17007142]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2201385498046875, + 'right_pupil_posn': array([-0.32630348, -0.23218048]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04110843688249588, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1115.290437977761, + 'timestamp_carla': 1115294, + 'timestamp_device': 4268720, + 'timestamp_stream': 1115.290437977761, + 'transform': [array([2.22937870e+00, 1.30921412e+01, 1.46846764e-03]), + array([-0.06905321, -8.93873596, 0.02384876])]} +{'AngularVelocity': array([ 2.00253469e-03, -2.79247652e-05, 1.00788617e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.453758239746094, + 'FR_Wheel_Angle': -7.852097511291504, + 'Location': array([ -1.38357604, -25.81470108, 0.17079245]), + 'Rotation': array([-4.57144529e-02, -5.37734032e+01, 5.49814329e-02]), + 'Velocity': array([-2.16159910e-01, 3.52377653e-01, 3.37686535e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.99104786, 15.4237175 , -0.19561748]), + 'camera_rotation': array([-6.27962112, -6.78316975, -1.01182711]), + 'current_gear_input': False, + 'focus_actor_dist': 1692.94482421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -677.68103027, -3197.17675781, 71.91104126]), + 'frame': 34688, + 'frame_number': 34688, + 'framesequence': 132728, + 'gaze_dir': array([ 0.98870087, -0.12956238, 0.07225037]), + 'gaze_origin': array([-2.9428103 , 0.0911705 , -0.13254471]), + 'gaze_valid': True, + 'gaze_vergence': 57.26782989501953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98841858, -0.12103271, 0.09138489]), + 'left_gaze_origin': array([-2.89736032, 2.95626831, -0.09502259]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.18267822265625, + 'left_pupil_posn': array([ 0.1426729 , -0.14031661]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98898315, -0.13809204, 0.05311584]), + 'right_gaze_origin': array([-2.98826003, -2.77392745, -0.17006683]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.234649658203125, + 'right_pupil_posn': array([-0.32667649, -0.23358262]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0443861223757267, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1115.3239635787904, + 'timestamp_carla': 1115328, + 'timestamp_device': 4268754, + 'timestamp_stream': 1115.3239635787904, + 'transform': [array([2.26136804e+00, 1.30185385e+01, 2.00029369e-03]), + array([-0.06947668, -9.00337696, 0.02284758])]} +{'AngularVelocity': array([-0.00354983, 0.00249802, 0.68573844]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.722949981689453, + 'FR_Wheel_Angle': -8.189583778381348, + 'Location': array([ -1.42811418, -25.74472618, 0.170836 ]), + 'Rotation': array([-4.64794338e-02, -5.35458717e+01, 5.52283712e-02]), + 'Velocity': array([-0.16024081, 0.26016748, 0.00032222]), + 'brake_input': 0.0, + 'camera_location': array([-9.01934528, 15.42490196, -0.17804305]), + 'camera_rotation': array([-6.15972376, -6.69108105, -1.05719519]), + 'current_gear_input': False, + 'focus_actor_dist': 1686.4945068359375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -677.76403809, -3197.18017578, 69.82917786]), + 'frame': 34689, + 'frame_number': 34689, + 'framesequence': 132732, + 'gaze_dir': array([ 0.98942566, -0.12754822, 0.06439209]), + 'gaze_origin': array([-2.99298048, 0.09306335, -0.11797791]), + 'gaze_valid': True, + 'gaze_vergence': 38.74808120727539, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98892212, -0.11964417, 0.08772278]), + 'left_gaze_origin': array([-2.94574761, 2.95785236, -0.07895966]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.24200439453125, + 'left_pupil_posn': array([ 0.14296985, -0.14305341]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9899292 , -0.13545227, 0.0410614 ]), + 'right_gaze_origin': array([-3.04021311, -2.77172542, -0.15699616]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2519683837890625, + 'right_pupil_posn': array([-0.3283177 , -0.23607385]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.047114480286836624, + 'throttle_input': 0.0476234070956707, + 'timestamp': 1115.3563280776143, + 'timestamp_carla': 1115360, + 'timestamp_device': 4268787, + 'timestamp_stream': 1115.3563280776143, + 'transform': [array([2.29407716e+00, 1.29472790e+01, 2.56414409e-03]), + array([-0.0697977 , -9.06977844, 0.0218016 ])]} +{'AngularVelocity': array([-0.00764208, 0.00625591, 2.01957321]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.357563972473145, + 'FR_Wheel_Angle': -9.631948471069336, + 'Location': array([ -1.46332455, -25.68901634, 0.17088945]), + 'Rotation': array([-4.87402268e-02, -5.33443909e+01, 5.42970374e-02]), + 'Velocity': array([-1.30461648e-01, 2.16468975e-01, 1.18436808e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.04496765, 15.4332943 , -0.16790883]), + 'camera_rotation': array([-6.09933138, -6.57924175, -1.10377944]), + 'current_gear_input': False, + 'focus_actor_dist': 1679.1485595703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -671.84783936, -3197.31738281, 60.22180176]), + 'frame': 34690, + 'frame_number': 34690, + 'framesequence': 132737, + 'gaze_dir': array([ 0.99017334, -0.12534332, 0.05812073]), + 'gaze_origin': array([-3.03322768, 0.09621659, -0.1067215 ]), + 'gaze_valid': True, + 'gaze_vergence': 23.969715118408203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98937988, -0.12203979, 0.07875061]), + 'left_gaze_origin': array([-3.02331567, 2.96369791, -0.05753479]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2849578857421875, + 'left_pupil_posn': array([ 0.14195538, -0.14477754]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9909668 , -0.12864685, 0.03749084]), + 'right_gaze_origin': array([-3.0431397 , -2.77126479, -0.15590821]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2618255615234375, + 'right_pupil_posn': array([-0.32954055, -0.23909247]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04998932033777237, + 'throttle_input': 0.035706110298633575, + 'timestamp': 1115.3924551792443, + 'timestamp_carla': 1115396, + 'timestamp_device': 4268829, + 'timestamp_stream': 1115.3924551792443, + 'transform': [array([2.33243465e+00, 1.28678789e+01, 3.28372954e-03]), + array([-0.07006408, -9.14802742, 0.02039306])]} +{'AngularVelocity': array([-1.17004234e-02, -1.38736272e-03, 1.98794270e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.650607109069824, + 'FR_Wheel_Angle': -11.56149959564209, + 'Location': array([ -1.49332702, -25.64042854, 0.17093892]), + 'Rotation': array([-5.06253578e-02, -5.31418533e+01, 5.36914952e-02]), + 'Velocity': array([-0.1137273 , 0.19624133, 0.00047938]), + 'brake_input': 0.0, + 'camera_location': array([-9.05583954, 15.4407959 , -0.14417696]), + 'camera_rotation': array([-6.01911068, -6.45393801, -1.14005935]), + 'current_gear_input': False, + 'focus_actor_dist': 2361.022705078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -819.15026855, -3868.30712891, 17.58945465]), + 'frame': 34691, + 'frame_number': 34691, + 'framesequence': 132740, + 'gaze_dir': array([ 0.99124908, -0.1190033 , 0.04951477]), + 'gaze_origin': array([-3.11566544, 0.10200654, -0.08056946]), + 'gaze_valid': True, + 'gaze_vergence': 8.933005332946777, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98945618, -0.12225342, 0.07746887]), + 'left_gaze_origin': array([-3.18704844, 2.97429204, -0.00532379]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.253570556640625, + 'left_pupil_posn': array([ 0.14034486, -0.14641094]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99304199, -0.11575317, 0.02156067]), + 'right_gaze_origin': array([-3.04428267, -2.77027893, -0.15581514]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.26898193359375, + 'right_pupil_posn': array([-0.33030683, -0.23973727]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.052754297852516174, + 'throttle_input': 0.0317387655377388, + 'timestamp': 1115.4239681772888, + 'timestamp_carla': 1115428, + 'timestamp_device': 4268854, + 'timestamp_stream': 1115.4239681772888, + 'transform': [array([2.36734891e+00, 1.27986889e+01, 3.92105104e-03]), + array([-0.07031679, -9.21954346, 0.01923143])]} +{'AngularVelocity': array([0.06796096, 0.00615884, 1.30385756]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.938422203063965, + 'FR_Wheel_Angle': -13.295084953308105, + 'Location': array([ -1.52339458, -25.59013557, 0.1709958 ]), + 'Rotation': array([-5.47234714e-02, -5.29002495e+01, 5.18083237e-02]), + 'Velocity': array([-1.53698906e-01, 2.76660651e-01, 1.67379374e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.06301594, 15.456563 , -0.13798273]), + 'camera_rotation': array([-5.95492077, -6.29429293, -1.25039196]), + 'current_gear_input': False, + 'focus_actor_dist': 2059.982666015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -737.16796875, -3584.91308594, 17.50688934]), + 'frame': 34692, + 'frame_number': 34692, + 'framesequence': 132744, + 'gaze_dir': array([ 0.99113464, -0.12129974, 0.046875 ]), + 'gaze_origin': array([-3.1269815 , 0.10638504, -0.07923966]), + 'gaze_valid': True, + 'gaze_vergence': 17.01984405517578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98928833, -0.12626648, 0.07315063]), + 'left_gaze_origin': array([-3.18704844, 2.97608948, -0.00664673]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.240997314453125, + 'left_pupil_posn': array([ 0.13889837, -0.14764559]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99298096, -0.11633301, 0.02059937]), + 'right_gaze_origin': array([-3.06691456, -2.76331949, -0.15183258]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3247222900390625, + 'right_pupil_posn': array([-0.33681756, -0.24305999]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05465865135192871, + 'throttle_input': 0.027771420776844025, + 'timestamp': 1115.4576999768615, + 'timestamp_carla': 1115461, + 'timestamp_device': 4268887, + 'timestamp_stream': 1115.4576999768615, + 'transform': [array([2.40587878e+00, 1.27249422e+01, 4.60008625e-03]), + array([-0.07050804, -9.29876804, 0.01794613])]} +{'AngularVelocity': array([0.07529064, 0.00318093, 2.12929153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.662027359008789, + 'FR_Wheel_Angle': -13.638577461242676, + 'Location': array([ -1.57075453, -25.5100174 , 0.1710785 ]), + 'Rotation': array([-5.98734356e-02, -5.24379692e+01, 4.95830551e-02]), + 'Velocity': array([-0.23923235, 0.43361342, 0.00051301]), + 'brake_input': 0.0, + 'camera_location': array([-9.07040596, 15.47817898, -0.13688949]), + 'camera_rotation': array([-5.96088314, -6.12040997, -1.27890003]), + 'current_gear_input': False, + 'focus_actor_dist': 1996.8646240234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -725.14550781, -3529.07861328, 17.49488831]), + 'frame': 34693, + 'frame_number': 34693, + 'framesequence': 132748, + 'gaze_dir': array([ 0.99077606, -0.11856079, 0.06206512]), + 'gaze_origin': array([-2.94992542, 0.08146897, -0.13387834]), + 'gaze_valid': True, + 'gaze_vergence': 95.57080841064453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99156189, -0.10404968, 0.0771637 ]), + 'left_gaze_origin': array([-2.85481739, 2.94670725, -0.1121933 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2534332275390625, + 'left_pupil_posn': array([ 0.1506573 , -0.14598572]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98999023, -0.1330719 , 0.04696655]), + 'right_gaze_origin': array([-3.04503345, -2.78376937, -0.15556335]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1916351318359375, + 'right_pupil_posn': array([-0.31473136, -0.23951828]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05637989565730095, + 'throttle_input': 0.0238040741533041, + 'timestamp': 1115.489937376231, + 'timestamp_carla': 1115494, + 'timestamp_device': 4268920, + 'timestamp_stream': 1115.489937376231, + 'transform': [array([2.44348454e+00, 1.26548386e+01, 5.22935856e-03]), + array([-0.07059 , -9.37635422, 0.01678098])]} +{'AngularVelocity': array([ 3.56528535e-02, -3.67668341e-04, 3.09359336e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.624430656433105, + 'FR_Wheel_Angle': -13.61246395111084, + 'Location': array([ -1.63882077, -25.39737701, 0.17115781]), + 'Rotation': array([-6.29879981e-02, -5.17771416e+01, 4.90396284e-02]), + 'Velocity': array([-3.3015278e-01, 5.7830137e-01, 2.1044731e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.07396126, 15.49346161, -0.13502748]), + 'camera_rotation': array([-5.96985817, -5.92316246, -1.21863639]), + 'current_gear_input': False, + 'focus_actor_dist': 2648.114990234375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST40', + 'focus_actor_pt': array([ -856.26782227, -4174.82910156, 19.13179779]), + 'frame': 34694, + 'frame_number': 34694, + 'framesequence': 132752, + 'gaze_dir': array([ 0.99446869, -0.06970978, 0.0764389 ]), + 'gaze_origin': array([-2.91223073, 0.03983155, -0.14204332]), + 'gaze_valid': True, + 'gaze_vergence': 161.2196807861328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99542236, -0.05259705, 0.0796814 ]), + 'left_gaze_origin': array([-2.76479959, 2.89839482, -0.13974763]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2945709228515625, + 'left_pupil_posn': array([ 0.1975801 , -0.13803709]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99351501, -0.08682251, 0.07319641]), + 'right_gaze_origin': array([-3.05966187, -2.81873178, -0.144339 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2309722900390625, + 'right_pupil_posn': array([-0.27277833, -0.23401296]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05769829824566841, + 'throttle_input': 0.019836727529764175, + 'timestamp': 1115.5226806774735, + 'timestamp_carla': 1115526, + 'timestamp_device': 4268954, + 'timestamp_stream': 1115.5226806774735, + 'transform': [array([2.48216009e+00, 1.25841436e+01, 5.83566632e-03]), + array([-0.07057634, -9.45639324, 0.01564792])]} +{'AngularVelocity': array([-0.01708729, -0.0058395 , 3.16435933]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.621965408325195, + 'FR_Wheel_Angle': -13.606313705444336, + 'Location': array([ -1.72157478, -25.26314735, 0.17121767]), + 'Rotation': array([ -0.05880792, -50.99909592, 0.05109842]), + 'Velocity': array([-3.47186238e-01, 5.92811346e-01, 4.94155858e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.06628132, 15.52058506, -0.12759772]), + 'camera_rotation': array([-5.92903423, -5.73314571, -1.25553429]), + 'current_gear_input': False, + 'focus_actor_dist': 1624.9248046875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -557.13574219, -3198.91259766, 87.67681885]), + 'frame': 34695, + 'frame_number': 34695, + 'framesequence': 132756, + 'gaze_dir': array([ 0.99463654, -0.07224274, 0.07125854]), + 'gaze_origin': array([-2.9117198 , 0.04141617, -0.14279404]), + 'gaze_valid': True, + 'gaze_vergence': 138.52427673339844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99555969, -0.05354309, 0.07730103]), + 'left_gaze_origin': array([-2.7717135 , 2.90095377, -0.13831329]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2806243896484375, + 'left_pupil_posn': array([ 0.19457066, -0.14113486]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99371338, -0.09094238, 0.06521606]), + 'right_gaze_origin': array([-3.05172586, -2.81812143, -0.14727479]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.217437744140625, + 'right_pupil_posn': array([-0.27350122, -0.23526168]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05887020751833916, + 'throttle_input': 0.0158693827688694, + 'timestamp': 1115.5573211759329, + 'timestamp_carla': 1115561, + 'timestamp_device': 4268987, + 'timestamp_stream': 1115.5573211759329, + 'transform': [array([2.52333856e+00, 1.25101051e+01, 6.45723334e-03]), + array([-0.07047389, -9.54186535, 0.0144579 ])]} +{'AngularVelocity': array([-0.00462916, 0.00460998, 3.74956536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.051864624023438, + 'FR_Wheel_Angle': -12.994705200195312, + 'Location': array([ -1.81349778, -25.11890984, 0.17135049]), + 'Rotation': array([ -0.06033789, -50.16101837, 0.0507429 ]), + 'Velocity': array([-4.13248897e-01, 6.76236689e-01, 3.92875663e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.0403204 , 15.54141712, -0.13285835]), + 'camera_rotation': array([-5.89054585, -5.55726242, -1.28671372]), + 'current_gear_input': False, + 'focus_actor_dist': 1619.36767578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -557.22058105, -3199.38037109, 80.42256165]), + 'frame': 34696, + 'frame_number': 34696, + 'framesequence': 132760, + 'gaze_dir': array([ 0.99531555, -0.06984711, 0.06365967]), + 'gaze_origin': array([-2.94686985, 0.04393234, -0.12894136]), + 'gaze_valid': True, + 'gaze_vergence': 107.26131439208984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99549866, -0.05508423, 0.07701111]), + 'left_gaze_origin': array([-2.84239197, 2.90570545, -0.1106537 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2569427490234375, + 'left_pupil_posn': array([ 0.19436228, -0.14111066]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99513245, -0.08460999, 0.05030823]), + 'right_gaze_origin': array([-3.05134749, -2.81784058, -0.14722902]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2194366455078125, + 'right_pupil_posn': array([-0.27422607, -0.23529124]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05945616215467453, + 'throttle_input': 0.01190203707665205, + 'timestamp': 1115.589265178889, + 'timestamp_carla': 1115593, + 'timestamp_device': 4269020, + 'timestamp_stream': 1115.589265178889, + 'transform': [array([2.56129813e+00, 1.24424715e+01, 6.97763450e-03]), + array([-0.07030313, -9.62087727, 0.01351256])]} +{'AngularVelocity': array([-0.02916506, -0.00677534, 3.34210134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.096226692199707, + 'FR_Wheel_Angle': -11.444445610046387, + 'Location': array([ -1.93506646, -24.93833733, 0.17146318]), + 'Rotation': array([ -0.05776974, -49.18535995, 0.05337355]), + 'Velocity': array([-4.44440842e-01, 6.72252059e-01, 5.95540972e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.03466797, 15.56182766, -0.12598488]), + 'camera_rotation': array([-5.97049332, -5.37916374, -1.22225547]), + 'current_gear_input': False, + 'focus_actor_dist': 1611.3524169921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -549.47998047, -3198.72460938, 69.46523285]), + 'frame': 34697, + 'frame_number': 34697, + 'framesequence': 132764, + 'gaze_dir': array([ 0.99530792, -0.06944275, 0.06446838]), + 'gaze_origin': array([-2.94741917, 0.04455566, -0.12882768]), + 'gaze_valid': True, + 'gaze_vergence': 111.53141784667969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99545288, -0.05548096, 0.07733154]), + 'left_gaze_origin': array([-2.84305882, 2.90675378, -0.11078339]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2555084228515625, + 'left_pupil_posn': array([ 0.19406843, -0.14086998]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99516296, -0.08340454, 0.05160522]), + 'right_gaze_origin': array([-3.05177927, -2.81764221, -0.14687195]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2308349609375, + 'right_pupil_posn': array([-0.27450013, -0.23503804]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05951109528541565, + 'throttle_input': 0.0, + 'timestamp': 1115.6226863786578, + 'timestamp_carla': 1115626, + 'timestamp_device': 4269054, + 'timestamp_stream': 1115.6226863786578, + 'transform': [array([2.60083485e+00, 1.23720503e+01, 7.26285903e-03]), + array([-0.07006408, -9.70343113, 0.0129988 ])]} +{'AngularVelocity': array([-0.01003298, -0.01240286, 2.43775225]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.356325149536133, + 'FR_Wheel_Angle': -10.139333724975586, + 'Location': array([ -2.03558683, -24.79798317, 0.17153558]), + 'Rotation': array([ -0.05215532, -48.51621246, 0.05497107]), + 'Velocity': array([-3.88960004e-01, 5.54056942e-01, 1.78146365e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.01636505, 15.58389759, -0.10625205]), + 'camera_rotation': array([-5.97321177, -5.24307203, -1.17931342]), + 'current_gear_input': False, + 'focus_actor_dist': 1604.2843017578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -545.02258301, -3198.29174805, 68.93386078]), + 'frame': 34698, + 'frame_number': 34698, + 'framesequence': 132768, + 'gaze_dir': array([ 0.99512482, -0.07124329, 0.06570435]), + 'gaze_origin': array([-2.94713926, 0.04509201, -0.12946472]), + 'gaze_valid': True, + 'gaze_vergence': 128.57937622070312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99546814, -0.05665588, 0.07635498]), + 'left_gaze_origin': array([-2.84204865, 2.90745711, -0.11250153]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2521209716796875, + 'left_pupil_posn': array([ 0.19275343, -0.14065349]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99478149, -0.08583069, 0.05505371]), + 'right_gaze_origin': array([-3.0522294 , -2.81727314, -0.14642793]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.209136962890625, + 'right_pupil_posn': array([-0.27516145, -0.23509884]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05958434194326401, + 'throttle_input': 0.0, + 'timestamp': 1115.6560907773674, + 'timestamp_carla': 1115660, + 'timestamp_device': 4269087, + 'timestamp_stream': 1115.6560907773674, + 'transform': [array([2.64005804e+00, 1.23021212e+01, 7.45719904e-03]), + array([-0.06974988, -9.78555489, 0.01266629])]} +{'AngularVelocity': array([ 0.02057036, -0.00726324, 1.79215896]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.811905860900879, + 'FR_Wheel_Angle': -9.798884391784668, + 'Location': array([ -2.1085012 , -24.69999886, 0.17161314]), + 'Rotation': array([ -0.05027019, -48.08664703, 0.05383009]), + 'Velocity': array([-3.27711493e-01, 4.55086738e-01, 2.01559058e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.00204468, 15.61103821, -0.12540394]), + 'camera_rotation': array([-6.0314188 , -5.09752846, -1.1455586 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1598.6087646484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -545.62194824, -3198.82275391, 71.11772156]), + 'frame': 34699, + 'frame_number': 34699, + 'framesequence': 132772, + 'gaze_dir': array([ 0.9949646 , -0.07322693, 0.06617737]), + 'gaze_origin': array([-2.94678497, 0.04565506, -0.12918702]), + 'gaze_valid': True, + 'gaze_vergence': 141.1132354736328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99537659, -0.05908203, 0.07556152]), + 'left_gaze_origin': array([-2.84081125, 2.90818644, -0.11250153]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2390594482421875, + 'left_pupil_posn': array([ 0.19171071, -0.13978696]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99455261, -0.08737183, 0.05679321]), + 'right_gaze_origin': array([-3.05275893, -2.81687641, -0.1458725 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2091217041015625, + 'right_pupil_posn': array([-0.27627671, -0.23508692]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05958434194326401, + 'throttle_input': 0.0, + 'timestamp': 1115.689158976078, + 'timestamp_carla': 1115693, + 'timestamp_device': 4269120, + 'timestamp_stream': 1115.689158976078, + 'transform': [array([2.67842245e+00, 1.22335243e+01, 7.66378408e-03]), + array([-0.06941521, -9.86609077, 0.01231558])]} +{'AngularVelocity': array([0.0227869 , 0.00496993, 1.55742216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.833877563476562, + 'FR_Wheel_Angle': -9.816536903381348, + 'Location': array([ -2.17785358, -24.60854912, 0.17168961]), + 'Rotation': array([ -0.05100102, -47.68725967, 0.05191488]), + 'Velocity': array([-2.64685005e-01, 3.61612350e-01, 1.95980072e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.99725151, 15.6467371 , -0.15216921]), + 'camera_rotation': array([-6.10135317, -4.98402452, -1.16527295]), + 'current_gear_input': False, + 'focus_actor_dist': 1592.4429931640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -546.14117432, -3198.70263672, 70.50584412]), + 'frame': 34700, + 'frame_number': 34700, + 'framesequence': 132776, + 'gaze_dir': array([ 0.99493408, -0.07077789, 0.06899261]), + 'gaze_origin': array([-2.95070052, 0.04121247, -0.12723771]), + 'gaze_valid': True, + 'gaze_vergence': 125.9285888671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99517822, -0.05656433, 0.08007812]), + 'left_gaze_origin': array([-2.84216166, 2.90581536, -0.11053925]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1584014892578125, + 'left_pupil_posn': array([ 0.19415891, -0.13850117]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99468994, -0.08499146, 0.0579071 ]), + 'right_gaze_origin': array([-3.05923939, -2.82339025, -0.14393616]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.098358154296875, + 'right_pupil_posn': array([-0.2709536, -0.2335937]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05958434194326401, + 'throttle_input': 0.0, + 'timestamp': 1115.7214839756489, + 'timestamp_carla': 1115725, + 'timestamp_device': 4269154, + 'timestamp_stream': 1115.7214839756489, + 'transform': [array([2.71543550e+00, 1.21671638e+01, 7.90451001e-03]), + array([-0.06910102, -9.94396973, 0.01190533])]} +{'AngularVelocity': array([0.00023499, 0.00343805, 0.10974043]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.850214004516602, + 'FR_Wheel_Angle': -9.828277587890625, + 'Location': array([ -2.23357487, -24.53602791, 0.17177095]), + 'Rotation': array([ -0.05261295, -47.37918472, 0.0506783 ]), + 'Velocity': array([-0.21283706, 0.28635278, 0.00062245]), + 'brake_input': 0.0, + 'camera_location': array([-8.98000336, 15.6943512 , -0.1702136 ]), + 'camera_rotation': array([-6.12805223, -4.83709192, -1.2695353 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1585.702392578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST37', + 'focus_actor_pt': array([ -540.60992432, -3198.96655273, 73.29205322]), + 'frame': 34701, + 'frame_number': 34701, + 'framesequence': 132780, + 'gaze_dir': array([0.99671936, 0.01391602, 0.07727814]), + 'gaze_origin': array([-2.96243525, -0.01163635, -0.12028428]), + 'gaze_valid': True, + 'gaze_vergence': 123.4078140258789, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99736023, 0.02938843, 0.06622314]), + 'left_gaze_origin': array([-2.74047875, 2.8487885 , -0.14580537]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.223419189453125, + 'left_pupil_posn': array([ 0.25900805, -0.1327126 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99607849, -0.0015564 , 0.08833313]), + 'right_gaze_origin': array([-3.18439198, -2.87206125, -0.09476319]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0113372802734375, + 'right_pupil_posn': array([-0.20779687, -0.22914732]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05958434194326401, + 'throttle_input': 0.0, + 'timestamp': 1115.7561521790922, + 'timestamp_carla': 1115760, + 'timestamp_device': 4269187, + 'timestamp_stream': 1115.7561521790922, + 'transform': [array([2.75457025e+00, 1.20967989e+01, 8.15021526e-03]), + array([ -0.06879366, -10.02655697, 0.01144832])]} +{'AngularVelocity': array([0.01540061, 0.0045966 , 0.83045739]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.84162712097168, + 'FR_Wheel_Angle': -9.82673454284668, + 'Location': array([ -2.28331017, -24.47204018, 0.17184775]), + 'Rotation': array([ -0.05740774, -47.1027565 , 0.04847832]), + 'Velocity': array([-0.22293819, 0.2986297 , 0.00029996]), + 'brake_input': 0.0, + 'camera_location': array([-8.95880795, 15.72869205, -0.17802876]), + 'camera_rotation': array([-6.24473238, -4.70921421, -1.11802721]), + 'current_gear_input': False, + 'focus_actor_dist': 3998.875244140625, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -577.71063232, -5626.81640625, 17.41929626]), + 'frame': 34702, + 'frame_number': 34702, + 'framesequence': 132784, + 'gaze_dir': array([0.99684143, 0.01307678, 0.07678223]), + 'gaze_origin': array([-2.95102477, -0.01226654, -0.12359543]), + 'gaze_valid': True, + 'gaze_vergence': 166.6071014404297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99728394, 0.02534485, 0.06893921]), + 'left_gaze_origin': array([-2.73900151, 2.84814453, -0.14652559]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.350189208984375, + 'left_pupil_posn': array([ 0.26020086, -0.13396847]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([9.96398926e-01, 8.08715820e-04, 8.46252441e-02]), + 'right_gaze_origin': array([-3.16304779, -2.8726778 , -0.10066529]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0504608154296875, + 'right_pupil_posn': array([-0.20878863, -0.22822046]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05958434194326401, + 'throttle_input': 0.0, + 'timestamp': 1115.789186079055, + 'timestamp_carla': 1115793, + 'timestamp_device': 4269220, + 'timestamp_stream': 1115.789186079055, + 'transform': [array([2.79128981e+00, 1.20305748e+01, 8.39363039e-03]), + array([ -0.06853411, -10.10421848, 0.01102998])]} +{'AngularVelocity': array([ 0.01811474, -0.02597113, 2.28564382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.807578086853027, + 'FR_Wheel_Angle': -9.794742584228516, + 'Location': array([ -2.36329198, -24.37091446, 0.17199574]), + 'Rotation': array([-6.66763037e-02, -4.66508713e+01, 4.52241525e-02]), + 'Velocity': array([-3.55448633e-01, 4.73377794e-01, 3.86037806e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.95688152, 15.75796032, -0.15366663]), + 'camera_rotation': array([-6.29627991, -4.60780811, -0.98494858]), + 'current_gear_input': False, + 'focus_actor_dist': 3674.155029296875, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -554.1574707 , -5309.06347656, 17.35358429]), + 'frame': 34703, + 'frame_number': 34703, + 'framesequence': 132788, + 'gaze_dir': array([0.99687195, 0.01381683, 0.0759964 ]), + 'gaze_origin': array([-2.95958948, -0.01119156, -0.12111359]), + 'gaze_valid': True, + 'gaze_vergence': 155.32037353515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99728394, 0.02784729, 0.06803894]), + 'left_gaze_origin': array([-2.73504043, 2.84943867, -0.14813691]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3421173095703125, + 'left_pupil_posn': array([ 0.25892317, -0.13447738]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 9.96459961e-01, -2.13623047e-04, 8.39538574e-02]), + 'right_gaze_origin': array([-3.18413854, -2.87182188, -0.09409028]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0233917236328125, + 'right_pupil_posn': array([-0.20851332, -0.22816896]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05958434194326401, + 'throttle_input': 0.0, + 'timestamp': 1115.823813777417, + 'timestamp_carla': 1115828, + 'timestamp_device': 4269254, + 'timestamp_stream': 1115.823813777417, + 'transform': [array([2.82920003e+00, 1.19620161e+01, 8.60677660e-03]), + array([ -0.06827457, -10.1846056 , 0.01064509])]} +{'AngularVelocity': array([-0.03897639, 0.01449132, 1.69217491]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.294950485229492, + 'FR_Wheel_Angle': -9.14619255065918, + 'Location': array([ -2.44391966, -24.27017021, 0.17204702]), + 'Rotation': array([ -0.0621274 , -46.20630646, 0.04714158]), + 'Velocity': array([-3.67284715e-01, 4.66197759e-01, 9.04178596e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.92683887, 15.77754974, -0.14738731]), + 'camera_rotation': array([-6.22749281, -4.48797798, -0.90308446]), + 'current_gear_input': False, + 'focus_actor_dist': 3488.997314453125, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -536.48529053, -5130.44628906, 17.31253815]), + 'frame': 34704, + 'frame_number': 34704, + 'framesequence': 132792, + 'gaze_dir': array([0.99682617, 0.01397705, 0.07643127]), + 'gaze_origin': array([-2.95965672, -0.01087494, -0.12227251]), + 'gaze_valid': True, + 'gaze_vergence': 144.24754333496094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99732971, 0.02809143, 0.06732178]), + 'left_gaze_origin': array([-2.73404098, 2.84996057, -0.1504471 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.32220458984375, + 'left_pupil_posn': array([ 0.25858855, -0.13528419]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 9.96322632e-01, -1.37329102e-04, 8.55407715e-02]), + 'right_gaze_origin': array([-3.18527222, -2.87171054, -0.0940979 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.033905029296875, + 'right_pupil_posn': array([-0.20851332, -0.2286222 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05938291549682617, + 'throttle_input': 0.0, + 'timestamp': 1115.8567533791065, + 'timestamp_carla': 1115861, + 'timestamp_device': 4269287, + 'timestamp_stream': 1115.8567533791065, + 'transform': [array([2.86458373e+00, 1.18976574e+01, 8.81828275e-03]), + array([ -0.06804234, -10.25982761, 0.010294 ])]} +{'AngularVelocity': array([0.07255321, 0.05124707, 2.1085763 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.656718730926514, + 'FR_Wheel_Angle': -5.9497971534729, + 'Location': array([ -2.53290534, -24.1634922 , 0.1721755 ]), + 'Rotation': array([ -0.06353442, -45.80381775, 0.04859035]), + 'Velocity': array([-0.46222815, 0.55025113, 0.00144932]), + 'brake_input': 0.0, + 'camera_location': array([-8.91987133, 15.80172348, -0.16163069]), + 'camera_rotation': array([-6.231987 , -4.40607262, -0.96159494]), + 'current_gear_input': False, + 'focus_actor_dist': 3664.43603515625, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -545.44207764, -5311.87402344, 17.34600067]), + 'frame': 34705, + 'frame_number': 34705, + 'framesequence': 132796, + 'gaze_dir': array([0.99698639, 0.0124588 , 0.07452393]), + 'gaze_origin': array([-2.96051955, -0.01080322, -0.12141495]), + 'gaze_valid': True, + 'gaze_vergence': 147.65008544921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99742126, 0.02731323, 0.06620789]), + 'left_gaze_origin': array([-2.73427439, 2.8500824 , -0.14967652]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3026275634765625, + 'left_pupil_posn': array([ 0.25774825, -0.13568389]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99655151, -0.00239563, 0.08283997]), + 'right_gaze_origin': array([-3.18676448, -2.87168908, -0.09315339]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0336151123046875, + 'right_pupil_posn': array([-0.20880342, -0.2286787 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.059144873172044754, + 'throttle_input': 0.0, + 'timestamp': 1115.8908523768187, + 'timestamp_carla': 1115895, + 'timestamp_device': 4269320, + 'timestamp_stream': 1115.8908523768187, + 'transform': [array([2.90053058e+00, 1.18319187e+01, 8.98740720e-03]), + array([-6.78032860e-02, -1.03364248e+01, 1.00036729e-02])]} +{'AngularVelocity': array([ 7.41765834e-05, -6.34161988e-03, 1.45950150e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.188959121704102, + 'FR_Wheel_Angle': -3.9554007053375244, + 'Location': array([ -2.65326095, -24.02881813, 0.17238306]), + 'Rotation': array([ -0.07205166, -45.47978592, 0.0487743 ]), + 'Velocity': array([-6.59362614e-01, 7.35101283e-01, 4.24547179e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.90615273, 15.82374001, -0.18492979]), + 'camera_rotation': array([-6.31763077, -4.28954029, -1.00825143]), + 'current_gear_input': False, + 'focus_actor_dist': 3447.998779296875, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -535.72644043, -5101.16748047, 17.30770874]), + 'frame': 34706, + 'frame_number': 34706, + 'framesequence': 132800, + 'gaze_dir': array([0.99700928, 0.01097107, 0.07440948]), + 'gaze_origin': array([-2.95996952, -0.01058502, -0.12156221]), + 'gaze_valid': True, + 'gaze_vergence': 143.55613708496094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99746704, 0.02644348, 0.065979 ]), + 'left_gaze_origin': array([-2.73439813, 2.85043502, -0.14967652]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.296875, + 'left_pupil_posn': array([ 0.25680101, -0.13568389]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99655151, -0.00450134, 0.08283997]), + 'right_gaze_origin': array([-3.18554091, -2.87160492, -0.09344788]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.02044677734375, + 'right_pupil_posn': array([-0.20916212, -0.2286787 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.059016697108745575, + 'throttle_input': 0.0, + 'timestamp': 1115.9229795783758, + 'timestamp_carla': 1115927, + 'timestamp_device': 4269354, + 'timestamp_stream': 1115.9229795783758, + 'transform': [array([2.93376946e+00, 1.17707930e+01, 9.13616177e-03]), + array([-6.75983801e-02, -1.04074373e+01, 9.78123769e-03])]} +{'AngularVelocity': array([ 0.00473132, -0.04242423, 1.9993335 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.197158336639404, + 'FR_Wheel_Angle': -5.358516216278076, + 'Location': array([ -2.81281066, -23.85564232, 0.17248331]), + 'Rotation': array([ -0.06957913, -45.13679123, 0.04597943]), + 'Velocity': array([-7.54815817e-01, 8.42226923e-01, 6.19230268e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.90580273, 15.83956051, -0.1839077 ]), + 'camera_rotation': array([-6.29371834, -4.18229437, -0.98352104]), + 'current_gear_input': False, + 'focus_actor_dist': 3289.75830078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -527.60998535, -4948.83496094, 17.28582764]), + 'frame': 34707, + 'frame_number': 34707, + 'framesequence': 132804, + 'gaze_dir': array([0.99701691, 0.01013184, 0.07441711]), + 'gaze_origin': array([-2.96195769, -0.01000595, -0.12030717]), + 'gaze_valid': True, + 'gaze_vergence': 145.61483764648438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99749756, 0.02523804, 0.06600952]), + 'left_gaze_origin': array([-2.7375505 , 2.85161757, -0.14745027]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.28741455078125, + 'left_pupil_posn': array([ 0.25590169, -0.13479853]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99653625, -0.00497437, 0.08282471]), + 'right_gaze_origin': array([-3.18636489, -2.87162948, -0.09316407]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0168914794921875, + 'right_pupil_posn': array([-0.209571 , -0.22863686]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.059016697108745575, + 'throttle_input': 0.0, + 'timestamp': 1115.9563536792994, + 'timestamp_carla': 1115960, + 'timestamp_device': 4269387, + 'timestamp_stream': 1115.9563536792994, + 'transform': [array([2.96774435e+00, 1.17081175e+01, 9.25256684e-03]), + array([-6.74207956e-02, -1.04801960e+01, 9.59535129e-03])]} +{'AngularVelocity': array([-0.07563823, -0.03420269, 2.7255919 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.07701587677002, + 'FR_Wheel_Angle': -8.699960708618164, + 'Location': array([ -2.94200802, -23.71203804, 0.17258959]), + 'Rotation': array([-6.08228296e-02, -4.46974297e+01, 4.29713614e-02]), + 'Velocity': array([-0.66941893, 0.77811176, -0.00164585]), + 'brake_input': 0.0, + 'camera_location': array([-8.91682434, 15.85147381, -0.18034282]), + 'camera_rotation': array([-6.3681469 , -4.12428331, -0.97601926]), + 'current_gear_input': False, + 'focus_actor_dist': 3327.173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -531.04901123, -4991.52246094, 17.2925415 ]), + 'frame': 34708, + 'frame_number': 34708, + 'framesequence': 132808, + 'gaze_dir': array([0.99691772, 0.00957489, 0.07566833]), + 'gaze_origin': array([-2.96469045, -0.00979996, -0.11925431]), + 'gaze_valid': True, + 'gaze_vergence': 138.55030822753906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99746704, 0.02485657, 0.06648254]), + 'left_gaze_origin': array([-2.74301624, 2.85200524, -0.14552765]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.271270751953125, + 'left_pupil_posn': array([ 0.25547564, -0.13383305]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99636841, -0.00570679, 0.08485413]), + 'right_gaze_origin': array([-3.18636489, -2.87160492, -0.09298097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0172576904296875, + 'right_pupil_posn': array([-0.20971328, -0.22832644]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.059016697108745575, + 'throttle_input': 0.0, + 'timestamp': 1115.990143276751, + 'timestamp_carla': 1115994, + 'timestamp_device': 4269420, + 'timestamp_stream': 1115.990143276751, + 'transform': [array([3.00160241e+00, 1.16455059e+01, 9.33336280e-03]), + array([-6.72568679e-02, -1.05528631e+01, 9.47390590e-03])]} +{'AngularVelocity': array([0.07315864, 0.04987931, 3.3148551 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.56971263885498, + 'FR_Wheel_Angle': -10.48649787902832, + 'Location': array([ -3.0600009 , -23.57613945, 0.17273328]), + 'Rotation': array([-5.39243408e-02, -4.40933304e+01, 4.35700826e-02]), + 'Velocity': array([-5.74184537e-01, 6.95821762e-01, 6.44273765e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.92491055, 15.86034679, -0.17777222]), + 'camera_rotation': array([-6.35455513, -4.05177402, -0.91010517]), + 'current_gear_input': False, + 'focus_actor_dist': 3321.97900390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -533.63006592, -4991.64697266, 17.29502106]), + 'frame': 34709, + 'frame_number': 34709, + 'framesequence': 132812, + 'gaze_dir': array([0.99702454, 0.00886536, 0.07434845]), + 'gaze_origin': array([-2.96708536, -0.00980301, -0.11784134]), + 'gaze_valid': True, + 'gaze_vergence': 134.27879333496094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99763489, 0.02368164, 0.06440735]), + 'left_gaze_origin': array([-2.7438097 , 2.85200524, -0.14495698]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2420806884765625, + 'left_pupil_posn': array([ 0.2554028 , -0.13377512]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99641418, -0.00595093, 0.08428955]), + 'right_gaze_origin': array([-3.19036126, -2.87161112, -0.09072571]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0142822265625, + 'right_pupil_posn': array([-0.21012378, -0.22826755]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.059016697108745575, + 'throttle_input': 0.0, + 'timestamp': 1116.0228852778673, + 'timestamp_carla': 1116027, + 'timestamp_device': 4269454, + 'timestamp_stream': 1116.0228852778673, + 'transform': [array([3.03389001e+00, 1.15856342e+01, 9.40485019e-03]), + array([-6.71202689e-02, -1.06223173e+01, 9.38698184e-03])]} +{'AngularVelocity': array([-0.50674123, 1.54395139, 4.0138998 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.24169635772705, + 'FR_Wheel_Angle': -11.08732795715332, + 'Location': array([ -3.16396236, -23.45647621, 0.17341392]), + 'Rotation': array([ -0.08114947, -43.4922142 , 0.09357013]), + 'Velocity': array([-0.48453483, 0.59841669, 0.01535237]), + 'brake_input': 0.0, + 'camera_location': array([-8.91445255, 15.87058353, -0.16920598]), + 'camera_rotation': array([-6.28606176, -3.94927931, -0.90586424]), + 'current_gear_input': False, + 'focus_actor_dist': 3220.82763671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -528.50604248, -4896.05078125, 17.2844696 ]), + 'frame': 34710, + 'frame_number': 34710, + 'framesequence': 132816, + 'gaze_dir': array([0.99704742, 0.00866699, 0.07406616]), + 'gaze_origin': array([-2.96817112, -0.00990601, -0.11749115]), + 'gaze_valid': True, + 'gaze_vergence': 133.21881103515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99766541, 0.02355957, 0.06402588]), + 'left_gaze_origin': array([-2.7438097 , 2.85186315, -0.14495698]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2400665283203125, + 'left_pupil_posn': array([ 0.2554028 , -0.13379431]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99642944, -0.00622559, 0.08410645]), + 'right_gaze_origin': array([-3.19253254, -2.87167525, -0.09002534]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.004913330078125, + 'right_pupil_posn': array([-0.21012378, -0.22834134]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.056828778237, + 'timestamp_carla': 1116061, + 'timestamp_device': 4269487, + 'timestamp_stream': 1116.056828778237, + 'transform': [array([3.06684160e+00, 1.15243883e+01, 9.43420362e-03]), + array([-6.69768304e-02, -1.06933651e+01, 9.36196279e-03])]} +{'AngularVelocity': array([-5.62485890e-04, -3.67003903e-02, 3.02848649e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.838580131530762, + 'FR_Wheel_Angle': -13.355195045471191, + 'Location': array([ -3.23876667, -23.36975479, 0.17443885]), + 'Rotation': array([ -0.10073845, -43.02918243, 0.12995601]), + 'Velocity': array([-2.87739038e-01, 3.52488697e-01, -2.27737419e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.91082001, 15.88086128, -0.17500144]), + 'camera_rotation': array([-6.33154392, -3.83077884, -1.0410707 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3303.08447265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -533.42578125, -4983.50927734, 17.29418182]), + 'frame': 34711, + 'frame_number': 34711, + 'framesequence': 132820, + 'gaze_dir': array([0.99697113, 0.00833893, 0.07483673]), + 'gaze_origin': array([-2.96922994, -0.01000671, -0.11805955]), + 'gaze_valid': True, + 'gaze_vergence': 121.85470581054688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99769592, 0.02357483, 0.06347656]), + 'left_gaze_origin': array([-2.74320841, 2.85166192, -0.14629823]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2101287841796875, + 'left_pupil_posn': array([ 0.25529468, -0.13383305]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99624634, -0.00689697, 0.0861969 ]), + 'right_gaze_origin': array([-3.19525146, -2.87167525, -0.08982086]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0075225830078125, + 'right_pupil_posn': array([-0.21013075, -0.22893417]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.0901362784207, + 'timestamp_carla': 1116094, + 'timestamp_device': 4269520, + 'timestamp_stream': 1116.0901362784207, + 'transform': [array([3.09864259e+00, 1.14650974e+01, 9.45403986e-03]), + array([-6.68402240e-02, -1.07620850e+01, 9.36855283e-03])]} +{'AngularVelocity': array([ 0.09092342, -0.01198249, 2.59794736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.152873992919922, + 'FR_Wheel_Angle': -15.629966735839844, + 'Location': array([ -3.28549981, -23.31389809, 0.17432465]), + 'Rotation': array([ -0.10086823, -42.66066742, 0.12337653]), + 'Velocity': array([-0.19966497, 0.26663217, -0.00028615]), + 'brake_input': 0.0, + 'camera_location': array([-8.91074562, 15.89244366, -0.19258338]), + 'camera_rotation': array([-6.39188194, -3.65312862, -1.05837035]), + 'current_gear_input': False, + 'focus_actor_dist': 3302.092041015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -532.56616211, -4987.97607422, 17.2937088 ]), + 'frame': 34712, + 'frame_number': 34712, + 'framesequence': 132824, + 'gaze_dir': array([0.99697113, 0.00699615, 0.07457733]), + 'gaze_origin': array([-2.96900034, -0.00986939, -0.11789704]), + 'gaze_valid': True, + 'gaze_vergence': 110.99711608886719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99780273, 0.0231781 , 0.06195068]), + 'left_gaze_origin': array([-2.74267745, 2.85166192, -0.14629823]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1832122802734375, + 'left_pupil_posn': array([ 0.25449526, -0.13330901]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99613953, -0.00918579, 0.08720398]), + 'right_gaze_origin': array([-3.19532347, -2.87140059, -0.08949585]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0011749267578125, + 'right_pupil_posn': array([-0.21046633, -0.22925019]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.1230979785323, + 'timestamp_carla': 1116127, + 'timestamp_device': 4269554, + 'timestamp_stream': 1116.1230979785323, + 'transform': [array([3.12962461e+00, 1.14071894e+01, 9.47395340e-03]), + array([-6.67104572e-02, -1.08291950e+01, 9.37750563e-03])]} +{'AngularVelocity': array([-5.10062790e-04, -7.54104182e-03, 2.10686469e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.209842681884766, + 'FR_Wheel_Angle': -18.22687339782715, + 'Location': array([ -3.33383107, -23.25438881, 0.17439982]), + 'Rotation': array([ -0.10717932, -42.19649124, 0.11818422]), + 'Velocity': array([-0.18922313, 0.2571688 , 0.00033689]), + 'brake_input': 0.0, + 'camera_location': array([-8.92044163, 15.90737438, -0.20098753]), + 'camera_rotation': array([-6.40967464, -3.4979763 , -1.0828197 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3182.159423828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -522.456604 , -4873.60449219, 17.27839661]), + 'frame': 34713, + 'frame_number': 34713, + 'framesequence': 132828, + 'gaze_dir': array([0.99674988, 0.00583649, 0.07756805]), + 'gaze_origin': array([-2.96890044, -0.0093544 , -0.11786576]), + 'gaze_valid': True, + 'gaze_vergence': 105.47314453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99772644, 0.02107239, 0.06393433]), + 'left_gaze_origin': array([-2.74320841, 2.85226464, -0.14591065]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1634674072265625, + 'left_pupil_posn': array([ 0.25402689, -0.1318028 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99577332, -0.00939941, 0.09120178]), + 'right_gaze_origin': array([-3.19459248, -2.87097335, -0.08982086]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.002197265625, + 'right_pupil_posn': array([-0.21148568, -0.22861719]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.1559899784625, + 'timestamp_carla': 1116160, + 'timestamp_device': 4269587, + 'timestamp_stream': 1116.1559899784625, + 'transform': [array([3.16006160e+00, 1.13501654e+01, 9.47631802e-03]), + array([-6.65943399e-02, -1.08952713e+01, 9.41845123e-03])]} +{'AngularVelocity': array([-1.28095446e-03, 5.28909324e-04, 1.66963887e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.677717208862305, + 'FR_Wheel_Angle': -20.31680679321289, + 'Location': array([ -3.37168908, -23.20573235, 0.17439117]), + 'Rotation': array([ -0.10598404, -41.75108337, 0.1179501 ]), + 'Velocity': array([-0.12742397, 0.18190625, 0.00057987]), + 'brake_input': 0.0, + 'camera_location': array([-8.91189289, 15.93434715, -0.20965895]), + 'camera_rotation': array([-6.43521261, -3.36483216, -1.15573442]), + 'current_gear_input': False, + 'focus_actor_dist': 3429.903564453125, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -539.39813232, -5126.01318359, 17.31454468]), + 'frame': 34714, + 'frame_number': 34714, + 'framesequence': 132832, + 'gaze_dir': array([0.99689484, 0.00240326, 0.07605743]), + 'gaze_origin': array([-2.96563196, -0.00857315, -0.11734391]), + 'gaze_valid': True, + 'gaze_vergence': 109.90095520019531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99784851, 0.01766968, 0.06307983]), + 'left_gaze_origin': array([-2.74678063, 2.85318613, -0.14302368]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1303863525390625, + 'left_pupil_posn': array([ 0.25229144, -0.1312412 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99594116, -0.01286316, 0.08903503]), + 'right_gaze_origin': array([-3.18448353, -2.87033248, -0.09166413]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.01025390625, + 'right_pupil_posn': array([-0.21310353, -0.22818172]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.1897882781923, + 'timestamp_carla': 1116194, + 'timestamp_device': 4269620, + 'timestamp_stream': 1116.1897882781923, + 'transform': [array([3.19086838e+00, 1.12923479e+01, 9.45545174e-03]), + array([-6.64782301e-02, -1.09622812e+01, 9.48993210e-03])]} +{'AngularVelocity': array([-0.05887322, 0.0472993 , 0.43994644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.427045822143555, + 'FR_Wheel_Angle': -22.099655151367188, + 'Location': array([ -3.39366722, -23.17635918, 0.17441864]), + 'Rotation': array([ -0.10476827, -41.45777893, 0.11892316]), + 'Velocity': array([-0.06012737, 0.07737841, 0.00098214]), + 'brake_input': 0.0, + 'camera_location': array([-8.90654087, 15.94246674, -0.20263059]), + 'camera_rotation': array([-6.42095804, -3.25592232, -1.06178832]), + 'current_gear_input': False, + 'focus_actor_dist': 3238.160888671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -533.50769043, -4939.1015625 , 17.29073334]), + 'frame': 34715, + 'frame_number': 34715, + 'framesequence': 132836, + 'gaze_dir': array([ 0.99686432, -0.00205231, 0.07707977]), + 'gaze_origin': array([-2.96051359, -0.0070015 , -0.11844407]), + 'gaze_valid': True, + 'gaze_vergence': 142.2439422607422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99757385, 0.01318359, 0.06834412]), + 'left_gaze_origin': array([-2.75079513, 2.85527062, -0.14042208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.11248779296875, + 'left_pupil_posn': array([ 0.24945486, -0.1312412 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99615479, -0.01728821, 0.08581543]), + 'right_gaze_origin': array([-3.17023182, -2.86927342, -0.09646606]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0007781982421875, + 'right_pupil_posn': array([-0.21536148, -0.2268002 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.2219605781138, + 'timestamp_carla': 1116226, + 'timestamp_device': 4269654, + 'timestamp_stream': 1116.2219605781138, + 'transform': [array([3.21970201e+00, 1.12380419e+01, 9.44648683e-03]), + array([-6.63552806e-02, -1.10251493e+01, 9.56298504e-03])]} +{'AngularVelocity': array([-0.05167824, 0.05092855, 0.06508321]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.784809112548828, + 'FR_Wheel_Angle': -22.835622787475586, + 'Location': array([ -3.40440392, -23.16146851, 0.1744678 ]), + 'Rotation': array([ -0.1072408 , -41.29740524, 0.11736045]), + 'Velocity': array([-0.03682349, 0.04109129, 0.00042329]), + 'brake_input': 0.0, + 'camera_location': array([-8.89110661, 15.9624176 , -0.19941552]), + 'camera_rotation': array([-6.37997007, -3.16493678, -1.12303746]), + 'current_gear_input': False, + 'focus_actor_dist': 3347.931884765625, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -553.89849854, -5052.80859375, 17.31961823]), + 'frame': 34716, + 'frame_number': 34716, + 'framesequence': 132840, + 'gaze_dir': array([ 0.9969635 , -0.00335693, 0.07543945]), + 'gaze_origin': array([-2.95562148, -0.00647278, -0.11899719]), + 'gaze_valid': True, + 'gaze_vergence': 127.76229858398438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99781799, 0.0118103 , 0.06484985]), + 'left_gaze_origin': array([-2.75079513, 2.85610676, -0.14042208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.104461669921875, + 'left_pupil_posn': array([ 0.24848247, -0.13117909]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99610901, -0.01852417, 0.08602905]), + 'right_gaze_origin': array([-3.16044807, -2.86905217, -0.09757233]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.984100341796875, + 'right_pupil_posn': array([-0.21598274, -0.22679567]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.255799278617, + 'timestamp_carla': 1116260, + 'timestamp_device': 4269687, + 'timestamp_stream': 1116.255799278617, + 'transform': [array([3.24960041e+00, 1.11816750e+01, 9.40700527e-03]), + array([-6.62460029e-02, -1.10904522e+01, 9.66651458e-03])]} +{'AngularVelocity': array([-0.1013858 , 0.03617683, 0.43456912]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.78687286376953, + 'FR_Wheel_Angle': -22.836444854736328, + 'Location': array([ -3.41017532, -23.15352821, 0.17296357]), + 'Rotation': array([-5.66086061e-02, -4.12082329e+01, 3.82699035e-02]), + 'Velocity': array([-0.01310093, 0.01209456, -0.00132854]), + 'brake_input': 0.0, + 'camera_location': array([-8.88771629, 15.98595715, -0.2024475 ]), + 'camera_rotation': array([-6.46984863, -3.00917149, -1.07845044]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.14697265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -550.08813477, -4968.78710938, 17.3090744 ]), + 'frame': 34717, + 'frame_number': 34717, + 'framesequence': 132844, + 'gaze_dir': array([ 0.9965744 , -0.00315857, 0.08156586]), + 'gaze_origin': array([-2.92250991, -0.00549698, -0.13132249]), + 'gaze_valid': True, + 'gaze_vergence': 213.60630798339844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99694824, 0.00891113, 0.07749939]), + 'left_gaze_origin': array([-2.73784184, 2.85816216, -0.14423829]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0851898193359375, + 'left_pupil_posn': array([ 0.24802005, -0.1313622 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99620056, -0.01522827, 0.08563232]), + 'right_gaze_origin': array([-3.10717773, -2.86915588, -0.11840669]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9914398193359375, + 'right_pupil_posn': array([-0.2168501 , -0.22624242]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.289438676089, + 'timestamp_carla': 1116293, + 'timestamp_device': 4269720, + 'timestamp_stream': 1116.289438676089, + 'transform': [array([3.27883053e+00, 1.11264009e+01, 9.37110838e-03]), + array([-6.61298856e-02, -1.11544485e+01, 9.77096334e-03])]} +{'AngularVelocity': array([-0.07046197, 0.03847031, 0.28818852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.862287521362305, + 'FR_Wheel_Angle': -22.945581436157227, + 'Location': array([ -3.41466331, -23.14724541, 0.17305711]), + 'Rotation': array([ -0.06094578, -41.14090729, 0.04176164]), + 'Velocity': array([-0.00507555, 0.00135989, 0.0016175 ]), + 'brake_input': 0.0, + 'camera_location': array([-8.88827801, 16.0027256 , -0.21378691]), + 'camera_rotation': array([-6.54766464, -2.88295984, -1.08808541]), + 'current_gear_input': False, + 'focus_actor_dist': 3732.193603515625, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -580.79077148, -5446.12451172, 17.39701843]), + 'frame': 34718, + 'frame_number': 34718, + 'framesequence': 132848, + 'gaze_dir': array([ 0.99667358, -0.0019989 , 0.08061981]), + 'gaze_origin': array([-2.91807175, -0.00461807, -0.13211824]), + 'gaze_valid': True, + 'gaze_vergence': 252.03909301757812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99699402, 0.00805664, 0.07695007]), + 'left_gaze_origin': array([-2.73367167, 2.85996413, -0.14472657]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0989227294921875, + 'left_pupil_posn': array([ 0.24782968, -0.1313622 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99635315, -0.01205444, 0.08428955]), + 'right_gaze_origin': array([-3.10247207, -2.86920023, -0.1195099 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9822998046875, + 'right_pupil_posn': array([-0.21710783, -0.22624242]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.3236280791461, + 'timestamp_carla': 1116327, + 'timestamp_device': 4269754, + 'timestamp_stream': 1116.3236280791461, + 'transform': [array([3.30807161e+00, 1.10709839e+01, 9.31690168e-03]), + array([-6.60206079e-02, -1.12185993e+01, 9.90609452e-03])]} +{'AngularVelocity': array([ 0.08846135, -0.02334859, 0.120513 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.17753791809082, + 'FR_Wheel_Angle': -23.108501434326172, + 'Location': array([ -3.41732264, -23.14342499, 0.17313807]), + 'Rotation': array([ -0.06307679, -41.10256958, 0.04144315]), + 'Velocity': array([-0.02095114, 0.04051052, 0.00042622]), + 'brake_input': 0.0, + 'camera_location': array([-8.87688255, 16.03283691, -0.22598973]), + 'camera_rotation': array([-6.60230637, -2.74185443, -1.17584085]), + 'current_gear_input': False, + 'focus_actor_dist': 3479.359375, + 'focus_actor_name': 'Road_Grass_Town05_129', + 'focus_actor_pt': array([ -553.96166992, -5199.31396484, 17.3381424 ]), + 'frame': 34719, + 'frame_number': 34719, + 'framesequence': 132852, + 'gaze_dir': array([0.99594879, 0.05617523, 0.06728363]), + 'gaze_origin': array([-2.95269942, -0.05345383, -0.11579667]), + 'gaze_valid': True, + 'gaze_vergence': 112.73043060302734, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99595642, 0.0712738 , 0.05462646]), + 'left_gaze_origin': array([-2.702672 , 2.81039596, -0.15755768]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0324859619140625, + 'left_pupil_posn': array([ 0.298244 , -0.13558602]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99594116, 0.04107666, 0.0799408 ]), + 'right_gaze_origin': array([-3.20272708, -2.91730356, -0.07403564]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8134613037109375, + 'right_pupil_posn': array([-0.16178751, -0.22295809]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.3559570759535, + 'timestamp_carla': 1116360, + 'timestamp_device': 4269787, + 'timestamp_stream': 1116.3559570759535, + 'transform': [array([3.33526492e+00, 1.10192871e+01, 9.27720964e-03]), + array([-6.59113228e-02, -1.12783871e+01, 1.00421058e-02])]} +{'AngularVelocity': array([ 0.03501734, -0.00697553, 2.84870267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.09381866455078, + 'FR_Wheel_Angle': -23.757707595825195, + 'Location': array([ -3.42942047, -23.12735748, 0.17322378]), + 'Rotation': array([-7.33630583e-02, -4.09290810e+01, 3.30200866e-02]), + 'Velocity': array([-1.29244298e-01, 2.00506926e-01, 1.65987018e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.86278534, 16.06489182, -0.23326035]), + 'camera_rotation': array([-6.57330561, -2.55937028, -1.1372093 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2513.431884765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -332.91796875, -4246.70458984, 17.08733368]), + 'frame': 34720, + 'frame_number': 34720, + 'framesequence': 132856, + 'gaze_dir': array([0.96894073, 0.23672485, 0.0639801 ]), + 'gaze_origin': array([-2.96657348, -0.1922783 , -0.12545013]), + 'gaze_valid': True, + 'gaze_vergence': 69.61809539794922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9641571 , 0.26152039, 0.04478455]), + 'left_gaze_origin': array([-2.76759195, 2.65120387, -0.1532837 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1449127197265625, + 'left_pupil_posn': array([ 0.46656847, -0.14666605]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97372437, 0.21192932, 0.08317566]), + 'right_gaze_origin': array([-3.165555 , -3.03576064, -0.09761658]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.850372314453125, + 'right_pupil_posn': array([-0.01396662, -0.23977399]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.0, + 'timestamp': 1116.3903365768492, + 'timestamp_carla': 1116394, + 'timestamp_device': 4269820, + 'timestamp_stream': 1116.3903365768492, + 'transform': [array([3.36377501e+00, 1.09650335e+01, 9.21833050e-03]), + array([-6.58088699e-02, -1.13411865e+01, 1.01787020e-02])]} +{'AngularVelocity': array([-0.05957202, -0.01711788, 4.60721731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.5662899017334, + 'FR_Wheel_Angle': -23.970247268676758, + 'Location': array([ -3.50133038, -23.03041267, 0.17333208]), + 'Rotation': array([-7.42851347e-02, -3.97728653e+01, 3.29335481e-02]), + 'Velocity': array([-0.27652118, 0.41583538, 0.00057471]), + 'brake_input': 0.0, + 'camera_location': array([-8.85508537, 16.10616684, -0.24300684]), + 'camera_rotation': array([-6.54141521, -2.2740922 , -1.16155028]), + 'current_gear_input': False, + 'focus_actor_dist': 2736.324462890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 167.69317627, -4434.70605469, 16.57466888]), + 'frame': 34721, + 'frame_number': 34721, + 'framesequence': 132860, + 'gaze_dir': array([0.92681122, 0.37107849, 0.05722046]), + 'gaze_origin': array([-2.99950194, -0.28496933, -0.13025819]), + 'gaze_valid': True, + 'gaze_vergence': 658.93994140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92810059, 0.36769104, 0.05825806]), + 'left_gaze_origin': array([-2.80471969, 2.5470171 , -0.15832826]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3780364990234375, + 'left_pupil_posn': array([ 0.60230625, -0.17249799]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92552185, 0.37446594, 0.05618286]), + 'right_gaze_origin': array([-3.19428396, -3.11695576, -0.10218811]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9285736083984375, + 'right_pupil_posn': array([ 0.08092082, -0.24769664]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.043656062334775925, + 'timestamp': 1116.422680478543, + 'timestamp_carla': 1116427, + 'timestamp_device': 4269854, + 'timestamp_stream': 1116.422680478543, + 'transform': [array([3.38868666e+00, 1.09156723e+01, 9.57111362e-03]), + array([-6.57337382e-02, -1.13963947e+01, 9.54575557e-03])]} +{'AngularVelocity': array([-2.51722168e-02, -4.11058636e-03, 6.29912949e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.427955627441406, + 'FR_Wheel_Angle': -23.882719039916992, + 'Location': array([ -3.5973804 , -22.90677834, 0.17343752]), + 'Rotation': array([-7.67166838e-02, -3.82890358e+01, 3.10207326e-02]), + 'Velocity': array([-4.43548739e-01, 6.25507057e-01, 4.50239168e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.83320808, 16.1818943 , -0.23302393]), + 'camera_rotation': array([-6.53871059, -1.82101643, -1.19166958]), + 'current_gear_input': False, + 'focus_actor_dist': 2829.981689453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 581.10565186, -4432.94140625, 16.19151306]), + 'frame': 34722, + 'frame_number': 34722, + 'framesequence': 132864, + 'gaze_dir': array([0.92731476, 0.37138367, 0.0462265 ]), + 'gaze_origin': array([-2.99769378, -0.2854355 , -0.12706909]), + 'gaze_valid': True, + 'gaze_vergence': 304.9366149902344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9276123 , 0.37088013, 0.04423523]), + 'left_gaze_origin': array([-2.80199003, 2.54931188, -0.15548249]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.347320556640625, + 'left_pupil_posn': array([ 0.59949255, -0.17261457]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.92701721, 0.37188721, 0.04821777]), + 'right_gaze_origin': array([-3.19339776, -3.12018299, -0.09865571]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.863861083984375, + 'right_pupil_posn': array([ 0.08406186, -0.25030851]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.09919890016317368, + 'timestamp': 1116.4563090763986, + 'timestamp_carla': 1116460, + 'timestamp_device': 4269887, + 'timestamp_stream': 1116.4563090763986, + 'transform': [array([3.41478896e+00, 1.08657742e+01, 1.00837322e-02]), + array([-6.56722635e-02, -1.14541054e+01, 8.57433956e-03])]} +{'AngularVelocity': array([-0.03225548, -0.05026663, 10.68968582]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.249372482299805, + 'FR_Wheel_Angle': -23.82868766784668, + 'Location': array([ -3.74326658, -22.73041534, 0.17364271]), + 'Rotation': array([-8.26452821e-02, -3.61421509e+01, 2.68521570e-02]), + 'Velocity': array([-6.66984618e-01, 8.87133837e-01, 6.96420670e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.83993912, 16.27256393, -0.22966632]), + 'camera_rotation': array([-6.55664635, -1.180457 , -1.18643761]), + 'current_gear_input': False, + 'focus_actor_dist': 2247.57421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 416.02914429, -3877.71972656, 16.31973267]), + 'frame': 34723, + 'frame_number': 34723, + 'framesequence': 132868, + 'gaze_dir': array([0.92969513, 0.36438751, 0.05267334]), + 'gaze_origin': array([-2.99669218, -0.2839081 , -0.12655488]), + 'gaze_valid': True, + 'gaze_vergence': 85.21675109863281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9291687 , 0.36706543, 0.04353333]), + 'left_gaze_origin': array([-2.80047011, 2.55287504, -0.15596925]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1802215576171875, + 'left_pupil_posn': array([ 0.59292018, -0.1673913 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93022156, 0.36170959, 0.06181335]), + 'right_gaze_origin': array([-3.19291401, -3.12069106, -0.09714051]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8245391845703125, + 'right_pupil_posn': array([ 0.08307707, -0.2492007 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.12300297617912292, + 'timestamp': 1116.4894268773496, + 'timestamp_carla': 1116493, + 'timestamp_device': 4269920, + 'timestamp_stream': 1116.4894268773496, + 'transform': [array([3.44031763e+00, 1.08177452e+01, 1.04107661e-02]), + array([-6.56039640e-02, -1.15105333e+01, 7.97403231e-03])]} +{'AngularVelocity': array([-0.10465296, 0.01499417, 9.51197529]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.461090087890625, + 'FR_Wheel_Angle': -26.08806800842285, + 'Location': array([ -3.90277123, -22.54766464, 0.17377351]), + 'Rotation': array([ -0.06789891, -33.78660583, 0.03792261]), + 'Velocity': array([-0.60713577, 0.75884718, 0.00094501]), + 'brake_input': 0.0, + 'camera_location': array([-8.84327221, 16.38934326, -0.22197893]), + 'camera_rotation': array([-6.55814934, -0.35707882, -1.17853689]), + 'current_gear_input': False, + 'focus_actor_dist': 2520.84326171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 508.63668823, -4139.51171875, 16.2229538 ]), + 'frame': 34724, + 'frame_number': 34724, + 'framesequence': 132872, + 'gaze_dir': array([0.93531799, 0.34857178, 0.05917358]), + 'gaze_origin': array([-2.99388742, -0.27875063, -0.12688752]), + 'gaze_valid': True, + 'gaze_vergence': 109.75621795654297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93371582, 0.35470581, 0.04827881]), + 'left_gaze_origin': array([-2.79704618, 2.55927587, -0.1582367 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21728515625, + 'left_pupil_posn': array([ 0.58076203, -0.16448712]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93692017, 0.34243774, 0.07006836]), + 'right_gaze_origin': array([-3.19072914, -3.11677718, -0.09553833]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8492584228515625, + 'right_pupil_posn': array([ 0.07587802, -0.24548006]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058998387306928635, + 'throttle_input': 0.12300297617912292, + 'timestamp': 1116.522679578513, + 'timestamp_carla': 1116526, + 'timestamp_device': 4269953, + 'timestamp_stream': 1116.522679578513, + 'transform': [array([3.46574616e+00, 1.07703114e+01, 1.04681393e-02]), + array([-6.55288324e-02, -1.15667772e+01, 7.89643545e-03])]} +{'AngularVelocity': array([-0.07960139, 0.02940236, 8.50829887]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.52149200439453, + 'FR_Wheel_Angle': -28.55414581298828, + 'Location': array([ -4.00510883, -22.43169403, 0.17385274]), + 'Rotation': array([ -0.06136242, -32.1089325 , 0.04072442]), + 'Velocity': array([-0.49506351, 0.62500131, 0.00069519]), + 'brake_input': 0.0, + 'camera_location': array([-8.84490204, 16.54429626, -0.23102483]), + 'camera_rotation': array([-6.57083988, 0.63101035, -1.23609233]), + 'current_gear_input': False, + 'focus_actor_dist': 2850.5732421875, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 604.06994629, -4459.75097656, 16.22582245]), + 'frame': 34725, + 'frame_number': 34725, + 'framesequence': 132876, + 'gaze_dir': array([0.93703461, 0.34334564, 0.05970764]), + 'gaze_origin': array([-2.99076772, -0.2706711 , -0.1233635 ]), + 'gaze_valid': True, + 'gaze_vergence': 9.68428897857666, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9379425 , 0.3447113 , 0.03765869]), + 'left_gaze_origin': array([-2.79486108, 2.56873631, -0.15434265]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.205169677734375, + 'left_pupil_posn': array([ 0.57356501, -0.1576488 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93612671, 0.34197998, 0.08175659]), + 'right_gaze_origin': array([-3.18667483, -3.11007857, -0.09238434]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8016357421875, + 'right_pupil_posn': array([ 0.06757414, -0.24570954]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05874202772974968, + 'throttle_input': 0.1269855797290802, + 'timestamp': 1116.5558009780943, + 'timestamp_carla': 1116559, + 'timestamp_device': 4269987, + 'timestamp_stream': 1116.5558009780943, + 'transform': [array([3.49050736e+00, 1.07236814e+01, 1.02905082e-02]), + array([-6.54058903e-02, -1.16216793e+01, 8.27915315e-03])]} +{'AngularVelocity': array([ 0.07767052, -0.04083332, 8.50870609]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.6369743347168, + 'FR_Wheel_Angle': -30.36264419555664, + 'Location': array([ -4.09860849, -22.32505035, 0.17393091]), + 'Rotation': array([ -0.06051547, -30.39588356, 0.03974326]), + 'Velocity': array([-0.3891975 , 0.52687627, 0.00062519]), + 'brake_input': 0.0, + 'camera_location': array([-8.85007286, 16.70643425, -0.25123763]), + 'camera_rotation': array([-6.58370113, 1.74073577, -1.23667264]), + 'current_gear_input': False, + 'focus_actor_dist': 2876.226318359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 641.08862305, -4478.35595703, 16.1428299 ]), + 'frame': 34726, + 'frame_number': 34726, + 'framesequence': 132880, + 'gaze_dir': array([0.94413757, 0.32487488, 0.05181885]), + 'gaze_origin': array([-2.98512197, -0.25873566, -0.12065049]), + 'gaze_valid': True, + 'gaze_vergence': 19.52976417541504, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94613647, 0.322052 , 0.03312683]), + 'left_gaze_origin': array([-2.78834701, 2.58276534, -0.15120392]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2905731201171875, + 'left_pupil_posn': array([ 0.55769384, -0.15744328]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94213867, 0.32769775, 0.07051086]), + 'right_gaze_origin': array([-3.18189716, -3.10023665, -0.09009705]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.82171630859375, + 'right_pupil_posn': array([ 0.05238795, -0.24405062]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05802789703011513, + 'throttle_input': 0.1587243527173996, + 'timestamp': 1116.590544179082, + 'timestamp_carla': 1116594, + 'timestamp_device': 4270020, + 'timestamp_stream': 1116.590544179082, + 'transform': [array([3.51550126e+00, 1.06753969e+01, 9.93211754e-03]), + array([-6.52214736e-02, -1.16773119e+01, 8.99117533e-03])]} +{'AngularVelocity': array([ 0.0918223 , -0.05610054, 7.65456533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.610015869140625, + 'FR_Wheel_Angle': -30.759218215942383, + 'Location': array([ -4.17393827, -22.24006271, 0.173953 ]), + 'Rotation': array([ -0.06256453, -28.92592812, 0.03843991]), + 'Velocity': array([-0.33157259, 0.44764054, -0.00142762]), + 'brake_input': 0.0, + 'camera_location': array([-8.86439419, 16.87904358, -0.23881169]), + 'camera_rotation': array([-6.5459981 , 2.96425915, -1.2872144 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2337.573974609375, + 'focus_actor_name': 'Plane20', + 'focus_actor_pt': array([ 462.68927002, -3973.54052734, 16.62313843]), + 'frame': 34727, + 'frame_number': 34727, + 'framesequence': 132884, + 'gaze_dir': array([0.94824219, 0.31169128, 0.05677032]), + 'gaze_origin': array([-2.98259306, -0.24872208, -0.11942139]), + 'gaze_valid': True, + 'gaze_vergence': 23.54293441772461, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95083618, 0.30757141, 0.03614807]), + 'left_gaze_origin': array([-2.78606129, 2.59457564, -0.15027466]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2050323486328125, + 'left_pupil_posn': array([ 0.5447371 , -0.15345144]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94564819, 0.31581116, 0.07739258]), + 'right_gaze_origin': array([-3.17912483, -3.0920198 , -0.08856812]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.917266845703125, + 'right_pupil_posn': array([ 0.04144835, -0.24089885]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0568193644285202, + 'throttle_input': 0.20236514508724213, + 'timestamp': 1116.6221218779683, + 'timestamp_carla': 1116626, + 'timestamp_device': 4270053, + 'timestamp_stream': 1116.6221218779683, + 'transform': [array([3.53759766e+00, 1.06316576e+01, 9.41564515e-03]), + array([-6.49892464e-02, -1.17266855e+01, 1.00648850e-02])]} +{'AngularVelocity': array([-0.08625735, 0.05249769, 5.26346779]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67329788208008, + 'FR_Wheel_Angle': -30.797170639038086, + 'Location': array([ -4.25002956, -22.15785408, 0.17408358]), + 'Rotation': array([ -0.06444966, -27.45448303, 0.03791246]), + 'Velocity': array([-0.30255809, 0.34889331, 0.00036149]), + 'brake_input': 0.0, + 'camera_location': array([-8.87985325, 17.05971146, -0.23231469]), + 'camera_rotation': array([-6.51844549, 4.22984028, -1.35375559]), + 'current_gear_input': False, + 'focus_actor_dist': 2609.5146484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 566.65795898, -4229.7421875 , 16.17647552]), + 'frame': 34728, + 'frame_number': 34728, + 'framesequence': 132888, + 'gaze_dir': array([0.95350647, 0.29544067, 0.05743408]), + 'gaze_origin': array([-2.97828913, -0.23788454, -0.11733476]), + 'gaze_valid': True, + 'gaze_vergence': 6.7346391677856445, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95429993, 0.29573059, 0.04275513]), + 'left_gaze_origin': array([-2.78119993, 2.60606718, -0.14964142]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1728057861328125, + 'left_pupil_posn': array([ 0.52870297, -0.15310359]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95271301, 0.29515076, 0.07211304]), + 'right_gaze_origin': array([-3.17537856, -3.08183599, -0.08502808]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8775634765625, + 'right_pupil_posn': array([ 0.03021109, -0.23493528]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05542771890759468, + 'throttle_input': 0.26189059019088745, + 'timestamp': 1116.6551843769848, + 'timestamp_carla': 1116659, + 'timestamp_device': 4270087, + 'timestamp_stream': 1116.6551843769848, + 'transform': [array([3.56015658e+00, 1.05857782e+01, 8.70717969e-03]), + array([-6.46818876e-02, -1.17772465e+01, 1.14819771e-02])]} +{'AngularVelocity': array([ 0.10175169, -0.01380756, 5.08386469]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.73828887939453, + 'FR_Wheel_Angle': -30.819181442260742, + 'Location': array([ -4.31128979, -22.09478951, 0.1741451 ]), + 'Rotation': array([ -0.06564494, -26.30103302, 0.03504717]), + 'Velocity': array([-0.2668446 , 0.31418693, 0.00069287]), + 'brake_input': 0.0, + 'camera_location': array([-8.89911461, 17.22665405, -0.22919871]), + 'camera_rotation': array([-6.50108957, 5.39854765, -1.47447503]), + 'current_gear_input': False, + 'focus_actor_dist': 2629.705810546875, + 'focus_actor_name': 'Plane19', + 'focus_actor_pt': array([ 583.23413086, -4249.10644531, 16.62149811]), + 'frame': 34729, + 'frame_number': 34729, + 'framesequence': 132892, + 'gaze_dir': array([0.95823669, 0.27991486, 0.05625916]), + 'gaze_origin': array([-2.97488356, -0.22670138, -0.1158722 ]), + 'gaze_valid': True, + 'gaze_vergence': 96.15103912353516, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.956604 , 0.28816223, 0.0430603 ]), + 'left_gaze_origin': array([-2.77669835, 2.61767125, -0.14729005]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1454925537109375, + 'left_pupil_posn': array([ 0.51173747, -0.15060329]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95986938, 0.27166748, 0.06945801]), + 'right_gaze_origin': array([-3.17306852, -3.07107401, -0.08445435]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.83660888671875, + 'right_pupil_posn': array([ 0.02011156, -0.23362887]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.053468432277441025, + 'throttle_input': 0.27775996923446655, + 'timestamp': 1116.6892485767603, + 'timestamp_carla': 1116693, + 'timestamp_device': 4270120, + 'timestamp_stream': 1116.6892485767603, + 'transform': [array([3.58280277e+00, 1.05381832e+01, 7.84194935e-03]), + array([ -0.06431989, -11.8281908 , 0.01319288])]} +{'AngularVelocity': array([-6.67864399e-04, 4.16594706e-02, 4.58038378e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.702484130859375, + 'FR_Wheel_Angle': -30.804107666015625, + 'Location': array([ -4.37114859, -22.03610039, 0.17421247]), + 'Rotation': array([ -0.06679925, -25.20487213, 0.03261279]), + 'Velocity': array([-0.24210988, 0.25494987, 0.00052977]), + 'brake_input': 0.0, + 'camera_location': array([-8.88053036, 17.39635849, -0.22859989]), + 'camera_rotation': array([-6.47817469, 6.50352812, -1.65474236]), + 'current_gear_input': False, + 'focus_actor_dist': 2572.26025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 571.54162598, -4196.1484375 , 16.16728973]), + 'frame': 34730, + 'frame_number': 34730, + 'framesequence': 132897, + 'gaze_dir': array([0.96311188, 0.26206207, 0.05860138]), + 'gaze_origin': array([-2.97199106, -0.21488953, -0.11731492]), + 'gaze_valid': True, + 'gaze_vergence': 58.74614334106445, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96255493, 0.26760864, 0.04296875]), + 'left_gaze_origin': array([-2.77377486, 2.6310854 , -0.14991455]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.132904052734375, + 'left_pupil_posn': array([ 0.49674881, -0.14987314]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96366882, 0.2565155 , 0.07423401]), + 'right_gaze_origin': array([-3.1702075 , -3.06086445, -0.08471527]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.914093017578125, + 'right_pupil_posn': array([ 0.00561893, -0.2327466 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05086825415492058, + 'throttle_input': 0.2856946587562561, + 'timestamp': 1116.7329714782536, + 'timestamp_carla': 1116737, + 'timestamp_device': 4270162, + 'timestamp_stream': 1116.7329714782536, + 'transform': [array([3.61096883e+00, 1.04761839e+01, 6.58264151e-03]), + array([ -0.06371883, -11.89185238, 0.01567468])]} +{'AngularVelocity': array([-0.03841162, 0.02768073, 6.41336489]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.57698059082031, + 'FR_Wheel_Angle': -30.71118927001953, + 'Location': array([ -4.45356274, -21.95864677, 0.17435357]), + 'Rotation': array([-7.52550215e-02, -2.37374649e+01, 2.07724925e-02]), + 'Velocity': array([-3.79387975e-01, 3.92612249e-01, -8.36276959e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.81759739, 17.69495773, -0.2456315 ]), + 'camera_rotation': array([-6.47854996, 8.33373737, -1.75567031]), + 'current_gear_input': False, + 'focus_actor_dist': 2721.914306640625, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 620.98156738, -4341.72509766, 16.22583771]), + 'frame': 34731, + 'frame_number': 34731, + 'framesequence': 132901, + 'gaze_dir': array([0.93452454, 0.35181427, 0.05198669]), + 'gaze_origin': array([-2.9911828 , -0.27414629, -0.1286255 ]), + 'gaze_valid': True, + 'gaze_vergence': 53.335472106933594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93412781, 0.35467529, 0.03973389]), + 'left_gaze_origin': array([-2.7942903 , 2.56103992, -0.16275635]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0364837646484375, + 'left_pupil_posn': array([ 0.58181691, -0.16891527]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93492126, 0.34895325, 0.0642395 ]), + 'right_gaze_origin': array([-3.18807554, -3.10933232, -0.09449463]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9431915283203125, + 'right_pupil_posn': array([ 0.07040405, -0.24740791]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04698630049824715, + 'throttle_input': 0.29364460706710815, + 'timestamp': 1116.7657384760678, + 'timestamp_carla': 1116769, + 'timestamp_device': 4270195, + 'timestamp_stream': 1116.7657384760678, + 'transform': [array([3.63121080e+00, 1.04287758e+01, 5.58204623e-03]), + array([ -0.06323389, -11.93791199, 0.01768987])]} +{'AngularVelocity': array([ 0.04685767, -0.04057166, 9.21906376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.500099182128906, + 'FR_Wheel_Angle': -30.635032653808594, + 'Location': array([ -4.56545448, -21.86036301, 0.17449099]), + 'Rotation': array([-7.58970603e-02, -2.17927418e+01, 1.95628386e-02]), + 'Velocity': array([-0.48182651, 0.49011379, 0.00076571]), + 'brake_input': 0.0, + 'camera_location': array([-8.79225063, 17.8430481 , -0.25681496]), + 'camera_rotation': array([-6.52350664, 9.14598751, -1.84865737]), + 'current_gear_input': False, + 'focus_actor_dist': 2714.3671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 929.86584473, -4205.51611328, 15.84028625]), + 'frame': 34732, + 'frame_number': 34732, + 'framesequence': 132906, + 'gaze_dir': array([0.93090057, 0.36270142, 0.04055023]), + 'gaze_origin': array([-2.9913516 , -0.27541199, -0.12795487]), + 'gaze_valid': True, + 'gaze_vergence': 5.882866859436035, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93144226, 0.36291504, 0.02627563]), + 'left_gaze_origin': array([-2.79480767, 2.55930352, -0.16243592]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0415191650390625, + 'left_pupil_posn': array([ 0.58827794, -0.17278492]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93035889, 0.36248779, 0.05482483]), + 'right_gaze_origin': array([-3.1878953 , -3.11012745, -0.09347382]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.877716064453125, + 'right_pupil_posn': array([ 0.07392573, -0.25167203]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.043891724199056625, + 'throttle_input': 0.30951398611068726, + 'timestamp': 1116.8060948774219, + 'timestamp_carla': 1116810, + 'timestamp_device': 4270237, + 'timestamp_stream': 1116.8060948774219, + 'transform': [array([3.65506697e+00, 1.03689270e+01, 4.24612034e-03]), + array([ -0.06266698, -11.99257278, 0.0203703 ])]} +{'AngularVelocity': array([ 0.02742605, -0.05698357, 10.99527931]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.42445373535156, + 'FR_Wheel_Angle': -30.646438598632812, + 'Location': array([ -4.70749807, -21.74483871, 0.17463918]), + 'Rotation': array([ -0.07614294, -19.41638374, 0.01953029]), + 'Velocity': array([-6.04934454e-01, 5.65184057e-01, 4.89826198e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.74649715, 17.98184395, -0.27405068]), + 'camera_rotation': array([-6.52271414, 9.87373924, -1.81010115]), + 'current_gear_input': False, + 'focus_actor_dist': 2173.94677734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 733.52819824, -3701.74267578, 15.9944458 ]), + 'frame': 34733, + 'frame_number': 34733, + 'framesequence': 132910, + 'gaze_dir': array([0.93734741, 0.34463501, 0.04872131]), + 'gaze_origin': array([-2.98959374, -0.27299044, -0.12882158]), + 'gaze_valid': True, + 'gaze_vergence': 56.949974060058594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93656921, 0.34870911, 0.03488159]), + 'left_gaze_origin': array([-2.79216647, 2.56327224, -0.16413575]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1548004150390625, + 'left_pupil_posn': array([ 0.57693267, -0.1698668 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93812561, 0.34056091, 0.06256104]), + 'right_gaze_origin': array([-3.18702078, -3.10925293, -0.09350739]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.84124755859375, + 'right_pupil_posn': array([ 0.06825352, -0.24787986]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03977172449231148, + 'throttle_input': 0.3293507397174835, + 'timestamp': 1116.8392649777234, + 'timestamp_carla': 1116843, + 'timestamp_device': 4270270, + 'timestamp_stream': 1116.8392649777234, + 'transform': [array([3.67345667e+00, 1.03185053e+01, 3.18941101e-03]), + array([ -0.06212057, -12.0351162 , 0.02247269])]} +{'AngularVelocity': array([ 0.04384422, -0.05312046, 9.53973961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.514625549316406, + 'FR_Wheel_Angle': -30.707170486450195, + 'Location': array([ -4.84818363, -21.63837051, 0.17475541]), + 'Rotation': array([ -0.06802185, -17.12803268, 0.02828739]), + 'Velocity': array([-0.54071432, 0.47080612, 0.00090807]), + 'brake_input': 0.0, + 'camera_location': array([-8.67600727, 18.12837219, -0.29336661]), + 'camera_rotation': array([-6.49975777, 10.48410034, -1.87878966]), + 'current_gear_input': False, + 'focus_actor_dist': 2475.965576171875, + 'focus_actor_name': 'Plane9', + 'focus_actor_pt': array([ 859.91467285, -3982.3984375 , 15.99294281]), + 'frame': 34734, + 'frame_number': 34734, + 'framesequence': 132914, + 'gaze_dir': array([0.94078827, 0.33437347, 0.05315399]), + 'gaze_origin': array([-2.98788309, -0.26803589, -0.13092576]), + 'gaze_valid': True, + 'gaze_vergence': 38.64940643310547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94314575, 0.33027649, 0.03726196]), + 'left_gaze_origin': array([-2.79031992, 2.57149982, -0.16512452]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.31182861328125, + 'left_pupil_posn': array([ 0.57009554, -0.16816533]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93843079, 0.33847046, 0.06904602]), + 'right_gaze_origin': array([-3.18544626, -3.1075716 , -0.09672699]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.803558349609375, + 'right_pupil_posn': array([ 0.06051099, -0.24816334]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.036072880029678345, + 'throttle_input': 0.34125277400016785, + 'timestamp': 1116.8735857792199, + 'timestamp_carla': 1116877, + 'timestamp_device': 4270303, + 'timestamp_stream': 1116.8735857792199, + 'transform': [array([3.69110537e+00, 1.02651424e+01, 2.18227389e-03]), + array([ -0.06152634, -12.07640553, 0.02446431])]} +{'AngularVelocity': array([ 0.10049532, -0.0379384 , 7.03858566]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.64563751220703, + 'FR_Wheel_Angle': -30.781578063964844, + 'Location': array([ -4.97499371, -21.54900551, 0.17486466]), + 'Rotation': array([ -0.06234596, -15.10115337, 0.03238095]), + 'Velocity': array([-3.89849693e-01, 3.22645217e-01, 1.40314092e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.60071945, 18.27925682, -0.29304984]), + 'camera_rotation': array([-6.65071201, 11.19543362, -1.88446534]), + 'current_gear_input': False, + 'focus_actor_dist': 2501.047119140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST10', + 'focus_actor_pt': array([ 868.90612793, -4011.11376953, 26.01900482]), + 'frame': 34735, + 'frame_number': 34735, + 'framesequence': 132918, + 'gaze_dir': array([0.94210052, 0.33078766, 0.04975891]), + 'gaze_origin': array([-2.98613763, -0.26462787, -0.12931138]), + 'gaze_valid': True, + 'gaze_vergence': 18.024749755859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94221497, 0.33392334, 0.0267334 ]), + 'left_gaze_origin': array([-2.78840804, 2.57532978, -0.16439058]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2995452880859375, + 'left_pupil_posn': array([ 0.56316364, -0.16559958]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94198608, 0.32765198, 0.07278442]), + 'right_gaze_origin': array([-3.18386698, -3.10458541, -0.09423219]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.945159912109375, + 'right_pupil_posn': array([ 0.05966294, -0.24996138]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.032099369913339615, + 'throttle_input': 0.3531548082828522, + 'timestamp': 1116.905033878982, + 'timestamp_carla': 1116909, + 'timestamp_device': 4270337, + 'timestamp_stream': 1116.905033878982, + 'transform': [array([3.70598865e+00, 1.02148809e+01, 1.20586390e-03]), + array([ -0.06094578, -12.11168957, 0.02644214])]} +{'AngularVelocity': array([-1.78143533e-03, 9.86442715e-03, 3.03314328e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.80461883544922, + 'FR_Wheel_Angle': -30.880840301513672, + 'Location': array([ -5.04910707, -21.49930954, 0.17489973]), + 'Rotation': array([ -0.05996223, -13.96974564, 0.03367602]), + 'Velocity': array([-0.24398923, 0.18059073, 0.00112545]), + 'brake_input': 0.0, + 'camera_location': array([-8.54294205, 18.42552567, -0.31624141]), + 'camera_rotation': array([-6.74073362, 11.90040016, -1.76986933]), + 'current_gear_input': False, + 'focus_actor_dist': 2398.67236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 837.79382324, -3915.86376953, 15.88762665]), + 'frame': 34736, + 'frame_number': 34736, + 'framesequence': 132922, + 'gaze_dir': array([0.94568634, 0.32082367, 0.04621887]), + 'gaze_origin': array([-2.98473978, -0.26341859, -0.12898102]), + 'gaze_valid': True, + 'gaze_vergence': 12.544576644897461, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94789124, 0.31776428, 0.02223206]), + 'left_gaze_origin': array([-2.78788161, 2.5761795 , -0.16439058]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3033294677734375, + 'left_pupil_posn': array([ 0.56109285, -0.16625905]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94348145, 0.32388306, 0.07020569]), + 'right_gaze_origin': array([-3.18159795, -3.10301685, -0.09357148]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8058929443359375, + 'right_pupil_posn': array([ 0.05265164, -0.25008631]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.028272347524762154, + 'throttle_input': 0.3610894978046417, + 'timestamp': 1116.9354483783245, + 'timestamp_carla': 1116939, + 'timestamp_device': 4270370, + 'timestamp_stream': 1116.9354483783245, + 'transform': [array([3.71899915e+00, 1.01648598e+01, 2.17075343e-04]), + array([ -0.06034472, -12.14308262, 0.02844417])]} +{'AngularVelocity': array([0.02019659, 0.04190639, 3.00189114]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.876922607421875, + 'FR_Wheel_Angle': -30.918628692626953, + 'Location': array([ -5.09307432, -21.47186661, 0.17499803]), + 'Rotation': array([ -0.06277627, -13.27369881, 0.02838612]), + 'Velocity': array([-1.74916133e-01, 1.14319004e-01, 6.62708262e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.4722023 , 18.59765244, -0.3339363 ]), + 'camera_rotation': array([-6.7634511 , 12.60720253, -1.99263966]), + 'current_gear_input': False, + 'focus_actor_dist': 2120.507080078125, + 'focus_actor_name': 'Plane_635', + 'focus_actor_pt': array([ 708.17211914, -3673.91113281, 16.1232605 ]), + 'frame': 34737, + 'frame_number': 34737, + 'framesequence': 132926, + 'gaze_dir': array([0.94734192, 0.31742096, 0.04097748]), + 'gaze_origin': array([-2.98197412, -0.25569764, -0.1295189 ]), + 'gaze_valid': True, + 'gaze_vergence': 11.9002046585083, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94792175, 0.31690979, 0.03167725]), + 'left_gaze_origin': array([-2.78288603, 2.58480239, -0.16247101]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2985382080078125, + 'left_pupil_posn': array([ 0.55236399, -0.17061198]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94676208, 0.31793213, 0.05027771]), + 'right_gaze_origin': array([-3.1810627 , -3.09619784, -0.09656677]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9456939697265625, + 'right_pupil_posn': array([ 0.04749513, -0.24886906]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02468337118625641, + 'throttle_input': 0.3690241873264313, + 'timestamp': 1116.967732977122, + 'timestamp_carla': 1116971, + 'timestamp_device': 4270403, + 'timestamp_stream': 1116.967732977122, + 'transform': [array([ 3.73129082e+00, 1.01103354e+01, -7.24735262e-04]), + array([ -0.05973683, -12.17336655, 0.03032096])]} +{'AngularVelocity': array([ 0.00916829, -0.00347001, 2.30861354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.871360778808594, + 'FR_Wheel_Angle': -30.906005859375, + 'Location': array([ -5.12959528, -21.44937897, 0.17505105]), + 'Rotation': array([ -0.06722955, -12.70009136, 0.02095834]), + 'Velocity': array([-0.1448195 , 0.1040694 , 0.00026746]), + 'brake_input': 0.0, + 'camera_location': array([-8.41497707, 18.77608109, -0.3855418 ]), + 'camera_rotation': array([-6.92993021, 13.39406586, -1.9247905 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1958.2783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 644.66149902, -3528.08813477, 16.08680725]), + 'frame': 34738, + 'frame_number': 34738, + 'framesequence': 132930, + 'gaze_dir': array([0.94807434, 0.31423187, 0.0475769 ]), + 'gaze_origin': array([-2.98058772, -0.25092927, -0.12566376]), + 'gaze_valid': True, + 'gaze_vergence': 70.33123016357422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94975281, 0.31077576, 0.03686523]), + 'left_gaze_origin': array([-2.78175211, 2.59040236, -0.16031343]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2139434814453125, + 'left_pupil_posn': array([ 0.54822326, -0.16596866]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94639587, 0.31768799, 0.05828857]), + 'right_gaze_origin': array([-3.17942357, -3.09226084, -0.0910141 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0054473876953125, + 'right_pupil_posn': array([ 0.04254186, -0.24274421]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.020947905257344246, + 'throttle_input': 0.37299153208732605, + 'timestamp': 1117.000225879252, + 'timestamp_carla': 1117004, + 'timestamp_device': 4270437, + 'timestamp_stream': 1117.000225879252, + 'transform': [array([ 3.74195862e+00, 1.00539656e+01, -1.55866623e-03]), + array([ -0.05916309, -12.20046425, 0.03198749])]} +{'AngularVelocity': array([0.04984362, 0.0363549 , 4.2957077 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.80907440185547, + 'FR_Wheel_Angle': -30.877965927124023, + 'Location': array([ -5.16674614, -21.42717934, 0.17511961]), + 'Rotation': array([ -0.07177845, -12.12645245, 0.01364227]), + 'Velocity': array([-2.15517968e-01, 1.45162016e-01, 1.16500851e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.35716629, 18.93704224, -0.44007546]), + 'camera_rotation': array([-7.07660818, 14.13362789, -1.85716569]), + 'current_gear_input': False, + 'focus_actor_dist': 2068.58984375, + 'focus_actor_name': 'Plane_635', + 'focus_actor_pt': array([ 715.29248047, -3620.31005859, 16.12326813]), + 'frame': 34739, + 'frame_number': 34739, + 'framesequence': 132933, + 'gaze_dir': array([0.95301056, 0.29863739, 0.0483017 ]), + 'gaze_origin': array([-2.97802591, -0.24574052, -0.12205429]), + 'gaze_valid': True, + 'gaze_vergence': 107.78607177734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9508667 , 0.30744934, 0.03605652]), + 'left_gaze_origin': array([-2.77865767, 2.59549403, -0.15653992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0425262451171875, + 'left_pupil_posn': array([ 0.53415251, -0.16083217]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95515442, 0.28982544, 0.06054688]), + 'right_gaze_origin': array([-3.17739439, -3.0869751 , -0.08756867]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.98675537109375, + 'right_pupil_posn': array([ 0.03771842, -0.24009085]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.017651906237006187, + 'throttle_input': 0.3809414803981781, + 'timestamp': 1117.033383578062, + 'timestamp_carla': 1117037, + 'timestamp_device': 4270462, + 'timestamp_stream': 1117.033383578062, + 'transform': [array([ 3.75115275e+00, 9.99488831e+00, -2.29408266e-03]), + array([ -0.058644 , -12.22469711, 0.0334565 ])]} +{'AngularVelocity': array([0.07571661, 0.0609652 , 5.95076227]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6807861328125, + 'FR_Wheel_Angle': -30.79373550415039, + 'Location': array([ -5.22179604, -21.39588737, 0.17520173]), + 'Rotation': array([-7.68737718e-02, -1.13443165e+01, 8.55960324e-03]), + 'Velocity': array([-0.36676657, 0.23216224, 0.00043534]), + 'brake_input': 0.0, + 'camera_location': array([-8.29698372, 19.12406921, -0.46457839]), + 'camera_rotation': array([-7.20580149, 14.8837347 , -1.98694766]), + 'current_gear_input': False, + 'focus_actor_dist': 1960.19970703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 655.19897461, -3534.8449707 , 16.07594299]), + 'frame': 34740, + 'frame_number': 34740, + 'framesequence': 132938, + 'gaze_dir': array([0.95593262, 0.28822327, 0.05371094]), + 'gaze_origin': array([-2.97598052, -0.23958132, -0.11947709]), + 'gaze_valid': True, + 'gaze_vergence': 62.8708381652832, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95530701, 0.2928772 , 0.03979492]), + 'left_gaze_origin': array([-2.77644968, 2.60284281, -0.15224916]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2749176025390625, + 'left_pupil_posn': array([ 0.52647746, -0.15534544]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95655823, 0.28356934, 0.06762695]), + 'right_gaze_origin': array([-3.17551112, -3.0820055 , -0.08670502]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0340423583984375, + 'right_pupil_posn': array([ 0.0290252 , -0.23738337]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.014392529614269733, + 'throttle_input': 0.38887616991996765, + 'timestamp': 1117.0669387765229, + 'timestamp_carla': 1117071, + 'timestamp_device': 4270503, + 'timestamp_stream': 1117.0669387765229, + 'transform': [array([ 3.75871778e+00, 9.93344116e+00, -2.94387806e-03]), + array([ -0.05817272, -12.2457552 , 0.03476018])]} +{'AngularVelocity': array([-1.11442871e-01, 9.79274977e-04, 6.64410782e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.61277770996094, + 'FR_Wheel_Angle': -30.480571746826172, + 'Location': array([ -5.32403612, -21.33952141, 0.17531255]), + 'Rotation': array([-7.79734328e-02, -9.85136223e+00, 7.49410968e-03]), + 'Velocity': array([-4.77628231e-01, 2.95769870e-01, 4.49633575e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.24591255, 19.29942131, -0.48928216]), + 'camera_rotation': array([-7.34560156, 15.67684555, -1.83650863]), + 'current_gear_input': False, + 'focus_actor_dist': 2068.510986328125, + 'focus_actor_name': 'Plane_635', + 'focus_actor_pt': array([ 710.54370117, -3633.83496094, 16.12326813]), + 'frame': 34741, + 'frame_number': 34741, + 'framesequence': 132942, + 'gaze_dir': array([0.95943451, 0.27619934, 0.05298615]), + 'gaze_origin': array([-2.97394729, -0.23449403, -0.11939926]), + 'gaze_valid': True, + 'gaze_vergence': 32.50777053833008, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95932007, 0.28018188, 0.03425598]), + 'left_gaze_origin': array([-2.77458048, 2.60827494, -0.15255585]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2497406005859375, + 'left_pupil_posn': array([ 0.51842117, -0.15339279]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95954895, 0.2722168 , 0.07171631]), + 'right_gaze_origin': array([-3.17331409, -3.07726312, -0.08624268]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.03106689453125, + 'right_pupil_posn': array([ 0.02115619, -0.23817241]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.011114842258393764, + 'throttle_input': 0.3968108594417572, + 'timestamp': 1117.099856376648, + 'timestamp_carla': 1117104, + 'timestamp_device': 4270537, + 'timestamp_stream': 1117.099856376648, + 'transform': [array([ 3.76430392e+00, 9.87142467e+00, -3.55428690e-03]), + array([ -0.05770826, -12.26275158, 0.03600405])]} +{'AngularVelocity': array([-0.13927139, 0.00699202, 6.42724085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.882164001464844, + 'FR_Wheel_Angle': -28.13027572631836, + 'Location': array([ -5.44083929, -21.27927399, 0.17538454]), + 'Rotation': array([-0.07419634, -8.18027592, 0.01634818]), + 'Velocity': array([-5.10773063e-01, 2.75605112e-01, 4.13465488e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.19051838, 19.46854019, -0.53039402]), + 'camera_rotation': array([-7.59710979, 16.47817802, -1.74384499]), + 'current_gear_input': False, + 'focus_actor_dist': 1913.833251953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 636.57104492, -3503.54589844, 16.09529877]), + 'frame': 34742, + 'frame_number': 34742, + 'framesequence': 132946, + 'gaze_dir': array([0.96101379, 0.27101898, 0.05395508]), + 'gaze_origin': array([-2.97246647, -0.22772981, -0.11433563]), + 'gaze_valid': True, + 'gaze_vergence': 32.66597366333008, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96128845, 0.27178955, 0.04519653]), + 'left_gaze_origin': array([-2.77243209, 2.61630106, -0.14656831]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.193939208984375, + 'left_pupil_posn': array([ 0.51192331, -0.15185153]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96073914, 0.27024841, 0.06271362]), + 'right_gaze_origin': array([-3.17250085, -3.07176065, -0.08210297]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.93994140625, + 'right_pupil_posn': array([ 0.01463139, -0.23084807]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.008368175476789474, + 'throttle_input': 0.40474554896354675, + 'timestamp': 1117.1338712759316, + 'timestamp_carla': 1117138, + 'timestamp_device': 4270570, + 'timestamp_stream': 1117.1338712759316, + 'transform': [array([ 3.76828504e+00, 9.80553722e+00, -4.10829531e-03]), + array([ -0.05729162, -12.27670383, 0.03712404])]} +{'AngularVelocity': array([0.17976569, 0.08435141, 5.82205296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.12040328979492, + 'FR_Wheel_Angle': -24.33660316467285, + 'Location': array([ -5.583148 , -21.21746254, 0.17624952]), + 'Rotation': array([-0.09988468, -6.44309044, -0.02380371]), + 'Velocity': array([-0.50116062, 0.23508525, 0.00428791]), + 'brake_input': 0.0, + 'camera_location': array([-8.16477108, 19.65459251, -0.56807005]), + 'camera_rotation': array([-7.83378267, 17.27826118, -1.72625899]), + 'current_gear_input': False, + 'focus_actor_dist': 1795.1185302734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 591.12890625, -3398.53955078, 16.14263916]), + 'frame': 34743, + 'frame_number': 34743, + 'framesequence': 132949, + 'gaze_dir': array([0.96342468, 0.26146698, 0.05770111]), + 'gaze_origin': array([-2.97084904, -0.22308122, -0.11208801]), + 'gaze_valid': True, + 'gaze_vergence': 124.66889953613281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96276855, 0.26589966, 0.04862976]), + 'left_gaze_origin': array([-2.77083898, 2.61967945, -0.14454041]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.14251708984375, + 'left_pupil_posn': array([ 0.50468874, -0.14836109]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96408081, 0.2570343 , 0.06677246]), + 'right_gaze_origin': array([-3.1708591 , -3.06584191, -0.07963562]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.016265869140625, + 'right_pupil_posn': array([ 0.00838852, -0.22757137]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00536515424028039, + 'throttle_input': 0.4166475832462311, + 'timestamp': 1117.1652757786214, + 'timestamp_carla': 1117169, + 'timestamp_device': 4270595, + 'timestamp_stream': 1117.1652757786214, + 'transform': [array([ 3.77018619e+00, 9.74285221e+00, -4.67584608e-03]), + array([ -0.05687498, -12.28604698, 0.03831146])]} +{'AngularVelocity': array([-0.0336197 , -0.03057047, 4.08472824]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.4494571685791, + 'FR_Wheel_Angle': -19.12740135192871, + 'Location': array([ -5.68490934, -21.18255806, 0.17646948]), + 'Rotation': array([-0.10083408, -5.47815275, -0.02038574]), + 'Velocity': array([-4.99365836e-01, 1.79020494e-01, -5.61618799e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.16477108, 19.65459251, -0.56807005]), + 'camera_rotation': array([-7.83378267, 17.27826118, -1.72625899]), + 'current_gear_input': False, + 'focus_actor_dist': 1769.302978515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 583.79199219, -3379.29492188, 16.15029907]), + 'frame': 34744, + 'frame_number': 34744, + 'framesequence': 132954, + 'gaze_dir': array([0.9648056 , 0.25289154, 0.07149506]), + 'gaze_origin': array([-2.96910334, -0.21537554, -0.10965119]), + 'gaze_valid': True, + 'gaze_vergence': 67.03728485107422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9650116 , 0.25436401, 0.06343079]), + 'left_gaze_origin': array([-2.76833367, 2.6295166 , -0.14380342]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.220977783203125, + 'left_pupil_posn': array([ 0.4957056 , -0.14300728]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96459961, 0.25141907, 0.07955933]), + 'right_gaze_origin': array([-3.16987324, -3.06026793, -0.07549897]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8197174072265625, + 'right_pupil_posn': array([ 0.00087798, -0.21859705]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0027649770490825176, + 'throttle_input': 0.42458227276802063, + 'timestamp': 1117.201414577663, + 'timestamp_carla': 1117205, + 'timestamp_device': 4270637, + 'timestamp_stream': 1117.201414577663, + 'transform': [array([ 3.77028823e+00, 9.66882038e+00, -5.12191746e-03]), + array([ -0.05649249, -12.29258251, 0.0391872 ])]} +{'AngularVelocity': array([ 5.25432639e-04, -1.04707144e-02, 2.43602395e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.630369186401367, + 'FR_Wheel_Angle': -13.543200492858887, + 'Location': array([ -5.80937195, -21.15037155, 0.17647344]), + 'Rotation': array([-0.09564313, -4.6253686 , -0.0161438 ]), + 'Velocity': array([-0.43732685, 0.10921923, 0.00085336]), + 'brake_input': 0.0, + 'camera_location': array([-8.13124084, 20.02870941, -0.68896431]), + 'camera_rotation': array([-8.21427917, 18.84691811, -1.65722191]), + 'current_gear_input': False, + 'focus_actor_dist': 2212.948486328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 787.71691895, -3780.64990234, 15.93823242]), + 'frame': 34745, + 'frame_number': 34745, + 'framesequence': 132957, + 'gaze_dir': array([0.96716309, 0.24235535, 0.07502747]), + 'gaze_origin': array([-2.96801925, -0.20897524, -0.10539093]), + 'gaze_valid': True, + 'gaze_vergence': 164.9591522216797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96472168, 0.25439453, 0.06759644]), + 'left_gaze_origin': array([-2.76666594, 2.6363008 , -0.13742219]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2891693115234375, + 'left_pupil_posn': array([ 0.48328924, -0.13706279]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96960449, 0.23031616, 0.0824585 ]), + 'right_gaze_origin': array([-3.16937256, -3.05425143, -0.07335968]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.875457763671875, + 'right_pupil_posn': array([-0.00326568, -0.21561921]), + 'right_pupil_posn_valid': True, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.4325169622898102, + 'timestamp': 1117.2332711778581, + 'timestamp_carla': 1117237, + 'timestamp_device': 4270662, + 'timestamp_stream': 1117.2332711778581, + 'transform': [array([ 3.76845574e+00, 9.60154438e+00, -5.60028059e-03]), + array([ -0.05608268, -12.29447556, 0.04021144])]} +{'AngularVelocity': array([ 6.46145968e-03, -7.40008254e-04, 2.11093879e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.644956588745117, + 'FR_Wheel_Angle': -7.075972080230713, + 'Location': array([ -5.90687132, -21.13286781, 0.17652139]), + 'Rotation': array([-0.09450933, -4.22506809, -0.01577759]), + 'Velocity': array([-0.40274471, 0.06572035, 0.00057561]), + 'brake_input': 0.0, + 'camera_location': array([-8.1130619 , 20.19773865, -0.73020333]), + 'camera_rotation': array([-8.45747471, 19.54402351, -1.58653295]), + 'current_gear_input': False, + 'focus_actor_dist': 2060.70654296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 741.86791992, -3638.47216797, 15.98622894]), + 'frame': 34746, + 'frame_number': 34746, + 'framesequence': 132961, + 'gaze_dir': array([0.96636963, 0.24588776, 0.0740509 ]), + 'gaze_origin': array([-2.96821213, -0.21242753, -0.10017167]), + 'gaze_valid': True, + 'gaze_vergence': 113.6744155883789, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96559143, 0.25224304, 0.06311035]), + 'left_gaze_origin': array([-2.76743484, 2.63344431, -0.13098907]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2454833984375, + 'left_pupil_posn': array([ 0.48855758, -0.13218963]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96714783, 0.23953247, 0.08499146]), + 'right_gaze_origin': array([-3.16898966, -3.05829954, -0.06935425]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.927001953125, + 'right_pupil_posn': array([-0.00134122, -0.21445191]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0017761773196980357, + 'throttle_input': 0.43648430705070496, + 'timestamp': 1117.2669247761369, + 'timestamp_carla': 1117271, + 'timestamp_device': 4270695, + 'timestamp_stream': 1117.2669247761369, + 'transform': [array([ 3.76479006e+00, 9.52837276e+00, -6.07446674e-03]), + array([ -0.055748 , -12.29300404, 0.0411926 ])]} +{'AngularVelocity': array([0.00139628, 0.00917151, 0.32089603]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6906400918960571, + 'FR_Wheel_Angle': 0.3294527232646942, + 'Location': array([ -6.00095606, -21.1225338 , 0.17659242]), + 'Rotation': array([-0.09597781, -4.09124851, -0.01553345]), + 'Velocity': array([-4.23542649e-01, 3.40620689e-02, 1.47924424e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.08451843, 20.35755539, -0.76213783]), + 'camera_rotation': array([-8.61434364, 20.17661095, -1.40744507]), + 'current_gear_input': False, + 'focus_actor_dist': 1888.898193359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 680.29406738, -3481.39038086, 16.0504837 ]), + 'frame': 34747, + 'frame_number': 34747, + 'framesequence': 132965, + 'gaze_dir': array([0.96443176, 0.25435638, 0.07089996]), + 'gaze_origin': array([-2.96722126, -0.21895142, -0.08835221]), + 'gaze_valid': True, + 'gaze_vergence': 74.10272216796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96437073, 0.25764465, 0.05996704]), + 'left_gaze_origin': array([-2.76655602, 2.62343001, -0.11841127]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.308563232421875, + 'left_pupil_posn': array([ 0.4995358 , -0.12515366]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9644928 , 0.25106812, 0.08183289]), + 'right_gaze_origin': array([-3.16788673, -3.06133294, -0.05829316]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.945220947265625, + 'right_pupil_posn': array([ 0.00266194, -0.20798421]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0029114659409970045, + 'throttle_input': 0.4444190263748169, + 'timestamp': 1117.2994089759886, + 'timestamp_carla': 1117303, + 'timestamp_device': 4270728, + 'timestamp_stream': 1117.2994089759886, + 'transform': [array([ 3.76003861e+00, 9.45546627e+00, -6.54418953e-03]), + array([ -0.05553627, -12.28922844, 0.0421824 ])]} +{'AngularVelocity': array([ 0.00212661, 0.02314919, -0.93220687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1052481085062027, + 'FR_Wheel_Angle': 0.013952813111245632, + 'Location': array([ -6.11196947, -21.11464119, 0.17674609]), + 'Rotation': array([-0.10230257, -4.09271336, -0.01779175]), + 'Velocity': array([-0.59389055, 0.04290911, 0.00088037]), + 'brake_input': 0.0, + 'camera_location': array([-8.03617477, 20.51807404, -0.72562039]), + 'camera_rotation': array([-8.31975079, 20.71718979, -1.28185523]), + 'current_gear_input': False, + 'focus_actor_dist': 1719.6600341796875, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 621.29138184, -3325.60107422, 16.22581482]), + 'frame': 34748, + 'frame_number': 34748, + 'framesequence': 132969, + 'gaze_dir': array([0.96442413, 0.25283051, 0.07541656]), + 'gaze_origin': array([-2.96723628, -0.21474688, -0.08984757]), + 'gaze_valid': True, + 'gaze_vergence': 33.14635467529297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9649353 , 0.25550842, 0.05993652]), + 'left_gaze_origin': array([-2.76604009, 2.63034678, -0.12022248]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.305084228515625, + 'left_pupil_posn': array([ 0.49440658, -0.12312257]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96391296, 0.25015259, 0.09089661]), + 'right_gaze_origin': array([-3.16843271, -3.05984068, -0.05947266]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.971527099609375, + 'right_pupil_posn': array([ 0.00084341, -0.20888412]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0039002655539661646, + 'throttle_input': 0.4603036642074585, + 'timestamp': 1117.3331479765475, + 'timestamp_carla': 1117337, + 'timestamp_device': 4270762, + 'timestamp_stream': 1117.3331479765475, + 'transform': [array([ 3.75404906e+00, 9.37737751e+00, -6.97357161e-03]), + array([ -0.05542698, -12.28324223, 0.04307184])]} +{'AngularVelocity': array([-0.00629185, -0.01037357, -0.90728033]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.053252171725034714, + 'FR_Wheel_Angle': 0.053185489028692245, + 'Location': array([ -6.22684717, -21.10646439, 0.17678033]), + 'Rotation': array([-0.09627834, -4.10080099, -0.01748657]), + 'Velocity': array([-5.71594596e-01, 4.11224738e-02, 3.37648380e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.98787498, 20.66718483, -0.65501606]), + 'camera_rotation': array([-7.81092215, 21.18929291, -1.00896633]), + 'current_gear_input': False, + 'focus_actor_dist': 1980.375244140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 774.74438477, -3544.7878418 , 15.95300293]), + 'frame': 34749, + 'frame_number': 34749, + 'framesequence': 132973, + 'gaze_dir': array([0.96559143, 0.24816132, 0.07653046]), + 'gaze_origin': array([-2.96750426, -0.21458969, -0.09786302]), + 'gaze_valid': True, + 'gaze_vergence': 35.53227615356445, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96611023, 0.25016785, 0.0634613 ]), + 'left_gaze_origin': array([-2.76617908, 2.63085032, -0.12908632]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.363739013671875, + 'left_pupil_posn': array([ 0.49266911, -0.12953496]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96507263, 0.24615479, 0.08959961]), + 'right_gaze_origin': array([-3.16882944, -3.06002975, -0.06663971]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8754425048828125, + 'right_pupil_posn': array([-0.00080788, -0.21231031]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004522843286395073, + 'throttle_input': 0.46823835372924805, + 'timestamp': 1117.3663417771459, + 'timestamp_carla': 1117370, + 'timestamp_device': 4270795, + 'timestamp_stream': 1117.3663417771459, + 'transform': [array([ 3.74731374e+00, 9.29803085e+00, -7.38458615e-03]), + array([ -0.05539283, -12.27579498, 0.04393803])]} +{'AngularVelocity': array([-0.01199791, -0.0180482 , -0.00220627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020251009613275528, + 'FR_Wheel_Angle': 0.015190227888524532, + 'Location': array([ -6.39458323, -21.09448624, 0.17691785]), + 'Rotation': array([-0.09627834, -4.0913415 , -0.01513672]), + 'Velocity': array([-0.68583488, 0.0492627 , 0.00071857]), + 'brake_input': 0.0, + 'camera_location': array([-7.9836731 , 20.8144722 , -0.64047885]), + 'camera_rotation': array([-7.60131693, 21.73312759, -0.73327816]), + 'current_gear_input': False, + 'focus_actor_dist': 2304.365234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 958.52728271, -3820.12988281, 15.76324463]), + 'frame': 34750, + 'frame_number': 34750, + 'framesequence': 132978, + 'gaze_dir': array([0.96638489, 0.24484253, 0.0765152 ]), + 'gaze_origin': array([-2.96754313, -0.21356356, -0.09915849]), + 'gaze_valid': True, + 'gaze_vergence': 11.388056755065918, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9680481 , 0.24343872, 0.06004333]), + 'left_gaze_origin': array([-2.76728821, 2.63121963, -0.13066864]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.364410400390625, + 'left_pupil_posn': array([ 0.49252427, -0.12965655]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96472168, 0.24624634, 0.09298706]), + 'right_gaze_origin': array([-3.16779804, -3.05834675, -0.06764832]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9311676025390625, + 'right_pupil_posn': array([-0.00447571, -0.21392345]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005420087371021509, + 'throttle_input': 0.4722056984901428, + 'timestamp': 1117.4004936777055, + 'timestamp_carla': 1117404, + 'timestamp_device': 4270837, + 'timestamp_stream': 1117.4004936777055, + 'transform': [array([ 3.73942399e+00, 9.21380997e+00, -7.76256528e-03]), + array([ -0.05534502, -12.26627636, 0.04472822])]} +{'AngularVelocity': array([-0.01346646, -0.00896815, -0.00862591]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.01518178079277277, + 'FR_Wheel_Angle': 0.015182919800281525, + 'Location': array([ -6.55802107, -21.08275032, 0.17702608]), + 'Rotation': array([-0.09283593, -4.09198141, -0.01260376]), + 'Velocity': array([-0.71180189, 0.05120357, 0.00092493]), + 'brake_input': 0.0, + 'camera_location': array([-8.00601578, 20.95480156, -0.6550917 ]), + 'camera_rotation': array([-7.62484026, 22.3130703 , -0.658544 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2408.990966796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 1028.93774414, -3907.09960938, 15.70801544]), + 'frame': 34751, + 'frame_number': 34751, + 'framesequence': 132981, + 'gaze_dir': array([0.96723175, 0.24315643, 0.070755 ]), + 'gaze_origin': array([-2.96719217, -0.2104912 , -0.0982399 ]), + 'gaze_valid': True, + 'gaze_vergence': 61.152793884277344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96679688, 0.24960327, 0.05447388]), + 'left_gaze_origin': array([-2.76687479, 2.63265085, -0.13017274]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.38775634765625, + 'left_pupil_posn': array([ 0.48806167, -0.13108051]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96766663, 0.23670959, 0.08703613]), + 'right_gaze_origin': array([-3.16750956, -3.05363321, -0.06630707]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9859466552734375, + 'right_pupil_posn': array([-0.0056383 , -0.21513987]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.006775109563022852, + 'throttle_input': 0.4761730432510376, + 'timestamp': 1117.4321004785597, + 'timestamp_carla': 1117436, + 'timestamp_device': 4270862, + 'timestamp_stream': 1117.4321004785597, + 'transform': [array([ 3.73092103e+00, 9.13340473e+00, -8.16526357e-03]), + array([ -0.05517427, -12.25513268, 0.04560634])]} +{'AngularVelocity': array([-0.01396283, -0.00727699, -0.0076431 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015175390057265759, + 'FR_Wheel_Angle': 0.015177317894995213, + 'Location': array([ -6.70631742, -21.07209396, 0.17710203]), + 'Rotation': array([-0.09082102, -4.09228611, -0.01019287]), + 'Velocity': array([-7.29792058e-01, 5.25146052e-02, 2.69699085e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.02500916, 21.0980072 , -0.67812121]), + 'camera_rotation': array([-7.62669802, 22.89925385, -0.52227271]), + 'current_gear_input': False, + 'focus_actor_dist': 2122.48486328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 885.52502441, -3666.24414062, 15.83839417]), + 'frame': 34752, + 'frame_number': 34752, + 'framesequence': 132985, + 'gaze_dir': array([0.96772766, 0.24095917, 0.07215881]), + 'gaze_origin': array([-2.96684885, -0.20868914, -0.09782792]), + 'gaze_valid': True, + 'gaze_vergence': 41.8377571105957, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96806335, 0.24380493, 0.05810547]), + 'left_gaze_origin': array([-2.76643085, 2.63381982, -0.12971954]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4037322998046875, + 'left_pupil_posn': array([ 0.48772597, -0.13102436]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96739197, 0.2381134 , 0.08621216]), + 'right_gaze_origin': array([-3.16726708, -3.05119801, -0.06593628]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0627593994140625, + 'right_pupil_posn': array([-0.00931394, -0.21337116]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.008075198158621788, + 'throttle_input': 0.4761730432510376, + 'timestamp': 1117.464905679226, + 'timestamp_carla': 1117469, + 'timestamp_device': 4270895, + 'timestamp_stream': 1117.464905679226, + 'transform': [array([ 3.72066760e+00, 9.04749393e+00, -8.54108762e-03]), + array([ -0.05492155, -12.24073601, 0.04640863])]} +{'AngularVelocity': array([-0.01406845, -0.00556922, 0.00088407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015171553939580917, + 'FR_Wheel_Angle': 0.015172830782830715, + 'Location': array([ -6.89976358, -21.05820084, 0.1772743 ]), + 'Rotation': array([-0.08865585, -4.09405661, -0.00698852]), + 'Velocity': array([-7.48527884e-01, 5.38699888e-02, 3.53164651e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.02500916, 21.0980072 , -0.67812121]), + 'camera_rotation': array([-7.62669802, 22.89925385, -0.52227271]), + 'current_gear_input': False, + 'focus_actor_dist': 2146.705810546875, + 'focus_actor_name': 'Plane10', + 'focus_actor_pt': array([ 913.64208984, -3684.47387695, 15.99401093]), + 'frame': 34753, + 'frame_number': 34753, + 'framesequence': 132990, + 'gaze_dir': array([0.96881104, 0.23574829, 0.07497406]), + 'gaze_origin': array([-2.96425939, -0.20013583, -0.09688645]), + 'gaze_valid': True, + 'gaze_vergence': 121.826904296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96765137, 0.24406433, 0.06381226]), + 'left_gaze_origin': array([-2.76165032, 2.64546061, -0.12747957]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3465423583984375, + 'left_pupil_posn': array([ 0.47564101, -0.12827313]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9699707 , 0.22743225, 0.08613586]), + 'right_gaze_origin': array([-3.16686893, -3.04573226, -0.06629334]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.013641357421875, + 'right_pupil_posn': array([-0.01297796, -0.21158373]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.010144352912902832, + 'throttle_input': 0.4761730432510376, + 'timestamp': 1117.5000968761742, + 'timestamp_carla': 1117504, + 'timestamp_device': 4270937, + 'timestamp_stream': 1117.5000968761742, + 'transform': [array([ 3.70756006e+00, 8.95286465e+00, -8.72190483e-03]), + array([ -0.05523574, -12.22101307, 0.04678256])]} +{'AngularVelocity': array([-0.01454716, -0.00681879, 0.00010767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015167021192610264, + 'FR_Wheel_Angle': 0.015168586745858192, + 'Location': array([ -7.0761857 , -21.04551697, 0.17740045]), + 'Rotation': array([-8.69141519e-02, -4.09472752e+00, -4.05883742e-03]), + 'Velocity': array([-7.64527142e-01, 5.50435036e-02, 4.32519912e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.03820801, 21.36586761, -0.73011321]), + 'camera_rotation': array([-7.82355785, 24.08242035, -0.26577011]), + 'current_gear_input': False, + 'focus_actor_dist': 2258.946044921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 967.45800781, -3792.38916016, 15.7534256 ]), + 'frame': 34754, + 'frame_number': 34754, + 'framesequence': 132994, + 'gaze_dir': array([0.97164917, 0.2241745 , 0.07436371]), + 'gaze_origin': array([-2.96251535, -0.19769135, -0.09481584]), + 'gaze_valid': True, + 'gaze_vergence': 161.7796630859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97097778, 0.22982788, 0.06613159]), + 'left_gaze_origin': array([-2.75954747, 2.65048242, -0.1250824 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.489959716796875, + 'left_pupil_posn': array([ 0.46888578, -0.12757611]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97232056, 0.21852112, 0.08259583]), + 'right_gaze_origin': array([-3.165483 , -3.04586506, -0.06454926]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.03485107421875, + 'right_pupil_posn': array([-0.01793408, -0.20901644]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.012176885269582272, + 'throttle_input': 0.4801403880119324, + 'timestamp': 1117.5326934792101, + 'timestamp_carla': 1117537, + 'timestamp_device': 4270970, + 'timestamp_stream': 1117.5326934792101, + 'transform': [array([ 3.69321012e+00, 8.86286449e+00, -8.77696928e-03]), + array([ -0.05563872, -12.19824886, 0.04695062])]} +{'AngularVelocity': array([-0.0146959 , -0.00725071, -0.00254774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015163817442953587, + 'FR_Wheel_Angle': 0.015166936442255974, + 'Location': array([ -7.25565672, -21.03261375, 0.17753118]), + 'Rotation': array([-8.50290209e-02, -4.09530783e+00, -1.06811512e-03]), + 'Velocity': array([-7.75659084e-01, 5.58606647e-02, 6.73322647e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.05126286, 21.48793793, -0.74231088]), + 'camera_rotation': array([-7.993855 , 24.65756607, -0.09489066]), + 'current_gear_input': False, + 'focus_actor_dist': 2043.86083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 861.99951172, -3613.12036133, 15.86290741]), + 'frame': 34755, + 'frame_number': 34755, + 'framesequence': 132997, + 'gaze_dir': array([0.97195435, 0.22341919, 0.07054901]), + 'gaze_origin': array([-2.96226978, -0.19514389, -0.090728 ]), + 'gaze_valid': True, + 'gaze_vergence': 53.651649475097656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97164917, 0.23057556, 0.05215454]), + 'left_gaze_origin': array([-2.75927448, 2.65356159, -0.12278138]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4704132080078125, + 'left_pupil_posn': array([ 0.46594453, -0.12375462]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97225952, 0.21626282, 0.08894348]), + 'right_gaze_origin': array([-3.16526508, -3.04384947, -0.05867463]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0133209228515625, + 'right_pupil_posn': array([-0.01912034, -0.20979738]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.014319284819066525, + 'throttle_input': 0.4801403880119324, + 'timestamp': 1117.5655278787017, + 'timestamp_carla': 1117569, + 'timestamp_device': 4270995, + 'timestamp_stream': 1117.5655278787017, + 'transform': [array([ 3.67630148e+00, 8.76992416e+00, -8.60589929e-03]), + array([ -0.05553627, -12.17023659, 0.04665504])]} +{'AngularVelocity': array([-0.01571261, -0.01502961, -0.0097735 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015156731009483337, + 'FR_Wheel_Angle': 0.015159332193434238, + 'Location': array([ -7.39744234, -21.02241135, 0.17768118]), + 'Rotation': array([-8.46260414e-02, -4.09567356e+00, 1.34708907e-03]), + 'Velocity': array([-8.03781569e-01, 5.79266436e-02, 2.03633303e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.13977718, 21.64218521, -0.74085391]), + 'camera_rotation': array([-8.02469349, 25.27331924, 0.05225495]), + 'current_gear_input': False, + 'focus_actor_dist': 1809.6378173828125, + 'focus_actor_name': 'Plane11', + 'focus_actor_pt': array([ 742.63330078, -3419.32788086, 15.99460602]), + 'frame': 34756, + 'frame_number': 34756, + 'framesequence': 133001, + 'gaze_dir': array([0.97219086, 0.22298431, 0.06973267]), + 'gaze_origin': array([-2.96209407, -0.19362031, -0.08999329]), + 'gaze_valid': True, + 'gaze_vergence': 85.39807891845703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9715271 , 0.23017883, 0.05589294]), + 'left_gaze_origin': array([-2.75836039, 2.65498519, -0.12286225]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.476104736328125, + 'left_pupil_posn': array([ 0.46475267, -0.12543559]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97285461, 0.21578979, 0.08357239]), + 'right_gaze_origin': array([-3.16582799, -3.04222584, -0.05712433]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0649871826171875, + 'right_pupil_posn': array([-0.02035171, -0.2075516 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.016150396317243576, + 'throttle_input': 0.45235371589660645, + 'timestamp': 1117.5985120758414, + 'timestamp_carla': 1117602, + 'timestamp_device': 4271028, + 'timestamp_stream': 1117.5985120758414, + 'transform': [array([ 3.65692735e+00, 8.67428303e+00, -8.26055463e-03]), + array([ -0.05526306, -12.13712883, 0.04600369])]} +{'AngularVelocity': array([-0.01306751, -0.0206644 , -0.00270606]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015165417455136776, + 'FR_Wheel_Angle': 0.015170151367783546, + 'Location': array([ -7.55585146, -21.01101494, 0.17777056]), + 'Rotation': array([-8.07191730e-02, -4.09601021e+00, 3.95768601e-03]), + 'Velocity': array([-7.67741740e-01, 5.53027838e-02, 2.95209873e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.13977718, 21.64218521, -0.74085391]), + 'camera_rotation': array([-8.02469349, 25.27331924, 0.05225495]), + 'current_gear_input': False, + 'focus_actor_dist': 1755.380126953125, + 'focus_actor_name': 'Plane_635', + 'focus_actor_pt': array([ 726.59454346, -3373.33203125, 16.12327576]), + 'frame': 34757, + 'frame_number': 34757, + 'framesequence': 133005, + 'gaze_dir': array([0.9723587 , 0.22097015, 0.07409668]), + 'gaze_origin': array([-2.96209812, -0.18975145, -0.09005051]), + 'gaze_valid': True, + 'gaze_vergence': 109.7720718383789, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97166443, 0.22787476, 0.06256104]), + 'left_gaze_origin': array([-2.75779128, 2.65714121, -0.12298585]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5423431396484375, + 'left_pupil_posn': array([ 0.462641 , -0.12479115]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97305298, 0.21406555, 0.08563232]), + 'right_gaze_origin': array([-3.16640472, -3.03664422, -0.05711518]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1474456787109375, + 'right_pupil_posn': array([-0.02503937, -0.20543706]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.017706841230392456, + 'throttle_input': 0.42458227276802063, + 'timestamp': 1117.6307034790516, + 'timestamp_carla': 1117635, + 'timestamp_device': 4271062, + 'timestamp_stream': 1117.6307034790516, + 'transform': [array([ 3.63586688e+00, 8.57877445e+00, -7.78350793e-03]), + array([ -0.05501034, -12.10035133, 0.04509811])]} +{'AngularVelocity': array([ 0.00226101, -0.04380361, 0.00021115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.58486843, -21.00892448, 0.17753652]), + 'Rotation': array([-3.81466039e-02, -4.09555149e+00, 4.08380898e-03]), + 'Velocity': array([ 0.27123344, -0.01958244, -0.00054363]), + 'brake_input': 0.0, + 'camera_location': array([-8.18803883, 21.77633476, -0.74637157]), + 'camera_rotation': array([-8.07931423, 25.82421684, 0.08400137]), + 'current_gear_input': False, + 'focus_actor_dist': 1878.7591552734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 796.63586426, -3484.98828125, 15.93086243]), + 'frame': 34758, + 'frame_number': 34758, + 'framesequence': 133009, + 'gaze_dir': array([0.9723587 , 0.22042847, 0.07542419]), + 'gaze_origin': array([-2.96213484, -0.18842164, -0.09005051]), + 'gaze_valid': True, + 'gaze_vergence': 135.4741668701172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97076416, 0.23098755, 0.06503296]), + 'left_gaze_origin': array([-2.75761104, 2.65807366, -0.12276611]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5605316162109375, + 'left_pupil_posn': array([ 0.46049833, -0.12452722]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97395325, 0.20986938, 0.08581543]), + 'right_gaze_origin': array([-3.16665816, -3.03491688, -0.0573349 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1594696044921875, + 'right_pupil_posn': array([-0.0251174 , -0.20487583]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01983092911541462, + 'throttle_input': 0.3928435146808624, + 'timestamp': 1117.6647110767663, + 'timestamp_carla': 1117669, + 'timestamp_device': 4271095, + 'timestamp_stream': 1117.6647110767663, + 'transform': [array([ 3.61099839e+00, 8.47583961e+00, -7.07489019e-03]), + array([ -0.05473713, -12.05601215, 0.0437056 ])]} +{'AngularVelocity': array([0.01497708, 0.12425401, 0.00059977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.011501438915729523, + 'Location': array([ -7.50593138, -21.01461411, 0.17752634]), + 'Rotation': array([-5.91972470e-02, -4.09530735e+00, 2.99769966e-03]), + 'Velocity': array([ 4.14365888e-01, -2.98891719e-02, -1.26142506e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.21457481, 21.89263535, -0.76225245]), + 'camera_rotation': array([-8.1476984 , 26.32327271, 0.20519854]), + 'current_gear_input': False, + 'focus_actor_dist': 1886.4625244140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 815.79553223, -3490.34863281, 15.91113281]), + 'frame': 34759, + 'frame_number': 34759, + 'framesequence': 133013, + 'gaze_dir': array([0.97268677, 0.21913147, 0.07499695]), + 'gaze_origin': array([-2.96228886, -0.18756792, -0.09035187]), + 'gaze_valid': True, + 'gaze_vergence': 131.5712127685547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97132874, 0.2288208 , 0.06430054]), + 'left_gaze_origin': array([-2.75761104, 2.65891433, -0.12319794]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5090179443359375, + 'left_pupil_posn': array([ 0.45977449, -0.12486529]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9740448 , 0.20944214, 0.08569336]), + 'right_gaze_origin': array([-3.16696644, -3.03405023, -0.0575058 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1597747802734375, + 'right_pupil_posn': array([-0.02648604, -0.20524776]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.022724082693457603, + 'throttle_input': 0.3333180844783783, + 'timestamp': 1117.6943420767784, + 'timestamp_carla': 1117698, + 'timestamp_device': 4271128, + 'timestamp_stream': 1117.6943420767784, + 'transform': [array([ 3.58671021e+00, 8.38501453e+00, -6.12993212e-03]), + array([ -0.05453906, -12.01182079, 0.04177738])]} +{'AngularVelocity': array([-1.62140548e-03, -2.17367467e-02, 5.58215979e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451887667179108, + 'FR_Wheel_Angle': 0.0038453307934105396, + 'Location': array([ -7.50239611, -21.01486778, 0.17776132]), + 'Rotation': array([-8.83143395e-02, -4.09530783e+00, 3.14935599e-03]), + 'Velocity': array([-1.23440095e-05, 6.96098414e-06, 3.78998695e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.28304577, 21.9894371 , -0.76895934]), + 'camera_rotation': array([-8.32792664, 26.82824898, 0.43829188]), + 'current_gear_input': False, + 'focus_actor_dist': 1824.260009765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 790.70483398, -3441.9609375 , 15.93722534]), + 'frame': 34760, + 'frame_number': 34760, + 'framesequence': 133017, + 'gaze_dir': array([0.97359467, 0.21562195, 0.07351685]), + 'gaze_origin': array([-2.96086287, -0.1834961 , -0.08513337]), + 'gaze_valid': True, + 'gaze_vergence': 25.173147201538086, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9743042 , 0.21714783, 0.05957031]), + 'left_gaze_origin': array([-2.7552979 , 2.66450524, -0.11900941]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5432586669921875, + 'left_pupil_posn': array([ 0.45746994, -0.12103581]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97288513, 0.21409607, 0.08746338]), + 'right_gaze_origin': array([-3.16642785, -3.03149724, -0.05125733]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2493133544921875, + 'right_pupil_posn': array([-0.03241622, -0.20234358]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.025727104395627975, + 'throttle_input': 0.3055466413497925, + 'timestamp': 1117.7311449758708, + 'timestamp_carla': 1117735, + 'timestamp_device': 4271162, + 'timestamp_stream': 1117.7311449758708, + 'transform': [array([ 3.55250216e+00, 8.27114582e+00, -4.67679976e-03]), + array([ -0.05417023, -11.94831085, 0.03893768])]} +{'AngularVelocity': array([-1.01248862e-03, -1.37126660e-02, 5.17007757e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.006408886518329382, + 'Location': array([ -7.50236654, -21.01486969, 0.17770013]), + 'Rotation': array([-8.41410980e-02, -4.09530735e+00, 3.14997835e-03]), + 'Velocity': array([-7.01318459e-06, 6.24429049e-06, 1.48529158e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.34162235, 22.05369377, -0.79639661]), + 'camera_rotation': array([-8.51639843, 27.28211594, 0.66396916]), + 'current_gear_input': False, + 'focus_actor_dist': 1677.6072998046875, + 'focus_actor_name': 'Plane_635', + 'focus_actor_pt': array([ 710.63726807, -3327.65551758, 16.12326813]), + 'frame': 34761, + 'frame_number': 34761, + 'framesequence': 133021, + 'gaze_dir': array([0.97319031, 0.21765137, 0.07314301]), + 'gaze_origin': array([-2.96046233, -0.18374558, -0.08293687]), + 'gaze_valid': True, + 'gaze_vergence': 84.07545471191406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97305298, 0.22224426, 0.06135559]), + 'left_gaze_origin': array([-2.7543838 , 2.66441202, -0.11795502]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.543060302734375, + 'left_pupil_posn': array([ 0.45711732, -0.12103581]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97332764, 0.21305847, 0.08493042]), + 'right_gaze_origin': array([-3.16654062, -3.03190303, -0.0479187 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.18182373046875, + 'right_pupil_posn': array([-0.03026807, -0.19952631]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03162328153848648, + 'throttle_input': 0.2380865216255188, + 'timestamp': 1117.760087877512, + 'timestamp_carla': 1117764, + 'timestamp_device': 4271195, + 'timestamp_stream': 1117.760087877512, + 'transform': [array([ 3.52097273e+00, 8.18134117e+00, -3.31932050e-03]), + array([ -0.05351453, -11.88845539, 0.0362702 ])]} +{'AngularVelocity': array([-2.08049198e-04, -3.34043382e-03, 6.09081799e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011534708552062511, + 'FR_Wheel_Angle': 0.011535996571183205, + 'Location': array([ -7.50235415, -21.0148735 , 0.17770021]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([2.45980914e-07, 6.07523225e-06, 2.52887607e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.37517929, 22.12417984, -0.79734451]), + 'camera_rotation': array([-8.664361 , 27.67598915, 0.91663975]), + 'current_gear_input': False, + 'focus_actor_dist': 1578.82177734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 664.63122559, -3249.95166016, 16.06797028]), + 'frame': 34762, + 'frame_number': 34762, + 'framesequence': 133025, + 'gaze_dir': array([0.97447968, 0.21138 , 0.07355499]), + 'gaze_origin': array([-2.96068668, -0.18424073, -0.08334503]), + 'gaze_valid': True, + 'gaze_vergence': 78.40847778320312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97393799, 0.21910095, 0.05853271]), + 'left_gaze_origin': array([-2.75464177, 2.66361403, -0.11789246]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.58026123046875, + 'left_pupil_posn': array([ 0.45436704, -0.11971927]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97502136, 0.20365906, 0.08857727]), + 'right_gaze_origin': array([-3.16673136, -3.03209543, -0.04879761]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2091827392578125, + 'right_pupil_posn': array([-0.03130555, -0.20112383]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.036768700927495956, + 'throttle_input': 0.18649576604366302, + 'timestamp': 1117.7973906770349, + 'timestamp_carla': 1117801, + 'timestamp_device': 4271228, + 'timestamp_stream': 1117.7973906770349, + 'transform': [array([ 3.47336626e+00, 8.06590939e+00, -1.29169459e-03]), + array([ -0.05247634, -11.79637718, 0.03233539])]} +{'AngularVelocity': array([-1.14152084e-04, -7.63690390e-04, 1.76066842e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021785616874694824, + 'FR_Wheel_Angle': 0.021790215745568275, + 'Location': array([ -7.50235081, -21.0148735 , 0.17769895]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([2.13024668e-06, 1.84957585e-07, 1.05715264e-03]), + 'brake_input': 0.0, + 'camera_location': array([-8.41702843, 22.1974411 , -0.76749241]), + 'camera_rotation': array([-8.69704342, 28.02541733, 1.06727469]), + 'current_gear_input': False, + 'focus_actor_dist': 1512.2996826171875, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 625.65563965, -3205.29614258, 16.22583008]), + 'frame': 34763, + 'frame_number': 34763, + 'framesequence': 133029, + 'gaze_dir': array([0.97444153, 0.21148682, 0.07394409]), + 'gaze_origin': array([-2.96073461, -0.18427125, -0.08298874]), + 'gaze_valid': True, + 'gaze_vergence': 91.87372589111328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97377014, 0.21931458, 0.06036377]), + 'left_gaze_origin': array([-2.75481892, 2.66361403, -0.11700439]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5881500244140625, + 'left_pupil_posn': array([ 0.45436704, -0.11952627]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97511292, 0.20365906, 0.08752441]), + 'right_gaze_origin': array([-3.16665053, -3.03215647, -0.04897308]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.19696044921875, + 'right_pupil_posn': array([-0.03115934, -0.20057583]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.044807277619838715, + 'throttle_input': 0.13492026925086975, + 'timestamp': 1117.826854776591, + 'timestamp_carla': 1117831, + 'timestamp_device': 4271262, + 'timestamp_stream': 1117.826854776591, + 'transform': [array([3.42923856e+00, 7.97558451e+00, 5.52520738e-04]), + array([ -0.05144498, -11.70958233, 0.02872687])]} +{'AngularVelocity': array([ 3.14001113e-06, -2.14793894e-04, 2.55798568e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.005127109121531248, + 'FR_Wheel_Angle': -0.005126854870468378, + 'Location': array([ -7.50235033, -21.0148735 , 0.17769766]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.29978173e-06, 3.64164023e-08, -4.16221796e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.48104286, 22.27952957, -0.77082807]), + 'camera_rotation': array([-8.77919674, 28.35149574, 1.29906237]), + 'current_gear_input': False, + 'focus_actor_dist': 1498.179443359375, + 'focus_actor_name': 'Plane2', + 'focus_actor_pt': array([ 626.17346191, -3199.28735352, 16.22582245]), + 'frame': 34764, + 'frame_number': 34764, + 'framesequence': 133033, + 'gaze_dir': array([0.96794891, 0.23580933, 0.08449554]), + 'gaze_origin': array([-2.96463418, -0.19821855, -0.08513337]), + 'gaze_valid': True, + 'gaze_vergence': 90.35457611083984, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96688843, 0.24537659, 0.06994629]), + 'left_gaze_origin': array([-2.75875711, 2.65029764, -0.11735535]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5960693359375, + 'left_pupil_posn': array([ 0.47168624, -0.11710811]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9690094 , 0.22624207, 0.0990448 ]), + 'right_gaze_origin': array([-3.17051125, -3.04673481, -0.05291138]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.184478759765625, + 'right_pupil_posn': array([-0.01183516, -0.20134962]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05154576525092125, + 'throttle_input': 0.10713358968496323, + 'timestamp': 1117.8654365763068, + 'timestamp_carla': 1117869, + 'timestamp_device': 4271295, + 'timestamp_stream': 1117.8654365763068, + 'transform': [array([3.36172009e+00, 7.85908937e+00, 3.20196152e-03]), + array([ -0.04996966, -11.57490444, 0.02357704])]} +{'AngularVelocity': array([ 2.00989361e-05, -4.61938798e-05, 1.14968661e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.006408886983990669, + 'FR_Wheel_Angle': -0.006408488377928734, + 'Location': array([ -7.50235033, -21.0148735 , 0.17771326]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([2.12053760e-06, 1.24581049e-07, 3.96746735e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.54958534, 22.520998 , -0.75924176]), + 'camera_rotation': array([-8.52234745, 29.10635376, 2.00525308]), + 'current_gear_input': False, + 'focus_actor_dist': 1685.7159423828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 785.66815186, -3321.39916992, 15.94316101]), + 'frame': 34765, + 'frame_number': 34765, + 'framesequence': 133037, + 'gaze_dir': array([0.96718597, 0.2399826 , 0.0819397 ]), + 'gaze_origin': array([-2.96542215, -0.20573579, -0.08022691]), + 'gaze_valid': True, + 'gaze_vergence': 41.58976364135742, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96766663, 0.24298096, 0.06745911]), + 'left_gaze_origin': array([-2.75952601, 2.64147043, -0.11256562]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.58538818359375, + 'left_pupil_posn': array([ 0.48162961, -0.11519575]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96670532, 0.23698425, 0.09642029]), + 'right_gaze_origin': array([-3.17131805, -3.05294204, -0.04788819]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.169586181640625, + 'right_pupil_posn': array([-0.00838685, -0.19890988]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06044496223330498, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1117.8940129764378, + 'timestamp_carla': 1117898, + 'timestamp_device': 4271328, + 'timestamp_stream': 1117.8940129764378, + 'transform': [array([3.30437183e+00, 7.77439451e+00, 5.28951641e-03]), + array([ -0.04872657, -11.45924187, 0.01952945])]} +{'AngularVelocity': array([-3.76549397e-05, 5.37783808e-06, 5.35098843e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17769976]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.68037127e-06, 8.04321019e-08, -1.34518792e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.54958534, 22.520998 , -0.75924176]), + 'camera_rotation': array([-8.52234745, 29.10635376, 2.00525308]), + 'current_gear_input': False, + 'focus_actor_dist': 1658.3353271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 793.87860107, -3291.11767578, 15.93486023]), + 'frame': 34766, + 'frame_number': 34766, + 'framesequence': 133041, + 'gaze_dir': array([0.96481323, 0.2474823 , 0.08709717]), + 'gaze_origin': array([-2.96531773, -0.2047348 , -0.07138901]), + 'gaze_valid': True, + 'gaze_vergence': 6.158191204071045, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9662323 , 0.24778748, 0.07052612]), + 'left_gaze_origin': array([-2.76022673, 2.64219379, -0.10430755]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.479278564453125, + 'left_pupil_posn': array([ 0.4848001 , -0.10739505]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96339417, 0.24717712, 0.10366821]), + 'right_gaze_origin': array([-3.17040873, -3.0516634 , -0.03847046]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.157958984375, + 'right_pupil_posn': array([-0.00746644, -0.19128907]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06727500259876251, + 'throttle_input': 0.0238040741533041, + 'timestamp': 1117.9328160770237, + 'timestamp_carla': 1117937, + 'timestamp_device': 4271362, + 'timestamp_stream': 1117.9328160770237, + 'transform': [array([3.21695042, 7.66195536, 0.00824966]), + array([ -0.04736736, -11.28133965, 0.01376848])]} +{'AngularVelocity': array([ 2.16207154e-05, -1.25169881e-05, 4.10826442e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17769849]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.56442627e-06, 5.03447239e-08, -2.74059566e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.60233688, 22.85335922, -0.75704515]), + 'camera_rotation': array([-8.58292484, 30.12842369, 2.39086914]), + 'current_gear_input': False, + 'focus_actor_dist': 1789.7427978515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 894.48242188, -3387.56811523, 15.83087158]), + 'frame': 34767, + 'frame_number': 34767, + 'framesequence': 133045, + 'gaze_dir': array([0.96515656, 0.24855042, 0.08003235]), + 'gaze_origin': array([-2.9641335 , -0.20170137, -0.0709732 ]), + 'gaze_valid': True, + 'gaze_vergence': 36.950439453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96755981, 0.24446106, 0.06375122]), + 'left_gaze_origin': array([-2.75872827, 2.64611363, -0.10327148]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.531646728515625, + 'left_pupil_posn': array([ 0.48393357, -0.10912013]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9627533 , 0.25263977, 0.09631348]), + 'right_gaze_origin': array([-3.16953921, -3.04951644, -0.03867493]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.165985107421875, + 'right_pupil_posn': array([-0.01020652, -0.19355738]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07637562602758408, + 'throttle_input': 0.0, + 'timestamp': 1117.9609846770763, + 'timestamp_carla': 1117965, + 'timestamp_device': 4271395, + 'timestamp_stream': 1117.9609846770763, + 'transform': [array([3.14673305, 7.58220196, 0.01038196]), + array([-4.63769808e-02, -1.11373920e+01, 9.64027643e-03])]} +{'AngularVelocity': array([ 4.25244343e-06, -1.65559195e-05, 5.82060557e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17770612]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.68919098e-06, 1.01621644e-07, -1.41701588e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.60233688, 22.85335922, -0.75704515]), + 'camera_rotation': array([-8.58292484, 30.12842369, 2.39086914]), + 'current_gear_input': False, + 'focus_actor_dist': 1556.1531982421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 763.18823242, -3203.54394531, 15.96694946]), + 'frame': 34768, + 'frame_number': 34768, + 'framesequence': 133049, + 'gaze_dir': array([0.96582031, 0.24686432, 0.07833099]), + 'gaze_origin': array([-2.96305323, -0.19700317, -0.06906815]), + 'gaze_valid': True, + 'gaze_vergence': 22.854373931884766, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96682739, 0.24595642, 0.0688324 ]), + 'left_gaze_origin': array([-2.75646234, 2.65032363, -0.09823914]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.414947509765625, + 'left_pupil_posn': array([ 0.47912836, -0.10797834]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96481323, 0.24777222, 0.08782959]), + 'right_gaze_origin': array([-3.16964436, -3.04432988, -0.03989716]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0944976806640625, + 'right_pupil_posn': array([-0.01320738, -0.19267046]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08166753500699997, + 'throttle_input': 0.0, + 'timestamp': 1117.9983995780349, + 'timestamp_carla': 1118002, + 'timestamp_device': 4271428, + 'timestamp_stream': 1117.9983995780349, + 'transform': [array([3.04540062, 7.47875452, 0.01312179]), + array([-4.54549082e-02, -1.09283981e+01, 4.32712538e-03])]} +{'AngularVelocity': array([-2.86591367e-05, 5.03544152e-06, 8.36650179e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17770825]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([1.89765819e-06, 7.80133007e-08, 8.82264649e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.65643406, 23.02995682, -0.76892126]), + 'camera_rotation': array([-8.59446716, 30.63822174, 2.465873 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1521.15771484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 739.94787598, -3186.87841797, 15.99094391]), + 'frame': 34769, + 'frame_number': 34769, + 'framesequence': 133053, + 'gaze_dir': array([0.96751404, 0.23954773, 0.07978821]), + 'gaze_origin': array([-2.96086287, -0.18857728, -0.06252442]), + 'gaze_valid': True, + 'gaze_vergence': 80.85102844238281, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96742249, 0.24377441, 0.06819153]), + 'left_gaze_origin': array([-2.75376129, 2.65820312, -0.08891297]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4705810546875, + 'left_pupil_posn': array([ 0.46912038, -0.09979451]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96760559, 0.23532104, 0.09138489]), + 'right_gaze_origin': array([-3.16796422, -3.03535771, -0.03613587]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1552886962890625, + 'right_pupil_posn': array([-0.02010185, -0.18981552]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08811304718255997, + 'throttle_input': 0.0, + 'timestamp': 1118.0276826769114, + 'timestamp_carla': 1118032, + 'timestamp_device': 4271461, + 'timestamp_stream': 1118.0276826769114, + 'transform': [array([2.96098876, 7.39960432, 0.01516803]), + array([-4.50792462e-02, -1.07534161e+01, 3.24853027e-04])]} +{'AngularVelocity': array([-4.29478569e-05, 5.06314473e-06, 1.51527092e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17771639]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([2.41653993e-06, 1.63182520e-07, 6.84795494e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.74202538, 23.13097763, -0.81184578]), + 'camera_rotation': array([-8.81078625, 31.20221901, 3.11535239]), + 'current_gear_input': False, + 'focus_actor_dist': 1539.9827880859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 759.05383301, -3207.69091797, 15.97118378]), + 'frame': 34770, + 'frame_number': 34770, + 'framesequence': 133057, + 'gaze_dir': array([0.96670532, 0.24134064, 0.08371735]), + 'gaze_origin': array([-2.9617126 , -0.19070512, -0.06155625]), + 'gaze_valid': True, + 'gaze_vergence': 88.86913299560547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96629333, 0.24740601, 0.0710144 ]), + 'left_gaze_origin': array([-2.75631738, 2.65523839, -0.09728699]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.394073486328125, + 'left_pupil_posn': array([ 0.47131109, -0.10407996]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96711731, 0.23527527, 0.09642029]), + 'right_gaze_origin': array([-3.16710854, -3.03664875, -0.0258255 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0095367431640625, + 'right_pupil_posn': array([-0.01777792, -0.18161213]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0920865535736084, + 'throttle_input': 0.0, + 'timestamp': 1118.0646429769695, + 'timestamp_carla': 1118069, + 'timestamp_device': 4271495, + 'timestamp_stream': 1118.0646429769695, + 'transform': [array([2.84989977, 7.30173063, 0.01762983]), + array([-4.52295095e-02, -1.05221491e+01, -4.45106253e-03])]} +{'AngularVelocity': array([-3.77726356e-05, 5.02040120e-06, 7.65592722e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17770177]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([1.85198610e-06, 8.26158839e-08, 5.38669156e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.78252125, 23.16189384, -0.824682 ]), + 'camera_rotation': array([-8.92459774, 31.70947266, 4.29989433]), + 'current_gear_input': False, + 'focus_actor_dist': 1490.48193359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 741.8671875 , -3165.14648438, 15.98910522]), + 'frame': 34771, + 'frame_number': 34771, + 'framesequence': 133061, + 'gaze_dir': array([0.96615601, 0.23950958, 0.09475708]), + 'gaze_origin': array([-2.96137547, -0.18841858, -0.05835648]), + 'gaze_valid': True, + 'gaze_vergence': 93.87181091308594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96586609, 0.24554443, 0.08247375]), + 'left_gaze_origin': array([-2.75564289, 2.65724039, -0.0974411 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5208587646484375, + 'left_pupil_posn': array([ 0.4693073 , -0.10055065]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96644592, 0.23347473, 0.10704041]), + 'right_gaze_origin': array([-3.16710854, -3.03407764, -0.01927185]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.011444091796875, + 'right_pupil_posn': array([-0.01984906, -0.17278147]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09902646392583847, + 'throttle_input': 0.0, + 'timestamp': 1118.0943907760084, + 'timestamp_carla': 1118098, + 'timestamp_device': 4271528, + 'timestamp_stream': 1118.0943907760084, + 'transform': [array([2.75653434, 7.22470951, 0.01948207]), + array([-4.54685651e-02, -1.03270006e+01, -8.09628144e-03])]} +{'AngularVelocity': array([ 8.94946788e-05, -3.10699284e-06, 5.06875949e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17768624]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.66506970e-06, -7.21821358e-09, -1.34642323e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.86340237, 23.22884369, -0.87236762]), + 'camera_rotation': array([-9.0706892 , 32.103405 , 4.33999586]), + 'current_gear_input': False, + 'focus_actor_dist': 1572.969970703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 815.12548828, -3221.41455078, 15.91345978]), + 'frame': 34772, + 'frame_number': 34772, + 'framesequence': 133065, + 'gaze_dir': array([0.9654007 , 0.24044037, 0.09963989]), + 'gaze_origin': array([-2.96039891, -0.18433152, -0.05629044]), + 'gaze_valid': True, + 'gaze_vergence': 51.85291290283203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96588135, 0.24485779, 0.08432007]), + 'left_gaze_origin': array([-2.75305486, 2.66275644, -0.09024964]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5076446533203125, + 'left_pupil_posn': array([ 0.46631241, -0.09262371]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96492004, 0.23602295, 0.11495972]), + 'right_gaze_origin': array([-3.16774321, -3.03141952, -0.02233124]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.985443115234375, + 'right_pupil_posn': array([-0.02190328, -0.17429852]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10411694645881653, + 'throttle_input': 0.0, + 'timestamp': 1118.131766475737, + 'timestamp_carla': 1118136, + 'timestamp_device': 4271561, + 'timestamp_stream': 1118.131766475737, + 'transform': [array([2.63378596, 7.13016844, 0.02163274]), + array([ -0.0456803 , -10.0695343 , -0.01227346])]} +{'AngularVelocity': array([ 8.30735371e-05, -3.87866658e-06, 5.76224238e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17770392]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.70473004e-06, 1.68912120e-08, -1.21664627e-04]), + 'brake_input': 0.0, + 'camera_location': array([-8.96175766, 23.32242584, -1.04186976]), + 'camera_rotation': array([-9.38360023, 32.43774033, 4.12885571]), + 'current_gear_input': False, + 'focus_actor_dist': 1620.220458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 862.45733643, -3250.77441406, 15.86462402]), + 'frame': 34773, + 'frame_number': 34773, + 'framesequence': 133069, + 'gaze_dir': array([0.9646759 , 0.24293518, 0.10022736]), + 'gaze_origin': array([-2.96181345, -0.19080354, -0.05614548]), + 'gaze_valid': True, + 'gaze_vergence': 54.7159309387207, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96495056, 0.24879456, 0.08343506]), + 'left_gaze_origin': array([-2.75548267, 2.6557405 , -0.09088135]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5052642822265625, + 'left_pupil_posn': array([ 0.4716202 , -0.09291148]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96440125, 0.23707581, 0.11701965]), + 'right_gaze_origin': array([-3.16814446, -3.03734756, -0.02140961]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.96502685546875, + 'right_pupil_posn': array([-0.01650375, -0.17429292]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11140476912260056, + 'throttle_input': 0.0, + 'timestamp': 1118.1611783765256, + 'timestamp_carla': 1118165, + 'timestamp_device': 4271595, + 'timestamp_stream': 1118.1611783765256, + 'transform': [array([2.53264737, 7.05756569, 0.02316704]), + array([-0.04563932, -9.85669136, -0.01528661])]} +{'AngularVelocity': array([-2.28998088e-05, 1.10275619e-06, 7.69448889e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17772055]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.83347140e-06, 1.27327695e-07, -1.22812153e-05]), + 'brake_input': 0.0, + 'camera_location': array([-8.96175766, 23.32242584, -1.04186976]), + 'camera_rotation': array([-9.38360023, 32.43774033, 4.12885571]), + 'current_gear_input': False, + 'focus_actor_dist': 1535.1094970703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 814.97119141, -3189.45898438, 15.91382599]), + 'frame': 34774, + 'frame_number': 34774, + 'framesequence': 133073, + 'gaze_dir': array([0.96405792, 0.24364471, 0.10519409]), + 'gaze_origin': array([-2.96215916, -0.1944191 , -0.04944153]), + 'gaze_valid': True, + 'gaze_vergence': 112.04981994628906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96389771, 0.24873352, 0.09489441]), + 'left_gaze_origin': array([-2.75561523, 2.65173817, -0.08308411]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5251617431640625, + 'left_pupil_posn': array([ 0.47486508, -0.08838356]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96421814, 0.23855591, 0.11549377]), + 'right_gaze_origin': array([-3.16870284, -3.04057646, -0.01579895]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9496917724609375, + 'right_pupil_posn': array([-0.01421463, -0.16669619]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11810663342475891, + 'throttle_input': 0.0, + 'timestamp': 1118.1983664780855, + 'timestamp_carla': 1118202, + 'timestamp_device': 4271628, + 'timestamp_stream': 1118.1983664780855, + 'transform': [array([2.39916158, 6.9680028 , 0.02499556]), + array([-0.04556419, -9.57496357, -0.01883317])]} +{'AngularVelocity': array([-2.03122618e-05, 2.59654735e-06, 6.66395727e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17770784]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.76570836e-06, 1.41193041e-07, -7.59373143e-05]), + 'brake_input': 0.0, + 'camera_location': array([-9.10285091, 23.39049911, -1.03391361]), + 'camera_rotation': array([-10.07585335, 32.70023346, 4.2586174 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1641.543212890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 898.59606934, -3266.14648438, 15.82736969]), + 'frame': 34775, + 'frame_number': 34775, + 'framesequence': 133077, + 'gaze_dir': array([0.95717621, 0.2689743 , 0.10604858]), + 'gaze_origin': array([-2.96484232, -0.20357515, -0.04586792]), + 'gaze_valid': True, + 'gaze_vergence': 90.59480285644531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95681763, 0.27526855, 0.09333801]), + 'left_gaze_origin': array([-2.75760674, 2.6432817 , -0.07723236]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5080108642578125, + 'left_pupil_posn': array([ 0.48940492, -0.08424664]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95753479, 0.26268005, 0.11875916]), + 'right_gaze_origin': array([-3.17207789, -3.05043197, -0.01450348]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.96405029296875, + 'right_pupil_posn': array([ 0.00213361, -0.16757309]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12748192250728607, + 'throttle_input': 0.0, + 'timestamp': 1118.2268183790147, + 'timestamp_carla': 1118231, + 'timestamp_device': 4271661, + 'timestamp_stream': 1118.2268183790147, + 'transform': [array([2.29202938, 6.90125942, 0.02630465]), + array([-0.04529781, -9.34827137, -0.0213898 ])]} +{'AngularVelocity': array([ 6.98372460e-05, -3.83619681e-06, 9.38327594e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17772062]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.95487405e-06, -6.40478870e-09, 1.25460414e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.10285091, 23.39049911, -1.03391361]), + 'camera_rotation': array([-10.07585335, 32.70023346, 4.2586174 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1404.2186279296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 758.77807617, -3077.88232422, 15.97224426]), + 'frame': 34776, + 'frame_number': 34776, + 'framesequence': 133081, + 'gaze_dir': array([0.94828033, 0.30005646, 0.10256958]), + 'gaze_origin': array([-2.97204065, -0.23485948, -0.04947587]), + 'gaze_valid': True, + 'gaze_vergence': 19.722017288208008, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95025635, 0.2984314 , 0.08908081]), + 'left_gaze_origin': array([-2.76684427, 2.60489821, -0.08609467]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.6917724609375, + 'left_pupil_posn': array([ 0.53082156, -0.09417021]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94630432, 0.30168152, 0.11605835]), + 'right_gaze_origin': array([-3.17723703, -3.07461715, -0.01285706]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.001953125, + 'right_pupil_posn': array([ 0.02696884, -0.16982877]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13445845246315002, + 'throttle_input': 0.0, + 'timestamp': 1118.2652293778956, + 'timestamp_carla': 1118269, + 'timestamp_device': 4271695, + 'timestamp_stream': 1118.2652293778956, + 'transform': [array([2.14005256, 6.8135519 , 0.027892 ]), + array([-0.04488117, -9.02591991, -0.02450037])]} +{'AngularVelocity': array([-1.63792756e-05, 1.73952981e-06, 1.44032606e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17767262]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.37757968e-06, 7.37039016e-08, -4.62815224e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.11934471, 23.50275421, -0.85148937]), + 'camera_rotation': array([-9.17531395, 33.00538254, 4.73807764]), + 'current_gear_input': False, + 'focus_actor_dist': 1337.7353515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 739.79150391, -3005.87182617, 15.99220276]), + 'frame': 34777, + 'frame_number': 34777, + 'framesequence': 133085, + 'gaze_dir': array([0.94459534, 0.31249237, 0.09923553]), + 'gaze_origin': array([-2.97413588, -0.2384987 , -0.0592865 ]), + 'gaze_valid': True, + 'gaze_vergence': 10.231485366821289, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94650269, 0.31137085, 0.08457947]), + 'left_gaze_origin': array([-2.76868606, 2.60185719, -0.09628754]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.657470703125, + 'left_pupil_posn': array([ 0.53752065, -0.10228086]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94268799, 0.31361389, 0.1138916 ]), + 'right_gaze_origin': array([-3.17958546, -3.07885456, -0.02228546]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2363433837890625, + 'right_pupil_posn': array([ 0.03421545, -0.17904341]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14606769382953644, + 'throttle_input': 0.0, + 'timestamp': 1118.2946006767452, + 'timestamp_carla': 1118299, + 'timestamp_device': 4271728, + 'timestamp_stream': 1118.2946006767452, + 'transform': [array([2.01719499, 6.74840307, 0.02901507]), + array([-0.04412985, -8.76482296, -0.02670784])]} +{'AngularVelocity': array([-3.09003954e-05, 3.07832579e-06, 6.89407580e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17771974]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.78199252e-06, 1.32904717e-07, -5.51665107e-05]), + 'brake_input': 0.0, + 'camera_location': array([-9.11948586, 23.50274849, -0.85149461]), + 'camera_rotation': array([-9.17531395, 33.00538254, 4.73807764]), + 'current_gear_input': False, + 'focus_actor_dist': 1486.7926025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 879.62005615, -3082.79663086, 15.84799194]), + 'frame': 34778, + 'frame_number': 34778, + 'framesequence': 133089, + 'gaze_dir': array([0.9442749 , 0.31575775, 0.09230804]), + 'gaze_origin': array([-2.9774096 , -0.24905473, -0.06891785]), + 'gaze_valid': True, + 'gaze_vergence': 7.062145233154297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94526672, 0.31582642, 0.08197021]), + 'left_gaze_origin': array([-2.77117944, 2.59097767, -0.10436707]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5431365966796875, + 'left_pupil_posn': array([ 0.54611695, -0.11186719]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94328308, 0.31568909, 0.10264587]), + 'right_gaze_origin': array([-3.18363976, -3.08908701, -0.03346863]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1275634765625, + 'right_pupil_posn': array([ 0.04285169, -0.18855238]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15458236634731293, + 'throttle_input': 0.0, + 'timestamp': 1118.332318779081, + 'timestamp_carla': 1118336, + 'timestamp_device': 4271761, + 'timestamp_stream': 1118.332318779081, + 'transform': [array([1.85190034, 6.66694307, 0.03037779]), + array([-0.04335804, -8.41287422, -0.02935557])]} +{'AngularVelocity': array([-3.46715206e-05, 6.28636008e-06, 3.81457130e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.1776983 ]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.54645647e-06, 7.56796226e-08, -3.15429701e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.15371323, 23.69930649, -0.81665558]), + 'camera_rotation': array([-8.84039497, 33.13699722, 4.22111416]), + 'current_gear_input': False, + 'focus_actor_dist': 1364.5980224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 789.09289551, -3009.07763672, 15.9414978 ]), + 'frame': 34779, + 'frame_number': 34779, + 'framesequence': 133093, + 'gaze_dir': array([0.94320679, 0.31990051, 0.08929443]), + 'gaze_origin': array([-2.97852349, -0.25349349, -0.07080765]), + 'gaze_valid': True, + 'gaze_vergence': 193.4609832763672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94308472, 0.32157898, 0.08454895]), + 'left_gaze_origin': array([-2.7715776 , 2.58636498, -0.10402375]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.59088134765625, + 'left_pupil_posn': array([ 0.55030131, -0.11471999]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94332886, 0.31822205, 0.09403992]), + 'right_gaze_origin': array([-3.18546939, -3.09335208, -0.03759155]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.196380615234375, + 'right_pupil_posn': array([ 0.04773498, -0.1912564 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1668141782283783, + 'throttle_input': 0.0, + 'timestamp': 1118.3611955791712, + 'timestamp_carla': 1118365, + 'timestamp_device': 4271795, + 'timestamp_stream': 1118.3611955791712, + 'transform': [array([1.71913147, 6.60623503, 0.03136858]), + array([-0.04270234, -8.12973118, -0.03129856])]} +{'AngularVelocity': array([ 6.23286894e-07, -1.84609980e-05, 1.08564318e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17771646]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([2.07294238e-06, 9.50120338e-08, 3.00487678e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.15371323, 23.69930649, -0.81665558]), + 'camera_rotation': array([-8.84039497, 33.13699722, 4.22111416]), + 'current_gear_input': False, + 'focus_actor_dist': 1454.4732666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 872.67700195, -3060.61474609, 15.85527039]), + 'frame': 34780, + 'frame_number': 34780, + 'framesequence': 133097, + 'gaze_dir': array([0.93925476, 0.33000946, 0.09408569]), + 'gaze_origin': array([-2.98046279, -0.25773239, -0.06718674]), + 'gaze_valid': True, + 'gaze_vergence': 95.84833526611328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93948364, 0.33059692, 0.08972168]), + 'left_gaze_origin': array([-2.77378559, 2.5814743 , -0.10048371]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5672149658203125, + 'left_pupil_posn': array([ 0.55806768, -0.11165929]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93902588, 0.329422 , 0.09844971]), + 'right_gaze_origin': array([-3.18713999, -3.09693933, -0.03388977]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1366119384765625, + 'right_pupil_posn': array([ 0.05369496, -0.18735766]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1759331077337265, + 'throttle_input': 0.0, + 'timestamp': 1118.3983558788896, + 'timestamp_carla': 1118403, + 'timestamp_device': 4271828, + 'timestamp_stream': 1118.3983558788896, + 'transform': [array([1.53958094, 6.53015375, 0.03252883]), + array([-0.04189638, -7.74629831, -0.03354843])]} +{'AngularVelocity': array([-2.19382127e-05, 4.15524164e-06, 7.56608915e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17770521]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([1.83644238e-06, 7.66121602e-08, 1.81609139e-05]), + 'brake_input': 0.0, + 'camera_location': array([-9.25580025, 23.91516876, -0.85794955]), + 'camera_rotation': array([-9.05769062, 33.62427521, 4.24001884]), + 'current_gear_input': False, + 'focus_actor_dist': 1542.9022216796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 959.45703125, -3101.56958008, 15.76581573]), + 'frame': 34781, + 'frame_number': 34781, + 'framesequence': 133101, + 'gaze_dir': array([0.93955231, 0.33126068, 0.08614349]), + 'gaze_origin': array([-2.97977614, -0.2588585 , -0.06669617]), + 'gaze_valid': True, + 'gaze_vergence': 253.96437072753906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94204712, 0.32540894, 0.0814209 ]), + 'left_gaze_origin': array([-2.77359009, 2.58091593, -0.09977112]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.709564208984375, + 'left_pupil_posn': array([ 0.56127334, -0.11425006]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9370575 , 0.33711243, 0.09086609]), + 'right_gaze_origin': array([-3.1859622 , -3.09863305, -0.03362122]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1557159423828125, + 'right_pupil_posn': array([ 0.05284357, -0.18973768]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.18735924363136292, + 'throttle_input': 0.0, + 'timestamp': 1118.4268935769796, + 'timestamp_carla': 1118431, + 'timestamp_device': 4271861, + 'timestamp_stream': 1118.4268935769796, + 'transform': [array([1.39541221, 6.4731102 , 0.03331985]), + array([-0.04118604, -7.43804407, -0.03509966])]} +{'AngularVelocity': array([ 1.63186560e-05, -2.09036953e-05, 6.10898360e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17770807]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.69986390e-06, 1.55275472e-08, -1.28694155e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.25580025, 23.91516876, -0.85794955]), + 'camera_rotation': array([-9.05769062, 33.62427521, 4.24001884]), + 'current_gear_input': False, + 'focus_actor_dist': 1337.2025146484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 804.87567139, -2975.10693359, 15.92549133]), + 'frame': 34782, + 'frame_number': 34782, + 'framesequence': 133105, + 'gaze_dir': array([0.93849182, 0.33367157, 0.08848572]), + 'gaze_origin': array([-2.98018122, -0.25931549, -0.06815033]), + 'gaze_valid': True, + 'gaze_vergence': 298.7653503417969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94070435, 0.32847595, 0.08454895]), + 'left_gaze_origin': array([-2.77378559, 2.58052826, -0.10083161]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.74774169921875, + 'left_pupil_posn': array([ 0.56222904, -0.11458254]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9362793 , 0.33886719, 0.09242249]), + 'right_gaze_origin': array([-3.18657684, -3.09915924, -0.03546906]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.188568115234375, + 'right_pupil_posn': array([ 0.05429316, -0.19020259]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.19494004547595978, + 'throttle_input': 0.0, + 'timestamp': 1118.4654916785657, + 'timestamp_carla': 1118470, + 'timestamp_device': 4271895, + 'timestamp_stream': 1118.4654916785657, + 'transform': [array([1.19436491, 6.39729977, 0.03413455]), + array([-0.04095381, -7.00752735, -0.03671994])]} +{'AngularVelocity': array([-3.50953669e-05, 3.47822584e-06, 6.06990079e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.50235033, -21.0148735 , 0.17769861]), + 'Rotation': array([-8.23925659e-02, -4.09530783e+00, 3.14862560e-03]), + 'Velocity': array([ 1.72306318e-06, 8.17995058e-08, -1.04832492e-04]), + 'brake_input': 0.0, + 'camera_location': array([-9.32617664, 24.13379669, -0.82408571]), + 'camera_rotation': array([-8.85708141, 34.26296616, 4.41845512]), + 'current_gear_input': False, + 'focus_actor_dist': 1373.4093017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 842.12121582, -2994.57397461, 15.8870697 ]), + 'frame': 34783, + 'frame_number': 34783, + 'framesequence': 133109, + 'gaze_dir': array([0.93750763, 0.3368988 , 0.08647919]), + 'gaze_origin': array([-2.98059702, -0.2610321 , -0.06756821]), + 'gaze_valid': True, + 'gaze_vergence': 57.77409362792969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93901062, 0.3349762 , 0.07765198]), + 'left_gaze_origin': array([-2.77397013, 2.58033466, -0.10202332]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.7393646240234375, + 'left_pupil_posn': array([ 0.56238949, -0.11442673]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93600464, 0.33882141, 0.0953064 ]), + 'right_gaze_origin': array([-3.18722391, -3.10239887, -0.0331131 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2696533203125, + 'right_pupil_posn': array([ 0.05867457, -0.19152939]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.20440688729286194, + 'throttle_input': 0.0, + 'timestamp': 1118.493859179318, + 'timestamp_carla': 1118498, + 'timestamp_device': 4271928, + 'timestamp_stream': 1118.493859179318, + 'transform': [array([1.04293704, 6.34235096, 0.0344577 ]), + array([-0.04094015, -6.68278694, -0.03737405])]} diff --git a/PythonAPI/data/trials/trial8.txt b/PythonAPI/data/trials/trial8.txt new file mode 100644 index 0000000..84e6293 --- /dev/null +++ b/PythonAPI/data/trials/trial8.txt @@ -0,0 +1,9635 @@ +{'AngularVelocity': array([-3.14443532e-05, 2.05701908e-05, -1.08112756e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.21546435, -31.60477066, 0.17153774]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([5.36402695e-06, 1.50463356e-05, 5.09411853e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.40250397, 12.38743687, 3.77166629]), + 'camera_rotation': array([-6.77999353, 0.48141086, -0.86502284]), + 'current_gear_input': False, + 'focus_actor_dist': 1273.5821533203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -515.16168213, -1930.44592285, 17.29349518]), + 'frame': 10075, + 'frame_number': 10075, + 'framesequence': 38416, + 'gaze_dir': array([0.96271515, 0.27001953, 0.01306915]), + 'gaze_origin': array([-3.12415862, -0.25257799, 0.01488037]), + 'gaze_valid': True, + 'gaze_vergence': 322.56793212890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96025085, 0.27871704, 0.0149231 ]), + 'left_gaze_origin': array([-3.04855061, 2.92589426, 0.02081757]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.12030029296875, + 'left_pupil_posn': array([ 0.30307591, -0.10844028]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96517944, 0.26132202, 0.01121521]), + 'right_gaze_origin': array([-3.19976664, -3.43105006, 0.00894318]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1408843994140625, + 'right_pupil_posn': array([ 0.26549315, -0.18740058]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 330.8771512620151, + 'timestamp_carla': 330877, + 'timestamp_device': 4069090, + 'timestamp_stream': 330.8771512620151, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05339242e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 1.61602857e-05, -2.21664832e-05, -2.16200831e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.21546435, -31.60477066, 0.17152843]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([ 3.15280613e-06, 2.99252188e-05, -1.03823986e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.35785103, 12.38915062, 3.76180077]), + 'camera_rotation': array([-6.77689981, 0.53066891, -1.07503724]), + 'current_gear_input': False, + 'focus_actor_dist': 1253.157958984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -510.57693481, -1950.4309082 , 17.29593658]), + 'frame': 10076, + 'frame_number': 10076, + 'framesequence': 38420, + 'gaze_dir': array([0.96226501, 0.2717514 , 0.01078796]), + 'gaze_origin': array([-3.12376881, -0.25241241, 0.01501007]), + 'gaze_valid': True, + 'gaze_vergence': 399.5275573730469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9602356 , 0.27890015, 0.01191711]), + 'left_gaze_origin': array([-3.04774642, 2.92760324, 0.02133484]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1290740966796875, + 'left_pupil_posn': array([ 0.30302668, -0.10855091]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96429443, 0.26460266, 0.00965881]), + 'right_gaze_origin': array([-3.19979119, -3.43242812, 0.0086853 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1570587158203125, + 'right_pupil_posn': array([ 0.26648033, -0.18870771]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 330.91144766286016, + 'timestamp_carla': 330912, + 'timestamp_device': 4069124, + 'timestamp_stream': 330.91144766286016, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05242729e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 8.71431166e-06, 1.75664027e-05, -2.36632023e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.21546388, -31.60477066, 0.17152686]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([3.31630918e-06, 3.53173527e-05, 3.77782053e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.32060051, 12.40507126, 3.74586153]), + 'camera_rotation': array([-6.70674658, 0.5855847 , -1.15535903]), + 'current_gear_input': False, + 'focus_actor_dist': 1238.3681640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -509.93423462, -1965.59655762, 17.30063629]), + 'frame': 10077, + 'frame_number': 10077, + 'framesequence': 38424, + 'gaze_dir': array([0.9631424 , 0.26873016, 0.00469208]), + 'gaze_origin': array([-3.12231994, -0.25252992, 0.01728287]), + 'gaze_valid': True, + 'gaze_vergence': 270.2486267089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96052551, 0.2780304 , 0.00863647]), + 'left_gaze_origin': array([-3.04487777, 2.92938852, 0.02596436]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0774688720703125, + 'left_pupil_posn': array([ 0.29991412, -0.10776997]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([9.65759277e-01, 2.59429932e-01, 7.47680664e-04]), + 'right_gaze_origin': array([-3.19976211, -3.43444824, 0.00860138]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1663818359375, + 'right_pupil_posn': array([ 0.26754522, -0.18992651]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 330.94530226290226, + 'timestamp_carla': 330946, + 'timestamp_device': 4069157, + 'timestamp_stream': 330.94530226290226, + 'transform': [array([-4.4660446e-01, -1.8417244e+01, 1.0522251e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-2.74666108e-05, 1.00367379e-05, -1.14336621e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.21546412, -31.60476685, 0.17152424]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([4.99687167e-06, 1.53298861e-05, 9.44828149e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.29498863, 12.44995308, 3.69751024]), + 'camera_rotation': array([-6.77592993, 0.71593684, -1.12414551]), + 'current_gear_input': False, + 'focus_actor_dist': 1181.6512451171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -492.91079712, -2020.00317383, 17.30284119]), + 'frame': 10078, + 'frame_number': 10078, + 'framesequence': 38428, + 'gaze_dir': array([0.96424866, 0.2647171 , 0.00735474]), + 'gaze_origin': array([-3.1207993 , -0.25398943, 0.02221985]), + 'gaze_valid': True, + 'gaze_vergence': 365.8340148925781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96224976, 0.27206421, 0.00500488]), + 'left_gaze_origin': array([-3.04346943, 2.93145299, 0.02966461]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0977935791015625, + 'left_pupil_posn': array([ 0.29774106, -0.10187638]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96624756, 0.25737 , 0.00970459]), + 'right_gaze_origin': array([-3.19812942, -3.43943191, 0.01477509]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.185638427734375, + 'right_pupil_posn': array([ 0.26876009, -0.18652868]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 330.97742896154523, + 'timestamp_carla': 330978, + 'timestamp_device': 4069190, + 'timestamp_stream': 330.97742896154523, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05336187e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-1.93600936e-05, -6.06470567e-05, -6.28552458e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.2154634 , -31.60476685, 0.17154609]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([5.28071087e-06, 8.63113928e-06, 2.79182481e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.24582005, 12.50064754, 3.64958453]), + 'camera_rotation': array([-6.84908104, 0.92125237, -1.04161739]), + 'current_gear_input': False, + 'focus_actor_dist': 1189.6231689453125, + 'focus_actor_name': 'Plane38', + 'focus_actor_pt': array([ -492.74551392, -2011.57141113, 17.79415894]), + 'frame': 10079, + 'frame_number': 10079, + 'framesequence': 38432, + 'gaze_dir': array([0.9662323 , 0.2572937 , 0.01065063]), + 'gaze_origin': array([-3.11985326, -0.25243685, 0.02494965]), + 'gaze_valid': True, + 'gaze_vergence': 242.05624389648438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9649353 , 0.26243591, 0.00440979]), + 'left_gaze_origin': array([-3.04291868, 2.93281269, 0.03130951]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1270904541015625, + 'left_pupil_posn': array([ 0.29496038, -0.09803259]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9675293 , 0.25215149, 0.01689148]), + 'right_gaze_origin': array([-3.19678831, -3.43768644, 0.01858978]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.224761962890625, + 'right_pupil_posn': array([ 0.26411366, -0.18340099]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 331.01084976270795, + 'timestamp_carla': 331011, + 'timestamp_device': 4069224, + 'timestamp_stream': 331.01084976270795, + 'transform': [array([-4.4660446e-01, -1.8417244e+01, 1.0530605e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 6.91897139e-06, -2.75249749e-05, -8.10387894e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.21546388, -31.60476685, 0.17154026]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([5.06545393e-06, 1.12493617e-05, 2.23995085e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.22897148, 12.56578064, 3.62756205]), + 'camera_rotation': array([-6.89702892, 1.23733401, -0.87352484]), + 'current_gear_input': False, + 'focus_actor_dist': 1209.6607666015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -493.0098877 , -1990.80187988, 17.29272461]), + 'frame': 10080, + 'frame_number': 10080, + 'framesequence': 38436, + 'gaze_dir': array([0.96942902, 0.24491119, 0.01010132]), + 'gaze_origin': array([-3.11735225, -0.24914552, 0.02689056]), + 'gaze_valid': True, + 'gaze_vergence': 147.1298370361328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96826172, 0.24992371, 0.00109863]), + 'left_gaze_origin': array([-3.04112411, 2.93551636, 0.03229981]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1081085205078125, + 'left_pupil_posn': array([ 0.28875494, -0.09598017]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97059631, 0.23989868, 0.019104 ]), + 'right_gaze_origin': array([-3.19358063, -3.43380761, 0.02148132]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1656036376953125, + 'right_pupil_posn': array([ 0.2566936 , -0.18174732]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 331.04423276335, + 'timestamp_carla': 331044, + 'timestamp_device': 4069257, + 'timestamp_stream': 331.04423276335, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05289267e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 4.11524707e-06, -6.21812287e-05, -1.56801520e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.21546388, -31.60476685, 0.17152824]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([4.16077683e-06, 2.26437660e-05, 1.42114048e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.22029972, 12.6361084 , 3.59762859]), + 'camera_rotation': array([-6.92993021, 1.61178672, -0.74585903]), + 'current_gear_input': True, + 'focus_actor_dist': 1177.957763671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -476.84161377, -2019.51391602, 17.28678894]), + 'frame': 10081, + 'frame_number': 10081, + 'framesequence': 38440, + 'gaze_dir': array([0.96797943, 0.25016022, 0.01838684]), + 'gaze_origin': array([-3.11706877, -0.24562454, 0.03166046]), + 'gaze_valid': True, + 'gaze_vergence': 315.2695007324219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96565247, 0.2592926 , 0.01670837]), + 'left_gaze_origin': array([-3.03990483, 2.93928099, 0.03698273]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1675872802734375, + 'left_pupil_posn': array([ 0.28648615, -0.09235883]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9703064 , 0.24102783, 0.02006531]), + 'right_gaze_origin': array([-3.19423223, -3.43053007, 0.0263382 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17236328125, + 'right_pupil_posn': array([ 0.25787425, -0.17326975]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 331.0780438631773, + 'timestamp_carla': 331078, + 'timestamp_device': 4069290, + 'timestamp_stream': 331.0780438631773, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05246156e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 1.55466751e-05, -1.85116296e-05, -1.14461360e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.2154634 , -31.60476685, 0.17153217]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([ 4.17933779e-06, 1.66299742e-05, -1.63519566e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.23779488, 12.71883011, 3.58189821]), + 'camera_rotation': array([-6.96192265, 2.00757694, -0.71118635]), + 'current_gear_input': False, + 'focus_actor_dist': 1269.028076171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -513.64215088, -1934.48071289, 17.29340363]), + 'frame': 10082, + 'frame_number': 10082, + 'framesequence': 38444, + 'gaze_dir': array([0.97071075, 0.23932648, 0.01976013]), + 'gaze_origin': array([-3.115098 , -0.24104081, 0.03302689]), + 'gaze_valid': True, + 'gaze_vergence': 48.462589263916016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97068787, 0.23989868, 0.01371765]), + 'left_gaze_origin': array([-3.03866911, 2.94399428, 0.03929749]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1391754150390625, + 'left_pupil_posn': array([ 0.28239167, -0.08862114]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97073364, 0.23875427, 0.02580261]), + 'right_gaze_origin': array([-3.19152689, -3.4260757 , 0.02675629]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.13427734375, + 'right_pupil_posn': array([ 0.2476964 , -0.17300415]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 331.11072056367993, + 'timestamp_carla': 331111, + 'timestamp_device': 4069324, + 'timestamp_stream': 331.11072056367993, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05303377e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 2.36540982e-05, 4.45921614e-05, -2.25976529e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020500145852565765, + 'FR_Wheel_Angle': 0.02050458826124668, + 'Location': array([ -2.2154634 , -31.60476685, 0.17152672]), + 'Rotation': array([-1.13859251e-02, 8.87055664e+01, -6.01196289e-02]), + 'Velocity': array([ 3.27099110e-06, 3.37248675e-05, -3.53972500e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.23474026, 12.8211832 , 3.60391641]), + 'camera_rotation': array([-6.91652918, 2.39639616, -0.78106445]), + 'current_gear_input': False, + 'focus_actor_dist': 1271.7357177734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -509.09994507, -1930.46643066, 17.28749847]), + 'frame': 10083, + 'frame_number': 10083, + 'framesequence': 38448, + 'gaze_dir': array([0.97158813, 0.23569489, 0.01977539]), + 'gaze_origin': array([-3.11336541, -0.23517686, 0.03301544]), + 'gaze_valid': True, + 'gaze_vergence': 449.6410827636719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97009277, 0.24198914, 0.01820374]), + 'left_gaze_origin': array([-3.03638029, 2.94864655, 0.03928375]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1526336669921875, + 'left_pupil_posn': array([ 0.27591777, -0.08941603]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9730835 , 0.22940063, 0.02134705]), + 'right_gaze_origin': array([-3.19035053, -3.41900039, 0.02674713]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1541595458984375, + 'right_pupil_posn': array([ 0.24347925, -0.17126 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 331.1440267637372, + 'timestamp_carla': 331144, + 'timestamp_device': 4069357, + 'timestamp_stream': 331.1440267637372, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05290031e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-0.02983685, 0.00097462, -0.76808161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020495843142271042, + 'FR_Wheel_Angle': 0.020498281344771385, + 'Location': array([ -2.21549368, -31.60556412, 0.17152019]), + 'Rotation': array([-1.13517735e-02, 8.87060699e+01, -6.02111816e-02]), + 'Velocity': array([-0.0007245 , -0.01324749, -0.00033372]), + 'brake_input': 0.0, + 'camera_location': array([-7.24748802, 12.89877796, 3.64455819]), + 'camera_rotation': array([-6.89410591, 2.78861618, -0.73007095]), + 'current_gear_input': False, + 'focus_actor_dist': 1284.314208984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -516.06201172, -1919.20043945, 17.29045868]), + 'frame': 10084, + 'frame_number': 10084, + 'framesequence': 38452, + 'gaze_dir': array([0.97921753, 0.20127869, 0.02118683]), + 'gaze_origin': array([-3.07624602, -0.20062181, 0.0267891 ]), + 'gaze_valid': True, + 'gaze_vergence': 38.86458969116211, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97909546, 0.20318604, 0.0088501 ]), + 'left_gaze_origin': array([-2.98433089, 2.98100591, 0.02663727]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0567779541015625, + 'left_pupil_posn': array([ 0.24264693, -0.08310843]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9793396 , 0.19937134, 0.03352356]), + 'right_gaze_origin': array([-3.16816115, -3.38224959, 0.02694092]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16070556640625, + 'right_pupil_posn': array([ 0.20349896, -0.16893244]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 331.177663564682, + 'timestamp_carla': 331178, + 'timestamp_device': 4069390, + 'timestamp_stream': 331.177663564682, + 'transform': [array([-4.46604460e-01, -1.84172440e+01, 1.05256457e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.02695668, -0.00425749, -0.07617401]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020424149930477142, + 'FR_Wheel_Angle': 0.02044142782688141, + 'Location': array([ -2.21522355, -31.58746529, 0.17149097]), + 'Rotation': array([-3.48339626e-03, 8.86984406e+01, -5.99670373e-02]), + 'Velocity': array([0.00540875, 0.19546029, 0.00048092]), + 'brake_input': 0.0, + 'camera_location': array([-7.2775898 , 12.96636295, 3.65389609]), + 'camera_rotation': array([-6.84400606, 3.16995215, -0.53273857]), + 'current_gear_input': False, + 'focus_actor_dist': 1287.5771484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -481.43927002, -1907.16967773, 17.25197601]), + 'frame': 10085, + 'frame_number': 10085, + 'framesequence': 38456, + 'gaze_dir': array([0.98042297, 0.19576263, 0.01756287]), + 'gaze_origin': array([-3.06904244, -0.19871674, 0.02505036]), + 'gaze_valid': True, + 'gaze_vergence': 33.19964599609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98085022, 0.19456482, 0.00700378]), + 'left_gaze_origin': array([-2.97426319, 2.98312402, 0.02373657]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0562896728515625, + 'left_pupil_posn': array([ 0.24020267, -0.08498645]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97999573, 0.19696045, 0.02812195]), + 'right_gaze_origin': array([-3.1638217 , -3.38055754, 0.02636414]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.18280029296875, + 'right_pupil_posn': array([ 0.199121 , -0.16898799]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006408886983990669, + 'throttle_input': 0.0, + 'timestamp': 331.2119163647294, + 'timestamp_carla': 331212, + 'timestamp_device': 4069424, + 'timestamp_stream': 331.2119163647294, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05189318e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.01762324, -0.00341815, 0.02648472]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02032439596951008, + 'FR_Wheel_Angle': 0.020324325188994408, + 'Location': array([ -2.21333933, -31.50918198, 0.17145729]), + 'Rotation': array([ 1.77584914e-03, 8.87041092e+01, -6.00585975e-02]), + 'Velocity': array([ 1.17596183e-02, 4.77056295e-01, -4.33063506e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.25886726, 13.02380657, 3.66963243]), + 'camera_rotation': array([-6.62848663, 3.51528597, -0.39206845]), + 'current_gear_input': False, + 'focus_actor_dist': 1239.6937255859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -471.97622681, -1954.36730957, 17.25914001]), + 'frame': 10086, + 'frame_number': 10086, + 'framesequence': 38460, + 'gaze_dir': array([0.98072052, 0.19419098, 0.01551819]), + 'gaze_origin': array([-3.06643224, -0.19500199, 0.02335358]), + 'gaze_valid': True, + 'gaze_vergence': 45.94291305541992, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98156738, 0.1910553 , 0.00126648]), + 'left_gaze_origin': array([-2.96214151, 2.98549366, 0.01859894]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.09417724609375, + 'left_pupil_posn': array([ 0.23851764, -0.0856545 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97987366, 0.19732666, 0.0297699 ]), + 'right_gaze_origin': array([-3.1707232 , -3.37549734, 0.02810822]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2124481201171875, + 'right_pupil_posn': array([ 0.19457209, -0.17108011]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006408886983990669, + 'throttle_input': 0.0, + 'timestamp': 331.24435806274414, + 'timestamp_carla': 331245, + 'timestamp_device': 4069457, + 'timestamp_stream': 331.24435806274414, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05287358e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.04980204, -0.00124893, 0.08047837]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020222555845975876, + 'FR_Wheel_Angle': 0.020212432369589806, + 'Location': array([ -2.20984626, -31.35544205, 0.17142922]), + 'Rotation': array([ 5.14996238e-03, 8.86874161e+01, -6.01196215e-02]), + 'Velocity': array([ 1.95107330e-02, 8.34578276e-01, -1.20286939e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.20734596, 13.08889198, 3.68356657]), + 'camera_rotation': array([-6.44684458, 3.78130555, -0.4455606 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1254.049560546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -480.74023438, -1941.58898926, 17.2633667 ]), + 'frame': 10087, + 'frame_number': 10087, + 'framesequence': 38464, + 'gaze_dir': array([0.98156738, 0.18995667, 0.01519775]), + 'gaze_origin': array([-3.05623555, -0.1921013 , 0.01903534]), + 'gaze_valid': True, + 'gaze_vergence': 96.30438232421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9828949 , 0.18411255, 0.00274658]), + 'left_gaze_origin': array([-2.95164204, 2.98850107, 0.01433563]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0963287353515625, + 'left_pupil_posn': array([ 0.2357899 , -0.08724844]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98023987, 0.19580078, 0.02764893]), + 'right_gaze_origin': array([-3.16082954, -3.37270379, 0.02373505]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2405242919921875, + 'right_pupil_posn': array([ 0.18986988, -0.1715498 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0006408886983990669, + 'throttle_input': 0.0, + 'timestamp': 331.27851616218686, + 'timestamp_carla': 331279, + 'timestamp_device': 4069490, + 'timestamp_stream': 331.27851616218686, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05215646e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.02595958, -0.00058937, 0.00694893]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020142139866948128, + 'FR_Wheel_Angle': 0.020140228793025017, + 'Location': array([ -2.20480394, -31.14000893, 0.1714513 ]), + 'Rotation': array([ 1.71437743e-03, 8.86894760e+01, -6.01196215e-02]), + 'Velocity': array([2.43000239e-02, 1.04245698e+00, 5.45692419e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.20266247, 13.14101791, 3.67383885]), + 'camera_rotation': array([-6.48113871, 3.98652673, -0.48373836]), + 'current_gear_input': False, + 'focus_actor_dist': 1292.021484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -489.97387695, -1904.50231934, 17.25949097]), + 'frame': 10088, + 'frame_number': 10088, + 'framesequence': 38469, + 'gaze_dir': array([0.98249817, 0.18496704, 0.02069092]), + 'gaze_origin': array([-2.98209310e+00, -1.86502084e-01, 1.60217296e-05]), + 'gaze_valid': True, + 'gaze_vergence': 211.90821838378906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98323059, 0.18174744, 0.01461792]), + 'left_gaze_origin': array([-2.87076592, 2.99667668, -0.00682526]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.169097900390625, + 'left_pupil_posn': array([ 0.2264334 , -0.08657527]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98176575, 0.18818665, 0.02676392]), + 'right_gaze_origin': array([-3.09342051, -3.36968088, 0.0068573 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0831756591796875, + 'right_pupil_posn': array([ 0.18499148, -0.16573322]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004577776708174497, + 'throttle_input': 0.0, + 'timestamp': 331.3119660615921, + 'timestamp_carla': 331312, + 'timestamp_device': 4069532, + 'timestamp_stream': 331.3119660615921, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05230520e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.02517837, -0.00055137, 0.00752794]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020119570195674896, + 'FR_Wheel_Angle': 0.020122366026043892, + 'Location': array([ -2.19990325, -30.93003845, 0.17147656]), + 'Rotation': array([-4.48743394e-03, 8.86909332e+01, -6.01196215e-02]), + 'Velocity': array([2.55056191e-02, 1.09555435e+00, 2.69060140e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.19576073, 13.17084026, 3.6409719 ]), + 'camera_rotation': array([-6.66452265, 4.10439396, -0.44927797]), + 'current_gear_input': False, + 'focus_actor_dist': 1362.464111328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -504.29779053, -1835.10400391, 17.24935913]), + 'frame': 10089, + 'frame_number': 10089, + 'framesequence': 38472, + 'gaze_dir': array([0.9826889 , 0.18358612, 0.02333832]), + 'gaze_origin': array([-2.9961679 , -0.18619232, 0.00626297]), + 'gaze_valid': True, + 'gaze_vergence': 191.84629821777344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98352051, 0.17999268, 0.01660156]), + 'left_gaze_origin': array([-2.89228082e+00, 2.99677134e+00, 1.41906750e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.18304443359375, + 'left_pupil_posn': array([ 0.2263267 , -0.08393526]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9818573 , 0.18717957, 0.03007507]), + 'right_gaze_origin': array([-3.10005498, -3.36915588, 0.01110687]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.152679443359375, + 'right_pupil_posn': array([ 0.184196 , -0.16349339]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.3434194624424, + 'timestamp_carla': 331344, + 'timestamp_device': 4069557, + 'timestamp_stream': 331.3434194624424, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05376625e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.04771318, -0.00107018, -0.00223862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.006285485345870256, + 'FR_Wheel_Angle': -0.006283303257077932, + 'Location': array([ -2.19401288, -30.67852211, 0.17149544]), + 'Rotation': array([-8.51041544e-03, 8.86914062e+01, -6.00891076e-02]), + 'Velocity': array([ 2.64228862e-02, 1.12315750e+00, -1.43184661e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.17246342, 13.18836975, 3.61327887]), + 'camera_rotation': array([-6.75901842, 4.17385197, -0.31654957]), + 'current_gear_input': False, + 'focus_actor_dist': 1352.4215087890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -502.84066772, -1845.11865234, 17.25141907]), + 'frame': 10090, + 'frame_number': 10090, + 'framesequence': 38476, + 'gaze_dir': array([0.98273468, 0.18335724, 0.02353668]), + 'gaze_origin': array([-2.99317193, -0.18602602, 0.00533829]), + 'gaze_valid': True, + 'gaze_vergence': 229.13827514648438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98342896, 0.18034363, 0.0178833 ]), + 'left_gaze_origin': array([-2.89761066e+00, 2.99700189e+00, 2.89611844e-03]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1946563720703125, + 'left_pupil_posn': array([ 0.22594285, -0.08426797]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98204041, 0.18637085, 0.02919006]), + 'right_gaze_origin': array([-3.08873296, -3.36905384, 0.00778046]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1740264892578125, + 'right_pupil_posn': array([ 0.18390894, -0.16315222]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.377226062119, + 'timestamp_carla': 331377, + 'timestamp_device': 4069590, + 'timestamp_stream': 331.377226062119, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05291940e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.05990963, -0.00127346, -0.00244985]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.006274193525314331, + 'FR_Wheel_Angle': -0.006271922029554844, + 'Location': array([ -2.18774486, -30.41193581, 0.17147933]), + 'Rotation': array([-7.23316986e-03, 8.86909485e+01, -6.00891076e-02]), + 'Velocity': array([ 2.85045411e-02, 1.21200967e+00, -1.45912170e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.11987305, 13.19564247, 3.57818627]), + 'camera_rotation': array([-6.84057045, 4.17063046, -0.28918737]), + 'current_gear_input': False, + 'focus_actor_dist': 1324.780517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -497.78027344, -1872.41235352, 17.25598907]), + 'frame': 10091, + 'frame_number': 10091, + 'framesequence': 38480, + 'gaze_dir': array([0.96194458, 0.27160645, 0.02899933]), + 'gaze_origin': array([-3.05529499, -0.25265199, 0.02158737]), + 'gaze_valid': True, + 'gaze_vergence': 557.32861328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96334839, 0.26654053, 0.03001404]), + 'left_gaze_origin': array([-2.95904851, 2.92595673, 0.02127075]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.148895263671875, + 'left_pupil_posn': array([ 0.3064487 , -0.08597577]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96054077, 0.27667236, 0.02798462]), + 'right_gaze_origin': array([-3.15154123, -3.43126106, 0.02190399]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1924591064453125, + 'right_pupil_posn': array([ 0.25945902, -0.16361439]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.4101628623903, + 'timestamp_carla': 331410, + 'timestamp_device': 4069624, + 'timestamp_stream': 331.4101628623903, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05306813e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.05740117, -0.00143887, -0.00266928]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.00625962670892477, + 'FR_Wheel_Angle': -0.0062567428685724735, + 'Location': array([ -2.18092966, -30.12196732, 0.1714627 ]), + 'Rotation': array([-5.40267956e-03, 8.86904907e+01, -6.00891113e-02]), + 'Velocity': array([ 3.13751996e-02, 1.33461738e+00, -2.71863944e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.0788908 , 13.1869297 , 3.55676508]), + 'camera_rotation': array([-7.00967932, 4.19152164, -0.10772966]), + 'current_gear_input': False, + 'focus_actor_dist': 1250.2518310546875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -589.2454834 , -1975.18225098, 32.74559784]), + 'frame': 10092, + 'frame_number': 10092, + 'framesequence': 38484, + 'gaze_dir': array([0.95761871, 0.28634644, 0.02815247]), + 'gaze_origin': array([-3.05662465, -0.25848007, 0.02625275]), + 'gaze_valid': True, + 'gaze_vergence': 194.8639373779297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96063232, 0.27557373, 0.03515625]), + 'left_gaze_origin': array([-2.96039748, 2.91922474, 0.02528992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2351837158203125, + 'left_pupil_posn': array([ 0.31819975, -0.08650243]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9546051 , 0.29711914, 0.02114868]), + 'right_gaze_origin': array([-3.15285206, -3.43618464, 0.02721558]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2879486083984375, + 'right_pupil_posn': array([ 0.26615036, -0.15881145]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.4441663622856, + 'timestamp_carla': 331444, + 'timestamp_device': 4069657, + 'timestamp_stream': 331.4441663622856, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05234720e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.0494576 , -0.00195397, -0.01405248]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.023727187886834145, + 'FR_Wheel_Angle': 0.06866270303726196, + 'Location': array([ -2.17338872, -29.80138206, 0.17145687]), + 'Rotation': array([-4.52158507e-03, 8.86896133e+01, -6.00585975e-02]), + 'Velocity': array([3.47802155e-02, 1.46702147e+00, 1.79853436e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.04227638, 13.17682266, 3.55013013]), + 'camera_rotation': array([-7.10629225, 4.12993193, -0.1523993 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1368.0220947265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -647.28375244, -1871.57421875, 17.40352631]), + 'frame': 10093, + 'frame_number': 10093, + 'framesequence': 38488, + 'gaze_dir': array([0.95868683, 0.28257751, 0.02990723]), + 'gaze_origin': array([-3.05642176, -0.26104736, 0.02728272]), + 'gaze_valid': True, + 'gaze_vergence': 239.13055419921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96200562, 0.27102661, 0.03271484]), + 'left_gaze_origin': array([-2.9599824 , 2.91965961, 0.02672577]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.224884033203125, + 'left_pupil_posn': array([ 0.31689179, -0.0832777 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95536804, 0.29412842, 0.02709961]), + 'right_gaze_origin': array([-3.15286112, -3.44175434, 0.02783966]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2037506103515625, + 'right_pupil_posn': array([ 0.26835847, -0.15914035]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.4775435626507, + 'timestamp_carla': 331478, + 'timestamp_device': 4069690, + 'timestamp_stream': 331.4775435626507, + 'transform': [array([-4.46604133e-01, -1.84172440e+01, 1.05234720e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([0.04837 , 0.03945346, 1.44669271]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.7669851779937744, + 'FR_Wheel_Angle': 3.5685367584228516, + 'Location': array([ -2.16687775, -29.39570808, 0.17145008]), + 'Rotation': array([-4.39864164e-03, 8.88159790e+01, -6.56127781e-02]), + 'Velocity': array([-6.46731304e-03, 1.61226439e+00, -4.94956976e-06]), + 'brake_input': 0.0, + 'camera_location': array([-7.01842022, 13.1695385 , 3.528826 ]), + 'camera_rotation': array([-7.1492815 , 4.07108116, -0.26605931]), + 'current_gear_input': False, + 'focus_actor_dist': 1371.3077392578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -641.8649292 , -1866.12805176, 17.39625549]), + 'frame': 10094, + 'frame_number': 10094, + 'framesequence': 38493, + 'gaze_dir': array([0.95704651, 0.2880249 , 0.03213501]), + 'gaze_origin': array([-3.05706334, -0.26314926, 0.02733688]), + 'gaze_valid': True, + 'gaze_vergence': 358.98974609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95851135, 0.28271484, 0.03617859]), + 'left_gaze_origin': array([-2.95989394, 2.91995549, 0.02765198]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2278289794921875, + 'left_pupil_posn': array([ 0.31639791, -0.08229387]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95558167, 0.29333496, 0.02809143]), + 'right_gaze_origin': array([-3.15423298, -3.44625425, 0.02702179]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.20135498046875, + 'right_pupil_posn': array([ 0.27572799, -0.15918124]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.5153877623379, + 'timestamp_carla': 331516, + 'timestamp_device': 4069732, + 'timestamp_stream': 331.5153877623379, + 'transform': [array([-4.46604609e-01, -1.84172401e+01, 1.04852486e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([0.04893073, 0.02926711, 3.9573133 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.1971235275268555, + 'FR_Wheel_Angle': 8.221487045288086, + 'Location': array([ -2.17408228, -29.06554794, 0.17145748]), + 'Rotation': array([-4.08445299e-03, 8.93770218e+01, -7.34252855e-02]), + 'Velocity': array([-9.44927186e-02, 1.71324205e+00, -7.76672314e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.01300716, 13.15698433, 3.51959324]), + 'camera_rotation': array([-7.16409636, 3.99798441, -0.27712026]), + 'current_gear_input': False, + 'focus_actor_dist': 1407.61376953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -659.90179443, -1833.82507324, 17.40279388]), + 'frame': 10095, + 'frame_number': 10095, + 'framesequence': 38496, + 'gaze_dir': array([0.95571136, 0.29264069, 0.03076935]), + 'gaze_origin': array([-3.05742955, -0.26468277, 0.02792435]), + 'gaze_valid': True, + 'gaze_vergence': 250.43511962890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95582581, 0.29194641, 0.03364563]), + 'left_gaze_origin': array([-2.95980239, 2.91995549, 0.02793427]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2319488525390625, + 'left_pupil_posn': array([ 0.31639791, -0.08217287]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95559692, 0.29333496, 0.02789307]), + 'right_gaze_origin': array([-3.15505672, -3.44932127, 0.02791443]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.232452392578125, + 'right_pupil_posn': array([ 0.28122449, -0.15987849]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.54607586190104, + 'timestamp_carla': 331546, + 'timestamp_device': 4069757, + 'timestamp_stream': 331.54607586190104, + 'transform': [array([-4.46604311e-01, -1.84172401e+01, 1.05204200e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([0.04917947, 0.03572988, 6.3351531 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.382678985595703, + 'FR_Wheel_Angle': 12.068942070007324, + 'Location': array([ -2.20077872, -28.66083145, 0.17151111]), + 'Rotation': array([-2.65694340e-03, 9.05586929e+01, -7.69042745e-02]), + 'Velocity': array([-2.00424477e-01, 1.82507336e+00, 3.11002717e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.01042461, 13.15084362, 3.51670098]), + 'camera_rotation': array([-7.17961454, 3.90529442, -0.29527363]), + 'current_gear_input': False, + 'focus_actor_dist': 1385.562744140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -657.15264893, -1856.34606934, 17.40794373]), + 'frame': 10096, + 'frame_number': 10096, + 'framesequence': 38501, + 'gaze_dir': array([0.95359039, 0.29963684, 0.02830505]), + 'gaze_origin': array([-3.05697799, -0.26390001, 0.02830048]), + 'gaze_valid': True, + 'gaze_vergence': 390.2213439941406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9513092 , 0.30696106, 0.02775574]), + 'left_gaze_origin': array([-2.95959783, 2.91994929, 0.02819367]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.222259521484375, + 'left_pupil_posn': array([ 0.31604767, -0.08158636]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95587158, 0.29231262, 0.02885437]), + 'right_gaze_origin': array([-3.15435791, -3.44774938, 0.02840729]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2280120849609375, + 'right_pupil_posn': array([ 0.28550947, -0.16191435]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.58176006376743, + 'timestamp_carla': 331582, + 'timestamp_device': 4069799, + 'timestamp_stream': 331.58176006376743, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05056567e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([0.04946183, 0.01934628, 8.4795866 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.252424240112305, + 'FR_Wheel_Angle': 13.833025932312012, + 'Location': array([ -2.25211143, -28.22619057, 0.17157799]), + 'Rotation': array([-5.19094348e-04, 9.23169174e+01, -7.94067308e-02]), + 'Velocity': array([-3.24203879e-01, 1.93190992e+00, 6.01510983e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.01470375, 13.13482857, 3.51973844]), + 'camera_rotation': array([-7.22293854, 3.80911565, -0.32394332]), + 'current_gear_input': False, + 'focus_actor_dist': 1349.7308349609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -652.32543945, -1892.85949707, 17.41597748]), + 'frame': 10097, + 'frame_number': 10097, + 'framesequence': 38505, + 'gaze_dir': array([0.95375061, 0.29904175, 0.02921295]), + 'gaze_origin': array([-3.05705571, -0.26506042, 0.02834091]), + 'gaze_valid': True, + 'gaze_vergence': 361.1324157714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95146179, 0.30653381, 0.02719116]), + 'left_gaze_origin': array([-2.9593966 , 2.91957879, 0.02841644]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2229766845703125, + 'left_pupil_posn': array([ 0.31604588, -0.0805366 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95603943, 0.29154968, 0.03123474]), + 'right_gaze_origin': array([-3.15471506, -3.44969964, 0.02826538]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2075653076171875, + 'right_pupil_posn': array([ 0.28673828, -0.16225481]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.61553206294775, + 'timestamp_carla': 331616, + 'timestamp_device': 4069832, + 'timestamp_stream': 331.61553206294775, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05133243e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.04590745, -0.01496365, 8.16212463]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.657303810119629, + 'FR_Wheel_Angle': 11.354235649108887, + 'Location': array([ -2.32503271, -27.76524353, 0.17166495]), + 'Rotation': array([ 2.29494344e-03, 9.42945251e+01, -7.28454664e-02]), + 'Velocity': array([-3.92931461e-01, 2.04654074e+00, 5.90391166e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.0313139 , 13.124259 , 3.51947141]), + 'camera_rotation': array([-7.22984362, 3.77349281, -0.30811831]), + 'current_gear_input': False, + 'focus_actor_dist': 1354.4422607421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -650.98059082, -1887.34338379, 17.41269684]), + 'frame': 10098, + 'frame_number': 10098, + 'framesequence': 38509, + 'gaze_dir': array([0.97439575, 0.21520233, 0.0632019 ]), + 'gaze_origin': array([-3.04208302, -0.21567002, 0.04447861]), + 'gaze_valid': True, + 'gaze_vergence': 200.79898071289062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97128296, 0.22998047, 0.06095886]), + 'left_gaze_origin': array([-2.94141245, 2.97348642, 0.04351959]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2099609375, + 'left_pupil_posn': array([ 0.24739385, -0.05325353]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97750854, 0.20042419, 0.06544495]), + 'right_gaze_origin': array([-3.1427536 , -3.40482664, 0.04543763]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.059417724609375, + 'right_pupil_posn': array([ 0.2281009 , -0.13381422]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.6466389633715, + 'timestamp_carla': 331647, + 'timestamp_device': 4069865, + 'timestamp_stream': 331.6466389633715, + 'transform': [array([-4.46603835e-01, -1.84172401e+01, 1.05359461e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.02432698, -0.02125802, 5.46439266]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.293435096740723, + 'FR_Wheel_Angle': 7.27955436706543, + 'Location': array([ -2.41864872, -27.21443939, 0.17180565]), + 'Rotation': array([ 2.05588690e-03, 9.61121750e+01, -6.11572154e-02]), + 'Velocity': array([-3.87361735e-01, 2.10586262e+00, 7.05308921e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.05455685, 13.12605858, 3.53727198]), + 'camera_rotation': array([-7.17150688, 3.74407816, -0.30929258]), + 'current_gear_input': False, + 'focus_actor_dist': 1221.7645263671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -503.89044189, -1976.61083984, 66.36141968]), + 'frame': 10099, + 'frame_number': 10099, + 'framesequence': 38513, + 'gaze_dir': array([0.97506714, 0.21062469, 0.06876373]), + 'gaze_origin': array([-3.04119873, -0.20311892, 0.05334702]), + 'gaze_valid': True, + 'gaze_vergence': 256.7137145996094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97271729, 0.22215271, 0.06681824]), + 'left_gaze_origin': array([-2.94203353, 2.98368549, 0.05145416]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.186492919921875, + 'left_pupil_posn': array([ 0.24012196, -0.04612207]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97741699, 0.19909668, 0.07070923]), + 'right_gaze_origin': array([-3.14036417, -3.38992333, 0.05523987]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1944427490234375, + 'right_pupil_posn': array([ 0.21493089, -0.1246748 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.68046026304364, + 'timestamp_carla': 331681, + 'timestamp_device': 4069899, + 'timestamp_stream': 331.68046026304364, + 'transform': [array([-4.46603835e-01, -1.84172401e+01, 1.05300713e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.03081825, -0.00302022, 2.55537415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.551755905151367, + 'FR_Wheel_Angle': 3.0784366130828857, + 'Location': array([ -2.49615622, -26.73239708, 0.17192435]), + 'Rotation': array([-1.98758487e-03, 9.70184784e+01, -5.33141941e-02]), + 'Velocity': array([-3.27206075e-01, 2.04111052e+00, 2.26650227e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.07970619, 13.12567329, 3.56609106]), + 'camera_rotation': array([-7.04057932, 3.73243999, -0.30384958]), + 'current_gear_input': False, + 'focus_actor_dist': 1225.3515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -498.63024902, -1971.08886719, 74.02471161]), + 'frame': 10100, + 'frame_number': 10100, + 'framesequence': 38517, + 'gaze_dir': array([0.97510529, 0.2102356 , 0.06948853]), + 'gaze_origin': array([-3.04053664, -0.20378418, 0.05183563]), + 'gaze_valid': True, + 'gaze_vergence': 230.87762451171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97366333, 0.21903992, 0.06304932]), + 'left_gaze_origin': array([-2.94102049, 2.98441768, 0.0492569 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1752166748046875, + 'left_pupil_posn': array([ 0.24041915, -0.0457114 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97654724, 0.20143127, 0.07592773]), + 'right_gaze_origin': array([-3.1400528 , -3.39198637, 0.05441437]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1506195068359375, + 'right_pupil_posn': array([ 0.21525204, -0.12631881]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.7136499620974, + 'timestamp_carla': 331714, + 'timestamp_device': 4069932, + 'timestamp_stream': 331.7136499620974, + 'transform': [array([-4.46603835e-01, -1.84172401e+01, 1.05311396e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.04532364, -0.01890663, -0.05124852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8568025231361389, + 'FR_Wheel_Angle': -1.1999363899230957, + 'Location': array([ -2.55228305, -26.33365822, 0.17200428]), + 'Rotation': array([-2.16516992e-03, 9.72596893e+01, -4.84008752e-02]), + 'Velocity': array([-2.55112141e-01, 2.00494027e+00, 4.46357706e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.10496902, 13.11959457, 3.58316708]), + 'camera_rotation': array([-6.88661289, 3.75163746, -0.27304977]), + 'current_gear_input': False, + 'focus_actor_dist': 1226.897705078125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -498.31195068, -1969.24768066, 77.55026245]), + 'frame': 10101, + 'frame_number': 10101, + 'framesequence': 38521, + 'gaze_dir': array([0.97520447, 0.20974731, 0.06974792]), + 'gaze_origin': array([-3.04026508, -0.20451586, 0.05074997]), + 'gaze_valid': True, + 'gaze_vergence': 217.59445190429688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97412109, 0.21717834, 0.06253052]), + 'left_gaze_origin': array([-2.94082808, 2.98461938, 0.04793396]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17449951171875, + 'left_pupil_posn': array([ 0.24059391, -0.04624867]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97628784, 0.20231628, 0.07696533]), + 'right_gaze_origin': array([-3.13970184, -3.39365077, 0.05356598]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1406707763671875, + 'right_pupil_posn': array([ 0.21572399, -0.12694621]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.7469489648938, + 'timestamp_carla': 331747, + 'timestamp_device': 4069965, + 'timestamp_stream': 331.7469489648938, + 'transform': [array([-4.46603835e-01, -1.84172401e+01, 1.05311396e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.04310486, 0.02036518, -1.50785577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.5502521991729736, + 'FR_Wheel_Angle': -2.7283785343170166, + 'Location': array([ -2.60467625, -25.87323189, 0.17206691]), + 'Rotation': array([-1.24992453e-03, 9.70255814e+01, -4.93774340e-02]), + 'Velocity': array([-2.00079724e-01, 1.98920834e+00, 1.52387613e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.14482021, 13.1107769 , 3.5872426 ]), + 'camera_rotation': array([-6.81883001, 3.76018119, -0.25226617]), + 'current_gear_input': False, + 'focus_actor_dist': 1230.78173828125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -499.12969971, -1965.31164551, 80.75834656]), + 'frame': 10102, + 'frame_number': 10102, + 'framesequence': 38524, + 'gaze_dir': array([0.9754715 , 0.20880127, 0.06889343]), + 'gaze_origin': array([-3.03996444, -0.20491867, 0.05029374]), + 'gaze_valid': True, + 'gaze_vergence': 231.21739196777344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97453308, 0.21542358, 0.06208801]), + 'left_gaze_origin': array([-2.94055033, 2.98474121, 0.04724884]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1604156494140625, + 'left_pupil_posn': array([ 0.2404654 , -0.04704022]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97640991, 0.20217896, 0.07569885]), + 'right_gaze_origin': array([-3.13937855, -3.3945787 , 0.05333862]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.140289306640625, + 'right_pupil_posn': array([ 0.21572399, -0.12716627]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.77852956205606, + 'timestamp_carla': 331779, + 'timestamp_device': 4069990, + 'timestamp_stream': 331.77852956205606, + 'transform': [array([-4.46603686e-01, -1.84172401e+01, 1.05422782e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.04847599, -0.01697708, -3.19361663]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.000822067260742, + 'FR_Wheel_Angle': -5.173214435577393, + 'Location': array([ -2.65296865, -25.34296989, 0.1721344 ]), + 'Rotation': array([-7.92301900e-04, 9.64110413e+01, -4.84924316e-02]), + 'Velocity': array([-1.30191192e-01, 1.99207258e+00, -1.18713375e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.16164684, 13.0989666 , 3.58937263]), + 'camera_rotation': array([-6.77997303, 3.74057937, -0.29275376]), + 'current_gear_input': False, + 'focus_actor_dist': 1227.2646484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -497.30053711, -1968.49780273, 81.16239929]), + 'frame': 10103, + 'frame_number': 10103, + 'framesequence': 38529, + 'gaze_dir': array([0.9757309 , 0.20797729, 0.06786346]), + 'gaze_origin': array([-3.03975296, -0.20516436, 0.05017548]), + 'gaze_valid': True, + 'gaze_vergence': 277.3246154785156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97480774, 0.21412659, 0.06222534]), + 'left_gaze_origin': array([-2.94032764, 2.98492599, 0.04722138]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.157012939453125, + 'left_pupil_posn': array([ 0.24020481, -0.04775095]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97665405, 0.201828 , 0.07350159]), + 'right_gaze_origin': array([-3.13917851, -3.39525461, 0.05312958]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.141754150390625, + 'right_pupil_posn': array([ 0.21572423, -0.12720907]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.8126646615565, + 'timestamp_carla': 331813, + 'timestamp_device': 4070032, + 'timestamp_stream': 331.8126646615565, + 'transform': [array([-4.46603835e-01, -1.84172401e+01, 1.05296895e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 4.23800275e-02, -2.50389613e-03, -4.60346413e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.142195224761963, + 'FR_Wheel_Angle': -6.866748809814453, + 'Location': array([ -2.67890382, -24.88747215, 0.17222363]), + 'Rotation': array([ 6.14716992e-05, 9.54888077e+01, -4.66613770e-02]), + 'Velocity': array([-5.79850152e-02, 2.01615930e+00, 4.67534061e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.2043457 , 13.08639145, 3.60573483]), + 'camera_rotation': array([-6.70464325, 3.7245779 , -0.3402701 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1228.403076171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -496.10955811, -1967.05053711, 80.80362701]), + 'frame': 10104, + 'frame_number': 10104, + 'framesequence': 38533, + 'gaze_dir': array([0.97583008, 0.20783234, 0.06695557]), + 'gaze_origin': array([-3.03905559, -0.20534213, 0.04995117]), + 'gaze_valid': True, + 'gaze_vergence': 330.4096374511719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97486877, 0.21380615, 0.06239319]), + 'left_gaze_origin': array([-2.93960452, 2.98492599, 0.04702454]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15234375, + 'left_pupil_posn': array([ 0.24020481, -0.0484184 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97679138, 0.20185852, 0.07151794]), + 'right_gaze_origin': array([-3.13850713, -3.39561033, 0.05287781]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.155426025390625, + 'right_pupil_posn': array([ 0.2158246 , -0.12721896]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.84610096365213, + 'timestamp_carla': 331846, + 'timestamp_device': 4070065, + 'timestamp_stream': 331.84610096365213, + 'transform': [array([-4.46603835e-01, -1.84172401e+01, 1.05276676e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.04062763, -0.02239355, -5.78831482]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.34852409362793, + 'FR_Wheel_Angle': -8.899948120117188, + 'Location': array([ -2.68976092, -24.48703957, 0.17226875]), + 'Rotation': array([ 2.59547174e-04, 9.44635773e+01, -4.55932580e-02]), + 'Velocity': array([1.03164678e-02, 2.04005742e+00, 5.91373428e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.23056889, 13.07952881, 3.62436771]), + 'camera_rotation': array([-6.61651993, 3.67198086, -0.37885436]), + 'current_gear_input': False, + 'focus_actor_dist': 1229.09375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -495.69833374, -1966.24597168, 81.44711304]), + 'frame': 10105, + 'frame_number': 10105, + 'framesequence': 38537, + 'gaze_dir': array([0.97576141, 0.2088089 , 0.06486511]), + 'gaze_origin': array([-3.0387888 , -0.20555726, 0.04966278]), + 'gaze_valid': True, + 'gaze_vergence': 304.58831787109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97463989, 0.21556091, 0.06001282]), + 'left_gaze_origin': array([-2.93916631, 2.98490477, 0.04681244]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1528472900390625, + 'left_pupil_posn': array([ 0.24027157, -0.04908216]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97688293, 0.20205688, 0.06971741]), + 'right_gaze_origin': array([-3.13841105, -3.39601898, 0.05251312]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2038116455078125, + 'right_pupil_posn': array([ 0.21667635, -0.12841487]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.88060096278787, + 'timestamp_carla': 331881, + 'timestamp_device': 4070099, + 'timestamp_stream': 331.88060096278787, + 'transform': [array([-4.46603835e-01, -1.84172401e+01, 1.05181690e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.03557612, -0.0223926 , -7.49621677]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.815521240234375, + 'FR_Wheel_Angle': -10.850199699401855, + 'Location': array([ -2.68407106, -24.01499367, 0.17231365]), + 'Rotation': array([-3.34679266e-04, 9.29123154e+01, -4.25415039e-02]), + 'Velocity': array([1.14196539e-01, 2.06572342e+00, 7.46726982e-06]), + 'brake_input': 0.0, + 'camera_location': array([-7.25429821, 13.07058907, 3.63056755]), + 'camera_rotation': array([-6.53837585, 3.61685395, -0.36190975]), + 'current_gear_input': False, + 'focus_actor_dist': 1228.9844970703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -495.72531128, -1966.41845703, 80.94877625]), + 'frame': 10106, + 'frame_number': 10106, + 'framesequence': 38540, + 'gaze_dir': array([0.97534943, 0.21092224, 0.0641098 ]), + 'gaze_origin': array([-3.03861403, -0.20623018, 0.04886628]), + 'gaze_valid': True, + 'gaze_vergence': 356.4587097167969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97399902, 0.21813965, 0.06089783]), + 'left_gaze_origin': array([-2.93883061, 2.98435378, 0.0463089 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1607208251953125, + 'left_pupil_posn': array([ 0.24119079, -0.05021381]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97669983, 0.20370483, 0.06732178]), + 'right_gaze_origin': array([-3.13839722, -3.39681387, 0.05142365]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2212066650390625, + 'right_pupil_posn': array([ 0.21812594, -0.12893116]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.912310462445, + 'timestamp_carla': 331913, + 'timestamp_device': 4070124, + 'timestamp_stream': 331.912310462445, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05330851e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.03245375, -0.02062174, -8.82189274]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.639825820922852, + 'FR_Wheel_Angle': -12.228277206420898, + 'Location': array([ -2.6560216 , -23.53582382, 0.1723513 ]), + 'Rotation': array([-1.12698111e-03, 9.10060196e+01, -4.15344201e-02]), + 'Velocity': array([2.21545622e-01, 2.08750415e+00, 4.44393139e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.28363609, 13.06123638, 3.63971138]), + 'camera_rotation': array([-6.43948841, 3.56889009, -0.30526552]), + 'current_gear_input': False, + 'focus_actor_dist': 1227.676025390625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -496.85247803, -1968.05090332, 81.72431946]), + 'frame': 10107, + 'frame_number': 10107, + 'framesequence': 38545, + 'gaze_dir': array([0.97550964, 0.21089172, 0.06190491]), + 'gaze_origin': array([-3.03858352, -0.20669785, 0.04851532]), + 'gaze_valid': True, + 'gaze_vergence': 406.2723388671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97410583, 0.21794128, 0.06007385]), + 'left_gaze_origin': array([-2.93875289, 2.98392057, 0.04620209]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1764984130859375, + 'left_pupil_posn': array([ 0.24150288, -0.05154371]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97691345, 0.20384216, 0.06373596]), + 'right_gaze_origin': array([-3.13841391, -3.39731622, 0.05082855]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.23272705078125, + 'right_pupil_posn': array([ 0.21838617, -0.12965298]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.94659846276045, + 'timestamp_carla': 331947, + 'timestamp_device': 4070165, + 'timestamp_stream': 331.94659846276045, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05228992e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.03191229, -0.02207342, -9.8086338 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.898385047912598, + 'FR_Wheel_Angle': -13.218692779541016, + 'Location': array([ -2.60450244, -23.0499649 , 0.1723471 ]), + 'Rotation': array([-2.07637739e-03, 8.88277512e+01, -4.15649302e-02]), + 'Velocity': array([ 3.29306513e-01, 2.10820055e+00, -2.64663686e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.28678703, 13.0492115 , 3.65348697]), + 'camera_rotation': array([-6.37451935, 3.53138113, -0.40769279]), + 'current_gear_input': False, + 'focus_actor_dist': 1228.5235595703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -496.11495972, -1967.06152344, 80.79304504]), + 'frame': 10108, + 'frame_number': 10108, + 'framesequence': 38549, + 'gaze_dir': array([0.9756012 , 0.21076965, 0.0608902 ]), + 'gaze_origin': array([-3.03877878, -0.20732118, 0.04790802]), + 'gaze_valid': True, + 'gaze_vergence': 378.8369445800781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97416687, 0.21809387, 0.05851746]), + 'left_gaze_origin': array([-2.93873453, 2.98337722, 0.04530792]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2322540283203125, + 'left_pupil_posn': array([ 0.2416836 , -0.05238307]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97703552, 0.20344543, 0.06326294]), + 'right_gaze_origin': array([-3.13882303, -3.39801955, 0.05050812]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2237091064453125, + 'right_pupil_posn': array([ 0.21892941, -0.1304642 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 331.97953106462955, + 'timestamp_carla': 331980, + 'timestamp_device': 4070199, + 'timestamp_stream': 331.97953106462955, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05274003e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 0.02095411, -0.04457955, -10.89874744]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.37030029296875, + 'FR_Wheel_Angle': -14.392170906066895, + 'Location': array([ -2.52864981, -22.56389427, 0.17233817]), + 'Rotation': array([-3.51071707e-03, 8.64348297e+01, -3.99169922e-02]), + 'Velocity': array([ 4.50012743e-01, 2.11760664e+00, -3.37810518e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.30491447, 13.04069805, 3.66731691]), + 'camera_rotation': array([-6.38150692, 3.51317406, -0.33333069]), + 'current_gear_input': False, + 'focus_actor_dist': 1229.626220703125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -495.32275391, -1965.70031738, 81.31661224]), + 'frame': 10109, + 'frame_number': 10109, + 'framesequence': 38553, + 'gaze_dir': array([0.97576141, 0.2104187 , 0.05957031]), + 'gaze_origin': array([-3.03923893, -0.20772554, 0.04677048]), + 'gaze_valid': True, + 'gaze_vergence': 424.757568359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97419739, 0.21748352, 0.06016541]), + 'left_gaze_origin': array([-2.93875122, 2.98333287, 0.04506988]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2350921630859375, + 'left_pupil_posn': array([ 0.24165738, -0.05401409]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97732544, 0.20335388, 0.05897522]), + 'right_gaze_origin': array([-3.1397264 , -3.39878392, 0.04847107]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.217437744140625, + 'right_pupil_posn': array([ 0.21928442, -0.13144588]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.0127273648977, + 'timestamp_carla': 332013, + 'timestamp_device': 4070232, + 'timestamp_stream': 332.0127273648977, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05274003e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ -0.0139763 , -0.05805309, -12.81299496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.571369171142578, + 'FR_Wheel_Angle': -17.006345748901367, + 'Location': array([ -2.42378426, -22.07722664, 0.17222732]), + 'Rotation': array([-9.91743430e-03, 8.37221680e+01, -3.22570764e-02]), + 'Velocity': array([ 6.05925143e-01, 2.10506797e+00, -8.01081653e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.31592751, 13.03104305, 3.66343379]), + 'camera_rotation': array([-6.39175224, 3.50335336, -0.39949459]), + 'current_gear_input': False, + 'focus_actor_dist': 1229.567138671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -494.60028076, -1965.69995117, 79.21547699]), + 'frame': 10110, + 'frame_number': 10110, + 'framesequence': 38556, + 'gaze_dir': array([0.97598267, 0.20989227, 0.05767059]), + 'gaze_origin': array([-3.03913832, -0.20808564, 0.04581833]), + 'gaze_valid': True, + 'gaze_vergence': 419.1325378417969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97451782, 0.2170105 , 0.05665588]), + 'left_gaze_origin': array([-2.93852234, 2.98335123, 0.04346009]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2398834228515625, + 'left_pupil_posn': array([ 0.24144137, -0.05513978]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97744751, 0.20277405, 0.0586853 ]), + 'right_gaze_origin': array([-3.13975406, -3.39952254, 0.04817658]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1806793212890625, + 'right_pupil_posn': array([ 0.21962833, -0.13280487]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.0446632616222, + 'timestamp_carla': 332045, + 'timestamp_device': 4070257, + 'timestamp_stream': 332.0446632616222, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05364416e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ -0.03360429, -0.01996784, -14.91378689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.607643127441406, + 'FR_Wheel_Angle': -19.655349731445312, + 'Location': array([ -2.28192091, -21.60263824, 0.17207146]), + 'Rotation': array([-2.34958492e-02, 8.04456253e+01, -2.74658203e-02]), + 'Velocity': array([ 7.63813078e-01, 1.94572699e+00, -1.01192470e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.33361435, 13.01416969, 3.64480162]), + 'camera_rotation': array([-6.41541195, 3.48899031, -0.48552513]), + 'current_gear_input': False, + 'focus_actor_dist': 1228.937255859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -493.5201416 , -1966.20166016, 76.96628571]), + 'frame': 10111, + 'frame_number': 10111, + 'framesequence': 38560, + 'gaze_dir': array([0.97592163, 0.21022034, 0.05754852]), + 'gaze_origin': array([-3.03906035, -0.2081154 , 0.04552994]), + 'gaze_valid': True, + 'gaze_vergence': 440.3199157714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97451782, 0.21699524, 0.05657959]), + 'left_gaze_origin': array([-2.93836689, 2.98337722, 0.04335633]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22271728515625, + 'left_pupil_posn': array([ 0.24165738, -0.05524373]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97732544, 0.20344543, 0.05851746]), + 'right_gaze_origin': array([-3.13975406, -3.3996079 , 0.04770356]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16192626953125, + 'right_pupil_posn': array([ 0.21969271, -0.13310206]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.07730666175485, + 'timestamp_carla': 332078, + 'timestamp_device': 4070290, + 'timestamp_stream': 332.07730666175485, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05364416e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 4.42428136e-04, -3.19983661e-02, -1.53230438e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.067768096923828, + 'FR_Wheel_Angle': -21.38555908203125, + 'Location': array([ -2.11170936, -21.1701355 , 0.17187598]), + 'Rotation': array([-3.52779254e-02, 7.68779144e+01, -3.12194731e-02]), + 'Velocity': array([ 8.55512500e-01, 1.72930110e+00, -8.36496358e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.34083557, 12.99873543, 3.63532543]), + 'camera_rotation': array([-6.41071272, 3.4096055 , -0.47270551]), + 'current_gear_input': False, + 'focus_actor_dist': 1228.868896484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -493.48083496, -1966.29699707, 76.70413208]), + 'frame': 10112, + 'frame_number': 10112, + 'framesequence': 38564, + 'gaze_dir': array([0.98309326, 0.17479706, 0.05151367]), + 'gaze_origin': array([-3.05862379, -0.17992096, 0.05185699]), + 'gaze_valid': True, + 'gaze_vergence': 178.8387451171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98023987, 0.19163513, 0.04876709]), + 'left_gaze_origin': array([-2.96800542, 3.01382613, 0.05252839]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.173248291015625, + 'left_pupil_posn': array([ 0.20578563, -0.05511296]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98594666, 0.15795898, 0.05426025]), + 'right_gaze_origin': array([-3.14924192, -3.37366796, 0.05118561]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1469268798828125, + 'right_pupil_posn': array([ 0.19319522, -0.13443148]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.10939126461744, + 'timestamp_carla': 332110, + 'timestamp_device': 4070324, + 'timestamp_stream': 332.10939126461744, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05398744e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ -0.02612445, -0.01967474, -16.20201302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.002290725708008, + 'FR_Wheel_Angle': -23.911779403686523, + 'Location': array([ -1.89641023, -20.74188232, 0.17166641]), + 'Rotation': array([-4.31804545e-02, 7.27143784e+01, -2.87170392e-02]), + 'Velocity': array([ 9.63504910e-01, 1.49314117e+00, -9.99751035e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.34295368, 12.9845686 , 3.62079835]), + 'camera_rotation': array([-6.43885326, 3.32953835, -0.54460168]), + 'current_gear_input': False, + 'focus_actor_dist': 1295.1622314453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -462.72055054, -1891.57580566, 64.19061279]), + 'frame': 10113, + 'frame_number': 10113, + 'framesequence': 38568, + 'gaze_dir': array([0.9881134 , 0.14398956, 0.05270386]), + 'gaze_origin': array([-3.02164841, -0.14597856, 0.03906327]), + 'gaze_valid': True, + 'gaze_vergence': 303.4130859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98674011, 0.15402222, 0.05111694]), + 'left_gaze_origin': array([-2.93401814, 3.04353046, 0.03963623]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1635284423828125, + 'left_pupil_posn': array([ 0.1771549 , -0.05701602]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98948669, 0.13395691, 0.05429077]), + 'right_gaze_origin': array([-3.10927916, -3.33548737, 0.0384903 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1385040283203125, + 'right_pupil_posn': array([ 0.1526618 , -0.13378465]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.1420758627355, + 'timestamp_carla': 332142, + 'timestamp_device': 4070357, + 'timestamp_stream': 332.1420758627355, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05371661e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ -0.02256174, 0.03927397, -16.2201767 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.36210632324219, + 'FR_Wheel_Angle': -25.236698150634766, + 'Location': array([ -1.72693825, -20.47105408, 0.17149295]), + 'Rotation': array([-4.90066037e-02, 6.96426392e+01, -3.03344652e-02]), + 'Velocity': array([ 1.00658929e+00, 1.33039320e+00, -1.16595265e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.32309723, 12.9598217 , 3.59388089]), + 'camera_rotation': array([-6.49975777, 3.24662089, -0.59687692]), + 'current_gear_input': False, + 'focus_actor_dist': 2120.849365234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -568.63256836, -1072.23510742, 17.08512878]), + 'frame': 10114, + 'frame_number': 10114, + 'framesequence': 38572, + 'gaze_dir': array([0.98840332, 0.14332581, 0.04862976]), + 'gaze_origin': array([-3.02921247, -0.14780045, 0.04176865]), + 'gaze_valid': True, + 'gaze_vergence': 248.98779296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98661804, 0.15426636, 0.05271912]), + 'left_gaze_origin': array([-2.94780898, 3.04193592, 0.04434052]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17669677734375, + 'left_pupil_posn': array([ 0.17778134, -0.05976093]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9901886 , 0.13238525, 0.04454041]), + 'right_gaze_origin': array([-3.11061573, -3.33753681, 0.03919678]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1367950439453125, + 'right_pupil_posn': array([ 0.15416217, -0.13316202]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.1774065643549, + 'timestamp_carla': 332178, + 'timestamp_device': 4070390, + 'timestamp_stream': 332.1774065643549, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05142780e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-1.10102352e-02, 3.07246912e-02, -1.50269756e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.17543411254883, + 'FR_Wheel_Angle': -25.63754653930664, + 'Location': array([ -1.48201871, -20.1390934 , 0.17122795]), + 'Rotation': array([-5.66700771e-02, 6.54726334e+01, -3.67431678e-02]), + 'Velocity': array([ 0.99997884, 1.11389303, -0.00115063]), + 'brake_input': 0.0, + 'camera_location': array([-7.30653667, 12.91858101, 3.59992433]), + 'camera_rotation': array([-6.55551958, 3.10854673, -0.58991414]), + 'current_gear_input': False, + 'focus_actor_dist': 1949.1944580078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -533.88439941, -1240.69104004, 17.09302521]), + 'frame': 10115, + 'frame_number': 10115, + 'framesequence': 38576, + 'gaze_dir': array([0.98842621, 0.14356995, 0.04730225]), + 'gaze_origin': array([-3.0331192 , -0.14850083, 0.04328308]), + 'gaze_valid': True, + 'gaze_vergence': 260.0484619140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98664856, 0.15496826, 0.04978943]), + 'left_gaze_origin': array([-2.95184183, 3.04164767, 0.04546204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1877593994140625, + 'left_pupil_posn': array([ 0.17793179, -0.05969739]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99020386, 0.13217163, 0.04481506]), + 'right_gaze_origin': array([-3.11439681, -3.33864903, 0.04110413]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1933441162109375, + 'right_pupil_posn': array([ 0.1552397 , -0.13366711]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.21007416397333, + 'timestamp_carla': 332210, + 'timestamp_device': 4070424, + 'timestamp_stream': 332.21007416397333, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05225565e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ -0.0184315 , -0.01428859, -13.96114159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.26002502441406, + 'FR_Wheel_Angle': -25.685972213745117, + 'Location': array([ -1.28882754, -19.91096497, 0.17099029]), + 'Rotation': array([-6.02149442e-02, 6.24143524e+01, -3.86352502e-02]), + 'Velocity': array([ 0.97371268, 0.96954936, -0.00151183]), + 'brake_input': 0.0, + 'camera_location': array([-7.28155231, 12.88268375, 3.61559224]), + 'camera_rotation': array([-6.6113224 , 2.95557117, -0.66633493]), + 'current_gear_input': False, + 'focus_actor_dist': 1879.6734619140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -517.62158203, -1308.54418945, 17.09384918]), + 'frame': 10116, + 'frame_number': 10116, + 'framesequence': 38580, + 'gaze_dir': array([0.98865509, 0.14381409, 0.04106903]), + 'gaze_origin': array([-3.06453657, -0.15218964, 0.05288773]), + 'gaze_valid': True, + 'gaze_vergence': 236.48486328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98706055, 0.15586853, 0.03729248]), + 'left_gaze_origin': array([-2.95281839, 3.04104638, 0.04570923]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1952056884765625, + 'left_pupil_posn': array([ 0.17821002, -0.05969739]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99024963, 0.13175964, 0.04484558]), + 'right_gaze_origin': array([-3.17625451, -3.34542537, 0.06006623]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2064056396484375, + 'right_pupil_posn': array([ 0.16187954, -0.13697314]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.2439600639045, + 'timestamp_carla': 332244, + 'timestamp_device': 4070457, + 'timestamp_stream': 332.2439600639045, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05186272e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-1.24994060e-02, -3.61869275e-03, -1.24038582e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.22041320800781, + 'FR_Wheel_Angle': -25.656204223632812, + 'Location': array([ -1.0513711 , -19.6615715 , 0.17073604]), + 'Rotation': array([-6.27216250e-02, 5.88870468e+01, -3.71398926e-02]), + 'Velocity': array([ 0.92349815, 0.81410742, -0.00100804]), + 'brake_input': 0.0, + 'camera_location': array([-7.25384617, 12.84537697, 3.61005187]), + 'camera_rotation': array([-6.67303991, 2.84258723, -0.72507197]), + 'current_gear_input': False, + 'focus_actor_dist': 1695.8260498046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -481.50219727, -1489.30297852, 17.10575104]), + 'frame': 10117, + 'frame_number': 10117, + 'framesequence': 38584, + 'gaze_dir': array([0.98825836, 0.14478302, 0.04589081]), + 'gaze_origin': array([-3.06314874, -0.16318665, 0.04807663]), + 'gaze_valid': True, + 'gaze_vergence': 171.80181884765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98651123, 0.15911865, 0.03834534]), + 'left_gaze_origin': array([-2.96302652, 3.02989817, 0.04508057]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1347808837890625, + 'left_pupil_posn': array([ 0.18546093, -0.05891371]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99000549, 0.13044739, 0.05343628]), + 'right_gaze_origin': array([-3.16327071, -3.35627151, 0.05107269]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1517791748046875, + 'right_pupil_posn': array([ 0.17008471, -0.140342 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.2768068648875, + 'timestamp_carla': 332277, + 'timestamp_device': 4070490, + 'timestamp_stream': 332.2768068648875, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05244257e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-7.55853252e-03, 2.62691127e-03, -1.13575182e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.01239013671875, + 'FR_Wheel_Angle': -25.497535705566406, + 'Location': array([ -0.88568366, -19.5044136 , 0.17052059]), + 'Rotation': array([-6.43608719e-02, 5.65544090e+01, -3.56750488e-02]), + 'Velocity': array([ 0.88137281, 0.71787548, -0.00107209]), + 'brake_input': 0.0, + 'camera_location': array([-7.23157215, 12.83262825, 3.56296587]), + 'camera_rotation': array([-6.79860592, 2.834723 , -0.68807584]), + 'current_gear_input': False, + 'focus_actor_dist': 1794.61376953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -496.53057861, -1391.3828125 , 17.09366608]), + 'frame': 10118, + 'frame_number': 10118, + 'framesequence': 38588, + 'gaze_dir': array([0.96801758, 0.24798584, 0.03243256]), + 'gaze_origin': array([-3.06493759, -0.24323198, 0.02706528]), + 'gaze_valid': True, + 'gaze_vergence': 158.00851440429688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96322632, 0.26635742, 0.03497314]), + 'left_gaze_origin': array([-2.9634583 , 2.93981957, 0.02492676]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.272674560546875, + 'left_pupil_posn': array([ 0.28051329, -0.08277988]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97280884, 0.22961426, 0.02989197]), + 'right_gaze_origin': array([-3.16641712, -3.4262836 , 0.0292038 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2483978271484375, + 'right_pupil_posn': array([ 0.25638783, -0.15998673]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0004028443363495171, + 'throttle_input': 0.0, + 'timestamp': 332.3101237639785, + 'timestamp_carla': 332310, + 'timestamp_device': 4070524, + 'timestamp_stream': 332.3101237639785, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05244257e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-7.81017682e-03, 1.03798939e-03, -1.01427460e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.954429626464844, + 'FR_Wheel_Angle': -25.496929168701172, + 'Location': array([ -0.67008758, -19.31738663, 0.17025974]), + 'Rotation': array([-6.62869811e-02, 5.36562576e+01, -3.31726037e-02]), + 'Velocity': array([ 0.82137132, 0.60351259, -0.0011533 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.22750473, 12.82592201, 3.51355052]), + 'camera_rotation': array([-6.95110369, 2.92234564, -0.72057623]), + 'current_gear_input': False, + 'focus_actor_dist': 1229.818603515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -526.1854248 , -1976.55493164, 40.5071106 ]), + 'frame': 10119, + 'frame_number': 10119, + 'framesequence': 38592, + 'gaze_dir': array([0.96393585, 0.26461792, 0.02800751]), + 'gaze_origin': array([-3.06686878, -0.25207064, 0.02877274]), + 'gaze_valid': True, + 'gaze_vergence': 698.2291870117188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96299744, 0.26820374, 0.02644348]), + 'left_gaze_origin': array([-2.96674681, 2.9301424 , 0.02622833]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.33154296875, + 'left_pupil_posn': array([ 0.29819918, -0.08326375]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96487427, 0.2610321 , 0.02957153]), + 'right_gaze_origin': array([-3.16699076, -3.43428373, 0.03131714]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2349090576171875, + 'right_pupil_posn': array([ 0.26267481, -0.16151202]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 332.34366196393967, + 'timestamp_carla': 332344, + 'timestamp_device': 4070557, + 'timestamp_stream': 332.34366196393967, + 'transform': [array([-4.46603984e-01, -1.84172401e+01, 1.05228992e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-7.11577293e-03, 1.78043483e-04, -9.37502575e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.00787353515625, + 'FR_Wheel_Angle': -25.52993392944336, + 'Location': array([ -0.5197196 , -19.19781494, 0.17008728]), + 'Rotation': array([-6.75027594e-02, 5.17042694e+01, -3.11889630e-02]), + 'Velocity': array([ 0.77657551, 0.52990079, -0.00107368]), + 'brake_input': 0.0, + 'camera_location': array([-7.22900677, 12.82774734, 3.4837172 ]), + 'camera_rotation': array([-7.07541323, 3.00164342, -0.84575164]), + 'current_gear_input': False, + 'focus_actor_dist': 1237.32421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -550.42266846, -1976.57019043, 32.3419342 ]), + 'frame': 10120, + 'frame_number': 10120, + 'framesequence': 38597, + 'gaze_dir': array([0.96442413, 0.2625351 , 0.02983856]), + 'gaze_origin': array([-3.06629038, -0.25219348, 0.03113251]), + 'gaze_valid': True, + 'gaze_vergence': 447.56707763671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96266174, 0.26907349, 0.02931213]), + 'left_gaze_origin': array([-2.96547866, 2.93224049, 0.02867737]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3029327392578125, + 'left_pupil_posn': array([ 0.29495275, -0.08103192]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96618652, 0.2559967 , 0.03036499]), + 'right_gaze_origin': array([-3.1671021 , -3.43662715, 0.03358765]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2298431396484375, + 'right_pupil_posn': array([ 0.26461017, -0.15906918]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 332.37859616428614, + 'timestamp_carla': 332379, + 'timestamp_device': 4070599, + 'timestamp_stream': 332.37859616428614, + 'transform': [array([-4.46604311e-01, -1.84172401e+01, 1.05112642e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-2.33748578e-03, 5.15174004e-04, -8.54930305e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.040870666503906, + 'FR_Wheel_Angle': -25.54929542541504, + 'Location': array([ -0.35401547, -19.07549095, 0.16988148]), + 'Rotation': array([-6.80833235e-02, 4.96084175e+01, -2.99682580e-02]), + 'Velocity': array([ 0.72440046, 0.45558158, -0.00090393]), + 'brake_input': 0.0, + 'camera_location': array([-7.22441292, 12.82978058, 3.48849201]), + 'camera_rotation': array([-7.03313398, 3.02413988, -1.00886667]), + 'current_gear_input': False, + 'focus_actor_dist': 1236.9681396484375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -549.28369141, -1976.56982422, 32.61333466]), + 'frame': 10121, + 'frame_number': 10121, + 'framesequence': 38600, + 'gaze_dir': array([0.96405792, 0.26407623, 0.02749634]), + 'gaze_origin': array([-3.06648803, -0.25358582, 0.03044815]), + 'gaze_valid': True, + 'gaze_vergence': 270.10723876953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96221924, 0.27134705, 0.02212524]), + 'left_gaze_origin': array([-2.96571207, 2.93243408, 0.02862091]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3372955322265625, + 'left_pupil_posn': array([ 0.29508543, -0.08032072]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96589661, 0.25680542, 0.03286743]), + 'right_gaze_origin': array([-3.16726375, -3.43960595, 0.03227539]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1758575439453125, + 'right_pupil_posn': array([ 0.26747179, -0.16257811]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 332.4106351621449, + 'timestamp_carla': 332411, + 'timestamp_device': 4070623, + 'timestamp_stream': 332.4106351621449, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05264094e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-1.81586493e-03, 4.65612597e-04, -7.76298189e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.842525482177734, + 'FR_Wheel_Angle': -25.35726547241211, + 'Location': array([ -0.20029251, -18.97011375, 0.16968864]), + 'Rotation': array([-6.85136244e-02, 4.77122803e+01, -2.89611779e-02]), + 'Velocity': array([ 0.67298621, 0.39347503, -0.00081151]), + 'brake_input': 0.0, + 'camera_location': array([-7.19488716, 12.83057976, 3.51288056]), + 'camera_rotation': array([-6.9271636 , 3.01388955, -1.03137326]), + 'current_gear_input': True, + 'focus_actor_dist': 1237.7904052734375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -551.81066895, -1976.57189941, 31.55015564]), + 'frame': 10122, + 'frame_number': 10122, + 'framesequence': 38604, + 'gaze_dir': array([0.96340179, 0.26648712, 0.02787018]), + 'gaze_origin': array([-3.0670557 , -0.25520936, 0.02889023]), + 'gaze_valid': True, + 'gaze_vergence': 425.0746765136719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96173096, 0.27276611, 0.02575684]), + 'left_gaze_origin': array([-2.96592879, 2.93188477, 0.02793427]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3309783935546875, + 'left_pupil_posn': array([ 0.2966547 , -0.08187532]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96507263, 0.26020813, 0.02998352]), + 'right_gaze_origin': array([-3.16818237, -3.44230342, 0.02984619]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2393951416015625, + 'right_pupil_posn': array([ 0.26989698, -0.16324329]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 332.4445354640484, + 'timestamp_carla': 332445, + 'timestamp_device': 4070657, + 'timestamp_stream': 332.4445354640484, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05220219e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-3.28427705e-05, 1.80192466e-03, -6.82024288e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.659454345703125, + 'FR_Wheel_Angle': -24.63280487060547, + 'Location': array([ -0.05535187, -18.8764286 , 0.16949928]), + 'Rotation': array([-6.87595084e-02, 4.59900742e+01, -2.86560040e-02]), + 'Velocity': array([ 0.62009716, 0.3465668 , -0.00062454]), + 'brake_input': 0.0, + 'camera_location': array([-7.18643761, 12.82414436, 3.51076818]), + 'camera_rotation': array([-6.97337675, 3.03108764, -0.90508443]), + 'current_gear_input': False, + 'focus_actor_dist': 1238.37353515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -554.70373535, -1976.56628418, 34.462677 ]), + 'frame': 10123, + 'frame_number': 10123, + 'framesequence': 38608, + 'gaze_dir': array([0.96334076, 0.26679993, 0.02727509]), + 'gaze_origin': array([-3.06712508, -0.25572512, 0.02832184]), + 'gaze_valid': True, + 'gaze_vergence': 497.46527099609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96220398, 0.27116394, 0.02455139]), + 'left_gaze_origin': array([-2.96621561, 2.93172169, 0.02703094]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3314971923828125, + 'left_pupil_posn': array([ 0.29754901, -0.08259499]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96447754, 0.26243591, 0.02999878]), + 'right_gaze_origin': array([-3.16803455, -3.44317174, 0.02961273]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.277587890625, + 'right_pupil_posn': array([ 0.26986575, -0.16383028]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 332.47621006146073, + 'timestamp_carla': 332476, + 'timestamp_device': 4070690, + 'timestamp_stream': 332.47621006146073, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05351061e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-2.84986128e-03, -6.06413116e-04, -6.16715670e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.553102493286133, + 'FR_Wheel_Angle': -24.6126766204834, + 'Location': array([ 0.07607504, -18.79549408, 0.16933872]), + 'Rotation': array([-6.91556633e-02, 4.44885559e+01, -2.71301270e-02]), + 'Velocity': array([ 0.57266277, 0.30222523, -0.00087865]), + 'brake_input': 0.0, + 'camera_location': array([-7.19401932, 12.84653378, 3.46951365]), + 'camera_rotation': array([-7.16584492, 3.16090584, -0.8767153 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1238.853515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -555.66760254, -1976.57092285, 32.02696991]), + 'frame': 10124, + 'frame_number': 10124, + 'framesequence': 38612, + 'gaze_dir': array([0.96387482, 0.26438904, 0.03104401]), + 'gaze_origin': array([-3.06679773, -0.25466615, 0.02915268]), + 'gaze_valid': True, + 'gaze_vergence': 338.6058654785156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96220398, 0.27095032, 0.02711487]), + 'left_gaze_origin': array([-2.9658494 , 2.93385935, 0.02782593]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.318695068359375, + 'left_pupil_posn': array([ 0.29456997, -0.08004856]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96554565, 0.25782776, 0.03497314]), + 'right_gaze_origin': array([-3.16774631, -3.44319153, 0.03047943]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2787322998046875, + 'right_pupil_posn': array([ 0.26980686, -0.16227889]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 332.5098806619644, + 'timestamp_carla': 332510, + 'timestamp_device': 4070723, + 'timestamp_stream': 332.5098806619644, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05283540e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 4.26594988e-06, 1.03995751e-03, -5.56749487e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.996353149414062, + 'FR_Wheel_Angle': -24.1091365814209, + 'Location': array([ 0.1986251 , -18.7240963 , 0.16919388]), + 'Rotation': array([-6.93947151e-02, 4.31132507e+01, -2.59399451e-02]), + 'Velocity': array([ 0.52779198, 0.2643702 , -0.00067899]), + 'brake_input': 0.0, + 'camera_location': array([-7.21733761, 12.87363815, 3.44502091]), + 'camera_rotation': array([-7.29364443, 3.29474187, -1.04925525]), + 'current_gear_input': False, + 'focus_actor_dist': 1238.717529296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -555.31036377, -1976.57019043, 32.35572052]), + 'frame': 10125, + 'frame_number': 10125, + 'framesequence': 38616, + 'gaze_dir': array([0.96427155, 0.26314545, 0.02923584]), + 'gaze_origin': array([-3.0658114 , -0.25362933, 0.03087845]), + 'gaze_valid': True, + 'gaze_vergence': 367.42120361328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96208191, 0.27111816, 0.02973938]), + 'left_gaze_origin': array([-2.96414185, 2.93577743, 0.03090363]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.31982421875, + 'left_pupil_posn': array([ 0.29219425, -0.07985032]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96646118, 0.25517273, 0.0287323 ]), + 'right_gaze_origin': array([-3.16748071, -3.44303632, 0.03085327]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2722320556640625, + 'right_pupil_posn': array([ 0.26977646, -0.16104186]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 332.54317816346884, + 'timestamp_carla': 332543, + 'timestamp_device': 4070757, + 'timestamp_stream': 332.54317816346884, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05272103e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-3.18199350e-03, -1.79125892e-03, -4.89921093e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.840709686279297, + 'FR_Wheel_Angle': -23.443313598632812, + 'Location': array([ 0.31135496, -18.66069984, 0.16906829]), + 'Rotation': array([-6.95176646e-02, 4.18989944e+01, -2.53601074e-02]), + 'Velocity': array([ 4.84358668e-01, 2.36474812e-01, -1.94511405e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.22690678, 12.90783501, 3.47069407]), + 'camera_rotation': array([-7.31394386, 3.42299891, -1.0160861 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1239.482421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -556.68786621, -1976.57775879, 28.28174591]), + 'frame': 10126, + 'frame_number': 10126, + 'framesequence': 38620, + 'gaze_dir': array([0.96463013, 0.26173401, 0.03059387]), + 'gaze_origin': array([-3.06572437, -0.2528435 , 0.03184815]), + 'gaze_valid': True, + 'gaze_vergence': 526.5100708007812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96311951, 0.26731873, 0.03031921]), + 'left_gaze_origin': array([-2.96444559, 2.93636203, 0.03064728]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.177459716796875, + 'left_pupil_posn': array([ 0.29219425, -0.07931077]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96614075, 0.25614929, 0.03086853]), + 'right_gaze_origin': array([-3.16700292, -3.44204855, 0.03304901]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17156982421875, + 'right_pupil_posn': array([ 0.2677207 , -0.15909421]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 332.57667676359415, + 'timestamp_carla': 332577, + 'timestamp_device': 4070790, + 'timestamp_stream': 332.57667676359415, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05249211e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-2.09337403e-03, -6.36579120e-04, -4.34470463e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.154376983642578, + 'FR_Wheel_Angle': -23.049951553344727, + 'Location': array([ 0.41585249, -18.60371017, 0.16893424]), + 'Rotation': array([-6.97362274e-02, 4.08153610e+01, -2.42309570e-02]), + 'Velocity': array([ 4.44048911e-01, 2.10287750e-01, -4.36258299e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.21257401, 12.93246841, 3.51121378]), + 'camera_rotation': array([-7.16530514, 3.55337763, -0.93822771]), + 'current_gear_input': False, + 'focus_actor_dist': 1239.6917724609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -557.67724609, -1976.5760498 , 29.2672348 ]), + 'frame': 10127, + 'frame_number': 10127, + 'framesequence': 38624, + 'gaze_dir': array([0.95985413, 0.27949524, 0.02246094]), + 'gaze_origin': array([-3.06767201, -0.26100314, 0.02959137]), + 'gaze_valid': True, + 'gaze_vergence': 415.5297546386719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95788574, 0.28634644, 0.02133179]), + 'left_gaze_origin': array([-2.96653295, 2.92576003, 0.02750092]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2498016357421875, + 'left_pupil_posn': array([ 0.30530131, -0.08460391]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96182251, 0.27264404, 0.02359009]), + 'right_gaze_origin': array([-3.16881132, -3.4477663 , 0.03168182]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.20819091796875, + 'right_pupil_posn': array([ 0.27868032, -0.16390502]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 332.6101236641407, + 'timestamp_carla': 332610, + 'timestamp_device': 4070823, + 'timestamp_stream': 332.6101236641407, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05249211e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-4.01495723e-03, -2.18080473e-03, -3.98680592e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.637060165405273, + 'FR_Wheel_Angle': -23.59676170349121, + 'Location': array([ 0.51078576, -18.55377388, 0.16882637]), + 'Rotation': array([-6.99206442e-02, 3.98504143e+01, -2.28576642e-02]), + 'Velocity': array([ 4.08426613e-01, 1.84357718e-01, -3.82966973e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.20796394, 12.95510864, 3.54621005]), + 'camera_rotation': array([-7.0220418 , 3.58031154, -0.86226147]), + 'current_gear_input': False, + 'focus_actor_dist': 1301.1094970703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -601.77697754, -1927.15527344, 17.37799072]), + 'frame': 10128, + 'frame_number': 10128, + 'framesequence': 38628, + 'gaze_dir': array([0.95976257, 0.27931976, 0.02667236]), + 'gaze_origin': array([-3.06810021, -0.26097795, 0.0282814 ]), + 'gaze_valid': True, + 'gaze_vergence': 282.226318359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95739746, 0.2878418 , 0.02252197]), + 'left_gaze_origin': array([-2.96708226, 2.92663288, 0.02568207]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2120361328125, + 'left_pupil_posn': array([ 0.30407727, -0.08342206]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96212769, 0.27079773, 0.03082275]), + 'right_gaze_origin': array([-3.16911793, -3.44858885, 0.03088074]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2073974609375, + 'right_pupil_posn': array([ 0.27975893, -0.16426945]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 332.64315006136894, + 'timestamp_carla': 332643, + 'timestamp_device': 4070857, + 'timestamp_stream': 332.64315006136894, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05274385e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-4.99774411e-04, 3.68610927e-04, -3.89527893e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.858579635620117, + 'FR_Wheel_Angle': -24.853792190551758, + 'Location': array([ 0.59929812, -18.51028633, 0.16871853]), + 'Rotation': array([-7.01255500e-02, 3.89180984e+01, -2.09350567e-02]), + 'Velocity': array([ 0.3773497 , 0.15354586, -0.00048426]), + 'brake_input': 0.0, + 'camera_location': array([-7.19923306, 12.96850777, 3.56208205]), + 'camera_rotation': array([-6.99200296, 3.54007053, -0.82281798]), + 'current_gear_input': False, + 'focus_actor_dist': 1394.787841796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -631.83673096, -1838.0234375 , 17.37651062]), + 'frame': 10129, + 'frame_number': 10129, + 'framesequence': 38632, + 'gaze_dir': array([0.95955658, 0.28010559, 0.02619171]), + 'gaze_origin': array([-3.0681994 , -0.26105577, 0.02738876]), + 'gaze_valid': True, + 'gaze_vergence': 306.02154541015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95713806, 0.28868103, 0.02316284]), + 'left_gaze_origin': array([-2.96708226, 2.92699599, 0.02480927]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.236663818359375, + 'left_pupil_posn': array([ 0.30408633, -0.08457839]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9619751 , 0.27153015, 0.02922058]), + 'right_gaze_origin': array([-3.16931653, -3.44910765, 0.02996826]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2270965576171875, + 'right_pupil_posn': array([ 0.28042054, -0.16476178]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 332.67679446190596, + 'timestamp_carla': 332677, + 'timestamp_device': 4070890, + 'timestamp_stream': 332.67679446190596, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05244257e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([ 1.36909564e-03, 1.16009859e-03, -3.53482819e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.96977424621582, + 'FR_Wheel_Angle': -24.874767303466797, + 'Location': array([ 0.69147748, -18.46805 , 0.16860923]), + 'Rotation': array([-7.01596960e-02, 3.79193764e+01, -2.06298791e-02]), + 'Velocity': array([ 0.34267733, 0.13153096, -0.00034663]), + 'brake_input': 0.0, + 'camera_location': array([-7.20982838, 12.98345184, 3.57405758]), + 'camera_rotation': array([-7.06464195, 3.50765562, -0.79741132]), + 'current_gear_input': False, + 'focus_actor_dist': 1392.8665771484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -631.43457031, -1839.91027832, 17.37675476]), + 'frame': 10130, + 'frame_number': 10130, + 'framesequence': 38636, + 'gaze_dir': array([0.9593811, 0.2807312, 0.0254364]), + 'gaze_origin': array([-3.06812668, -0.26127777, 0.0269104 ]), + 'gaze_valid': True, + 'gaze_vergence': 262.4335632324219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95677185, 0.2900238 , 0.02110291]), + 'left_gaze_origin': array([-2.96687961, 2.92694569, 0.02447663]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2115325927734375, + 'left_pupil_posn': array([ 0.30408633, -0.08457839]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96199036, 0.2714386 , 0.0297699 ]), + 'right_gaze_origin': array([-3.16937423, -3.44950104, 0.02934418]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2263946533203125, + 'right_pupil_posn': array([ 0.2811563 , -0.16598797]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.0, + 'timestamp': 332.71041586250067, + 'timestamp_carla': 332711, + 'timestamp_device': 4070923, + 'timestamp_stream': 332.71041586250067, + 'transform': [array([-4.46603537e-01, -1.84172401e+01, 1.05228992e-02]), + array([-0.06011932, -1.2944535 , 0.01138307])]} +{'AngularVelocity': array([-1.11423829e-03, -5.84947178e-04, -3.28780150e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.9874267578125, + 'FR_Wheel_Angle': -24.882505416870117, + 'Location': array([ 0.75460339, -18.44025993, 0.16854534]), + 'Rotation': array([-7.01596960e-02, 3.72392731e+01, -2.02026349e-02]), + 'Velocity': array([ 3.18823248e-01, 1.17829815e-01, -4.51850865e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.20852566, 13.00154018, 3.56079435]), + 'camera_rotation': array([-7.12588835, 3.4437623 , -0.738199 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1360.75830078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -621.41522217, -1870.5526123 , 17.37760162]), + 'frame': 10131, + 'frame_number': 10131, + 'framesequence': 38640, + 'gaze_dir': array([0.96816254, 0.24653625, 0.0391922 ]), + 'gaze_origin': array([-3.06148839, -0.23431094, 0.02941437]), + 'gaze_valid': True, + 'gaze_vergence': 169.2998504638672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96388245, 0.26376343, 0.03649902]), + 'left_gaze_origin': array([-2.95837569, 2.95963311, 0.0276413 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.225372314453125, + 'left_pupil_posn': array([ 0.26701367, -0.07565951]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97244263, 0.22930908, 0.04188538]), + 'right_gaze_origin': array([-3.16460133, -3.42825508, 0.03118744]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2297821044921875, + 'right_pupil_posn': array([ 0.25684786, -0.15752137]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.05555810034275055, + 'timestamp': 332.744660962373, + 'timestamp_carla': 332745, + 'timestamp_device': 4070957, + 'timestamp_stream': 332.744660962373, + 'transform': [array([-4.47583765e-01, -1.84174538e+01, 1.04220193e-02]), + array([-0.060092 , -1.29010606, 0.01181032])]} +{'AngularVelocity': array([-6.59078010e-04, -1.31915527e-04, -2.99409747e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.997129440307617, + 'FR_Wheel_Angle': -24.891801834106445, + 'Location': array([ 0.82323301, -18.41106033, 0.1684584 ]), + 'Rotation': array([-7.01596960e-02, 3.65038795e+01, -1.95617676e-02]), + 'Velocity': array([ 0.29260251, 0.10397588, -0.00046653]), + 'brake_input': 0.0, + 'camera_location': array([-7.2053442 , 13.02313614, 3.51925206]), + 'camera_rotation': array([-7.2114706 , 3.46045113, -0.59747726]), + 'current_gear_input': False, + 'focus_actor_dist': 1232.8553466796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -537.78710938, -1976.55224609, 41.98925781]), + 'frame': 10132, + 'frame_number': 10132, + 'framesequence': 38644, + 'gaze_dir': array([0.98767853, 0.13035583, 0.0845871 ]), + 'gaze_origin': array([-3.01678944, -0.13683015, 0.04892426]), + 'gaze_valid': True, + 'gaze_vergence': 173.23338317871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98519897, 0.14830017, 0.08583069]), + 'left_gaze_origin': array([-2.93078327, 3.05784154, 0.05202789]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2510528564453125, + 'left_pupil_posn': array([ 0.16021013, -0.03803372]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99015808, 0.1124115 , 0.08334351]), + 'right_gaze_origin': array([-3.1027956 , -3.33150172, 0.04582062]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1693572998046875, + 'right_pupil_posn': array([ 0.14790833, -0.11578262]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.08332952111959457, + 'timestamp': 332.7763765640557, + 'timestamp_carla': 332777, + 'timestamp_device': 4070990, + 'timestamp_stream': 332.7763765640557, + 'transform': [array([-4.47538286e-01, -1.84176674e+01, 1.04301637e-02]), + array([-0.060092 , -1.29029739, 0.01184083])]} +{'AngularVelocity': array([-1.22069113e-03, -6.28754555e-04, -2.70644641e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.01185607910156, + 'FR_Wheel_Angle': -24.90013885498047, + 'Location': array([ 0.89566588, -18.38137627, 0.16838318]), + 'Rotation': array([-7.01596960e-02, 3.57317696e+01, -1.87683124e-02]), + 'Velocity': array([2.65195638e-01, 9.00811628e-02, 4.77695467e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.23306656, 13.0483942 , 3.50821447]), + 'camera_rotation': array([-7.33113527, 3.47463131, -0.43740976]), + 'current_gear_input': False, + 'focus_actor_dist': 3564.43603515625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-785.11804199, 356.31787109, 0. ]), + 'frame': 10133, + 'frame_number': 10133, + 'framesequence': 38648, + 'gaze_dir': array([0.99473572, 0.02528381, 0.09803772]), + 'gaze_origin': array([-3.09793711, -0.0601471 , 0.08656464]), + 'gaze_valid': True, + 'gaze_vergence': 186.15176391601562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99372864, 0.03916931, 0.10466003]), + 'left_gaze_origin': array([-3.02449203, 3.12765193, 0.09538575]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1781158447265625, + 'left_pupil_posn': array([ 0.07901096, -0.02232695]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9957428 , 0.01139832, 0.09141541]), + 'right_gaze_origin': array([-3.17138243, -3.2479465 , 0.07774353]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.228790283203125, + 'right_pupil_posn': array([ 0.05471539, -0.0985471 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 332.81033036485314, + 'timestamp_carla': 332811, + 'timestamp_device': 4071023, + 'timestamp_stream': 332.81033036485314, + 'transform': [array([-4.47536916e-01, -1.84178314e+01, 1.04224589e-02]), + array([-0.060092 , -1.29029739, 0.01184083])]} +{'AngularVelocity': array([ 5.61380759e-04, 6.88664266e-04, -2.47539449e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.809356689453125, + 'FR_Wheel_Angle': -24.680862426757812, + 'Location': array([ 0.94540614, -18.3616333 , 0.16831234]), + 'Rotation': array([-7.01596960e-02, 3.52047691e+01, -1.82800256e-02]), + 'Velocity': array([ 0.24614745, 0.08157808, -0.00066584]), + 'brake_input': 0.0, + 'camera_location': array([-7.25938988, 13.06776237, 3.52065492]), + 'camera_rotation': array([-7.26248503, 3.5099597 , -0.41380379]), + 'current_gear_input': False, + 'focus_actor_dist': 4148.251953125, + 'focus_actor_name': 'Road_Sidewalk_Town05_155', + 'focus_actor_pt': array([-449.93395996, 982.7824707 , 15.20635223]), + 'frame': 10134, + 'frame_number': 10134, + 'framesequence': 38652, + 'gaze_dir': array([0.99520111, 0.02610016, 0.09317017]), + 'gaze_origin': array([-3.10125303, -0.06286621, 0.08792344]), + 'gaze_valid': True, + 'gaze_vergence': 214.13934326171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99441528, 0.03930664, 0.09783936]), + 'left_gaze_origin': array([-3.04877043, 3.12654114, 0.10285036]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1468658447265625, + 'left_pupil_posn': array([ 0.08032358, -0.02279878]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99598694, 0.01289368, 0.08850098]), + 'right_gaze_origin': array([-3.1537354 , -3.2522738 , 0.07299652]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.236328125, + 'right_pupil_posn': array([ 0.05732489, -0.10101485]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 332.84296096488833, + 'timestamp_carla': 332843, + 'timestamp_device': 4071057, + 'timestamp_stream': 332.84296096488833, + 'transform': [array([-4.47437137e-01, -1.84179783e+01, 1.04478644e-02]), + array([-0.06011932, -1.29076195, 0.01174928])]} +{'AngularVelocity': array([ 3.39047765e-05, 1.97562287e-04, -2.15926647e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.63860511779785, + 'FR_Wheel_Angle': -23.9166259765625, + 'Location': array([ 1.00565898, -18.33806419, 0.1682484 ]), + 'Rotation': array([-7.01596960e-02, 3.45821953e+01, -1.78527813e-02]), + 'Velocity': array([ 2.23026752e-01, 7.38675892e-02, -7.19165764e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.27242279, 13.07790947, 3.54319906]), + 'camera_rotation': array([-7.09427786, 3.53238773, -0.47854555]), + 'current_gear_input': False, + 'focus_actor_dist': 4041.979248046875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-449.37524414, 875.86157227, 3.44152832]), + 'frame': 10135, + 'frame_number': 10135, + 'framesequence': 38656, + 'gaze_dir': array([0.99523926, 0.0255661 , 0.09288788]), + 'gaze_origin': array([-3.08776188, -0.0630455 , 0.08171845]), + 'gaze_valid': True, + 'gaze_vergence': 163.61924743652344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99407959, 0.03544617, 0.10261536]), + 'left_gaze_origin': array([-3.04329848, 3.12948942, 0.10083313]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.141143798828125, + 'left_pupil_posn': array([ 0.07927394, -0.02507663]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99639893, 0.01568604, 0.0831604 ]), + 'right_gaze_origin': array([-3.13222528, -3.25558043, 0.06260376]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.26397705078125, + 'right_pupil_posn': array([ 0.05778778, -0.10240555]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1269855797290802, + 'timestamp': 332.8768560625613, + 'timestamp_carla': 332877, + 'timestamp_device': 4071090, + 'timestamp_stream': 332.8768560625613, + 'transform': [array([-4.47343141e-01, -1.84180756e+01, 1.04614254e-02]), + array([-0.06015347, -1.2911818 , 0.01165773])]} +{'AngularVelocity': array([-1.76745541e-02, -2.41130106e-02, 3.25559886e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.135013580322266, + 'FR_Wheel_Angle': -22.04319953918457, + 'Location': array([ 1.0350858 , -18.32663536, 0.16827498]), + 'Rotation': array([-7.96536654e-02, 3.43081970e+01, -2.62451172e-02]), + 'Velocity': array([-9.57328302e-06, 2.20388870e-06, 4.58244525e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.27907658, 13.08710861, 3.56995654]), + 'camera_rotation': array([-6.97754335, 3.51568079, -0.50785708]), + 'current_gear_input': False, + 'focus_actor_dist': 2166.421630859375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-328.53363037, -994.58422852, 71.7333374 ]), + 'frame': 10136, + 'frame_number': 10136, + 'framesequence': 38660, + 'gaze_dir': array([0.99504852, 0.02537537, 0.09457397]), + 'gaze_origin': array([-3.08786416, -0.06314469, 0.08104783]), + 'gaze_valid': True, + 'gaze_vergence': 130.80807495117188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99362183, 0.03622437, 0.10667419]), + 'left_gaze_origin': array([-3.04583597, 3.12980366, 0.10084992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.145050048828125, + 'left_pupil_posn': array([ 0.07865918, -0.0258615 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99647522, 0.01452637, 0.08247375]), + 'right_gaze_origin': array([-3.12989211, -3.25609303, 0.06124573]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2627410888671875, + 'right_pupil_posn': array([ 0.05837095, -0.10162973]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.15078964829444885, + 'timestamp': 332.9098152630031, + 'timestamp_carla': 332910, + 'timestamp_device': 4071123, + 'timestamp_stream': 332.9098152630031, + 'transform': [array([-4.47169334e-01, -1.84181366e+01, 1.04846954e-02]), + array([-0.06018079, -1.29199123, 0.01156618])]} +{'AngularVelocity': array([-1.93062157e-03, -2.64149792e-02, 8.80900625e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.85921287536621, + 'FR_Wheel_Angle': -18.14544677734375, + 'Location': array([ 1.035151 , -18.3266449 , 0.16823612]), + 'Rotation': array([-7.24478140e-02, 3.43084450e+01, -1.95617657e-02]), + 'Velocity': array([-1.27936155e-05, -4.61417494e-06, -3.13019002e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.27129173, 13.08045959, 3.57102251]), + 'camera_rotation': array([-6.97788477, 3.45450711, -0.4886069 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4482.13623046875, + 'focus_actor_name': 'Road_Grass_Town05_118', + 'focus_actor_pt': array([-474.02838135, 1315.93408203, 17.56529236]), + 'frame': 10137, + 'frame_number': 10137, + 'framesequence': 38664, + 'gaze_dir': array([0.99508667, 0.02557373, 0.09433746]), + 'gaze_origin': array([-3.09069991, -0.06320038, 0.08094864]), + 'gaze_valid': True, + 'gaze_vergence': 152.5117950439453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99380493, 0.03694153, 0.10473633]), + 'left_gaze_origin': array([-3.05198836, 3.12996697, 0.10084992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1041259765625, + 'left_pupil_posn': array([ 0.07845199, -0.02643454]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99636841, 0.01420593, 0.0839386 ]), + 'right_gaze_origin': array([-3.12941146, -3.25636744, 0.06104737]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2036285400390625, + 'right_pupil_posn': array([ 0.05878508, -0.10228741]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1745937317609787, + 'timestamp': 332.94246546179056, + 'timestamp_carla': 332943, + 'timestamp_device': 4071157, + 'timestamp_stream': 332.94246546179056, + 'transform': [array([-4.46955562e-01, -1.84181366e+01, 1.05085373e-02]), + array([-0.06021494, -1.29299188, 0.01147462])]} +{'AngularVelocity': array([-7.81351759e-04, -6.93619577e-03, 4.76674677e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.779747009277344, + 'FR_Wheel_Angle': -13.95128345489502, + 'Location': array([ 1.03517425, -18.3266468 , 0.16822673]), + 'Rotation': array([-6.99206442e-02, 3.43086777e+01, -1.74255352e-02]), + 'Velocity': array([-1.06785910e-06, -8.79042773e-07, 1.77555470e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.25015545, 13.06452179, 3.56311369]), + 'camera_rotation': array([-6.99096441, 3.36353874, -0.44977459]), + 'current_gear_input': False, + 'focus_actor_dist': 4451.5048828125, + 'focus_actor_name': 'Road_Grass_Town05_118', + 'focus_actor_pt': array([-468.31005859, 1285.58300781, 17.27600098]), + 'frame': 10138, + 'frame_number': 10138, + 'framesequence': 38668, + 'gaze_dir': array([0.99524689, 0.02558136, 0.09256744]), + 'gaze_origin': array([-3.09091663, -0.06348266, 0.08082886]), + 'gaze_valid': True, + 'gaze_vergence': 151.22744750976562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99397278, 0.03721619, 0.1030426 ]), + 'left_gaze_origin': array([-3.05200362, 3.12988472, 0.10057831]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.096649169921875, + 'left_pupil_posn': array([ 0.07841396, -0.02721703]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.996521 , 0.01394653, 0.08209229]), + 'right_gaze_origin': array([-3.12982941, -3.25685 , 0.06107941]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.190460205078125, + 'right_pupil_posn': array([ 0.05921423, -0.10283482]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1904631108045578, + 'timestamp': 332.97732016444206, + 'timestamp_carla': 332978, + 'timestamp_device': 4071190, + 'timestamp_stream': 332.97732016444206, + 'transform': [array([-4.46750939e-01, -1.84180202e+01, 1.05210682e-02]), + array([-0.06021494, -1.29394472, 0.01135255])]} +{'AngularVelocity': array([-4.24740021e-04, -1.80535612e-03, -1.10498095e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.714163780212402, + 'FR_Wheel_Angle': -9.967761993408203, + 'Location': array([ 1.03517997, -18.32664871, 0.16821189]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([ 1.51805580e-06, 8.52090309e-08, -6.61044542e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.22870255, 13.04600716, 3.5464139 ]), + 'camera_rotation': array([-7.00210476, 3.27516723, -0.41357747]), + 'current_gear_input': False, + 'focus_actor_dist': 4219.953125, + 'focus_actor_name': 'Road_Sidewalk_Town05_155', + 'focus_actor_pt': array([-447.43331909, 1054.74780273, 15.02524567]), + 'frame': 10139, + 'frame_number': 10139, + 'framesequence': 38672, + 'gaze_dir': array([0.99539185, 0.02631378, 0.09061432]), + 'gaze_origin': array([-3.0911324 , -0.06412812, 0.08083192]), + 'gaze_valid': True, + 'gaze_vergence': 145.53793334960938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99407959, 0.03887939, 0.10144043]), + 'left_gaze_origin': array([-3.05208755, 3.12966919, 0.10042877]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0979156494140625, + 'left_pupil_posn': array([ 0.07849002, -0.0281322 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9967041 , 0.01374817, 0.07978821]), + 'right_gaze_origin': array([-3.1301775 , -3.25792551, 0.06123505]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.186981201171875, + 'right_pupil_posn': array([ 0.0605216 , -0.10334468]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.20236514508724213, + 'timestamp': 333.0094371624291, + 'timestamp_carla': 333010, + 'timestamp_device': 4071223, + 'timestamp_stream': 333.0094371624291, + 'transform': [array([-4.46456283e-01, -1.84177551e+01, 1.05874632e-02]), + array([-0.06024227, -1.29532754, 0.01110841])]} +{'AngularVelocity': array([-1.69387844e-04, -6.34466298e-04, -1.26842851e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.842127323150635, + 'FR_Wheel_Angle': -5.7495036125183105, + 'Location': array([ 1.03518152, -18.32664871, 0.1682148 ]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([2.47182311e-06, 2.29082062e-07, 1.12225542e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.21147537, 13.02692604, 3.51963615]), + 'camera_rotation': array([-7.04587269, 3.20371819, -0.40290141]), + 'current_gear_input': False, + 'focus_actor_dist': 4042.1533203125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-433.54296875, 877.30810547, 11.46282196]), + 'frame': 10140, + 'frame_number': 10140, + 'framesequence': 38676, + 'gaze_dir': array([0.99533844, 0.02713013, 0.09129333]), + 'gaze_origin': array([-3.09534383, -0.06518021, 0.08101425]), + 'gaze_valid': True, + 'gaze_vergence': 179.45562744140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99424744, 0.03878784, 0.09971619]), + 'left_gaze_origin': array([-3.05129242, 3.12859035, 0.09864807]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1034088134765625, + 'left_pupil_posn': array([ 0.07981396, -0.0281322 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99642944, 0.01547241, 0.08287048]), + 'right_gaze_origin': array([-3.13939524, -3.25895095, 0.06338044]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16094970703125, + 'right_pupil_posn': array([ 0.06137633, -0.10411227]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2063324898481369, + 'timestamp': 333.04328756406903, + 'timestamp_carla': 333044, + 'timestamp_device': 4071257, + 'timestamp_stream': 333.04328756406903, + 'transform': [array([-4.46232587e-01, -1.84172230e+01, 1.06508061e-02]), + array([-0.06024227, -1.29638982, 0.01080323])]} +{'AngularVelocity': array([ 1.67098660e-05, -1.06710664e-04, -1.08243366e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.6534926891326904, + 'FR_Wheel_Angle': -1.061819076538086, + 'Location': array([ 1.035182 , -18.32664871, 0.16820003]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([4.16714238e-06, 6.29657848e-07, 1.29659823e-03]), + 'brake_input': 0.0, + 'camera_location': array([-7.20311928, 13.01460266, 3.51479101]), + 'camera_rotation': array([-7.12774611, 3.15149546, -0.41636258]), + 'current_gear_input': False, + 'focus_actor_dist': 4041.94775390625, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-431.7310791 , 877.2434082 , 11.13592529]), + 'frame': 10141, + 'frame_number': 10141, + 'framesequence': 38681, + 'gaze_dir': array([0.99542236, 0.0308075 , 0.08969116]), + 'gaze_origin': array([-3.09743667, -0.06603012, 0.08228531]), + 'gaze_valid': True, + 'gaze_vergence': 252.3928985595703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99462891, 0.03967285, 0.09544373]), + 'left_gaze_origin': array([-3.04172087, 3.12770414, 0.09601441]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1199798583984375, + 'left_pupil_posn': array([ 0.08262372, -0.02784336]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99621582, 0.02194214, 0.0839386 ]), + 'right_gaze_origin': array([-3.1531527 , -3.25976419, 0.06855621]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1466522216796875, + 'right_pupil_posn': array([ 0.06251574, -0.10459411]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2063324898481369, + 'timestamp': 333.07880076393485, + 'timestamp_carla': 333079, + 'timestamp_device': 4071298, + 'timestamp_stream': 333.07880076393485, + 'transform': [array([-4.45989817e-01, -1.84163456e+01, 1.07228663e-02]), + array([-0.06027642, -1.29750979, 0.01040651])]} +{'AngularVelocity': array([-5.20749127e-05, -5.95382662e-05, -1.00524112e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.014097630977630615, + 'FR_Wheel_Angle': -0.104998879134655, + 'Location': array([ 1.03518212, -18.32664871, 0.16823849]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([3.06224911e-06, 2.75669152e-07, 1.57837363e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.18120098, 12.99623871, 3.51537609]), + 'camera_rotation': array([-7.13599014, 3.1117065 , -0.51007921]), + 'current_gear_input': False, + 'focus_actor_dist': 4014.850830078125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-4.41075684e+02, 8.49202148e+02, 1.52587891e-05]), + 'frame': 10142, + 'frame_number': 10142, + 'framesequence': 38684, + 'gaze_dir': array([0.99555206, 0.03206635, 0.08781433]), + 'gaze_origin': array([-3.09260511, -0.06635056, 0.08273011]), + 'gaze_valid': True, + 'gaze_vergence': 277.811767578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99491882, 0.04246521, 0.09112549]), + 'left_gaze_origin': array([-3.0291214 , 3.12717605, 0.09403992]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.124176025390625, + 'left_pupil_posn': array([ 0.08285701, -0.0267036 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9961853 , 0.02166748, 0.08450317]), + 'right_gaze_origin': array([-3.15608835, -3.2598772 , 0.0714203 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1350555419921875, + 'right_pupil_posn': array([ 0.06361866, -0.10469651]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2063324898481369, + 'timestamp': 333.10934306308627, + 'timestamp_carla': 333110, + 'timestamp_device': 4071323, + 'timestamp_stream': 333.10934306308627, + 'transform': [array([-4.44902480e-01, -1.84149818e+01, 1.09637640e-02]), + array([-0.06021494, -1.30229056, 0.00946046])]} +{'AngularVelocity': array([-6.15763638e-05, -7.31165055e-05, -1.03545444e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04740398749709129, + 'FR_Wheel_Angle': 0.047425754368305206, + 'Location': array([ 1.03518212, -18.32664871, 0.16820705]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([ 2.31743775e-06, 8.86712215e-08, -4.01193392e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.1508913 , 12.9708252 , 3.51198483]), + 'camera_rotation': array([-7.23808098, 3.0432744 , -0.5306865 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3798.94091796875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-429.13760376, 633.59619141, 0. ]), + 'frame': 10143, + 'frame_number': 10143, + 'framesequence': 38688, + 'gaze_dir': array([0.99537659, 0.03327942, 0.08934784]), + 'gaze_origin': array([-3.09099221, -0.066819 , 0.08205491]), + 'gaze_valid': True, + 'gaze_vergence': 287.5582580566406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99479675, 0.04374695, 0.09185791]), + 'left_gaze_origin': array([-3.02495742, 3.12702203, 0.09268952]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0687103271484375, + 'left_pupil_posn': array([ 0.08335328, -0.02592421]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99595642, 0.02281189, 0.08683777]), + 'right_gaze_origin': array([-3.15702677, -3.26065969, 0.0714203 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.123138427734375, + 'right_pupil_posn': array([ 0.06461751, -0.10459411]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2063324898481369, + 'timestamp': 333.14478746429086, + 'timestamp_carla': 333145, + 'timestamp_device': 4071357, + 'timestamp_stream': 333.14478746429086, + 'transform': [array([-4.44777817e-01, -1.84113159e+01, 1.14449309e-02]), + array([-0.06021494, -1.30260718, 0.00723267])]} +{'AngularVelocity': array([ 2.33401897e-05, -4.30039472e-06, -1.00714724e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04612337425351143, + 'FR_Wheel_Angle': 0.04614398255944252, + 'Location': array([ 1.03518212, -18.32664871, 0.16822834]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([3.42215867e-06, 3.63346174e-07, 4.49615938e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.11549854, 12.94219971, 3.50182986]), + 'camera_rotation': array([-7.30725718, 2.97193074, -0.58511168]), + 'current_gear_input': False, + 'focus_actor_dist': 3778.51416015625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-4.27417175e+02, 6.13400391e+02, -1.52587891e-05]), + 'frame': 10144, + 'frame_number': 10144, + 'framesequence': 38693, + 'gaze_dir': array([0.9952774 , 0.03305817, 0.09056091]), + 'gaze_origin': array([-3.08901143, -0.06761093, 0.08084869]), + 'gaze_valid': True, + 'gaze_vergence': 310.3695068359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99482727, 0.04316711, 0.09181213]), + 'left_gaze_origin': array([-3.02099633, 3.12682652, 0.09048005]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0352325439453125, + 'left_pupil_posn': array([ 0.08352947, -0.02575719]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99572754, 0.02294922, 0.08930969]), + 'right_gaze_origin': array([-3.15702677, -3.26204848, 0.07121734]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09942626953125, + 'right_pupil_posn': array([ 0.06536126, -0.10469651]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2063324898481369, + 'timestamp': 333.17873776331544, + 'timestamp_carla': 333179, + 'timestamp_device': 4071398, + 'timestamp_stream': 333.17873776331544, + 'transform': [array([-4.44803298e-01, -1.84061050e+01, 1.19587798e-02]), + array([-0.0600237 , -1.30190575, 0.00497438])]} +{'AngularVelocity': array([ 6.83702501e-06, -1.35189894e-05, -1.04461087e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07172967493534088, + 'FR_Wheel_Angle': 0.079470194876194, + 'Location': array([ 1.03518212, -18.32664871, 0.16819607]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([ 2.68722874e-06, 8.62032152e-08, -1.18820608e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.08392811, 12.92012787, 3.47823644]), + 'camera_rotation': array([-7.40723753, 2.81878066, -0.6761114 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3786.016845703125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-4.21928802e+02, 6.21660889e+02, 1.52587891e-05]), + 'frame': 10145, + 'frame_number': 10145, + 'framesequence': 38696, + 'gaze_dir': array([0.99526978, 0.03435516, 0.09026337]), + 'gaze_origin': array([-3.08754969, -0.06822739, 0.08059464]), + 'gaze_valid': True, + 'gaze_vergence': 333.2686767578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99485779, 0.04382324, 0.09121704]), + 'left_gaze_origin': array([-3.01931024, 3.12649536, 0.09013215]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9839019775390625, + 'left_pupil_posn': array([ 0.08442163, -0.02564347]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99568176, 0.02488708, 0.08930969]), + 'right_gaze_origin': array([-3.15578914, -3.26295018, 0.07105713]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0727996826171875, + 'right_pupil_posn': array([ 0.06617975, -0.10472834]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.21428243815898895, + 'timestamp': 333.21013026311994, + 'timestamp_carla': 333210, + 'timestamp_device': 4071423, + 'timestamp_stream': 333.21013026311994, + 'transform': [array([-4.44723189e-01, -1.84001369e+01, 1.23153683e-02]), + array([-0.05996223, -1.30157042, 0.00347901])]} +{'AngularVelocity': array([ 5.24067127e-06, -1.06948246e-05, -1.04791525e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03518212, -18.32664871, 0.16817355]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([3.35893583e-06, 2.85331623e-07, 5.26873395e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.03749561, 12.89377785, 3.45438719]), + 'camera_rotation': array([-7.49701309, 2.64878321, -0.64420575]), + 'current_gear_input': False, + 'focus_actor_dist': 3594.901611328125, + 'focus_actor_name': 'Road_Marking_Town05_93', + 'focus_actor_pt': array([-404.8012085 , 431.64550781, 0. ]), + 'frame': 10146, + 'frame_number': 10146, + 'framesequence': 38700, + 'gaze_dir': array([0.9949646 , 0.03697968, 0.09264374]), + 'gaze_origin': array([-3.08744144, -0.06877823, 0.08062591]), + 'gaze_valid': True, + 'gaze_vergence': 331.9917907714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99455261, 0.04653931, 0.09326172]), + 'left_gaze_origin': array([-3.0194962 , 3.12591577, 0.09013215]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.86151123046875, + 'left_pupil_posn': array([ 0.08569539, -0.02466059]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99537659, 0.02742004, 0.09202576]), + 'right_gaze_origin': array([-3.15538645, -3.26347208, 0.07111969]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0389404296875, + 'right_pupil_posn': array([ 0.06748295, -0.10387182]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.23015183210372925, + 'timestamp': 333.24295376241207, + 'timestamp_carla': 333243, + 'timestamp_device': 4071457, + 'timestamp_stream': 333.24295376241207, + 'transform': [array([-4.44105685e-01, -1.83928070e+01, 1.25756068e-02]), + array([-0.0600237 , -1.30352664, 0.00231934])]} +{'AngularVelocity': array([-2.67317864e-05, 1.08435997e-05, -1.04203764e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03518212, -18.32664871, 0.16819248]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([3.14997510e-06, 2.92188474e-07, 3.27898510e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.99352169, 12.86578274, 3.4425385 ]), + 'camera_rotation': array([-7.49310637, 2.45269799, -0.70704335]), + 'current_gear_input': False, + 'focus_actor_dist': 3677.899169921875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-408.58953857, 515.26171875, 0. ]), + 'frame': 10147, + 'frame_number': 10147, + 'framesequence': 38704, + 'gaze_dir': array([ 0.99475098, -0.04343414, 0.09037018]), + 'gaze_origin': array([-3.12405872, -0.00790482, 0.08889695]), + 'gaze_valid': True, + 'gaze_vergence': 161.3663787841797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99551392, -0.0236969 , 0.09144592]), + 'left_gaze_origin': array([-3.0643847 , 3.18910551, 0.10122224]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.91094970703125, + 'left_pupil_posn': array([ 0.01158297, -0.02581942]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99398804, -0.06317139, 0.08929443]), + 'right_gaze_origin': array([-3.18373299, -3.20491505, 0.07657166]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0115814208984375, + 'right_pupil_posn': array([ 0.00355268, -0.10521078]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2539559006690979, + 'timestamp': 333.2760940641165, + 'timestamp_carla': 333276, + 'timestamp_device': 4071490, + 'timestamp_stream': 333.2760940641165, + 'transform': [array([-4.43461001e-01, -1.83845520e+01, 1.27151962e-02]), + array([-0.06011932, -1.30555856, 0.00167847])]} +{'AngularVelocity': array([ 1.23631135e-05, 6.11716896e-05, -1.04048067e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03518212, -18.32664871, 0.16821842]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([2.99109138e-06, 2.02693045e-07, 8.26961332e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.97257423, 12.81742191, 3.47815466]), + 'camera_rotation': array([-7.27911663, 2.02691817, -0.62931007]), + 'current_gear_input': False, + 'focus_actor_dist': 3390.894775390625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-106.95256805, 234.27075195, 0. ]), + 'frame': 10148, + 'frame_number': 10148, + 'framesequence': 38708, + 'gaze_dir': array([ 0.99167633, -0.09949493, 0.08131409]), + 'gaze_origin': array([-3.20765638, 0.05125657, 0.10265275]), + 'gaze_valid': True, + 'gaze_vergence': 25.759002685546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99110413, -0.09912109, 0.08879089]), + 'left_gaze_origin': array([-3.22010231, 3.24415159, 0.13613586]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9221954345703125, + 'left_pupil_posn': array([-0.03959459, -0.03641009]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99224854, -0.09986877, 0.07383728]), + 'right_gaze_origin': array([-3.19521046, -3.14163828, 0.06916962]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9341888427734375, + 'right_pupil_posn': array([-0.06597596, -0.11289144]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2737926244735718, + 'timestamp': 333.30986216291785, + 'timestamp_carla': 333310, + 'timestamp_device': 4071523, + 'timestamp_stream': 333.30986216291785, + 'transform': [array([-4.43061680e-01, -1.83743572e+01, 1.30121512e-02]), + array([-6.00578487e-02, -1.30622709e+00, 3.35697056e-04])]} +{'AngularVelocity': array([ 1.16686997e-05, -1.90050996e-05, -1.02946224e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03518212, -18.32664871, 0.16822048]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([3.03670754e-06, 2.32898159e-07, 1.46442486e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.98157883, 12.72736931, 3.53477669]), + 'camera_rotation': array([-7.0742178 , 1.15375781, -0.50719124]), + 'current_gear_input': False, + 'focus_actor_dist': 2990.672607421875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.26379242e+01, -1.76114014e+02, -1.52587891e-05]), + 'frame': 10149, + 'frame_number': 10149, + 'framesequence': 38712, + 'gaze_dir': array([ 0.99236298, -0.09329224, 0.08002472]), + 'gaze_origin': array([-3.12277627, 0.03554612, 0.07321625]), + 'gaze_valid': True, + 'gaze_vergence': 339.2056884765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99319458, -0.08396912, 0.08052063]), + 'left_gaze_origin': array([-3.0601809 , 3.22649693, 0.08531342]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.782684326171875, + 'left_pupil_posn': array([-0.02744555, -0.03933001]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99153137, -0.10261536, 0.07952881]), + 'right_gaze_origin': array([-3.18537164, -3.15540481, 0.06111908]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0134429931640625, + 'right_pupil_posn': array([-0.05142325, -0.11954546]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.28172731399536133, + 'timestamp': 333.3433567620814, + 'timestamp_carla': 333344, + 'timestamp_device': 4071557, + 'timestamp_stream': 333.3433567620814, + 'transform': [array([-4.44754928e-01, -1.83629131e+01, 1.30935861e-02]), + array([-6.00578487e-02, -1.29749060e+00, -3.41438754e-05])]} +{'AngularVelocity': array([-2.97195384e-05, 5.82908660e-06, -1.03725697e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.3098167181015015, + 'FR_Wheel_Angle': -1.4631493091583252, + 'Location': array([ 1.03518212, -18.32664871, 0.16820911]), + 'Rotation': array([-6.95518106e-02, 3.43087578e+01, -1.70593262e-02]), + 'Velocity': array([2.98645341e-06, 1.74161968e-07, 8.72265882e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.02122116, 12.62468243, 3.59230256]), + 'camera_rotation': array([-6.89670134, -0.0344739 , -0.34519359]), + 'current_gear_input': False, + 'focus_actor_dist': 3159.798583984375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([115.33447266, -8.95703125, 0. ]), + 'frame': 10150, + 'frame_number': 10150, + 'framesequence': 38716, + 'gaze_dir': array([ 0.9936676 , -0.081604 , 0.07679749]), + 'gaze_origin': array([-3.09874129, 0.02212296, 0.06026917]), + 'gaze_valid': True, + 'gaze_vergence': 326.33306884765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99380493, -0.07545471, 0.08154297]), + 'left_gaze_origin': array([-3.02813888, 3.21589518, 0.07020111]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9207763671875, + 'left_pupil_posn': array([-0.01495826, -0.04601169]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99353027, -0.0877533 , 0.072052 ]), + 'right_gaze_origin': array([-3.16934371, -3.17164922, 0.05033722]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.90692138671875, + 'right_pupil_posn': array([-0.03770834, -0.12321508]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2856946587562561, + 'timestamp': 333.3764414638281, + 'timestamp_carla': 333377, + 'timestamp_device': 4071590, + 'timestamp_stream': 333.3764414638281, + 'transform': [array([-4.44468379e-01, -1.83503189e+01, 1.32552432e-02]), + array([-6.01193234e-02, -1.29749036e+00, -7.51315907e-04])]} +{'AngularVelocity': array([-0.01505806, 0.02418105, 0.73423868]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.265939712524414, + 'FR_Wheel_Angle': -3.5102663040161133, + 'Location': array([ 1.0314126 , -18.32922935, 0.16821377]), + 'Rotation': array([-7.00640753e-02, 3.43209038e+01, -1.70593262e-02]), + 'Velocity': array([-2.87968051e-02, -1.93731729e-02, -4.83512886e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.08302879, 12.53078175, 3.62564898]), + 'camera_rotation': array([-6.5884409 , -1.11531162, -0.24864392]), + 'current_gear_input': False, + 'focus_actor_dist': 3164.345947265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.42886612e+02, -6.06958008e+00, -1.52587891e-05]), + 'frame': 10151, + 'frame_number': 10151, + 'framesequence': 38720, + 'gaze_dir': array([ 0.99523163, -0.0644455 , 0.0723877 ]), + 'gaze_origin': array([-3.11869907, 0.00956802, 0.06076432]), + 'gaze_valid': True, + 'gaze_vergence': 234.23463439941406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99526978, -0.05635071, 0.0790863 ]), + 'left_gaze_origin': array([-3.02121282, 3.20254087, 0.0629364 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0247039794921875, + 'left_pupil_posn': array([-0.00065756, -0.05168474]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99519348, -0.07254028, 0.06568909]), + 'right_gaze_origin': array([-3.21618509, -3.18340468, 0.05859223]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.88983154296875, + 'right_pupil_posn': array([-0.02236086, -0.12732625]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2856946587562561, + 'timestamp': 333.4087469615042, + 'timestamp_carla': 333409, + 'timestamp_device': 4071623, + 'timestamp_stream': 333.4087469615042, + 'transform': [array([-4.44115132e-01, -1.83370571e+01, 1.32901287e-02]), + array([-6.00920022e-02, -1.29764390e+00, -8.74258752e-04])]} +{'AngularVelocity': array([-0.01795293, 0.02692822, 0.75059247]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.178092956542969, + 'FR_Wheel_Angle': -6.184396266937256, + 'Location': array([ 1.02810955, -18.33141136, 0.1682172 ]), + 'Rotation': array([-6.97977021e-02, 3.43300209e+01, -1.70593262e-02]), + 'Velocity': array([-0.03002368, -0.01956869, -0.00022882]), + 'brake_input': 0.0, + 'camera_location': array([-7.16585541, 12.4667511 , 3.65338802]), + 'camera_rotation': array([-6.27723026, -2.03314829, -0.1954013 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3240.353515625, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([155.7775116 , 70.24609375, 0. ]), + 'frame': 10152, + 'frame_number': 10152, + 'framesequence': 38724, + 'gaze_dir': array([ 0.99598694, -0.05503845, 0.06828308]), + 'gaze_origin': array([-3.11683750e+00, -2.26745615e-03, 5.74348494e-02]), + 'gaze_valid': True, + 'gaze_vergence': 139.8004608154297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99591064, -0.04232788, 0.07965088]), + 'left_gaze_origin': array([-3.03675842, 3.18980598, 0.06546021]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.94683837890625, + 'left_pupil_posn': array([ 0.00958276, -0.0560782 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99606323, -0.06774902, 0.05691528]), + 'right_gaze_origin': array([-3.19691634, -3.19434071, 0.04940949]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.82421875, + 'right_pupil_posn': array([-0.01029527, -0.12973678]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2856946587562561, + 'timestamp': 333.44172636419535, + 'timestamp_carla': 333442, + 'timestamp_device': 4071657, + 'timestamp_stream': 333.44172636419535, + 'transform': [array([-4.44142610e-01, -1.83216629e+01, 1.34921735e-02]), + array([-0.06005785, -1.29589832, -0.00177584])]} +{'AngularVelocity': array([-0.0187619 , 0.0265846 , 0.75858754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.648253440856934, + 'FR_Wheel_Angle': -8.169517517089844, + 'Location': array([ 1.02392876, -18.33397484, 0.16822483]), + 'Rotation': array([-7.00026080e-02, 3.43438225e+01, -1.70593243e-02]), + 'Velocity': array([-3.60536501e-02, -2.24655662e-02, -8.84342153e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.23355103, 12.42395115, 3.67677832]), + 'camera_rotation': array([-6.00849676, -2.69919848, -0.14037733]), + 'current_gear_input': False, + 'focus_actor_dist': 3345.38232421875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.88684311e+02, 1.73616455e+02, -3.05175781e-05]), + 'frame': 10153, + 'frame_number': 10153, + 'framesequence': 38728, + 'gaze_dir': array([ 0.99674225, -0.04510498, 0.06468964]), + 'gaze_origin': array([-3.1186769 , -0.00792542, 0.05561219]), + 'gaze_valid': True, + 'gaze_vergence': 133.9490509033203, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99650574, -0.03321838, 0.07662964]), + 'left_gaze_origin': array([-3.0404191 , 3.18461013, 0.06450044]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8889923095703125, + 'left_pupil_posn': array([ 0.01680279, -0.05886662]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99697876, -0.05699158, 0.05274963]), + 'right_gaze_origin': array([-3.1969347 , -3.20046091, 0.04672394]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.882110595703125, + 'right_pupil_posn': array([-0.00291735, -0.13285732]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2856946587562561, + 'timestamp': 333.4762607626617, + 'timestamp_carla': 333477, + 'timestamp_device': 4071690, + 'timestamp_stream': 333.4762607626617, + 'transform': [array([-4.43929136e-01, -1.83040237e+01, 1.36580272e-02]), + array([-0.060092 , -1.29498923, -0.00257498])]} +{'AngularVelocity': array([-0.01960591, 0.02619662, 0.80670077]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.61256217956543, + 'FR_Wheel_Angle': -8.85505485534668, + 'Location': array([ 1.01785362, -18.33753204, 0.16822852]), + 'Rotation': array([-7.02553242e-02, 3.43660164e+01, -1.70593243e-02]), + 'Velocity': array([-0.04571709, -0.02759643, -0.00017906]), + 'brake_input': 0.0, + 'camera_location': array([-7.29916382, 12.39942551, 3.73589182]), + 'camera_rotation': array([-5.73033714, -3.13581204, -0.12157899]), + 'current_gear_input': False, + 'focus_actor_dist': 3438.631103515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([204.62814331, 267.19311523, 0. ]), + 'frame': 10154, + 'frame_number': 10154, + 'framesequence': 38732, + 'gaze_dir': array([ 0.99734497, -0.03780365, 0.06008911]), + 'gaze_origin': array([-3.11276793, -0.01212082, 0.04996033]), + 'gaze_valid': True, + 'gaze_vergence': 142.9638214111328, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99708557, -0.02696228, 0.0712738 ]), + 'left_gaze_origin': array([-3.03548145, 3.18115234, 0.05891266]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8625640869140625, + 'left_pupil_posn': array([ 0.02203977, -0.06307757]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99760437, -0.04864502, 0.04890442]), + 'right_gaze_origin': array([-3.19005442, -3.20539403, 0.041008 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9259185791015625, + 'right_pupil_posn': array([ 0.00248957, -0.13736653]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2658579349517822, + 'timestamp': 333.5095705613494, + 'timestamp_carla': 333510, + 'timestamp_device': 4071723, + 'timestamp_stream': 333.5095705613494, + 'transform': [array([-4.44513381e-01, -1.82848606e+01, 1.39089581e-02]), + array([-0.06015347, -1.29041231, -0.0036883 ])]} +{'AngularVelocity': array([-0.01797803, 0.0240581 , 0.79756224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.801512718200684, + 'FR_Wheel_Angle': -8.958698272705078, + 'Location': array([ 1.00945556, -18.3424015 , 0.16825405]), + 'Rotation': array([-7.03441128e-02, 3.43981018e+01, -1.70593262e-02]), + 'Velocity': array([-0.05557536, -0.03287198, 0.00027218]), + 'brake_input': 0.0, + 'camera_location': array([-7.33994389, 12.38214874, 3.80008245]), + 'camera_rotation': array([-5.35817385, -3.42361999, -0.06532072]), + 'current_gear_input': False, + 'focus_actor_dist': 3461.215087890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([2.08155396e+02, 2.91240723e+02, 3.05175781e-05]), + 'frame': 10155, + 'frame_number': 10155, + 'framesequence': 38736, + 'gaze_dir': array([ 0.99784851, -0.03094482, 0.0563736 ]), + 'gaze_origin': array([-3.09483814, -0.01528473, 0.03753739]), + 'gaze_valid': True, + 'gaze_vergence': 261.0790100097656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99804688, -0.01939392, 0.05918884]), + 'left_gaze_origin': array([-2.99792647, 3.17815089, 0.03997803]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8636322021484375, + 'left_pupil_posn': array([ 0.02620935, -0.06682444]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99765015, -0.04249573, 0.05355835]), + 'right_gaze_origin': array([-3.19174981, -3.20872068, 0.03509674]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.012786865234375, + 'right_pupil_posn': array([ 0.00738525, -0.14616573]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2539559006690979, + 'timestamp': 333.5423803627491, + 'timestamp_carla': 333543, + 'timestamp_device': 4071757, + 'timestamp_stream': 333.5423803627491, + 'transform': [array([-4.41970825e-01, -1.82650833e+01, 1.40349763e-02]), + array([-0.06015347, -1.29967415, -0.00422788])]} +{'AngularVelocity': array([-0.02013387, 0.02612041, 0.90845054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.086529731750488, + 'FR_Wheel_Angle': -9.260859489440918, + 'Location': array([ 0.99887258, -18.34855461, 0.16824615]), + 'Rotation': array([-7.02826455e-02, 3.44401588e+01, -1.70898419e-02]), + 'Velocity': array([-0.0645937 , -0.03814066, -0.00036985]), + 'brake_input': 0.0, + 'camera_location': array([-7.36509514, 12.35908127, 3.85565877]), + 'camera_rotation': array([-5.0288496 , -3.51988459, -0.0271052 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3723.787353515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([2.31067154e+02, 5.54984131e+02, 1.52587891e-05]), + 'frame': 10156, + 'frame_number': 10156, + 'framesequence': 38740, + 'gaze_dir': array([ 0.9977417 , -0.02745819, 0.0602417 ]), + 'gaze_origin': array([-3.09010267, -0.01553345, 0.03212738]), + 'gaze_valid': True, + 'gaze_vergence': 299.58367919921875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9979248 , -0.01704407, 0.06185913]), + 'left_gaze_origin': array([-2.99720478, 3.17813277, 0.03575898]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7495269775390625, + 'left_pupil_posn': array([ 0.02780843, -0.06781244]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99755859, -0.03787231, 0.05862427]), + 'right_gaze_origin': array([-3.18300009, -3.20919967, 0.02849579]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.904632568359375, + 'right_pupil_posn': array([ 0.00835121, -0.14798832]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2539559006690979, + 'timestamp': 333.57597106322646, + 'timestamp_carla': 333576, + 'timestamp_device': 4071790, + 'timestamp_stream': 333.57597106322646, + 'transform': [array([-4.39767301e-01, -1.82430115e+01, 1.41816996e-02]), + array([-0.06011932, -1.30715001, -0.00489041])]} +{'AngularVelocity': array([-0.00278666, 0.03121301, 0.29161298]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.506282806396484, + 'FR_Wheel_Angle': -9.623176574707031, + 'Location': array([ 0.98410332, -18.35715294, 0.16827816]), + 'Rotation': array([-7.07675889e-02, 3.45055161e+01, -1.74255352e-02]), + 'Velocity': array([-0.08395731, -0.04549817, 0.00013517]), + 'brake_input': 0.0, + 'camera_location': array([-7.35378742, 12.3505497 , 3.88503981]), + 'camera_rotation': array([-4.77285385, -3.4624114 , 0.01276812]), + 'current_gear_input': False, + 'focus_actor_dist': 4451.53759765625, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 306.04119873, 1281.76708984, 15.92468262]), + 'frame': 10157, + 'frame_number': 10157, + 'framesequence': 38744, + 'gaze_dir': array([ 0.99790192, -0.02893066, 0.0562973 ]), + 'gaze_origin': array([-3.0864718, -0.0153595, 0.029599 ]), + 'gaze_valid': True, + 'gaze_vergence': 237.63668823242188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99812317, -0.01603699, 0.05895996]), + 'left_gaze_origin': array([-2.99090886, 3.17824411, 0.03192902]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8436126708984375, + 'left_pupil_posn': array([ 0.02638638, -0.07095683]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99768066, -0.04182434, 0.05363464]), + 'right_gaze_origin': array([-3.18203449, -3.20896316, 0.02726898]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9305419921875, + 'right_pupil_posn': array([ 0.00851095, -0.1496619 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2539559006690979, + 'timestamp': 333.60985466465354, + 'timestamp_carla': 333610, + 'timestamp_device': 4071823, + 'timestamp_stream': 333.60985466465354, + 'transform': [array([-4.39074397e-01, -1.82189350e+01, 1.42681114e-02]), + array([-0.06011932, -1.30775774, -0.00529339])]} +{'AngularVelocity': array([-0.01100326, 0.02952312, 0.67196006]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.457768440246582, + 'FR_Wheel_Angle': -10.470481872558594, + 'Location': array([ 0.95442379, -18.37415886, 0.16832782]), + 'Rotation': array([-7.44012445e-02, 3.46190414e+01, -1.88598596e-02]), + 'Velocity': array([-1.89392671e-01, -1.03580989e-01, 6.91890673e-05]), + 'brake_input': 0.0, + 'camera_location': array([-7.32990837, 12.3270607 , 3.89767218]), + 'camera_rotation': array([-4.67780495, -3.4198451 , 0.03233339]), + 'current_gear_input': False, + 'focus_actor_dist': 4509.81005859375, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 315.10931396, 1341.67797852, 16.81538391]), + 'frame': 10158, + 'frame_number': 10158, + 'framesequence': 38748, + 'gaze_dir': array([ 0.99746704, -0.04298401, 0.05373383]), + 'gaze_origin': array([-3.11420608e+00, -9.65881394e-04, 4.04754654e-02]), + 'gaze_valid': True, + 'gaze_vergence': 184.59689331054688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9981842 , -0.02571106, 0.05422974]), + 'left_gaze_origin': array([-3.02667856, 3.19253683, 0.0432663 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8774566650390625, + 'left_pupil_posn': array([ 0.01027691, -0.07015276]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99674988, -0.06025696, 0.05323792]), + 'right_gaze_origin': array([-3.20173359, -3.19446874, 0.03768463]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8035430908203125, + 'right_pupil_posn': array([-0.00444025, -0.14782763]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.2539559006690979, + 'timestamp': 333.6419768631458, + 'timestamp_carla': 333642, + 'timestamp_device': 4071857, + 'timestamp_stream': 333.6419768631458, + 'transform': [array([-4.37455297e-01, -1.81949043e+01, 1.42922588e-02]), + array([-0.06011932, -1.31245363, -0.00535486])]} +{'AngularVelocity': array([-0.00966638, 0.01708286, 0.07820801]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.679941177368164, + 'FR_Wheel_Angle': -11.369243621826172, + 'Location': array([ 0.91544372, -18.39603424, 0.16836937]), + 'Rotation': array([-7.24136606e-02, 3.47913132e+01, -1.85852014e-02]), + 'Velocity': array([-0.2129789 , -0.11400544, 0.0002822 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.28746796, 12.29527473, 3.88043642]), + 'camera_rotation': array([-4.73569107, -3.35865688, -0.04230119]), + 'current_gear_input': False, + 'focus_actor_dist': 4429.43896484375, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 364.73876953, 1257.15136719, 15.22199249]), + 'frame': 10159, + 'frame_number': 10159, + 'framesequence': 38752, + 'gaze_dir': array([ 0.99304962, -0.09966278, 0.06101227]), + 'gaze_origin': array([-3.24083567, 0.04896851, 0.08145295]), + 'gaze_valid': True, + 'gaze_vergence': 15.430564880371094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99229431, -0.09895325, 0.0743866 ]), + 'left_gaze_origin': array([-3.26044035, 3.24378824, 0.1186142 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7940216064453125, + 'left_pupil_posn': array([-0.03994399, -0.06489944]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99380493, -0.10037231, 0.04763794]), + 'right_gaze_origin': array([-3.22123122, -3.14585114, 0.04429169]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8227996826171875, + 'right_pupil_posn': array([-0.06307572, -0.1396842 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.24998855590820312, + 'timestamp': 333.67554096132517, + 'timestamp_carla': 333676, + 'timestamp_device': 4071890, + 'timestamp_stream': 333.67554096132517, + 'transform': [array([-4.36806798e-01, -1.81684322e+01, 1.42412847e-02]), + array([-0.06011932, -1.31258368, -0.00514996])]} +{'AngularVelocity': array([-0.01756245, -0.02688703, 0.53656483]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.828764915466309, + 'FR_Wheel_Angle': -11.429012298583984, + 'Location': array([ 0.85993719, -18.42742348, 0.16842052]), + 'Rotation': array([-7.07675889e-02, 3.50668755e+01, -1.77001934e-02]), + 'Velocity': array([-0.22355038, -0.12398304, 0.00025399]), + 'brake_input': 0.0, + 'camera_location': array([-7.24100208, 12.25824165, 3.83756781]), + 'camera_rotation': array([-4.98699427, -3.37455344, -0.10538994]), + 'current_gear_input': False, + 'focus_actor_dist': 5720.64208984375, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 842.52886963, 2492.05712891, 16.31744385]), + 'frame': 10160, + 'frame_number': 10160, + 'framesequence': 38756, + 'gaze_dir': array([ 0.99315643, -0.09746552, 0.06314087]), + 'gaze_origin': array([-3.23060298, 0.04853211, 0.07962952]), + 'gaze_valid': True, + 'gaze_vergence': 17.270545959472656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9924469 , -0.09681702, 0.07531738]), + 'left_gaze_origin': array([-3.26125073, 3.24449015, 0.11923981]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.778076171875, + 'left_pupil_posn': array([-0.03962767, -0.06349266]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99386597, -0.09811401, 0.05096436]), + 'right_gaze_origin': array([-3.19995594, -3.14742589, 0.04001923]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7999267578125, + 'right_pupil_posn': array([-0.06153679, -0.13803947]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.23411917686462402, + 'timestamp': 333.7096626646817, + 'timestamp_carla': 333710, + 'timestamp_device': 4071923, + 'timestamp_stream': 333.7096626646817, + 'transform': [array([-4.36268300e-01, -1.81401615e+01, 1.41772358e-02]), + array([-0.06011932, -1.31204069, -0.00489724])]} +{'AngularVelocity': array([ 0.02413265, -0.01673112, 1.84924459]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.812530517578125, + 'FR_Wheel_Angle': -11.417667388916016, + 'Location': array([ 0.79502761, -18.46450615, 0.16852069]), + 'Rotation': array([-7.29600787e-02, 3.53918610e+01, -1.89208947e-02]), + 'Velocity': array([-0.30615157, -0.16325718, 0.00047764]), + 'brake_input': 0.0, + 'camera_location': array([-7.17036057, 12.20625305, 3.79789615]), + 'camera_rotation': array([-5.26091194, -3.4988358 , -0.14953774]), + 'current_gear_input': False, + 'focus_actor_dist': 5145.2626953125, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 729.39794922, 1930.39990234, 16.42520142]), + 'frame': 10161, + 'frame_number': 10161, + 'framesequence': 38760, + 'gaze_dir': array([ 0.99228668, -0.10199738, 0.06926727]), + 'gaze_origin': array([-3.13938856, 0.04557724, 0.05391541]), + 'gaze_valid': True, + 'gaze_vergence': 173.4613800048828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99241638, -0.09458923, 0.07833862]), + 'left_gaze_origin': array([-3.08222818, 3.2395463 , 0.06820221]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8054656982421875, + 'left_pupil_posn': array([-0.03890908, -0.06147659]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99215698, -0.10940552, 0.06019592]), + 'right_gaze_origin': array([-3.1965487 , -3.14839172, 0.0396286 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.800323486328125, + 'right_pupil_posn': array([-0.06012326, -0.13660967]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.21031509339809418, + 'timestamp': 333.74234806373715, + 'timestamp_carla': 333743, + 'timestamp_device': 4071957, + 'timestamp_stream': 333.74234806373715, + 'transform': [array([-4.35733169e-01, -1.81117687e+01, 1.41406823e-02]), + array([-0.06011932, -1.31147397, -0.004706 ])]} +{'AngularVelocity': array([ 0.02793499, -0.0290794 , 1.04819727]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.727693557739258, + 'FR_Wheel_Angle': -11.267295837402344, + 'Location': array([ 0.71915746, -18.50855827, 0.16857444]), + 'Rotation': array([-6.79330602e-02, 3.57651825e+01, -1.73645001e-02]), + 'Velocity': array([-2.47878000e-01, -1.34737149e-01, 1.40104297e-04]), + 'brake_input': 0.0, + 'camera_location': array([-7.11760521, 12.15730762, 3.76093197]), + 'camera_rotation': array([-5.51516581, -3.67781496, -0.32114571]), + 'current_gear_input': False, + 'focus_actor_dist': 5451.615234375, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 820.58422852, 2228.16992188, 16.33843994]), + 'frame': 10162, + 'frame_number': 10162, + 'framesequence': 38764, + 'gaze_dir': array([ 0.99268341, -0.09867859, 0.06867218]), + 'gaze_origin': array([-3.14036489, 0.04439545, 0.05740051]), + 'gaze_valid': True, + 'gaze_vergence': 185.2041778564453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99276733, -0.09196472, 0.07711792]), + 'left_gaze_origin': array([-3.08056521, 3.2390871 , 0.07067566]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8537445068359375, + 'left_pupil_posn': array([-0.03718871, -0.05938864]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99259949, -0.10539246, 0.06022644]), + 'right_gaze_origin': array([-3.20016479, -3.15029621, 0.04412537]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.834625244140625, + 'right_pupil_posn': array([-0.0578112 , -0.13472366]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.17856107652187347, + 'timestamp': 333.77479776367545, + 'timestamp_carla': 333775, + 'timestamp_device': 4071990, + 'timestamp_stream': 333.77479776367545, + 'transform': [array([-4.35095966e-01, -1.80823994e+01, 1.40950773e-02]), + array([-0.06011932, -1.311252 , -0.0044806 ])]} +{'AngularVelocity': array([-0.00574728, 0.0139295 , 0.1778927 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.605735778808594, + 'FR_Wheel_Angle': -10.291658401489258, + 'Location': array([ 0.65651238, -18.5454998 , 0.16867386]), + 'Rotation': array([-7.09519982e-02, 3.60372391e+01, -1.86462384e-02]), + 'Velocity': array([-0.30635184, -0.17387685, 0.0004671 ]), + 'brake_input': 0.0, + 'camera_location': array([-7.06003189, 12.10775948, 3.71245909]), + 'camera_rotation': array([-5.69053078, -3.92295218, -0.43450552]), + 'current_gear_input': False, + 'focus_actor_dist': 4443.72119140625, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 633.85235596, 1240.28930664, 15.16253662]), + 'frame': 10163, + 'frame_number': 10163, + 'framesequence': 38768, + 'gaze_dir': array([ 0.99294281, -0.09571075, 0.06832123]), + 'gaze_origin': array([-3.13496971, 0.04397278, 0.0575325 ]), + 'gaze_valid': True, + 'gaze_vergence': 173.78582763671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99343872, -0.08422852, 0.07723999]), + 'left_gaze_origin': array([-3.05744791, 3.2381196 , 0.06514435]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9105987548828125, + 'left_pupil_posn': array([-0.03693354, -0.05930638]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9924469 , -0.10719299, 0.05940247]), + 'right_gaze_origin': array([-3.21249104, -3.15017414, 0.04992066]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.826934814453125, + 'right_pupil_posn': array([-0.05503446, -0.13294208]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.15078964829444885, + 'timestamp': 333.8097988627851, + 'timestamp_carla': 333810, + 'timestamp_device': 4072023, + 'timestamp_stream': 333.8097988627851, + 'transform': [array([-4.34346318e-01, -1.80497112e+01, 1.39488028e-02]), + array([-0.06011932, -1.31120777, -0.00390686])]} +{'AngularVelocity': array([0.00769601, 0.0263532 , 0.61827683]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.346752166748047, + 'FR_Wheel_Angle': -9.260367393493652, + 'Location': array([ 0.59218472, -18.58452034, 0.16873084]), + 'Rotation': array([-6.80491701e-02, 3.63027687e+01, -1.76086407e-02]), + 'Velocity': array([-0.26747221, -0.15620324, 0.00048823]), + 'brake_input': 0.0, + 'camera_location': array([-6.98322964, 12.0477314 , 3.67324615]), + 'camera_rotation': array([-5.78784752, -4.23541164, -0.47756606]), + 'current_gear_input': False, + 'focus_actor_dist': 4070.08056640625, + 'focus_actor_name': 'Road_Curb_Town05_157', + 'focus_actor_pt': array([570.42840576, 874.74707031, 10.82413483]), + 'frame': 10164, + 'frame_number': 10164, + 'framesequence': 38772, + 'gaze_dir': array([ 0.9925766 , -0.09359741, 0.07645416]), + 'gaze_origin': array([-3.11211181, 0.03911896, 0.05106736]), + 'gaze_valid': True, + 'gaze_vergence': 228.9736328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99337769, -0.0813446 , 0.08097839]), + 'left_gaze_origin': array([-3.01139545, 3.23298192, 0.05133057]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.844512939453125, + 'left_pupil_posn': array([-0.03274447, -0.05557501]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99177551, -0.10585022, 0.07192993]), + 'right_gaze_origin': array([-3.21282816, -3.15474415, 0.05080414]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8774871826171875, + 'right_pupil_posn': array([-0.05085754, -0.13120425]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.13492026925086975, + 'timestamp': 333.8427806645632, + 'timestamp_carla': 333843, + 'timestamp_device': 4072057, + 'timestamp_stream': 333.8427806645632, + 'transform': [array([-4.33661640e-01, -1.80179749e+01, 1.38104726e-02]), + array([-0.06011932, -1.31094885, -0.00326483])]} +{'AngularVelocity': array([-0.00216528, -0.0027104 , 0.99637234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.503567695617676, + 'FR_Wheel_Angle': -7.439644813537598, + 'Location': array([ 0.54845381, -18.6118412 , 0.16877399]), + 'Rotation': array([-6.63757771e-02, 3.64627762e+01, -1.72424279e-02]), + 'Velocity': array([-2.03539044e-01, -1.24947973e-01, 1.79014198e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.92282104, 11.98029995, 3.65045381]), + 'camera_rotation': array([-5.885355 , -4.63312387, -0.42937994]), + 'current_gear_input': False, + 'focus_actor_dist': 4884.59423828125, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 739.15124512, 1675.625 , 16.41501617]), + 'frame': 10165, + 'frame_number': 10165, + 'framesequence': 38776, + 'gaze_dir': array([ 0.99312592, -0.08811951, 0.07602692]), + 'gaze_origin': array([-3.12205148, 0.03540039, 0.05333862]), + 'gaze_valid': True, + 'gaze_vergence': 208.16885375976562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99331665, -0.07945251, 0.08364868]), + 'left_gaze_origin': array([-3.04059601, 3.22818613, 0.06025086]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.751800537109375, + 'left_pupil_posn': array([-0.02651668, -0.05625057]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99293518, -0.0967865 , 0.06840515]), + 'right_gaze_origin': array([-3.20350671, -3.15738535, 0.04642639]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7805023193359375, + 'right_pupil_posn': array([-0.04849696, -0.13155437]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1269855797290802, + 'timestamp': 333.8753650635481, + 'timestamp_carla': 333876, + 'timestamp_device': 4072090, + 'timestamp_stream': 333.8753650635481, + 'transform': [array([-4.32962477e-01, -1.79858513e+01, 1.36491200e-02]), + array([-0.06011932, -1.31072712, -0.00252034])]} +{'AngularVelocity': array([ 0.00325849, -0.02295987, -0.08352574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.407203197479248, + 'FR_Wheel_Angle': -3.6572415828704834, + 'Location': array([ 0.50779206, -18.63845253, 0.16882332]), + 'Rotation': array([-6.63211346e-02, 3.65665283e+01, -1.71508752e-02]), + 'Velocity': array([-0.14645813, -0.0977582 , 0.00032001]), + 'brake_input': 0.0, + 'camera_location': array([-6.87615013, 11.90426064, 3.64063025]), + 'camera_rotation': array([-5.9597702 , -4.96501303, -0.3915534 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2162.96337890625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([ 225.13301086, -993.03637695, 79.75750732]), + 'frame': 10166, + 'frame_number': 10166, + 'framesequence': 38780, + 'gaze_dir': array([ 0.99349213, -0.08279419, 0.07662964]), + 'gaze_origin': array([-3.12128377, 0.03130265, 0.05255737]), + 'gaze_valid': True, + 'gaze_vergence': 130.171142578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99337769, -0.07301331, 0.08868408]), + 'left_gaze_origin': array([-3.05010843, 3.2265656 , 0.06319886]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.78204345703125, + 'left_pupil_posn': array([-0.02404785, -0.05718243]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99360657, -0.09257507, 0.0645752 ]), + 'right_gaze_origin': array([-3.19245934, -3.16396046, 0.04191589]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8759765625, + 'right_pupil_posn': array([-0.04189026, -0.13081038]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1269855797290802, + 'timestamp': 333.9080379642546, + 'timestamp_carla': 333908, + 'timestamp_device': 4072123, + 'timestamp_stream': 333.9080379642546, + 'transform': [array([-4.32240427e-01, -1.79529457e+01, 1.34704206e-02]), + array([-0.06011932, -1.31052601, -0.00171437])]} +{'AngularVelocity': array([ 0.00528103, -0.00064554, 0.28350061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.3091561794281006, + 'FR_Wheel_Angle': -2.259113311767578, + 'Location': array([ 0.47594458, -18.6607933 , 0.16886669]), + 'Rotation': array([-6.67719245e-02, 3.66074295e+01, -1.77307073e-02]), + 'Velocity': array([-0.11888138, -0.08438693, 0.00017735]), + 'brake_input': 0.0, + 'camera_location': array([-6.82993889, 11.84802914, 3.63940096]), + 'camera_rotation': array([-6.05074835, -5.2466898 , -0.41583234]), + 'current_gear_input': False, + 'focus_actor_dist': 2159.848388671875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([ 225.51727295, -993.03466797, 78.42753601]), + 'frame': 10167, + 'frame_number': 10167, + 'framesequence': 38784, + 'gaze_dir': array([ 0.99358368, -0.08046722, 0.07857513]), + 'gaze_origin': array([-3.13225436, 0.02756958, 0.05508423]), + 'gaze_valid': True, + 'gaze_vergence': 107.333984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99310303, -0.07592773, 0.08932495]), + 'left_gaze_origin': array([-3.07324553, 3.22407556, 0.0699646 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.877166748046875, + 'left_pupil_posn': array([-0.01980698, -0.05602908]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99406433, -0.08500671, 0.06782532]), + 'right_gaze_origin': array([-3.19126296, -3.16893649, 0.04020386]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8053741455078125, + 'right_pupil_posn': array([-0.03951615, -0.13162994]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1269855797290802, + 'timestamp': 333.9408487640321, + 'timestamp_carla': 333941, + 'timestamp_device': 4072156, + 'timestamp_stream': 333.9408487640321, + 'transform': [array([-4.31507707e-01, -1.79193554e+01, 1.32643795e-02]), + array([-6.01193234e-02, -1.31031132e+00, -7.99125351e-04])]} +{'AngularVelocity': array([-0.02486998, 0.0396321 , 0.28725559]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.8373792171478271, + 'FR_Wheel_Angle': -1.5447722673416138, + 'Location': array([ 0.4428758 , -18.68447304, 0.16891316]), + 'Rotation': array([-7.43397772e-02, 3.66372910e+01, -1.91345196e-02]), + 'Velocity': array([-0.23150699, -0.16480297, -0.0005793 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.79338455, 11.79740238, 3.63070798]), + 'camera_rotation': array([-6.07543945, -5.48666048, -0.49078956]), + 'current_gear_input': False, + 'focus_actor_dist': 4483.47900390625, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 682.57904053, 1287.70068359, 15.59820557]), + 'frame': 10168, + 'frame_number': 10168, + 'framesequence': 38788, + 'gaze_dir': array([ 0.99429321, -0.07212067, 0.07656097]), + 'gaze_origin': array([-3.13797641, 0.02576523, 0.05628815]), + 'gaze_valid': True, + 'gaze_vergence': 139.54306030273438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99436951, -0.0589447 , 0.0879364 ]), + 'left_gaze_origin': array([-3.0746448 , 3.22335672, 0.07016297]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8353424072265625, + 'left_pupil_posn': array([-0.01945394, -0.05694532]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99421692, -0.08529663, 0.06518555]), + 'right_gaze_origin': array([-3.20130777, -3.17182612, 0.04241333]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.78729248046875, + 'right_pupil_posn': array([-0.03149217, -0.1323688 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.11903563141822815, + 'timestamp': 333.97497426345944, + 'timestamp_carla': 333975, + 'timestamp_device': 4072190, + 'timestamp_stream': 333.97497426345944, + 'transform': [array([-4.30740505e-01, -1.78840332e+01, 1.29985996e-02]), + array([-6.01193234e-02, -1.31006944e+00, 3.35700548e-04])]} +{'AngularVelocity': array([0.00264953, 0.00654299, 1.09762478]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.49098145961761475, + 'FR_Wheel_Angle': 0.49334150552749634, + 'Location': array([ 0.41240761, -18.70673943, 0.16893448]), + 'Rotation': array([-6.08843043e-02, 3.66430244e+01, -1.87072717e-02]), + 'Velocity': array([-0.01427828, -0.00997736, 0.0005786 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.78072262, 11.74485207, 3.6004622 ]), + 'camera_rotation': array([-6.09972763, -5.58597326, -0.54969096]), + 'current_gear_input': False, + 'focus_actor_dist': 4112.1064453125, + 'focus_actor_name': 'Road_Sidewalk_Town05_159', + 'focus_actor_pt': array([593.97247314, 929.87939453, 15.23272705]), + 'frame': 10169, + 'frame_number': 10169, + 'framesequence': 38792, + 'gaze_dir': array([ 0.99427032, -0.07156372, 0.07780457]), + 'gaze_origin': array([-3.13380504, 0.02480469, 0.05528565]), + 'gaze_valid': True, + 'gaze_vergence': 152.56849670410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9942627 , -0.06022644, 0.08828735]), + 'left_gaze_origin': array([-3.06711292, 3.22209477, 0.06790314]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.851593017578125, + 'left_pupil_posn': array([-0.01772279, -0.05635953]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99427795, -0.082901 , 0.06732178]), + 'right_gaze_origin': array([-3.20049739, -3.17248559, 0.04266815]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.825408935546875, + 'right_pupil_posn': array([-0.03149217, -0.13193393]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 334.0082766637206, + 'timestamp_carla': 334009, + 'timestamp_device': 4072223, + 'timestamp_stream': 334.0082766637206, + 'transform': [array([-4.29982752e-01, -1.78492603e+01, 1.27446651e-02]), + array([-0.06011932, -1.30982077, 0.00146485])]} +{'AngularVelocity': array([-0.00662913, 0.01544887, 1.25235248]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2620377242565155, + 'FR_Wheel_Angle': 0.26398515701293945, + 'Location': array([ 0.40976545, -18.7086525 , 0.16895282]), + 'Rotation': array([-6.61298856e-02, 3.66411285e+01, -1.90124456e-02]), + 'Velocity': array([-0.01038304, -0.00729725, -0.00024854]), + 'brake_input': 0.0, + 'camera_location': array([-6.77528858, 11.70912743, 3.57828641]), + 'camera_rotation': array([-6.17651224, -5.60736609, -0.60397714]), + 'current_gear_input': False, + 'focus_actor_dist': 4223.01416015625, + 'focus_actor_name': 'Road_Sidewalk_Town05_159', + 'focus_actor_pt': array([ 620.42755127, 1041.33789062, 14.95980072]), + 'frame': 10170, + 'frame_number': 10170, + 'framesequence': 38796, + 'gaze_dir': array([ 0.9943161 , -0.07081604, 0.07824707]), + 'gaze_origin': array([-3.12686563, 0.02372055, 0.05368118]), + 'gaze_valid': True, + 'gaze_vergence': 172.7896728515625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99432373, -0.0605011 , 0.08746338]), + 'left_gaze_origin': array([-3.05307627, 3.22045159, 0.0637558 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8588104248046875, + 'left_pupil_posn': array([-0.01591599, -0.05595016]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99430847, -0.08113098, 0.06903076]), + 'right_gaze_origin': array([-3.20065475, -3.17301035, 0.04360657]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.824859619140625, + 'right_pupil_posn': array([-0.03122216, -0.13159215]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.04141396284103, + 'timestamp_carla': 334042, + 'timestamp_device': 4072256, + 'timestamp_stream': 334.04141396284103, + 'transform': [array([-4.29222256e-01, -1.78143139e+01, 1.25191975e-02]), + array([-0.06011932, -1.30958545, 0.00247193])]} +{'AngularVelocity': array([-7.25107267e-04, 5.76272048e-03, 1.20791245e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.35626915097236633, + 'FR_Wheel_Angle': 0.37927237153053284, + 'Location': array([ 0.40706137, -18.71067619, 0.16896209]), + 'Rotation': array([-6.83565289e-02, 3.66431847e+01, -1.91040020e-02]), + 'Velocity': array([-0.01310476, -0.00957075, 0.00043774]), + 'brake_input': 0.0, + 'camera_location': array([-6.77200127, 11.68218613, 3.57921839]), + 'camera_rotation': array([-6.25594044, -5.5897336 , -0.67000985]), + 'current_gear_input': False, + 'focus_actor_dist': 4075.84765625, + 'focus_actor_name': 'Road_Sidewalk_Town05_159', + 'focus_actor_pt': array([591.13104248, 900.56933594, 15.23835754]), + 'frame': 10171, + 'frame_number': 10171, + 'framesequence': 38800, + 'gaze_dir': array([ 0.99542999, -0.04693604, 0.08171082]), + 'gaze_origin': array([-3.12160444e+00, 2.17285170e-03, 6.38443083e-02]), + 'gaze_valid': True, + 'gaze_vergence': 199.6128387451172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99571228, -0.03256226, 0.08656311]), + 'left_gaze_origin': array([-3.04427814, 3.19531417, 0.07219544]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9178314208984375, + 'left_pupil_posn': array([ 0.00809765, -0.04630399]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99514771, -0.06130981, 0.07685852]), + 'right_gaze_origin': array([-3.19893074, -3.19096851, 0.05549316]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8696746826171875, + 'right_pupil_posn': array([-0.00904238, -0.12390351]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.07620776444674, + 'timestamp_carla': 334077, + 'timestamp_device': 4072290, + 'timestamp_stream': 334.07620776444674, + 'transform': [array([-4.28423464e-01, -1.77774696e+01, 1.22595215e-02]), + array([-0.06011932, -1.30932307, 0.00357056])]} +{'AngularVelocity': array([-0.0327622 , 0.05046556, -0.5105778 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.38570624589920044, + 'FR_Wheel_Angle': 0.3871791958808899, + 'Location': array([ 0.38834617, -18.72459793, 0.16904697]), + 'Rotation': array([-8.15114751e-02, 3.66281700e+01, -1.89208928e-02]), + 'Velocity': array([-0.24802333, -0.18541141, 0.00107852]), + 'brake_input': 0.0, + 'camera_location': array([-6.7694006 , 11.65322304, 3.58638215]), + 'camera_rotation': array([-6.26906157, -5.58541775, -0.71015048]), + 'current_gear_input': False, + 'focus_actor_dist': 4391.2607421875, + 'focus_actor_name': 'Road_Grass_Town05_119', + 'focus_actor_pt': array([ 547.47088623, 1232.78222656, 15.15281677]), + 'frame': 10172, + 'frame_number': 10172, + 'framesequence': 38804, + 'gaze_dir': array([ 0.99571228, -0.01914215, 0.08921814]), + 'gaze_origin': array([-3.1152513 , -0.01649246, 0.06759949]), + 'gaze_valid': True, + 'gaze_vergence': 170.53546142578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99674988, -0.00741577, 0.08015442]), + 'left_gaze_origin': array([-2.98299122, 3.17442942, 0.05709534]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.890869140625, + 'left_pupil_posn': array([ 0.0328269 , -0.03757787]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99467468, -0.03086853, 0.09828186]), + 'right_gaze_origin': array([-3.24751139, -3.20741415, 0.07810364]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8166656494140625, + 'right_pupil_posn': array([ 0.01185155, -0.11974239]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.1086343638599, + 'timestamp_carla': 334109, + 'timestamp_device': 4072323, + 'timestamp_stream': 334.1086343638599, + 'transform': [array([-4.27675456e-01, -1.77429447e+01, 1.20645994e-02]), + array([-0.06011932, -1.30908453, 0.0044861 ])]} +{'AngularVelocity': array([ 0.0269793 , -0.03032017, -0.2332501 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3840758204460144, + 'FR_Wheel_Angle': 0.3852604329586029, + 'Location': array([ 0.31801856, -18.77705002, 0.16912089]), + 'Rotation': array([-8.56027529e-02, 3.65965347e+01, -1.89208984e-02]), + 'Velocity': array([-4.45769995e-01, -3.33254188e-01, 2.56919848e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.77617455, 11.61803246, 3.59311581]), + 'camera_rotation': array([-6.23262262, -5.57211113, -0.73470807]), + 'current_gear_input': False, + 'focus_actor_dist': 4220.533203125, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([ 403.45349121, 1086.99609375, 51.69004822]), + 'frame': 10173, + 'frame_number': 10173, + 'framesequence': 38808, + 'gaze_dir': array([ 0.99569702, -0.01888275, 0.08937836]), + 'gaze_origin': array([-3.10868311, -0.01766128, 0.06508255]), + 'gaze_valid': True, + 'gaze_vergence': 170.53195190429688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99673462, -0.00663757, 0.08045959]), + 'left_gaze_origin': array([-2.97769332, 3.17482018, 0.05444641]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.891143798828125, + 'left_pupil_posn': array([ 0.03247976, -0.03838789]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99465942, -0.03112793, 0.09829712]), + 'right_gaze_origin': array([-3.2396729 , -3.21014261, 0.07571869]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8431243896484375, + 'right_pupil_posn': array([ 0.01385069, -0.11971784]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.1408240646124, + 'timestamp_carla': 334141, + 'timestamp_device': 4072356, + 'timestamp_stream': 334.1408240646124, + 'transform': [array([-4.26924735e-01, -1.77084942e+01, 1.18937297e-02]), + array([-0.06011932, -1.30885279, 0.00527955])]} +{'AngularVelocity': array([ 0.0253984 , -0.03384014, -0.10209485]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.38409653306007385, + 'FR_Wheel_Angle': 0.38542795181274414, + 'Location': array([ 0.1719548 , -18.88643456, 0.1693486 ]), + 'Rotation': array([-8.00498128e-02, 3.66016731e+01, -1.89208928e-02]), + 'Velocity': array([-0.61849755, -0.46307689, 0.00080293]), + 'brake_input': 0.0, + 'camera_location': array([-6.76912403, 11.57659245, 3.58807635]), + 'camera_rotation': array([-6.16978455, -5.64968443, -0.78408974]), + 'current_gear_input': False, + 'focus_actor_dist': 4217.603515625, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([ 401.269104 , 1087.88208008, 55.02532196]), + 'frame': 10174, + 'frame_number': 10174, + 'framesequence': 38812, + 'gaze_dir': array([ 0.99559784, -0.01802826, 0.09069824]), + 'gaze_origin': array([-3.1047318 , -0.0182106 , 0.06312485]), + 'gaze_valid': True, + 'gaze_vergence': 197.7302703857422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99642944, -0.00523376, 0.08413696]), + 'left_gaze_origin': array([-2.97711349, 3.17498922, 0.05335389]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9380645751953125, + 'left_pupil_posn': array([ 0.03247976, -0.03942347]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99476624, -0.03082275, 0.09725952]), + 'right_gaze_origin': array([-3.23235011, -3.21141076, 0.07289582]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8553314208984375, + 'right_pupil_posn': array([ 0.01510429, -0.11910999]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.1756453625858, + 'timestamp_carla': 334176, + 'timestamp_device': 4072390, + 'timestamp_stream': 334.1756453625858, + 'transform': [array([-4.26110685e-01, -1.76711140e+01, 1.16991233e-02]), + array([-0.06011932, -1.30861068, 0.00607301])]} +{'AngularVelocity': array([ 0.00539128, -0.01962418, -0.30378896]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.8818112015724182, + 'FR_Wheel_Angle': 1.1454075574874878, + 'Location': array([ 5.02286898e-03, -1.90113125e+01, 1.69470206e-01]), + 'Rotation': array([-7.53779635e-02, 3.65679092e+01, -1.84631310e-02]), + 'Velocity': array([-0.70025641, -0.52885002, 0.00113496]), + 'brake_input': 0.0, + 'camera_location': array([-6.76200104, 11.53204823, 3.5847342 ]), + 'camera_rotation': array([-6.13028574, -5.72450829, -0.80493319]), + 'current_gear_input': False, + 'focus_actor_dist': 4213.4453125, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([ 403.30102539, 1087.05810547, 65.20683289]), + 'frame': 10175, + 'frame_number': 10175, + 'framesequence': 38816, + 'gaze_dir': array([ 0.99575806, -0.01831818, 0.08880615]), + 'gaze_origin': array([-3.08955693, -0.02051926, 0.05737915]), + 'gaze_valid': True, + 'gaze_vergence': 180.96664428710938, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9967041 , -0.0059967 , 0.08070374]), + 'left_gaze_origin': array([-2.97711349, 3.17487979, 0.05295258]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0, + 'left_pupil_posn': array([ 0.032619 , -0.03993165]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99481201, -0.03063965, 0.09690857]), + 'right_gaze_origin': array([-3.20200062, -3.21591806, 0.06180573]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.992401123046875, + 'right_pupil_posn': array([ 0.0173763 , -0.12239313]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00018311107123736292, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.2095775641501, + 'timestamp_carla': 334210, + 'timestamp_device': 4072423, + 'timestamp_stream': 334.2095775641501, + 'transform': [array([-4.25302714e-01, -1.76346169e+01, 1.15325162e-02]), + array([-0.06011932, -1.30841291, 0.00680542])]} +{'AngularVelocity': array([ 0.00854549, -0.0247246 , -0.84861934]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.773916721343994, + 'FR_Wheel_Angle': 3.3043835163116455, + 'Location': array([ -0.14836034, -19.12844849, 0.1696178 ]), + 'Rotation': array([-6.94630221e-02, 3.64443169e+01, -1.68762188e-02]), + 'Velocity': array([-0.66066146, -0.51863003, 0.0009427 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.74312687, 11.48589706, 3.57929707]), + 'camera_rotation': array([-6.11025953, -5.85674858, -0.86483985]), + 'current_gear_input': False, + 'focus_actor_dist': 4209.68505859375, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([ 409.5501709 , 1086.0546875 , 60.05702972]), + 'frame': 10176, + 'frame_number': 10176, + 'framesequence': 38820, + 'gaze_dir': array([ 0.99563599, -0.01643372, 0.09072113]), + 'gaze_origin': array([-3.08736968, -0.0218071 , 0.05563431]), + 'gaze_valid': True, + 'gaze_vergence': 236.52114868164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99601746, -0.00315857, 0.08892822]), + 'left_gaze_origin': array([-2.97735286, 3.17484283, 0.05297547]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9994659423828125, + 'left_pupil_posn': array([ 0.03296423, -0.04148531]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99525452, -0.02970886, 0.09251404]), + 'right_gaze_origin': array([-3.1973865 , -3.21845722, 0.05829316]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9234619140625, + 'right_pupil_posn': array([ 0.02004933, -0.12119603]), + 'right_pupil_posn_valid': True, + 'steering_input': -7.32444241293706e-05, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.24110416322947, + 'timestamp_carla': 334241, + 'timestamp_device': 4072456, + 'timestamp_stream': 334.24110416322947, + 'transform': [array([-4.24508035e-01, -1.76004982e+01, 1.14459991e-02]), + array([-0.060092 , -1.30839598, 0.00726319])]} +{'AngularVelocity': array([ 0.02964165, 0.00167092, -1.25216269]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.029139518737793, + 'FR_Wheel_Angle': 5.500698566436768, + 'Location': array([ -0.30065984, -19.24823761, 0.16981433]), + 'Rotation': array([-6.48867935e-02, 3.61836090e+01, -1.72119122e-02]), + 'Velocity': array([-0.56790763, -0.45776448, 0.00078105]), + 'brake_input': 0.0, + 'camera_location': array([-6.74179077, 11.44771385, 3.58110523]), + 'camera_rotation': array([-6.1725235 , -5.97251511, -0.89845222]), + 'current_gear_input': False, + 'focus_actor_dist': 4206.9560546875, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([ 411.5703125 , 1086.86474609, 69.61282349]), + 'frame': 10177, + 'frame_number': 10177, + 'framesequence': 38824, + 'gaze_dir': array([ 0.99568176, -0.01644135, 0.09046936]), + 'gaze_origin': array([-3.09032226, -0.02233582, 0.05559006]), + 'gaze_valid': True, + 'gaze_vergence': 255.78541564941406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99604797, -0.00421143, 0.08865356]), + 'left_gaze_origin': array([-2.98441935, 3.17438698, 0.0534256 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.016632080078125, + 'left_pupil_posn': array([ 0.03361607, -0.04256153]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99531555, -0.02867126, 0.09228516]), + 'right_gaze_origin': array([-3.19622493, -3.21905828, 0.05775452]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8670654296875, + 'right_pupil_posn': array([ 0.02004933, -0.12119603]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.10316624492406845, + 'timestamp': 334.2752082645893, + 'timestamp_carla': 334276, + 'timestamp_device': 4072490, + 'timestamp_stream': 334.2752082645893, + 'transform': [array([-4.23629910e-01, -1.75635929e+01, 1.13057513e-02]), + array([-0.060092 , -1.3084476 , 0.00784302])]} +{'AngularVelocity': array([ 0.02748247, 0.00671089, -1.39038396]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.931606769561768, + 'FR_Wheel_Angle': 6.411029815673828, + 'Location': array([ -0.4332473 , -19.35438538, 0.16999355]), + 'Rotation': array([-6.30767941e-02, 3.58586998e+01, -1.84631292e-02]), + 'Velocity': array([-0.46720558, -0.38203874, 0.0011025 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.74732971, 11.42084503, 3.59809303]), + 'camera_rotation': array([-6.18894339, -5.99296331, -0.89847428]), + 'current_gear_input': False, + 'focus_actor_dist': 6584.31103515625, + 'focus_actor_name': 'BP_RepSpline76', + 'focus_actor_pt': array([ 763.5769043 , 3440.99633789, 21.9657135 ]), + 'frame': 10178, + 'frame_number': 10178, + 'framesequence': 38828, + 'gaze_dir': array([ 0.99627686, -0.01158905, 0.08444214]), + 'gaze_origin': array([-3.10805607, -0.02832489, 0.0594307 ]), + 'gaze_valid': True, + 'gaze_vergence': 265.87713623046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([9.96459961e-01, 4.11987305e-04, 8.38928223e-02]), + 'left_gaze_origin': array([-2.99604058, 3.16818881, 0.05543976]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.06317138671875, + 'left_pupil_posn': array([ 0.03952932, -0.04594266]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99609375, -0.02359009, 0.08499146]), + 'right_gaze_origin': array([-3.22007155, -3.2248385 , 0.06342164]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.7957000732421875, + 'right_pupil_posn': array([ 0.02605736, -0.12364316]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.13888761401176453, + 'timestamp': 334.30776346474886, + 'timestamp_carla': 334308, + 'timestamp_device': 4072523, + 'timestamp_stream': 334.30776346474886, + 'transform': [array([-4.22779828e-01, -1.75282154e+01, 1.12290950e-02]), + array([-0.060092 , -1.3085196 , 0.00820924])]} +{'AngularVelocity': array([-0.06831255, 0.01903447, -1.31169283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.059622764587402, + 'FR_Wheel_Angle': 9.429352760314941, + 'Location': array([ -0.53238797, -19.43460464, 0.17012207]), + 'Rotation': array([-6.53990582e-02, 3.55645332e+01, -1.78527832e-02]), + 'Velocity': array([-0.4459188 , -0.38142252, 0.00131774]), + 'brake_input': 0.0, + 'camera_location': array([-6.74394894, 11.39946461, 3.59322071]), + 'camera_rotation': array([-6.23389292, -6.0078578 , -1.06511676]), + 'current_gear_input': False, + 'focus_actor_dist': 4200.36474609375, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([ 400.29498291, 1088.27661133, 37.68523407]), + 'frame': 10179, + 'frame_number': 10179, + 'framesequence': 38832, + 'gaze_dir': array([0.98605347, 0.14876556, 0.07357788]), + 'gaze_origin': array([-3.10583067, -0.14433976, 0.04914551]), + 'gaze_valid': True, + 'gaze_vergence': 261.3244323730469, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98419189, 0.1592865 , 0.07728577]), + 'left_gaze_origin': array([-3.01416039, 3.04839325, 0.05229187]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9091033935546875, + 'left_pupil_posn': array([ 0.1761874 , -0.05805492]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98791504, 0.13824463, 0.06987 ]), + 'right_gaze_origin': array([-3.19750094, -3.33707285, 0.04599915]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.859466552734375, + 'right_pupil_posn': array([ 0.15833879, -0.13581669]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.15475699305534363, + 'timestamp': 334.34150026366115, + 'timestamp_carla': 334342, + 'timestamp_device': 4072556, + 'timestamp_stream': 334.34150026366115, + 'transform': [array([-4.21894968e-01, -1.74914246e+01, 1.11544989e-02]), + array([-0.060092 , -1.30860507, 0.00851441])]} +{'AngularVelocity': array([ 0.03434315, 0.01699584, -2.55182886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.526447296142578, + 'FR_Wheel_Angle': 16.10552406311035, + 'Location': array([ -0.62607825, -19.51503563, 0.17024398]), + 'Rotation': array([-6.55288324e-02, 3.50989723e+01, -1.57470684e-02]), + 'Velocity': array([-0.37743494, -0.35209316, 0.00075812]), + 'brake_input': 0.0, + 'camera_location': array([-6.73788738, 11.37843704, 3.59001851]), + 'camera_rotation': array([-6.21545124, -6.04297543, -1.15413761]), + 'current_gear_input': False, + 'focus_actor_dist': 3947.010986328125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-267.01638794, 878.1784668 , 14.57440948]), + 'frame': 10180, + 'frame_number': 10180, + 'framesequence': 38836, + 'gaze_dir': array([0.961586 , 0.2673111 , 0.05992889]), + 'gaze_origin': array([-3.13130069, -0.24276429, 0.03889237]), + 'gaze_valid': True, + 'gaze_vergence': 177.06411743164062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95704651, 0.28382874, 0.05909729]), + 'left_gaze_origin': array([-3.0366838 , 2.93725753, 0.04210053]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.119140625, + 'left_pupil_posn': array([ 0.29142666, -0.07446325]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96612549, 0.25079346, 0.0607605 ]), + 'right_gaze_origin': array([-3.22591734, -3.42278624, 0.03568421]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9729156494140625, + 'right_pupil_posn': array([ 0.26297081, -0.15832472]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 334.3755881637335, + 'timestamp_carla': 334376, + 'timestamp_device': 4072590, + 'timestamp_stream': 334.3755881637335, + 'transform': [array([-4.20997471e-01, -1.74539948e+01, 1.11206239e-02]), + array([-0.060092 , -1.30867672, 0.00863648])]} +{'AngularVelocity': array([ 0.06661851, 0.03774741, -2.702245 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.915067672729492, + 'FR_Wheel_Angle': 21.675798416137695, + 'Location': array([ -0.68823743, -19.57222176, 0.17028175]), + 'Rotation': array([-6.56995848e-02, 3.46272011e+01, -1.62963830e-02]), + 'Velocity': array([-3.44926089e-01, -3.36623639e-01, -2.34699237e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.73620415, 11.36776352, 3.58893251]), + 'camera_rotation': array([-6.15425301, -6.0512929 , -1.17110801]), + 'current_gear_input': False, + 'focus_actor_dist': 3524.833984375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-6.82556946e+02, 4.24599365e+02, -1.52587891e-05]), + 'frame': 10181, + 'frame_number': 10181, + 'framesequence': 38840, + 'gaze_dir': array([0.96084595, 0.27024841, 0.05891418]), + 'gaze_origin': array([-3.13203144, -0.246402 , 0.03940811]), + 'gaze_valid': True, + 'gaze_vergence': 189.43077087402344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95657349, 0.28565979, 0.05787659]), + 'left_gaze_origin': array([-3.03710032, 2.93733239, 0.04242707]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1426544189453125, + 'left_pupil_posn': array([ 0.29283261, -0.07466161]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96511841, 0.25483704, 0.05995178]), + 'right_gaze_origin': array([-3.22696233, -3.4301362 , 0.03638916]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0366363525390625, + 'right_pupil_posn': array([ 0.26877367, -0.15861213]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 334.40791296213865, + 'timestamp_carla': 334408, + 'timestamp_device': 4072623, + 'timestamp_stream': 334.40791296213865, + 'transform': [array([-4.20138091e-01, -1.74180679e+01, 1.11640925e-02]), + array([-0.060092 , -1.30874169, 0.00848389])]} +{'AngularVelocity': array([ 0.00813961, -0.00772821, -4.67078495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.873703002929688, + 'FR_Wheel_Angle': 26.401552200317383, + 'Location': array([ -0.81623161, -19.6959095 , 0.17044327]), + 'Rotation': array([-6.93673939e-02, 3.33497086e+01, -1.51062012e-02]), + 'Velocity': array([-3.76588762e-01, -4.07061875e-01, 3.94058225e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.74460697, 11.37210083, 3.58877659]), + 'camera_rotation': array([-6.15256596, -6.06893635, -1.15335703]), + 'current_gear_input': False, + 'focus_actor_dist': 3546.35400390625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-6.95651978e+02, 4.48203857e+02, -2.28881836e-04]), + 'frame': 10182, + 'frame_number': 10182, + 'framesequence': 38844, + 'gaze_dir': array([0.96107483, 0.26980591, 0.05690002]), + 'gaze_origin': array([-3.13167715, -0.2470192 , 0.04030457]), + 'gaze_valid': True, + 'gaze_vergence': 173.40003967285156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95690918, 0.28559875, 0.05232239]), + 'left_gaze_origin': array([-3.03680587, 2.93808913, 0.0431839 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.14013671875, + 'left_pupil_posn': array([ 0.29201949, -0.07355273]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96524048, 0.25401306, 0.06147766]), + 'right_gaze_origin': array([-3.22654891, -3.43212748, 0.03742523]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.981842041015625, + 'right_pupil_posn': array([ 0.27015615, -0.15966463]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 334.4421640634537, + 'timestamp_carla': 334442, + 'timestamp_device': 4072656, + 'timestamp_stream': 334.4421640634537, + 'transform': [array([-4.19219047e-01, -1.73796597e+01, 1.11890221e-02]), + array([-0.060092 , -1.30881011, 0.00833131])]} +{'AngularVelocity': array([-0.08637085, -0.03886341, -6.32289076]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.48053741455078, + 'FR_Wheel_Angle': 30.222389221191406, + 'Location': array([ -0.9250766 , -19.80438995, 0.17059608]), + 'Rotation': array([-6.92444518e-02, 3.20250969e+01, -1.44653339e-02]), + 'Velocity': array([-0.39809978, -0.45872885, 0.00059762]), + 'brake_input': 0.0, + 'camera_location': array([-6.75153637, 11.3759079 , 3.59500003]), + 'camera_rotation': array([-6.17155361, -5.99905014, -1.09693527]), + 'current_gear_input': False, + 'focus_actor_dist': 3365.80224609375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-6.67361450e+02, 2.73292725e+02, 1.52587891e-05]), + 'frame': 10183, + 'frame_number': 10183, + 'framesequence': 38848, + 'gaze_dir': array([0.96097565, 0.27041626, 0.05609131]), + 'gaze_origin': array([-3.13125253, -0.2475075 , 0.04159623]), + 'gaze_valid': True, + 'gaze_vergence': 188.6518096923828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9571228 , 0.28497314, 0.05195618]), + 'left_gaze_origin': array([-3.03646255, 2.93891764, 0.04393311]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1341400146484375, + 'left_pupil_posn': array([ 0.29209375, -0.07343638]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96482849, 0.25585938, 0.06022644]), + 'right_gaze_origin': array([-3.22604227, -3.43393278, 0.03925934]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0413970947265625, + 'right_pupil_posn': array([ 0.27113545, -0.15846324]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 334.4754243642092, + 'timestamp_carla': 334476, + 'timestamp_device': 4072690, + 'timestamp_stream': 334.4754243642092, + 'transform': [array([-4.18315113e-01, -1.73418922e+01, 1.12528224e-02]), + array([-0.060092 , -1.3088814 , 0.00805665])]} +{'AngularVelocity': array([ 3.70147708e-03, -7.20300945e-03, -5.95954990e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.586463928222656, + 'FR_Wheel_Angle': 31.522348403930664, + 'Location': array([ -1.00913322, -19.88825417, 0.17072822]), + 'Rotation': array([-7.01596960e-02, 3.09158840e+01, -1.50146475e-02]), + 'Velocity': array([-0.42847988, -0.47266895, 0.00089747]), + 'brake_input': 0.0, + 'camera_location': array([-6.77127647, 11.3956213 , 3.60599518]), + 'camera_rotation': array([-6.1390214 , -5.92991638, -1.09323025]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.14306640625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-6.58121033e+02, 1.69570801e+02, 4.57763672e-05]), + 'frame': 10184, + 'frame_number': 10184, + 'framesequence': 38852, + 'gaze_dir': array([0.96151733, 0.26857758, 0.05631256]), + 'gaze_origin': array([-3.13098693, -0.24747774, 0.04185486]), + 'gaze_valid': True, + 'gaze_vergence': 234.9777069091797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95838928, 0.28039551, 0.05322266]), + 'left_gaze_origin': array([-3.03618622, 2.93981194, 0.0442749 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.114349365234375, + 'left_pupil_posn': array([ 0.29180849, -0.07343638]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96464539, 0.25675964, 0.05940247]), + 'right_gaze_origin': array([-3.2257874 , -3.43476725, 0.03943482]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0394287109375, + 'right_pupil_posn': array([ 0.27002621, -0.15779769]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 334.5091799646616, + 'timestamp_carla': 334509, + 'timestamp_device': 4072723, + 'timestamp_stream': 334.5091799646616, + 'transform': [array([-4.17389989e-01, -1.73031139e+01, 1.13118738e-02]), + array([-0.060092 , -1.30893588, 0.00778199])]} +{'AngularVelocity': array([ 0.04077118, 0.00698361, -5.68539476]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.00279998779297, + 'FR_Wheel_Angle': 32.38385772705078, + 'Location': array([ -1.11224282, -19.98799896, 0.17082542]), + 'Rotation': array([-6.68607205e-02, 2.95095634e+01, -1.86767522e-02]), + 'Velocity': array([-0.40550116, -0.42623588, 0.00065813]), + 'brake_input': 0.0, + 'camera_location': array([-6.77688885, 11.41694927, 3.62375045]), + 'camera_rotation': array([-6.09054089, -5.83360767, -1.09663582]), + 'current_gear_input': False, + 'focus_actor_dist': 3310.048583984375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-663.20776367, 225.07617188, 0. ]), + 'frame': 10185, + 'frame_number': 10185, + 'framesequence': 38856, + 'gaze_dir': array([0.96122742, 0.26968384, 0.05640411]), + 'gaze_origin': array([-3.13071465, -0.24706346, 0.04203796]), + 'gaze_valid': True, + 'gaze_vergence': 262.0001525878906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95857239, 0.27987671, 0.05293274]), + 'left_gaze_origin': array([-3.03577733, 2.94147658, 0.04455566]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0965576171875, + 'left_pupil_posn': array([ 0.29165304, -0.07303143]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96388245, 0.25949097, 0.05987549]), + 'right_gaze_origin': array([-3.22565174, -3.43560362, 0.03952027]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0278472900390625, + 'right_pupil_posn': array([ 0.27041376, -0.15779769]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 334.5420134626329, + 'timestamp_carla': 334542, + 'timestamp_device': 4072756, + 'timestamp_stream': 334.5420134626329, + 'transform': [array([-4.16476727e-01, -1.72648869e+01, 1.13855172e-02]), + array([-0.060092 , -1.30900407, 0.00747681])]} +{'AngularVelocity': array([-2.51411684e-02, 5.64479176e-03, -5.78976727e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.478334426879883, + 'FR_Wheel_Angle': 32.92287063598633, + 'Location': array([ -1.22393119, -20.09215164, 0.17096676]), + 'Rotation': array([-6.65601864e-02, 2.79549809e+01, -1.77001934e-02]), + 'Velocity': array([-0.39563888, -0.4045577 , 0.00126214]), + 'brake_input': 0.0, + 'camera_location': array([-6.78256226, 11.43039703, 3.62519073]), + 'camera_rotation': array([-6.06342506, -5.75105333, -1.07145262]), + 'current_gear_input': False, + 'focus_actor_dist': 3390.168212890625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-6.84095642e+02, 3.06914307e+02, 1.52587891e-05]), + 'frame': 10186, + 'frame_number': 10186, + 'framesequence': 38860, + 'gaze_dir': array([0.96076202, 0.27135468, 0.05659485]), + 'gaze_origin': array([-3.130481 , -0.24633639, 0.04219132]), + 'gaze_valid': True, + 'gaze_vergence': 293.5113525390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95881653, 0.27914429, 0.0521698 ]), + 'left_gaze_origin': array([-3.03536701, 2.94360995, 0.04467621]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.070037841796875, + 'left_pupil_posn': array([ 0.29165304, -0.07250941]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96270752, 0.26356506, 0.0610199 ]), + 'right_gaze_origin': array([-3.22559524, -3.43628263, 0.03970642]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0139312744140625, + 'right_pupil_posn': array([ 0.27063084, -0.15785563]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 334.57601446285844, + 'timestamp_carla': 334576, + 'timestamp_device': 4072790, + 'timestamp_stream': 334.57601446285844, + 'transform': [array([-4.15520787e-01, -1.72248497e+01, 1.14342310e-02]), + array([-0.060092 , -1.30906188, 0.00723267])]} +{'AngularVelocity': array([-0.01382687, -0.00710594, -4.90843391]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.453248977661133, + 'FR_Wheel_Angle': 30.876941680908203, + 'Location': array([ -1.31471443, -20.17274666, 0.17106716]), + 'Rotation': array([-6.51804954e-02, 2.67395763e+01, -1.92871038e-02]), + 'Velocity': array([-3.57849270e-01, -3.45855087e-01, 2.88143143e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.7772541 , 11.44409275, 3.62158966]), + 'camera_rotation': array([-6.05218267, -5.70032167, -1.0210731 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3442.358154296875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-7.02538086e+02, 3.60766846e+02, -1.52587891e-05]), + 'frame': 10187, + 'frame_number': 10187, + 'framesequence': 38864, + 'gaze_dir': array([0.96025085, 0.27326202, 0.05615234]), + 'gaze_origin': array([-3.13022614, -0.24549869, 0.04278794]), + 'gaze_valid': True, + 'gaze_vergence': 289.1522216796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95872498, 0.27967834, 0.05097961]), + 'left_gaze_origin': array([-3.03517175, 2.94535089, 0.0451767 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0437774658203125, + 'left_pupil_posn': array([ 0.29165304, -0.07205319]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96177673, 0.2668457 , 0.06132507]), + 'right_gaze_origin': array([-3.225281 , -3.4363482 , 0.04039917]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.01348876953125, + 'right_pupil_posn': array([ 0.27085209, -0.15776682]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.16665904223918915, + 'timestamp': 334.60902796313167, + 'timestamp_carla': 334609, + 'timestamp_device': 4072823, + 'timestamp_stream': 334.60902796313167, + 'transform': [array([-4.14581150e-01, -1.71854534e+01, 1.14928717e-02]), + array([-0.060092 , -1.3091166 , 0.00698853])]} +{'AngularVelocity': array([ 0.02039267, 0.0042391 , -3.75904346]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.466426849365234, + 'FR_Wheel_Angle': 29.861642837524414, + 'Location': array([ -1.395123 , -20.23911858, 0.17111893]), + 'Rotation': array([-6.40944913e-02, 2.57640877e+01, -1.94396954e-02]), + 'Velocity': array([-0.31118149, -0.27598101, 0.00060203]), + 'brake_input': 0.0, + 'camera_location': array([-6.78224754, 11.44901562, 3.61454797]), + 'camera_rotation': array([-6.05690193, -5.66047668, -0.98520339]), + 'current_gear_input': False, + 'focus_actor_dist': 3408.90625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-707.31488037, 330.16064453, 0. ]), + 'frame': 10188, + 'frame_number': 10188, + 'framesequence': 38868, + 'gaze_dir': array([0.97040558, 0.23471832, 0.05344391]), + 'gaze_origin': array([-3.12188292, -0.21719895, 0.04261322]), + 'gaze_valid': True, + 'gaze_vergence': 160.0850067138672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9664917 , 0.25209045, 0.04821777]), + 'left_gaze_origin': array([-3.02436543, 2.97933531, 0.04360047]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.91131591796875, + 'left_pupil_posn': array([ 0.25083077, -0.07079446]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97431946, 0.21734619, 0.05867004]), + 'right_gaze_origin': array([-3.21940041, -3.41373301, 0.04162598]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.969390869140625, + 'right_pupil_posn': array([ 0.24494755, -0.15569758]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.1745937317609787, + 'timestamp': 334.64204416424036, + 'timestamp_carla': 334642, + 'timestamp_device': 4072856, + 'timestamp_stream': 334.64204416424036, + 'transform': [array([-4.13625479e-01, -1.71455212e+01, 1.15563395e-02]), + array([-0.060092 , -1.30919158, 0.00671387])]} +{'AngularVelocity': array([-9.20569003e-02, -2.67839362e-03, -3.27199936e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.553911209106445, + 'FR_Wheel_Angle': 31.830352783203125, + 'Location': array([ -1.45376587, -20.28614426, 0.17123222]), + 'Rotation': array([-6.38417751e-02, 2.50578213e+01, -1.70593262e-02]), + 'Velocity': array([-0.27916625, -0.2544919 , 0.00067071]), + 'brake_input': 0.0, + 'camera_location': array([-6.78200626, 11.44932556, 3.60894966]), + 'camera_rotation': array([-6.06148529, -5.64313555, -0.98613733]), + 'current_gear_input': False, + 'focus_actor_dist': 3053.327880859375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-5.34884277e+02, -1.69335938e+00, -1.52587891e-05]), + 'frame': 10189, + 'frame_number': 10189, + 'framesequence': 38872, + 'gaze_dir': array([0.99748993, 0.03366852, 0.05828857]), + 'gaze_origin': array([-3.10964131, -0.06181793, 0.05345917]), + 'gaze_valid': True, + 'gaze_vergence': 148.5738525390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99659729, 0.05470276, 0.06140137]), + 'left_gaze_origin': array([-3.0602417 , 3.13810158, 0.06824799]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.85992431640625, + 'left_pupil_posn': array([ 0.07234335, -0.05926228]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99838257, 0.01263428, 0.05517578]), + 'right_gaze_origin': array([-3.15904093, -3.26173711, 0.03867035]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.739166259765625, + 'right_pupil_posn': array([ 0.06894326, -0.13712704]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.6754346638918, + 'timestamp_carla': 334676, + 'timestamp_device': 4072890, + 'timestamp_stream': 334.6754346638918, + 'transform': [array([-4.12648618e-01, -1.71045837e+01, 1.16089052e-02]), + array([-0.060092 , -1.30925298, 0.00646973])]} +{'AngularVelocity': array([-0.02578753, 0.01194161, -2.76115298]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.070505142211914, + 'FR_Wheel_Angle': 34.32942581176758, + 'Location': array([ -1.52270532, -20.34175301, 0.17131972]), + 'Rotation': array([-6.58566803e-02, 2.41373692e+01, -1.30310059e-02]), + 'Velocity': array([-0.25729167, -0.23672377, 0.00054747]), + 'brake_input': 0.0, + 'camera_location': array([-6.77929688, 11.44833183, 3.62651229]), + 'camera_rotation': array([-6.0497303 , -5.71090174, -1.00922203]), + 'current_gear_input': False, + 'focus_actor_dist': 2938.526123046875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.36533813e+01, -1.04078369e+02, -1.52587891e-05]), + 'frame': 10190, + 'frame_number': 10190, + 'framesequence': 38876, + 'gaze_dir': array([ 0.99356842, -0.08982849, 0.06637573]), + 'gaze_origin': array([-3.26481652, 0.04927979, 0.09486313]), + 'gaze_valid': True, + 'gaze_vergence': 71.10440826416016, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99310303, -0.0826416 , 0.08312988]), + 'left_gaze_origin': array([-3.30005813, 3.2426424 , 0.13566589]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7328643798828125, + 'left_pupil_posn': array([-0.03820956, -0.06010854]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99403381, -0.09701538, 0.04962158]), + 'right_gaze_origin': array([-3.22957492, -3.14408278, 0.05406037]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8005218505859375, + 'right_pupil_posn': array([-0.05846101, -0.13117945]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.70813436433673, + 'timestamp_carla': 334708, + 'timestamp_device': 4072923, + 'timestamp_stream': 334.70813436433673, + 'transform': [array([-4.11676019e-01, -1.70638866e+01, 1.16808796e-02]), + array([-0.060092 , -1.3093245 , 0.00616456])]} +{'AngularVelocity': array([ 0.04608772, 0.03577678, -3.9597013 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.95720672607422, + 'FR_Wheel_Angle': 37.44166564941406, + 'Location': array([ -1.57537258, -20.38467979, 0.17140152]), + 'Rotation': array([-6.67104572e-02, 2.33808479e+01, -1.15356436e-02]), + 'Velocity': array([-2.61065513e-01, -2.34468296e-01, 2.55022052e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.7678566 , 11.42887306, 3.62092423]), + 'camera_rotation': array([-6.04632902, -5.84230375, -1.02076232]), + 'current_gear_input': False, + 'focus_actor_dist': 3402.748779296875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([5.34942932e+02, 2.98726807e+02, 6.10351562e-05]), + 'frame': 10191, + 'frame_number': 10191, + 'framesequence': 38880, + 'gaze_dir': array([ 0.9931488 , -0.09645081, 0.06420135]), + 'gaze_origin': array([-3.25475717, 0.05319367, 0.09227143]), + 'gaze_valid': True, + 'gaze_vergence': 73.51312255859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99272156, -0.09147644, 0.07827759]), + 'left_gaze_origin': array([-3.27438068, 3.24634862, 0.1284958 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.811004638671875, + 'left_pupil_posn': array([-0.04214126, -0.06000316]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99357605, -0.10142517, 0.05012512]), + 'right_gaze_origin': array([-3.23513341, -3.13996148, 0.05604706]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8249969482421875, + 'right_pupil_posn': array([-0.06427568, -0.1328007 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.74239886179566, + 'timestamp_carla': 334743, + 'timestamp_device': 4072956, + 'timestamp_stream': 334.74239886179566, + 'transform': [array([-4.10646975e-01, -1.70206680e+01, 1.17254350e-02]), + array([-0.060092 , -1.30938923, 0.00592042])]} +{'AngularVelocity': array([-0.07639518, 0.03254189, -4.38549328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.931978225708008, + 'FR_Wheel_Angle': 40.52898406982422, + 'Location': array([ -1.65010118, -20.44750977, 0.17150001]), + 'Rotation': array([-6.79945275e-02, 2.22052383e+01, -8.60595703e-03]), + 'Velocity': array([-0.29939187, -0.28304836, 0.00070939]), + 'brake_input': 0.0, + 'camera_location': array([-6.76504803, 11.39157391, 3.61116576]), + 'camera_rotation': array([-6.06675816, -6.00223589, -1.01932073]), + 'current_gear_input': False, + 'focus_actor_dist': 3228.005126953125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 5.26069580e+02, 1.25669922e+02, -1.52587891e-05]), + 'frame': 10192, + 'frame_number': 10192, + 'framesequence': 38884, + 'gaze_dir': array([ 0.99295044, -0.09744263, 0.06525421]), + 'gaze_origin': array([-3.24798083, 0.05171357, 0.08992767]), + 'gaze_valid': True, + 'gaze_vergence': 19.434432983398438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99200439, -0.09597778, 0.08175659]), + 'left_gaze_origin': array([-3.27670169, 3.24766111, 0.12903748]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.801971435546875, + 'left_pupil_posn': array([-0.04219174, -0.06048977]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99389648, -0.09890747, 0.04875183]), + 'right_gaze_origin': array([-3.21925998, -3.1442337 , 0.05081787]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.859710693359375, + 'right_pupil_posn': array([-0.06311625, -0.13216233]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.7744989618659, + 'timestamp_carla': 334775, + 'timestamp_device': 4072990, + 'timestamp_stream': 334.7744989618659, + 'transform': [array([-4.09662604e-01, -1.69795074e+01, 1.18036456e-02]), + array([-0.060092 , -1.30946088, 0.00561524])]} +{'AngularVelocity': array([ 4.44309078e-02, -4.15225048e-03, -5.55660248e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.801925659179688, + 'FR_Wheel_Angle': 41.69955062866211, + 'Location': array([ -1.72470343, -20.50893021, 0.17159247]), + 'Rotation': array([-6.88209832e-02, 2.09640675e+01, -7.99560454e-03]), + 'Velocity': array([-0.31706756, -0.29818115, 0.00053621]), + 'brake_input': 0.0, + 'camera_location': array([-6.75460148, 11.35148239, 3.6142509 ]), + 'camera_rotation': array([-6.06862974, -6.18436861, -1.0380733 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3281.1083984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([550.1060791 , 179.06201172, 0. ]), + 'frame': 10193, + 'frame_number': 10193, + 'framesequence': 38888, + 'gaze_dir': array([ 0.99297333, -0.09749603, 0.06507874]), + 'gaze_origin': array([-3.24362111, 0.05088501, 0.08731766]), + 'gaze_valid': True, + 'gaze_vergence': 19.1557674407959, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99206543, -0.09619141, 0.0809021 ]), + 'left_gaze_origin': array([-3.27599955, 3.24785638, 0.12802583]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7969970703125, + 'left_pupil_posn': array([-0.04227674, -0.06088769]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99388123, -0.09880066, 0.04925537]), + 'right_gaze_origin': array([-3.21124268, -3.14608622, 0.0466095 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8610992431640625, + 'right_pupil_posn': array([-0.06202883, -0.13383901]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.80884156376123, + 'timestamp_carla': 334809, + 'timestamp_device': 4073023, + 'timestamp_stream': 334.80884156376123, + 'transform': [array([-4.08599377e-01, -1.69348888e+01, 1.18402196e-02]), + array([-0.060092 , -1.30952549, 0.00540162])]} +{'AngularVelocity': array([-0.09672524, -0.00884264, -5.08331776]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.819515228271484, + 'FR_Wheel_Angle': 41.734458923339844, + 'Location': array([ -1.79841101, -20.5676384 , 0.17164424]), + 'Rotation': array([-6.62869811e-02, 1.97388744e+01, -1.19323721e-02]), + 'Velocity': array([-3.09630543e-01, -2.79636532e-01, -5.02490984e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.72721958, 11.31808662, 3.60540247]), + 'camera_rotation': array([-6.12622166, -6.33804178, -1.0716306 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2076.498046875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([ 286.61590576, -991.17614746, 50.22546387]), + 'frame': 10194, + 'frame_number': 10194, + 'framesequence': 38892, + 'gaze_dir': array([ 0.99298859, -0.09734344, 0.06503296]), + 'gaze_origin': array([-3.23595667, 0.05009613, 0.0835785 ]), + 'gaze_valid': True, + 'gaze_vergence': 4.117424964904785, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99197388, -0.09721375, 0.08081055]), + 'left_gaze_origin': array([-3.26108408, 3.24779367, 0.12080384]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.7642822265625, + 'left_pupil_posn': array([-0.04170936, -0.06281376]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9940033 , -0.09747314, 0.04925537]), + 'right_gaze_origin': array([-3.21082926, -3.14760137, 0.04635315]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.86004638671875, + 'right_pupil_posn': array([-0.06135148, -0.13399827]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.8422874622047, + 'timestamp_carla': 334843, + 'timestamp_device': 4073056, + 'timestamp_stream': 334.8422874622047, + 'transform': [array([-4.07548219e-01, -1.68907852e+01, 1.18815321e-02]), + array([-0.060092 , -1.30958688, 0.00521851])]} +{'AngularVelocity': array([-0.02517416, 0.07516732, -6.87864876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.767309188842773, + 'FR_Wheel_Angle': 41.61138153076172, + 'Location': array([ -1.86816108, -20.6206131 , 0.17175071]), + 'Rotation': array([-7.03167915e-02, 1.85931377e+01, -6.95800735e-03]), + 'Velocity': array([-0.40914497, -0.33315316, 0.00065999]), + 'brake_input': 0.0, + 'camera_location': array([-6.70775509, 11.27846909, 3.60146976]), + 'camera_rotation': array([-6.15583038, -6.44101524, -1.02968228]), + 'current_gear_input': False, + 'focus_actor_dist': 3179.691162109375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([5.45584473e+02, 8.45666504e+01, 1.52587891e-05]), + 'frame': 10195, + 'frame_number': 10195, + 'framesequence': 38896, + 'gaze_dir': array([ 0.99287415, -0.09797668, 0.06625366]), + 'gaze_origin': array([-3.23302007, 0.04935379, 0.08219682]), + 'gaze_valid': True, + 'gaze_vergence': 17.755929946899414, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99203491, -0.09706116, 0.0801239 ]), + 'left_gaze_origin': array([-3.25518966, 3.24757695, 0.11809998]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.84808349609375, + 'left_pupil_posn': array([-0.04196256, -0.06269276]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99371338, -0.09889221, 0.05238342]), + 'right_gaze_origin': array([-3.21085072, -3.14886951, 0.04629364]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8596343994140625, + 'right_pupil_posn': array([-0.06043172, -0.13428319]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.8748682625592, + 'timestamp_carla': 334875, + 'timestamp_device': 4073090, + 'timestamp_stream': 334.8748682625592, + 'transform': [array([-4.06508327e-01, -1.68471584e+01, 1.19356345e-02]), + array([-0.060092 , -1.30965173, 0.00500489])]} +{'AngularVelocity': array([-0.06946824, -0.03703741, -7.44516945]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75971031188965, + 'FR_Wheel_Angle': 41.62539291381836, + 'Location': array([ -1.96611917, -20.69327354, 0.17184681]), + 'Rotation': array([-6.99684545e-02, 1.69988003e+01, -7.32421922e-03]), + 'Velocity': array([-4.06658351e-01, -3.58145177e-01, 3.89337540e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.70057201, 11.2420702 , 3.58722067]), + 'camera_rotation': array([-6.24441814, -6.60441685, -1.1768688 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3237.316650390625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([566.56817627, 143.33032227, 0. ]), + 'frame': 10196, + 'frame_number': 10196, + 'framesequence': 38900, + 'gaze_dir': array([ 0.99182129, -0.10617065, 0.06934357]), + 'gaze_origin': array([-3.14128208, 0.04515763, 0.05583725]), + 'gaze_valid': True, + 'gaze_vergence': 147.27841186523438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99203491, -0.09718323, 0.08006287]), + 'left_gaze_origin': array([-3.07132125, 3.2400806 , 0.06532136]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8329925537109375, + 'left_pupil_posn': array([-0.04115564, -0.06204951]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99160767, -0.11515808, 0.05862427]), + 'right_gaze_origin': array([-3.21124268, -3.14976501, 0.04635315]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8580169677734375, + 'right_pupil_posn': array([-0.05985594, -0.13432741]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.9080727621913, + 'timestamp_carla': 334908, + 'timestamp_device': 4073123, + 'timestamp_stream': 334.9080727621913, + 'transform': [array([-4.05432880e-01, -1.68020592e+01, 1.19754216e-02]), + array([-0.060092 , -1.30971992, 0.00482178])]} +{'AngularVelocity': array([ 0.10085806, 0.02464723, -6.27683687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.764259338378906, + 'FR_Wheel_Angle': 41.63747787475586, + 'Location': array([ -2.06102896, -20.75987816, 0.17198169]), + 'Rotation': array([-6.86024129e-02, 1.54767523e+01, -1.10168438e-02]), + 'Velocity': array([-4.19494629e-01, -3.19036275e-01, 3.51562485e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.68962383, 11.19042206, 3.56016707]), + 'camera_rotation': array([-6.30734444, -6.75025702, -1.25879848]), + 'current_gear_input': False, + 'focus_actor_dist': 3331.52783203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.25248535e+02, 2.30529053e+02, -1.52587891e-05]), + 'frame': 10197, + 'frame_number': 10197, + 'framesequence': 38904, + 'gaze_dir': array([ 0.99207306, -0.10247803, 0.07113647]), + 'gaze_origin': array([-3.14299798, 0.0445343 , 0.05576782]), + 'gaze_valid': True, + 'gaze_vergence': 168.60275268554688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99250793, -0.0917511 , 0.08055115]), + 'left_gaze_origin': array([-3.06895757, 3.23959517, 0.06376038]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8155670166015625, + 'left_pupil_posn': array([-0.0401547 , -0.06150746]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99163818, -0.11320496, 0.0617218 ]), + 'right_gaze_origin': array([-3.21703815, -3.15052652, 0.04777527]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8521881103515625, + 'right_pupil_posn': array([-0.05736458, -0.13428319]), + 'right_pupil_posn_valid': True, + 'steering_input': -9.155553561868146e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.94272136315703, + 'timestamp_carla': 334943, + 'timestamp_device': 4073156, + 'timestamp_stream': 334.94272136315703, + 'transform': [array([-4.04313207e-01, -1.67544098e+01, 1.19626420e-02]), + array([-0.060092 , -1.30971992, 0.00482178])]} +{'AngularVelocity': array([ 4.26757894e-02, 1.97889633e-03, -6.41871309e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77029037475586, + 'FR_Wheel_Angle': 41.648433685302734, + 'Location': array([ -2.14452505, -20.81533241, 0.17196915]), + 'Rotation': array([-6.85409456e-02, 1.41615467e+01, -1.15356445e-02]), + 'Velocity': array([-4.18147832e-01, -3.08981836e-01, -9.57012162e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.67177105, 11.14663029, 3.54660344]), + 'camera_rotation': array([-6.34217167, -6.90772295, -1.34382701]), + 'current_gear_input': False, + 'focus_actor_dist': 3379.430419921875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([633.68383789, 282.3984375 , 0. ]), + 'frame': 10198, + 'frame_number': 10198, + 'framesequence': 38908, + 'gaze_dir': array([ 0.9924469 , -0.09934998, 0.0699234 ]), + 'gaze_origin': array([-3.14144373, 0.0429245 , 0.05651855]), + 'gaze_valid': True, + 'gaze_vergence': 168.3523406982422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99331665, -0.08499146, 0.07806396]), + 'left_gaze_origin': array([-3.06402445, 3.23798704, 0.06337433]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.8211212158203125, + 'left_pupil_posn': array([-0.03920013, -0.06083953]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99157715, -0.1137085 , 0.06178284]), + 'right_gaze_origin': array([-3.21886325, -3.15213799, 0.04966278]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8359527587890625, + 'right_pupil_posn': array([-0.05386901, -0.13413477]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00010986663983203471, + 'throttle_input': 0.17856107652187347, + 'timestamp': 334.97436126321554, + 'timestamp_carla': 334975, + 'timestamp_device': 4073190, + 'timestamp_stream': 334.97436126321554, + 'transform': [array([-4.03248727e-01, -1.67102013e+01, 1.20184897e-02]), + array([-0.060092 , -1.30983245, 0.00463868])]} +{'AngularVelocity': array([ 1.33482879e-02, 1.19823124e-03, -5.62588310e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79424476623535, + 'FR_Wheel_Angle': 41.682613372802734, + 'Location': array([ -2.24574947, -20.87829971, 0.17211697]), + 'Rotation': array([-0.06649872, 12.60926056, -0.01373291]), + 'Velocity': array([-0.37281266, -0.26024818, 0.00118831]), + 'brake_input': 0.0, + 'camera_location': array([-6.67237568, 11.09776878, 3.53907728]), + 'camera_rotation': array([-6.37389803, -7.04473591, -1.3437916 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3226.53271484375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([5.95739502e+02, 1.38965820e+02, 1.52587891e-05]), + 'frame': 10199, + 'frame_number': 10199, + 'framesequence': 38912, + 'gaze_dir': array([ 0.99430084, -0.07405853, 0.07317352]), + 'gaze_origin': array([-3.13371038, 0.01923981, 0.05404358]), + 'gaze_valid': True, + 'gaze_vergence': 122.26184844970703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99491882, -0.05448914, 0.08451843]), + 'left_gaze_origin': array([-3.04098845, 3.21432495, 0.05756988]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.822479248046875, + 'left_pupil_posn': array([-0.01603544, -0.06040239]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99368286, -0.09362793, 0.06182861]), + 'right_gaze_origin': array([-3.22643304, -3.17584538, 0.05051728]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8021697998046875, + 'right_pupil_posn': array([-0.02686191, -0.13255143]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.17856107652187347, + 'timestamp': 335.009101562202, + 'timestamp_carla': 335009, + 'timestamp_device': 4073223, + 'timestamp_stream': 335.009101562202, + 'transform': [array([-4.02050167e-01, -1.66610966e+01, 1.20104980e-02]), + array([-0.060092 , -1.31001353, 0.00460816])]} +{'AngularVelocity': array([ 5.25167503e-04, 3.65134515e-02, -5.48343754e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.821889877319336, + 'FR_Wheel_Angle': 41.68523025512695, + 'Location': array([ -2.31878376, -20.92158127, 0.17214699]), + 'Rotation': array([-0.06634846, 11.50308704, -0.01364136]), + 'Velocity': array([-3.56632024e-01, -2.32263371e-01, 5.41114787e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.67210197, 11.05233192, 3.53752613]), + 'camera_rotation': array([-6.3997364 , -7.15940619, -1.33239329]), + 'current_gear_input': False, + 'focus_actor_dist': 3476.960693359375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 5.79074402e+02, 4.04982666e+02, -1.52587891e-05]), + 'frame': 10200, + 'frame_number': 10200, + 'framesequence': 38916, + 'gaze_dir': array([0.98668671, 0.15457916, 0.04492188]), + 'gaze_origin': array([-3.15117574, -0.16085587, 0.04589081]), + 'gaze_valid': True, + 'gaze_vergence': 131.5293426513672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98362732, 0.17607117, 0.03804016]), + 'left_gaze_origin': array([-3.08388519, 3.02684188, 0.05662842]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0023040771484375, + 'left_pupil_posn': array([ 0.18991911, -0.07362032]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98974609, 0.13308716, 0.05180359]), + 'right_gaze_origin': array([-3.21846652, -3.34855366, 0.0351532 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.903106689453125, + 'right_pupil_posn': array([ 0.17263329, -0.16109955]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0004577776708174497, + 'throttle_input': 0.17856107652187347, + 'timestamp': 335.0417274646461, + 'timestamp_carla': 335042, + 'timestamp_device': 4073256, + 'timestamp_stream': 335.0417274646461, + 'transform': [array([-4.00857091e-01, -1.66143284e+01, 1.20394230e-02]), + array([-0.06005785, -1.31040645, 0.00451661])]} +{'AngularVelocity': array([ 0.06146494, -0.00771314, -5.390522 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80042839050293, + 'FR_Wheel_Angle': 41.70571517944336, + 'Location': array([ -2.41044378, -20.97285652, 0.17231174]), + 'Rotation': array([-0.06845215, 10.13288879, -0.01043701]), + 'Velocity': array([-0.37008259, -0.23485173, 0.00041655]), + 'brake_input': 0.0, + 'camera_location': array([-6.65762043, 11.02476788, 3.54039574]), + 'camera_rotation': array([-6.45195341, -7.18618488, -1.35465515]), + 'current_gear_input': False, + 'focus_actor_dist': 1962.077880859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -197.56593323, -1021.07519531, 16.69667053]), + 'frame': 10201, + 'frame_number': 10201, + 'framesequence': 38920, + 'gaze_dir': array([0.94181824, 0.33486938, 0.02780914]), + 'gaze_origin': array([-3.19675684, -0.29755557, 0.03581009]), + 'gaze_valid': True, + 'gaze_vergence': 356.87811279296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93943787, 0.34129333, 0.03096008]), + 'left_gaze_origin': array([-3.13760376, 2.87541819, 0.04984589]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.014373779296875, + 'left_pupil_posn': array([ 0.36447001, -0.10279465]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94419861, 0.32844543, 0.0246582 ]), + 'right_gaze_origin': array([-3.25591016, -3.47052932, 0.02177429]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.852325439453125, + 'right_pupil_posn': array([ 0.31883991, -0.18560553]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.000347911030985415, + 'throttle_input': 0.17856107652187347, + 'timestamp': 335.0748085640371, + 'timestamp_carla': 335075, + 'timestamp_device': 4073290, + 'timestamp_stream': 335.0748085640371, + 'transform': [array([-3.99626762e-01, -1.65662842e+01, 1.20537756e-02]), + array([-0.06005785, -1.31080592, 0.00445557])]} +{'AngularVelocity': array([ 4.18607220e-02, 2.69716466e-03, -4.83109283e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82281494140625, + 'FR_Wheel_Angle': 41.731727600097656, + 'Location': array([ -2.49217057, -21.01643944, 0.1723716 ]), + 'Rotation': array([-0.06686072, 8.9201746 , -0.01199341]), + 'Velocity': array([-3.28198045e-01, -1.97165757e-01, 2.12621686e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.63314724, 11.07236958, 3.57241344]), + 'camera_rotation': array([-6.3542614 , -7.00566196, -1.39013338]), + 'current_gear_input': False, + 'focus_actor_dist': 1723.0966796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -514.46411133, -1287.9083252 , 17.08535767]), + 'frame': 10202, + 'frame_number': 10202, + 'framesequence': 38924, + 'gaze_dir': array([0.93174744, 0.36261749, 0.0144043 ]), + 'gaze_origin': array([-3.20345688, -0.31886598, 0.03484268]), + 'gaze_valid': True, + 'gaze_vergence': 202.82525634765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.92871094, 0.37013245, 0.02159119]), + 'left_gaze_origin': array([-3.14200926, 2.85721445, 0.05249787]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1280670166015625, + 'left_pupil_posn': array([ 0.38691974, -0.10908163]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93478394, 0.35510254, 0.00721741]), + 'right_gaze_origin': array([-3.26490474, -3.49494624, 0.0171875 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9195404052734375, + 'right_pupil_posn': array([ 0.34732831, -0.19521558]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0010071108117699623, + 'throttle_input': 0.17856107652187347, + 'timestamp': 335.10865906253457, + 'timestamp_carla': 335109, + 'timestamp_device': 4073323, + 'timestamp_stream': 335.10865906253457, + 'transform': [array([-3.98615420e-01, -1.65164909e+01, 1.20449346e-02]), + array([-0.06018079, -1.31017733, 0.00445557])]} +{'AngularVelocity': array([ 0.11906742, 0.04657028, -3.59537983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.832782745361328, + 'FR_Wheel_Angle': 41.746395111083984, + 'Location': array([ -2.55613256, -21.04882812, 0.17242241]), + 'Rotation': array([-0.06735249, 7.99648046, -0.01199341]), + 'Velocity': array([-3.26395243e-01, -1.64822072e-01, 2.18610759e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.61250782, 11.21113014, 3.5635941 ]), + 'camera_rotation': array([-6.30772018, -6.30484915, -1.18521369]), + 'current_gear_input': False, + 'focus_actor_dist': 1513.5084228515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -523.34838867, -1499.87280273, 17.15081787]), + 'frame': 10203, + 'frame_number': 10203, + 'framesequence': 38928, + 'gaze_dir': array([0.93836212, 0.34474182, 0.0235672 ]), + 'gaze_origin': array([-3.1986804 , -0.30825427, 0.04064026]), + 'gaze_valid': True, + 'gaze_vergence': 84.68678283691406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93864441, 0.34352112, 0.03012085]), + 'left_gaze_origin': array([-3.13804197, 2.87070632, 0.05447083]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0273284912109375, + 'left_pupil_posn': array([ 0.37404799, -0.10314178]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.93807983, 0.34596252, 0.01701355]), + 'right_gaze_origin': array([-3.25931859, -3.4872148 , 0.02680969]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.82281494140625, + 'right_pupil_posn': array([ 0.33171678, -0.18311548]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.004138309974223375, + 'throttle_input': 0.17856107652187347, + 'timestamp': 335.1426226645708, + 'timestamp_carla': 335143, + 'timestamp_device': 4073356, + 'timestamp_stream': 335.1426226645708, + 'transform': [array([-3.98297101e-01, -1.64658470e+01, 1.20248413e-02]), + array([-0.06051547, -1.3067348 , 0.00448609])]} +{'AngularVelocity': array([ 0.08368934, 0.01545714, -4.02574015]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.837594985961914, + 'FR_Wheel_Angle': 41.765647888183594, + 'Location': array([ -2.63931584, -21.08913994, 0.1725359 ]), + 'Rotation': array([-0.06802185, 6.79102564, -0.00985718]), + 'Velocity': array([-0.30702749, -0.16054378, 0.00032819]), + 'brake_input': 0.0, + 'camera_location': array([-6.62751198, 11.34194374, 3.58660936]), + 'camera_rotation': array([-6.38986683, -5.22968435, -0.28882235]), + 'current_gear_input': False, + 'focus_actor_dist': 1669.921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -546.78771973, -1339.33251953, 17.13123322]), + 'frame': 10204, + 'frame_number': 10204, + 'framesequence': 38932, + 'gaze_dir': array([0.9421463 , 0.33405304, 0.02357483]), + 'gaze_origin': array([-3.19320703, -0.29460451, 0.04206772]), + 'gaze_valid': True, + 'gaze_vergence': 210.78054809570312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.93786621, 0.34638977, 0.01980591]), + 'left_gaze_origin': array([-3.1330719 , 2.88480687, 0.04978791]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9666595458984375, + 'left_pupil_posn': array([ 0.35540736, -0.10073972]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.94642639, 0.32171631, 0.02734375]), + 'right_gaze_origin': array([-3.25334191, -3.47401619, 0.03434753]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9211578369140625, + 'right_pupil_posn': array([ 0.32290506, -0.18074524]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.009192175231873989, + 'throttle_input': 0.17856107652187347, + 'timestamp': 335.1755203641951, + 'timestamp_carla': 335176, + 'timestamp_device': 4073390, + 'timestamp_stream': 335.1755203641951, + 'transform': [array([-3.99187624e-01, -1.64160080e+01, 1.20216366e-02]), + array([-0.06113019, -1.29858935, 0.00445557])]} +{'AngularVelocity': array([ 0.06623662, 0.02551326, -4.43786383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.842830657958984, + 'FR_Wheel_Angle': 41.75840377807617, + 'Location': array([ -2.71012497, -21.12252426, 0.17260982]), + 'Rotation': array([-0.06845215, 5.74623919, -0.00814819]), + 'Velocity': array([-0.31032702, -0.158959 , 0.00055697]), + 'brake_input': 0.0, + 'camera_location': array([-6.60334587, 11.45775604, 3.57782578]), + 'camera_rotation': array([-6.16977787, -4.42832279, -0.21280393]), + 'current_gear_input': False, + 'focus_actor_dist': 1519.8558349609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -525.98944092, -1483.90112305, 17.14783478]), + 'frame': 10205, + 'frame_number': 10205, + 'framesequence': 38936, + 'gaze_dir': array([0.94619751, 0.32263184, 0.02115631]), + 'gaze_origin': array([-3.19086242, -0.2909531 , 0.04059983]), + 'gaze_valid': True, + 'gaze_vergence': 250.1548614501953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94233704, 0.3339386 , 0.0214386 ]), + 'left_gaze_origin': array([-3.12987518, 2.89019465, 0.04988556]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9654541015625, + 'left_pupil_posn': array([ 0.34773898, -0.10203755]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95005798, 0.31132507, 0.02087402]), + 'right_gaze_origin': array([-3.25184941, -3.47210097, 0.03131409]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.97393798828125, + 'right_pupil_posn': array([ 0.31686127, -0.18151987]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.015070040710270405, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.20830376446247, + 'timestamp_carla': 335209, + 'timestamp_device': 4073423, + 'timestamp_stream': 335.20830376446247, + 'transform': [array([-4.01653737e-01, -1.63655262e+01, 1.20110409e-02]), + array([-0.06194981, -1.28422117, 0.00442506])]} +{'AngularVelocity': array([ 0.12484563, -0.02173266, -2.99050856]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.844654083251953, + 'FR_Wheel_Angle': 41.767601013183594, + 'Location': array([ -2.77891135, -21.15299034, 0.17267631]), + 'Rotation': array([-0.06789891, 4.75407076, -0.00881958]), + 'Velocity': array([-0.26712757, -0.13225856, 0.00066098]), + 'brake_input': 0.0, + 'camera_location': array([-6.58447647, 11.57384872, 3.57604504]), + 'camera_rotation': array([-6.09275389, -3.82442498, -0.59513825]), + 'current_gear_input': False, + 'focus_actor_dist': 1525.16845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -530.16339111, -1474.41369629, 17.14886475]), + 'frame': 10206, + 'frame_number': 10206, + 'framesequence': 38940, + 'gaze_dir': array([0.9480896 , 0.31684113, 0.02128601]), + 'gaze_origin': array([-3.18849349, -0.28656846, 0.04254761]), + 'gaze_valid': True, + 'gaze_vergence': 181.4678497314453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9432373 , 0.33161926, 0.01737976]), + 'left_gaze_origin': array([-3.12714529, 2.89525604, 0.05368653]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.00390625, + 'left_pupil_posn': array([ 0.34091949, -0.09695089]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95294189, 0.30206299, 0.02519226]), + 'right_gaze_origin': array([-3.24984145, -3.46839309, 0.03140869]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.968109130859375, + 'right_pupil_posn': array([ 0.31328297, -0.18237543]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02226630598306656, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.24268206208944, + 'timestamp_carla': 335243, + 'timestamp_device': 4073456, + 'timestamp_stream': 335.24268206208944, + 'transform': [array([-4.06307518e-01, -1.63117733e+01, 1.19675733e-02]), + array([-0.062988 , -1.26097655, 0.00445557])]} +{'AngularVelocity': array([-0.07661311, -0.01254561, -4.98305702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.2010555267334, + 'FR_Wheel_Angle': 40.3123664855957, + 'Location': array([ -2.83846664, -21.17811775, 0.17274429]), + 'Rotation': array([-0.0697977 , 3.89572406, -0.00543213]), + 'Velocity': array([-0.30751136, -0.16493683, 0.00043364]), + 'brake_input': 0.0, + 'camera_location': array([-6.59834099, 11.69847488, 3.55446887]), + 'camera_rotation': array([-6.25931501, -3.14995718, -0.57948291]), + 'current_gear_input': False, + 'focus_actor_dist': 1590.8516845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -551.98840332, -1406.8371582 , 17.15370941]), + 'frame': 10207, + 'frame_number': 10207, + 'framesequence': 38944, + 'gaze_dir': array([0.95189667, 0.30516815, 0.01783752]), + 'gaze_origin': array([-3.18457818, -0.27622911, 0.0435585 ]), + 'gaze_valid': True, + 'gaze_vergence': 142.76605224609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.94560242, 0.32495117, 0.01522827]), + 'left_gaze_origin': array([-3.12285924, 2.90480804, 0.05444031]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9222869873046875, + 'left_pupil_posn': array([ 0.32801497, -0.09699142]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95819092, 0.28538513, 0.02044678]), + 'right_gaze_origin': array([-3.24629688, -3.45726657, 0.0326767 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.025482177734375, + 'right_pupil_posn': array([ 0.30272841, -0.18140459]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03151341527700424, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.2757459618151, + 'timestamp_carla': 335276, + 'timestamp_device': 4073490, + 'timestamp_stream': 335.2757459618151, + 'transform': [array([-4.13310081e-01, -1.62591419e+01, 1.19478889e-02]), + array([-0.0642106 , -1.22868848, 0.00442505])]} +{'AngularVelocity': array([-2.68711876e-02, -3.57222883e-03, -4.48683405e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.477689743041992, + 'FR_Wheel_Angle': 37.32443618774414, + 'Location': array([ -2.91362166, -21.20709419, 0.17280892]), + 'Rotation': array([-0.06936739, 2.89929795, -0.00726318]), + 'Velocity': array([-3.17982912e-01, -1.42160118e-01, -4.08554079e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.6276722 , 11.82890606, 3.5135932 ]), + 'camera_rotation': array([-6.48788691, -2.53977561, -0.26376462]), + 'current_gear_input': False, + 'focus_actor_dist': 1460.0125732421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -521.72637939, -1529.23339844, 17.15950775]), + 'frame': 10208, + 'frame_number': 10208, + 'framesequence': 38948, + 'gaze_dir': array([0.95448303, 0.29629517, 0.03083038]), + 'gaze_origin': array([-3.18219781, -0.26819614, 0.04954529]), + 'gaze_valid': True, + 'gaze_vergence': 168.78292846679688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95101929, 0.30654907, 0.03953552]), + 'left_gaze_origin': array([-3.11963367, 2.91635299, 0.06348572]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.952972412109375, + 'left_pupil_posn': array([ 0.3201344 , -0.08965147]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95794678, 0.28604126, 0.02212524]), + 'right_gaze_origin': array([-3.24476171, -3.45274496, 0.03560486]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0882415771484375, + 'right_pupil_posn': array([ 0.29281271, -0.16988301]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04178594425320625, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.3092977628112, + 'timestamp_carla': 335310, + 'timestamp_device': 4073523, + 'timestamp_stream': 335.3092977628112, + 'transform': [array([-4.23447728e-01, -1.62047768e+01, 1.19182589e-02]), + array([-0.06561762, -1.18403351, 0.00439454])]} +{'AngularVelocity': array([ 2.82359449e-03, 4.24509458e-02, -4.66975737e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.23942756652832, + 'FR_Wheel_Angle': 33.576717376708984, + 'Location': array([ -3.0093689 , -21.23835564, 0.17291331]), + 'Rotation': array([-0.07049438, 1.77722657, -0.00668335]), + 'Velocity': array([-0.38925451, -0.13396123, 0.00042729]), + 'brake_input': 0.0, + 'camera_location': array([-6.68698215, 11.91271973, 3.4779129 ]), + 'camera_rotation': array([-6.8046236 , -2.0009954 , 0.41768983]), + 'current_gear_input': False, + 'focus_actor_dist': 1597.599365234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -556.46289062, -1390.45153809, 17.15409088]), + 'frame': 10209, + 'frame_number': 10209, + 'framesequence': 38952, + 'gaze_dir': array([0.95821381, 0.28340149, 0.03645325]), + 'gaze_origin': array([-3.17888665, -0.25924608, 0.05552292]), + 'gaze_valid': True, + 'gaze_vergence': 227.6505584716797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95481873, 0.29428101, 0.04109192]), + 'left_gaze_origin': array([-3.11685514, 2.92516041, 0.06333923]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1136016845703125, + 'left_pupil_posn': array([ 0.30904615, -0.08566272]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96160889, 0.27252197, 0.03181458]), + 'right_gaze_origin': array([-3.24091792, -3.44365239, 0.04770661]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9718017578125, + 'right_pupil_posn': array([ 0.28187776, -0.15961182]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05246131867170334, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.3443864621222, + 'timestamp_carla': 335345, + 'timestamp_device': 4073556, + 'timestamp_stream': 335.3443864621222, + 'transform': [array([-4.37512517e-01, -1.61469765e+01, 1.18544670e-02]), + array([-0.0671066 , -1.12382579, 0.00445557])]} +{'AngularVelocity': array([-0.08570146, 0.02097983, -4.55626059]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.69348907470703, + 'FR_Wheel_Angle': 29.484060287475586, + 'Location': array([ -3.08333254, -21.25899887, 0.17299457]), + 'Rotation': array([-0.06894393, 1.00763464, -0.00756836]), + 'Velocity': array([-3.68018031e-01, -1.21462941e-01, 1.21011733e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.69671917, 11.9587431 , 3.46942258]), + 'camera_rotation': array([-6.87727594, -1.55963326, 1.25086951]), + 'current_gear_input': False, + 'focus_actor_dist': 1526.449462890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -535.64709473, -1453.56262207, 17.14913177]), + 'frame': 10210, + 'frame_number': 10210, + 'framesequence': 38956, + 'gaze_dir': array([0.95904541, 0.28078461, 0.03670502]), + 'gaze_origin': array([-3.17764354, -0.25454563, 0.05794602]), + 'gaze_valid': True, + 'gaze_vergence': 546.4441528320312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95802307, 0.28392029, 0.03941345]), + 'left_gaze_origin': array([-3.11595011, 2.93145609, 0.06651917]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1126861572265625, + 'left_pupil_posn': array([ 0.30651057, -0.08269191]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96006775, 0.27764893, 0.03399658]), + 'right_gaze_origin': array([-3.23933744, -3.44054747, 0.04937287]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.002593994140625, + 'right_pupil_posn': array([ 0.27581561, -0.1584779 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0653340294957161, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.37752306461334, + 'timestamp_carla': 335378, + 'timestamp_device': 4073590, + 'timestamp_stream': 335.37752306461334, + 'transform': [array([-4.54552293e-01, -1.60913391e+01, 1.18311401e-02]), + array([-0.06866389, -1.05232775, 0.00442505])]} +{'AngularVelocity': array([ 0.0445835 , -0.02930861, -3.52396107]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.94571876525879, + 'FR_Wheel_Angle': 25.382200241088867, + 'Location': array([ -3.17535567, -21.28026962, 0.17309795]), + 'Rotation': array([-0.07140962, 0.17456371, -0.00579834]), + 'Velocity': array([-4.11482722e-01, -1.04617901e-01, 4.34112553e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.70932674, 12.0038147 , 3.4468298 ]), + 'camera_rotation': array([-6.9153614 , -1.28800845, 1.57270598]), + 'current_gear_input': False, + 'focus_actor_dist': 1434.1197509765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -523.50604248, -1540.28662109, 17.16513824]), + 'frame': 10211, + 'frame_number': 10211, + 'framesequence': 38960, + 'gaze_dir': array([0.96169281, 0.27206421, 0.03108978]), + 'gaze_origin': array([-3.1755724 , -0.25031358, 0.05767365]), + 'gaze_valid': True, + 'gaze_vergence': 253.31466674804688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95843506, 0.28363037, 0.03062439]), + 'left_gaze_origin': array([-3.11376667, 2.93443608, 0.06583252]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0598297119140625, + 'left_pupil_posn': array([ 0.29840124, -0.08294415]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96495056, 0.26049805, 0.03155518]), + 'right_gaze_origin': array([-3.23737812, -3.43506336, 0.04951477]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.038787841796875, + 'right_pupil_posn': array([ 0.27175474, -0.16107416]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0765221118927002, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.4083688631654, + 'timestamp_carla': 335409, + 'timestamp_device': 4073623, + 'timestamp_stream': 335.4083688631654, + 'transform': [array([-4.73862588e-01, -1.60385265e+01, 1.18578048e-02]), + array([-0.07009823, -0.9724046 , 0.00424195])]} +{'AngularVelocity': array([-0.04461212, 0.07359374, -2.52969027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.24087142944336, + 'FR_Wheel_Angle': 21.360719680786133, + 'Location': array([ -3.27955317, -21.29929924, 0.1732022 ]), + 'Rotation': array([-0.06894393, -0.62469476, -0.00717163]), + 'Velocity': array([-0.4338845 , -0.08236923, 0.00109009]), + 'brake_input': 0.0, + 'camera_location': array([-6.68629265, 12.03181171, 3.45298791]), + 'camera_rotation': array([-7.0152936 , -1.00849485, 1.93090034]), + 'current_gear_input': False, + 'focus_actor_dist': 1311.4482421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -490.71334839, -1653.64624023, 17.17240906]), + 'frame': 10212, + 'frame_number': 10212, + 'framesequence': 38964, + 'gaze_dir': array([0.96169281, 0.27101898, 0.03842926]), + 'gaze_origin': array([-3.17551112, -0.24714205, 0.05718308]), + 'gaze_valid': True, + 'gaze_vergence': 203.99378967285156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95770264, 0.28475952, 0.04135132]), + 'left_gaze_origin': array([-3.11352086, 2.93656945, 0.06489564]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0306396484375, + 'left_pupil_posn': array([ 0.29577327, -0.08211648]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96568298, 0.25727844, 0.0355072 ]), + 'right_gaze_origin': array([-3.23750162, -3.43085337, 0.04947052]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0777740478515625, + 'right_pupil_posn': array([ 0.26926649, -0.15739024]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08765526115894318, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.44272086396813, + 'timestamp_carla': 335443, + 'timestamp_device': 4073656, + 'timestamp_stream': 335.44272086396813, + 'transform': [array([-4.99216437e-01, -1.59788008e+01, 1.18258381e-02]), + array([-0.07146426, -0.86858225, 0.00418091])]} +{'AngularVelocity': array([-0.01894977, -0.00664308, -2.81077456]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.186614036560059, + 'FR_Wheel_Angle': 17.119264602661133, + 'Location': array([ -3.36820722, -21.31175232, 0.17329223]), + 'Rotation': array([-0.06906004, -1.18585205, -0.00668335]), + 'Velocity': array([-0.42586711, -0.06874802, 0.0007599 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.67353439, 12.04503822, 3.42582035]), + 'camera_rotation': array([-7.18884897, -0.78874338, 2.18318844]), + 'current_gear_input': False, + 'focus_actor_dist': 1370.580078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -512.03759766, -1592.59692383, 17.17209625]), + 'frame': 10213, + 'frame_number': 10213, + 'framesequence': 38968, + 'gaze_dir': array([0.96297455, 0.26603699, 0.04184723]), + 'gaze_origin': array([-3.17356873, -0.24376374, 0.06191025]), + 'gaze_valid': True, + 'gaze_vergence': 258.6637268066406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96009827, 0.27685547, 0.03918457]), + 'left_gaze_origin': array([-3.11166549, 2.94080973, 0.07049561]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.124298095703125, + 'left_pupil_posn': array([ 0.29202664, -0.0749234 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96585083, 0.25521851, 0.04450989]), + 'right_gaze_origin': array([-3.23547244, -3.42833734, 0.05332489]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0928192138671875, + 'right_pupil_posn': array([ 0.26447284, -0.15501344]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09787286072969437, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.4759552627802, + 'timestamp_carla': 335476, + 'timestamp_device': 4073689, + 'timestamp_stream': 335.4759552627802, + 'transform': [array([-5.27293384e-01, -1.59201078e+01, 1.18159773e-02]), + array([-0.07257076, -0.75456297, 0.00411988])]} +{'AngularVelocity': array([-0.01436769, 0.00351788, -1.00710893]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.212035179138184, + 'FR_Wheel_Angle': 13.251775741577148, + 'Location': array([ -3.45671749, -21.32079697, 0.17337288]), + 'Rotation': array([-0.06765302, -1.63400245, -0.00692749]), + 'Velocity': array([-0.39905867, -0.04524804, 0.00082093]), + 'brake_input': 0.0, + 'camera_location': array([-6.64997864, 12.03518009, 3.39050031]), + 'camera_rotation': array([-7.3348031 , -0.69999605, 2.5534122 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1360.1480712890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -510.64334106, -1597.25732422, 17.17234802]), + 'frame': 10214, + 'frame_number': 10214, + 'framesequence': 38972, + 'gaze_dir': array([0.96286774, 0.26577759, 0.04475403]), + 'gaze_origin': array([-3.17338586, -0.24219818, 0.06129227]), + 'gaze_valid': True, + 'gaze_vergence': 198.3572998046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95877075, 0.28060913, 0.0447998 ]), + 'left_gaze_origin': array([-3.11079574, 2.94187021, 0.06941376]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.125244140625, + 'left_pupil_posn': array([ 0.28972256, -0.07537031]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96696472, 0.25094604, 0.04470825]), + 'right_gaze_origin': array([-3.23597574, -3.42626643, 0.05317078]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0939178466796875, + 'right_pupil_posn': array([ 0.26445889, -0.1533072 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10673543810844421, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.51056376472116, + 'timestamp_carla': 335511, + 'timestamp_device': 4073723, + 'timestamp_stream': 335.51056376472116, + 'transform': [array([-5.59923410e-01, -1.58581800e+01, 1.17955869e-02]), + array([-0.07342453, -0.62298733, 0.00408936])]} +{'AngularVelocity': array([-0.03484651, 0.02555347, -1.91571176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.43227767944336, + 'FR_Wheel_Angle': 9.912558555603027, + 'Location': array([ -3.54478478, -21.32658577, 0.17345478]), + 'Rotation': array([-0.06722955, -2.00192237, -0.00598145]), + 'Velocity': array([-0.37715796, -0.02934869, 0.00056088]), + 'brake_input': 0.0, + 'camera_location': array([-6.61500549, 12.00544548, 3.38294911]), + 'camera_rotation': array([-7.49293566, -0.70208663, 3.15649223]), + 'current_gear_input': False, + 'focus_actor_dist': 1340.9288330078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -510.91809082, -1611.5402832 , 17.1776123 ]), + 'frame': 10215, + 'frame_number': 10215, + 'framesequence': 38976, + 'gaze_dir': array([0.96265411, 0.26675415, 0.04292297]), + 'gaze_origin': array([-3.17268372, -0.24064714, 0.06340408]), + 'gaze_valid': True, + 'gaze_vergence': 178.76315307617188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95837402, 0.28271484, 0.0398407 ]), + 'left_gaze_origin': array([-3.11073613, 2.94231272, 0.06928711]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.118804931640625, + 'left_pupil_posn': array([ 0.28937316, -0.07498801]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9669342 , 0.25079346, 0.04600525]), + 'right_gaze_origin': array([-3.23463154, -3.42360687, 0.05752106]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.100189208984375, + 'right_pupil_posn': array([ 0.26328754, -0.15184069]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.113913394510746, + 'throttle_input': 0.18252842128276825, + 'timestamp': 335.5424404628575, + 'timestamp_carla': 335543, + 'timestamp_device': 4073756, + 'timestamp_stream': 335.5424404628575, + 'transform': [array([-5.92722297e-01, -1.58003159e+01, 1.18424036e-02]), + array([-0.07397778, -0.49151129, 0.00390626])]} +{'AngularVelocity': array([-0.02465427, 0.02698144, -1.69983602]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.420588970184326, + 'FR_Wheel_Angle': 6.259906768798828, + 'Location': array([ -3.6352725 , -21.32971954, 0.17355594]), + 'Rotation': array([-0.07012555, -2.272156 , -0.00445557]), + 'Velocity': array([-0.42256764, -0.01685585, 0.0004292 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.60765934, 11.9591856 , 3.30976486]), + 'camera_rotation': array([-7.88109541, -0.80900455, 3.73290873]), + 'current_gear_input': False, + 'focus_actor_dist': 1240.6278076171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -490.99139404, -1704.43505859, 17.19043732]), + 'frame': 10216, + 'frame_number': 10216, + 'framesequence': 38980, + 'gaze_dir': array([0.96099091, 0.27017975, 0.05644226]), + 'gaze_origin': array([-3.17272496, -0.23998185, 0.06815415]), + 'gaze_valid': True, + 'gaze_vergence': 176.90060424804688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95632935, 0.28675842, 0.05641174]), + 'left_gaze_origin': array([-3.11013508, 2.94247603, 0.07501526]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1239776611328125, + 'left_pupil_posn': array([ 0.29030216, -0.06740236]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96565247, 0.25360107, 0.05647278]), + 'right_gaze_origin': array([-3.23531508, -3.42243981, 0.06129303]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1514892578125, + 'right_pupil_posn': array([ 0.26404226, -0.14375806]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12114628404378891, + 'throttle_input': 0.18649576604366302, + 'timestamp': 335.57502226158977, + 'timestamp_carla': 335575, + 'timestamp_device': 4073789, + 'timestamp_stream': 335.57502226158977, + 'transform': [array([-6.28923655e-01, -1.57404346e+01, 1.18889995e-02]), + array([-0.07440124, -0.34713706, 0.00369263])]} +{'AngularVelocity': array([-0.01223156, -0.01714338, -0.30430356]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.3081209659576416, + 'FR_Wheel_Angle': 1.7396483421325684, + 'Location': array([ -3.72876215, -21.32989883, 0.17365585]), + 'Rotation': array([-0.06982502, -2.40795922, -0.00494385]), + 'Velocity': array([-4.10044312e-01, 2.78430851e-03, 3.80659098e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.5825491 , 11.88240719, 3.24356318]), + 'camera_rotation': array([-8.19535923, -0.93697327, 4.30870247]), + 'current_gear_input': False, + 'focus_actor_dist': 1115.67724609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -465.97180176, -1820.38598633, 34.01087189]), + 'frame': 10217, + 'frame_number': 10217, + 'framesequence': 38984, + 'gaze_dir': array([0.96489716, 0.25238037, 0.07170868]), + 'gaze_origin': array([-3.16879034, -0.22960053, 0.07895584]), + 'gaze_valid': True, + 'gaze_vergence': 293.42108154296875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9622345 , 0.26194763, 0.07385254]), + 'left_gaze_origin': array([-3.10589623, 2.95264292, 0.08368836]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2772979736328125, + 'left_pupil_posn': array([ 0.27932835, -0.05616987]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96755981, 0.24281311, 0.06956482]), + 'right_gaze_origin': array([-3.23168492, -3.41184402, 0.07422333]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.087646484375, + 'right_pupil_posn': array([ 0.24786472, -0.12687242]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12845240533351898, + 'throttle_input': 0.1904631108045578, + 'timestamp': 335.6091528646648, + 'timestamp_carla': 335610, + 'timestamp_device': 4073823, + 'timestamp_stream': 335.6091528646648, + 'transform': [array([-6.69689178e-01, -1.56770153e+01, 1.19109629e-02]), + array([-0.07477008, -0.18536004, 0.00354004])]} +{'AngularVelocity': array([-0.01555772, 0.07262492, 1.02440965]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.45702341198921204, + 'FR_Wheel_Angle': -0.4716240167617798, + 'Location': array([ -3.82110715, -21.32668686, 0.1737186 ]), + 'Rotation': array([-0.06783743, -2.42715526, -0.00488281]), + 'Velocity': array([-4.25574988e-01, 2.01031733e-02, -6.58988938e-06]), + 'brake_input': 0.0, + 'camera_location': array([-6.54619598, 11.79765987, 3.16540098]), + 'camera_rotation': array([-8.44481087, -1.03086722, 4.87541962]), + 'current_gear_input': False, + 'focus_actor_dist': 1415.6475830078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -518.91455078, -1518.93261719, 17.15310669]), + 'frame': 10218, + 'frame_number': 10218, + 'framesequence': 38988, + 'gaze_dir': array([0.96483612, 0.24619293, 0.09169769]), + 'gaze_origin': array([-3.16771865, -0.22566836, 0.0893158 ]), + 'gaze_valid': True, + 'gaze_vergence': 442.9798278808594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96336365, 0.25257874, 0.09005737]), + 'left_gaze_origin': array([-3.10555577, 2.95503688, 0.09220887]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.182373046875, + 'left_pupil_posn': array([ 0.27671373, -0.04209948]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96630859, 0.23980713, 0.09333801]), + 'right_gaze_origin': array([-3.22988153, -3.40637374, 0.08642273]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1111602783203125, + 'right_pupil_posn': array([ 0.24060655, -0.11254013]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13658253848552704, + 'throttle_input': 0.1904631108045578, + 'timestamp': 335.6417850628495, + 'timestamp_carla': 335642, + 'timestamp_device': 4073856, + 'timestamp_stream': 335.6417850628495, + 'transform': [array([-7.11611629e-01, -1.56156321e+01, 1.19606592e-02]), + array([-0.07519355, -0.019779 , 0.00332642])]} +{'AngularVelocity': array([-0.01336366, 0.03382367, 1.07798755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.2429035902023315, + 'FR_Wheel_Angle': -1.4350777864456177, + 'Location': array([ -3.91970062, -21.32183075, 0.17382751]), + 'Rotation': array([-0.06789891, -2.39157128, -0.00274658]), + 'Velocity': array([-3.85154039e-01, 1.90961603e-02, 3.25479486e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.53792286, 11.74177933, 3.07597947]), + 'camera_rotation': array([-8.72809982, -1.18797112, 4.8698945 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1681.8233642578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -577.05102539, -1252.18786621, 17.13960266]), + 'frame': 10219, + 'frame_number': 10219, + 'framesequence': 38992, + 'gaze_dir': array([0.96498108, 0.2448349 , 0.09391022]), + 'gaze_origin': array([-3.16769028, -0.22982103, 0.09334259]), + 'gaze_valid': True, + 'gaze_vergence': 475.5151062011719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9634552 , 0.25106812, 0.09333801]), + 'left_gaze_origin': array([-3.10484481, 2.95226002, 0.09967652]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2816925048828125, + 'left_pupil_posn': array([ 0.27807128, -0.03672755]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96650696, 0.23860168, 0.09448242]), + 'right_gaze_origin': array([-3.23053598, -3.41190219, 0.08700867]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.130889892578125, + 'right_pupil_posn': array([ 0.24389994, -0.11125326]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.14394360780715942, + 'throttle_input': 0.1904631108045578, + 'timestamp': 335.67607656493783, + 'timestamp_carla': 335676, + 'timestamp_device': 4073889, + 'timestamp_stream': 335.67607656493783, + 'transform': [array([-7.58727074e-01, -1.55504589e+01, 1.19896792e-02]), + array([-0.07563068, 0.1655003 , 0.00314332])]} +{'AngularVelocity': array([-0.01103611, -0.01043625, -0.24182487]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.2022852897644043, + 'FR_Wheel_Angle': -3.3801276683807373, + 'Location': array([ -4.0161643 , -21.31591797, 0.17393604]), + 'Rotation': array([-0.06957913, -2.32189965, -0.00323486]), + 'Velocity': array([-0.41348928, 0.03124864, 0.0006389 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.52320194, 11.73149014, 3.03221059]), + 'camera_rotation': array([-9.01951694, -1.28895533, 4.32970905]), + 'current_gear_input': False, + 'focus_actor_dist': 1624.9166259765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -562.47406006, -1301.47253418, 17.13746643]), + 'frame': 10220, + 'frame_number': 10220, + 'framesequence': 38996, + 'gaze_dir': array([0.96491241, 0.24402618, 0.09658813]), + 'gaze_origin': array([-3.16766691, -0.23070528, 0.09546891]), + 'gaze_valid': True, + 'gaze_vergence': 391.8036193847656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96389771, 0.24946594, 0.09294128]), + 'left_gaze_origin': array([-3.10513473, 2.95141149, 0.10392914]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.35626220703125, + 'left_pupil_posn': array([ 0.27866411, -0.03196454]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96592712, 0.23858643, 0.10023499]), + 'right_gaze_origin': array([-3.23019886, -3.41282225, 0.08700867]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.127166748046875, + 'right_pupil_posn': array([ 0.24395692, -0.11125326]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.15280619263648987, + 'throttle_input': 0.1904631108045578, + 'timestamp': 335.7089119628072, + 'timestamp_carla': 335709, + 'timestamp_device': 4073923, + 'timestamp_stream': 335.7089119628072, + 'transform': [array([-8.07078362e-01, -1.54873323e+01, 1.20439529e-02]), + array([-0.07619759, 0.35484067, 0.00289918])]} +{'AngularVelocity': array([-0.00639883, 0.06928454, 1.75454068]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.959908485412598, + 'FR_Wheel_Angle': -4.806463241577148, + 'Location': array([ -4.1004405 , -21.30944824, 0.17400204]), + 'Rotation': array([-0.06793306, -2.18246484, -0.00256348]), + 'Velocity': array([-4.09517646e-01, 3.46646048e-02, 1.65901176e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.5134201 , 11.7584343 , 3.02672863]), + 'camera_rotation': array([-9.20816708, -1.16242743, 3.94182444]), + 'current_gear_input': False, + 'focus_actor_dist': 1627.7091064453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -563.76629639, -1292.62353516, 17.13645935]), + 'frame': 10221, + 'frame_number': 10221, + 'framesequence': 39000, + 'gaze_dir': array([0.96514893, 0.24320221, 0.09636688]), + 'gaze_origin': array([-3.16745305, -0.23119508, 0.09639741]), + 'gaze_valid': True, + 'gaze_vergence': 506.02252197265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96385193, 0.24885559, 0.09506226]), + 'left_gaze_origin': array([-3.10477138, 2.95142221, 0.10502167]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3276824951171875, + 'left_pupil_posn': array([ 0.27829242, -0.03196454]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96644592, 0.23754883, 0.09767151]), + 'right_gaze_origin': array([-3.23013473, -3.4138124 , 0.08777314]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1926727294921875, + 'right_pupil_posn': array([ 0.24442887, -0.11000347]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.16190679371356964, + 'throttle_input': 0.1904631108045578, + 'timestamp': 335.74202836304903, + 'timestamp_carla': 335742, + 'timestamp_device': 4073956, + 'timestamp_stream': 335.74202836304903, + 'transform': [array([-8.59343112e-01, -1.54229803e+01, 1.20909978e-02]), + array([-0.07690109, 0.55868942, 0.00265503])]} +{'AngularVelocity': array([-0.0120014 , 0.02438796, 1.51517367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.728240966796875, + 'FR_Wheel_Angle': -4.226475238800049, + 'Location': array([ -4.18083191, -21.30327034, 0.17410496]), + 'Rotation': array([-7.01596960e-02, -2.04858398e+00, -1.77001965e-03]), + 'Velocity': array([-0.42972654, 0.03410877, 0.00050389]), + 'brake_input': 0.0, + 'camera_location': array([-6.49332047, 11.82699966, 3.05214071]), + 'camera_rotation': array([-9.17520428, -0.84499192, 3.50991488]), + 'current_gear_input': False, + 'focus_actor_dist': 1591.2706298828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -562.14349365, -1323.73413086, 17.14279938]), + 'frame': 10222, + 'frame_number': 10222, + 'framesequence': 39004, + 'gaze_dir': array([0.96689606, 0.23664856, 0.09446716]), + 'gaze_origin': array([-3.16543984, -0.22878647, 0.0973198 ]), + 'gaze_valid': True, + 'gaze_vergence': 224.5889892578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96443176, 0.24853516, 0.08996582]), + 'left_gaze_origin': array([-3.10112619, 2.95503545, 0.10519715]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.278289794921875, + 'left_pupil_posn': array([ 0.27132916, -0.03021216]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96936035, 0.22476196, 0.09896851]), + 'right_gaze_origin': array([-3.22975326, -3.41260839, 0.08944245]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1970672607421875, + 'right_pupil_posn': array([ 0.24342406, -0.11052823]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.17016510665416718, + 'throttle_input': 0.1904631108045578, + 'timestamp': 335.7761535644531, + 'timestamp_carla': 335776, + 'timestamp_device': 4073989, + 'timestamp_stream': 335.7761535644531, + 'transform': [array([-9.16740119e-01, -1.53560534e+01, 1.21248150e-02]), + array([-0.07757729, 0.78167862, 0.00244142])]} +{'AngularVelocity': array([ 0.00505075, -0.00706898, 0.2842344 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.871352195739746, + 'FR_Wheel_Angle': -1.4765536785125732, + 'Location': array([ -4.27748632, -21.2969265 , 0.17420605]), + 'Rotation': array([-7.03441128e-02, -1.94259679e+00, -3.05175723e-04]), + 'Velocity': array([-4.35525835e-01, 2.66493354e-02, 1.93500513e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.45350647, 11.94838905, 3.10224843]), + 'camera_rotation': array([-9.00681305, -0.58959204, 3.02303624]), + 'current_gear_input': False, + 'focus_actor_dist': 1605.3834228515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -568.54705811, -1304.49865723, 17.14434052]), + 'frame': 10223, + 'frame_number': 10223, + 'framesequence': 39008, + 'gaze_dir': array([0.96841431, 0.23171234, 0.09165192]), + 'gaze_origin': array([-3.16385818, -0.22414628, 0.0944664 ]), + 'gaze_valid': True, + 'gaze_vergence': 377.6316223144531, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96646118, 0.23928833, 0.09320068]), + 'left_gaze_origin': array([-3.09895182, 2.96182251, 0.10372163]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2576446533203125, + 'left_pupil_posn': array([ 0.2663393 , -0.03389752]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97036743, 0.22413635, 0.09010315]), + 'right_gaze_origin': array([-3.22876453, -3.410115 , 0.08521119]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.176422119140625, + 'right_pupil_posn': array([ 0.23832762, -0.11193454]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.17822200059890747, + 'throttle_input': 0.1904631108045578, + 'timestamp': 335.80882166326046, + 'timestamp_carla': 335809, + 'timestamp_device': 4074023, + 'timestamp_stream': 335.80882166326046, + 'transform': [array([-9.75028813e-01, -1.52913771e+01, 1.21872136e-02]), + array([-0.07821249, 1.00725281, 0.00216676])]} +{'AngularVelocity': array([ 0.00846767, 0.01461985, -0.64366436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.09906259924173355, + 'FR_Wheel_Angle': -0.06601416319608688, + 'Location': array([ -4.3784647 , -21.29256248, 0.17430748]), + 'Rotation': array([-7.07334355e-02, -1.91812146e+00, 2.01265095e-04]), + 'Velocity': array([-0.47078609, 0.0175112 , 0.00052443]), + 'brake_input': 0.0, + 'camera_location': array([-6.41024399, 12.07559204, 3.12078786]), + 'camera_rotation': array([-8.86784554, -0.4812974 , 2.67497873]), + 'current_gear_input': False, + 'focus_actor_dist': 1652.494384765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -584.25640869, -1253.19494629, 17.14714813]), + 'frame': 10224, + 'frame_number': 10224, + 'framesequence': 39012, + 'gaze_dir': array([0.96723938, 0.23640442, 0.09228516]), + 'gaze_origin': array([-3.16398787, -0.2227318 , 0.09295045]), + 'gaze_valid': True, + 'gaze_vergence': 587.3905639648438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96606445, 0.24145508, 0.0916748 ]), + 'left_gaze_origin': array([-3.09912109, 2.96357751, 0.10251313]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2730560302734375, + 'left_pupil_posn': array([ 0.26767778, -0.03397989]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96841431, 0.23135376, 0.09289551]), + 'right_gaze_origin': array([-3.22885442, -3.40904117, 0.08338776]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1745452880859375, + 'right_pupil_posn': array([ 0.23832762, -0.11382186]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1854182481765747, + 'throttle_input': 0.19839780032634735, + 'timestamp': 335.84270506352186, + 'timestamp_carla': 335843, + 'timestamp_device': 4074056, + 'timestamp_stream': 335.84270506352186, + 'transform': [array([-1.03879738e+00, -1.52237720e+01, 1.22412015e-02]), + array([-0.07876574, 1.25310755, 0.0018921 ])]} +{'AngularVelocity': array([-0.00178077, -0.02718128, -0.15973978]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.06604664772748947, + 'FR_Wheel_Angle': -0.06602548807859421, + 'Location': array([ -4.51506138, -21.28781128, 0.17443012]), + 'Rotation': array([-7.04670548e-02, -1.92376733e+00, -7.01904239e-04]), + 'Velocity': array([-4.94846612e-01, 1.69067495e-02, -4.01592260e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.3645153 , 12.19053841, 3.10562325]), + 'camera_rotation': array([-8.81260967, -0.48444977, 2.54547358]), + 'current_gear_input': False, + 'focus_actor_dist': 1757.654052734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -627.52868652, -1149.06616211, 17.16432953]), + 'frame': 10225, + 'frame_number': 10225, + 'framesequence': 39016, + 'gaze_dir': array([0.9680481 , 0.23407745, 0.08934021]), + 'gaze_origin': array([-3.16376567, -0.22210923, 0.0916916 ]), + 'gaze_valid': True, + 'gaze_vergence': 311.3692321777344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96627808, 0.24266052, 0.08609009]), + 'left_gaze_origin': array([-3.09890604, 2.9642396 , 0.10138702]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2572174072265625, + 'left_pupil_posn': array([ 0.26515138, -0.03469133]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96981812, 0.22549438, 0.09259033]), + 'right_gaze_origin': array([-3.22862577, -3.40845799, 0.08199616]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.161590576171875, + 'right_pupil_posn': array([ 0.23832762, -0.11666179]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.19206519424915314, + 'throttle_input': 0.19839780032634735, + 'timestamp': 335.87562856450677, + 'timestamp_carla': 335876, + 'timestamp_device': 4074089, + 'timestamp_stream': 335.87562856450677, + 'transform': [array([-1.10386074e+00, -1.51575623e+01, 1.23137375e-02]), + array([-0.07922336, 1.50298452, 0.00158693])]} +{'AngularVelocity': array([-0.00178321, -0.01899159, -0.11906364]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.08387124538421631, + 'FR_Wheel_Angle': -0.09904463589191437, + 'Location': array([ -4.62615395, -21.28393936, 0.17453811]), + 'Rotation': array([-6.81721121e-02, -1.92465222e+00, -7.93456915e-04]), + 'Velocity': array([-4.65331018e-01, 1.61104482e-02, 4.22124867e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.33389759, 12.28739166, 3.07121658]), + 'camera_rotation': array([-8.98988056, -0.61689246, 2.6631155 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1720.7957763671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -621.69781494, -1179.08288574, 17.16609955]), + 'frame': 10226, + 'frame_number': 10226, + 'framesequence': 39020, + 'gaze_dir': array([0.97399139, 0.20184326, 0.10163879]), + 'gaze_origin': array([-3.13874817, -0.19428101, 0.09614869]), + 'gaze_valid': True, + 'gaze_vergence': 187.23472595214844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97155762, 0.21632385, 0.09617615]), + 'left_gaze_origin': array([-3.05502343, 2.99460459, 0.09862824]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2488861083984375, + 'left_pupil_posn': array([ 0.23034847, -0.02284443]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97642517, 0.18736267, 0.10710144]), + 'right_gaze_origin': array([-3.22247338, -3.38316679, 0.09366913]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1587371826171875, + 'right_pupil_posn': array([ 0.21124637, -0.10324574]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.19695426523685455, + 'throttle_input': 0.19839780032634735, + 'timestamp': 335.9087064638734, + 'timestamp_carla': 335909, + 'timestamp_device': 4074123, + 'timestamp_stream': 335.9087064638734, + 'transform': [array([-1.17197847e+00, -1.50905828e+01, 1.23963542e-02]), + array([-7.94692487e-02, 1.76359653e+00, 1.25122443e-03])]} +{'AngularVelocity': array([-0.00253645, -0.01378533, -0.25295395]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.2389744520187378, + 'FR_Wheel_Angle': -0.2382948249578476, + 'Location': array([ -4.72009754, -21.28063965, 0.17462638]), + 'Rotation': array([-6.85409456e-02, -1.91751099e+00, -7.93456915e-04]), + 'Velocity': array([-4.64527577e-01, 1.67042054e-02, 2.79235828e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.32726002, 12.38024902, 3.05357075]), + 'camera_rotation': array([-9.19777107, -0.77731758, 2.68071795]), + 'current_gear_input': False, + 'focus_actor_dist': 2013.2518310546875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-636.85302734, -874.76208496, 15.08521271]), + 'frame': 10227, + 'frame_number': 10227, + 'framesequence': 39024, + 'gaze_dir': array([0.97301483, 0.2078476 , 0.09886169]), + 'gaze_origin': array([-3.1499896 , -0.19895174, 0.10116883]), + 'gaze_valid': True, + 'gaze_vergence': 185.7523956298828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97052002, 0.22221375, 0.09315491]), + 'left_gaze_origin': array([-3.07748723, 2.9865799 , 0.10804597]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.224517822265625, + 'left_pupil_posn': array([ 0.23827541, -0.02157307]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97550964, 0.19348145, 0.10456848]), + 'right_gaze_origin': array([-3.2224915 , -3.38448358, 0.09429169]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1845550537109375, + 'right_pupil_posn': array([ 0.21423304, -0.10405552]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.2011658102273941, + 'throttle_input': 0.19839780032634735, + 'timestamp': 335.9431907646358, + 'timestamp_carla': 335944, + 'timestamp_device': 4074156, + 'timestamp_stream': 335.9431907646358, + 'transform': [array([-1.24554348e+00, -1.50203876e+01, 1.24741169e-02]), + array([-7.94965699e-02, 2.04393983e+00, 9.15533979e-04])]} +{'AngularVelocity': array([ 0.00608498, -0.01732845, 0.96427679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.23873116075992584, + 'FR_Wheel_Angle': -0.23817263543605804, + 'Location': array([ -4.84064341, -21.27645683, 0.17477921]), + 'Rotation': array([-7.09246770e-02, -1.89178431e+00, -8.23974609e-04]), + 'Velocity': array([-0.52872956, 0.02107897, 0.00062005]), + 'brake_input': 0.0, + 'camera_location': array([-6.30657768, 12.4686718 , 3.06371737]), + 'camera_rotation': array([-9.21559143, -0.96116102, 2.8045218 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1790.2216796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -601.91937256, -1089.39196777, 17.12319946]), + 'frame': 10228, + 'frame_number': 10228, + 'framesequence': 39028, + 'gaze_dir': array([0.97266388, 0.20801544, 0.10192108]), + 'gaze_origin': array([-3.1503036 , -0.19949342, 0.10045243]), + 'gaze_valid': True, + 'gaze_vergence': 189.12542724609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97000122, 0.22277832, 0.09718323]), + 'left_gaze_origin': array([-3.07790995, 2.9863236 , 0.10707703]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2732391357421875, + 'left_pupil_posn': array([ 0.23839962, -0.02157307]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97532654, 0.19325256, 0.10665894]), + 'right_gaze_origin': array([-3.2226975 , -3.38531065, 0.09382782]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1896820068359375, + 'right_pupil_posn': array([ 0.21502793, -0.10307336]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.2041505128145218, + 'throttle_input': 0.19839780032634735, + 'timestamp': 335.9759009629488, + 'timestamp_carla': 335976, + 'timestamp_device': 4074189, + 'timestamp_stream': 335.9759009629488, + 'transform': [array([-1.31747770e+00, -1.49534082e+01, 1.25866979e-02]), + array([-7.94009417e-02, 2.31691718e+00, 5.18799468e-04])]} +{'AngularVelocity': array([6.66142255e-03, 1.24440843e-03, 1.25768518e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22369113564491272, + 'FR_Wheel_Angle': -0.22325792908668518, + 'Location': array([ -4.96028233, -21.27222061, 0.17482792]), + 'Rotation': array([-6.74139634e-02, -1.88153064e+00, -2.13623236e-04]), + 'Velocity': array([-4.84340012e-01, 1.74052324e-02, -4.48484410e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.29374981, 12.5473423 , 3.09557843]), + 'camera_rotation': array([-9.19674015, -1.03444219, 3.0454309 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1852.9810791015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -621.26953125, -1022.41101074, 17.18748474]), + 'frame': 10229, + 'frame_number': 10229, + 'framesequence': 39032, + 'gaze_dir': array([0.97264099, 0.20811462, 0.10190582]), + 'gaze_origin': array([-3.15029478, -0.19942552, 0.09921647]), + 'gaze_valid': True, + 'gaze_vergence': 187.4230194091797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.970047 , 0.22276306, 0.09675598]), + 'left_gaze_origin': array([-3.07789326, 2.9865799 , 0.10489045]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.287322998046875, + 'left_pupil_posn': array([ 0.23828018, -0.02297354]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97523499, 0.19346619, 0.10705566]), + 'right_gaze_origin': array([-3.22269607, -3.38543105, 0.09354249]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1898193359375, + 'right_pupil_posn': array([ 0.21510434, -0.10342753]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.2052125632762909, + 'throttle_input': 0.19839780032634735, + 'timestamp': 336.00898526236415, + 'timestamp_carla': 336009, + 'timestamp_device': 4074223, + 'timestamp_stream': 336.00898526236415, + 'transform': [array([-1.39187181e+00, -1.48853331e+01, 1.27061745e-02]), + array([-7.91004151e-02, 2.59802437e+00, 9.15591736e-05])]} +{'AngularVelocity': array([-0.00307532, -0.00796094, 1.27447855]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22377759218215942, + 'FR_Wheel_Angle': -0.22341082990169525, + 'Location': array([ -5.06662416, -21.26853752, 0.17495616]), + 'Rotation': array([-6.70178160e-02, -1.87014771e+00, 3.73754447e-05]), + 'Velocity': array([-4.39192504e-01, 1.45291090e-02, 3.10068135e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.30253601, 12.63648605, 3.12033415]), + 'camera_rotation': array([-9.25173664, -1.05956709, 3.03407407]), + 'current_gear_input': False, + 'focus_actor_dist': 1838.04345703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -625.90344238, -1032.2923584 , 17.13552856]), + 'frame': 10230, + 'frame_number': 10230, + 'framesequence': 39036, + 'gaze_dir': array([0.97264099, 0.20814514, 0.10179901]), + 'gaze_origin': array([-3.15005231, -0.19914399, 0.09858933]), + 'gaze_valid': True, + 'gaze_vergence': 184.4202423095703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9699707 , 0.22311401, 0.09667969]), + 'left_gaze_origin': array([-3.07750249, 2.98698282, 0.10335083]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.290283203125, + 'left_pupil_posn': array([ 0.23789716, -0.02397478]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97531128, 0.19317627, 0.10691833]), + 'right_gaze_origin': array([-3.22260141, -3.38527083, 0.09382782]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2161102294921875, + 'right_pupil_posn': array([ 0.21510434, -0.10326767]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.20473647117614746, + 'throttle_input': 0.19839780032634735, + 'timestamp': 336.04285226389766, + 'timestamp_carla': 336043, + 'timestamp_device': 4074256, + 'timestamp_stream': 336.04285226389766, + 'transform': [array([-1.46914995e+00, -1.48153887e+01, 1.28227519e-02]), + array([-7.84925297e-02, 2.88869834e+00, -3.14182398e-04])]} +{'AngularVelocity': array([-0.00072506, 0.07731021, 0.48016879]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.223543182015419, + 'FR_Wheel_Angle': -0.22296303510665894, + 'Location': array([ -5.16746998, -21.26503563, 0.17506622]), + 'Rotation': array([-6.84794709e-02, -1.86190796e+00, 6.00306885e-05]), + 'Velocity': array([-4.73921150e-01, 1.60285141e-02, -3.13663477e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.35712242, 12.72216988, 3.15581203]), + 'camera_rotation': array([-9.12673759, -1.13647246, 2.73072505]), + 'current_gear_input': False, + 'focus_actor_dist': 1810.9407958984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -628.44226074, -1054.11523438, 17.14102173]), + 'frame': 10231, + 'frame_number': 10231, + 'framesequence': 39040, + 'gaze_dir': array([0.97383881, 0.20555115, 0.096138 ]), + 'gaze_origin': array([-3.14514112, -0.19542237, 0.09391785]), + 'gaze_valid': True, + 'gaze_vergence': 245.7950439453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97229004, 0.21537781, 0.09085083]), + 'left_gaze_origin': array([-3.06881428, 2.9936769 , 0.09835816]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3909454345703125, + 'left_pupil_posn': array([ 0.23402417, -0.02775407]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97538757, 0.19572449, 0.10142517]), + 'right_gaze_origin': array([-3.22146797, -3.38452148, 0.08947755]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3434906005859375, + 'right_pupil_posn': array([ 0.21170568, -0.10794592]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.2029602974653244, + 'throttle_input': 0.19839780032634735, + 'timestamp': 336.0757414624095, + 'timestamp_carla': 336076, + 'timestamp_device': 4074289, + 'timestamp_stream': 336.0757414624095, + 'transform': [array([-1.54484534e+00, -1.47471981e+01, 1.29565047e-02]), + array([-7.77275488e-02, 3.17202878e+00, -7.37654627e-04])]} +{'AngularVelocity': array([-0.00032596, -0.01027997, -0.14873764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22370165586471558, + 'FR_Wheel_Angle': -0.2232258915901184, + 'Location': array([ -5.28540993, -21.26093292, 0.17520802]), + 'Rotation': array([-6.86638877e-02, -1.85708630e+00, 2.55430088e-04]), + 'Velocity': array([-0.47145686, 0.01645694, 0.00083021]), + 'brake_input': 0.0, + 'camera_location': array([-6.35411739, 12.82703876, 3.21705842]), + 'camera_rotation': array([-8.81416035, -1.18687367, 2.433815 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1748.12646484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -615.00469971, -1108.70056152, 17.14137268]), + 'frame': 10232, + 'frame_number': 10232, + 'framesequence': 39044, + 'gaze_dir': array([0.97533417, 0.2000351 , 0.0920105 ]), + 'gaze_origin': array([-3.14064503, -0.19450989, 0.08469086]), + 'gaze_valid': True, + 'gaze_vergence': 163.0410919189453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97375488, 0.21203613, 0.08267212]), + 'left_gaze_origin': array([-3.06253982, 2.99537659, 0.08971253]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3301849365234375, + 'left_pupil_posn': array([ 0.23006701, -0.03237653]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97691345, 0.18803406, 0.10134888]), + 'right_gaze_origin': array([-3.21875024, -3.38439655, 0.07966919]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2721710205078125, + 'right_pupil_posn': array([ 0.2102735, -0.116889 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.19970093667507172, + 'throttle_input': 0.19839780032634735, + 'timestamp': 336.10915676504374, + 'timestamp_carla': 336110, + 'timestamp_device': 4074323, + 'timestamp_stream': 336.10915676504374, + 'transform': [array([-1.62189019e+00, -1.46776829e+01, 1.30920885e-02]), + array([-7.67508298e-02, 3.45890832e+00, -1.16795546e-03])]} +{'AngularVelocity': array([-0.00557098, -0.01391785, 1.25369787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22369170188903809, + 'FR_Wheel_Angle': -0.22327610850334167, + 'Location': array([ -5.39490175, -21.25710487, 0.17531078]), + 'Rotation': array([-6.82062656e-02, -1.84335315e+00, 4.02272621e-04]), + 'Velocity': array([-0.45920405, 0.01574555, 0.00079642]), + 'brake_input': 0.0, + 'camera_location': array([-6.31005478, 12.9243288 , 3.22074866]), + 'camera_rotation': array([-8.5267868 , -1.27004373, 2.34849596]), + 'current_gear_input': False, + 'focus_actor_dist': 1809.35400390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -626.96020508, -1041.57250977, 17.13632202]), + 'frame': 10233, + 'frame_number': 10233, + 'framesequence': 39048, + 'gaze_dir': array([0.97489166, 0.20505524, 0.08592224]), + 'gaze_origin': array([-3.13864827, -0.19339448, 0.08044968]), + 'gaze_valid': True, + 'gaze_vergence': 230.66307067871094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97343445, 0.21458435, 0.07974243]), + 'left_gaze_origin': array([-3.05763412, 2.99673629, 0.08454285]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2896270751953125, + 'left_pupil_posn': array([ 0.231722 , -0.0380441]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97634888, 0.19552612, 0.09210205]), + 'right_gaze_origin': array([-3.21966267, -3.38352513, 0.07635652]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3494720458984375, + 'right_pupil_posn': array([ 0.21049595, -0.12063086]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.19537949562072754, + 'throttle_input': 0.19839780032634735, + 'timestamp': 336.1419990621507, + 'timestamp_carla': 336142, + 'timestamp_device': 4074356, + 'timestamp_stream': 336.1419990621507, + 'transform': [array([-1.69733405e+00, -1.46091242e+01, 1.32379532e-02]), + array([-7.56306797e-02, 3.73826480e+00, -1.60508917e-03])]} +{'AngularVelocity': array([0.00925762, 0.01093016, 0.81563318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22375091910362244, + 'FR_Wheel_Angle': -0.22310052812099457, + 'Location': array([ -5.50039482, -21.25338173, 0.17542084]), + 'Rotation': array([-6.84521496e-02, -1.83798230e+00, 5.82482375e-04]), + 'Velocity': array([-0.46163878, 0.01722275, 0.00112488]), + 'brake_input': 0.0, + 'camera_location': array([-6.33980942, 12.99796295, 3.24112725]), + 'camera_rotation': array([-8.44429207, -1.33931923, 2.3270545 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1783.6920166015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -636.39367676, -1063.34484863, 17.15142822]), + 'frame': 10234, + 'frame_number': 10234, + 'framesequence': 39052, + 'gaze_dir': array([0.97502136, 0.2028656 , 0.08937836]), + 'gaze_origin': array([-3.13463855, -0.1919716 , 0.07613984]), + 'gaze_valid': True, + 'gaze_vergence': 213.859130859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97319031, 0.21429443, 0.08340454]), + 'left_gaze_origin': array([-3.05010557, 2.99773884, 0.07924043]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3592071533203125, + 'left_pupil_posn': array([ 0.22946429, -0.03918004]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97685242, 0.19143677, 0.09535217]), + 'right_gaze_origin': array([-3.21917129, -3.38168192, 0.07303925]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2947235107421875, + 'right_pupil_posn': array([ 0.20913148, -0.12148821]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.18975800275802612, + 'throttle_input': 0.1745937317609787, + 'timestamp': 336.17628206312656, + 'timestamp_carla': 336177, + 'timestamp_device': 4074389, + 'timestamp_stream': 336.17628206312656, + 'transform': [array([-1.77523339e+00, -1.45373888e+01, 1.33639146e-02]), + array([-7.42851347e-02, 4.02497959e+00, -1.98075292e-03])]} +{'AngularVelocity': array([-0.00268996, -0.02563637, 0.22989148]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22339048981666565, + 'FR_Wheel_Angle': -0.22298941016197205, + 'Location': array([ -5.63734961, -21.24872589, 0.17557479]), + 'Rotation': array([-7.13823065e-02, -1.82232678e+00, 7.73320266e-04]), + 'Velocity': array([-0.535537 , 0.01856848, 0.00057878]), + 'brake_input': 0.0, + 'camera_location': array([-6.36427116, 13.06765366, 3.2592063 ]), + 'camera_rotation': array([-8.41997623, -1.39691854, 2.31571269]), + 'current_gear_input': False, + 'focus_actor_dist': 1958.490966796875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-683.44592285, -887.74389648, 15.05634308]), + 'frame': 10235, + 'frame_number': 10235, + 'framesequence': 39056, + 'gaze_dir': array([0.97576904, 0.19995117, 0.08747101]), + 'gaze_origin': array([-3.12801886, -0.18960495, 0.07076187]), + 'gaze_valid': True, + 'gaze_vergence': 196.76470947265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97358704, 0.21315002, 0.08164978]), + 'left_gaze_origin': array([-3.0375123 , 2.99914098, 0.07114258]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.302032470703125, + 'left_pupil_posn': array([ 0.2266053 , -0.04318631]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97795105, 0.18675232, 0.09329224]), + 'right_gaze_origin': array([-3.21852612, -3.37835097, 0.07038117]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2979888916015625, + 'right_pupil_posn': array([ 0.20635426, -0.12383175]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.18279977142810822, + 'throttle_input': 0.17062638700008392, + 'timestamp': 336.2093157619238, + 'timestamp_carla': 336210, + 'timestamp_device': 4074423, + 'timestamp_stream': 336.2093157619238, + 'transform': [array([-1.84896827e+00, -1.44681005e+01, 1.34914871e-02]), + array([-7.28439614e-02, 4.29452085e+00, -2.29493529e-03])]} +{'AngularVelocity': array([-0.00238487, -0.01439914, 0.2752924 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.2234865427017212, + 'FR_Wheel_Angle': -0.22051699459552765, + 'Location': array([ -5.75837517, -21.24459457, 0.175662 ]), + 'Rotation': array([-6.83906823e-02, -1.81317163e+00, 9.78254597e-04]), + 'Velocity': array([-5.06696761e-01, 1.75236501e-02, 3.47843161e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.39356232, 13.1364193 , 3.27245188]), + 'camera_rotation': array([-8.3599329 , -1.42057252, 2.44718313]), + 'current_gear_input': False, + 'focus_actor_dist': 1916.4273681640625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-676.01977539, -922.0189209 , 14.96955872]), + 'frame': 10236, + 'frame_number': 10236, + 'framesequence': 39060, + 'gaze_dir': array([0.97602081, 0.20024872, 0.08401489]), + 'gaze_origin': array([-3.1239624 , -0.18603212, 0.06722184]), + 'gaze_valid': True, + 'gaze_vergence': 202.62518310546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97369385, 0.21368408, 0.07907104]), + 'left_gaze_origin': array([-3.03125763, 3.00308704, 0.06638642]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.377197265625, + 'left_pupil_posn': array([ 0.22393405, -0.04642141]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97834778, 0.18681335, 0.08895874]), + 'right_gaze_origin': array([-3.21666741, -3.3751514 , 0.06805725]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3899078369140625, + 'right_pupil_posn': array([ 0.204229 , -0.12602842]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.17598803341388702, + 'throttle_input': 0.16665904223918915, + 'timestamp': 336.2419741638005, + 'timestamp_carla': 336242, + 'timestamp_device': 4074456, + 'timestamp_stream': 336.2419741638005, + 'transform': [array([-1.92031002e+00, -1.43994646e+01, 1.36084454e-02]), + array([-7.13823065e-02, 4.55351353e+00, -2.55448348e-03])]} +{'AngularVelocity': array([-0.00942616, -0.00828659, -0.83356273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1969803422689438, + 'FR_Wheel_Angle': -0.19661754369735718, + 'Location': array([ -5.87286472, -21.24063492, 0.17579426]), + 'Rotation': array([-6.74754381e-02, -1.81283581e+00, 1.14764832e-03]), + 'Velocity': array([-0.47782126, 0.01604421, 0.00077007]), + 'brake_input': 0.0, + 'camera_location': array([-6.4228754 , 13.16084957, 3.26659226]), + 'camera_rotation': array([-8.32833576, -1.36765754, 2.71952367]), + 'current_gear_input': False, + 'focus_actor_dist': 1800.6446533203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -656.57714844, -1029.57397461, 17.18065643]), + 'frame': 10237, + 'frame_number': 10237, + 'framesequence': 39064, + 'gaze_dir': array([0.97698975, 0.19271851, 0.08996582]), + 'gaze_origin': array([-3.12297988, -0.18087998, 0.06659774]), + 'gaze_valid': True, + 'gaze_vergence': 167.17735290527344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97537231, 0.20510864, 0.08105469]), + 'left_gaze_origin': array([-3.03315306, 3.00976276, 0.06636963]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3489227294921875, + 'left_pupil_posn': array([ 0.21719539, -0.04331088]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97860718, 0.18032837, 0.09887695]), + 'right_gaze_origin': array([-3.21280694, -3.37152267, 0.06682587]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.477325439453125, + 'right_pupil_posn': array([ 0.19849324, -0.12543404]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1684255450963974, + 'throttle_input': 0.16269169747829437, + 'timestamp': 336.2767272628844, + 'timestamp_carla': 336277, + 'timestamp_device': 4074489, + 'timestamp_stream': 336.2767272628844, + 'transform': [array([-1.99418557e+00, -1.43263950e+01, 1.36788273e-02]), + array([-6.97977021e-02, 4.81965256e+00, -2.67059566e-03])]} +{'AngularVelocity': array([-0.00802304, -0.00197058, -0.99016577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.19721440970897675, + 'FR_Wheel_Angle': -0.19688253104686737, + 'Location': array([ -5.97695732, -21.23715019, 0.17587334]), + 'Rotation': array([-6.55561537e-02, -1.80368042e+00, 1.38666900e-03]), + 'Velocity': array([-4.11609560e-01, 1.35245277e-02, 2.29406345e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.43474483, 13.17825317, 3.25443697]), + 'camera_rotation': array([-8.39188385, -1.3310746 , 2.78573871]), + 'current_gear_input': False, + 'focus_actor_dist': 1998.9736328125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-704.78588867, -829.81311035, 15.20366669]), + 'frame': 10238, + 'frame_number': 10238, + 'framesequence': 39068, + 'gaze_dir': array([0.97744751, 0.19261932, 0.08455658]), + 'gaze_origin': array([-3.12139225, -0.17946626, 0.06667252]), + 'gaze_valid': True, + 'gaze_vergence': 133.30799865722656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97570801, 0.20655823, 0.07293701]), + 'left_gaze_origin': array([-3.03197193, 3.01114511, 0.06701355]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3485870361328125, + 'left_pupil_posn': array([ 0.21562934, -0.04362524]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97918701, 0.17868042, 0.09617615]), + 'right_gaze_origin': array([-3.21081233, -3.37007761, 0.06633148]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.417694091796875, + 'right_pupil_posn': array([ 0.19792867, -0.12814105]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1610644906759262, + 'throttle_input': 0.1587243527173996, + 'timestamp': 336.3085041642189, + 'timestamp_carla': 336309, + 'timestamp_device': 4074523, + 'timestamp_stream': 336.3085041642189, + 'transform': [array([-2.05986404e+00, -1.42594719e+01, 1.37678906e-02]), + array([-6.84521496e-02, 5.05438185e+00, -2.77987914e-03])]} +{'AngularVelocity': array([-0.0058829 , 0.03141047, -0.54383945]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1974170058965683, + 'FR_Wheel_Angle': -0.19692300260066986, + 'Location': array([ -6.06706047, -21.23416138, 0.17595768]), + 'Rotation': array([-6.57337382e-02, -1.79074085e+00, 1.58686563e-03]), + 'Velocity': array([-3.73457491e-01, 1.18496455e-02, 1.01823804e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.43626308, 13.18600178, 3.26028752]), + 'camera_rotation': array([-8.41273689, -1.37175643, 2.73971105]), + 'current_gear_input': False, + 'focus_actor_dist': 1772.7110595703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -657.82641602, -1044.18017578, 17.16821289]), + 'frame': 10239, + 'frame_number': 10239, + 'framesequence': 39072, + 'gaze_dir': array([0.97800446, 0.18972015, 0.08489227]), + 'gaze_origin': array([-3.11884236, -0.17820893, 0.06586152]), + 'gaze_valid': True, + 'gaze_vergence': 144.76222229003906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97637939, 0.20285034, 0.07424927]), + 'left_gaze_origin': array([-3.02732873, 3.01254606, 0.06636963]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3491973876953125, + 'left_pupil_posn': array([ 0.21390581, -0.04331088]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97962952, 0.17658997, 0.09553528]), + 'right_gaze_origin': array([-3.21035647, -3.36896372, 0.06535339]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4073638916015625, + 'right_pupil_posn': array([ 0.19584811, -0.12815201]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1530442237854004, + 'throttle_input': 0.15078964829444885, + 'timestamp': 336.3442889638245, + 'timestamp_carla': 336345, + 'timestamp_device': 4074556, + 'timestamp_stream': 336.3442889638245, + 'transform': [array([-2.13129568e+00, -1.41841450e+01, 1.37935346e-02]), + array([-6.68948665e-02, 5.30745745e+00, -2.73889885e-03])]} +{'AngularVelocity': array([0.00610979, 0.03020704, 0.48827738]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.19109855592250824, + 'FR_Wheel_Angle': -0.1829451322555542, + 'Location': array([ -6.14033365, -21.23207283, 0.1760509 ]), + 'Rotation': array([-0.06747544, -1.75161755, 0.00187312]), + 'Velocity': array([-3.78439546e-01, 1.13057476e-02, 2.90384283e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.43984699, 13.1658411 , 3.26571536]), + 'camera_rotation': array([-8.36562252, -1.41017544, 2.89536881]), + 'current_gear_input': False, + 'focus_actor_dist': 1777.5462646484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -660.87854004, -1032.98352051, 17.17144775]), + 'frame': 10240, + 'frame_number': 10240, + 'framesequence': 39076, + 'gaze_dir': array([0.97841644, 0.18785858, 0.08403778]), + 'gaze_origin': array([-3.11731052, -0.17769395, 0.06576386]), + 'gaze_valid': True, + 'gaze_vergence': 137.5042266845703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97668457, 0.20187378, 0.07287598]), + 'left_gaze_origin': array([-3.02482629, 3.01306629, 0.06567078]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3494415283203125, + 'left_pupil_posn': array([ 0.21257472, -0.04338956]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98014832, 0.17384338, 0.09519958]), + 'right_gaze_origin': array([-3.20979476, -3.36845398, 0.06585694]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4073944091796875, + 'right_pupil_posn': array([ 0.1951195 , -0.12816298]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.1437971144914627, + 'throttle_input': 0.13492026925086975, + 'timestamp': 336.37597316503525, + 'timestamp_carla': 336376, + 'timestamp_device': 4074589, + 'timestamp_stream': 336.37597316503525, + 'transform': [array([-2.19205046e+00, -1.41173754e+01, 1.38630578e-02]), + array([-6.55288324e-02, 5.52054739e+00, -2.73890118e-03])]} +{'AngularVelocity': array([-0.01014138, 0.02245536, 0.99104714]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.16549043357372284, + 'FR_Wheel_Angle': -0.1651146411895752, + 'Location': array([ -6.22962284, -21.22912788, 0.17613895]), + 'Rotation': array([-6.98591694e-02, -1.75201428e+00, 1.74768490e-03]), + 'Velocity': array([-4.10386771e-01, 1.19217737e-02, -2.06279747e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.43054295, 13.13677025, 3.25475717]), + 'camera_rotation': array([-8.3398037 , -1.47524786, 2.95009804]), + 'current_gear_input': False, + 'focus_actor_dist': 1763.6683349609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -662.03955078, -1039.79821777, 17.17134857]), + 'frame': 10241, + 'frame_number': 10241, + 'framesequence': 39080, + 'gaze_dir': array([0.97835541, 0.18787384, 0.08475494]), + 'gaze_origin': array([-3.11605024, -0.17675172, 0.06435928]), + 'gaze_valid': True, + 'gaze_vergence': 126.46511840820312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.977005 , 0.20056152, 0.07225037]), + 'left_gaze_origin': array([-3.02274632, 3.01432967, 0.06343994]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.349395751953125, + 'left_pupil_posn': array([ 0.21216261, -0.04383099]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97970581, 0.17518616, 0.09725952]), + 'right_gaze_origin': array([-3.20935369, -3.36783314, 0.06527863]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4105987548828125, + 'right_pupil_posn': array([ 0.19420552, -0.12865496]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.13517259061336517, + 'throttle_input': 0.11506828665733337, + 'timestamp': 336.41016206145287, + 'timestamp_carla': 336410, + 'timestamp_device': 4074623, + 'timestamp_stream': 336.41016206145287, + 'transform': [array([-2.25465703e+00, -1.40453711e+01, 1.38841914e-02]), + array([-6.39988706e-02, 5.73779106e+00, -2.61595799e-03])]} +{'AngularVelocity': array([0.00514293, 0.03001743, 0.64102519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1591624915599823, + 'FR_Wheel_Angle': -0.157626211643219, + 'Location': array([ -6.32269096, -21.22617722, 0.17623383]), + 'Rotation': array([-6.91829845e-02, -1.75088501e+00, 1.69054326e-03]), + 'Velocity': array([-4.19577897e-01, 1.48392431e-02, 1.81255338e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.40732193, 13.10853291, 3.24371004]), + 'camera_rotation': array([-8.3735857 , -1.58584464, 2.89147615]), + 'current_gear_input': False, + 'focus_actor_dist': 1786.872314453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -673.83630371, -1011.84924316, 17.30950165]), + 'frame': 10242, + 'frame_number': 10242, + 'framesequence': 39084, + 'gaze_dir': array([0.97841644, 0.1891861 , 0.08119965]), + 'gaze_origin': array([-3.11294198, -0.17442094, 0.06395035]), + 'gaze_valid': True, + 'gaze_vergence': 136.67225646972656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97698975, 0.20150757, 0.06967163]), + 'left_gaze_origin': array([-3.01995564, 3.01597929, 0.0624054 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.350555419921875, + 'left_pupil_posn': array([ 0.21156526, -0.04557943]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97984314, 0.17686462, 0.09272766]), + 'right_gaze_origin': array([-3.20592833, -3.3648212 , 0.0654953 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3978118896484375, + 'right_pupil_posn': array([ 0.19234324, -0.12873018]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.12614521384239197, + 'throttle_input': 0.09126421064138412, + 'timestamp': 336.4430691637099, + 'timestamp_carla': 336443, + 'timestamp_device': 4074656, + 'timestamp_stream': 336.4430691637099, + 'transform': [array([-2.31193757e+00, -1.39761534e+01, 1.38895409e-02]), + array([-6.25986829e-02, 5.93418932e+00, -2.38373061e-03])]} +{'AngularVelocity': array([-0.00591592, 0.06524505, -0.56678134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1552104353904724, + 'FR_Wheel_Angle': -0.15499237179756165, + 'Location': array([ -6.41234398, -21.22323227, 0.1763337 ]), + 'Rotation': array([-0.06933325, -1.74807727, 0.00192596]), + 'Velocity': array([-0.43422455, 0.01408173, 0.00060664]), + 'brake_input': 0.0, + 'camera_location': array([-6.3972559 , 13.06635475, 3.21360946]), + 'camera_rotation': array([-8.50289536, -1.68009448, 2.9403193 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1689.140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -654.34197998, -1100.46691895, 17.179039 ]), + 'frame': 10243, + 'frame_number': 10243, + 'framesequence': 39088, + 'gaze_dir': array([0.97939301, 0.18466187, 0.08016205]), + 'gaze_origin': array([-3.11020589, -0.17393647, 0.06216965]), + 'gaze_valid': True, + 'gaze_vergence': 128.7469940185547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97860718, 0.19403076, 0.06819153]), + 'left_gaze_origin': array([-3.01795363, 3.01748657, 0.06169892]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3510894775390625, + 'left_pupil_posn': array([ 0.20997059, -0.0458653 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98017883, 0.17529297, 0.09213257]), + 'right_gaze_origin': array([-3.20245838, -3.36535978, 0.06264038]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4457244873046875, + 'right_pupil_posn': array([ 0.18991113, -0.13049281]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.11645863950252533, + 'throttle_input': 0.07539482414722443, + 'timestamp': 336.4751169644296, + 'timestamp_carla': 336475, + 'timestamp_device': 4074689, + 'timestamp_stream': 336.4751169644296, + 'transform': [array([-2.36455822e+00, -1.39088860e+01, 1.38769718e-02]), + array([-6.11575097e-02, 6.11217356e+00, -2.05588341e-03])]} +{'AngularVelocity': array([-0.00089785, -0.04229906, -0.19274963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.15537293255329132, + 'FR_Wheel_Angle': -0.1551963984966278, + 'Location': array([ -6.50142479, -21.22036743, 0.17641014]), + 'Rotation': array([-0.06677192, -1.7404176 , 0.00210534]), + 'Velocity': array([-0.33297741, 0.01143396, 0.00036015]), + 'brake_input': 0.0, + 'camera_location': array([-6.37861633, 13.02553368, 3.20010304]), + 'camera_rotation': array([-8.54416275, -1.83700192, 2.74648309]), + 'current_gear_input': False, + 'focus_actor_dist': 1613.879638671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -631.25769043, -1165.06970215, 17.17220306]), + 'frame': 10244, + 'frame_number': 10244, + 'framesequence': 39092, + 'gaze_dir': array([0.97949219, 0.18360138, 0.08174896]), + 'gaze_origin': array([-3.10838699, -0.17367402, 0.06075287]), + 'gaze_valid': True, + 'gaze_vergence': 161.89585876464844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97851562, 0.19316101, 0.07197571]), + 'left_gaze_origin': array([-3.016922 , 3.01803303, 0.06169892]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3509368896484375, + 'left_pupil_posn': array([ 0.20914698, -0.0458653 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98046875, 0.17404175, 0.09152222]), + 'right_gaze_origin': array([-3.19985223, -3.365381 , 0.05980683]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4126434326171875, + 'right_pupil_posn': array([ 0.18959033, -0.13053548]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.10805384069681168, + 'throttle_input': 0.07142747938632965, + 'timestamp': 336.5098032616079, + 'timestamp_carla': 336510, + 'timestamp_device': 4074723, + 'timestamp_stream': 336.5098032616079, + 'transform': [array([-2.41802406e+00, -1.38364487e+01, 1.37822628e-02]), + array([-5.97573221e-02, 6.29038477e+00, -1.46848604e-03])]} +{'AngularVelocity': array([-0.0111654 , 0.03226282, -0.79866701]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.14669501781463623, + 'FR_Wheel_Angle': -0.14146830141544342, + 'Location': array([ -6.57433891, -21.21772194, 0.17647345]), + 'Rotation': array([-0.06533758, -1.75280762, 0.00209108]), + 'Velocity': array([-0.29607436, 0.01008892, 0.00063538]), + 'brake_input': 0.0, + 'camera_location': array([-6.35759926, 12.98434544, 3.19722533]), + 'camera_rotation': array([-8.58925629, -1.94289911, 2.80174994]), + 'current_gear_input': False, + 'focus_actor_dist': 1647.1676025390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -639.67108154, -1125.63781738, 17.17063141]), + 'frame': 10245, + 'frame_number': 10245, + 'framesequence': 39096, + 'gaze_dir': array([0.98056793, 0.17336273, 0.0895462 ]), + 'gaze_origin': array([-3.08192992, -0.16310655, 0.05361328]), + 'gaze_valid': True, + 'gaze_vergence': 122.21929168701172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97900391, 0.18878174, 0.076828 ]), + 'left_gaze_origin': array([-2.97380543, 3.02966475, 0.04764557]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.301788330078125, + 'left_pupil_posn': array([ 0.19523227, -0.04342258]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98213196, 0.15794373, 0.1022644 ]), + 'right_gaze_origin': array([-3.19005442, -3.35587788, 0.059581 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4335479736328125, + 'right_pupil_posn': array([ 0.18120658, -0.12707341]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09785455465316772, + 'throttle_input': 0.07142747938632965, + 'timestamp': 336.54289546236396, + 'timestamp_carla': 336543, + 'timestamp_device': 4074756, + 'timestamp_stream': 336.54289546236396, + 'transform': [array([-2.46544909e+00, -1.37677040e+01, 1.36914253e-02]), + array([-5.84049448e-02, 6.44568062e+00, -8.26447678e-04])]} +{'AngularVelocity': array([ 0.01331449, 0.07750063, -1.13002241]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1339840292930603, + 'FR_Wheel_Angle': -0.13385896384716034, + 'Location': array([ -6.63390779, -21.21553993, 0.17654811]), + 'Rotation': array([-0.06759155, -1.76239014, 0.00288389]), + 'Velocity': array([-0.30492496, 0.0095259 , 0.00035372]), + 'brake_input': 0.0, + 'camera_location': array([-6.3408308 , 12.94509888, 3.18971586]), + 'camera_rotation': array([-8.69118977, -2.08657765, 2.83959842]), + 'current_gear_input': False, + 'focus_actor_dist': 1855.2962646484375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-679.49963379, -912.80944824, 14.99298859]), + 'frame': 10246, + 'frame_number': 10246, + 'framesequence': 39100, + 'gaze_dir': array([0.98080444, 0.1750946 , 0.08369446]), + 'gaze_origin': array([-3.09026957, -0.16661225, 0.05524826]), + 'gaze_valid': True, + 'gaze_vergence': 128.0766143798828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97949219, 0.18833923, 0.07136536]), + 'left_gaze_origin': array([-2.99252653, 3.02543521, 0.05387726]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3604278564453125, + 'left_pupil_posn': array([ 0.19962478, -0.04489696]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9821167 , 0.16184998, 0.09602356]), + 'right_gaze_origin': array([-3.18801284, -3.35865951, 0.05661927]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4217071533203125, + 'right_pupil_posn': array([ 0.18285918, -0.1306175 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08912014961242676, + 'throttle_input': 0.07142747938632965, + 'timestamp': 336.5773298628628, + 'timestamp_carla': 336578, + 'timestamp_device': 4074789, + 'timestamp_stream': 336.5773298628628, + 'transform': [array([-2.51111484e+00, -1.36966305e+01, 1.35692405e-02]), + array([-5.71276993e-02, 6.59231234e+00, -1.02449754e-04])]} +{'AngularVelocity': array([0.00671394, 0.00362006, 0.1962408 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.13149026036262512, + 'FR_Wheel_Angle': -0.13128404319286346, + 'Location': array([ -6.70231247, -21.21338272, 0.17663719]), + 'Rotation': array([-0.06729102, -1.751068 , 0.00294303]), + 'Velocity': array([-0.22821431, 0.00565619, 0.00058646]), + 'brake_input': 0.0, + 'camera_location': array([-6.32479954, 12.93471909, 3.17269325]), + 'camera_rotation': array([-8.7891283 , -2.2340529 , 2.59745693]), + 'current_gear_input': False, + 'focus_actor_dist': 1631.1756591796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -626.90167236, -1123.85620117, 17.15724945]), + 'frame': 10247, + 'frame_number': 10247, + 'framesequence': 39104, + 'gaze_dir': array([0.9809494 , 0.17448425, 0.08348083]), + 'gaze_origin': array([-3.08950353, -0.1661728 , 0.05521698]), + 'gaze_valid': True, + 'gaze_vergence': 135.55767822265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97958374, 0.18769836, 0.07191467]), + 'left_gaze_origin': array([-2.99104333, 3.0260849 , 0.05418854]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.41546630859375, + 'left_pupil_posn': array([ 0.19892609, -0.04485893]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98231506, 0.16127014, 0.095047 ]), + 'right_gaze_origin': array([-3.1879642 , -3.35843086, 0.05624542]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3816986083984375, + 'right_pupil_posn': array([ 0.18249929, -0.13056743]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07985474169254303, + 'throttle_input': 0.07142747938632965, + 'timestamp': 336.6108483634889, + 'timestamp_carla': 336611, + 'timestamp_device': 4074823, + 'timestamp_stream': 336.6108483634889, + 'transform': [array([-2.55202627e+00, -1.36278744e+01, 1.34624671e-02]), + array([-5.60007170e-02, 6.72069311e+00, 5.79839689e-04])]} +{'AngularVelocity': array([0.0018828 , 0.03824387, 0.75485969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.098272904753685, + 'FR_Wheel_Angle': -0.09051403403282166, + 'Location': array([ -6.7519269 , -21.21150398, 0.17668457]), + 'Rotation': array([-0.06927177, -1.76950097, 0.00259562]), + 'Velocity': array([-0.27157271, 0.00913348, 0.00052982]), + 'brake_input': 0.0, + 'camera_location': array([-6.30961323, 12.91745758, 3.13802361]), + 'camera_rotation': array([-8.83408451, -2.29686642, 2.72628617]), + 'current_gear_input': False, + 'focus_actor_dist': 1606.0421142578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -620.20849609, -1140.63024902, 17.15479279]), + 'frame': 10248, + 'frame_number': 10248, + 'framesequence': 39108, + 'gaze_dir': array([0.98073578, 0.17497253, 0.08467102]), + 'gaze_origin': array([-3.08921456, -0.16582642, 0.05553894]), + 'gaze_valid': True, + 'gaze_vergence': 116.3825912475586, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97961426, 0.18785095, 0.07106018]), + 'left_gaze_origin': array([-2.99058867, 3.02661753, 0.05447694]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4090423583984375, + 'left_pupil_posn': array([ 0.19886112, -0.04348958]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9818573 , 0.16209412, 0.09828186]), + 'right_gaze_origin': array([-3.18784046, -3.35827065, 0.05660095]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3813629150390625, + 'right_pupil_posn': array([ 0.18243527, -0.13059247]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07097384333610535, + 'throttle_input': 0.07142747938632965, + 'timestamp': 336.64321456477046, + 'timestamp_carla': 336643, + 'timestamp_device': 4074856, + 'timestamp_stream': 336.64321456477046, + 'transform': [array([-2.58819509e+00, -1.35618401e+01, 1.33886719e-02]), + array([-5.49898483e-02, 6.83121157e+00, 1.12915691e-03])]} +{'AngularVelocity': array([ 0.00072112, 0.00297987, -0.04810328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.088143490254879, + 'FR_Wheel_Angle': -0.08803018927574158, + 'Location': array([ -6.80089331, -21.21018791, 0.17671329]), + 'Rotation': array([-0.06646457, -1.75747681, 0.00260035]), + 'Velocity': array([-0.1946765 , 0.00640082, 0.0006802 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.29515743, 12.90396118, 3.11389613]), + 'camera_rotation': array([-8.87120628, -2.39161015, 2.91200352]), + 'current_gear_input': False, + 'focus_actor_dist': 1605.6727294921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -624.14215088, -1134.76977539, 17.15724182]), + 'frame': 10249, + 'frame_number': 10249, + 'framesequence': 39112, + 'gaze_dir': array([0.98066711, 0.17537689, 0.08467102]), + 'gaze_origin': array([-3.08855891, -0.1655304 , 0.05610581]), + 'gaze_valid': True, + 'gaze_vergence': 118.42642211914062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97952271, 0.18821716, 0.07128906]), + 'left_gaze_origin': array([-2.98936486, 3.02676868, 0.05506134]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.404998779296875, + 'left_pupil_posn': array([ 0.19889438, -0.0429405 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98181152, 0.16253662, 0.09805298]), + 'right_gaze_origin': array([-3.18775368, -3.35782957, 0.05715027]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3822021484375, + 'right_pupil_posn': array([ 0.18226933, -0.13010764]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.062807098031044, + 'throttle_input': 0.0952315554022789, + 'timestamp': 336.675664562732, + 'timestamp_carla': 336676, + 'timestamp_device': 4074889, + 'timestamp_stream': 336.675664562732, + 'transform': [array([-2.62128258e+00, -1.34959888e+01, 1.33271692e-02]), + array([-5.41087538e-02, 6.92929506e+00, 1.58691651e-03])]} +{'AngularVelocity': array([ 0.00298146, -0.1889146 , 0.2945902 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.84983397, -21.20874977, 0.17675342]), + 'Rotation': array([-0.06436087, -1.74276721, 0.00293625]), + 'Velocity': array([-0.02447394, 0.00062829, 0.00056005]), + 'brake_input': 0.0, + 'camera_location': array([-6.27888489, 12.89735222, 3.12502265]), + 'camera_rotation': array([-8.91453743, -2.45234299, 2.99771285]), + 'current_gear_input': False, + 'focus_actor_dist': 1579.546142578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -619.98809814, -1153.7911377 , 17.15794373]), + 'frame': 10250, + 'frame_number': 10250, + 'framesequence': 39116, + 'gaze_dir': array([0.98058319, 0.17558289, 0.08547211]), + 'gaze_origin': array([-3.08825541, -0.16521454, 0.05690613]), + 'gaze_valid': True, + 'gaze_vergence': 133.99508666992188, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97930908, 0.18841553, 0.07369995]), + 'left_gaze_origin': array([-2.98883533, 3.02691817, 0.05525208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.404998779296875, + 'left_pupil_posn': array([ 0.19885957, -0.04300141]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9818573 , 0.16275024, 0.09724426]), + 'right_gaze_origin': array([-3.18767571, -3.35734701, 0.05856019]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.35491943359375, + 'right_pupil_posn': array([ 0.18202436, -0.12829781]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05453047528862953, + 'throttle_input': 0.09919890016317368, + 'timestamp': 336.7095201648772, + 'timestamp_carla': 336710, + 'timestamp_device': 4074923, + 'timestamp_stream': 336.7095201648772, + 'transform': [array([-2.65250731e+00, -1.34276628e+01, 1.32646272e-02]), + array([-5.33096232e-02, 7.01848125e+00, 1.98364607e-03])]} +{'AngularVelocity': array([0.00281059, 0.06347886, 0.24790739]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.78771162, -21.21067429, 0.17660205]), + 'Rotation': array([-0.05154061, -1.74136353, 0.00261108]), + 'Velocity': array([ 0.36124903, -0.01112772, -0.0005636 ]), + 'brake_input': 0.0, + 'camera_location': array([-6.25599384, 12.90012741, 3.13190055]), + 'camera_rotation': array([-8.92096424, -2.5063386 , 3.15131664]), + 'current_gear_input': False, + 'focus_actor_dist': 1575.15283203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -621.45623779, -1151.78466797, 17.15890503]), + 'frame': 10251, + 'frame_number': 10251, + 'framesequence': 39120, + 'gaze_dir': array([0.9807663 , 0.17533875, 0.08400726]), + 'gaze_origin': array([-3.08700514, -0.16529083, 0.05488358]), + 'gaze_valid': True, + 'gaze_vergence': 136.1352996826172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97955322, 0.18768311, 0.07240295]), + 'left_gaze_origin': array([-2.98772764, 3.02686477, 0.05525208]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3797454833984375, + 'left_pupil_posn': array([ 0.19898117, -0.04329515]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98197937, 0.16299438, 0.09561157]), + 'right_gaze_origin': array([-3.18628263, -3.35744667, 0.05451508]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.366180419921875, + 'right_pupil_posn': array([ 0.18177044, -0.13123274]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.045631278306245804, + 'throttle_input': 0.09919890016317368, + 'timestamp': 336.7433922626078, + 'timestamp_carla': 336744, + 'timestamp_device': 4074956, + 'timestamp_stream': 336.7433922626078, + 'transform': [array([-2.68035698e+00, -1.33596258e+01, 1.32306097e-02]), + array([-5.25787920e-02, 7.09421492e+00, 2.25830660e-03])]} +{'AngularVelocity': array([ 0.00169912, 0.04134702, -0.04009034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -6.71712303, -21.21282578, 0.17660533]), + 'Rotation': array([-0.06272162, -1.7444458 , 0.00251773]), + 'Velocity': array([ 3.55685830e-01, -1.09640155e-02, 1.66702273e-04]), + 'brake_input': 0.0, + 'camera_location': array([-6.21682739, 12.89832973, 3.12460732]), + 'camera_rotation': array([-8.94163227, -2.5454824 , 3.19875121]), + 'current_gear_input': False, + 'focus_actor_dist': 1534.0882568359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -612.72857666, -1184.87194824, 17.15850067]), + 'frame': 10252, + 'frame_number': 10252, + 'framesequence': 39124, + 'gaze_dir': array([0.98081207, 0.17484283, 0.08361816]), + 'gaze_origin': array([-3.08563399, -0.16530839, 0.05351258]), + 'gaze_valid': True, + 'gaze_vergence': 115.18120574951172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97924805, 0.19017029, 0.06997681]), + 'left_gaze_origin': array([-2.98654342, 3.02643132, 0.05163117]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3582916259765625, + 'left_pupil_posn': array([ 0.19805384, -0.04492629]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9823761 , 0.15951538, 0.09725952]), + 'right_gaze_origin': array([-3.18472457, -3.35704827, 0.05539398]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.415618896484375, + 'right_pupil_posn': array([ 0.18230367, -0.13126647]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03735465556383133, + 'throttle_input': 0.10316624492406845, + 'timestamp': 336.77645756304264, + 'timestamp_carla': 336777, + 'timestamp_device': 4074989, + 'timestamp_stream': 336.77645756304264, + 'transform': [array([-2.70434737e+00, -1.32934456e+01, 1.32369138e-02]), + array([-5.19094355e-02, 7.15546703e+00, 2.38037598e-03])]} +{'AngularVelocity': array([ 0.00223395, 0.03707851, -1.25299001]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.08305046707391739, + 'FR_Wheel_Angle': -0.07535906881093979, + 'Location': array([ -6.6469841 , -21.21498299, 0.17658496]), + 'Rotation': array([-0.07342453, -1.74740613, 0.00244098]), + 'Velocity': array([ 0.19650175, -0.00612661, -0.00036424]), + 'brake_input': 0.0, + 'camera_location': array([-6.22020721, 12.91515541, 3.06886744]), + 'camera_rotation': array([-9.2274828 , -2.58718109, 3.13062263]), + 'current_gear_input': False, + 'focus_actor_dist': 1517.0902099609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -609.68426514, -1194.52185059, 17.15788269]), + 'frame': 10253, + 'frame_number': 10253, + 'framesequence': 39128, + 'gaze_dir': array([0.98078918, 0.17417908, 0.08605194]), + 'gaze_origin': array([-3.08389068, -0.16434327, 0.06034165]), + 'gaze_valid': True, + 'gaze_vergence': 141.39739990234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97943115, 0.18725586, 0.07502747]), + 'left_gaze_origin': array([-2.97923756, 3.02731347, 0.05708771]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3957061767578125, + 'left_pupil_posn': array([ 0.19789875, -0.04007626]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98214722, 0.16110229, 0.09707642]), + 'right_gaze_origin': array([-3.1885438 , -3.35599995, 0.06359559]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.43621826171875, + 'right_pupil_posn': array([ 0.18074274, -0.1245209 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02863856963813305, + 'throttle_input': 0.10316624492406845, + 'timestamp': 336.8091567642987, + 'timestamp_carla': 336809, + 'timestamp_device': 4075023, + 'timestamp_stream': 336.8091567642987, + 'transform': [array([ -2.72488952, -13.2281723 , 0.01327036]), + array([-5.12673967e-02, 7.20345020e+00, 2.38038204e-03])]} +{'AngularVelocity': array([-6.18960010e-04, -9.08364821e-03, -1.16567743e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.05888821929693222, + 'FR_Wheel_Angle': -0.05886124074459076, + 'Location': array([ -6.61801863, -21.21589088, 0.17658226]), + 'Rotation': array([-0.07483155, -1.74786353, 0.00234927]), + 'Velocity': array([ 0.07634296, -0.00235649, 0.00026786]), + 'brake_input': 0.0, + 'camera_location': array([-6.20057106, 12.94333839, 3.01716876]), + 'camera_rotation': array([-9.3534174 , -2.67133045, 3.15993381]), + 'current_gear_input': False, + 'focus_actor_dist': 1475.1363525390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -599.48236084, -1228.42199707, 17.15622711]), + 'frame': 10254, + 'frame_number': 10254, + 'framesequence': 39132, + 'gaze_dir': array([0.9810791 , 0.17268372, 0.08531189]), + 'gaze_origin': array([-3.08334684, -0.16561891, 0.05537491]), + 'gaze_valid': True, + 'gaze_vergence': 98.89208221435547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98039246, 0.18418884, 0.06988525]), + 'left_gaze_origin': array([-2.98613286, 3.02542424, 0.05342255]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.398345947265625, + 'left_pupil_posn': array([ 0.19931614, -0.04249942]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98176575, 0.16117859, 0.10073853]), + 'right_gaze_origin': array([-3.18056059, -3.35666203, 0.05732727]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3380889892578125, + 'right_pupil_posn': array([ 0.17983472, -0.12897718]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.018402662128210068, + 'throttle_input': 0.10713358968496323, + 'timestamp': 336.8436526618898, + 'timestamp_carla': 336844, + 'timestamp_device': 4075056, + 'timestamp_stream': 336.8436526618898, + 'transform': [array([ -2.74270463, -13.15952682, 0.01329301]), + array([-5.04409447e-02, 7.23890543e+00, 2.38037948e-03])]} +{'AngularVelocity': array([ 1.23714050e-03, -1.00742448e-02, 1.25558150e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.05765250325202942, + 'FR_Wheel_Angle': -0.05762443691492081, + 'Location': array([ -6.60593414, -21.21634293, 0.17654563]), + 'Rotation': array([-0.07183993, -1.73638916, 0.00231764]), + 'Velocity': array([ 0.0255022 , -0.00060497, -0.00016583]), + 'brake_input': 0.0, + 'camera_location': array([-6.15975189, 12.98066998, 3.00758839]), + 'camera_rotation': array([-9.28870869, -2.72251463, 3.30985665]), + 'current_gear_input': False, + 'focus_actor_dist': 1423.306396484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -584.21313477, -1271.33190918, 17.15174866]), + 'frame': 10255, + 'frame_number': 10255, + 'framesequence': 39136, + 'gaze_dir': array([0.98111725, 0.17198181, 0.08657074]), + 'gaze_origin': array([-3.08434677, -0.16504899, 0.05623245]), + 'gaze_valid': True, + 'gaze_vergence': 125.0447006225586, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98010254, 0.18412781, 0.07389832]), + 'left_gaze_origin': array([-2.9903872 , 3.02600408, 0.05630951]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4654693603515625, + 'left_pupil_posn': array([ 0.19848144, -0.04190862]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98213196, 0.15983582, 0.09924316]), + 'right_gaze_origin': array([-3.17830658, -3.35610199, 0.0561554 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4740142822265625, + 'right_pupil_posn': array([ 0.17941248, -0.12787855]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0075991093181073666, + 'throttle_input': 0.10713358968496323, + 'timestamp': 336.87629156187177, + 'timestamp_carla': 336877, + 'timestamp_device': 4075089, + 'timestamp_stream': 336.87629156187177, + 'transform': [array([ -2.75568962, -13.09467506, 0.01335755]), + array([-4.95052077e-02, 7.25724983e+00, 2.28882395e-03])]} +{'AngularVelocity': array([ 0.0015139 , -0.00506862, 1.17709637]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04998506233096123, + 'FR_Wheel_Angle': -0.0499630905687809, + 'Location': array([ -6.60296059, -21.21643829, 0.1765417 ]), + 'Rotation': array([-0.07031679, -1.73620605, 0.00233825]), + 'Velocity': array([ 0.00645449, -0.00012931, 0.00029535]), + 'brake_input': 0.0, + 'camera_location': array([-6.16779709, 13.02583408, 2.95984554]), + 'camera_rotation': array([-9.55137062, -2.75652313, 3.35065794]), + 'current_gear_input': False, + 'focus_actor_dist': 1456.2525634765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -592.60571289, -1232.15539551, 17.15028381]), + 'frame': 10256, + 'frame_number': 10256, + 'framesequence': 39140, + 'gaze_dir': array([0.98093414, 0.17158508, 0.09016418]), + 'gaze_origin': array([-3.08545995, -0.16433488, 0.06418075]), + 'gaze_valid': True, + 'gaze_vergence': 171.8962860107422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98014832, 0.1809082 , 0.08093262]), + 'left_gaze_origin': array([-2.97945428, 3.02687407, 0.06091156]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.463165283203125, + 'left_pupil_posn': array([ 0.1985935 , -0.03685093]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98171997, 0.16226196, 0.09939575]), + 'right_gaze_origin': array([-3.19146585, -3.35554361, 0.06744996]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3614654541015625, + 'right_pupil_posn': array([ 0.17828751, -0.12038565]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0034241769462823868, + 'throttle_input': 0.1111009418964386, + 'timestamp': 336.9090235643089, + 'timestamp_carla': 336909, + 'timestamp_device': 4075123, + 'timestamp_stream': 336.9090235643089, + 'transform': [array([ -2.76462913, -13.02969933, 0.01342838]), + array([-4.83987182e-02, 7.25967979e+00, 2.16675294e-03])]} +{'AngularVelocity': array([ 0.00235544, -0.00251172, 1.28332329]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04998154565691948, + 'FR_Wheel_Angle': -0.049955956637859344, + 'Location': array([ -6.60355139, -21.21640396, 0.17651993]), + 'Rotation': array([-0.06946302, -1.73681653, 0.00231511]), + 'Velocity': array([-0.00892358, 0.00052075, -0.00019773]), + 'brake_input': 0.0, + 'camera_location': array([-6.19165802, 13.06034946, 2.92704296]), + 'camera_rotation': array([-9.73950768, -2.77496028, 3.64702249]), + 'current_gear_input': False, + 'focus_actor_dist': 1438.216552734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -588.36608887, -1243.02001953, 17.14870453]), + 'frame': 10257, + 'frame_number': 10257, + 'framesequence': 39144, + 'gaze_dir': array([0.98056793, 0.17333984, 0.09077454]), + 'gaze_origin': array([-3.08598113, -0.16393434, 0.06461258]), + 'gaze_valid': True, + 'gaze_vergence': 178.44712829589844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97947693, 0.18405151, 0.08210754]), + 'left_gaze_origin': array([-2.98143625, 3.02717757, 0.06158753]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4320068359375, + 'left_pupil_posn': array([ 0.19854665, -0.0367142 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98165894, 0.16262817, 0.09944153]), + 'right_gaze_origin': array([-3.19052601, -3.35504627, 0.06763764]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4106292724609375, + 'right_pupil_posn': array([ 0.17904246, -0.11971509]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.01268959604203701, + 'throttle_input': 0.11506828665733337, + 'timestamp': 336.94415836408734, + 'timestamp_carla': 336944, + 'timestamp_device': 4075156, + 'timestamp_stream': 336.94415836408734, + 'transform': [array([ -2.77014589, -12.96013069, 0.0134548 ]), + array([-4.74493206e-02, 7.24650860e+00, 2.13623093e-03])]} +{'AngularVelocity': array([ 2.08428316e-03, -3.20916908e-04, 1.13263190e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.049970194697380066, + 'FR_Wheel_Angle': -0.04994472861289978, + 'Location': array([ -6.60678768, -21.21630859, 0.17656173]), + 'Rotation': array([-0.06921713, -1.73675549, 0.00232757]), + 'Velocity': array([-1.99918225e-02, 7.84579548e-04, 9.31358300e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.16577053, 13.1022377 , 2.9425478 ]), + 'camera_rotation': array([-9.59801388, -2.8242662 , 3.75548887]), + 'current_gear_input': False, + 'focus_actor_dist': 1379.2686767578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -576.90332031, -1294.48022461, 17.15023041]), + 'frame': 10258, + 'frame_number': 10258, + 'framesequence': 39148, + 'gaze_dir': array([0.9805603 , 0.17279816, 0.09186554]), + 'gaze_origin': array([-3.08787775, -0.16369553, 0.06431046]), + 'gaze_valid': True, + 'gaze_vergence': 176.387939453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97967529, 0.18258667, 0.08291626]), + 'left_gaze_origin': array([-2.98517776, 3.02751946, 0.06167145]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4309234619140625, + 'left_pupil_posn': array([ 0.19849229, -0.0369072 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98144531, 0.16300964, 0.10081482]), + 'right_gaze_origin': array([-3.19057775, -3.35491037, 0.06694946]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4110260009765625, + 'right_pupil_posn': array([ 0.17844105, -0.11986887]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.017981506884098053, + 'throttle_input': 0.11903563141822815, + 'timestamp': 336.97563076391816, + 'timestamp_carla': 336976, + 'timestamp_device': 4075189, + 'timestamp_stream': 336.97563076391816, + 'transform': [array([ -2.77263212, -12.89781952, 0.01352617]), + array([-4.71214727e-02, 7.22526550e+00, 1.98364747e-03])]} +{'AngularVelocity': array([-2.62708962e-03, 2.29096782e-04, -1.05987418e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04995931312441826, + 'FR_Wheel_Angle': -0.04993226379156113, + 'Location': array([ -6.61208248, -21.21605492, 0.17657474]), + 'Rotation': array([-0.06929909, -1.7482605 , 0.00233821]), + 'Velocity': array([-3.29111889e-02, 9.87386797e-04, 3.57818608e-05]), + 'brake_input': 0.0, + 'camera_location': array([-6.12940502, 13.1163702 , 2.9472084 ]), + 'camera_rotation': array([-9.48526764, -2.87138009, 4.04218292]), + 'current_gear_input': False, + 'focus_actor_dist': 1431.7027587890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -589.2487793 , -1236.10852051, 17.14779663]), + 'frame': 10259, + 'frame_number': 10259, + 'framesequence': 39152, + 'gaze_dir': array([0.98058319, 0.17340851, 0.09049225]), + 'gaze_origin': array([-3.08941364, -0.1636162 , 0.06384049]), + 'gaze_valid': True, + 'gaze_vergence': 177.8135223388672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97953796, 0.18389893, 0.08174133]), + 'left_gaze_origin': array([-2.98828292, 3.02751946, 0.06176605]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.429840087890625, + 'left_pupil_posn': array([ 0.19849229, -0.03791571]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98162842, 0.16291809, 0.09924316]), + 'right_gaze_origin': array([-3.19054413, -3.35475159, 0.06591492]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4102325439453125, + 'right_pupil_posn': array([ 0.17877221, -0.12102067]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02215643785893917, + 'throttle_input': 0.11903563141822815, + 'timestamp': 337.0085930638015, + 'timestamp_carla': 337009, + 'timestamp_device': 4075222, + 'timestamp_stream': 337.0085930638015, + 'transform': [array([ -2.77337337, -12.8326149 , 0.01357531]), + array([-4.72444147e-02, 7.19593763e+00, 1.80054200e-03])]} +{'AngularVelocity': array([ 0.00304452, 0.04007602, -0.48007903]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04982777312397957, + 'FR_Wheel_Angle': -0.049686603248119354, + 'Location': array([ -6.6193018 , -21.21584892, 0.17657684]), + 'Rotation': array([-0.06970207, -1.74301136, 0.00237075]), + 'Velocity': array([-0.07020134, 0.00237326, 0.00037874]), + 'brake_input': 0.0, + 'camera_location': array([-6.08149242, 13.10337925, 2.95442963]), + 'camera_rotation': array([-9.45072746, -2.88421512, 4.44909763]), + 'current_gear_input': False, + 'focus_actor_dist': 1425.8585205078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -588.16204834, -1235.44458008, 17.14654541]), + 'frame': 10260, + 'frame_number': 10260, + 'framesequence': 39156, + 'gaze_dir': array([0.98034668, 0.17425537, 0.09122467]), + 'gaze_origin': array([-3.09715581, -0.16566545, 0.06288376]), + 'gaze_valid': True, + 'gaze_vergence': 145.7904815673828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97953796, 0.18447876, 0.08035278]), + 'left_gaze_origin': array([-3.00361633, 3.02352929, 0.05948639]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.5058746337890625, + 'left_pupil_posn': array([ 0.20180821, -0.041206 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9811554 , 0.16403198, 0.10209656]), + 'right_gaze_origin': array([-3.19069552, -3.35486007, 0.06628113]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4097900390625, + 'right_pupil_posn': array([ 0.1790489 , -0.12130046]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.025983460247516632, + 'throttle_input': 0.11903563141822815, + 'timestamp': 337.0420362651348, + 'timestamp_carla': 337042, + 'timestamp_device': 4075256, + 'timestamp_stream': 337.0420362651348, + 'transform': [array([ -2.77253079, -12.76654434, 0.01360632]), + array([-4.76337373e-02, 7.16018581e+00, 1.64795399e-03])]} +{'AngularVelocity': array([-0.01035485, 0.01048776, -0.92856479]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04957089200615883, + 'FR_Wheel_Angle': -0.04947870969772339, + 'Location': array([ -6.69342089, -21.21338081, 0.17672089]), + 'Rotation': array([-0.08294582, -1.76397705, 0.00249927]), + 'Velocity': array([-0.47234032, 0.01380293, 0.00074107]), + 'brake_input': 0.0, + 'camera_location': array([-6.04053402, 13.09499645, 2.97003388]), + 'camera_rotation': array([-9.45458603, -2.88202453, 4.36591911]), + 'current_gear_input': False, + 'focus_actor_dist': 1426.451416015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -590.08135986, -1228.60449219, 17.14676666]), + 'frame': 10261, + 'frame_number': 10261, + 'framesequence': 39160, + 'gaze_dir': array([0.98027039, 0.17827606, 0.08346558]), + 'gaze_origin': array([-3.09432769, -0.17090303, 0.05841522]), + 'gaze_valid': True, + 'gaze_vergence': 98.39019775390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97982788, 0.18756104, 0.06880188]), + 'left_gaze_origin': array([-2.99811864, 3.02037048, 0.05337983]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.40582275390625, + 'left_pupil_posn': array([ 0.20560932, -0.04563582]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98071289, 0.16899109, 0.09812927]), + 'right_gaze_origin': array([-3.19053674, -3.36217666, 0.06345062]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.314971923828125, + 'right_pupil_posn': array([ 0.18509793, -0.12728012]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.029023103415966034, + 'throttle_input': 0.12300297617912292, + 'timestamp': 337.0760783627629, + 'timestamp_carla': 337076, + 'timestamp_device': 4075289, + 'timestamp_stream': 337.0760783627629, + 'transform': [array([ -2.77032518, -12.69939327, 0.01362387]), + array([-4.81801517e-02, 7.11877298e+00, 1.52588345e-03])]} +{'AngularVelocity': array([-3.85333078e-05, -4.06191535e-02, 2.27135241e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04952695593237877, + 'FR_Wheel_Angle': -0.04946764186024666, + 'Location': array([ -6.77766991, -21.21085739, 0.17672668]), + 'Rotation': array([-0.07742019, -1.75390613, 0.00257702]), + 'Velocity': array([-0.51973605, 0.01661521, 0.00057819]), + 'brake_input': 0.0, + 'camera_location': array([-6.0073595 , 13.13646603, 2.93607378]), + 'camera_rotation': array([-9.5351553 , -2.99082899, 3.7370038 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1307.078857421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -563.94696045, -1338.84423828, 17.1484375 ]), + 'frame': 10262, + 'frame_number': 10262, + 'framesequence': 39164, + 'gaze_dir': array([0.97914886, 0.18118286, 0.09055328]), + 'gaze_origin': array([-3.0922761 , -0.17416917, 0.05976792]), + 'gaze_valid': True, + 'gaze_vergence': 141.77224731445312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97825623, 0.19158936, 0.07939148]), + 'left_gaze_origin': array([-2.99448252, 3.01753998, 0.05940705]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4642181396484375, + 'left_pupil_posn': array([ 0.20807004, -0.03989828]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9800415 , 0.17077637, 0.10171509]), + 'right_gaze_origin': array([-3.19006968, -3.36587834, 0.06012879]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3898773193359375, + 'right_pupil_posn': array([ 0.18913472, -0.12581885]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03175146132707596, + 'throttle_input': 0.12300297617912292, + 'timestamp': 337.10842556506395, + 'timestamp_carla': 337109, + 'timestamp_device': 4075322, + 'timestamp_stream': 337.10842556506395, + 'transform': [array([ -2.7671442 , -12.63559532, 0.01366213]), + array([-4.87743765e-02, 7.07539320e+00, 1.37329602e-03])]} +{'AngularVelocity': array([-0.00206695, -0.02376719, -0.15858442]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.049519773572683334, + 'FR_Wheel_Angle': -0.04947986453771591, + 'Location': array([ -6.90167093, -21.20693016, 0.17683013]), + 'Rotation': array([-0.07082906, -1.75183117, 0.00290979]), + 'Velocity': array([-5.23348510e-01, 1.60273276e-02, 5.05056349e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.98167038, 13.20875454, 2.8489666 ]), + 'camera_rotation': array([-9.9065609 , -3.1077497 , 3.23122144]), + 'current_gear_input': False, + 'focus_actor_dist': 1423.99267578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -594.8223877 , -1218.68237305, 17.14903259]), + 'frame': 10263, + 'frame_number': 10263, + 'framesequence': 39168, + 'gaze_dir': array([0.97868347, 0.18264008, 0.09307861]), + 'gaze_origin': array([-3.09463882, -0.17505036, 0.0666565 ]), + 'gaze_valid': True, + 'gaze_vergence': 180.16590881347656, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97816467, 0.18983459, 0.08441162]), + 'left_gaze_origin': array([-2.99650741, 3.01693583, 0.06701203]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4383392333984375, + 'left_pupil_posn': array([ 0.21007276, -0.03534532]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97920227, 0.17544556, 0.10174561]), + 'right_gaze_origin': array([-3.19277048, -3.36703658, 0.06630097]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.387847900390625, + 'right_pupil_posn': array([ 0.18943858, -0.12037182]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.034553058445453644, + 'throttle_input': 0.12300297617912292, + 'timestamp': 337.1424742639065, + 'timestamp_carla': 337143, + 'timestamp_device': 4075356, + 'timestamp_stream': 337.1424742639065, + 'transform': [array([ -2.76266575, -12.56851292, 0.01367728]), + array([-4.93822657e-02, 7.02558470e+00, 1.25122152e-03])]} +{'AngularVelocity': array([-0.00180927, -0.01607724, -0.15256426]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0495431087911129, + 'FR_Wheel_Angle': -0.04953213408589363, + 'Location': array([ -7.0239706 , -21.20314217, 0.17693779]), + 'Rotation': array([-0.06829505, -1.74304199, 0.00299192]), + 'Velocity': array([-5.06328940e-01, 1.59854591e-02, 2.56290426e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.92458248, 13.29078674, 2.79231167]), + 'camera_rotation': array([-10.14643002, -3.22446609, 3.48907495]), + 'current_gear_input': False, + 'focus_actor_dist': 1386.7672119140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -583.48461914, -1247.76037598, 17.14505768]), + 'frame': 10264, + 'frame_number': 10264, + 'framesequence': 39172, + 'gaze_dir': array([0.97797394, 0.18715668, 0.09115601]), + 'gaze_origin': array([-3.09566808, -0.17596589, 0.06590652]), + 'gaze_valid': True, + 'gaze_vergence': 131.796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9773407 , 0.19612122, 0.07949829]), + 'left_gaze_origin': array([-2.99958372, 3.01608586, 0.06589508]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4389495849609375, + 'left_pupil_posn': array([ 0.2116673 , -0.03627169]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97860718, 0.17819214, 0.10281372]), + 'right_gaze_origin': array([-3.19175267, -3.36801791, 0.06591797]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3770904541015625, + 'right_pupil_posn': array([ 0.19228172, -0.12227392]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.037757501006126404, + 'throttle_input': 0.12300297617912292, + 'timestamp': 337.1767571642995, + 'timestamp_carla': 337177, + 'timestamp_device': 4075389, + 'timestamp_stream': 337.1767571642995, + 'transform': [array([ -2.75693774, -12.50104809, 0.01368348]), + array([-4.98672090e-02, 6.97093725e+00, 1.19019288e-03])]} +{'AngularVelocity': array([-0.00134493, -0.0035406 , -0.17468144]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04956545680761337, + 'FR_Wheel_Angle': -0.04955802857875824, + 'Location': array([ -7.15057421, -21.19919205, 0.17706375]), + 'Rotation': array([-0.06701782, -1.74368286, 0.00328039]), + 'Velocity': array([-0.46339184, 0.01413361, 0.00069263]), + 'brake_input': 0.0, + 'camera_location': array([-5.87107372, 13.36567116, 2.7568624 ]), + 'camera_rotation': array([-10.33792782, -3.45831466, 3.775249 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1283.45654296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -560.32836914, -1342.01159668, 17.14562225]), + 'frame': 10265, + 'frame_number': 10265, + 'framesequence': 39176, + 'gaze_dir': array([0.97702789, 0.19165039, 0.09211731]), + 'gaze_origin': array([-3.09702015, -0.17727739, 0.06712113]), + 'gaze_valid': True, + 'gaze_vergence': 85.47051239013672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97727966, 0.1962738 , 0.07981873]), + 'left_gaze_origin': array([-3.00255752, 3.01374984, 0.06831971]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3739013671875, + 'left_pupil_posn': array([ 0.21627748, -0.03501368]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97677612, 0.18702698, 0.10441589]), + 'right_gaze_origin': array([-3.19148254, -3.36830473, 0.06592255]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2581939697265625, + 'right_pupil_posn': array([ 0.19253385, -0.12208295]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04149296507239342, + 'throttle_input': 0.12300297617912292, + 'timestamp': 337.20873606204987, + 'timestamp_carla': 337209, + 'timestamp_device': 4075422, + 'timestamp_stream': 337.20873606204987, + 'transform': [array([ -2.75031638, -12.43808174, 0.01372765]), + array([-5.01404144e-02, 6.91519260e+00, 1.06811745e-03])]} +{'AngularVelocity': array([0.01165945, 0.05126039, 0.17789926]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.049588680267333984, + 'FR_Wheel_Angle': -0.04953916743397713, + 'Location': array([ -7.2551055 , -21.19609833, 0.17717685]), + 'Rotation': array([-0.06765302, -1.73461902, 0.00337595]), + 'Velocity': array([-0.47230616, 0.01564479, 0.00089775]), + 'brake_input': 0.0, + 'camera_location': array([-5.86881447, 13.44309711, 2.69985843]), + 'camera_rotation': array([-10.65598202, -3.83080649, 3.90306497]), + 'current_gear_input': False, + 'focus_actor_dist': 1238.574462890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -549.58850098, -1378.85510254, 17.14411926]), + 'frame': 10266, + 'frame_number': 10266, + 'framesequence': 39180, + 'gaze_dir': array([0.97490692, 0.20041656, 0.09630585]), + 'gaze_origin': array([-3.09679794, -0.18236619, 0.07096405]), + 'gaze_valid': True, + 'gaze_vergence': 139.21705627441406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97492981, 0.20451355, 0.08752441]), + 'left_gaze_origin': array([-3.00023365, 3.008008 , 0.07133179]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4441070556640625, + 'left_pupil_posn': array([ 0.22340703, -0.03240252]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97488403, 0.19631958, 0.10508728]), + 'right_gaze_origin': array([-3.19336247, -3.37274027, 0.07059631]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1795654296875, + 'right_pupil_posn': array([ 0.19868517, -0.11656511]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.045539721846580505, + 'throttle_input': 0.1269855797290802, + 'timestamp': 337.2421048618853, + 'timestamp_carla': 337242, + 'timestamp_device': 4075456, + 'timestamp_stream': 337.2421048618853, + 'transform': [array([ -2.74189663, -12.37238884, 0.01375354]), + array([-5.02701886e-02, 6.85138226e+00, 9.76569369e-04])]} +{'AngularVelocity': array([ 0.00165385, 0.05086695, -0.09500083]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04959630221128464, + 'FR_Wheel_Angle': -0.04954684153199196, + 'Location': array([ -7.36190224, -21.19270515, 0.17728229]), + 'Rotation': array([-0.06839068, -1.73937976, 0.00353177]), + 'Velocity': array([-4.80762243e-01, 1.53488107e-02, 4.53281391e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.83984375, 13.51153755, 2.67005539]), + 'camera_rotation': array([-10.67602921, -4.17845964, 4.16618872]), + 'current_gear_input': False, + 'focus_actor_dist': 1214.1925048828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -546.32519531, -1396.90100098, 17.14547729]), + 'frame': 10267, + 'frame_number': 10267, + 'framesequence': 39184, + 'gaze_dir': array([0.97512054, 0.19949341, 0.09526825]), + 'gaze_origin': array([-3.09648752, -0.18752061, 0.06743775]), + 'gaze_valid': True, + 'gaze_vergence': 137.65835571289062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97396851, 0.21060181, 0.08378601]), + 'left_gaze_origin': array([-2.99957895, 3.00327158, 0.06858979]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4148406982421875, + 'left_pupil_posn': array([ 0.22405148, -0.03295362]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97627258, 0.18838501, 0.10675049]), + 'right_gaze_origin': array([-3.19339633, -3.37831259, 0.06628571]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.229522705078125, + 'right_pupil_posn': array([ 0.20468533, -0.12090409]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.050355542451143265, + 'throttle_input': 0.1269855797290802, + 'timestamp': 337.2761857621372, + 'timestamp_carla': 337276, + 'timestamp_device': 4075489, + 'timestamp_stream': 337.2761857621372, + 'transform': [array([ -2.73153067, -12.30534744, 0.01376574]), + array([-5.02087176e-02, 6.77963448e+00, 9.46047949e-04])]} +{'AngularVelocity': array([-0.00413121, -0.01882211, -1.23723459]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04958741366863251, + 'FR_Wheel_Angle': -0.049579400569200516, + 'Location': array([ -7.4699192 , -21.18928146, 0.17739323]), + 'Rotation': array([-0.06772132, -1.73004162, 0.00369476]), + 'Velocity': array([-0.44062254, 0.0141267 , 0.0005415 ]), + 'brake_input': 0.0, + 'camera_location': array([-5.76158142, 13.59957504, 2.67712283]), + 'camera_rotation': array([-10.50017929, -4.27663946, 4.54851294]), + 'current_gear_input': False, + 'focus_actor_dist': 1186.7606201171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -531.02453613, -1414.63623047, 17.13450623]), + 'frame': 10268, + 'frame_number': 10268, + 'framesequence': 39188, + 'gaze_dir': array([0.96907806, 0.22622681, 0.09771729]), + 'gaze_origin': array([-3.09936166, -0.19852905, 0.05987244]), + 'gaze_valid': True, + 'gaze_vergence': 251.11888122558594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96673584, 0.23754883, 0.09468079]), + 'left_gaze_origin': array([-3.00192881, 2.9907043 , 0.05798645]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4138031005859375, + 'left_pupil_posn': array([ 0.24170458, -0.04332709]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97142029, 0.21490479, 0.10075378]), + 'right_gaze_origin': array([-3.19679427, -3.38776255, 0.06175843]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3225860595703125, + 'right_pupil_posn': array([ 0.22095227, -0.12167621]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.05590381100773811, + 'throttle_input': 0.13492026925086975, + 'timestamp': 337.31101186200976, + 'timestamp_carla': 337311, + 'timestamp_device': 4075522, + 'timestamp_stream': 337.31101186200976, + 'transform': [array([ -2.71885467, -12.23690319, 0.0137652 ]), + array([-4.99833226e-02, 6.69852877e+00, 9.76567273e-04])]} +{'AngularVelocity': array([-0.00094029, -0.00873017, 0.11259998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04961913824081421, + 'FR_Wheel_Angle': -0.04958847910165787, + 'Location': array([ -7.56893396, -21.18627357, 0.17751163]), + 'Rotation': array([-0.0671066 , -1.72399914, 0.00393682]), + 'Velocity': array([-0.42498806, 0.01299603, 0.00149087]), + 'brake_input': 0.0, + 'camera_location': array([-5.68910885, 13.67321873, 2.67103457]), + 'camera_rotation': array([-10.42108536, -4.20457268, 4.95897484]), + 'current_gear_input': False, + 'focus_actor_dist': 1223.5465087890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -570.61254883, -1380.25195312, 17.16576385]), + 'frame': 10269, + 'frame_number': 10269, + 'framesequence': 39193, + 'gaze_dir': array([0.96920013, 0.22294617, 0.10391235]), + 'gaze_origin': array([-3.09927607, -0.19889756, 0.06086349]), + 'gaze_valid': True, + 'gaze_vergence': 239.21755981445312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96740723, 0.23320007, 0.09866333]), + 'left_gaze_origin': array([-3.00237894, 2.98926878, 0.05922241]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3905181884765625, + 'left_pupil_posn': array([ 0.24197745, -0.03965425]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97099304, 0.21269226, 0.10916138]), + 'right_gaze_origin': array([-3.19617319, -3.38706374, 0.06250458]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2688140869140625, + 'right_pupil_posn': array([ 0.21897078, -0.11944842]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0616534948348999, + 'throttle_input': 0.13492026925086975, + 'timestamp': 337.3450489640236, + 'timestamp_carla': 337345, + 'timestamp_device': 4075564, + 'timestamp_stream': 337.3450489640236, + 'transform': [array([ -2.70427871, -12.17001152, 0.0137857 ]), + array([-4.96281534e-02, 6.61108780e+00, 9.76565992e-04])]} +{'AngularVelocity': array([-0.00200252, 0.00491039, -0.05597349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.049605607986450195, + 'FR_Wheel_Angle': -0.04959417134523392, + 'Location': array([ -7.65104675, -21.18372726, 0.17761302]), + 'Rotation': array([-0.06765302, -1.72335815, 0.00401919]), + 'Velocity': array([-0.41512102, 0.01275237, 0.00054846]), + 'brake_input': 0.0, + 'camera_location': array([-5.65419292, 13.7406311 , 2.61617827]), + 'camera_rotation': array([-10.60296631, -4.20758724, 5.02604055]), + 'current_gear_input': False, + 'focus_actor_dist': 1303.202880859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -590.26190186, -1295.59326172, 17.16404724]), + 'frame': 10270, + 'frame_number': 10270, + 'framesequence': 39196, + 'gaze_dir': array([0.96868134, 0.22477722, 0.10482025]), + 'gaze_origin': array([-3.09921288, -0.20027238, 0.06528626]), + 'gaze_valid': True, + 'gaze_vergence': 179.15847778320312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96801758, 0.23165894, 0.09619141]), + 'left_gaze_origin': array([-3.00252843, 2.98898625, 0.06325531]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.42071533203125, + 'left_pupil_posn': array([ 0.24398363, -0.03567624]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96934509, 0.21789551, 0.1134491 ]), + 'right_gaze_origin': array([-3.1958971, -3.3895309, 0.0673172]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3084869384765625, + 'right_pupil_posn': array([ 0.22007418, -0.11702776]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06789758801460266, + 'throttle_input': 0.13492026925086975, + 'timestamp': 337.37687926366925, + 'timestamp_carla': 337377, + 'timestamp_device': 4075589, + 'timestamp_stream': 337.37687926366925, + 'transform': [array([ -2.68847013, -12.10734844, 0.01385147]), + array([-4.91295494e-02, 6.52111578e+00, 8.54495331e-04])]} +{'AngularVelocity': array([-0.00737591, -0.2215904 , 0.01188957]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.7015214 , -21.18217278, 0.17752109]), + 'Rotation': array([-0.04577592, -1.72106934, 0.00416575]), + 'Velocity': array([ 0.15950888, -0.00490026, -0.00020231]), + 'brake_input': 0.0, + 'camera_location': array([-5.60823727, 13.80423737, 2.55735469]), + 'camera_rotation': array([-10.79270267, -4.08311033, 5.14892626]), + 'current_gear_input': False, + 'focus_actor_dist': 1268.2843017578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -581.93493652, -1322.84375 , 17.16257477]), + 'frame': 10271, + 'frame_number': 10271, + 'framesequence': 39201, + 'gaze_dir': array([0.96834564, 0.22664642, 0.10398865]), + 'gaze_origin': array([-3.09882903, -0.20031433, 0.06634827]), + 'gaze_valid': True, + 'gaze_vergence': 205.9049530029297, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9675293 , 0.23364258, 0.09634399]), + 'left_gaze_origin': array([-3.0022583 , 2.98905802, 0.06405487]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3976287841796875, + 'left_pupil_posn': array([ 0.24455523, -0.03567624]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96916199, 0.21965027, 0.1116333 ]), + 'right_gaze_origin': array([-3.19539976, -3.38968682, 0.06864166]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.326446533203125, + 'right_pupil_posn': array([ 0.22086549, -0.11605549]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07403180003166199, + 'throttle_input': 0.13492026925086975, + 'timestamp': 337.41248006373644, + 'timestamp_carla': 337413, + 'timestamp_device': 4075631, + 'timestamp_stream': 337.41248006373644, + 'transform': [array([ -2.66824579, -12.03731918, 0.01387313]), + array([-4.84875105e-02, 6.41103029e+00, 7.93463376e-04])]} +{'AngularVelocity': array([ 0.00352994, 0.09402037, -0.00040826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.63303947, -21.18425941, 0.1774482 ]), + 'Rotation': array([-0.04623355, -1.71987927, 0.00400599]), + 'Velocity': array([ 4.06336129e-01, -1.23546096e-02, -3.21016298e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.55666924, 13.86071587, 2.53415227]), + 'camera_rotation': array([-10.89338589, -3.84194541, 5.31752348]), + 'current_gear_input': False, + 'focus_actor_dist': 1209.093994140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -569.32434082, -1374.68005371, 17.16306305]), + 'frame': 10272, + 'frame_number': 10272, + 'framesequence': 39204, + 'gaze_dir': array([0.96804047, 0.22760773, 0.10487366]), + 'gaze_origin': array([-3.09889603, -0.19980545, 0.06684799]), + 'gaze_valid': True, + 'gaze_vergence': 249.56692504882812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96722412, 0.23400879, 0.09855652]), + 'left_gaze_origin': array([-3.00224924, 2.98985457, 0.06408081]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.39788818359375, + 'left_pupil_posn': array([ 0.24455523, -0.03585553]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96885681, 0.22120667, 0.1111908 ]), + 'right_gaze_origin': array([-3.19554329, -3.38946533, 0.06961518]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3277435302734375, + 'right_pupil_posn': array([ 0.22086573, -0.11467731]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0806237980723381, + 'throttle_input': 0.13888761401176453, + 'timestamp': 337.4442320615053, + 'timestamp_carla': 337444, + 'timestamp_device': 4075656, + 'timestamp_stream': 337.4442320615053, + 'transform': [array([ -2.647892 , -11.97476578, 0.01394563]), + array([-4.78249826e-02, 6.30420828e+00, 6.71389396e-04])]} +{'AngularVelocity': array([0.00229363, 0.05349038, 0.00126746]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': -0.04979711398482323, + 'Location': array([ -7.55631447, -21.18659782, 0.17741866]), + 'Rotation': array([-0.0608843 , -1.71984863, 0.00387347]), + 'Velocity': array([ 3.98080081e-01, -1.21020479e-02, -1.66273108e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.50071812, 13.91236019, 2.51789641]), + 'camera_rotation': array([-11.00492954, -3.6609726 , 5.37233686]), + 'current_gear_input': False, + 'focus_actor_dist': 1190.4874267578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -568.85180664, -1386.86279297, 17.16573334]), + 'frame': 10273, + 'frame_number': 10273, + 'framesequence': 39208, + 'gaze_dir': array([0.96749878, 0.22908783, 0.1065979 ]), + 'gaze_origin': array([-3.09882283, -0.19920121, 0.06701737]), + 'gaze_valid': True, + 'gaze_vergence': 276.91668701171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96658325, 0.23556519, 0.10098267]), + 'left_gaze_origin': array([-3.00204325, 2.990587 , 0.06408844]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3990631103515625, + 'left_pupil_posn': array([ 0.24454939, -0.03548169]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96841431, 0.22261047, 0.11221313]), + 'right_gaze_origin': array([-3.19560242, -3.38898945, 0.0699463 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.32537841796875, + 'right_pupil_posn': array([ 0.2211169 , -0.11362445]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08613544702529907, + 'throttle_input': 0.13888761401176453, + 'timestamp': 337.47615836188197, + 'timestamp_carla': 337476, + 'timestamp_device': 4075689, + 'timestamp_stream': 337.47615836188197, + 'transform': [array([ -2.62523365, -11.91177559, 0.01401529]), + array([-4.71829437e-02, 6.18863297e+00, 5.18800633e-04])]} +{'AngularVelocity': array([-1.62128289e-03, -5.20266481e-02, 3.30141438e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04998928681015968, + 'FR_Wheel_Angle': -0.04996510595083237, + 'Location': array([ -7.55179262, -21.18682289, 0.1775389 ]), + 'Rotation': array([-0.07965367, -1.70632946, 0.00383401]), + 'Velocity': array([-3.36680278e-05, 1.18433418e-05, -4.22229423e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.44121933, 13.92715263, 2.4774971 ]), + 'camera_rotation': array([-11.16866302, -3.49453592, 5.50118732]), + 'current_gear_input': False, + 'focus_actor_dist': 1185.1448974609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -571.30285645, -1386.78894043, 17.16819 ]), + 'frame': 10274, + 'frame_number': 10274, + 'framesequence': 39212, + 'gaze_dir': array([0.96704865, 0.22909546, 0.11038971]), + 'gaze_origin': array([-3.09875894, -0.19971237, 0.06866761]), + 'gaze_valid': True, + 'gaze_vergence': 173.62002563476562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96655273, 0.23538208, 0.10169983]), + 'left_gaze_origin': array([-3.00210881, 2.98983479, 0.06711274]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.342437744140625, + 'left_pupil_posn': array([ 0.24520397, -0.03107893]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96754456, 0.22280884, 0.11907959]), + 'right_gaze_origin': array([-3.19540882, -3.38925934, 0.07022248]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3233489990234375, + 'right_pupil_posn': array([ 0.22124004, -0.11315846]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09089633077383041, + 'throttle_input': 0.1428549587726593, + 'timestamp': 337.50837176293135, + 'timestamp_carla': 337509, + 'timestamp_device': 4075722, + 'timestamp_stream': 337.50837176293135, + 'transform': [array([ -2.60041642, -11.84815884, 0.01407982]), + array([-4.67799641e-02, 6.06486750e+00, 3.35696794e-04])]} +{'AngularVelocity': array([-5.82527660e-04, -1.83150955e-02, 1.31524530e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.049989309161901474, + 'FR_Wheel_Angle': -0.049965132027864456, + 'Location': array([ -7.55173302, -21.18682289, 0.17748703]), + 'Rotation': array([-0.07146426, -1.70632946, 0.00384376]), + 'Velocity': array([-9.96818289e-06, 1.12880425e-05, 4.25291437e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.39552689, 13.95584869, 2.41940594]), + 'camera_rotation': array([-11.39147758, -3.41722775, 5.4472537 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1190.7999267578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -574.98583984, -1375.52294922, 17.1689682 ]), + 'frame': 10275, + 'frame_number': 10275, + 'framesequence': 39216, + 'gaze_dir': array([0.96750641, 0.22733307, 0.10997772]), + 'gaze_origin': array([-3.0985589 , -0.20194781, 0.07122803]), + 'gaze_valid': True, + 'gaze_vergence': 183.3481903076172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96664429, 0.2351532 , 0.10139465]), + 'left_gaze_origin': array([-3.00190735, 2.98594356, 0.06970062]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2596893310546875, + 'left_pupil_posn': array([ 0.24677491, -0.02921426]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96836853, 0.21951294, 0.11856079]), + 'right_gaze_origin': array([-3.19521046, -3.38983941, 0.07275544]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2681884765625, + 'right_pupil_posn': array([ 0.22159505, -0.11137533]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09547410905361176, + 'throttle_input': 0.1428549587726593, + 'timestamp': 337.54365016147494, + 'timestamp_carla': 337544, + 'timestamp_device': 4075756, + 'timestamp_stream': 337.54365016147494, + 'transform': [array([ -2.57123065, -11.77856064, 0.01408697]), + array([-4.66023795e-02, 5.92211199e+00, 2.74662161e-04])]} +{'AngularVelocity': array([-2.97917228e-04, -4.77263611e-03, -1.22529236e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.014099550433456898, + 'FR_Wheel_Angle': -0.014097626321017742, + 'Location': array([ -7.55171728, -21.18682289, 0.17747334]), + 'Rotation': array([-0.06924445, -1.70632946, 0.00384894]), + 'Velocity': array([-7.80075766e-07, 6.09132655e-07, 1.23696751e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.34196091, 13.98679066, 2.37557769]), + 'camera_rotation': array([-11.57271671, -3.36189151, 5.45348024]), + 'current_gear_input': False, + 'focus_actor_dist': 1146.5645751953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -559.79760742, -1410.92822266, 17.16264343]), + 'frame': 10276, + 'frame_number': 10276, + 'framesequence': 39220, + 'gaze_dir': array([0.96629333, 0.23012543, 0.11487579]), + 'gaze_origin': array([-3.09956145, -0.20632097, 0.07378388]), + 'gaze_valid': True, + 'gaze_vergence': 292.790283203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96427917, 0.23985291, 0.11228943]), + 'left_gaze_origin': array([-3.00203419, 2.98457193, 0.07031555]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2592010498046875, + 'left_pupil_posn': array([ 0.24801099, -0.02921426]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9683075 , 0.22039795, 0.11746216]), + 'right_gaze_origin': array([-3.19708872, -3.39721394, 0.0772522 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17620849609375, + 'right_pupil_posn': array([ 0.22861767, -0.1048466 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09953917562961578, + 'throttle_input': 0.1428549587726593, + 'timestamp': 337.57748706266284, + 'timestamp_carla': 337578, + 'timestamp_device': 4075789, + 'timestamp_stream': 337.57748706266284, + 'transform': [array([ -2.54147673, -11.71180534, 0.01411228]), + array([-4.65409048e-02, 5.77894306e+00, 2.13629202e-04])]} +{'AngularVelocity': array([-8.05402294e-07, -1.12706679e-03, -1.28984584e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.012816183269023895, + 'FR_Wheel_Angle': -0.0166604146361351, + 'Location': array([ -7.55171347, -21.1868248 , 0.17747127]), + 'Rotation': array([-0.06909419, -1.70632946, 0.00384804]), + 'Velocity': array([1.78409732e-06, 5.17609294e-07, 1.45650949e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.26995277, 14.00676441, 2.34552217]), + 'camera_rotation': array([-11.6756134 , -3.29324436, 5.50217915]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9874267578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -567.43206787, -1386.78833008, 17.16418457]), + 'frame': 10277, + 'frame_number': 10277, + 'framesequence': 39224, + 'gaze_dir': array([0.96646881, 0.22929382, 0.11509705]), + 'gaze_origin': array([-3.09954405, -0.20714419, 0.07359619]), + 'gaze_valid': True, + 'gaze_vergence': 313.5527038574219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96459961, 0.23838806, 0.11268616]), + 'left_gaze_origin': array([-3.00204635, 2.98367929, 0.0704773 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.259063720703125, + 'left_pupil_posn': array([ 0.24854887, -0.02910006]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96833801, 0.22019958, 0.11750793]), + 'right_gaze_origin': array([-3.19704151, -3.39796758, 0.07671509]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1760101318359375, + 'right_pupil_posn': array([ 0.22861075, -0.10502553]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10279855132102966, + 'throttle_input': 0.1428549587726593, + 'timestamp': 337.61010586470366, + 'timestamp_carla': 337610, + 'timestamp_device': 4075822, + 'timestamp_stream': 337.61010586470366, + 'transform': [array([ -2.51132226, -11.64738655, 0.01415802]), + array([-4.65682261e-02, 5.63574743e+00, 9.15528653e-05])]} +{'AngularVelocity': array([ 7.93235158e-05, -2.95368925e-04, -1.33746635e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.55171251, -21.1868248 , 0.1774697 ]), + 'Rotation': array([-0.06909419, -1.70632946, 0.00384804]), + 'Velocity': array([ 1.92033121e-06, 3.22631081e-07, -2.41394577e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21649361, 14.0519371 , 2.3067627 ]), + 'camera_rotation': array([-11.86139488, -3.23726678, 5.54198933]), + 'current_gear_input': False, + 'focus_actor_dist': 1146.206787109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -560.20800781, -1397.53662109, 17.15959167]), + 'frame': 10278, + 'frame_number': 10278, + 'framesequence': 39228, + 'gaze_dir': array([0.9662323 , 0.22989655, 0.11600494]), + 'gaze_origin': array([-3.09950948, -0.20760269, 0.07332078]), + 'gaze_valid': True, + 'gaze_vergence': 399.0411682128906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96456909, 0.23735046, 0.11506653]), + 'left_gaze_origin': array([-3.00202942, 2.98337412, 0.07101899]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2725372314453125, + 'left_pupil_posn': array([ 0.24952972, -0.0289681 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96789551, 0.22244263, 0.11694336]), + 'right_gaze_origin': array([-3.19698977, -3.39857984, 0.07562256]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.175994873046875, + 'right_pupil_posn': array([ 0.22867644, -0.10491467]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10578326135873795, + 'throttle_input': 0.1428549587726593, + 'timestamp': 337.64252626150846, + 'timestamp_carla': 337643, + 'timestamp_device': 4075856, + 'timestamp_stream': 337.64252626150846, + 'transform': [array([ -2.48001456, -11.58329773, 0.01420667]), + array([-4.66638505e-02, 5.48880339e+00, -6.14650489e-05])]} +{'AngularVelocity': array([ 4.65209887e-05, -7.94278458e-05, -1.29126938e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([ -7.55171251, -21.1868248 , 0.17747527]), + 'Rotation': array([-0.06909419, -1.70632946, 0.00384804]), + 'Velocity': array([2.58728846e-06, 4.49857907e-07, 1.86485544e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.1862011 , 14.10827065, 2.27507663]), + 'camera_rotation': array([-12.09482956, -3.13130522, 5.57868242]), + 'current_gear_input': False, + 'focus_actor_dist': 1120.1993408203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -552.42089844, -1415.95202637, 17.15653229]), + 'frame': 10279, + 'frame_number': 10279, + 'framesequence': 39232, + 'gaze_dir': array([0.9646225 , 0.23540497, 0.1183548 ]), + 'gaze_origin': array([-3.09947371, -0.20862809, 0.07365036]), + 'gaze_valid': True, + 'gaze_vergence': 368.4073181152344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96321106, 0.24261475, 0.11550903]), + 'left_gaze_origin': array([-3.00204802, 2.98198247, 0.0716034 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2931365966796875, + 'left_pupil_posn': array([ 0.25249517, -0.02730381]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.96603394, 0.22819519, 0.12120056]), + 'right_gaze_origin': array([-3.19689965, -3.39923882, 0.07569733]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.17791748046875, + 'right_pupil_posn': array([ 0.23102427, -0.10480762]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10891446471214294, + 'throttle_input': 0.1428549587726593, + 'timestamp': 337.67525236308575, + 'timestamp_carla': 337675, + 'timestamp_device': 4075889, + 'timestamp_stream': 337.67525236308575, + 'transform': [array([ -2.44707799, -11.51856136, 0.01424475]), + array([-4.67458107e-02, 5.33585739e+00, -1.91240979e-04])]} diff --git a/PythonAPI/data/trials/trial9.txt b/PythonAPI/data/trials/trial9.txt new file mode 100644 index 0000000..b5ccffa --- /dev/null +++ b/PythonAPI/data/trials/trial9.txt @@ -0,0 +1,8554 @@ +{'AngularVelocity': array([0.02683257, 0.00116821, 0.00229108]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.3271035 , -34.64346695, 0.17064244]), + 'Rotation': array([-1.56274717e-02, 9.24389496e+01, -6.08825609e-02]), + 'Velocity': array([-1.49760563e-02, 3.56859893e-01, 1.02305406e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.12791729, 12.92021561, 2.88193297]), + 'camera_rotation': array([-6.28410816, 0.33744347, -0.22140759]), + 'current_gear_input': False, + 'focus_actor_dist': 1542.60888671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -567.93536377, -1992.06787109, 17.36725616]), + 'frame': 12606, + 'frame_number': 12606, + 'framesequence': 48449, + 'gaze_dir': array([0.9670105 , 0.25296021, 0.02293396]), + 'gaze_origin': array([-3.11485767, -0.21834031, 0.04583436]), + 'gaze_valid': True, + 'gaze_vergence': 153.42648315429688, + 'handbrake_input': False, + 'left_eye_openness': 0.9734911322593689, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96272278, 0.26994324, 0.0163269 ]), + 'left_gaze_origin': array([-3.04841614, 2.96788788, 0.05322571]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9332427978515625, + 'left_pupil_posn': array([ 0.26553202, -0.07914555]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9625592231750488, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97129822, 0.23597717, 0.02954102]), + 'right_gaze_origin': array([-3.18129873, -3.40456843, 0.03844299]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9301300048828125, + 'right_pupil_posn': array([ 0.24343836, -0.16232681]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.4656210653484, + 'timestamp_carla': 414466, + 'timestamp_device': 4152681, + 'timestamp_stream': 414.4656210653484, + 'transform': [array([-4.20686334e-01, -2.13687592e+01, 8.63998383e-03]), + array([-0.0608843 , 2.43892264, 0.01562502])]} +{'AngularVelocity': array([0.00761266, 0.00042663, 0.01332642]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.33043265, -34.56408691, 0.17062721]), + 'Rotation': array([-1.21509060e-02, 9.24391022e+01, -6.08825572e-02]), + 'Velocity': array([-1.35579472e-02, 3.23268235e-01, 2.92563433e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.11397362, 12.94815826, 2.89094591]), + 'camera_rotation': array([-6.22728825, 0.38267154, -0.09288675]), + 'current_gear_input': False, + 'focus_actor_dist': 1460.8194580078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -538.94787598, -2067.72851562, 17.36510468]), + 'frame': 12607, + 'frame_number': 12607, + 'framesequence': 48453, + 'gaze_dir': array([0.96789551, 0.2496109 , 0.02108765]), + 'gaze_origin': array([-3.11212254, -0.21502534, 0.04475327]), + 'gaze_valid': True, + 'gaze_vergence': 149.86019897460938, + 'handbrake_input': False, + 'left_eye_openness': 0.9713931083679199, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96289062, 0.26922607, 0.01881409]), + 'left_gaze_origin': array([-3.04328156, 2.97470403, 0.05106354]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9730987548828125, + 'left_pupil_posn': array([ 0.25861883, -0.08171535]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9728001356124878, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97290039, 0.22999573, 0.02336121]), + 'right_gaze_origin': array([-3.18096328, -3.40475488, 0.03844299]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9423828125, + 'right_pupil_posn': array([ 0.24330246, -0.16137648]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.50174916535616, + 'timestamp_carla': 414502, + 'timestamp_device': 4152714, + 'timestamp_stream': 414.50174916535616, + 'transform': [array([-4.21240389e-01, -2.13559780e+01, 8.81284662e-03]), + array([-0.0608843 , 2.43899465, 0.01474 ])]} +{'AngularVelocity': array([0.00244771, 0.00016334, 0.04793739]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.33345008, -34.49205017, 0.17061535]), + 'Rotation': array([-1.12629812e-02, 9.24395599e+01, -6.08825684e-02]), + 'Velocity': array([-0.01226934, 0.29284745, -0.00035626]), + 'brake_input': 0.0, + 'camera_location': array([-5.10590839, 12.98124027, 2.89965868]), + 'camera_rotation': array([-6.24971151, 0.47092104, 0.05559556]), + 'current_gear_input': False, + 'focus_actor_dist': 1434.113037109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -527.45153809, -2091.00341797, 17.36186218]), + 'frame': 12608, + 'frame_number': 12608, + 'framesequence': 48457, + 'gaze_dir': array([0.96692657, 0.253685 , 0.02072144]), + 'gaze_origin': array([-3.11185408, -0.21373597, 0.04483566]), + 'gaze_valid': True, + 'gaze_vergence': 194.60958862304688, + 'handbrake_input': False, + 'left_eye_openness': 0.9751322865486145, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9630127 , 0.26873779, 0.01885986]), + 'left_gaze_origin': array([-3.04278731, 2.97730732, 0.05182343]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0602264404296875, + 'left_pupil_posn': array([ 0.25976288, -0.08170772]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9537398219108582, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97084045, 0.2386322 , 0.02258301]), + 'right_gaze_origin': array([-3.1809206 , -3.40477943, 0.0378479 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9688568115234375, + 'right_pupil_posn': array([ 0.24312198, -0.16179335]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.53415686637163, + 'timestamp_carla': 414534, + 'timestamp_device': 4152747, + 'timestamp_stream': 414.53415686637163, + 'transform': [array([-4.21709269e-01, -2.13446827e+01, 8.97222478e-03]), + array([-0.0608843 , 2.43897152, 0.01409913])]} +{'AngularVelocity': array([0.001258 , 0.00011137, 0.09452202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.33581674, -34.43551254, 0.17060398]), + 'Rotation': array([-1.11127170e-02, 9.24398804e+01, -6.08825609e-02]), + 'Velocity': array([-1.12597179e-02, 2.68984348e-01, 2.33335493e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.11904335, 12.99918461, 2.8968401 ]), + 'camera_rotation': array([-6.34228802, 0.61499429, 0.08386519]), + 'current_gear_input': False, + 'focus_actor_dist': 1412.932373046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -529.03338623, -2112.47998047, 17.36703491]), + 'frame': 12609, + 'frame_number': 12609, + 'framesequence': 48461, + 'gaze_dir': array([0.96821594, 0.2480545 , 0.024086 ]), + 'gaze_origin': array([-3.11178756, -0.21326295, 0.0448082 ]), + 'gaze_valid': True, + 'gaze_vergence': 143.73866271972656, + 'handbrake_input': False, + 'left_eye_openness': 0.9788839817047119, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96339417, 0.26737976, 0.01863098]), + 'left_gaze_origin': array([-3.04278731, 2.97825336, 0.0517685 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0255584716796875, + 'left_pupil_posn': array([ 0.25569713, -0.07909608]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9630178809165955, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97303772, 0.22872925, 0.02954102]), + 'right_gaze_origin': array([-3.1807878 , -3.40477943, 0.0378479 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9683380126953125, + 'right_pupil_posn': array([ 0.24262619, -0.16179335]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.5660465657711, + 'timestamp_carla': 414566, + 'timestamp_device': 4152781, + 'timestamp_stream': 414.5660465657711, + 'transform': [array([-4.22168255e-01, -2.13337154e+01, 9.10175312e-03]), + array([-0.0608843 , 2.43896842, 0.01358033])]} +{'AngularVelocity': array([ 5.92600729e-04, 5.25944924e-05, -1.10762417e-02]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -1.33862221, -34.36883163, 0.1706387 ]), + 'Rotation': array([-1.09283021e-02, 9.24370193e+01, -6.08825572e-02]), + 'Velocity': array([-1.00646913e-02, 2.40820497e-01, 3.83234001e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.14255714, 13.02587986, 2.8846302 ]), + 'camera_rotation': array([-6.32838154, 0.72265154, 0.10350616]), + 'current_gear_input': False, + 'focus_actor_dist': 1438.9158935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -532.46343994, -2085.08056641, 17.36473083]), + 'frame': 12610, + 'frame_number': 12610, + 'framesequence': 48465, + 'gaze_dir': array([0.96844482, 0.24721527, 0.02456665]), + 'gaze_origin': array([-3.11086369, -0.21217652, 0.04493485]), + 'gaze_valid': True, + 'gaze_vergence': 153.2096710205078, + 'handbrake_input': False, + 'left_eye_openness': 0.9759931564331055, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96385193, 0.26564026, 0.01998901]), + 'left_gaze_origin': array([-3.04156971, 2.97943425, 0.05160981]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.033477783203125, + 'left_pupil_posn': array([ 0.25490117, -0.07907939]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9617981314659119, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97303772, 0.22879028, 0.02914429]), + 'right_gaze_origin': array([-3.18015766, -3.40378737, 0.03825989]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.985687255859375, + 'right_pupil_posn': array([ 0.24127603, -0.16090429]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.60146736726165, + 'timestamp_carla': 414601, + 'timestamp_device': 4152814, + 'timestamp_stream': 414.60146736726165, + 'transform': [array([-4.22693312e-01, -2.13217106e+01, 9.19214264e-03]), + array([-0.0608843 , 2.43906736, 0.01309205])]} +{'AngularVelocity': array([-1.65167414e-02, -3.68013105e-04, -1.15979528e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17980894446372986, + 'FR_Wheel_Angle': 0.180165097117424, + 'Location': array([ -1.34073102, -34.3196373 , 0.17063968]), + 'Rotation': array([-1.21509060e-02, 9.24332733e+01, -6.08825609e-02]), + 'Velocity': array([-0.00778195, 0.1826293 , 0.00033151]), + 'brake_input': 0.0, + 'camera_location': array([-5.15209389, 13.0360775 , 2.8730185 ]), + 'camera_rotation': array([-6.2705164 , 0.75341958, 0.08818513]), + 'current_gear_input': False, + 'focus_actor_dist': 1449.477294921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -537.08935547, -2074.33203125, 17.36555481]), + 'frame': 12611, + 'frame_number': 12611, + 'framesequence': 48469, + 'gaze_dir': array([0.96897125, 0.24525452, 0.02433014]), + 'gaze_origin': array([-3.11060667, -0.21200334, 0.0450592 ]), + 'gaze_valid': True, + 'gaze_vergence': 160.97723388671875, + 'handbrake_input': False, + 'left_eye_openness': 0.9733055830001831, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9647522 , 0.2624054 , 0.01922607]), + 'left_gaze_origin': array([-3.04148889, 2.97978067, 0.05144348]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.040618896484375, + 'left_pupil_posn': array([ 0.25442111, -0.0790627 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9658878445625305, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97319031, 0.22810364, 0.0294342 ]), + 'right_gaze_origin': array([-3.17972422, -3.40378737, 0.03867493]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0186920166015625, + 'right_pupil_posn': array([ 0.24007189, -0.16075861]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.63407726585865, + 'timestamp_carla': 414634, + 'timestamp_device': 4152847, + 'timestamp_stream': 414.63407726585865, + 'transform': [array([-4.23146665e-01, -2.13108158e+01, 9.28569771e-03]), + array([-0.0608843 , 2.43905091, 0.01272584])]} +{'AngularVelocity': array([ 0.0023636 , -0.00348478, -1.16215038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17993919551372528, + 'FR_Wheel_Angle': 0.18020594120025635, + 'Location': array([ -1.34238493, -34.28120804, 0.1706309 ]), + 'Rotation': array([-1.19323395e-02, 9.24387207e+01, -6.08215295e-02]), + 'Velocity': array([-5.84541913e-03, 1.47195309e-01, 1.11808775e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.17046833, 13.05738926, 2.84490275]), + 'camera_rotation': array([-6.35186386, 0.77646863, 0.07047115]), + 'current_gear_input': False, + 'focus_actor_dist': 1462.7349853515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -539.04052734, -2059.79003906, 17.36237335]), + 'frame': 12612, + 'frame_number': 12612, + 'framesequence': 48473, + 'gaze_dir': array([0.96945953, 0.24317169, 0.02500916]), + 'gaze_origin': array([-3.11013055, -0.21190797, 0.04528503]), + 'gaze_valid': True, + 'gaze_vergence': 155.08518981933594, + 'handbrake_input': False, + 'left_eye_openness': 0.9763004183769226, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.96502686, 0.26133728, 0.02032471]), + 'left_gaze_origin': array([-3.04085255, 2.97997618, 0.05158997]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0806427001953125, + 'left_pupil_posn': array([ 0.25316966, -0.07874203]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9646981358528137, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97389221, 0.2250061 , 0.0296936 ]), + 'right_gaze_origin': array([-3.17940831, -3.4037919 , 0.0389801 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0544586181640625, + 'right_pupil_posn': array([ 0.23964512, -0.16014433]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.6676469668746, + 'timestamp_carla': 414668, + 'timestamp_device': 4152881, + 'timestamp_stream': 414.6676469668746, + 'transform': [array([-4.23623651e-01, -2.12997532e+01, 9.36130527e-03]), + array([-0.0608843 , 2.43911219, 0.01239015])]} +{'AngularVelocity': array([ 0.01091845, 0.00422702, -0.9941929 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17964281141757965, + 'FR_Wheel_Angle': 0.1798403412103653, + 'Location': array([ -1.34425247, -34.23844528, 0.17060047]), + 'Rotation': array([-6.34524552e-03, 9.24391327e+01, -6.09130897e-02]), + 'Velocity': array([-0.0109827 , 0.23903356, 0.00026907]), + 'brake_input': 0.0, + 'camera_location': array([-5.19664955, 13.06711578, 2.81523895]), + 'camera_rotation': array([-6.49014807, 0.81576067, 0.06503184]), + 'current_gear_input': False, + 'focus_actor_dist': 1450.6307373046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -533.06213379, -2069.55175781, 17.35990143]), + 'frame': 12613, + 'frame_number': 12613, + 'framesequence': 48477, + 'gaze_dir': array([0.97796631, 0.19486237, 0.07148743]), + 'gaze_origin': array([-3.08508539, -0.17694016, 0.0717453 ]), + 'gaze_valid': True, + 'gaze_vergence': 110.19561004638672, + 'handbrake_input': False, + 'left_eye_openness': 0.9816288352012634, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97567749, 0.21151733, 0.05743408]), + 'left_gaze_origin': array([-3.00041986, 3.01509571, 0.07502595]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.295440673828125, + 'left_pupil_posn': array([ 0.21242893, -0.03574467]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9646305441856384, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98025513, 0.1782074 , 0.08554077]), + 'right_gaze_origin': array([-3.16975117, -3.36897588, 0.06846467]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0656890869140625, + 'right_pupil_posn': array([ 0.19779098, -0.12374175]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.69959326833487, + 'timestamp_carla': 414700, + 'timestamp_device': 4152914, + 'timestamp_stream': 414.69959326833487, + 'transform': [array([-4.24053341e-01, -2.12893696e+01, 9.42771882e-03]), + array([-0.0608843 , 2.43908525, 0.01214601])]} +{'AngularVelocity': array([ 0.02971585, 0.00675232, -0.64415777]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1788301020860672, + 'FR_Wheel_Angle': 0.17898143827915192, + 'Location': array([ -1.34786487, -34.15570068, 0.1705534 ]), + 'Rotation': array([ 9.90377390e-04, 9.24425964e+01, -6.08825609e-02]), + 'Velocity': array([-2.14952137e-02, 4.84668732e-01, -6.88934306e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.21628666, 13.0764389 , 2.81391931]), + 'camera_rotation': array([-6.4877367 , 0.81876934, 0.08685426]), + 'current_gear_input': False, + 'focus_actor_dist': 1538.389892578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -487.23175049, -1960.20654297, 76.13970947]), + 'frame': 12614, + 'frame_number': 12614, + 'framesequence': 48482, + 'gaze_dir': array([0.97823334, 0.18347168, 0.09642029]), + 'gaze_origin': array([-3.04780746, -0.16523667, 0.07641907]), + 'gaze_valid': True, + 'gaze_vergence': 339.07220458984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97692871, 0.19180298, 0.09379578]), + 'left_gaze_origin': array([-2.93232751, 3.02505207, 0.06879273]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3220367431640625, + 'left_pupil_posn': array([ 0.20378351, -0.02307582]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97953796, 0.17514038, 0.0990448 ]), + 'right_gaze_origin': array([-3.1632874 , -3.35552549, 0.08404541]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.148284912109375, + 'right_pupil_posn': array([ 0.18158031, -0.09903073]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.7365962676704, + 'timestamp_carla': 414737, + 'timestamp_device': 4152956, + 'timestamp_stream': 414.7365962676704, + 'transform': [array([-4.24639285e-01, -2.12775173e+01, 9.44835600e-03]), + array([-0.0608843 , 2.43947458, 0.01190187])]} +{'AngularVelocity': array([0.09308276, 0.00651941, 0.14615977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1774541586637497, + 'FR_Wheel_Angle': 0.17750561237335205, + 'Location': array([ -1.35524094, -33.98688507, 0.17051482]), + 'Rotation': array([ 1.14473961e-02, 9.24426651e+01, -6.09130785e-02]), + 'Velocity': array([-4.29000854e-02, 9.85501289e-01, 1.24859813e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21587658, 13.08373547, 2.82438612]), + 'camera_rotation': array([-6.37499094, 0.83535659, 0.16446051]), + 'current_gear_input': False, + 'focus_actor_dist': 2524.513916015625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-706.01513672, -996.36010742, 99.38654327]), + 'frame': 12615, + 'frame_number': 12615, + 'framesequence': 48485, + 'gaze_dir': array([0.9779892 , 0.18592072, 0.09420776]), + 'gaze_origin': array([-3.04289937, -0.16541062, 0.07512055]), + 'gaze_valid': True, + 'gaze_vergence': 292.1500549316406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97715759, 0.19291687, 0.08905029]), + 'left_gaze_origin': array([-2.92308521, 3.0262742 , 0.06614075]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3021240234375, + 'left_pupil_posn': array([ 0.20417058, -0.02307582]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9788208 , 0.17892456, 0.09936523]), + 'right_gaze_origin': array([-3.16271377, -3.35709572, 0.08410034]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.130279541015625, + 'right_pupil_posn': array([ 0.18301475, -0.10051334]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.76781906560063, + 'timestamp_carla': 414768, + 'timestamp_device': 4152981, + 'timestamp_stream': 414.76781906560063, + 'transform': [array([-4.25006390e-01, -2.12676659e+01, 9.50899068e-03]), + array([-0.0608843 , 2.4392767 , 0.01174928])]} +{'AngularVelocity': array([0.05367442, 0.00267517, 0.08826604]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17561474442481995, + 'FR_Wheel_Angle': 0.176913321018219, + 'Location': array([ -1.36806345, -33.69338608, 0.17047824]), + 'Rotation': array([ 1.87488683e-02, 9.24610443e+01, -6.10656627e-02]), + 'Velocity': array([-6.83693215e-02, 1.54551864e+00, 3.55243683e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.22017002, 13.09285641, 2.82466412]), + 'camera_rotation': array([-6.33181715, 0.86180413, 0.20854531]), + 'current_gear_input': False, + 'focus_actor_dist': 2525.11181640625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-713.35552979, -996.38061523, 98.15258026]), + 'frame': 12616, + 'frame_number': 12616, + 'framesequence': 48489, + 'gaze_dir': array([0.97769928, 0.18723297, 0.09461975]), + 'gaze_origin': array([-3.0443368 , -0.16563036, 0.07568894]), + 'gaze_valid': True, + 'gaze_vergence': 300.850830078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97660828, 0.19517517, 0.09017944]), + 'left_gaze_origin': array([-2.92577076, 3.02645445, 0.06707001]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2935028076171875, + 'left_pupil_posn': array([ 0.20421267, -0.02302659]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97879028, 0.17929077, 0.09906006]), + 'right_gaze_origin': array([-3.16290307, -3.35771513, 0.08430786]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.10064697265625, + 'right_pupil_posn': array([ 0.18425512, -0.10007524]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.8007714673877, + 'timestamp_carla': 414801, + 'timestamp_device': 4153014, + 'timestamp_stream': 414.8007714673877, + 'transform': [array([-4.25441116e-01, -2.12574024e+01, 9.54767223e-03]), + array([-0.0608843 , 2.43929052, 0.01159669])]} +{'AngularVelocity': array([0.02550814, 0.02757997, 0.78452569]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.214335560798645, + 'FR_Wheel_Angle': 1.6285579204559326, + 'Location': array([ -1.38736832, -33.27920151, 0.17050518]), + 'Rotation': array([ 1.79838873e-02, 9.25294876e+01, -6.36596531e-02]), + 'Velocity': array([-1.10680178e-01, 2.02774787e+00, 1.19886397e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.22672653, 13.10498047, 2.81595087]), + 'camera_rotation': array([-6.34336042, 0.89031845, 0.27880022]), + 'current_gear_input': False, + 'focus_actor_dist': 4675.458984375, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([-1242.32958984, 1088.69873047, 69.70928192]), + 'frame': 12617, + 'frame_number': 12617, + 'framesequence': 48493, + 'gaze_dir': array([0.97781372, 0.18712616, 0.09363556]), + 'gaze_origin': array([-3.0463717 , -0.16570663, 0.07701951]), + 'gaze_valid': True, + 'gaze_vergence': 297.63067626953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97694397, 0.19418335, 0.08863831]), + 'left_gaze_origin': array([-2.93002939, 3.027179 , 0.06879273]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2930908203125, + 'left_pupil_posn': array([ 0.20404005, -0.02281034]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97868347, 0.18006897, 0.09863281]), + 'right_gaze_origin': array([-3.16271377, -3.35859251, 0.08524628]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.091796875, + 'right_pupil_posn': array([ 0.18451619, -0.09984159]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.8360009677708, + 'timestamp_carla': 414836, + 'timestamp_device': 4153047, + 'timestamp_stream': 414.8360009677708, + 'transform': [array([-4.25952762e-01, -2.12465858e+01, 9.56684072e-03]), + array([-0.0608843 , 2.43954325, 0.01144411])]} +{'AngularVelocity': array([-1.20529823e-03, 4.17568982e-02, 3.44302678e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.412266254425049, + 'FR_Wheel_Angle': 5.003339767456055, + 'Location': array([ -1.42346156, -32.75805664, 0.17056949]), + 'Rotation': array([ 1.55660007e-02, 9.30415421e+01, -7.39135668e-02]), + 'Velocity': array([-2.30471775e-01, 2.43709540e+00, 5.59277541e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21606541, 13.1184063 , 2.7939496 ]), + 'camera_rotation': array([-6.38183451, 0.9352777 , 0.35561907]), + 'current_gear_input': False, + 'focus_actor_dist': 1656.324462890625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -506.99163818, -1838.19909668, 110.98428345]), + 'frame': 12618, + 'frame_number': 12618, + 'framesequence': 48497, + 'gaze_dir': array([0.97777557, 0.18712616, 0.09410858]), + 'gaze_origin': array([-3.04855442, -0.16576082, 0.07793732]), + 'gaze_valid': True, + 'gaze_vergence': 354.0735168457031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97689819, 0.19364929, 0.0901947 ]), + 'left_gaze_origin': array([-2.93449712, 3.02760172, 0.07040863]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.27667236328125, + 'left_pupil_posn': array([ 0.20400012, -0.02271616]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97865295, 0.18060303, 0.09802246]), + 'right_gaze_origin': array([-3.16261172, -3.35912323, 0.085466 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0716705322265625, + 'right_pupil_posn': array([ 0.18471622, -0.09908819]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.86785396561027, + 'timestamp_carla': 414868, + 'timestamp_device': 4153081, + 'timestamp_stream': 414.86785396561027, + 'transform': [array([-4.26316202e-01, -2.12369480e+01, 9.60418675e-03]), + array([-0.0608843 , 2.43937254, 0.01135255])]} +{'AngularVelocity': array([0.0132481 , 0.00674866, 5.41555548]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.863330364227295, + 'FR_Wheel_Angle': 6.199177265167236, + 'Location': array([ -1.47653878, -32.23995972, 0.17064227]), + 'Rotation': array([ 1.46029433e-02, 9.40073166e+01, -7.89184347e-02]), + 'Velocity': array([-3.52838278e-01, 2.76542974e+00, 5.48534386e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21090126, 13.12565041, 2.77931809]), + 'camera_rotation': array([-6.47607088, 0.99484795, 0.3578853 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1635.069091796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -503.309021 , -1858.09667969, 110.5953064 ]), + 'frame': 12619, + 'frame_number': 12619, + 'framesequence': 48501, + 'gaze_dir': array([0.9775238 , 0.18769836, 0.0954361 ]), + 'gaze_origin': array([-3.05358672, -0.16594163, 0.07974472]), + 'gaze_valid': True, + 'gaze_vergence': 290.17608642578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97628784, 0.19631958, 0.09111023]), + 'left_gaze_origin': array([-2.94540405, 3.02805495, 0.0735199 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.243316650390625, + 'left_pupil_posn': array([ 0.20331955, -0.02199328]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97875977, 0.17907715, 0.09976196]), + 'right_gaze_origin': array([-3.16176939, -3.35993814, 0.08596955]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0653076171875, + 'right_pupil_posn': array([ 0.18619931, -0.09832025]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.8994792662561, + 'timestamp_carla': 414899, + 'timestamp_device': 4153114, + 'timestamp_stream': 414.8994792662561, + 'transform': [array([-4.26712334e-01, -2.12275047e+01, 9.61502083e-03]), + array([-0.0608843 , 2.43937254, 0.01135255])]} +{'AngularVelocity': array([-4.79250448e-03, -4.22894992e-02, 4.99143314e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.655414581298828, + 'FR_Wheel_Angle': 4.378443241119385, + 'Location': array([ -1.57881951, -31.43828392, 0.17074475]), + 'Rotation': array([ 1.40770189e-02, 9.55417175e+01, -7.26318359e-02]), + 'Velocity': array([-4.56182539e-01, 3.17087603e+00, 3.35683813e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.19846249, 13.14221287, 2.76705003]), + 'camera_rotation': array([-6.51955175, 1.06772816, 0.31026235]), + 'current_gear_input': False, + 'focus_actor_dist': 1621.1436767578125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -502.5057373 , -1871.2890625 , 110.36982727]), + 'frame': 12620, + 'frame_number': 12620, + 'framesequence': 48505, + 'gaze_dir': array([0.97747803, 0.18768311, 0.0958786 ]), + 'gaze_origin': array([-3.05476689, -0.16597901, 0.08114854]), + 'gaze_valid': True, + 'gaze_vergence': 300.9798889160156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97618103, 0.19638062, 0.09205627]), + 'left_gaze_origin': array([-2.94885421, 3.02845788, 0.07578889]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.235015869140625, + 'left_pupil_posn': array([ 0.20307779, -0.02105105]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97877502, 0.1789856 , 0.09970093]), + 'right_gaze_origin': array([-3.16067982, -3.36041594, 0.08650818]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0613250732421875, + 'right_pupil_posn': array([ 0.1865344 , -0.09741688]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.9340529665351, + 'timestamp_carla': 414934, + 'timestamp_device': 4153147, + 'timestamp_stream': 414.9340529665351, + 'transform': [array([-4.27178174e-01, -2.12173214e+01, 9.62013192e-03]), + array([-0.0608843 , 2.43954349, 0.011261 ])]} +{'AngularVelocity': array([-0.03860816, -0.06767245, 1.62783313]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.950995683670044, + 'FR_Wheel_Angle': 0.5233551859855652, + 'Location': array([ -1.66192758, -30.79414558, 0.17089584]), + 'Rotation': array([ 6.11301884e-03, 9.62314301e+01, -5.78308143e-02]), + 'Velocity': array([-4.10600930e-01, 3.27392840e+00, 3.52802279e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.19257832, 13.17019463, 2.74269199]), + 'camera_rotation': array([-6.53019333, 1.15527225, 0.23502359]), + 'current_gear_input': False, + 'focus_actor_dist': 1612.1500244140625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -502.18212891, -1879.52209473, 110.27958679]), + 'frame': 12621, + 'frame_number': 12621, + 'framesequence': 48509, + 'gaze_dir': array([0.97730255, 0.18687439, 0.0991745 ]), + 'gaze_origin': array([-3.05507898, -0.16574784, 0.08174134]), + 'gaze_valid': True, + 'gaze_vergence': 283.8256530761719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97615051, 0.19535828, 0.09449768]), + 'left_gaze_origin': array([-2.95015574, 3.02910638, 0.07695923]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2306976318359375, + 'left_pupil_posn': array([ 0.20247579, -0.01908004]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97845459, 0.1783905 , 0.10385132]), + 'right_gaze_origin': array([-3.16000247, -3.3606019 , 0.08652344]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.066741943359375, + 'right_pupil_posn': array([ 0.18629062, -0.09641004]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.96700356528163, + 'timestamp_carla': 414967, + 'timestamp_device': 4153181, + 'timestamp_stream': 414.96700356528163, + 'transform': [array([-4.27579045e-01, -2.12077560e+01, 9.62352753e-03]), + array([-0.0608843 , 2.43954349, 0.011261 ])]} +{'AngularVelocity': array([-0.02635405, 0.11410426, 2.65717006]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.7728259563446045, + 'FR_Wheel_Angle': 3.5460920333862305, + 'Location': array([ -1.76610124, -29.92261314, 0.17106257]), + 'Rotation': array([-4.24154708e-03, 9.65557175e+01, -6.64062276e-02]), + 'Velocity': array([-4.46026742e-01, 3.22734118e+00, 3.09743860e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21025658, 13.19098663, 2.71536851]), + 'camera_rotation': array([-6.59688997, 1.26100743, 0.289554 ]), + 'current_gear_input': False, + 'focus_actor_dist': 5389.4619140625, + 'focus_actor_name': 'BP_Block05_20', + 'focus_actor_pt': array([-1441.91967773, 1779.80371094, 65.25170135]), + 'frame': 12622, + 'frame_number': 12622, + 'framesequence': 48513, + 'gaze_dir': array([0.97749329, 0.18558502, 0.09964752]), + 'gaze_origin': array([-3.05527735, -0.16542588, 0.08228226]), + 'gaze_valid': True, + 'gaze_vergence': 266.18865966796875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97615051, 0.19511414, 0.09503174]), + 'left_gaze_origin': array([-2.95103478, 3.02975035, 0.07791443]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.068939208984375, + 'left_pupil_posn': array([ 0.20129073, -0.01831996]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97883606, 0.17605591, 0.10426331]), + 'right_gaze_origin': array([-3.15952015, -3.3606019 , 0.08665009]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0573272705078125, + 'right_pupil_posn': array([ 0.18619931, -0.09604406]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 414.99919636547565, + 'timestamp_carla': 414999, + 'timestamp_device': 4153214, + 'timestamp_stream': 414.99919636547565, + 'transform': [array([-4.27965701e-01, -2.11985378e+01, 9.63054597e-03]), + array([-0.0608843 , 2.43954349, 0.011261 ])]} +{'AngularVelocity': array([-0.0187436 , -0.01968711, 6.09421825]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.70129919052124, + 'FR_Wheel_Angle': 6.029513835906982, + 'Location': array([ -1.88333642, -29.18740654, 0.17123069]), + 'Rotation': array([-7.87520781e-03, 9.77363586e+01, -8.19396824e-02]), + 'Velocity': array([-5.94641149e-01, 3.09412432e+00, 7.79542897e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21157265, 13.21732807, 2.69492412]), + 'camera_rotation': array([-6.69382429, 1.34384537, 0.42806002]), + 'current_gear_input': False, + 'focus_actor_dist': 5389.365234375, + 'focus_actor_name': 'BP_Block05_20', + 'focus_actor_pt': array([-1445.24841309, 1779.73486328, 60.56522369]), + 'frame': 12623, + 'frame_number': 12623, + 'framesequence': 48517, + 'gaze_dir': array([0.95568085, 0.29147339, 0.03501129]), + 'gaze_origin': array([-3.07732558, -0.24030304, 0.04575348]), + 'gaze_valid': True, + 'gaze_vergence': 136.35948181152344, + 'handbrake_input': False, + 'left_eye_openness': 0.9790528416633606, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.949646 , 0.31178284, 0.03048706]), + 'left_gaze_origin': array([-2.97776055, 2.94040227, 0.04216156]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.10260009765625, + 'left_pupil_posn': array([ 0.2949872 , -0.07144773]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9689417481422424, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9617157 , 0.27116394, 0.03953552]), + 'right_gaze_origin': array([-3.17689061, -3.42100859, 0.0493454 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.078857421875, + 'right_pupil_posn': array([ 0.26977372, -0.15057743]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028382213786244392, + 'throttle_input': 0.0, + 'timestamp': 415.03247126564384, + 'timestamp_carla': 415032, + 'timestamp_device': 4153247, + 'timestamp_stream': 415.03247126564384, + 'transform': [array([-4.28359210e-01, -2.11891422e+01, 9.62673128e-03]), + array([-0.0608843 , 2.43954349, 0.011261 ])]} +{'AngularVelocity': array([-0.01047919, -0.04773236, 5.30878925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.119995594024658, + 'FR_Wheel_Angle': 5.10328483581543, + 'Location': array([ -1.99746513, -28.59049416, 0.17140476]), + 'Rotation': array([-1.29090566e-02, 9.88983536e+01, -7.31811523e-02]), + 'Velocity': array([-6.03295147e-01, 2.86361909e+00, 8.67009163e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.19902897, 13.23644066, 2.69989586]), + 'camera_rotation': array([-6.71798229, 1.46864772, 0.45419815]), + 'current_gear_input': True, + 'focus_actor_dist': 1521.4669189453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -641.37945557, -2020.41711426, 17.44981384]), + 'frame': 12624, + 'frame_number': 12624, + 'framesequence': 48521, + 'gaze_dir': array([0.95301819, 0.30072784, 0.03580475]), + 'gaze_origin': array([-3.08192468, -0.25538561, 0.03806305]), + 'gaze_valid': True, + 'gaze_vergence': 2.811230421066284, + 'handbrake_input': False, + 'left_eye_openness': 0.9590185284614563, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95317078, 0.30073547, 0.03170776]), + 'left_gaze_origin': array([-2.98344588, 2.92602253, 0.03583832]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15924072265625, + 'left_pupil_posn': array([ 0.31554699, -0.07717633]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9510628581047058, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9528656 , 0.30072021, 0.03990173]), + 'right_gaze_origin': array([-3.18040323, -3.4367938 , 0.04028779]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0718841552734375, + 'right_pupil_posn': array([ 0.27682257, -0.15687931]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0028199104126542807, + 'throttle_input': 0.0, + 'timestamp': 415.06662536785007, + 'timestamp_carla': 415067, + 'timestamp_device': 4153281, + 'timestamp_stream': 415.06662536785007, + 'transform': [array([-4.28780049e-01, -2.11796341e+01, 9.63172875e-03]), + array([-0.0608843 , 2.43963933, 0.01119996])]} +{'AngularVelocity': array([ 0.00418294, -0.01015126, 3.48844337]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9059441089630127, + 'FR_Wheel_Angle': 4.065712928771973, + 'Location': array([ -2.12696648, -27.95209694, 0.17157486]), + 'Rotation': array([-1.42204529e-02, 9.98986130e+01, -6.30798191e-02]), + 'Velocity': array([-5.56272447e-01, 2.59647369e+00, 9.68332286e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.20221901, 13.26414776, 2.68822885]), + 'camera_rotation': array([-6.76443434, 1.57007933, 0.46567672]), + 'current_gear_input': False, + 'focus_actor_dist': 1527.2318115234375, + 'focus_actor_name': 'Plane38', + 'focus_actor_pt': array([ -660.29376221, -2020.54223633, 17.79415131]), + 'frame': 12625, + 'frame_number': 12625, + 'framesequence': 48525, + 'gaze_dir': array([0.95335388, 0.29932404, 0.03861237]), + 'gaze_origin': array([-3.08126616, -0.25351182, 0.04015427]), + 'gaze_valid': True, + 'gaze_vergence': 270.6501770019531, + 'handbrake_input': False, + 'left_eye_openness': 0.9675379395484924, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95413208, 0.2973938 , 0.03436279]), + 'left_gaze_origin': array([-2.98225403, 2.93211222, 0.03870392]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0865936279296875, + 'left_pupil_posn': array([ 0.31163728, -0.07390618]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.956169605255127, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95257568, 0.30125427, 0.04286194]), + 'right_gaze_origin': array([-3.18027806, -3.43913579, 0.04160462]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0253753662109375, + 'right_pupil_posn': array([ 0.27733243, -0.1547786 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.002600177191197872, + 'throttle_input': 0.0, + 'timestamp': 415.1023568660021, + 'timestamp_carla': 415102, + 'timestamp_device': 4153314, + 'timestamp_stream': 415.1023568660021, + 'transform': [array([-4.29300994e-01, -2.11698246e+01, 9.62799042e-03]), + array([-0.0608843 , 2.44013786, 0.01113892])]} +{'AngularVelocity': array([ 0.01167556, -0.01415488, 2.76645851]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.266132354736328, + 'FR_Wheel_Angle': 3.109592914581299, + 'Location': array([ -2.24980116, -27.37469864, 0.17171001]), + 'Rotation': array([-1.27246417e-02, 1.00664894e+02, -6.21032529e-02]), + 'Velocity': array([-5.26815772e-01, 2.34823895e+00, 5.00564580e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.20999813, 13.2851963 , 2.65383244]), + 'camera_rotation': array([-6.90927553, 1.68378937, 0.43280038]), + 'current_gear_input': False, + 'focus_actor_dist': 1570.074951171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -676.49072266, -1979.7902832 , 17.47032166]), + 'frame': 12626, + 'frame_number': 12626, + 'framesequence': 48529, + 'gaze_dir': array([0.95539093, 0.29276276, 0.03770447]), + 'gaze_origin': array([-3.07990193, -0.25223696, 0.04249954]), + 'gaze_valid': True, + 'gaze_vergence': 315.75848388671875, + 'handbrake_input': False, + 'left_eye_openness': 0.9724950790405273, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95315552, 0.30050659, 0.03416443]), + 'left_gaze_origin': array([-2.97952747, 2.93452621, 0.03962402]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.05364990234375, + 'left_pupil_posn': array([ 0.30420697, -0.07284117]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9421716928482056, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95762634, 0.28501892, 0.04124451]), + 'right_gaze_origin': array([-3.18027663, -3.43900013, 0.04537506]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1130828857421875, + 'right_pupil_posn': array([ 0.27827847, -0.15250635]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.135818567127, + 'timestamp_carla': 415136, + 'timestamp_device': 4153347, + 'timestamp_stream': 415.135818567127, + 'transform': [array([-4.29618061e-01, -2.11607838e+01, 9.64397378e-03]), + array([-0.0608843 , 2.43986464, 0.01110841])]} +{'AngularVelocity': array([ 0.02665184, -0.09931307, 0.10763986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.36069441, -26.8544426 , 0.1718426 ]), + 'Rotation': array([-1.07165659e-02, 1.01099739e+02, -5.32226562e-02]), + 'Velocity': array([-4.27350163e-01, 2.14005613e+00, 5.59129694e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.22338009, 13.29932594, 2.6300292 ]), + 'camera_rotation': array([-7.06167078, 1.83650351, 0.57094926]), + 'current_gear_input': False, + 'focus_actor_dist': 1504.005126953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -645.50866699, -2037.83276367, 17.45999908]), + 'frame': 12627, + 'frame_number': 12627, + 'framesequence': 48534, + 'gaze_dir': array([0.9557724 , 0.29144287, 0.03771973]), + 'gaze_origin': array([-3.07979536, -0.25165102, 0.04358979]), + 'gaze_valid': True, + 'gaze_vergence': 242.12213134765625, + 'handbrake_input': False, + 'left_eye_openness': 0.964765727519989, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95324707, 0.30046082, 0.03224182]), + 'left_gaze_origin': array([-2.97943425, 2.93573165, 0.04078064]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.068817138671875, + 'left_pupil_posn': array([ 0.30245662, -0.07133722]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9467286467552185, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95829773, 0.28242493, 0.04319763]), + 'right_gaze_origin': array([-3.18015623, -3.43903375, 0.04639893]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1014862060546875, + 'right_pupil_posn': array([ 0.27827847, -0.15243125]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.1716581657529, + 'timestamp_carla': 415172, + 'timestamp_device': 4153389, + 'timestamp_stream': 415.1716581657529, + 'transform': [array([-4.30221230e-01, -2.11512146e+01, 9.63788945e-03]), + array([-0.0608843 , 2.44075632, 0.01107789])]} +{'AngularVelocity': array([ 0.00424342, 0.0017283 , -1.57679582]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.4610064029693604, + 'FR_Wheel_Angle': -2.7367305755615234, + 'Location': array([ -2.45236015, -26.37321281, 0.17192604]), + 'Rotation': array([-9.27539635e-03, 1.00989380e+02, -4.95910607e-02]), + 'Velocity': array([-3.36770803e-01, 1.94662118e+00, 4.32386383e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.21111012, 13.31293297, 2.6384275 ]), + 'camera_rotation': array([-6.98658657, 1.95247483, 0.57889074]), + 'current_gear_input': False, + 'focus_actor_dist': 1444.7410888671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -625.97894287, -2093.125 , 17.46004486]), + 'frame': 12628, + 'frame_number': 12628, + 'framesequence': 48537, + 'gaze_dir': array([0.95639038, 0.2897644 , 0.03489685]), + 'gaze_origin': array([-3.07978082, -0.25148928, 0.04317551]), + 'gaze_valid': True, + 'gaze_vergence': 278.2943420410156, + 'handbrake_input': False, + 'left_eye_openness': 0.9604395627975464, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95344543, 0.29975891, 0.03269958]), + 'left_gaze_origin': array([-2.9793582 , 2.93630242, 0.04002381]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.07781982421875, + 'left_pupil_posn': array([ 0.30108571, -0.0738579 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9408034682273865, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95933533, 0.2797699 , 0.03709412]), + 'right_gaze_origin': array([-3.1802032 , -3.43928075, 0.04632721]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1187896728515625, + 'right_pupil_posn': array([ 0.27819788, -0.15232134]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.20094226673245, + 'timestamp_carla': 415201, + 'timestamp_device': 4153414, + 'timestamp_stream': 415.20094226673245, + 'transform': [array([-4.29392695e-01, -2.11435986e+01, 9.61517356e-03]), + array([-0.0608843 , 2.43566298, 0.01104738])]} +{'AngularVelocity': array([-3.72731546e-03, -2.29802006e-03, -3.50940037e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.424396514892578, + 'FR_Wheel_Angle': -5.611611366271973, + 'Location': array([ -2.52173114, -25.9485836 , 0.17205223]), + 'Rotation': array([-1.07165659e-02, 1.00504982e+02, -4.95300256e-02]), + 'Velocity': array([-2.39551574e-01, 1.72378242e+00, 6.04777306e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.18879795, 13.319067 , 2.64369226]), + 'camera_rotation': array([-6.83048248, 2.01972246, 0.55406404]), + 'current_gear_input': False, + 'focus_actor_dist': 1416.6024169921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -616.15655518, -2118.61767578, 17.45454407]), + 'frame': 12629, + 'frame_number': 12629, + 'framesequence': 48541, + 'gaze_dir': array([0.95652771, 0.2891922 , 0.03583527]), + 'gaze_origin': array([-3.07977915, -0.25161973, 0.042482 ]), + 'gaze_valid': True, + 'gaze_vergence': 281.13543701171875, + 'handbrake_input': False, + 'left_eye_openness': 0.9666041135787964, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95368958, 0.29890442, 0.03323364]), + 'left_gaze_origin': array([-2.97929096, 2.93672037, 0.03922577]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.077880859375, + 'left_pupil_posn': array([ 0.30070889, -0.07391047]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9385666251182556, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95936584, 0.27947998, 0.03843689]), + 'right_gaze_origin': array([-3.18026757, -3.43996 , 0.04573822]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1195831298828125, + 'right_pupil_posn': array([ 0.27835906, -0.15254116]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.2337395660579, + 'timestamp_carla': 415234, + 'timestamp_device': 4153447, + 'timestamp_stream': 415.2337395660579, + 'transform': [array([-4.30023342e-01, -2.11350670e+01, 9.65385418e-03]), + array([-0.0608843 , 2.43687582, 0.01101686])]} +{'AngularVelocity': array([ 0.02812484, 0.0064181 , -5.00752211]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.542890548706055, + 'FR_Wheel_Angle': -8.253832817077637, + 'Location': array([ -2.57044911, -25.56716728, 0.17210288]), + 'Rotation': array([-7.44490558e-03, 9.96796570e+01, -4.80957031e-02]), + 'Velocity': array([-1.51632279e-01, 1.62014246e+00, 5.10811806e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.1778326 , 13.32895088, 2.63190675]), + 'camera_rotation': array([-6.86201763, 2.03918242, 0.4417156 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1480.312744140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -639.97149658, -2058.48339844, 17.46173859]), + 'frame': 12630, + 'frame_number': 12630, + 'framesequence': 48545, + 'gaze_dir': array([0.95677185, 0.28857422, 0.03496552]), + 'gaze_origin': array([-3.07971358, -0.25263518, 0.04260788]), + 'gaze_valid': True, + 'gaze_vergence': 372.87677001953125, + 'handbrake_input': False, + 'left_eye_openness': 0.9673760533332825, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95449829, 0.29623413, 0.03393555]), + 'left_gaze_origin': array([-2.97912765, 2.93684721, 0.03951263]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.097320556640625, + 'left_pupil_posn': array([ 0.30108571, -0.07462204]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9346628189086914, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95904541, 0.28091431, 0.03599548]), + 'right_gaze_origin': array([-3.18029976, -3.44211769, 0.04570313]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1238861083984375, + 'right_pupil_posn': array([ 0.27888811, -0.15227795]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.26542426645756, + 'timestamp_carla': 415265, + 'timestamp_device': 4153480, + 'timestamp_stream': 415.26542426645756, + 'transform': [array([-4.30436552e-01, -2.11269493e+01, 9.68725141e-03]), + array([-0.0608843 , 2.43721056, 0.01098634])]} +{'AngularVelocity': array([ 0.01740143, -0.02595599, -7.35315657]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.550410270690918, + 'FR_Wheel_Angle': -12.655860900878906, + 'Location': array([ -2.60180759, -25.19402122, 0.17211697]), + 'Rotation': array([-1.61875470e-03, 9.84650345e+01, -4.30603065e-02]), + 'Velocity': array([-5.50647117e-02, 1.65607142e+00, 1.88808437e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.16294098, 13.33237743, 2.60792208]), + 'camera_rotation': array([-7.00393534, 2.01602888, 0.46824393]), + 'current_gear_input': False, + 'focus_actor_dist': 1464.87451171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -633.9029541 , -2071.86181641, 17.4604187 ]), + 'frame': 12631, + 'frame_number': 12631, + 'framesequence': 48549, + 'gaze_dir': array([0.95681 , 0.28846741, 0.03520966]), + 'gaze_origin': array([-3.07948709, -0.25303498, 0.04238663]), + 'gaze_valid': True, + 'gaze_vergence': 505.7835693359375, + 'handbrake_input': False, + 'left_eye_openness': 0.972164511680603, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95507812, 0.29417419, 0.03555298]), + 'left_gaze_origin': array([-2.97866368, 2.93728042, 0.03951263]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1597442626953125, + 'left_pupil_posn': array([ 0.3013531 , -0.07506108]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9331433773040771, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95854187, 0.28276062, 0.03486633]), + 'right_gaze_origin': array([-3.18031025, -3.44335032, 0.04526062]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1334228515625, + 'right_pupil_posn': array([ 0.27900243, -0.15197647]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.3015911653638, + 'timestamp_carla': 415302, + 'timestamp_device': 4153514, + 'timestamp_stream': 415.3015911653638, + 'transform': [array([-4.30681139e-01, -2.11178360e+01, 9.67536867e-03]), + array([-0.0608843 , 2.43660927, 0.01095582])]} +{'AngularVelocity': array([ 1.35794999e-02, 3.25957639e-03, -8.54403400e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.265382766723633, + 'FR_Wheel_Angle': -15.074455261230469, + 'Location': array([ -2.6090436 , -24.75429344, 0.17214298]), + 'Rotation': array([ 1.02452832e-04, 9.63302765e+01, -3.92150842e-02]), + 'Velocity': array([8.09281394e-02, 1.72551405e+00, 3.63121013e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.14561939, 13.32917213, 2.59941697]), + 'camera_rotation': array([-7.07544041, 1.9861877 , 0.48787612]), + 'current_gear_input': False, + 'focus_actor_dist': 1425.361083984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -618.94274902, -2107.7421875 , 17.45819855]), + 'frame': 12632, + 'frame_number': 12632, + 'framesequence': 48554, + 'gaze_dir': array([0.95674133, 0.28871918, 0.03500366]), + 'gaze_origin': array([-3.07922673, -0.25379717, 0.04262009]), + 'gaze_valid': True, + 'gaze_vergence': 414.45184326171875, + 'handbrake_input': False, + 'left_eye_openness': 0.9783474206924438, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95497131, 0.29425049, 0.03790283]), + 'left_gaze_origin': array([-2.97805023, 2.93728042, 0.04054413]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.19097900390625, + 'left_pupil_posn': array([ 0.30144048, -0.07527065]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9379814267158508, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.95851135, 0.28318787, 0.03210449]), + 'right_gaze_origin': array([-3.18040323, -3.44487476, 0.04469605]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.12408447265625, + 'right_pupil_posn': array([ 0.28011501, -0.15155947]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.33550196513534, + 'timestamp_carla': 415335, + 'timestamp_device': 4153555, + 'timestamp_stream': 415.33550196513534, + 'transform': [array([-4.31067944e-01, -2.11093998e+01, 9.69100930e-03]), + array([-0.0608843 , 2.43675637, 0.01092531])]} +{'AngularVelocity': array([ 5.53291757e-03, -1.70211643e-02, -1.08917131e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.405460357666016, + 'FR_Wheel_Angle': -16.680227279663086, + 'Location': array([ -2.59030461, -24.33232689, 0.17215534]), + 'Rotation': array([ 4.50792443e-03, 9.39043579e+01, -3.65600586e-02]), + 'Velocity': array([2.05944493e-01, 1.91658950e+00, 8.94546520e-06]), + 'brake_input': 0.0, + 'camera_location': array([-5.13270569, 13.35607529, 2.58498931]), + 'camera_rotation': array([-7.16940308, 1.95099795, 0.58442026]), + 'current_gear_input': False, + 'focus_actor_dist': 1400.6263427734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -609.67834473, -2129.82983398, 17.44571686]), + 'frame': 12633, + 'frame_number': 12633, + 'framesequence': 48556, + 'gaze_dir': array([0.95907593, 0.27962494, 0.04175568]), + 'gaze_origin': array([-3.0768342 , -0.24141464, 0.04480744]), + 'gaze_valid': True, + 'gaze_vergence': 201.29083251953125, + 'handbrake_input': False, + 'left_eye_openness': 0.9706718325614929, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.95495605, 0.29399109, 0.04020691]), + 'left_gaze_origin': array([-2.97466302, 2.95150328, 0.04190827]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1865234375, + 'left_pupil_posn': array([ 0.2853061 , -0.06961286]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9414724707603455, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9631958 , 0.26525879, 0.04330444]), + 'right_gaze_origin': array([-3.17900562, -3.43433237, 0.04770661]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1033172607421875, + 'right_pupil_posn': array([ 0.27260089, -0.14844179]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.3573987670243, + 'timestamp_carla': 415357, + 'timestamp_device': 4153572, + 'timestamp_stream': 415.3573987670243, + 'transform': [array([-4.31349009e-01, -2.11040115e+01, 9.71807446e-03]), + array([-0.0608843 , 2.43700552, 0.01092531])]} +{'AngularVelocity': array([-6.13369234e-02, -1.03493854e-02, -1.37357702e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.65296745300293, + 'FR_Wheel_Angle': -19.80534553527832, + 'Location': array([ -2.55122375, -23.96635437, 0.17222255]), + 'Rotation': array([-1.28407544e-03, 9.14912567e+01, -3.17382850e-02]), + 'Velocity': array([ 3.53574663e-01, 1.91510725e+00, -9.88245010e-05]), + 'brake_input': 0.0, + 'camera_location': array([-5.13289261, 13.35608482, 2.58498931]), + 'camera_rotation': array([-7.16940308, 1.95099795, 0.58442026]), + 'current_gear_input': False, + 'focus_actor_dist': 1477.3143310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -623.8213501 , -2051.94287109, 17.44348907]), + 'frame': 12634, + 'frame_number': 12634, + 'framesequence': 48561, + 'gaze_dir': array([0.98105621, 0.15816498, 0.1111908 ]), + 'gaze_origin': array([-3.00842142, -0.14370652, 0.07434006]), + 'gaze_valid': True, + 'gaze_vergence': 273.6488037109375, + 'handbrake_input': False, + 'left_eye_openness': 0.9953559637069702, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97924805, 0.16950989, 0.11105347]), + 'left_gaze_origin': array([-2.9693377 , 3.04713917, 0.09071656]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.13494873046875, + 'left_pupil_posn': array([ 0.17969942, -0.01022112]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 0.9842880964279175, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98286438, 0.14682007, 0.11132812]), + 'right_gaze_origin': array([-3.04750538, -3.33455205, 0.05796357]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1328277587890625, + 'right_pupil_posn': array([ 0.15606129, -0.08929992]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.39808616787195, + 'timestamp_carla': 415398, + 'timestamp_device': 4153614, + 'timestamp_stream': 415.39808616787195, + 'transform': [array([-4.31761920e-01, -2.10941448e+01, 9.72093549e-03]), + array([-0.0608843 , 2.43700552, 0.01092531])]} +{'AngularVelocity': array([ -0.04227881, 0.03271256, -14.84880447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.041269302368164, + 'FR_Wheel_Angle': -21.981658935546875, + 'Location': array([ -2.48288059, -23.60002327, 0.17223488]), + 'Rotation': array([-1.28817363e-02, 8.85849228e+01, -3.38439941e-02]), + 'Velocity': array([ 4.81645465e-01, 1.74042785e+00, -5.35912521e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.13630867, 13.37339783, 2.57834768]), + 'camera_rotation': array([-7.26822948, 1.99543452, 0.57466561]), + 'current_gear_input': False, + 'focus_actor_dist': 4659.05517578125, + 'focus_actor_name': 'BP_RepSpline116', + 'focus_actor_pt': array([-1195.14282227, 1100.19458008, 73.20150757]), + 'frame': 12635, + 'frame_number': 12635, + 'framesequence': 48564, + 'gaze_dir': array([0.98119354, 0.16299438, 0.10329437]), + 'gaze_origin': array([-3.03309655, -0.1457985 , 0.07917023]), + 'gaze_valid': True, + 'gaze_vergence': 1127.0614013671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98091125, 0.1653595 , 0.10229492]), + 'left_gaze_origin': array([-2.95536661, 3.04752827, 0.0824936 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2060546875, + 'left_pupil_posn': array([ 0.18399918, -0.01584101]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98147583, 0.16062927, 0.10429382]), + 'right_gaze_origin': array([-3.11082625, -3.33912516, 0.07584687]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.114471435546875, + 'right_pupil_posn': array([ 0.15957797, -0.09139109]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.4264693669975, + 'timestamp_carla': 415426, + 'timestamp_device': 4153639, + 'timestamp_stream': 415.4264693669975, + 'transform': [array([-4.32212979e-01, -2.10873508e+01, 9.69148614e-03]), + array([-0.0608843 , 2.43774319, 0.01089479])]} +{'AngularVelocity': array([ -0.04920947, 0.05560254, -15.71608639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.47004508972168, + 'FR_Wheel_Angle': -24.041227340698242, + 'Location': array([ -2.40470076, -23.30541229, 0.17220984]), + 'Rotation': array([-1.87420379e-02, 8.58876801e+01, -3.77807617e-02]), + 'Velocity': array([ 5.61414540e-01, 1.55375254e+00, -4.17327858e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.11398792, 13.38876629, 2.60922241]), + 'camera_rotation': array([-7.1780777 , 2.05550766, 0.58424127]), + 'current_gear_input': False, + 'focus_actor_dist': 1578.9420166015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -481.81079102, -1895.23522949, 100.32334137]), + 'frame': 12636, + 'frame_number': 12636, + 'framesequence': 48568, + 'gaze_dir': array([0.98184967, 0.15825653, 0.10383606]), + 'gaze_origin': array([-3.04627538, -0.14648591, 0.08206178]), + 'gaze_valid': True, + 'gaze_vergence': 250.3486328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98072815, 0.16847229, 0.09890747]), + 'left_gaze_origin': array([-2.96702886, 3.04712844, 0.08452912]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1574554443359375, + 'left_pupil_posn': array([ 0.18008697, -0.01482821]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98297119, 0.14804077, 0.10876465]), + 'right_gaze_origin': array([-3.1255219 , -3.34010005, 0.07959443]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1110687255859375, + 'right_pupil_posn': array([ 0.16174424, -0.09273195]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.4563953652978, + 'timestamp_carla': 415456, + 'timestamp_device': 4153672, + 'timestamp_stream': 415.4563953652978, + 'transform': [array([-4.31526333e-01, -2.10803585e+01, 9.65158455e-03]), + array([-0.0608843 , 2.43339872, 0.01089479])]} +{'AngularVelocity': array([ 3.19225900e-02, -6.47617271e-03, -1.51406422e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.19934844970703, + 'FR_Wheel_Angle': -25.136741638183594, + 'Location': array([ -2.30336905, -23.00749016, 0.17215027]), + 'Rotation': array([-2.07227934e-02, 8.27685089e+01, -4.27551307e-02]), + 'Velocity': array([ 6.31677091e-01, 1.42985392e+00, -2.33283034e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.10128117, 13.38926792, 2.60743904]), + 'camera_rotation': array([-7.16951275, 2.09909034, 0.62382931]), + 'current_gear_input': False, + 'focus_actor_dist': 1602.629638671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -481.76184082, -1870.06994629, 103.04123688]), + 'frame': 12637, + 'frame_number': 12637, + 'framesequence': 48572, + 'gaze_dir': array([0.98174286, 0.15810394, 0.10506439]), + 'gaze_origin': array([-3.04363179, -0.14687195, 0.081633 ]), + 'gaze_valid': True, + 'gaze_vergence': 266.3561706542969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98036194, 0.16886902, 0.10177612]), + 'left_gaze_origin': array([-2.96174169, 3.04752064, 0.0835495 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15765380859375, + 'left_pupil_posn': array([ 0.17953229, -0.01463389]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98312378, 0.14733887, 0.10835266]), + 'right_gaze_origin': array([-3.1255219 , -3.34126472, 0.0797165 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.152069091796875, + 'right_pupil_posn': array([ 0.16267598, -0.09178329]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0, + 'timestamp': 415.4887599684298, + 'timestamp_carla': 415489, + 'timestamp_device': 4153705, + 'timestamp_stream': 415.4887599684298, + 'transform': [array([-4.32122946e-01, -2.10727921e+01, 9.69444215e-03]), + array([-0.0608843 , 2.43465519, 0.01086427])]} +{'AngularVelocity': array([-1.22639872e-02, 1.80303399e-02, -1.60901127e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.00151062011719, + 'FR_Wheel_Angle': -25.485244750976562, + 'Location': array([ -2.18733573, -22.72809029, 0.17202778]), + 'Rotation': array([-1.90084148e-02, 7.96369858e+01, -4.31213416e-02]), + 'Velocity': array([ 7.06153870e-01, 1.34650648e+00, -5.97920385e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.10234261, 13.40323734, 2.57292652]), + 'camera_rotation': array([-7.31134844, 2.14906693, 0.61433047]), + 'current_gear_input': False, + 'focus_actor_dist': 1610.7877197265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -484.68322754, -1861.61657715, 104.91057587]), + 'frame': 12638, + 'frame_number': 12638, + 'framesequence': 48576, + 'gaze_dir': array([0.98181915, 0.15759277, 0.10515594]), + 'gaze_origin': array([-3.04213357, -0.14664307, 0.08195038]), + 'gaze_valid': True, + 'gaze_vergence': 265.90435791015625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98042297, 0.16844177, 0.10195923]), + 'left_gaze_origin': array([-2.9601748 , 3.04827142, 0.08418427]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15606689453125, + 'left_pupil_posn': array([ 0.17880738, -0.01391697]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98321533, 0.14674377, 0.10835266]), + 'right_gaze_origin': array([-3.12409234, -3.3415575 , 0.0797165 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1585693359375, + 'right_pupil_posn': array([ 0.16267598, -0.09147263]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.01190203707665205, + 'timestamp': 415.5213524661958, + 'timestamp_carla': 415521, + 'timestamp_device': 4153739, + 'timestamp_stream': 415.5213524661958, + 'transform': [array([-4.32481974e-01, -2.10652943e+01, 9.72148869e-03]), + array([-0.0608843 , 2.43484998, 0.01083376])]} +{'AngularVelocity': array([ 0.0198435 , -0.03990248, -15.63928127]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.798137664794922, + 'FR_Wheel_Angle': -24.688980102539062, + 'Location': array([ -2.05384684, -22.45063972, 0.17187847]), + 'Rotation': array([-1.68159250e-02, 7.64824066e+01, -4.06494141e-02]), + 'Velocity': array([ 8.14189970e-01, 1.40626216e+00, -4.68263606e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.09287643, 13.39478302, 2.5561552 ]), + 'camera_rotation': array([-7.40689564, 2.15413165, 0.59538525]), + 'current_gear_input': False, + 'focus_actor_dist': 1592.4224853515625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -480.93069458, -1878.91491699, 101.54486084]), + 'frame': 12639, + 'frame_number': 12639, + 'framesequence': 48580, + 'gaze_dir': array([0.98161316, 0.15831757, 0.1060257 ]), + 'gaze_origin': array([-3.04084802, -0.14595948, 0.08272324]), + 'gaze_valid': True, + 'gaze_vergence': 290.486572265625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98025513, 0.16844177, 0.10345459]), + 'left_gaze_origin': array([-2.95945764, 3.04969954, 0.08572999]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.137969970703125, + 'left_pupil_posn': array([ 0.17833865, -0.01268554]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98297119, 0.14819336, 0.1085968 ]), + 'right_gaze_origin': array([-3.12223816, -3.34161854, 0.0797165 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1612548828125, + 'right_pupil_posn': array([ 0.16267598, -0.09063137]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.035706110298633575, + 'timestamp': 415.55581786856055, + 'timestamp_carla': 415556, + 'timestamp_device': 4153772, + 'timestamp_stream': 415.55581786856055, + 'transform': [array([-4.31225270e-01, -2.10580463e+01, 9.60706733e-03]), + array([-0.0609731 , 2.42782021, 0.01132203])]} +{'AngularVelocity': array([ -0.03418269, -0.03181365, -17.15676117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.27991485595703, + 'FR_Wheel_Angle': -24.39405059814453, + 'Location': array([ -1.89591575, -22.15818024, 0.17169315]), + 'Rotation': array([-1.70003399e-02, 7.32094803e+01, -3.35693322e-02]), + 'Velocity': array([ 9.51875746e-01, 1.46538281e+00, -7.82313349e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.05852318, 13.38496399, 2.55569577]), + 'camera_rotation': array([-7.43389559, 2.11759901, 0.54475588]), + 'current_gear_input': False, + 'focus_actor_dist': 1586.6336669921875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -480.81414795, -1884.10351562, 100.53694153]), + 'frame': 12640, + 'frame_number': 12640, + 'framesequence': 48584, + 'gaze_dir': array([0.98160553, 0.15875244, 0.10549164]), + 'gaze_origin': array([-3.03435445, -0.14593278, 0.08304215]), + 'gaze_valid': True, + 'gaze_vergence': 299.1185607910156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98008728, 0.16900635, 0.10417175]), + 'left_gaze_origin': array([-2.95773482, 3.05045629, 0.086969 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.167144775390625, + 'left_pupil_posn': array([ 0.17790127, -0.01219177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98312378, 0.14849854, 0.10681152]), + 'right_gaze_origin': array([-3.11097431, -3.34232187, 0.0791153 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1663665771484375, + 'right_pupil_posn': array([ 0.1630429 , -0.08875167]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.043656062334775925, + 'timestamp': 415.5897385664284, + 'timestamp_carla': 415590, + 'timestamp_device': 4153805, + 'timestamp_stream': 415.5897385664284, + 'transform': [array([-4.32513267e-01, -2.10511055e+01, 9.52983834e-03]), + array([-0.0608843 , 2.43223333, 0.01168824])]} +{'AngularVelocity': array([ -0.01892312, -0.04143416, -17.9918232 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.751739501953125, + 'FR_Wheel_Angle': -24.076547622680664, + 'Location': array([ -1.70536208, -21.84712029, 0.17148297]), + 'Rotation': array([-1.95616614e-02, 6.96998672e+01, -2.57263184e-02]), + 'Velocity': array([ 1.15002048e+00, 1.57843578e+00, -9.73029120e-04]), + 'brake_input': 0.0, + 'camera_location': array([-5.02916622, 13.37955093, 2.56555367]), + 'camera_rotation': array([-7.4180975 , 2.08286047, 0.50728929]), + 'current_gear_input': False, + 'focus_actor_dist': 1584.7174072265625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -479.74151611, -1885.0645752 , 99.20811462]), + 'frame': 12641, + 'frame_number': 12641, + 'framesequence': 48588, + 'gaze_dir': array([0.98139191, 0.15821075, 0.10823822]), + 'gaze_origin': array([-3.03360009, -0.14631806, 0.08275071]), + 'gaze_valid': True, + 'gaze_vergence': 304.41754150390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98008728, 0.16790771, 0.10583496]), + 'left_gaze_origin': array([-2.95695043, 3.05045629, 0.086969 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.187255859375, + 'left_pupil_posn': array([ 0.17790127, -0.01079571]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98269653, 0.14851379, 0.11064148]), + 'right_gaze_origin': array([-3.11024952, -3.34309268, 0.07853241]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1654510498046875, + 'right_pupil_posn': array([ 0.16317296, -0.0884366 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.043656062334775925, + 'timestamp': 415.62197226658463, + 'timestamp_carla': 415622, + 'timestamp_device': 4153839, + 'timestamp_stream': 415.62197226658463, + 'transform': [array([-4.33000326e-01, -2.10450096e+01, 9.44019295e-03]), + array([-0.0608843 , 2.43324399, 0.01214601])]} +{'AngularVelocity': array([ -0.03105106, -0.02648148, -19.3398838 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.326860427856445, + 'FR_Wheel_Angle': -23.789520263671875, + 'Location': array([ -1.50144053, -21.55275345, 0.17124836]), + 'Rotation': array([-2.42881514e-02, 6.63137817e+01, -1.95312444e-02]), + 'Velocity': array([ 1.3432591 , 1.64522839, -0.00170064]), + 'brake_input': 0.0, + 'camera_location': array([-5.00958538, 13.36952972, 2.55551839]), + 'camera_rotation': array([-7.47480154, 2.03540969, 0.48272231]), + 'current_gear_input': False, + 'focus_actor_dist': 1608.160888671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -483.58496094, -1861.03625488, 103.68078613]), + 'frame': 12642, + 'frame_number': 12642, + 'framesequence': 48592, + 'gaze_dir': array([0.98134613, 0.15800476, 0.10894775]), + 'gaze_origin': array([-3.0312891 , -0.14681701, 0.08156586]), + 'gaze_valid': True, + 'gaze_vergence': 296.65185546875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98023987, 0.16729736, 0.10545349]), + 'left_gaze_origin': array([-2.95358443, 3.05025029, 0.08518372]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.188720703125, + 'left_pupil_posn': array([ 0.17808044, -0.01079571]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98245239, 0.14871216, 0.11244202]), + 'right_gaze_origin': array([-3.10899377, -3.34388423, 0.077948 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1817474365234375, + 'right_pupil_posn': array([ 0.16344571, -0.08875167]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.043656062334775925, + 'timestamp': 415.6553641669452, + 'timestamp_carla': 415655, + 'timestamp_device': 4153872, + 'timestamp_stream': 415.6553641669452, + 'transform': [array([-4.33284134e-01, -2.10391693e+01, 9.34158266e-03]), + array([-0.06094578, 2.43334985, 0.01257325])]} +{'AngularVelocity': array([-5.44475764e-02, 1.92267969e-02, -2.11647415e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.038442611694336, + 'FR_Wheel_Angle': -23.643800735473633, + 'Location': array([ -1.23406756, -21.21310425, 0.17098072]), + 'Rotation': array([-3.23477760e-02, 6.22892189e+01, -1.42211886e-02]), + 'Velocity': array([ 1.54694474, 1.65572226, -0.00178667]), + 'brake_input': 0.0, + 'camera_location': array([-4.97512722, 13.3578701 , 2.53658128]), + 'camera_rotation': array([-7.58141375, 1.9927516 , 0.4720042 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1616.3480224609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -483.87518311, -1852.05456543, 103.16945648]), + 'frame': 12643, + 'frame_number': 12643, + 'framesequence': 48596, + 'gaze_dir': array([0.9811554 , 0.15885925, 0.10934448]), + 'gaze_origin': array([-3.03031778, -0.1472275 , 0.08126298]), + 'gaze_valid': True, + 'gaze_vergence': 282.1224670410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9797821 , 0.16925049, 0.10661316]), + 'left_gaze_origin': array([-2.95194101, 3.04985213, 0.08518372]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1853179931640625, + 'left_pupil_posn': array([ 0.17824721, -0.01061821]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98252869, 0.14846802, 0.11207581]), + 'right_gaze_origin': array([-3.10869455, -3.34430718, 0.07734223]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.186492919921875, + 'right_pupil_posn': array([ 0.16441393, -0.08875167]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0476234070956707, + 'timestamp': 415.6887583658099, + 'timestamp_carla': 415689, + 'timestamp_device': 4153905, + 'timestamp_stream': 415.6887583658099, + 'transform': [array([-4.34555799e-01, -2.10331631e+01, 9.39674396e-03]), + array([-0.0608843 , 2.43785167, 0.01232912])]} +{'AngularVelocity': array([-5.52303344e-02, 1.38538759e-02, -2.04812031e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.93758773803711, + 'FR_Wheel_Angle': -23.55802345275879, + 'Location': array([ -0.96957546, -20.91862297, 0.17065753]), + 'Rotation': array([-4.25725654e-02, 5.86309280e+01, -1.25427246e-02]), + 'Velocity': array([ 1.68223596, 1.58930123, -0.00221736]), + 'brake_input': 0.0, + 'camera_location': array([-4.95457935, 13.33946037, 2.51489687]), + 'camera_rotation': array([-7.66692781, 1.97141874, 0.42898318]), + 'current_gear_input': False, + 'focus_actor_dist': 1604.7227783203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -481.32278442, -1862.81921387, 101.14776611]), + 'frame': 12644, + 'frame_number': 12644, + 'framesequence': 48600, + 'gaze_dir': array([0.98104858, 0.16002655, 0.10862732]), + 'gaze_origin': array([-3.02740479, -0.14762956, 0.0807251 ]), + 'gaze_valid': True, + 'gaze_vergence': 261.15472412109375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97999573, 0.16975403, 0.10383606]), + 'left_gaze_origin': array([-2.95179605, 3.04962015, 0.08518372]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1864013671875, + 'left_pupil_posn': array([ 0.17903471, -0.01016688]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98210144, 0.15029907, 0.11341858]), + 'right_gaze_origin': array([-3.10301375, -3.34487939, 0.07626648]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.191619873046875, + 'right_pupil_posn': array([ 0.16479266, -0.08942473]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.05555810034275055, + 'timestamp': 415.7224009670317, + 'timestamp_carla': 415722, + 'timestamp_device': 4153939, + 'timestamp_stream': 415.7224009670317, + 'transform': [array([-4.34625089e-01, -2.10274506e+01, 9.40669980e-03]), + array([-0.06091162, 2.43701148, 0.01226808])]} +{'AngularVelocity': array([-3.64654809e-02, -2.10838951e-02, -2.12017078e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.307199478149414, + 'FR_Wheel_Angle': -23.050193786621094, + 'Location': array([ -0.56234199, -20.52796555, 0.17031406]), + 'Rotation': array([-5.10829836e-02, 5.34564209e+01, -7.59887835e-03]), + 'Velocity': array([ 1.89867508e+00, 1.51114500e+00, -1.30854128e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.9244833 , 13.32744026, 2.48453403]), + 'camera_rotation': array([-7.8119669 , 1.94942868, 0.40934348]), + 'current_gear_input': False, + 'focus_actor_dist': 1587.759033203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -478.56768799, -1879.05969238, 98.24684906]), + 'frame': 12645, + 'frame_number': 12645, + 'framesequence': 48604, + 'gaze_dir': array([0.9810257 , 0.16000366, 0.10888672]), + 'gaze_origin': array([-3.02531767, -0.14814912, 0.08042908]), + 'gaze_valid': True, + 'gaze_vergence': 252.07611083984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98005676, 0.16958618, 0.1035614 ]), + 'left_gaze_origin': array([-2.95250702, 3.04943705, 0.08575745]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.18328857421875, + 'left_pupil_posn': array([ 0.1792202 , -0.00962377]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98199463, 0.15042114, 0.11421204]), + 'right_gaze_origin': array([-3.09812784, -3.34573531, 0.07510071]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1898193359375, + 'right_pupil_posn': array([ 0.16517401, -0.08942473]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.07142747938632965, + 'timestamp': 415.7550659663975, + 'timestamp_carla': 415755, + 'timestamp_device': 4153972, + 'timestamp_stream': 415.7550659663975, + 'transform': [array([-4.34756905e-01, -2.10222549e+01, 9.38487984e-03]), + array([-0.0608843 , 2.43658137, 0.01239015])]} +{'AngularVelocity': array([ -0.03411101, 0.05504613, -20.23075294]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.27663230895996, + 'FR_Wheel_Angle': -21.625776290893555, + 'Location': array([ -0.19249947, -20.22305489, 0.16995597]), + 'Rotation': array([-6.02149442e-02, 4.92414627e+01, -8.48388765e-03]), + 'Velocity': array([ 1.97302973, 1.38101029, -0.00217975]), + 'brake_input': 0.0, + 'camera_location': array([-4.88599873, 13.32115936, 2.47525287]), + 'camera_rotation': array([-7.9206419 , 1.95743477, 0.4202508 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1580.7255859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -476.21679688, -1885.20568848, 94.94546509]), + 'frame': 12646, + 'frame_number': 12646, + 'framesequence': 48608, + 'gaze_dir': array([0.98071289, 0.16078186, 0.11064148]), + 'gaze_origin': array([-3.02535105, -0.1484955 , 0.0805275 ]), + 'gaze_valid': True, + 'gaze_vergence': 322.58489990234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97964478, 0.16941833, 0.10754395]), + 'left_gaze_origin': array([-2.95317698, 3.04935455, 0.08636475]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1810150146484375, + 'left_pupil_posn': array([ 0.17987943, -0.00950861]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98178101, 0.15214539, 0.11373901]), + 'right_gaze_origin': array([-3.09752512, -3.34634566, 0.07469025]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.191314697265625, + 'right_pupil_posn': array([ 0.16553819, -0.08822834]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.0952315554022789, + 'timestamp': 415.7879355661571, + 'timestamp_carla': 415788, + 'timestamp_device': 4154005, + 'timestamp_stream': 415.7879355661571, + 'transform': [array([-4.35232848e-01, -2.10167236e+01, 9.50267725e-03]), + array([-0.0608843 , 2.43758559, 0.01187135])]} +{'AngularVelocity': array([ -0.01762641, 0.03204912, -16.96681976]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.842350006103516, + 'FR_Wheel_Angle': -19.98276710510254, + 'Location': array([ 0.24503438, -19.90591812, 0.16947906]), + 'Rotation': array([-7.22907186e-02, 4.48500710e+01, -1.45263663e-02]), + 'Velocity': array([ 1.88047206, 1.16364384, -0.00203835]), + 'brake_input': 0.0, + 'camera_location': array([-4.8474884 , 13.30709171, 2.46532583]), + 'camera_rotation': array([-8.04480839, 1.92307866, 0.28391284]), + 'current_gear_input': False, + 'focus_actor_dist': 1576.0589599609375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -476.59329224, -1889.53930664, 94.866745 ]), + 'frame': 12647, + 'frame_number': 12647, + 'framesequence': 48612, + 'gaze_dir': array([0.98065186, 0.16079712, 0.11114502]), + 'gaze_origin': array([-3.02466059, -0.14871445, 0.08028107]), + 'gaze_valid': True, + 'gaze_vergence': 323.8101501464844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97944641, 0.16981506, 0.10870361]), + 'left_gaze_origin': array([-2.95402861, 3.04906321, 0.08668366]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.22393798828125, + 'left_pupil_posn': array([ 0.17992556, -0.00958693]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9818573 , 0.15177917, 0.11358643]), + 'right_gaze_origin': array([-3.09529281, -3.34649205, 0.07387848]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1851043701171875, + 'right_pupil_posn': array([ 0.16572464, -0.08796072]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.11903563141822815, + 'timestamp': 415.82248736545444, + 'timestamp_carla': 415822, + 'timestamp_device': 4154039, + 'timestamp_stream': 415.82248736545444, + 'transform': [array([-4.35610026e-01, -2.10113621e+01, 9.48385242e-03]), + array([-0.06085015, 2.43824172, 0.01190187])]} +{'AngularVelocity': array([-1.80163281e-03, 1.45502929e-02, -1.37435055e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.658767700195312, + 'FR_Wheel_Angle': -17.67194366455078, + 'Location': array([ 0.65287632, -19.64133835, 0.16904946]), + 'Rotation': array([-7.71196634e-02, 4.12793427e+01, -1.79443322e-02]), + 'Velocity': array([ 1.75231659, 0.99588394, -0.00189259]), + 'brake_input': 0.0, + 'camera_location': array([-4.8194809 , 13.2955761 , 2.44775486]), + 'camera_rotation': array([-8.14702225, 1.85736144, 0.2141702 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1574.8170166015625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -475.04406738, -1889.90026855, 92.9394455 ]), + 'frame': 12648, + 'frame_number': 12648, + 'framesequence': 48616, + 'gaze_dir': array([0.98027802, 0.16261292, 0.11178589]), + 'gaze_origin': array([-3.02428675, -0.14906389, 0.07996445]), + 'gaze_valid': True, + 'gaze_vergence': 329.26422119140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97901917, 0.17163086, 0.10969543]), + 'left_gaze_origin': array([-2.95525837, 3.04873824, 0.08689881]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2242279052734375, + 'left_pupil_posn': array([ 0.18078375, -0.00958693]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98153687, 0.15359497, 0.11387634]), + 'right_gaze_origin': array([-3.09331536, -3.34686589, 0.0730301 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1856689453125, + 'right_pupil_posn': array([ 0.16656053, -0.08785856]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.13492026925086975, + 'timestamp': 415.85550516843796, + 'timestamp_carla': 415855, + 'timestamp_device': 4154072, + 'timestamp_stream': 415.85550516843796, + 'transform': [array([-4.35918868e-01, -2.10064945e+01, 9.48228780e-03]), + array([-0.06082283, 2.43870258, 0.01193239])]} +{'AngularVelocity': array([-3.63530451e-03, 3.12783592e-03, -1.00295134e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.886049270629883, + 'FR_Wheel_Angle': -14.869638442993164, + 'Location': array([ 1.0901227 , -19.37795639, 0.16855922]), + 'Rotation': array([-7.89501518e-02, 3.80958366e+01, -2.04772912e-02]), + 'Velocity': array([ 1.58983314, 0.86536843, -0.00178492]), + 'brake_input': 0.0, + 'camera_location': array([-4.78772736, 13.28117752, 2.42406917]), + 'camera_rotation': array([-8.26178265, 1.7818253 , 0.11078977]), + 'current_gear_input': False, + 'focus_actor_dist': 1569.73779296875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -474.73083496, -1894.52111816, 91.67811584]), + 'frame': 12649, + 'frame_number': 12649, + 'framesequence': 48620, + 'gaze_dir': array([0.97980499, 0.1656723 , 0.11162567]), + 'gaze_origin': array([-3.03410053, -0.15053864, 0.08588715]), + 'gaze_valid': True, + 'gaze_vergence': 367.4495849609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97918701, 0.17189026, 0.10777283]), + 'left_gaze_origin': array([-2.98151422, 3.04712224, 0.0994339 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2597808837890625, + 'left_pupil_posn': array([ 0.18414855, -0.00557971]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98042297, 0.15945435, 0.11547852]), + 'right_gaze_origin': array([-3.08668685, -3.34819961, 0.07234039]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.187103271484375, + 'right_pupil_posn': array([ 0.16736007, -0.08779764]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.1428549587726593, + 'timestamp': 415.8876130655408, + 'timestamp_carla': 415888, + 'timestamp_device': 4154105, + 'timestamp_stream': 415.8876130655408, + 'transform': [array([-4.36390221e-01, -2.10014591e+01, 9.65446420e-03]), + array([-0.0608843 , 2.43980312, 0.01119996])]} +{'AngularVelocity': array([ 1.14549359e-03, 1.45985279e-02, -5.79392624e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.364925384521484, + 'FR_Wheel_Angle': -11.352629661560059, + 'Location': array([ 1.43270385, -19.17784882, 0.16818878]), + 'Rotation': array([-8.33419636e-02, 3.61259460e+01, -2.40783710e-02]), + 'Velocity': array([ 1.35347557e+00, 7.44967759e-01, -1.34656427e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.75082207, 13.27457619, 2.39947224]), + 'camera_rotation': array([-8.34278202, 1.68649864, 0.12572774]), + 'current_gear_input': False, + 'focus_actor_dist': 1560.712158203125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -475.00506592, -1903.44812012, 89.15225983]), + 'frame': 12650, + 'frame_number': 12650, + 'framesequence': 48624, + 'gaze_dir': array([0.98862457, 0.10411072, 0.10787964]), + 'gaze_origin': array([-3.07157516, -0.10619966, 0.09377671]), + 'gaze_valid': True, + 'gaze_vergence': 284.2509460449219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98724365, 0.11451721, 0.11048889]), + 'left_gaze_origin': array([-3.02478957, 3.09351802, 0.10779725]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.293243408203125, + 'left_pupil_posn': array([ 0.13040316, -0.01050341]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99000549, 0.09370422, 0.10527039]), + 'right_gaze_origin': array([-3.118361 , -3.3059175 , 0.07975616]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1477203369140625, + 'right_pupil_posn': array([ 0.11941159, -0.08644366]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.14682230353355408, + 'timestamp': 415.9213618673384, + 'timestamp_carla': 415921, + 'timestamp_device': 4154139, + 'timestamp_stream': 415.9213618673384, + 'transform': [array([-4.36418742e-01, -2.09964409e+01, 9.67737194e-03]), + array([-0.06078868, 2.43904138, 0.01107789])]} +{'AngularVelocity': array([ 0.05620249, -0.27449575, 0.00050295]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.890382766723633, + 'FR_Wheel_Angle': -7.604364395141602, + 'Location': array([ 1.54415941, -19.11252594, 0.16861537]), + 'Rotation': array([-0.12368789, 35.64980316, -0.06573484]), + 'Velocity': array([-1.57403090e-04, -8.80162552e-05, -1.06652582e-03]), + 'brake_input': 0.0, + 'camera_location': array([-4.72148418, 13.26156044, 2.38446259]), + 'camera_rotation': array([-8.42498302, 1.59448159, 0.17610255]), + 'current_gear_input': False, + 'focus_actor_dist': 3703.119384765625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-753.99401855, 224.92749023, 0. ]), + 'frame': 12651, + 'frame_number': 12651, + 'framesequence': 48628, + 'gaze_dir': array([0.99112701, 0.08907318, 0.09734344]), + 'gaze_origin': array([-3.10401106, -0.09805755, 0.10426255]), + 'gaze_valid': True, + 'gaze_vergence': 168.4147491455078, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98912048, 0.10180664, 0.1060791 ]), + 'left_gaze_origin': array([-3.0860703 , 3.09625721, 0.12762757]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1728668212890625, + 'left_pupil_posn': array([ 0.12292004, -0.01352036]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99313354, 0.07633972, 0.08860779]), + 'right_gaze_origin': array([-3.12195134, -3.29237247, 0.08089752]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.181640625, + 'right_pupil_posn': array([ 0.10579848, -0.08763003]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.14682230353355408, + 'timestamp': 415.95606246590614, + 'timestamp_carla': 415956, + 'timestamp_device': 4154172, + 'timestamp_stream': 415.95606246590614, + 'transform': [array([-4.35853124e-01, -2.09913139e+01, 9.72658116e-03]), + array([-0.06082283, 2.43558478, 0.01080324])]} +{'AngularVelocity': array([ 0.04002664, -0.13621345, 0.00014312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.097836494445801, + 'FR_Wheel_Angle': -3.285067081451416, + 'Location': array([ 1.5444479 , -19.11245918, 0.16839603]), + 'Rotation': array([-0.08123826, 35.64987946, -0.05004882]), + 'Velocity': array([-7.81496055e-05, -5.07642981e-05, -3.20644554e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.70365143, 13.25658417, 2.36303306]), + 'camera_rotation': array([-8.54511929, 1.50168717, 0.24764594]), + 'current_gear_input': False, + 'focus_actor_dist': 2434.06982421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -491.0838623 , -1017.51367188, 17.05233002]), + 'frame': 12652, + 'frame_number': 12652, + 'framesequence': 48632, + 'gaze_dir': array([0.99082947, 0.09122467, 0.09871674]), + 'gaze_origin': array([-3.09389353, -0.09779129, 0.10193634]), + 'gaze_valid': True, + 'gaze_vergence': 207.98912048339844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98912048, 0.10279846, 0.10514832]), + 'left_gaze_origin': array([-3.06790495, 3.09767175, 0.12289735]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.145538330078125, + 'left_pupil_posn': array([ 0.12301195, -0.01217711]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99253845, 0.07965088, 0.09228516]), + 'right_gaze_origin': array([-3.11988235, -3.29325414, 0.08097535]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1443023681640625, + 'right_pupil_posn': array([ 0.10669827, -0.08750927]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.15078964829444885, + 'timestamp': 415.98792906850576, + 'timestamp_carla': 415988, + 'timestamp_device': 4154205, + 'timestamp_stream': 415.98792906850576, + 'transform': [array([-4.37406152e-01, -2.09855957e+01, 9.95996408e-03]), + array([-0.06085015, 2.44138861, 0.00982667])]} +{'AngularVelocity': array([ 8.85466486e-03, -3.47659886e-02, 1.36520403e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5228681564331055, + 'FR_Wheel_Angle': 0.5345010161399841, + 'Location': array([ 1.54456103, -19.11242485, 0.16828941]), + 'Rotation': array([-0.06466823, 35.64989471, -0.04403687]), + 'Velocity': array([-1.70713192e-05, -1.36150375e-05, 3.04119494e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.67739487, 13.25590324, 2.36523199]), + 'camera_rotation': array([-8.51744366, 1.45778537, 0.26950943]), + 'current_gear_input': False, + 'focus_actor_dist': 2396.099609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -486.49630737, -1054.73706055, 16.99758911]), + 'frame': 12653, + 'frame_number': 12653, + 'framesequence': 48636, + 'gaze_dir': array([0.99073029, 0.09120178, 0.09980011]), + 'gaze_origin': array([-3.09487534, -0.0980095 , 0.10168152]), + 'gaze_valid': True, + 'gaze_vergence': 217.58961486816406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98910522, 0.10183716, 0.10618591]), + 'left_gaze_origin': array([-3.06267571, 3.09810352, 0.12091218]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.147308349609375, + 'left_pupil_posn': array([ 0.12301195, -0.01217711]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99235535, 0.08056641, 0.09341431]), + 'right_gaze_origin': array([-3.12707543, -3.2941227 , 0.08245087]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1620330810546875, + 'right_pupil_posn': array([ 0.107131 , -0.08750927]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.1587243527173996, + 'timestamp': 416.02139166742563, + 'timestamp_carla': 416021, + 'timestamp_device': 4154239, + 'timestamp_stream': 416.02139166742563, + 'transform': [array([-4.37782586e-01, -2.09791546e+01, 1.01934429e-02]), + array([-0.06100725, 2.44169664, 0.00875855])]} +{'AngularVelocity': array([ 1.77680317e-03, -8.84423684e-03, 1.12460075e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06532929837703705, + 'FR_Wheel_Angle': 0.02948087826371193, + 'Location': array([ 1.54459012, -19.11241722, 0.16826217]), + 'Rotation': array([-0.06057011, 35.64987564, -0.04238892]), + 'Velocity': array([-2.73450269e-06, -3.40574638e-06, -8.37502303e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.653862 , 13.2549324 , 2.36217594]), + 'camera_rotation': array([-8.49863338, 1.39797986, 0.31268051]), + 'current_gear_input': False, + 'focus_actor_dist': 2496.67578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-501.01037598, -954.54394531, 15.829422 ]), + 'frame': 12654, + 'frame_number': 12654, + 'framesequence': 48640, + 'gaze_dir': array([0.99053192, 0.0921402 , 0.10098267]), + 'gaze_origin': array([-3.09475875, -0.09834518, 0.10146027]), + 'gaze_valid': True, + 'gaze_vergence': 243.78485107421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98904419, 0.1035614 , 0.10513306]), + 'left_gaze_origin': array([-3.06158781, 3.09816146, 0.11976624]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.16729736328125, + 'left_pupil_posn': array([ 0.12301195, -0.0116657 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99201965, 0.08071899, 0.09683228]), + 'right_gaze_origin': array([-3.12792993, -3.29485202, 0.0831543 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.177276611328125, + 'right_pupil_posn': array([ 0.10824537, -0.08758664]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.1745937317609787, + 'timestamp': 416.0560008659959, + 'timestamp_carla': 416056, + 'timestamp_device': 4154272, + 'timestamp_stream': 416.0560008659959, + 'transform': [array([-4.38080907e-01, -2.09714108e+01, 1.05430605e-02]), + array([-0.0608843 , 2.44150972, 0.00717164])]} +{'AngularVelocity': array([ 3.07802227e-04, -2.23815371e-03, 1.19251081e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0640491247177124, + 'FR_Wheel_Angle': 0.0640888661146164, + 'Location': array([ 1.54459727, -19.11241722, 0.1682698 ]), + 'Rotation': array([-0.05983928, 35.64987564, -0.04205322]), + 'Velocity': array([ 9.33851084e-07, -8.06845492e-07, 1.21638795e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.62875366, 13.25297737, 2.35309148]), + 'camera_rotation': array([-8.52007961, 1.38117683, 0.33576146]), + 'current_gear_input': False, + 'focus_actor_dist': 2589.994384765625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-515.86889648, -861.67260742, 15.10836792]), + 'frame': 12655, + 'frame_number': 12655, + 'framesequence': 48644, + 'gaze_dir': array([0.99043274, 0.09341431, 0.10088348]), + 'gaze_origin': array([-3.09394622, -0.09852067, 0.10128327]), + 'gaze_valid': True, + 'gaze_vergence': 253.73277282714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98898315, 0.10388184, 0.10539246]), + 'left_gaze_origin': array([-3.05928516, 3.0982728 , 0.11929932]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.149688720703125, + 'left_pupil_posn': array([ 0.12370443, -0.01165009]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99188232, 0.08294678, 0.09637451]), + 'right_gaze_origin': array([-3.12860727, -3.29531431, 0.08326722]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1774749755859375, + 'right_pupil_posn': array([ 0.10868669, -0.08756137]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.18649576604366302, + 'timestamp': 416.0884334668517, + 'timestamp_carla': 416088, + 'timestamp_device': 4154305, + 'timestamp_stream': 416.0884334668517, + 'transform': [array([-4.37880397e-01, -2.09637108e+01, 1.07384771e-02]), + array([-0.06091162, 2.43911219, 0.00634766])]} +{'AngularVelocity': array([-4.64945915e-05, -6.43533131e-04, 1.32749701e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07812928408384323, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.54459918, -19.11241722, 0.16824466]), + 'Rotation': array([-0.05983928, 35.64987564, -0.04205322]), + 'Velocity': array([ 2.01776152e-06, -7.41728599e-08, 3.42864078e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.5994072 , 13.25405312, 2.35179496]), + 'camera_rotation': array([-8.51383686, 1.35326159, 0.3655774 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2565.363037109375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-514.57019043, -885.64233398, 15.04801941]), + 'frame': 12656, + 'frame_number': 12656, + 'framesequence': 48648, + 'gaze_dir': array([0.99035645, 0.09368134, 0.10140228]), + 'gaze_origin': array([-3.09298563, -0.09890137, 0.10082933]), + 'gaze_valid': True, + 'gaze_vergence': 253.49392700195312, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98890686, 0.10386658, 0.10617065]), + 'left_gaze_origin': array([-3.05639362, 3.0982728 , 0.11835938]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.189239501953125, + 'left_pupil_posn': array([ 0.12386823, -0.0117501 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99180603, 0.08349609, 0.09663391]), + 'right_gaze_origin': array([-3.12957764, -3.29607582, 0.08329926]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1807403564453125, + 'right_pupil_posn': array([ 0.10922468, -0.08746397]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.20236514508724213, + 'timestamp': 416.12227756530046, + 'timestamp_carla': 416122, + 'timestamp_device': 4154339, + 'timestamp_stream': 416.12227756530046, + 'transform': [array([-4.38371718e-01, -2.09548378e+01, 1.09259123e-02]), + array([-0.06094578, 2.43951201, 0.00549317])]} +{'AngularVelocity': array([ 7.17559960e-05, -1.19870470e-04, 3.33286448e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.54459941, -19.11241722, 0.16819549]), + 'Rotation': array([-0.05983928, 35.64987564, -0.04205322]), + 'Velocity': array([ 1.16345473e-06, -4.77267861e-07, -8.98577389e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.55716705, 13.26164627, 2.32981873]), + 'camera_rotation': array([-8.62168598, 1.34700787, 0.36872348]), + 'current_gear_input': False, + 'focus_actor_dist': 2596.290771484375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-519.03961182, -854.18994141, 15.12740326]), + 'frame': 12657, + 'frame_number': 12657, + 'framesequence': 48652, + 'gaze_dir': array([0.99033356, 0.09303284, 0.10218811]), + 'gaze_origin': array([-3.09238315, -0.09935837, 0.10061951]), + 'gaze_valid': True, + 'gaze_vergence': 263.7043762207031, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98893738, 0.10308838, 0.10653687]), + 'left_gaze_origin': array([-3.05452299, 3.09801054, 0.11772613]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1580657958984375, + 'left_pupil_posn': array([ 0.12386823, -0.01138151]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99172974, 0.08297729, 0.09783936]), + 'right_gaze_origin': array([-3.13024306, -3.29672742, 0.08351288]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1808624267578125, + 'right_pupil_posn': array([ 0.10941911, -0.08731723]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.21824978291988373, + 'timestamp': 416.1554163657129, + 'timestamp_carla': 416155, + 'timestamp_device': 4154372, + 'timestamp_stream': 416.1554163657129, + 'transform': [array([-4.37408119e-01, -2.09450588e+01, 1.12595363e-02]), + array([-0.06091162, 2.43330979, 0.00402832])]} +{'AngularVelocity': array([-4.55572808e-05, -5.50452860e-05, 1.29436539e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.54459953, -19.11241722, 0.16825148]), + 'Rotation': array([-0.05983928, 35.64987564, -0.04205322]), + 'Velocity': array([2.31380113e-06, 1.02769114e-07, 3.72934039e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.54820442, 13.2686758 , 2.31606531]), + 'camera_rotation': array([-8.71124363, 1.34533763, 0.40462682]), + 'current_gear_input': False, + 'focus_actor_dist': 2540.43359375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-508.28646851, -908.16674805, 14.99087524]), + 'frame': 12658, + 'frame_number': 12658, + 'framesequence': 48656, + 'gaze_dir': array([0.99033356, 0.09284973, 0.10237122]), + 'gaze_origin': array([-3.09225178, -0.09949036, 0.10146103]), + 'gaze_valid': True, + 'gaze_vergence': 278.62640380859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98904419, 0.10339355, 0.10522461]), + 'left_gaze_origin': array([-3.05492568, 3.09774637, 0.11788788]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1655426025390625, + 'left_pupil_posn': array([ 0.12382019, -0.01077914]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99162292, 0.08230591, 0.09951782]), + 'right_gaze_origin': array([-3.12957764, -3.29672742, 0.08503418]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.178314208984375, + 'right_pupil_posn': array([ 0.10950947, -0.08660936]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.24205386638641357, + 'timestamp': 416.18766156584024, + 'timestamp_carla': 416188, + 'timestamp_device': 4154405, + 'timestamp_stream': 416.18766156584024, + 'transform': [array([-4.38500673e-01, -2.09351215e+01, 1.13160508e-02]), + array([-0.06091162, 2.43622351, 0.0038147 ])]} +{'AngularVelocity': array([-2.10529361e-05, -1.07892620e-05, 1.20292243e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.54459953, -19.11241722, 0.16825508]), + 'Rotation': array([-0.05983928, 35.64987564, -0.04205322]), + 'Velocity': array([2.17713887e-06, 5.69270924e-08, 1.69506166e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.51873207, 13.2677803 , 2.30454946]), + 'camera_rotation': array([-8.72695255, 1.32530737, 0.42567062]), + 'current_gear_input': False, + 'focus_actor_dist': 2426.62158203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -489.59872437, -1019.47094727, 17.03548431]), + 'frame': 12659, + 'frame_number': 12659, + 'framesequence': 48660, + 'gaze_dir': array([0.990242 , 0.09256744, 0.1034317 ]), + 'gaze_origin': array([-3.09228158, -0.09992752, 0.10202026]), + 'gaze_valid': True, + 'gaze_vergence': 266.7041320800781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98904419, 0.10435486, 0.10430908]), + 'left_gaze_origin': array([-3.05727839, 3.09688735, 0.11871948]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.17083740234375, + 'left_pupil_posn': array([ 0.12389445, -0.00962305]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99143982, 0.08078003, 0.10255432]), + 'right_gaze_origin': array([-3.12728429, -3.29674268, 0.08532105]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.177154541015625, + 'right_pupil_posn': array([ 0.10979509, -0.08632052]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.2737926244735718, + 'timestamp': 416.22155026718974, + 'timestamp_carla': 416222, + 'timestamp_device': 4154439, + 'timestamp_stream': 416.22155026718974, + 'transform': [array([-4.37979430e-01, -2.09237061e+01, 1.14675714e-02]), + array([-0.0608843 , 2.43168736, 0.0031128 ])]} +{'AngularVelocity': array([ 9.93540380e-06, -2.98973318e-05, 9.90698391e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.54459953, -19.11241722, 0.1682463 ]), + 'Rotation': array([-0.05983928, 35.64987564, -0.04205322]), + 'Velocity': array([ 1.93686219e-06, -7.15837771e-08, -9.46304353e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.48535728, 13.27175617, 2.2891829 ]), + 'camera_rotation': array([-8.77384853, 1.28375149, 0.44979599]), + 'current_gear_input': False, + 'focus_actor_dist': 2474.34716796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-495.92388916, -971.08862305, 16.54919434]), + 'frame': 12660, + 'frame_number': 12660, + 'framesequence': 48664, + 'gaze_dir': array([0.99019623, 0.09165192, 0.10440826]), + 'gaze_origin': array([-3.09553862, -0.10064392, 0.10428467]), + 'gaze_valid': True, + 'gaze_vergence': 227.55230712890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98880005, 0.10545349, 0.10554504]), + 'left_gaze_origin': array([-3.06410837, 3.09545445, 0.12233429]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1643829345703125, + 'left_pupil_posn': array([ 0.12389445, -0.00815892]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99159241, 0.07785034, 0.10327148]), + 'right_gaze_origin': array([-3.12696838, -3.29674268, 0.08623505]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1653900146484375, + 'right_pupil_posn': array([ 0.11018646, -0.08521068]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.29364460706710815, + 'timestamp': 416.25334456562996, + 'timestamp_carla': 416253, + 'timestamp_device': 4154472, + 'timestamp_stream': 416.25334456562996, + 'transform': [array([-4.38067466e-01, -2.09114742e+01, 1.17943566e-02]), + array([-6.08843043e-02, 2.42973471e+00, 1.70898868e-03])]} +{'AngularVelocity': array([-0.01763311, 0.02639903, 0.67699254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.42238661646842957, + 'FR_Wheel_Angle': 0.4241235554218292, + 'Location': array([ 1.54469788, -19.11241913, 0.16824634]), + 'Rotation': array([-0.05987344, 35.65747833, -0.04205322]), + 'Velocity': array([-1.26703093e-02, -9.11229756e-03, 7.08961452e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.44962215, 13.27072906, 2.2713201 ]), + 'camera_rotation': array([-8.83215809, 1.24891376, 0.47429156]), + 'current_gear_input': False, + 'focus_actor_dist': 2514.3271484375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-498.17346191, -929.80737305, 14.93565369]), + 'frame': 12661, + 'frame_number': 12661, + 'framesequence': 48668, + 'gaze_dir': array([0.99031067, 0.091362 , 0.10352325]), + 'gaze_origin': array([-3.09730697, -0.10118332, 0.10578004]), + 'gaze_valid': True, + 'gaze_vergence': 226.60986328125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98901367, 0.10533142, 0.10362244]), + 'left_gaze_origin': array([-3.0674088 , 3.09477854, 0.12434083]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1368408203125, + 'left_pupil_posn': array([ 0.12422168, -0.00732243]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99160767, 0.07739258, 0.10342407]), + 'right_gaze_origin': array([-3.1272049 , -3.29714537, 0.08721925]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1599884033203125, + 'right_pupil_posn': array([ 0.1104244 , -0.08521068]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.31348133087158203, + 'timestamp': 416.28770116716623, + 'timestamp_carla': 416288, + 'timestamp_device': 4154505, + 'timestamp_stream': 416.28770116716623, + 'transform': [array([-4.42117155e-01, -2.08969555e+01, 1.20145129e-02]), + array([-6.09116219e-02, 2.44486046e+00, 6.71390968e-04])]} +{'AngularVelocity': array([-0.01828233, 0.02582444, 0.66500711]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3969913423061371, + 'FR_Wheel_Angle': 0.3985472023487091, + 'Location': array([ 1.54462504, -19.11249924, 0.16826469]), + 'Rotation': array([-0.05999638, 35.65670013, -0.04208374]), + 'Velocity': array([-0.0167863 , -0.01208552, 0.00012686]), + 'brake_input': 0.0, + 'camera_location': array([-4.43182087, 13.27387238, 2.25906134]), + 'camera_rotation': array([-8.88571358, 1.23338413, 0.49612272]), + 'current_gear_input': False, + 'focus_actor_dist': 2377.732421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -474.70187378, -1063.18725586, 16.9878006 ]), + 'frame': 12662, + 'frame_number': 12662, + 'framesequence': 48672, + 'gaze_dir': array([0.9899292 , 0.09257507, 0.10604858]), + 'gaze_origin': array([-3.09738779, -0.10136261, 0.10632096]), + 'gaze_valid': True, + 'gaze_vergence': 216.5660400390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98875427, 0.10702515, 0.10440063]), + 'left_gaze_origin': array([-3.0674088 , 3.09464121, 0.12434083]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.12286376953125, + 'left_pupil_posn': array([ 0.12459075, -0.00582719]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99110413, 0.078125 , 0.10769653]), + 'right_gaze_origin': array([-3.12736678, -3.29736662, 0.08830109]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.13909912109375, + 'right_pupil_posn': array([ 0.11117983, -0.0842458 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.3293507397174835, + 'timestamp': 416.3216524682939, + 'timestamp_carla': 416322, + 'timestamp_device': 4154539, + 'timestamp_stream': 416.3216524682939, + 'transform': [array([-4.42297190e-01, -2.08808880e+01, 1.23858452e-02]), + array([-6.08843043e-02, 2.44259000e+00, -9.90370638e-04])]} +{'AngularVelocity': array([-0.01898131, 0.02695791, 0.70819432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.39705130457878113, + 'FR_Wheel_Angle': 0.3909127712249756, + 'Location': array([ 1.54326975, -19.11351204, 0.16825053]), + 'Rotation': array([-0.06011932, 35.65726471, -0.04205322]), + 'Velocity': array([-2.36042142e-02, -1.69322118e-02, -8.13865627e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.41217041, 13.28117561, 2.24454045]), + 'camera_rotation': array([-8.91932487, 1.20388281, 0.4623464 ]), + 'current_gear_input': False, + 'focus_actor_dist': 2455.236328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-489.93988037, -985.57275391, 16.99401093]), + 'frame': 12663, + 'frame_number': 12663, + 'framesequence': 48676, + 'gaze_dir': array([0.98967743, 0.09358978, 0.10723877]), + 'gaze_origin': array([-3.09477329, -0.10138169, 0.10589676]), + 'gaze_valid': True, + 'gaze_vergence': 193.8612518310547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98867798, 0.10887146, 0.10313416]), + 'left_gaze_origin': array([-3.06036544, 3.09469461, 0.12231598]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.113433837890625, + 'left_pupil_posn': array([ 0.12459075, -0.00464177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99067688, 0.07830811, 0.11134338]), + 'right_gaze_origin': array([-3.12918091, -3.29745817, 0.08947755]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1385040283203125, + 'right_pupil_posn': array([ 0.11192691, -0.08422947]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.3333180844783783, + 'timestamp': 416.3546292670071, + 'timestamp_carla': 416355, + 'timestamp_device': 4154572, + 'timestamp_stream': 416.3546292670071, + 'transform': [array([-4.43484634e-01, -2.08631783e+01, 1.28305815e-02]), + array([-0.06091162, 2.44441867, -0.00294381])]} +{'AngularVelocity': array([-0.01905364, 0.02621821, 0.70644826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.18200182914733887, + 'FR_Wheel_Angle': -0.15101441740989685, + 'Location': array([ 1.54027915, -19.11568832, 0.16825764]), + 'Rotation': array([-0.06021494, 35.65846634, -0.04205322]), + 'Velocity': array([-3.08524817e-02, -2.20307875e-02, -4.28199746e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.38492203, 13.27823734, 2.23092198]), + 'camera_rotation': array([-9.04474068, 1.19167483, 0.54802608]), + 'current_gear_input': False, + 'focus_actor_dist': 2532.571044921875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-503.2159729 , -907.74389648, 14.99152374]), + 'frame': 12664, + 'frame_number': 12664, + 'framesequence': 48680, + 'gaze_dir': array([0.98952484, 0.09410095, 0.10829926]), + 'gaze_origin': array([-3.09021544, -0.10143967, 0.10482864]), + 'gaze_valid': True, + 'gaze_vergence': 201.55581665039062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98840332, 0.10926819, 0.10533142]), + 'left_gaze_origin': array([-3.04907393, 3.09520435, 0.11992645]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.076446533203125, + 'left_pupil_posn': array([ 0.12441325, -0.00415087]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99064636, 0.07893372, 0.11126709]), + 'right_gaze_origin': array([-3.13135672, -3.29808378, 0.08973084]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1189117431640625, + 'right_pupil_posn': array([ 0.1125685 , -0.08367479]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.3452201187610626, + 'timestamp': 416.38831286504865, + 'timestamp_carla': 416388, + 'timestamp_device': 4154605, + 'timestamp_stream': 416.38831286504865, + 'transform': [array([-4.43618447e-01, -2.08430653e+01, 1.32303331e-02]), + array([-0.06103457, 2.44100022, -0.00474015])]} +{'AngularVelocity': array([-0.01884146, 0.0250534 , 0.67474306]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.1155468225479126, + 'FR_Wheel_Angle': 1.4967306852340698, + 'Location': array([ 1.5356549 , -19.11904907, 0.1682695 ]), + 'Rotation': array([-0.06024227, 35.6602478 , -0.04190063]), + 'Velocity': array([-0.03745464, -0.02707375, 0.0001223 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.36320305, 13.28850174, 2.21162462]), + 'camera_rotation': array([-9.12662792, 1.20542443, 0.53429306]), + 'current_gear_input': False, + 'focus_actor_dist': 2427.2314453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -487.89102173, -1010.18359375, 17.10269165]), + 'frame': 12665, + 'frame_number': 12665, + 'framesequence': 48684, + 'gaze_dir': array([0.98920441, 0.09428406, 0.11116028]), + 'gaze_origin': array([-3.08771157, -0.10139466, 0.10313874]), + 'gaze_valid': True, + 'gaze_vergence': 208.0679931640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98835754, 0.10824585, 0.10687256]), + 'left_gaze_origin': array([-3.04324508, 3.09596872, 0.11679994]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.057708740234375, + 'left_pupil_posn': array([ 0.12435985, -0.00373876]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99005127, 0.08032227, 0.115448 ]), + 'right_gaze_origin': array([-3.13217783, -3.29875803, 0.08947755]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.104888916015625, + 'right_pupil_posn': array([ 0.11270213, -0.08342981]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.4213370680809, + 'timestamp_carla': 416421, + 'timestamp_device': 4154639, + 'timestamp_stream': 416.4213370680809, + 'transform': [array([-4.45111215e-01, -2.08212032e+01, 1.35686491e-02]), + array([-0.0609731 , 2.44336462, -0.00621547])]} +{'AngularVelocity': array([ 0.01807219, -0.02851652, -0.76213765]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.850045204162598, + 'FR_Wheel_Angle': 5.523260593414307, + 'Location': array([ 1.52834654, -19.12456894, 0.16824047]), + 'Rotation': array([-0.06015347, 35.65130615, -0.04153442]), + 'Velocity': array([-0.01689827, -0.01489378, 0.00034059]), + 'brake_input': 0.0, + 'camera_location': array([-4.35155582, 13.29551697, 2.19102097]), + 'camera_rotation': array([-9.26140118, 1.21144843, 0.47676319]), + 'current_gear_input': False, + 'focus_actor_dist': 2546.636962890625, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-507.78872681, -890.35009766, 15.03561401]), + 'frame': 12666, + 'frame_number': 12666, + 'framesequence': 48688, + 'gaze_dir': array([0.98891449, 0.09460449, 0.11359406]), + 'gaze_origin': array([-3.08458042, -0.10109711, 0.10259629]), + 'gaze_valid': True, + 'gaze_vergence': 228.2384490966797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98806763, 0.10762024, 0.1101532 ]), + 'left_gaze_origin': array([-3.03539753, 3.09658217, 0.11489411]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9917144775390625, + 'left_pupil_posn': array([ 0.12435985, -0.00293958]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98976135, 0.08158875, 0.11703491]), + 'right_gaze_origin': array([-3.13376331, -3.29877615, 0.09029847]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0655059814453125, + 'right_pupil_posn': array([ 0.1125685 , -0.08195531]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.38887616991996765, + 'timestamp': 416.45514626801014, + 'timestamp_carla': 416455, + 'timestamp_device': 4154672, + 'timestamp_stream': 416.45514626801014, + 'transform': [array([-4.45123583e-01, -2.07965698e+01, 1.39586348e-02]), + array([-0.06094578, 2.43859363, -0.00795717])]} +{'AngularVelocity': array([-0.50882226, -0.03691218, -0.82585371]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.682762622833252, + 'FR_Wheel_Angle': 8.684331893920898, + 'Location': array([ 1.50279939, -19.14535141, 0.1682962 ]), + 'Rotation': array([-7.94009417e-02, 3.55822105e+01, -2.37426776e-02]), + 'Velocity': array([-0.29032946, -0.23989262, -0.00415398]), + 'brake_input': 0.0, + 'camera_location': array([-4.34065247, 13.28876019, 2.17442703]), + 'camera_rotation': array([-9.32144547, 1.25675905, 0.45494696]), + 'current_gear_input': False, + 'focus_actor_dist': 2557.837646484375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-510.61444092, -877.23217773, 15.06884003]), + 'frame': 12667, + 'frame_number': 12667, + 'framesequence': 48692, + 'gaze_dir': array([0.98886871, 0.09490967, 0.11365509]), + 'gaze_origin': array([-3.0827415 , -0.10088654, 0.10279617]), + 'gaze_valid': True, + 'gaze_vergence': 227.20968627929688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98786926, 0.10839844, 0.11109924]), + 'left_gaze_origin': array([-3.03096652, 3.0969851 , 0.1147049 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9891204833984375, + 'left_pupil_posn': array([ 0.12401271, -0.00251377]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98986816, 0.0814209 , 0.11621094]), + 'right_gaze_origin': array([-3.13451695, -3.29875803, 0.09088746]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0315704345703125, + 'right_pupil_posn': array([ 0.11285853, -0.08131266]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.40474554896354675, + 'timestamp': 416.4888402670622, + 'timestamp_carla': 416489, + 'timestamp_device': 4154705, + 'timestamp_stream': 416.4888402670622, + 'transform': [array([-4.44384754e-01, -2.07702560e+01, 1.41703216e-02]), + array([-0.06085015, 2.43026304, -0.00888607])]} +{'AngularVelocity': array([ 0.05590736, -0.04022905, -1.28479409]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.552509307861328, + 'FR_Wheel_Angle': 12.251138687133789, + 'Location': array([ 1.43290901, -19.2036953 , 0.16811623]), + 'Rotation': array([-7.61975870e-02, 3.52872314e+01, -1.52587853e-02]), + 'Velocity': array([-0.26149336, -0.23331849, 0.00072514]), + 'brake_input': 0.0, + 'camera_location': array([-4.32690144, 13.29409027, 2.15855026]), + 'camera_rotation': array([-9.38216591, 1.26406586, 0.45984688]), + 'current_gear_input': False, + 'focus_actor_dist': 2511.82421875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-505.81591797, -920.63037109, 14.95935059]), + 'frame': 12668, + 'frame_number': 12668, + 'framesequence': 48696, + 'gaze_dir': array([0.98750305, 0.10062408, 0.12049103]), + 'gaze_origin': array([-3.07611251, -0.1036934 , 0.10128632]), + 'gaze_valid': True, + 'gaze_vergence': 238.3541259765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98661804, 0.11314392, 0.11730957]), + 'left_gaze_origin': array([-3.01340938, 3.09524703, 0.11022339]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.948760986328125, + 'left_pupil_posn': array([0.127437 , 0.0001967]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98838806, 0.08810425, 0.12367249]), + 'right_gaze_origin': array([-3.13881564, -3.30263376, 0.09234925]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.991058349609375, + 'right_pupil_posn': array([ 0.1173265, -0.0789386]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.40871289372444153, + 'timestamp': 416.5211990661919, + 'timestamp_carla': 416521, + 'timestamp_device': 4154739, + 'timestamp_stream': 416.5211990661919, + 'transform': [array([-4.45853859e-01, -2.07426224e+01, 1.44187920e-02]), + array([-0.06085015, 2.43151379, -0.00994475])]} +{'AngularVelocity': array([ 0.04795013, -0.02586815, -0.70980328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.834478378295898, + 'FR_Wheel_Angle': 14.865056991577148, + 'Location': array([ 1.38278043, -19.24738693, 0.16814868]), + 'Rotation': array([-6.62869811e-02, 3.50054092e+01, -1.90734882e-02]), + 'Velocity': array([-0.14164838, -0.13351382, 0.00014571]), + 'brake_input': 0.0, + 'camera_location': array([-4.31140327, 13.28888988, 2.14367938]), + 'camera_rotation': array([-9.46602058, 1.2436626 , 0.48033389]), + 'current_gear_input': False, + 'focus_actor_dist': 3209.128173828125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-635.69567871, -232.61206055, 0. ]), + 'frame': 12669, + 'frame_number': 12669, + 'framesequence': 48700, + 'gaze_dir': array([0.9812088 , 0.1315155 , 0.14070892]), + 'gaze_origin': array([-3.05792713, -0.12930299, 0.10038453]), + 'gaze_valid': True, + 'gaze_vergence': 244.65171813964844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98075867, 0.14103699, 0.13496399]), + 'left_gaze_origin': array([-3.01771712, 3.06655455, 0.11749115]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9517974853515625, + 'left_pupil_posn': array([0.15869832, 0.01161158]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98165894, 0.12199402, 0.14645386]), + 'right_gaze_origin': array([-3.09813714, -3.32516026, 0.0832779 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.00604248046875, + 'right_pupil_posn': array([ 0.14149439, -0.07217622]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.4126802384853363, + 'timestamp': 416.5538213662803, + 'timestamp_carla': 416554, + 'timestamp_device': 4154772, + 'timestamp_stream': 416.5538213662803, + 'transform': [array([-4.49689180e-01, -2.07120457e+01, 1.47600360e-02]), + array([-0.06091162, 2.44267392, -0.0114474 ])]} +{'AngularVelocity': array([-0.00452018, 0.00477977, -0.35838264]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.684621810913086, + 'FR_Wheel_Angle': 14.040841102600098, + 'Location': array([ 1.3577621 , -19.26954079, 0.16819164]), + 'Rotation': array([-6.55902997e-02, 3.48479614e+01, -2.03247033e-02]), + 'Velocity': array([-0.07941534, -0.07407992, 0.00038599]), + 'brake_input': 0.0, + 'camera_location': array([-4.29558754, 13.2778244 , 2.12715483]), + 'camera_rotation': array([-9.55553627, 1.22763062, 0.46076113]), + 'current_gear_input': False, + 'focus_actor_dist': 5082.01318359375, + 'focus_actor_name': 'Road_Grass_Town05_118', + 'focus_actor_pt': array([-1100.66784668, 1590.31640625, 18.16171265]), + 'frame': 12670, + 'frame_number': 12670, + 'framesequence': 48704, + 'gaze_dir': array([0.9812851 , 0.1343689 , 0.13739777]), + 'gaze_origin': array([-3.05718994, -0.12969895, 0.10016175]), + 'gaze_valid': True, + 'gaze_vergence': 266.02056884765625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98007202, 0.14570618, 0.13497925]), + 'left_gaze_origin': array([-3.01757669, 3.0665803 , 0.11704407]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9781341552734375, + 'left_pupil_posn': array([0.15899706, 0.00902891]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98249817, 0.12303162, 0.13981628]), + 'right_gaze_origin': array([-3.09680343, -3.32597828, 0.08327942]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.996612548828125, + 'right_pupil_posn': array([ 0.14366412, -0.07198095]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.4126802384853363, + 'timestamp': 416.5873731672764, + 'timestamp_carla': 416587, + 'timestamp_device': 4154805, + 'timestamp_stream': 416.5873731672764, + 'transform': [array([-4.51869965e-01, -2.06781750e+01, 1.50737660e-02]), + array([-0.06100725, 2.44576645, -0.01286808])]} +{'AngularVelocity': array([ 5.35787549e-04, 2.70674587e-03, -6.04660988e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.633857727050781, + 'FR_Wheel_Angle': 10.086960792541504, + 'Location': array([ 1.33458459, -19.28922844, 0.16824111]), + 'Rotation': array([-7.15257376e-02, 3.47267647e+01, -1.87377911e-02]), + 'Velocity': array([-1.32484287e-01, -1.14906639e-01, 1.25188832e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.27930927, 13.28068352, 2.1252346 ]), + 'camera_rotation': array([-9.58578777, 1.24214208, 0.46514946]), + 'current_gear_input': False, + 'focus_actor_dist': 4356.84033203125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-970.28033447, 879.58374023, 14.26799774]), + 'frame': 12671, + 'frame_number': 12671, + 'framesequence': 48708, + 'gaze_dir': array([0.98144531, 0.13378906, 0.13659668]), + 'gaze_origin': array([-3.05679393, -0.12971345, 0.10031433]), + 'gaze_valid': True, + 'gaze_vergence': 234.8986358642578, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97996521, 0.14683533, 0.13442993]), + 'left_gaze_origin': array([-3.01849532, 3.06679702, 0.11752625]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.96844482421875, + 'left_pupil_posn': array([0.15806532, 0.00888091]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98292542, 0.1207428 , 0.13876343]), + 'right_gaze_origin': array([-3.09509301, -3.32622385, 0.08310242]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9669189453125, + 'right_pupil_posn': array([ 0.14419413, -0.07192779]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.4126802384853363, + 'timestamp': 416.62066776677966, + 'timestamp_carla': 416621, + 'timestamp_device': 4154839, + 'timestamp_stream': 416.62066776677966, + 'transform': [array([-4.54011053e-01, -2.06418552e+01, 1.53870862e-02]), + array([-0.06103457, 2.44818544, -0.01426144])]} +{'AngularVelocity': array([ 0.00448115, -0.00664463, -0.34625852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.648897171020508, + 'FR_Wheel_Angle': 8.181248664855957, + 'Location': array([ 1.3070482 , -19.31144142, 0.16826275]), + 'Rotation': array([-6.92171305e-02, 3.46197929e+01, -1.96228027e-02]), + 'Velocity': array([-9.95508581e-02, -8.14517364e-02, -8.99600927e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.25718021, 13.28118038, 2.11742139]), + 'camera_rotation': array([-9.6086483 , 1.26461196, 0.39791095]), + 'current_gear_input': False, + 'focus_actor_dist': 4351.7822265625, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-968.26824951, 878.09082031, 8.65852356]), + 'frame': 12672, + 'frame_number': 12672, + 'framesequence': 48712, + 'gaze_dir': array([0.98119354, 0.13446045, 0.13777161]), + 'gaze_origin': array([-3.05684376, -0.12966157, 0.10052186]), + 'gaze_valid': True, + 'gaze_vergence': 227.98170471191406, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97976685, 0.14770508, 0.13497925]), + 'left_gaze_origin': array([-3.01945066, 3.06706405, 0.11776429]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.96673583984375, + 'left_pupil_posn': array([0.15806532, 0.00946426]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98262024, 0.12121582, 0.14056396]), + 'right_gaze_origin': array([-3.09423685, -3.32638741, 0.08327942]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.01348876953125, + 'right_pupil_posn': array([ 0.14457285, -0.07155395]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.4126802384853363, + 'timestamp': 416.6554815657437, + 'timestamp_carla': 416655, + 'timestamp_device': 4154872, + 'timestamp_stream': 416.6554815657437, + 'transform': [array([-4.56279427e-01, -2.06010590e+01, 1.56524088e-02]), + array([-0.06106872, 2.45029044, -0.01549087])]} +{'AngularVelocity': array([-0.00631406, 0.00324365, -0.04392014]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.606816291809082, + 'FR_Wheel_Angle': 8.229642868041992, + 'Location': array([ 1.29257417, -19.32291794, 0.16827923]), + 'Rotation': array([-6.78101107e-02, 3.45754128e+01, -1.94702130e-02]), + 'Velocity': array([-0.04762876, -0.03886596, 0.0002063 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.24630833, 13.28325939, 2.09416962]), + 'camera_rotation': array([-9.6703043 , 1.26289332, 0.40738773]), + 'current_gear_input': False, + 'focus_actor_dist': 4349.60498046875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-972.08770752, 878.90209961, 12.98616028]), + 'frame': 12673, + 'frame_number': 12673, + 'framesequence': 48716, + 'gaze_dir': array([0.98110962, 0.13448334, 0.13822174]), + 'gaze_origin': array([-3.05789042, -0.12968063, 0.10112076]), + 'gaze_valid': True, + 'gaze_vergence': 213.21983337402344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97952271, 0.14877319, 0.13557434]), + 'left_gaze_origin': array([-3.02151489, 3.06708241, 0.11879121]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9661712646484375, + 'left_pupil_posn': array([0.15771055, 0.0099014 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98269653, 0.12019348, 0.14086914]), + 'right_gaze_origin': array([-3.09426594, -3.32644367, 0.08345032]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0094451904296875, + 'right_pupil_posn': array([ 0.14498556, -0.07127011]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.4126802384853363, + 'timestamp': 416.6871522665024, + 'timestamp_carla': 416687, + 'timestamp_device': 4154905, + 'timestamp_stream': 416.6871522665024, + 'transform': [array([-4.58579391e-01, -2.05612125e+01, 1.59394164e-02]), + array([-0.06106872, 2.45270944, -0.01668615])]} +{'AngularVelocity': array([-0.00427622, 0.00252965, -0.00392824]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.213607788085938, + 'FR_Wheel_Angle': 9.017524719238281, + 'Location': array([ 1.28282928, -19.33063316, 0.16829059]), + 'Rotation': array([-6.92171305e-02, 3.45410271e+01, -1.89208928e-02]), + 'Velocity': array([-3.66524421e-02, -3.03503145e-02, -7.11250323e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.22365952, 13.27898407, 2.08066082]), + 'camera_rotation': array([-9.71857357, 1.24045467, 0.4178102 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4345.0830078125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-971.61309814, 878.42919922, 10.44506073]), + 'frame': 12674, + 'frame_number': 12674, + 'framesequence': 48720, + 'gaze_dir': array([0.98109436, 0.13568878, 0.1370163 ]), + 'gaze_origin': array([-3.05916619, -0.12978517, 0.10230637]), + 'gaze_valid': True, + 'gaze_vergence': 200.5392303466797, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97912598, 0.15124512, 0.13572693]), + 'left_gaze_origin': array([-3.02412581, 3.06708241, 0.12088624]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9805908203125, + 'left_pupil_posn': array([0.15769851, 0.00992948]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98306274, 0.12013245, 0.13830566]), + 'right_gaze_origin': array([-3.09420633, -3.32665253, 0.0837265 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.014984130859375, + 'right_pupil_posn': array([ 0.14599717, -0.07108295]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.38887616991996765, + 'timestamp': 416.72218396887183, + 'timestamp_carla': 416722, + 'timestamp_device': 4154939, + 'timestamp_stream': 416.72218396887183, + 'transform': [array([-4.61248010e-01, -2.05143700e+01, 1.61289405e-02]), + array([-0.06106872, 2.45539141, -0.01758774])]} +{'AngularVelocity': array([-0.00227683, 0.0012847 , -0.01261432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.648200988769531, + 'FR_Wheel_Angle': 9.436484336853027, + 'Location': array([ 1.27454352, -19.33727646, 0.16831413]), + 'Rotation': array([-7.00299293e-02, 3.45097046e+01, -1.86767541e-02]), + 'Velocity': array([-0.03438089, -0.02883546, 0.00011407]), + 'brake_input': 0.0, + 'camera_location': array([-4.20715427, 13.27851486, 2.06677628]), + 'camera_rotation': array([-9.77697086, 1.25055015, 0.43306941]), + 'current_gear_input': False, + 'focus_actor_dist': 4340.42138671875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-974.61700439, 876.82739258, 1.75410461]), + 'frame': 12675, + 'frame_number': 12675, + 'framesequence': 48724, + 'gaze_dir': array([0.98092651, 0.13583374, 0.13811493]), + 'gaze_origin': array([-3.061306 , -0.13017426, 0.10305176]), + 'gaze_valid': True, + 'gaze_vergence': 204.1892547607422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97921753, 0.15081787, 0.13554382]), + 'left_gaze_origin': array([-3.02676415, 3.06669474, 0.12143861]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9855804443359375, + 'left_pupil_posn': array([0.1582365 , 0.01061463]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9826355 , 0.12084961, 0.14068604]), + 'right_gaze_origin': array([-3.09584832, -3.32704329, 0.08466493]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0277557373046875, + 'right_pupil_posn': array([ 0.1461488, -0.0708164]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.7545602656901, + 'timestamp_carla': 416755, + 'timestamp_device': 4154972, + 'timestamp_stream': 416.7545602656901, + 'transform': [array([-4.63893116e-01, -2.04684086e+01, 1.63055696e-02]), + array([-0.06106872, 2.45812464, -0.01831174])]} +{'AngularVelocity': array([-0.00140737, 0.00033898, -0.01437632]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.842244148254395, + 'FR_Wheel_Angle': 9.778615951538086, + 'Location': array([ 1.2660557 , -19.34409714, 0.1683099 ]), + 'Rotation': array([-7.04943761e-02, 3.44767036e+01, -1.86157227e-02]), + 'Velocity': array([-0.03724471, -0.03122172, -0.00021971]), + 'brake_input': 0.0, + 'camera_location': array([-4.19085026, 13.27887154, 2.06010985]), + 'camera_rotation': array([-9.81585598, 1.26006138, 0.41246033]), + 'current_gear_input': False, + 'focus_actor_dist': 4336.0751953125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-975.70751953, 876.91772461, 2.22891235]), + 'frame': 12676, + 'frame_number': 12676, + 'framesequence': 48728, + 'gaze_dir': array([0.98101044, 0.13510895, 0.13819122]), + 'gaze_origin': array([-3.06296253, -0.13051759, 0.1038971 ]), + 'gaze_valid': True, + 'gaze_vergence': 198.71434020996094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97927856, 0.15046692, 0.13543701]), + 'left_gaze_origin': array([-3.02779102, 3.06609654, 0.12233429]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9829254150390625, + 'left_pupil_posn': array([0.15826559, 0.01113772]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98274231, 0.11975098, 0.14094543]), + 'right_gaze_origin': array([-3.09813404, -3.32713175, 0.0854599 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0307159423828125, + 'right_pupil_posn': array([ 0.1461488 , -0.07073653]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00258186599239707, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.78811936825514, + 'timestamp_carla': 416788, + 'timestamp_device': 4155005, + 'timestamp_stream': 416.78811936825514, + 'transform': [array([-4.66771990e-01, -2.04182396e+01, 1.64047517e-02]), + array([-0.06106872, 2.46105886, -0.01874887])]} +{'AngularVelocity': array([ 0.00010872, -0.00160322, -0.0568166 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.09345817565918, + 'FR_Wheel_Angle': 11.372688293457031, + 'Location': array([ 1.25662768, -19.35174179, 0.16832729]), + 'Rotation': array([-7.05900043e-02, 3.44375229e+01, -1.85241699e-02]), + 'Velocity': array([-0.04016821, -0.03456075, -0.00012879]), + 'brake_input': 0.0, + 'camera_location': array([-4.18230057, 13.27986336, 2.06106877]), + 'camera_rotation': array([-9.82368279, 1.26945889, 0.39400479]), + 'current_gear_input': False, + 'focus_actor_dist': 4330.52197265625, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-9.72388611e+02, 8.76504150e+02, 3.55529785e-02]), + 'frame': 12677, + 'frame_number': 12677, + 'framesequence': 48732, + 'gaze_dir': array([0.97912598, 0.15098572, 0.13518524]), + 'gaze_origin': array([-3.05956721, -0.13850708, 0.10637055]), + 'gaze_valid': True, + 'gaze_vergence': 184.8459930419922, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97821045, 0.16368103, 0.12763977]), + 'left_gaze_origin': array([-2.9967041 , 3.05968332, 0.11564942]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.00732421875, + 'left_pupil_posn': array([0.16877544, 0.01255602]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9800415 , 0.13829041, 0.14273071]), + 'right_gaze_origin': array([-3.12243056, -3.33669734, 0.09709168]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9603271484375, + 'right_pupil_posn': array([ 0.15800512, -0.07003403]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.002600177191197872, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.82108736783266, + 'timestamp_carla': 416821, + 'timestamp_device': 4155038, + 'timestamp_stream': 416.82108736783266, + 'transform': [array([-4.69747901e-01, -2.03664856e+01, 1.64614953e-02]), + array([-0.06106872, 2.46409202, -0.01897426])]} +{'AngularVelocity': array([ 0.00086475, -0.00190366, -0.04467568]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.511543273925781, + 'FR_Wheel_Angle': 11.560818672180176, + 'Location': array([ 1.247298 , -19.35945702, 0.16831917]), + 'Rotation': array([-7.03167915e-02, 3.43934479e+01, -1.86462384e-02]), + 'Velocity': array([-0.03676585, -0.03218611, -0.00067209]), + 'brake_input': 0.0, + 'camera_location': array([-4.174366 , 13.27755165, 2.06814981]), + 'camera_rotation': array([-9.80083561, 1.2716192 , 0.43725887]), + 'current_gear_input': False, + 'focus_actor_dist': 3976.8994140625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.64827942e+02, 5.21459473e+02, -4.57763672e-05]), + 'frame': 12678, + 'frame_number': 12678, + 'framesequence': 48736, + 'gaze_dir': array([0.97860718, 0.15122223, 0.13909149]), + 'gaze_origin': array([-3.06382775, -0.14450914, 0.10955429]), + 'gaze_valid': True, + 'gaze_vergence': 312.26324462890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97727966, 0.16105652, 0.13772583]), + 'left_gaze_origin': array([-3.00434732, 3.05060887, 0.11972504]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0237579345703125, + 'left_pupil_posn': array([0.17603314, 0.01305437]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97993469, 0.14138794, 0.14045715]), + 'right_gaze_origin': array([-3.12330794, -3.33962727, 0.09938355]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.005340576171875, + 'right_pupil_posn': array([ 0.15915561, -0.06527185]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00278328824788332, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.85443426668644, + 'timestamp_carla': 416854, + 'timestamp_device': 4155072, + 'timestamp_stream': 416.85443426668644, + 'transform': [array([-4.72937763e-01, -2.03117256e+01, 1.64701361e-02]), + array([-0.06109604, 2.46746707, -0.01900842])]} +{'AngularVelocity': array([-0.10868508, 0.0753573 , -0.53045315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.0032958984375, + 'FR_Wheel_Angle': 11.061524391174316, + 'Location': array([ 1.23739409, -19.36758804, 0.1683805 ]), + 'Rotation': array([-7.29942247e-02, 3.43474960e+01, -1.77001934e-02]), + 'Velocity': array([-0.12453111, -0.10502458, 0.00062473]), + 'brake_input': 0.0, + 'camera_location': array([-4.18714428, 13.27493286, 2.07491183]), + 'camera_rotation': array([-9.78216267, 1.22312033, 0.45938867]), + 'current_gear_input': False, + 'focus_actor_dist': 4336.56494140625, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1044.64111328, 877.77636719, 5.95988464]), + 'frame': 12679, + 'frame_number': 12679, + 'framesequence': 48740, + 'gaze_dir': array([0.97869873, 0.15192413, 0.13758087]), + 'gaze_origin': array([-3.06507206, -0.1445633 , 0.11062469]), + 'gaze_valid': True, + 'gaze_vergence': 301.93408203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97715759, 0.16223145, 0.13716125]), + 'left_gaze_origin': array([-3.00671411, 3.05086088, 0.12160493]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0236968994140625, + 'left_pupil_posn': array([0.17595446, 0.01305437]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98023987, 0.14161682, 0.13800049]), + 'right_gaze_origin': array([-3.12343001, -3.33998728, 0.09964447]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9775390625, + 'right_pupil_posn': array([ 0.15983152, -0.06527019]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.003534043440595269, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.8868864662945, + 'timestamp_carla': 416887, + 'timestamp_device': 4155105, + 'timestamp_stream': 416.8868864662945, + 'transform': [array([-4.76352841e-01, -2.02561073e+01, 1.64671410e-02]), + array([-0.06119166, 2.4715662 , -0.01896744])]} +{'AngularVelocity': array([ 0.04122378, -0.03346459, -1.0894686 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.003917694091797, + 'FR_Wheel_Angle': 12.610148429870605, + 'Location': array([ 1.17842197, -19.41575813, 0.16845992]), + 'Rotation': array([-7.51662254e-02, 3.40693207e+01, -1.70288086e-02]), + 'Velocity': array([-2.12846547e-01, -1.83857411e-01, 1.17568969e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.16167068, 13.25473881, 2.06743932]), + 'camera_rotation': array([-9.66619968, 1.21990108, 0.49679267]), + 'current_gear_input': False, + 'focus_actor_dist': 4330.12548828125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1.04334229e+03, 8.76812500e+02, 7.67288208e-01]), + 'frame': 12680, + 'frame_number': 12680, + 'framesequence': 48744, + 'gaze_dir': array([0.97854614, 0.1525116 , 0.13796997]), + 'gaze_origin': array([-3.07461023, -0.1450531 , 0.11082459]), + 'gaze_valid': True, + 'gaze_vergence': 268.31817626953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97680664, 0.16410828, 0.13749695]), + 'left_gaze_origin': array([-3.02555418, 3.0499773 , 0.1224167 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.988189697265625, + 'left_pupil_posn': array([0.17650867, 0.01044965]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98028564, 0.14091492, 0.13844299]), + 'right_gaze_origin': array([-3.12366652, -3.34008336, 0.09923249]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.981964111328125, + 'right_pupil_posn': array([ 0.16056347, -0.06555378]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00556657649576664, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.921838067472, + 'timestamp_carla': 416922, + 'timestamp_device': 4155138, + 'timestamp_stream': 416.921838067472, + 'transform': [array([-4.80748892e-01, -2.01937904e+01, 1.63845066e-02]), + array([-0.06145804, 2.47838449, -0.01868741])]} +{'AngularVelocity': array([ 0.02052038, -0.01670522, -0.63846862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.381295204162598, + 'FR_Wheel_Angle': 14.257750511169434, + 'Location': array([ 1.13641679, -19.45075607, 0.16845608]), + 'Rotation': array([-6.76257014e-02, 3.38427773e+01, -1.95007306e-02]), + 'Velocity': array([-0.13721198, -0.12186686, 0.00022199]), + 'brake_input': 0.0, + 'camera_location': array([-4.14204884, 13.20949364, 2.05381727]), + 'camera_rotation': array([-9.70241261, 1.18783987, 0.61917102]), + 'current_gear_input': False, + 'focus_actor_dist': 4326.6923828125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1045.81005859, 878.68237305, 10.83708954]), + 'frame': 12681, + 'frame_number': 12681, + 'framesequence': 48748, + 'gaze_dir': array([0.97821045, 0.15554047, 0.13707733]), + 'gaze_origin': array([-3.06952453, -0.14504549, 0.11227952]), + 'gaze_valid': True, + 'gaze_vergence': 317.7126159667969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97686768, 0.16519165, 0.13572693]), + 'left_gaze_origin': array([-3.01546645, 3.05008721, 0.12524262]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.03509521484375, + 'left_pupil_posn': array([0.17803967, 0.01399201]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97955322, 0.14588928, 0.13842773]), + 'right_gaze_origin': array([-3.1235826 , -3.34017801, 0.09931641]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.004364013671875, + 'right_pupil_posn': array([ 0.16098142, -0.06612086]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00906399730592966, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.95360776782036, + 'timestamp_carla': 416954, + 'timestamp_device': 4155172, + 'timestamp_stream': 416.95360776782036, + 'transform': [array([-4.85866070e-01, -2.01348438e+01, 1.63543690e-02]), + array([-0.06194981, 2.48861146, -0.01853031])]} +{'AngularVelocity': array([-4.47450322e-04, 3.13533098e-03, 5.81598461e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.627732276916504, + 'FR_Wheel_Angle': 15.842720031738281, + 'Location': array([ 1.11031711, -19.47299957, 0.16849071]), + 'Rotation': array([-6.71954006e-02, 3.36831512e+01, -1.97448693e-02]), + 'Velocity': array([-9.66061726e-02, -8.73739421e-02, 8.97026039e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.15907001, 13.16956139, 2.02449107]), + 'camera_rotation': array([-9.93052769, 1.09955633, 0.43558675]), + 'current_gear_input': False, + 'focus_actor_dist': 4321.91748046875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1057.27612305, 877.29003906, 3.1645813 ]), + 'frame': 12682, + 'frame_number': 12682, + 'framesequence': 48752, + 'gaze_dir': array([0.97809601, 0.15742493, 0.13559723]), + 'gaze_origin': array([-3.06241918, -0.14599839, 0.10935364]), + 'gaze_valid': True, + 'gaze_vergence': 275.71337890625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97631836, 0.16868591, 0.13534546]), + 'left_gaze_origin': array([-3.00117207, 3.04858875, 0.11896516]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.076934814453125, + 'left_pupil_posn': array([0.17897367, 0.01138669]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97987366, 0.14616394, 0.135849 ]), + 'right_gaze_origin': array([-3.12366652, -3.34058547, 0.09974213]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.00054931640625, + 'right_pupil_posn': array([ 0.16249561, -0.06603682]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.013238930143415928, + 'throttle_input': 0.37299153208732605, + 'timestamp': 416.98747926577926, + 'timestamp_carla': 416987, + 'timestamp_device': 4155205, + 'timestamp_stream': 416.98747926577926, + 'transform': [array([-4.92955625e-01, -2.00696621e+01, 1.62720382e-02]), + array([-0.06272162, 2.5054965 , -0.01826392])]} +{'AngularVelocity': array([-0.01316901, 0.0047445 , 0.7357285 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.476181983947754, + 'FR_Wheel_Angle': 16.965364456176758, + 'Location': array([ 1.09100521, -19.48972702, 0.16851696]), + 'Rotation': array([-6.80833235e-02, 3.35555344e+01, -1.92871056e-02]), + 'Velocity': array([-7.42828175e-02, -7.03703836e-02, 3.25202927e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.1600523 , 13.11012268, 2.02636051]), + 'camera_rotation': array([-9.94210434, 0.96570516, 0.45859599]), + 'current_gear_input': False, + 'focus_actor_dist': 3819.2958984375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.47359131e+02, 3.92373047e+02, 1.52587891e-05]), + 'frame': 12683, + 'frame_number': 12683, + 'framesequence': 48756, + 'gaze_dir': array([0.97595978, 0.16143799, 0.1457901 ]), + 'gaze_origin': array([-3.06410694, -0.15212022, 0.10890885]), + 'gaze_valid': True, + 'gaze_vergence': 240.30850219726562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97418213, 0.17408752, 0.14364624]), + 'left_gaze_origin': array([-3.00147581, 3.04556131, 0.1181488 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.03814697265625, + 'left_pupil_posn': array([0.18201411, 0.01490784]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97773743, 0.14878845, 0.14793396]), + 'right_gaze_origin': array([-3.12673831, -3.34980202, 0.09966888]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0280303955078125, + 'right_pupil_posn': array([ 0.17083454, -0.06400442]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.01820123940706253, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.020900066942, + 'timestamp_carla': 417021, + 'timestamp_device': 4155238, + 'timestamp_stream': 417.020900066942, + 'transform': [array([-5.01943529e-01, -2.00029888e+01, 1.61885545e-02]), + array([-0.06365736, 2.52950978, -0.01798389])]} +{'AngularVelocity': array([-3.63942632e-03, -3.53708223e-04, 7.13189960e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.37753677368164, + 'FR_Wheel_Angle': 18.017005920410156, + 'Location': array([ 1.07591903, -19.50292015, 0.16854835]), + 'Rotation': array([-6.84180036e-02, 3.34460182e+01, -1.93786602e-02]), + 'Velocity': array([-0.05359755, -0.05103828, 0.00023453]), + 'brake_input': 0.0, + 'camera_location': array([-4.18826771, 13.06827545, 2.01635242]), + 'camera_rotation': array([-10.08618069, 0.74719137, 0.24453276]), + 'current_gear_input': False, + 'focus_actor_dist': 4684.9951171875, + 'focus_actor_name': 'Road_Grass_Town05_118', + 'focus_actor_pt': array([-1147.96032715, 1242.04785156, 16.4105835 ]), + 'frame': 12684, + 'frame_number': 12684, + 'framesequence': 48760, + 'gaze_dir': array([0.9757309 , 0.16387939, 0.14485931]), + 'gaze_origin': array([-3.06775761, -0.15411682, 0.11272507]), + 'gaze_valid': True, + 'gaze_vergence': 332.51226806640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97479248, 0.17221069, 0.14176941]), + 'left_gaze_origin': array([-3.01053023, 3.04305124, 0.12544709]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0069122314453125, + 'left_pupil_posn': array([0.18619704, 0.01821047]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97666931, 0.1555481 , 0.14794922]), + 'right_gaze_origin': array([-3.12498498, -3.35128498, 0.10000306]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.005279541015625, + 'right_pupil_posn': array([ 0.1711328 , -0.06402671]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.024152349680662155, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.0554224662483, + 'timestamp_carla': 417055, + 'timestamp_device': 4155272, + 'timestamp_stream': 417.0554224662483, + 'transform': [array([-5.13792574e-01, -1.99317169e+01, 1.60764493e-02]), + array([-0.06482532, 2.56387448, -0.01763554])]} +{'AngularVelocity': array([-2.95752921e-04, -1.16931880e-03, 8.42737317e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.416974067687988, + 'FR_Wheel_Angle': 18.042461395263672, + 'Location': array([ 1.06560421, -19.51202011, 0.16855201]), + 'Rotation': array([-6.91829845e-02, 3.33654671e+01, -1.91040020e-02]), + 'Velocity': array([-4.75722440e-02, -4.53632250e-02, 5.45120238e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.23055553, 13.03776741, 2.01345491]), + 'camera_rotation': array([-10.21747112, 0.60620189, 0.24847695]), + 'current_gear_input': False, + 'focus_actor_dist': 2382.02099609375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-633.42614746, -995.43554688, 68.92957306]), + 'frame': 12685, + 'frame_number': 12685, + 'framesequence': 48764, + 'gaze_dir': array([0.97615051, 0.16585541, 0.1398468 ]), + 'gaze_origin': array([-3.06746149, -0.15485306, 0.11244889]), + 'gaze_valid': True, + 'gaze_vergence': 466.4710388183594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9750061 , 0.17248535, 0.13995361]), + 'left_gaze_origin': array([-3.01053023, 3.04204869, 0.12514801]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9846343994140625, + 'left_pupil_posn': array([0.18811917, 0.01518828]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97729492, 0.15922546, 0.13973999]), + 'right_gaze_origin': array([-3.12439275, -3.35175514, 0.09974976]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.00274658203125, + 'right_pupil_posn': array([ 0.17151737, -0.06472301]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.031403549015522, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.0878007672727, + 'timestamp_carla': 417088, + 'timestamp_device': 4155305, + 'timestamp_stream': 417.0878007672727, + 'transform': [array([-5.27838588e-01, -1.98625641e+01, 1.60057247e-02]), + array([-0.06616404, 2.60708976, -0.01740332])]} +{'AngularVelocity': array([-2.82977126e-03, -9.30261158e-04, 9.60246027e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.428571701049805, + 'FR_Wheel_Angle': 18.049985885620117, + 'Location': array([ 1.05608404, -19.52044678, 0.1685603 ]), + 'Rotation': array([-6.89985678e-02, 3.32962875e+01, -1.92565899e-02]), + 'Velocity': array([-0.03422642, -0.03274856, -0.0001897 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.27884579, 13.00988579, 2.01436949]), + 'camera_rotation': array([-10.07306671, 0.47674707, 0.50441784]), + 'current_gear_input': False, + 'focus_actor_dist': 3825.26171875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-952.66589355, 417.67578125, 0. ]), + 'frame': 12686, + 'frame_number': 12686, + 'framesequence': 48768, + 'gaze_dir': array([0.97616577, 0.16582489, 0.13976288]), + 'gaze_origin': array([-3.06688929, -0.15564424, 0.11116409]), + 'gaze_valid': True, + 'gaze_vergence': 466.1077880859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97544861, 0.17182922, 0.13764954]), + 'left_gaze_origin': array([-3.00937963, 3.04138184, 0.12280884]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9896697998046875, + 'left_pupil_posn': array([0.18876934, 0.01452607]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97688293, 0.15982056, 0.14187622]), + 'right_gaze_origin': array([-3.12439895, -3.35267043, 0.09951935]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0026702880859375, + 'right_pupil_posn': array([ 0.17189503, -0.06565976]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03905759006738663, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.1207391656935, + 'timestamp_carla': 417121, + 'timestamp_device': 4155338, + 'timestamp_stream': 417.1207391656935, + 'transform': [array([-5.45577407e-01, -1.97899323e+01, 1.59263890e-02]), + array([-0.06772132, 2.66396642, -0.01719158])]} +{'AngularVelocity': array([-3.28100473e-03, -9.70382476e-04, 1.07552743e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.45434856414795, + 'FR_Wheel_Angle': 18.09359359741211, + 'Location': array([ 1.048751 , -19.52692032, 0.16855022]), + 'Rotation': array([-6.92171305e-02, 3.32414093e+01, -1.90429688e-02]), + 'Velocity': array([-0.02674352, -0.02573098, -0.00025393]), + 'brake_input': 0.0, + 'camera_location': array([-4.32765198, 12.99570847, 2.02738309]), + 'camera_rotation': array([-10.05318451, 0.40909922, 0.61203098]), + 'current_gear_input': False, + 'focus_actor_dist': 2367.817138671875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-629.23840332, -995.42431641, 56.01061249]), + 'frame': 12687, + 'frame_number': 12687, + 'framesequence': 48772, + 'gaze_dir': array([0.97560883, 0.16757202, 0.14157867]), + 'gaze_origin': array([-3.06496215, -0.15697099, 0.10974732]), + 'gaze_valid': True, + 'gaze_vergence': 433.3702087402344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97450256, 0.17466736, 0.14079285]), + 'left_gaze_origin': array([-3.00598931, 3.04009104, 0.1216156 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.98828125, + 'left_pupil_posn': array([0.18983948, 0.01449323]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97671509, 0.16047668, 0.1423645 ]), + 'right_gaze_origin': array([-3.12393522, -3.35403299, 0.09787904]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.00701904296875, + 'right_pupil_posn': array([ 0.1738342 , -0.06567109]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04651021212339401, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.15488436818123, + 'timestamp_carla': 417155, + 'timestamp_device': 4155372, + 'timestamp_stream': 417.15488436818123, + 'transform': [array([-5.67772508e-01, -1.97123089e+01, 1.58226006e-02]), + array([-0.06936739, 2.73715544, -0.01692521])]} +{'AngularVelocity': array([ 6.33083575e-04, 2.21850723e-03, -1.38167226e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.6358060836792, + 'FR_Wheel_Angle': 18.33094596862793, + 'Location': array([ 1.04270744, -19.53211784, 0.16859272]), + 'Rotation': array([-6.96132854e-02, 3.31809273e+01, -1.88598596e-02]), + 'Velocity': array([-2.50051562e-02, -2.29987428e-02, 4.72164138e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.36162376, 13.00180149, 2.06588674]), + 'camera_rotation': array([-9.87967682, 0.42146394, 0.65437865]), + 'current_gear_input': False, + 'focus_actor_dist': 4249.3154296875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1.05110095e+03, 8.44598633e+02, -1.52587891e-05]), + 'frame': 12688, + 'frame_number': 12688, + 'framesequence': 48776, + 'gaze_dir': array([0.9758606 , 0.16735077, 0.14002228]), + 'gaze_origin': array([-3.06230497, -0.15927278, 0.10631791]), + 'gaze_valid': True, + 'gaze_vergence': 369.3295593261719, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97439575, 0.17570496, 0.14022827]), + 'left_gaze_origin': array([-3.00027943, 3.03606582, 0.11524506]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.072418212890625, + 'left_pupil_posn': array([0.19191074, 0.01020122]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97732544, 0.15899658, 0.13981628]), + 'right_gaze_origin': array([-3.12433028, -3.35461116, 0.09739076]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.007568359375, + 'right_pupil_posn': array([ 0.1745944 , -0.06627476]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05465865135192871, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.1875237673521, + 'timestamp_carla': 417188, + 'timestamp_device': 4155405, + 'timestamp_stream': 417.1875237673521, + 'transform': [array([-5.92794657e-01, -1.96359024e+01, 1.57399755e-02]), + array([-0.07101347, 2.82121921, -0.01668616])]} +{'AngularVelocity': array([-6.78118435e-04, 4.76768566e-03, -1.47090244e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.610413551330566, + 'FR_Wheel_Angle': 18.21431541442871, + 'Location': array([ 1.03619432, -19.53782082, 0.16859253]), + 'Rotation': array([-7.02211708e-02, 3.31307068e+01, -1.85241699e-02]), + 'Velocity': array([-0.03287651, -0.02986267, -0.00013003]), + 'brake_input': 0.0, + 'camera_location': array([-4.38496113, 13.02049637, 2.1073637 ]), + 'camera_rotation': array([-9.67285156, 0.39527217, 0.54808742]), + 'current_gear_input': False, + 'focus_actor_dist': 4276.439453125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1063.30981445, 877.57983398, 4.65408325]), + 'frame': 12689, + 'frame_number': 12689, + 'framesequence': 48780, + 'gaze_dir': array([0.97581482, 0.16867828, 0.1386261 ]), + 'gaze_origin': array([-3.06003428, -0.15950547, 0.10487595]), + 'gaze_valid': True, + 'gaze_vergence': 305.40130615234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97387695, 0.17834473, 0.14051819]), + 'left_gaze_origin': array([-2.99525166, 3.03605056, 0.11284333]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.056732177734375, + 'left_pupil_posn': array([0.19186032, 0.00847358]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97775269, 0.15901184, 0.13673401]), + 'right_gaze_origin': array([-3.12481713, -3.35506153, 0.09690857]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.00762939453125, + 'right_pupil_posn': array([ 0.17585301, -0.06664526]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06163518503308296, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.2219922654331, + 'timestamp_carla': 417222, + 'timestamp_device': 4155438, + 'timestamp_stream': 417.2219922654331, + 'transform': [array([-6.23844564e-01, -1.95531960e+01, 1.55603886e-02]), + array([-0.07254343, 2.92757821, -0.01607144])]} +{'AngularVelocity': array([ 0.04635125, -0.07349674, -4.33874702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.467241287231445, + 'FR_Wheel_Angle': 18.100309371948242, + 'Location': array([ 0.94041032, -19.61968613, 0.16885188]), + 'Rotation': array([-9.39902291e-02, 3.24269638e+01, -6.43921085e-03]), + 'Velocity': array([-0.54446167, -0.50304455, 0.0009168 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.412714 , 13.0556097 , 2.15301466]), + 'camera_rotation': array([-9.54255962, 0.45516634, 0.53838897]), + 'current_gear_input': False, + 'focus_actor_dist': 4278.9072265625, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1073.15039062, 885.84594727, 15.2399826 ]), + 'frame': 12690, + 'frame_number': 12690, + 'framesequence': 48784, + 'gaze_dir': array([0.9759903 , 0.16783905, 0.13839722]), + 'gaze_origin': array([-3.06073642, -0.15988007, 0.10327378]), + 'gaze_valid': True, + 'gaze_vergence': 290.9093322753906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97392273, 0.17749023, 0.14126587]), + 'left_gaze_origin': array([-2.99469924, 3.03626728, 0.11192018]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0466766357421875, + 'left_pupil_posn': array([0.1914258 , 0.00760406]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97805786, 0.15818787, 0.13552856]), + 'right_gaze_origin': array([-3.12677336, -3.35602713, 0.09462739]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9899749755859375, + 'right_pupil_posn': array([ 0.17627525, -0.0682472 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06883145123720169, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.25402596592903, + 'timestamp_carla': 417254, + 'timestamp_device': 4155472, + 'timestamp_stream': 417.25402596592903, + 'transform': [array([-6.56747699e-01, -1.94744701e+01, 1.54316425e-02]), + array([-0.07390948, 3.04156089, -0.01556601])]} +{'AngularVelocity': array([ 6.24263240e-03, -3.03718019e-02, -6.42931843e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.380876541137695, + 'FR_Wheel_Angle': 17.977855682373047, + 'Location': array([ 0.76185119, -19.76830482, 0.1690385 ]), + 'Rotation': array([-9.02950987e-02, 3.11288109e+01, -8.97216611e-03]), + 'Velocity': array([-0.82852203, -0.72679722, 0.0008576 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.42177773, 13.09547043, 2.1740222 ]), + 'camera_rotation': array([-9.40229416, 0.54551947, 0.6439485 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4606.56591796875, + 'focus_actor_name': 'Road_Grass_Town05_118', + 'focus_actor_pt': array([-1156.65881348, 1211.2644043 , 15.25632477]), + 'frame': 12691, + 'frame_number': 12691, + 'framesequence': 48788, + 'gaze_dir': array([0.97645569, 0.16791534, 0.13499451]), + 'gaze_origin': array([-3.06089878, -0.15951997, 0.10233689]), + 'gaze_valid': True, + 'gaze_vergence': 307.63922119140625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97451782, 0.17713928, 0.13757324]), + 'left_gaze_origin': array([-2.99469924, 3.0369873 , 0.11113434]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.04547119140625, + 'left_pupil_posn': array([0.19110143, 0.00603765]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97839355, 0.15869141, 0.13241577]), + 'right_gaze_origin': array([-3.12709808, -3.35602713, 0.09353943]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9821014404296875, + 'right_pupil_posn': array([ 0.17613184, -0.0702858 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07480087131261826, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.2871148660779, + 'timestamp_carla': 417287, + 'timestamp_device': 4155505, + 'timestamp_stream': 417.2871148660779, + 'transform': [array([-6.94436491e-01, -1.93912563e+01, 1.53117944e-02]), + array([-0.07519355, 3.17272472, -0.01514253])]} +{'AngularVelocity': array([ 0.04995225, -0.06358317, -6.68982124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.861635208129883, + 'FR_Wheel_Angle': 16.949705123901367, + 'Location': array([ 0.58106488, -19.91170311, 0.16919601]), + 'Rotation': array([-7.97766075e-02, 2.98384075e+01, -1.66320801e-02]), + 'Velocity': array([-0.89607871, -0.74704754, 0.00119606]), + 'brake_input': 0.0, + 'camera_location': array([-4.42121983, 13.15286446, 2.19342685]), + 'camera_rotation': array([-9.23392391, 0.61138606, 0.70024598]), + 'current_gear_input': False, + 'focus_actor_dist': 4387.1298828125, + 'focus_actor_name': 'Road_Sidewalk_Town05_155', + 'focus_actor_pt': array([-1124.02233887, 1001.36572266, 15.21987152]), + 'frame': 12692, + 'frame_number': 12692, + 'framesequence': 48792, + 'gaze_dir': array([0.97689819, 0.16708374, 0.13275146]), + 'gaze_origin': array([-3.06105447, -0.15912858, 0.10220719]), + 'gaze_valid': True, + 'gaze_vergence': 299.480224609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97491455, 0.17643738, 0.1355896 ]), + 'left_gaze_origin': array([-2.99491286, 3.03757477, 0.11107789]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0773773193359375, + 'left_pupil_posn': array([0.19034898, 0.00508714]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97888184, 0.1577301 , 0.12991333]), + 'right_gaze_origin': array([-3.12719607, -3.3558321 , 0.09333649]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9903564453125, + 'right_pupil_posn': array([ 0.17572856, -0.07113445]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08034913241863251, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.32264586538076, + 'timestamp_carla': 417323, + 'timestamp_device': 4155538, + 'timestamp_stream': 417.32264586538076, + 'transform': [array([-7.39008904e-01, -1.92999306e+01, 1.51624866e-02]), + array([-0.07632736, 3.32844758, -0.01465076])]} +{'AngularVelocity': array([-0.14384286, -0.2384114 , -4.33380938]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.1423978805542, + 'FR_Wheel_Angle': 14.59693431854248, + 'Location': array([ 0.38433737, -20.05793953, 0.16944298]), + 'Rotation': array([-5.69091327e-02, 2.85583649e+01, -1.04064951e-02]), + 'Velocity': array([-0.77354854, -0.57747811, 0.00444431]), + 'brake_input': 0.0, + 'camera_location': array([-4.42027473, 13.22258377, 2.1992166 ]), + 'camera_rotation': array([-9.20709419, 0.68769616, 0.81861693]), + 'current_gear_input': False, + 'focus_actor_dist': 4467.96533203125, + 'focus_actor_name': 'Road_Sidewalk_Town05_155', + 'focus_actor_pt': array([-1155.2166748 , 1085.45947266, 15.01377106]), + 'frame': 12693, + 'frame_number': 12693, + 'framesequence': 48796, + 'gaze_dir': array([0.97755432, 0.16529846, 0.13019562]), + 'gaze_origin': array([-3.06267023, -0.15767594, 0.1017952 ]), + 'gaze_valid': True, + 'gaze_vergence': 287.6110534667969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97557068, 0.17364502, 0.13453674]), + 'left_gaze_origin': array([-2.99805784, 3.03939533, 0.11107789]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.07464599609375, + 'left_pupil_posn': array([0.18885553, 0.00313783]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97953796, 0.1569519 , 0.12585449]), + 'right_gaze_origin': array([-3.12728286, -3.3547473 , 0.09251252]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.98931884765625, + 'right_pupil_posn': array([ 0.17399263, -0.07200456]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08622699975967407, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.3555992655456, + 'timestamp_carla': 417356, + 'timestamp_device': 4155572, + 'timestamp_stream': 417.3555992655456, + 'transform': [array([-7.83997774e-01, -1.92132816e+01, 1.51127046e-02]), + array([-0.07735872, 3.48579597, -0.01445951])]} +{'AngularVelocity': array([-0.02572076, -0.01159288, -3.24184132]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.204801559448242, + 'FR_Wheel_Angle': 13.708155632019043, + 'Location': array([ 0.22104138, -20.17108917, 0.16971527]), + 'Rotation': array([-4.77566794e-02, 2.76473389e+01, -8.57544038e-03]), + 'Velocity': array([-5.58857501e-01, -4.04482871e-01, 1.93061831e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.4265728 , 13.28206062, 2.19033885]), + 'camera_rotation': array([-9.31344032, 0.71900481, 0.9345094 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4248.900390625, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1115.23120117, 878.77197266, 10.40646362]), + 'frame': 12694, + 'frame_number': 12694, + 'framesequence': 48800, + 'gaze_dir': array([0.97779083, 0.16408539, 0.12994385]), + 'gaze_origin': array([-3.06616473, -0.15575105, 0.10198059]), + 'gaze_valid': True, + 'gaze_vergence': 305.2256774902344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97587585, 0.17311096, 0.13296509]), + 'left_gaze_origin': array([-3.00489521, 3.04203057, 0.11144868]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.084686279296875, + 'left_pupil_posn': array([0.18648601, 0.00251585]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97970581, 0.15505981, 0.12692261]), + 'right_gaze_origin': array([-3.12743402, -3.35353231, 0.09251252]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0096282958984375, + 'right_pupil_posn': array([ 0.17295718, -0.07261598]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09003570675849915, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.38731256872416, + 'timestamp_carla': 417387, + 'timestamp_device': 4155605, + 'timestamp_stream': 417.38731256872416, + 'transform': [array([-8.30197453e-01, -1.91280689e+01, 1.51229855e-02]), + array([-0.07821249, 3.64708734, -0.01449367])]} +{'AngularVelocity': array([ 0.13098235, 0.16464438, -2.61817479]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.272134780883789, + 'FR_Wheel_Angle': 14.258560180664062, + 'Location': array([ 0.11006565, -20.24476624, 0.16972259]), + 'Rotation': array([-5.47234714e-02, 2.70681095e+01, -1.97143536e-02]), + 'Velocity': array([-0.40003997, -0.28243166, -0.0022366 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.44009209, 13.34390545, 2.17780948]), + 'camera_rotation': array([-9.42158985, 0.6832248 , 0.93858308]), + 'current_gear_input': False, + 'focus_actor_dist': 4240.93701171875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1.12383533e+03, 8.76928223e+02, 3.32382202e-01]), + 'frame': 12695, + 'frame_number': 12695, + 'framesequence': 48804, + 'gaze_dir': array([0.97895813, 0.15470123, 0.13265991]), + 'gaze_origin': array([-3.04559636, -0.14726944, 0.10042191]), + 'gaze_valid': True, + 'gaze_vergence': 329.82769775390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97796631, 0.1633606 , 0.12988281]), + 'left_gaze_origin': array([-2.95989394, 3.05048084, 0.1019104 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2022247314453125, + 'left_pupil_posn': array([0.17723608, 0.00722957]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97994995, 0.14604187, 0.13543701]), + 'right_gaze_origin': array([-3.13129902, -3.34501982, 0.09893342]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0970916748046875, + 'right_pupil_posn': array([ 0.16377985, -0.069911 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09256264567375183, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.4210707657039, + 'timestamp_carla': 417421, + 'timestamp_device': 4155638, + 'timestamp_stream': 417.4210707657039, + 'transform': [array([-8.82177711e-01, -1.90355186e+01, 1.51203442e-02]), + array([-0.07876574, 3.82814026, -0.01452099])]} +{'AngularVelocity': array([-0.0372031 , 0.01207825, -2.08241653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.23733901977539, + 'FR_Wheel_Angle': 16.68924903869629, + 'Location': array([ 0.03019754, -20.29829216, 0.16971256]), + 'Rotation': array([-6.11916631e-02, 2.66339207e+01, -2.09655762e-02]), + 'Velocity': array([-0.30652392, -0.21903533, 0.00100049]), + 'brake_input': 0.0, + 'camera_location': array([-4.43613625, 13.42654037, 2.18397784]), + 'camera_rotation': array([-9.37877083, 0.68102145, 0.9711107 ]), + 'current_gear_input': False, + 'focus_actor_dist': 4225.3505859375, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1091.2677002 , 877.53320312, 4.02726746]), + 'frame': 12696, + 'frame_number': 12696, + 'framesequence': 48808, + 'gaze_dir': array([0.97946167, 0.15345764, 0.13034821]), + 'gaze_origin': array([-3.04804325, -0.14713898, 0.10041657]), + 'gaze_valid': True, + 'gaze_vergence': 304.1988220214844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97822571, 0.16325378, 0.12808228]), + 'left_gaze_origin': array([-2.96452808, 3.05065012, 0.10274353]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1992645263671875, + 'left_pupil_posn': array([0.1762588 , 0.00579852]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98069763, 0.1436615 , 0.13261414]), + 'right_gaze_origin': array([-3.13155842, -3.34492803, 0.09808961]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.028961181640625, + 'right_pupil_posn': array([ 0.16369247, -0.07107151]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09344157576560974, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.453329667449, + 'timestamp_carla': 417453, + 'timestamp_device': 4155672, + 'timestamp_stream': 417.453329667449, + 'transform': [array([-9.33842301e-01, -1.89453411e+01, 1.51536940e-02]), + array([-0.078916 , 4.00733232, -0.01460295])]} +{'AngularVelocity': array([-0.01752725, 0.00673142, -0.85733414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.250701904296875, + 'FR_Wheel_Angle': 17.950044631958008, + 'Location': array([ -0.0403944 , -20.34584618, 0.16982619]), + 'Rotation': array([-6.36573583e-02, 2.61820164e+01, -1.87683087e-02]), + 'Velocity': array([-0.24705881, -0.17886165, 0.00060336]), + 'brake_input': 0.0, + 'camera_location': array([-4.40299034, 13.51295662, 2.20940995]), + 'camera_rotation': array([-9.18871403, 0.76827103, 1.06979609]), + 'current_gear_input': False, + 'focus_actor_dist': 2291.0234375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-649.79241943, -995.48120117, 60.9381485 ]), + 'frame': 12697, + 'frame_number': 12697, + 'framesequence': 48812, + 'gaze_dir': array([0.98026276, 0.1502533 , 0.12789154]), + 'gaze_origin': array([-3.0663147 , -0.14413071, 0.10324173]), + 'gaze_valid': True, + 'gaze_vergence': 275.87457275390625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97840881, 0.16137695, 0.12905884]), + 'left_gaze_origin': array([-3.00172591, 3.055089 , 0.10916138]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1595458984375, + 'left_pupil_posn': array([0.17206943, 0.00163817]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9821167 , 0.13912964, 0.12672424]), + 'right_gaze_origin': array([-3.13090372, -3.34335041, 0.09732208]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.112030029296875, + 'right_pupil_posn': array([ 0.16191745, -0.0711931 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0935148149728775, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.48831536620855, + 'timestamp_carla': 417488, + 'timestamp_device': 4155705, + 'timestamp_stream': 417.48831536620855, + 'transform': [array([-9.91609633e-01, -1.88457336e+01, 1.51525969e-02]), + array([-0.07870427, 4.20664978, -0.01458929])]} +{'AngularVelocity': array([ 0.01115318, -0.00272929, -0.62576163]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.820155143737793, + 'FR_Wheel_Angle': 18.654335021972656, + 'Location': array([ -0.09737333, -20.38423347, 0.16991188]), + 'Rotation': array([-6.72910213e-02, 2.57921009e+01, -1.68456994e-02]), + 'Velocity': array([-0.24747641, -0.17786114, 0.00045599]), + 'brake_input': 0.0, + 'camera_location': array([-4.39520645, 13.60366821, 2.2316258 ]), + 'camera_rotation': array([-8.98573494, 0.9851321 , 1.34404421]), + 'current_gear_input': False, + 'focus_actor_dist': 4197.30419921875, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1101.23181152, 864.79638672, 0. ]), + 'frame': 12698, + 'frame_number': 12698, + 'framesequence': 48816, + 'gaze_dir': array([0.98135376, 0.14619446, 0.12445831]), + 'gaze_origin': array([-3.05800176, -0.13689041, 0.09815445]), + 'gaze_valid': True, + 'gaze_vergence': 405.8545227050781, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98033142, 0.15380859, 0.12355042]), + 'left_gaze_origin': array([-2.98267388, 3.06205463, 0.10195008]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1270751953125, + 'left_pupil_posn': array([ 0.16699445, -0.00018549]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9823761 , 0.13858032, 0.12536621]), + 'right_gaze_origin': array([-3.13332987, -3.33583546, 0.09435883]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.15142822265625, + 'right_pupil_posn': array([ 0.15409517, -0.07553494]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09338664263486862, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.5203720666468, + 'timestamp_carla': 417520, + 'timestamp_device': 4155738, + 'timestamp_stream': 417.5203720666468, + 'transform': [array([-1.04579890e+00, -1.87527943e+01, 1.52027607e-02]), + array([-0.07839691, 4.39243889, -0.01466442])]} +{'AngularVelocity': array([-0.05327365, 0.00232711, -1.35257363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.408266067504883, + 'FR_Wheel_Angle': 19.500791549682617, + 'Location': array([ -0.15484105, -20.42276764, 0.16997012]), + 'Rotation': array([-6.61298856e-02, 2.53715611e+01, -1.69677753e-02]), + 'Velocity': array([-0.23312046, -0.17161542, 0.00039509]), + 'brake_input': 0.0, + 'camera_location': array([-4.38470173, 13.68064785, 2.21421623]), + 'camera_rotation': array([-9.04693317, 1.1668694 , 1.57160139]), + 'current_gear_input': False, + 'focus_actor_dist': 4110.49609375, + 'focus_actor_name': 'Road_Marking_Town05_93', + 'focus_actor_pt': array([-1096.82397461, 786.68457031, 0. ]), + 'frame': 12699, + 'frame_number': 12699, + 'framesequence': 48820, + 'gaze_dir': array([0.98223114, 0.14060211, 0.12399292]), + 'gaze_origin': array([-3.08251047, -0.13195114, 0.1075821 ]), + 'gaze_valid': True, + 'gaze_vergence': 398.7978210449219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98123169, 0.14836121, 0.12310791]), + 'left_gaze_origin': array([-2.99526834, 3.06567407, 0.10735016]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1929168701171875, + 'left_pupil_posn': array([0.16264033, 0.00091791]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98323059, 0.13284302, 0.12487793]), + 'right_gaze_origin': array([-3.1697526 , -3.32957625, 0.10781404]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1387481689453125, + 'right_pupil_posn': array([ 0.14894104, -0.07305038]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09280069172382355, + 'throttle_input': 0.37299153208732605, + 'timestamp': 417.5534627661109, + 'timestamp_carla': 417553, + 'timestamp_device': 4155772, + 'timestamp_stream': 417.5534627661109, + 'transform': [array([-1.10274148e+00, -1.86551685e+01, 1.52515881e-02]), + array([-0.07800075, 4.58623743, -0.0147737 ])]} +{'AngularVelocity': array([-5.02555296e-02, 8.86158610e-04, -1.37856090e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.71722984313965, + 'FR_Wheel_Angle': 19.831439971923828, + 'Location': array([ -0.19438472, -20.44915962, 0.17005725]), + 'Rotation': array([-6.63757771e-02, 2.50750828e+01, -1.67236328e-02]), + 'Velocity': array([-2.20423460e-01, -1.62068367e-01, -1.63874618e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.37312794, 13.73280334, 2.19752169]), + 'camera_rotation': array([-9.23177242, 1.31284308, 1.69481206]), + 'current_gear_input': False, + 'focus_actor_dist': 2265.87744140625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-661.82733154, -995.51342773, 56.67369843]), + 'frame': 12700, + 'frame_number': 12700, + 'framesequence': 48824, + 'gaze_dir': array([0.98286438, 0.13492584, 0.12499237]), + 'gaze_origin': array([-3.09676147, -0.12888871, 0.11333923]), + 'gaze_valid': True, + 'gaze_vergence': 268.6707763671875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98194885, 0.1452179 , 0.12106323]), + 'left_gaze_origin': array([-3.01622796, 3.06957722, 0.11590577]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1767425537109375, + 'left_pupil_posn': array([0.15736067, 0.00438046]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98377991, 0.12463379, 0.12892151]), + 'right_gaze_origin': array([-3.17729521, -3.32735443, 0.11077271]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1338958740234375, + 'right_pupil_posn': array([ 0.14651155, -0.07305038]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09124423563480377, + 'throttle_input': 0.3650568425655365, + 'timestamp': 417.58785516768694, + 'timestamp_carla': 417588, + 'timestamp_device': 4155805, + 'timestamp_stream': 417.58785516768694, + 'transform': [array([-1.16275942e+00, -1.85520134e+01, 1.52760502e-02]), + array([-0.07742019, 4.78897619, -0.01479419])]} +{'AngularVelocity': array([ 2.34779101e-02, -1.23707089e-03, -2.30720758e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.729618072509766, + 'FR_Wheel_Angle': 19.839969635009766, + 'Location': array([ -0.23231488, -20.47433281, 0.17008033]), + 'Rotation': array([-6.50643781e-02, 2.47852917e+01, -1.74865704e-02]), + 'Velocity': array([-1.66229144e-01, -1.17305830e-01, -1.60264972e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.35012722, 13.75832176, 2.20065832]), + 'camera_rotation': array([-9.27364826, 1.43738186, 1.80009687]), + 'current_gear_input': False, + 'focus_actor_dist': 3617.355712890625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-987.98937988, 324.84399414, 0. ]), + 'frame': 12701, + 'frame_number': 12701, + 'framesequence': 48828, + 'gaze_dir': array([0.98344421, 0.13173676, 0.1238327 ]), + 'gaze_origin': array([-3.09252024, -0.12638932, 0.11126405]), + 'gaze_valid': True, + 'gaze_vergence': 280.2212829589844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98210144, 0.14283752, 0.12268066]), + 'left_gaze_origin': array([-3.01528788, 3.07341337, 0.11471405]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.197174072265625, + 'left_pupil_posn': array([0.15334964, 0.00241452]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98478699, 0.12063599, 0.12498474]), + 'right_gaze_origin': array([-3.1697526 , -3.32619166, 0.10781404]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.115081787109375, + 'right_pupil_posn': array([ 0.14468181, -0.07305038]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08875393122434616, + 'throttle_input': 0.3531548082828522, + 'timestamp': 417.6207232661545, + 'timestamp_carla': 417621, + 'timestamp_device': 4155838, + 'timestamp_stream': 417.6207232661545, + 'transform': [array([-1.22035599e+00, -1.84518433e+01, 1.53171634e-02]), + array([-0.07668936, 4.98173285, -0.01480102])]} +{'AngularVelocity': array([ 8.42782960e-04, -1.86055154e-03, -9.07845438e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.74287986755371, + 'FR_Wheel_Angle': 19.85749626159668, + 'Location': array([ -0.26154235, -20.49360466, 0.17003486]), + 'Rotation': array([-6.48526400e-02, 2.45702686e+01, -1.74865704e-02]), + 'Velocity': array([-0.13740483, -0.09791236, -0.0011869 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.34102154, 13.76220131, 2.22434092]), + 'camera_rotation': array([-9.26181126, 1.51179981, 1.90941274]), + 'current_gear_input': False, + 'focus_actor_dist': 3425.86328125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-952.3447876 , 146.88549805, 0. ]), + 'frame': 12702, + 'frame_number': 12702, + 'framesequence': 48832, + 'gaze_dir': array([0.98201752, 0.13528442, 0.13101196]), + 'gaze_origin': array([-3.03770089, -0.12470322, 0.09237976]), + 'gaze_valid': True, + 'gaze_vergence': 260.9017639160156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9803009 , 0.14726257, 0.1315155 ]), + 'left_gaze_origin': array([-2.9959321 , 3.07566404, 0.10600281]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2187957763671875, + 'left_pupil_posn': array([0.15260839, 0.00187665]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98373413, 0.12330627, 0.13050842]), + 'right_gaze_origin': array([-3.07946944, -3.32507038, 0.07875672]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.14129638671875, + 'right_pupil_posn': array([ 0.14300597, -0.07342589]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08547624945640564, + 'throttle_input': 0.3333180844783783, + 'timestamp': 417.65356876701117, + 'timestamp_carla': 417653, + 'timestamp_device': 4155872, + 'timestamp_stream': 417.65356876701117, + 'transform': [array([-1.27760661e+00, -1.83502274e+01, 1.53519241e-02]), + array([-0.07577411, 5.17116976, -0.01476688])]} +{'AngularVelocity': array([-0.00104888, -0.00667567, -0.64646488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.747831344604492, + 'FR_Wheel_Angle': 19.864572525024414, + 'Location': array([ -0.28990522, -20.51217651, 0.17003612]), + 'Rotation': array([-6.49072826e-02, 2.43648338e+01, -1.74560491e-02]), + 'Velocity': array([-1.02720782e-01, -7.27717578e-02, -2.68554686e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.33750248, 13.76478386, 2.21072936]), + 'camera_rotation': array([-9.25478935, 1.43357229, 1.82466018]), + 'current_gear_input': False, + 'focus_actor_dist': 4172.59423828125, + 'focus_actor_name': 'Road_Curb_Town05_153', + 'focus_actor_pt': array([-1169.8449707 , 872.96801758, 0. ]), + 'frame': 12703, + 'frame_number': 12703, + 'framesequence': 48836, + 'gaze_dir': array([0.9822998 , 0.13534546, 0.12895203]), + 'gaze_origin': array([-3.04282093, -0.12352677, 0.09423523]), + 'gaze_valid': True, + 'gaze_vergence': 287.60418701171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98068237, 0.14611816, 0.12997437]), + 'left_gaze_origin': array([-3.00624847, 3.07642365, 0.11084901]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.214630126953125, + 'left_pupil_posn': array([0.15260839, 0.00238526]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98391724, 0.12457275, 0.12792969]), + 'right_gaze_origin': array([-3.07939315, -3.32347751, 0.07762147]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.150390625, + 'right_pupil_posn': array([ 0.14152098, -0.07468164]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08007446676492691, + 'throttle_input': 0.3055466413497925, + 'timestamp': 417.6876900680363, + 'timestamp_carla': 417688, + 'timestamp_device': 4155905, + 'timestamp_stream': 417.6876900680363, + 'transform': [array([-1.33576369e+00, -1.82432156e+01, 1.53482622e-02]), + array([-0.07440124, 5.36080456, -0.01455514])]} +{'AngularVelocity': array([-1.35850889e-04, -2.26899679e-03, -5.71780562e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.754941940307617, + 'FR_Wheel_Angle': 19.845901489257812, + 'Location': array([ -0.31647369, -20.52943039, 0.17015804]), + 'Rotation': array([-6.59181550e-02, 2.41668434e+01, -1.65710431e-02]), + 'Velocity': array([-0.09134825, -0.06424594, 0.00032277]), + 'brake_input': 0.0, + 'camera_location': array([-4.34751034, 13.75384903, 2.20756555]), + 'camera_rotation': array([-9.28986263, 1.24940598, 1.69963503]), + 'current_gear_input': False, + 'focus_actor_dist': 3959.888427734375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1124.56542969, 675.35571289, 0. ]), + 'frame': 12704, + 'frame_number': 12704, + 'framesequence': 48840, + 'gaze_dir': array([0.98265839, 0.13381195, 0.12783051]), + 'gaze_origin': array([-3.04214811, -0.12406312, 0.09411392]), + 'gaze_valid': True, + 'gaze_vergence': 285.1358642578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98092651, 0.144104 , 0.13038635]), + 'left_gaze_origin': array([-3.00853133, 3.07590342, 0.11272126]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1968536376953125, + 'left_pupil_posn': array([0.15260839, 0.00238526]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98439026, 0.1235199 , 0.12527466]), + 'right_gaze_origin': array([-3.07576466, -3.32402968, 0.07550659]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1766357421875, + 'right_pupil_posn': array([ 0.14109838, -0.07524037]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07386700063943863, + 'throttle_input': 0.2658579349517822, + 'timestamp': 417.7221360653639, + 'timestamp_carla': 417722, + 'timestamp_device': 4155938, + 'timestamp_stream': 417.7221360653639, + 'transform': [array([-1.39229250e+00, -1.81338978e+01, 1.52961155e-02]), + array([-0.07263223, 5.54172039, -0.01407703])]} +{'AngularVelocity': array([-6.03756011e-02, -2.43418865e-04, -4.03840303e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.632919311523438, + 'FR_Wheel_Angle': 19.70353889465332, + 'Location': array([ -0.3832761 , -20.57149696, 0.17035122]), + 'Rotation': array([-8.53568688e-02, 2.36478539e+01, -4.57763625e-03]), + 'Velocity': array([-4.95092839e-01, -3.45546573e-01, 4.83627315e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.29516983, 13.74557686, 2.22041845]), + 'camera_rotation': array([-9.06900883, 0.9942854 , 1.70564485]), + 'current_gear_input': False, + 'focus_actor_dist': 3801.556884765625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.07956543e+03, 5.34442627e+02, 4.27246094e-04]), + 'frame': 12705, + 'frame_number': 12705, + 'framesequence': 48844, + 'gaze_dir': array([0.99125671, 0.04206085, 0.1230545 ]), + 'gaze_origin': array([-3.05180216, -0.04944229, 0.08181839]), + 'gaze_valid': True, + 'gaze_vergence': 145.1826171875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99005127, 0.06378174, 0.12538147]), + 'left_gaze_origin': array([-2.97085118, 3.15499115, 0.08502503]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.117889404296875, + 'left_pupil_posn': array([ 0.06360507, -0.00992191]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99246216, 0.02033997, 0.12072754]), + 'right_gaze_origin': array([-3.13275313, -3.25387597, 0.07861175]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.09814453125, + 'right_pupil_posn': array([ 0.06668079, -0.08388889]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0663960725069046, + 'throttle_input': 0.22618448734283447, + 'timestamp': 417.75455456599593, + 'timestamp_carla': 417754, + 'timestamp_device': 4155972, + 'timestamp_stream': 417.75455456599593, + 'transform': [array([-1.44267499e+00, -1.80299969e+01, 1.52206700e-02]), + array([-0.07065147, 5.69927931, -0.01339401])]} +{'AngularVelocity': array([-0.01641937, -0.03267291, -4.26804495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.62767791748047, + 'FR_Wheel_Angle': 19.68645477294922, + 'Location': array([ -0.50322241, -20.64652634, 0.17040507]), + 'Rotation': array([-7.49544948e-02, 2.27581387e+01, -1.22070303e-02]), + 'Velocity': array([-5.21186173e-01, -3.54554385e-01, 3.18717939e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.25037956, 13.72176933, 2.21512437]), + 'camera_rotation': array([-9.03823853, 0.77327496, 1.83358324]), + 'current_gear_input': False, + 'focus_actor_dist': 3832.151611328125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-7.38052185e+02, 6.48617920e+02, 1.52587891e-05]), + 'frame': 12706, + 'frame_number': 12706, + 'framesequence': 48848, + 'gaze_dir': array([ 0.99359131, -0.00498962, 0.1122818 ]), + 'gaze_origin': array([-3.08037448, -0.01284866, 0.08237153]), + 'gaze_valid': True, + 'gaze_vergence': 280.9421081542969, + 'handbrake_input': False, + 'left_eye_openness': 0.9909326434135437, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99351501, 0.00627136, 0.11340332]), + 'left_gaze_origin': array([-2.99150395, 3.18329787, 0.08233491]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1442413330078125, + 'left_pupil_posn': array([ 0.03194737, -0.01839483]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9936676 , -0.01625061, 0.11116028]), + 'right_gaze_origin': array([-3.16924453, -3.20899534, 0.08240815]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0518341064453125, + 'right_pupil_posn': array([ 0.01668525, -0.09131122]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0587054081261158, + 'throttle_input': 0.19839780032634735, + 'timestamp': 417.7878101654351, + 'timestamp_carla': 417788, + 'timestamp_device': 4156005, + 'timestamp_stream': 417.7878101654351, + 'transform': [array([-1.49073184e+00, -1.79225941e+01, 1.50709534e-02]), + array([-0.06832921, 5.8451519 , -0.01238996])]} +{'AngularVelocity': array([ 0.03376947, -0.02523638, -4.52386808]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.605571746826172, + 'FR_Wheel_Angle': 19.667203903198242, + 'Location': array([ -0.64355063, -20.73061562, 0.17055194]), + 'Rotation': array([-7.39094764e-02, 2.17447777e+01, -1.50451669e-02]), + 'Velocity': array([-6.18439555e-01, -3.94042611e-01, 4.18500887e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.22130966, 13.67554379, 2.1616683 ]), + 'camera_rotation': array([-9.33382225, 0.46410924, 1.87819779]), + 'current_gear_input': False, + 'focus_actor_dist': 3050.473388671875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-4.69264435e+02, -9.33708496e+01, -1.52587891e-05]), + 'frame': 12707, + 'frame_number': 12707, + 'framesequence': 48852, + 'gaze_dir': array([ 0.99328613, -0.01531982, 0.11380768]), + 'gaze_origin': array([-3.06130695, -0.01748123, 0.08088608]), + 'gaze_valid': True, + 'gaze_vergence': 199.9693145751953, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99261475, -0.00419617, 0.12113953]), + 'left_gaze_origin': array([-2.99572778, 3.17991185, 0.08910675]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1998748779296875, + 'left_pupil_posn': array([ 0.0307318 , -0.01615179]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99395752, -0.02644348, 0.10647583]), + 'right_gaze_origin': array([-3.12688613, -3.21487451, 0.07266541]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.06427001953125, + 'right_pupil_posn': array([ 0.01633799, -0.08731985]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.04964141175150871, + 'throttle_input': 0.18252842128276825, + 'timestamp': 417.82266856729984, + 'timestamp_carla': 417823, + 'timestamp_device': 4156038, + 'timestamp_stream': 417.82266856729984, + 'transform': [array([-1.53645658e+00, -1.78094234e+01, 1.48257064e-02]), + array([-0.06567226, 5.97842121, -0.01097612])]} +{'AngularVelocity': array([ 0.00616145, -0.01265382, -4.22046232]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.11069679260254, + 'FR_Wheel_Angle': 20.634851455688477, + 'Location': array([ -0.80082512, -20.82114792, 0.17067501]), + 'Rotation': array([-6.69563413e-02, 2.06181870e+01, -1.92871038e-02]), + 'Velocity': array([-5.60991704e-01, -3.46799374e-01, 2.66933435e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.20009613, 13.60563946, 2.1048398 ]), + 'camera_rotation': array([-9.64277172, -0.0127332 , 1.93058038]), + 'current_gear_input': False, + 'focus_actor_dist': 2840.523193359375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-4.10460266e+02, -2.87517334e+02, 1.37329102e-04]), + 'frame': 12708, + 'frame_number': 12708, + 'framesequence': 48856, + 'gaze_dir': array([ 0.99259186, -0.00647736, 0.12016296]), + 'gaze_origin': array([-3.06205535, -0.0207367 , 0.08419571]), + 'gaze_valid': True, + 'gaze_vergence': 176.94839477539062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99176025, 0.00733948, 0.1277771 ]), + 'left_gaze_origin': array([-2.99198484, 3.17621779, 0.09136353]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.174224853515625, + 'left_pupil_posn': array([ 0.03535795, -0.01211917]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99342346, -0.02029419, 0.11254883]), + 'right_gaze_origin': array([-3.13212609, -3.21769118, 0.07702789]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0724334716796875, + 'right_pupil_posn': array([ 0.02241802, -0.08328009]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03977172449231148, + 'throttle_input': 0.17062638700008392, + 'timestamp': 417.85371396690607, + 'timestamp_carla': 417854, + 'timestamp_device': 4156072, + 'timestamp_stream': 417.85371396690607, + 'transform': [array([-1.57259429e+00, -1.77082596e+01, 1.46045964e-02]), + array([-0.06307679, 6.07811785, -0.00954178])]} +{'AngularVelocity': array([-1.76594569e-03, -4.20955755e-03, -4.29606724e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.503042221069336, + 'FR_Wheel_Angle': 22.589462280273438, + 'Location': array([ -0.93308175, -20.89590073, 0.1708062 ]), + 'Rotation': array([-6.67719245e-02, 1.96065235e+01, -1.88598596e-02]), + 'Velocity': array([-0.53315157, -0.33005899, 0.00067838]), + 'brake_input': 0.0, + 'camera_location': array([-4.17825985, 13.52460003, 2.07560515]), + 'camera_rotation': array([-9.75107098, -0.47921297, 1.96203518]), + 'current_gear_input': False, + 'focus_actor_dist': 2880.81494140625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-424.96902466, -236.8918457 , 0. ]), + 'frame': 12709, + 'frame_number': 12709, + 'framesequence': 48860, + 'gaze_dir': array([0.99266052, 0.0013504 , 0.1198349 ]), + 'gaze_origin': array([-3.06524444, -0.02391663, 0.08486024]), + 'gaze_valid': True, + 'gaze_vergence': 200.67124938964844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99229431, 0.01676941, 0.12263489]), + 'left_gaze_origin': array([-2.99501657, 3.17483997, 0.09093018]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1853485107421875, + 'left_pupil_posn': array([ 0.03841174, -0.01104581]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99302673, -0.0140686 , 0.11703491]), + 'right_gaze_origin': array([-3.13547206, -3.22267294, 0.07879028]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.96612548828125, + 'right_pupil_posn': array([ 0.02912509, -0.08445668]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.032099369913339615, + 'throttle_input': 0.17062638700008392, + 'timestamp': 417.8873220682144, + 'timestamp_carla': 417887, + 'timestamp_device': 4156105, + 'timestamp_stream': 417.8873220682144, + 'transform': [array([-1.60669279e+00, -1.75984612e+01, 1.43058775e-02]), + array([-0.06042668, 6.16542959, -0.00786837])]} +{'AngularVelocity': array([ 1.27604706e-02, -1.39391655e-03, -4.30585432e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.422893524169922, + 'FR_Wheel_Angle': 23.90578842163086, + 'Location': array([ -1.0577209 , -20.96544838, 0.17093837]), + 'Rotation': array([-0.06747544, 18.57758522, -0.01916504]), + 'Velocity': array([-5.18013299e-01, -3.14845294e-01, 4.65373974e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.16618824, 13.42961025, 2.05121446]), + 'camera_rotation': array([-9.88158226, -0.94530433, 2.13040996]), + 'current_gear_input': False, + 'focus_actor_dist': 2735.77685546875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-4.15531769e+02, -3.71582520e+02, 1.52587891e-05]), + 'frame': 12710, + 'frame_number': 12710, + 'framesequence': 48864, + 'gaze_dir': array([0.99249268, 0.00363922, 0.12184906]), + 'gaze_origin': array([-3.04870081, -0.02691574, 0.08199158]), + 'gaze_valid': True, + 'gaze_vergence': 303.9677734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99194336, 0.01197815, 0.12606812]), + 'left_gaze_origin': array([-2.96161819, 3.17286992, 0.08250885]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1384735107421875, + 'left_pupil_posn': array([ 0.04299009, -0.01075089]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99304199, -0.00469971, 0.11763 ]), + 'right_gaze_origin': array([-3.13578367, -3.2267015 , 0.08147431]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0296783447265625, + 'right_pupil_posn': array([ 0.03022945, -0.08152914]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02233954891562462, + 'throttle_input': 0.16269169747829437, + 'timestamp': 417.9209411665797, + 'timestamp_carla': 417921, + 'timestamp_device': 4156138, + 'timestamp_stream': 417.9209411665797, + 'transform': [array([-1.63552380e+00, -1.74884949e+01, 1.39889428e-02]), + array([-5.78312092e-02, 6.23143291e+00, -6.11301791e-03])]} +{'AngularVelocity': array([ 8.45395923e-02, -1.03171868e-03, -5.79620981e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.679691314697266, + 'FR_Wheel_Angle': 27.841604232788086, + 'Location': array([ -1.20249176, -21.04530144, 0.17111942]), + 'Rotation': array([-7.31513202e-02, 1.72923222e+01, -1.44042959e-02]), + 'Velocity': array([-0.63551998, -0.38698918, 0.00064001]), + 'brake_input': 0.0, + 'camera_location': array([-4.17275524, 13.33877945, 2.01422 ]), + 'camera_rotation': array([-10.02984524, -1.49052668, 2.17548656]), + 'current_gear_input': False, + 'focus_actor_dist': 2713.99169921875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-4.04115692e+02, -3.81153320e+02, 1.52587891e-05]), + 'frame': 12711, + 'frame_number': 12711, + 'framesequence': 48868, + 'gaze_dir': array([0.99066925, 0.06327057, 0.11845398]), + 'gaze_origin': array([-3.08216429, -0.06716004, 0.10081406]), + 'gaze_valid': True, + 'gaze_vergence': 139.6272735595703, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98963928, 0.08560181, 0.11514282]), + 'left_gaze_origin': array([-3.0091157 , 3.13093591, 0.104776 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1518402099609375, + 'left_pupil_posn': array([ 0.08698988, -0.00324917]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99169922, 0.04093933, 0.12176514]), + 'right_gaze_origin': array([-3.1552124 , -3.26525617, 0.09685212]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.056976318359375, + 'right_pupil_posn': array([ 0.08257687, -0.07908845]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.014575640670955181, + 'throttle_input': 0.1587243527173996, + 'timestamp': 417.95427936688066, + 'timestamp_carla': 417954, + 'timestamp_device': 4156172, + 'timestamp_stream': 417.95427936688066, + 'transform': [array([-1.65913677e+00, -1.73793926e+01, 1.36740590e-02]), + array([-5.55704162e-02, 6.27692795e+00, -4.39180760e-03])]} +{'AngularVelocity': array([ 0.06261172, 0.02454346, -6.95147085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.831037521362305, + 'FR_Wheel_Angle': 32.325008392333984, + 'Location': array([ -1.33234346, -21.11903191, 0.17123814]), + 'Rotation': array([-7.13823065e-02, 1.59188614e+01, -1.43737802e-02]), + 'Velocity': array([-6.53501928e-01, -4.12944466e-01, 6.41107559e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.16521835, 13.25225258, 1.99768996]), + 'camera_rotation': array([-9.93698215, -2.04726744, 2.23411846]), + 'current_gear_input': False, + 'focus_actor_dist': 2057.447509765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -444.94482422, -1036.65332031, 16.95093536]), + 'frame': 12712, + 'frame_number': 12712, + 'framesequence': 48872, + 'gaze_dir': array([0.97637177, 0.16436005, 0.1398468 ]), + 'gaze_origin': array([-3.07267475, -0.15559922, 0.09720994]), + 'gaze_valid': True, + 'gaze_vergence': 279.0836181640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97424316, 0.17405701, 0.14328003]), + 'left_gaze_origin': array([-3.00342727, 3.03243423, 0.10513458]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.171234130859375, + 'left_pupil_posn': array([0.19279325, 0.00151724]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97850037, 0.15466309, 0.13641357]), + 'right_gaze_origin': array([-3.14192224, -3.3436327 , 0.08928528]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.957672119140625, + 'right_pupil_posn': array([ 0.16693735, -0.07410479]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00794702023267746, + 'throttle_input': 0.15078964829444885, + 'timestamp': 417.988419868052, + 'timestamp_carla': 417988, + 'timestamp_device': 4156205, + 'timestamp_stream': 417.988419868052, + 'transform': [array([-1.67883027e+00, -1.72677002e+01, 1.33466339e-02]), + array([-5.37399240e-02, 6.30567980e+00, -2.69109011e-03])]} +{'AngularVelocity': array([ 0.08009078, 0.02206899, -9.54958248]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.448949813842773, + 'FR_Wheel_Angle': 36.558387756347656, + 'Location': array([ -1.50403321, -21.21637344, 0.17143685]), + 'Rotation': array([-7.56306797e-02, 1.38698206e+01, -1.09863291e-02]), + 'Velocity': array([-7.80532002e-01, -4.96117532e-01, 5.04503259e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.12761307, 13.18153191, 2.00382209]), + 'camera_rotation': array([-9.77881527, -2.50920081, 2.24534822]), + 'current_gear_input': False, + 'focus_actor_dist': 3699.325927734375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.03262256e+03, 5.30487061e+02, 4.57763672e-04]), + 'frame': 12713, + 'frame_number': 12713, + 'framesequence': 48876, + 'gaze_dir': array([0.97566986, 0.17340088, 0.13358307]), + 'gaze_origin': array([-3.0730257 , -0.15744172, 0.10013657]), + 'gaze_valid': True, + 'gaze_vergence': 258.92755126953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97346497, 0.18521118, 0.1343689 ]), + 'left_gaze_origin': array([-3.00396132, 3.03313017, 0.10838167]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1790008544921875, + 'left_pupil_posn': array([0.19473386, 0.00231987]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97787476, 0.16159058, 0.13279724]), + 'right_gaze_origin': array([-3.14209008, -3.3480134 , 0.09189148]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.082672119140625, + 'right_pupil_posn': array([ 0.17385042, -0.07553828]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.005603198427706957, + 'throttle_input': 0.15078964829444885, + 'timestamp': 418.02052876725793, + 'timestamp_carla': 418020, + 'timestamp_device': 4156238, + 'timestamp_stream': 418.02052876725793, + 'transform': [array([-1.69490397e+00, -1.71627445e+01, 1.30580617e-02]), + array([-5.29476218e-02, 6.32309198e+00, -1.20893831e-03])]} +{'AngularVelocity': array([ -0.05220566, 0.07364195, -12.66461754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.34662437438965, + 'FR_Wheel_Angle': 37.592506408691406, + 'Location': array([ -1.70083046, -21.3249321 , 0.17167248]), + 'Rotation': array([-7.93463066e-02, 1.13052006e+01, -9.73510742e-03]), + 'Velocity': array([-0.97505444, -0.59024096, 0.00124825]), + 'brake_input': 0.0, + 'camera_location': array([-4.13343334, 13.10783958, 1.9867084 ]), + 'camera_rotation': array([-9.82623768, -2.78966784, 2.35251164]), + 'current_gear_input': False, + 'focus_actor_dist': 3358.933349609375, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-956.08398438, 210.03198242, 0. ]), + 'frame': 12714, + 'frame_number': 12714, + 'framesequence': 48880, + 'gaze_dir': array([0.97541046, 0.17636108, 0.13165283]), + 'gaze_origin': array([-3.07185602, -0.15987168, 0.0980629 ]), + 'gaze_valid': True, + 'gaze_vergence': 292.18328857421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97349548, 0.18688965, 0.13172913]), + 'left_gaze_origin': array([-3.0016818 , 3.03183317, 0.10383149]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.151763916015625, + 'left_pupil_posn': array([ 0.19706655, -0.00073838]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97732544, 0.16583252, 0.13157654]), + 'right_gaze_origin': array([-3.14203048, -3.35157633, 0.09229432]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9901123046875, + 'right_pupil_posn': array([ 0.17688859, -0.07612562]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.006994842551648617, + 'throttle_input': 0.15078964829444885, + 'timestamp': 418.054774466902, + 'timestamp_carla': 418055, + 'timestamp_device': 4156272, + 'timestamp_stream': 418.054774466902, + 'transform': [array([-1.71157348e+00, -1.70509682e+01, 1.27240466e-02]), + array([-5.34052476e-02, 6.33986902e+00, 2.44144117e-04])]} +{'AngularVelocity': array([ 0.08678754, -0.05524376, -10.28660202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.87876319885254, + 'FR_Wheel_Angle': 36.422027587890625, + 'Location': array([ -1.95390117, -21.44893265, 0.17184627]), + 'Rotation': array([-0.06643724, 8.0383625 , -0.03070068]), + 'Velocity': array([-0.81262892, -0.43031111, 0.00094543]), + 'brake_input': 0.0, + 'camera_location': array([-4.11531162, 12.99714375, 2.0305934 ]), + 'camera_rotation': array([-9.66003799, -2.93688011, 2.62374043]), + 'current_gear_input': False, + 'focus_actor_dist': 3117.4853515625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.94178955e+02, -1.27939453e+01, 6.86645508e-04]), + 'frame': 12715, + 'frame_number': 12715, + 'framesequence': 48884, + 'gaze_dir': array([0.97280884, 0.1871109 , 0.13599396]), + 'gaze_origin': array([-3.072963 , -0.16531755, 0.09528732]), + 'gaze_valid': True, + 'gaze_vergence': 277.8809509277344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97138977, 0.19708252, 0.13243103]), + 'left_gaze_origin': array([-3.00290084, 3.02669525, 0.09898224]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1767578125, + 'left_pupil_posn': array([ 0.20452833, -0.00170887]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97422791, 0.17713928, 0.13955688]), + 'right_gaze_origin': array([-3.14302516, -3.35733032, 0.09159241]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.919891357421875, + 'right_pupil_posn': array([ 0.18453753, -0.07655787]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.012671285308897495, + 'throttle_input': 0.15078964829444885, + 'timestamp': 418.0878163687885, + 'timestamp_carla': 418088, + 'timestamp_device': 4156305, + 'timestamp_stream': 418.0878163687885, + 'transform': [array([-1.72969246e+00, -1.69433537e+01, 1.24131013e-02]), + array([-5.52357361e-02, 6.36416292e+00, 1.49536855e-03])]} +{'AngularVelocity': array([-3.50875850e-03, -7.23417709e-03, -6.32177877e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.226802825927734, + 'FR_Wheel_Angle': 31.769285202026367, + 'Location': array([ -2.11535811, -21.51551056, 0.17198394]), + 'Rotation': array([-0.05919725, 6.14406681, -0.03805542]), + 'Velocity': array([-0.58499402, -0.25541022, 0.00071819]), + 'brake_input': 0.0, + 'camera_location': array([-4.15497971, 12.90044403, 2.04734635]), + 'camera_rotation': array([-9.76812649, -3.06890059, 2.4646945 ]), + 'current_gear_input': False, + 'focus_actor_dist': 3633.03759765625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-1.05338574e+03, 4.90620850e+02, 1.98364258e-04]), + 'frame': 12716, + 'frame_number': 12716, + 'framesequence': 48888, + 'gaze_dir': array([0.97369385, 0.18603516, 0.13109589]), + 'gaze_origin': array([-3.07172489, -0.16668931, 0.09886017]), + 'gaze_valid': True, + 'gaze_vergence': 302.10235595703125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9723053 , 0.19540405, 0.12811279]), + 'left_gaze_origin': array([-3.00107741, 3.02585006, 0.10536652]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1779022216796875, + 'left_pupil_posn': array([0.20487738, 0.00102651]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9750824 , 0.17666626, 0.13407898]), + 'right_gaze_origin': array([-3.14237213, -3.35922885, 0.09235382]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.936004638671875, + 'right_pupil_posn': array([ 0.18520081, -0.07736301]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.021167639642953873, + 'throttle_input': 0.15078964829444885, + 'timestamp': 418.12034106627107, + 'timestamp_carla': 418120, + 'timestamp_device': 4156338, + 'timestamp_stream': 418.12034106627107, + 'transform': [array([-1.75147545e+00, -1.68376751e+01, 1.21228406e-02]), + array([-5.82273602e-02, 6.40356159e+00, 2.53296574e-03])]} +{'AngularVelocity': array([-0.13899897, 0.10230996, -0.00117496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.560651779174805, + 'FR_Wheel_Angle': 24.43707275390625, + 'Location': array([ -2.1261766 , -21.51984024, 0.17193 ]), + 'Rotation': array([-0.04931396, 6.00075865, -0.03912353]), + 'Velocity': array([-4.94978894e-06, 3.56310658e-04, 1.28108586e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.20433331, 12.85335636, 2.03193402]), + 'camera_rotation': array([-9.80955791, -2.99998999, 1.83821321]), + 'current_gear_input': False, + 'focus_actor_dist': 3114.790283203125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-913.70153809, 2.04370117, 0. ]), + 'frame': 12717, + 'frame_number': 12717, + 'framesequence': 48892, + 'gaze_dir': array([0.97360992, 0.1859436 , 0.13168335]), + 'gaze_origin': array([-3.07132363, -0.16625138, 0.09857559]), + 'gaze_valid': True, + 'gaze_vergence': 255.50572204589844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97193909, 0.19709778, 0.12828064]), + 'left_gaze_origin': array([-3.00034499, 3.02630949, 0.10500031]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.146331787109375, + 'left_pupil_posn': array([0.20393801, 0.00137466]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97528076, 0.17478943, 0.13508606]), + 'right_gaze_origin': array([-3.14230204, -3.35881233, 0.09215088]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.913848876953125, + 'right_pupil_posn': array([ 0.18552804, -0.07741559]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.030780969187617302, + 'throttle_input': 0.15078964829444885, + 'timestamp': 418.1542455665767, + 'timestamp_carla': 418154, + 'timestamp_device': 4156372, + 'timestamp_stream': 418.1542455665767, + 'transform': [array([-1.77960920e+00, -1.67278519e+01, 1.18272202e-02]), + array([-6.20386042e-02, 6.46579456e+00, 3.44849471e-03])]} +{'AngularVelocity': array([-0.0394324 , 0.02870002, 0.0001497 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.194547653198242, + 'FR_Wheel_Angle': 17.970510482788086, + 'Location': array([ -2.12627578, -21.51991081, 0.17201343]), + 'Rotation': array([-0.06506438, 6.00067616, -0.02227783]), + 'Velocity': array([2.74869708e-05, 7.46136357e-06, 1.47663712e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.22348881, 12.81766319, 2.0566988 ]), + 'camera_rotation': array([-9.63611889, -2.85367107, 1.63050175]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.742431640625, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-951.70117188, 150.87353516, 0. ]), + 'frame': 12718, + 'frame_number': 12718, + 'framesequence': 48896, + 'gaze_dir': array([0.97409058, 0.1869812 , 0.12657928]), + 'gaze_origin': array([-3.06947565, -0.16843721, 0.09801102]), + 'gaze_valid': True, + 'gaze_vergence': 266.151123046875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97190857, 0.19850159, 0.12635803]), + 'left_gaze_origin': array([-2.99678206, 3.02235436, 0.10346986]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.213653564453125, + 'left_pupil_posn': array([ 0.20676756, -0.00183165]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97627258, 0.17546082, 0.12680054]), + 'right_gaze_origin': array([-3.14216948, -3.35922885, 0.09255219]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9185791015625, + 'right_pupil_posn': array([ 0.18629062, -0.07780802]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.043232522904872894, + 'throttle_input': 0.15078964829444885, + 'timestamp': 418.18858286738396, + 'timestamp_carla': 418188, + 'timestamp_device': 4156405, + 'timestamp_stream': 418.18858286738396, + 'transform': [array([-1.81502330e+00, -1.66170616e+01, 1.15456199e-02]), + array([-6.64030984e-02, 6.55570793e+00, 4.24194662e-03])]} +{'AngularVelocity': array([-1.13385683e-02, 7.20017450e-03, 1.44487694e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.616812705993652, + 'FR_Wheel_Angle': 7.757315158843994, + 'Location': array([ -2.12629676, -21.51994896, 0.17204043]), + 'Rotation': array([-0.06897125, 6.00074339, -0.0177002 ]), + 'Velocity': array([9.21796982e-06, 1.24091866e-06, 4.47405910e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.254076 , 12.80691242, 2.06280017]), + 'camera_rotation': array([-9.45412922, -2.86456847, 1.32502007]), + 'current_gear_input': False, + 'focus_actor_dist': 3145.993408203125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-9.37737732e+02, 5.03046875e+01, -1.52587891e-05]), + 'frame': 12719, + 'frame_number': 12719, + 'framesequence': 48900, + 'gaze_dir': array([0.97428131, 0.18863678, 0.12276459]), + 'gaze_origin': array([-3.0683229 , -0.16866302, 0.0978653 ]), + 'gaze_valid': True, + 'gaze_vergence': 305.6657409667969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97221375, 0.19836426, 0.12423706]), + 'left_gaze_origin': array([-2.99464893, 3.02240014, 0.10351411]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.08599853515625, + 'left_pupil_posn': array([ 0.20791805, -0.00321436]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97634888, 0.1789093 , 0.12129211]), + 'right_gaze_origin': array([-3.1419971 , -3.35972595, 0.09221649]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9111785888671875, + 'right_pupil_posn': array([ 0.1865654 , -0.07872283]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05379803106188774, + 'throttle_input': 0.14682230353355408, + 'timestamp': 418.22158796712756, + 'timestamp_carla': 418222, + 'timestamp_device': 4156438, + 'timestamp_stream': 418.22158796712756, + 'transform': [array([-1.85555923e+00, -1.65110054e+01, 1.13190366e-02]), + array([-7.04943761e-02, 6.66705465e+00, 4.88282181e-03])]} +{'AngularVelocity': array([-3.83887580e-03, 2.12505669e-03, -9.11068128e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.12630248, -21.5199585 , 0.17205288]), + 'Rotation': array([-0.06992064, 6.00078058, -0.01644897]), + 'Velocity': array([4.34641697e-06, 3.40745885e-07, 1.00274367e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.26023769, 12.82326317, 2.09721875]), + 'camera_rotation': array([-9.41523075, -2.85534596, 1.12220597]), + 'current_gear_input': False, + 'focus_actor_dist': 3166.47607421875, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-951.42987061, 79.39697266, 0. ]), + 'frame': 12720, + 'frame_number': 12720, + 'framesequence': 48904, + 'gaze_dir': array([0.97478485, 0.18772888, 0.12007141]), + 'gaze_origin': array([-3.06788206, -0.17042162, 0.09704056]), + 'gaze_valid': True, + 'gaze_vergence': 265.70367431640625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97314453, 0.19839478, 0.11672974]), + 'left_gaze_origin': array([-2.99393773, 3.02240014, 0.10222321]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0917205810546875, + 'left_pupil_posn': array([ 0.20727253, -0.00321436]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97642517, 0.17706299, 0.12341309]), + 'right_gaze_origin': array([-3.14182591, -3.3632431 , 0.09185792]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.8914947509765625, + 'right_pupil_posn': array([ 0.18893063, -0.08149791]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06440016627311707, + 'throttle_input': 0.13888761401176453, + 'timestamp': 418.2550514675677, + 'timestamp_carla': 418255, + 'timestamp_device': 4156472, + 'timestamp_stream': 418.2550514675677, + 'transform': [array([-1.90306652e+00, -1.64039745e+01, 1.11221503e-02]), + array([-7.43124560e-02, 6.80434227e+00, 5.40161366e-03])]} +{'AngularVelocity': array([-0.00112849, 0.00255924, -0.00016378]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.12446189, -21.51976776, 0.17203987]), + 'Rotation': array([-0.07049438, 6.00079107, -0.01602172]), + 'Velocity': array([-6.97825089e-06, -5.26318331e-07, -2.66982010e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.26674843, 12.86792946, 2.1552279 ]), + 'camera_rotation': array([-9.50406456, -2.85817146, 1.36591506]), + 'current_gear_input': False, + 'focus_actor_dist': 3068.40283203125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-9.30064392e+02, -5.42846680e+00, -1.37329102e-04]), + 'frame': 12721, + 'frame_number': 12721, + 'framesequence': 48908, + 'gaze_dir': array([0.97451782, 0.18989563, 0.11869049]), + 'gaze_origin': array([-3.06684208, -0.1707924 , 0.09531937]), + 'gaze_valid': True, + 'gaze_vergence': 226.15625, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97306824, 0.20085144, 0.11303711]), + 'left_gaze_origin': array([-2.99206853, 3.02238631, 0.10121003]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0905303955078125, + 'left_pupil_posn': array([ 0.20791805, -0.00326812]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97596741, 0.17893982, 0.12434387]), + 'right_gaze_origin': array([-3.14161563, -3.36397099, 0.08942872]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9065399169921875, + 'right_pupil_posn': array([ 0.19025004, -0.08446586]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0748191848397255, + 'throttle_input': 0.1269855797290802, + 'timestamp': 418.28710236772895, + 'timestamp_carla': 418287, + 'timestamp_device': 4156505, + 'timestamp_stream': 418.28710236772895, + 'transform': [array([-1.95450175e+00, -1.63020000e+01, 1.09761041e-02]), + array([-7.76046067e-02, 6.95823383e+00, 5.79834543e-03])]} +{'AngularVelocity': array([-1.55604881e-04, -4.96433291e-04, 1.08291324e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -2.12446094, -21.51976967, 0.17204517]), + 'Rotation': array([-0.07049438, 6.00079107, -0.01602172]), + 'Velocity': array([ 4.03364174e-06, 2.34919710e-07, -9.22173276e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.29365349, 12.93018055, 2.20289421]), + 'camera_rotation': array([-9.48823166, -2.89325786, 1.54160035]), + 'current_gear_input': False, + 'focus_actor_dist': 2835.405517578125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.86053284e+02, -2.23869141e+02, -1.52587891e-05]), + 'frame': 12722, + 'frame_number': 12722, + 'framesequence': 48912, + 'gaze_dir': array([0.97463226, 0.19352722, 0.11125183]), + 'gaze_origin': array([-3.06231165, -0.17240754, 0.09023514]), + 'gaze_valid': True, + 'gaze_vergence': 184.41290283203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97242737, 0.20802307, 0.10534668]), + 'left_gaze_origin': array([-2.98561883, 3.0203476 , 0.09496918]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0695037841796875, + 'left_pupil_posn': array([ 0.20923066, -0.00868833]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97683716, 0.17903137, 0.11715698]), + 'right_gaze_origin': array([-3.13900447, -3.36516285, 0.0855011 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.95654296875, + 'right_pupil_posn': array([ 0.19342697, -0.08958125]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08163091540336609, + 'throttle_input': 0.10316624492406845, + 'timestamp': 418.32091856747866, + 'timestamp_carla': 418321, + 'timestamp_device': 4156538, + 'timestamp_stream': 418.32091856747866, + 'transform': [array([-2.01390648e+00, -1.61950760e+01, 1.08334916e-02]), + array([-8.01659226e-02, 7.13966656e+00, 6.19507767e-03])]} +{'AngularVelocity': array([-0.00211021, 0.03385122, 0.52091509]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.17554907500743866, + 'FR_Wheel_Angle': -0.16757243871688843, + 'Location': array([ -2.12491202, -21.51984024, 0.17206195]), + 'Rotation': array([-0.07079491, 6.00282812, -0.01599121]), + 'Velocity': array([-0.0230567 , -0.00242934, 0.00046796]), + 'brake_input': 0.0, + 'camera_location': array([-4.2683754 , 13.02507973, 2.23674798]), + 'camera_rotation': array([-9.20800304, -2.89606047, 1.63624644]), + 'current_gear_input': False, + 'focus_actor_dist': 2173.18310546875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-728.11096191, -856.57592773, 15.13830566]), + 'frame': 12723, + 'frame_number': 12723, + 'framesequence': 48916, + 'gaze_dir': array([0.97463989, 0.19207001, 0.11356354]), + 'gaze_origin': array([-3.06181192, -0.17177507, 0.08615494]), + 'gaze_valid': True, + 'gaze_vergence': 167.9740753173828, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97261047, 0.20684814, 0.10600281]), + 'left_gaze_origin': array([-2.98370671, 3.0205965 , 0.08987122]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1092376708984375, + 'left_pupil_posn': array([ 0.20843279, -0.01041555]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97666931, 0.17729187, 0.12112427]), + 'right_gaze_origin': array([-3.13991714, -3.36414647, 0.08243866]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.977325439453125, + 'right_pupil_posn': array([ 0.19232857, -0.09158385]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08728904277086258, + 'throttle_input': 0.07142747938632965, + 'timestamp': 418.3545576669276, + 'timestamp_carla': 418354, + 'timestamp_device': 4156572, + 'timestamp_stream': 418.3545576669276, + 'transform': [array([-2.07690573e+00, -1.60895367e+01, 1.07080266e-02]), + array([-8.17232057e-02, 7.33433628e+00, 6.65284414e-03])]} +{'AngularVelocity': array([-0.00299006, 0.03829777, 0.53883117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1471250206232071, + 'FR_Wheel_Angle': 0.18962301313877106, + 'Location': array([ -2.12471938, -21.51988029, 0.17205139]), + 'Rotation': array([-0.07049438, 6.00472355, -0.01599121]), + 'Velocity': array([-0.01948256, -0.00226388, 0.00019241]), + 'brake_input': 0.0, + 'camera_location': array([-4.25243759, 13.14276409, 2.22262907]), + 'camera_rotation': array([-9.13236523, -2.91434574, 1.72267592]), + 'current_gear_input': False, + 'focus_actor_dist': 2780.539794921875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.96272888e+02, -2.61520752e+02, 1.52587891e-05]), + 'frame': 12724, + 'frame_number': 12724, + 'framesequence': 48920, + 'gaze_dir': array([0.97472382, 0.192276 , 0.11238861]), + 'gaze_origin': array([-3.06000376, -0.17084503, 0.08624115]), + 'gaze_valid': True, + 'gaze_vergence': 168.0443115234375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97262573, 0.20722961, 0.10498047]), + 'left_gaze_origin': array([-2.98101974, 3.02137303, 0.08987122]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0931396484375, + 'left_pupil_posn': array([ 0.20785856, -0.01043308]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9768219 , 0.17732239, 0.11979675]), + 'right_gaze_origin': array([-3.13898778, -3.3630631 , 0.08261109]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9859619140625, + 'right_pupil_posn': array([ 0.19167721, -0.09167004]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09054841846227646, + 'throttle_input': 0.0158693827688694, + 'timestamp': 418.3877343684435, + 'timestamp_carla': 418388, + 'timestamp_device': 4156605, + 'timestamp_stream': 418.3877343684435, + 'transform': [array([-2.14156699e+00, -1.59863977e+01, 1.05932802e-02]), + array([-8.22696239e-02, 7.53512144e+00, 7.20216148e-03])]} +{'AngularVelocity': array([-0.00924825, 0.04296159, 0.57709098]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.151639461517334, + 'FR_Wheel_Angle': 2.8839573860168457, + 'Location': array([ -2.12427306, -21.51990509, 0.1720283 ]), + 'Rotation': array([-0.07065147, 6.00691128, -0.01599121]), + 'Velocity': array([-0.02249396, -0.00318945, -0.00046467]), + 'brake_input': 0.0, + 'camera_location': array([-4.26118088, 13.25713348, 2.18402767]), + 'camera_rotation': array([-9.2763319 , -2.87461376, 1.86252928]), + 'current_gear_input': False, + 'focus_actor_dist': 2008.5244140625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-698.48284912, -995.61730957, 37.62610626]), + 'frame': 12725, + 'frame_number': 12725, + 'framesequence': 48924, + 'gaze_dir': array([0.97467041, 0.19229126, 0.11308289]), + 'gaze_origin': array([-3.05764103, -0.16797486, 0.08870011]), + 'gaze_valid': True, + 'gaze_vergence': 179.9911346435547, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97296143, 0.20539856, 0.10554504]), + 'left_gaze_origin': array([-2.97718525, 3.02612019, 0.09430695]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0881500244140625, + 'left_pupil_posn': array([ 0.20527935, -0.00644565]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97637939, 0.17918396, 0.12062073]), + 'right_gaze_origin': array([-3.13809657, -3.36207008, 0.08309326]), + 'right_gaze_valid': True, + 'right_pupil_diam': 2.9919891357421875, + 'right_pupil_posn': array([ 0.19031489, -0.09096766]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09137242287397385, + 'throttle_input': 0.0, + 'timestamp': 418.4204599671066, + 'timestamp_carla': 418420, + 'timestamp_device': 4156638, + 'timestamp_stream': 418.4204599671066, + 'transform': [array([-2.20644546e+00, -1.58857031e+01, 1.04768937e-02]), + array([-0.08194178, 7.73634577, 0.00787355])]} +{'AngularVelocity': array([ 0.02971826, -0.035803 , -0.4200947 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.468511581420898, + 'FR_Wheel_Angle': 8.886069297790527, + 'Location': array([ -2.12453723, -21.51999664, 0.17205077]), + 'Rotation': array([-0.07049438, 6.00359583, -0.01602173]), + 'Velocity': array([ 1.66674219e-02, 4.12323698e-03, -6.36577606e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.23397541, 13.36900425, 2.18072534]), + 'camera_rotation': array([-9.29400826, -2.76467013, 2.03531528]), + 'current_gear_input': False, + 'focus_actor_dist': 1133.3876953125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.54943848, -1828.03479004, 78.29779053]), + 'frame': 12726, + 'frame_number': 12726, + 'framesequence': 48928, + 'gaze_dir': array([0.97618866, 0.18564606, 0.1109848 ]), + 'gaze_origin': array([-3.05452895, -0.1634514 , 0.08177262]), + 'gaze_valid': True, + 'gaze_vergence': 181.00030517578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97428894, 0.19967651, 0.10420227]), + 'left_gaze_origin': array([-2.97303176, 3.02826238, 0.08408356]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2554931640625, + 'left_pupil_posn': array([ 0.20110142, -0.01349795]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97808838, 0.1716156 , 0.11776733]), + 'right_gaze_origin': array([-3.13602614, -3.35516524, 0.07946168]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0907135009765625, + 'right_pupil_posn': array([ 0.18337464, -0.09365833]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09126255661249161, + 'throttle_input': 0.0, + 'timestamp': 418.454626865685, + 'timestamp_carla': 418455, + 'timestamp_device': 4156671, + 'timestamp_stream': 418.454626865685, + 'transform': [array([-2.27410412e+00, -1.57818327e+01, 1.03263278e-02]), + array([-0.08089676, 7.94493103, 0.00872804])]} +{'AngularVelocity': array([ 0.04343603, -0.03576367, -0.38170087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.4978609085083, + 'FR_Wheel_Angle': 13.55959415435791, + 'Location': array([ -2.12615442, -21.52038574, 0.17204662]), + 'Rotation': array([-0.07059 , 5.99936914, -0.01602173]), + 'Velocity': array([ 0.01113072, 0.00431471, -0.00018844]), + 'brake_input': 0.0, + 'camera_location': array([-4.21037102, 13.49276543, 2.20214128]), + 'camera_rotation': array([-9.19901466, -2.54890561, 2.2480967 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1121.8187255859375, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -466.15512085, -1828.6932373 , 75.53860474]), + 'frame': 12727, + 'frame_number': 12727, + 'framesequence': 48932, + 'gaze_dir': array([0.9769516 , 0.17962646, 0.11446381]), + 'gaze_origin': array([-3.04025888, -0.15526429, 0.07817536]), + 'gaze_valid': True, + 'gaze_vergence': 190.27392578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97583008, 0.19073486, 0.10664368]), + 'left_gaze_origin': array([-2.94763207, 3.0371201 , 0.07708436]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2025146484375, + 'left_pupil_posn': array([ 0.19375193, -0.01209605]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.97807312, 0.16851807, 0.12228394]), + 'right_gaze_origin': array([-3.13288617, -3.34764862, 0.07926636]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.13372802734375, + 'right_pupil_posn': array([ 0.17501676, -0.09209502]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.09078646451234818, + 'throttle_input': 0.0, + 'timestamp': 418.48767886683345, + 'timestamp_carla': 418488, + 'timestamp_device': 4156705, + 'timestamp_stream': 418.48767886683345, + 'transform': [array([-2.33913779e+00, -1.56827040e+01, 1.01761241e-02]), + array([-0.07949657, 8.14422226, 0.00967409])]} +{'AngularVelocity': array([ 0.05628718, -0.03383428, -0.36853439]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.581787109375, + 'FR_Wheel_Angle': 17.367605209350586, + 'Location': array([ -2.12945962, -21.52120018, 0.17204571]), + 'Rotation': array([-0.07065147, 5.98541355, -0.01602173]), + 'Velocity': array([ 0.00346905, 0.00347184, -0.00022063]), + 'brake_input': 0.0, + 'camera_location': array([-4.20932579, 13.60205078, 2.17751622]), + 'camera_rotation': array([-9.28555298, -2.22129035, 2.39475203]), + 'current_gear_input': False, + 'focus_actor_dist': 2726.78759765625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-9.12476440e+02, -2.77612793e+02, 1.52587891e-05]), + 'frame': 12728, + 'frame_number': 12728, + 'framesequence': 48936, + 'gaze_dir': array([0.97914886, 0.16990662, 0.11057281]), + 'gaze_origin': array([-3.05694747, -0.14746934, 0.08367767]), + 'gaze_valid': True, + 'gaze_vergence': 216.14932250976562, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97813416, 0.18009949, 0.10385132]), + 'left_gaze_origin': array([-2.97858596, 3.04555678, 0.08721925]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.207366943359375, + 'left_pupil_posn': array([ 0.18532181, -0.01246095]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98016357, 0.15971375, 0.11729431]), + 'right_gaze_origin': array([-3.13530898, -3.34049535, 0.08013611]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1580047607421875, + 'right_pupil_posn': array([ 0.16640532, -0.09274662]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08988922089338303, + 'throttle_input': 0.0, + 'timestamp': 418.5219509676099, + 'timestamp_carla': 418522, + 'timestamp_device': 4156738, + 'timestamp_stream': 418.5219509676099, + 'transform': [array([-2.40571856e+00, -1.55813837e+01, 1.00143431e-02]), + array([-0.07791879, 8.34674644, 0.01065065])]} +{'AngularVelocity': array([ 0.05938019, -0.0301137 , -0.37145108]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.60772132873535, + 'FR_Wheel_Angle': 19.91025161743164, + 'Location': array([ -2.13465214, -21.52256775, 0.1720583 ]), + 'Rotation': array([-0.07073344, 5.95679808, -0.01599121]), + 'Velocity': array([-0.0066713 , 0.00091001, 0.00034158]), + 'brake_input': 0.0, + 'camera_location': array([-4.21150875, 13.66623783, 2.17788625]), + 'camera_rotation': array([-9.3314724 , -1.92764664, 2.86269331]), + 'current_gear_input': False, + 'focus_actor_dist': 1101.138671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -465.89416504, -1828.23217773, 75.23396301]), + 'frame': 12729, + 'frame_number': 12729, + 'framesequence': 48940, + 'gaze_dir': array([0.97968292, 0.161026 , 0.1187973 ]), + 'gaze_origin': array([-3.04809594, -0.14312287, 0.08113098]), + 'gaze_valid': True, + 'gaze_vergence': 233.23509216308594, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97831726, 0.17271423, 0.11421204]), + 'left_gaze_origin': array([-2.978827 , 3.04993773, 0.08526765]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2307891845703125, + 'left_pupil_posn': array([ 0.17878985, -0.01164913]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98104858, 0.14933777, 0.12338257]), + 'right_gaze_origin': array([-3.11736465, -3.33618331, 0.07699433]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.069000244140625, + 'right_pupil_posn': array([ 0.16049719, -0.08757019]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08860743790864944, + 'throttle_input': 0.0, + 'timestamp': 418.55475736781955, + 'timestamp_carla': 418555, + 'timestamp_device': 4156771, + 'timestamp_stream': 418.55475736781955, + 'transform': [array([-2.46849465e+00, -1.54858093e+01, 9.89330281e-03]), + array([-0.07636151, 8.5362463 , 0.01150514])]} +{'AngularVelocity': array([-0.04543415, -0.01669699, -1.14294243]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.45732307434082, + 'FR_Wheel_Angle': 20.939870834350586, + 'Location': array([ -2.15283632, -21.52747726, 0.17209999]), + 'Rotation': array([-0.07504328, 5.8354845 , -0.01296997]), + 'Velocity': array([-0.12569335, -0.04605446, 0.00068988]), + 'brake_input': 0.0, + 'camera_location': array([-4.22988319, 13.68753433, 2.17601085]), + 'camera_rotation': array([-9.33440208, -1.7846328 , 3.19257283]), + 'current_gear_input': False, + 'focus_actor_dist': 2752.621826171875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-924.57495117, -232.48364258, 0. ]), + 'frame': 12730, + 'frame_number': 12730, + 'framesequence': 48944, + 'gaze_dir': array([0.98013306, 0.15922546, 0.11756897]), + 'gaze_origin': array([-3.04963779, -0.14130327, 0.0826973 ]), + 'gaze_valid': True, + 'gaze_vergence': 248.7335205078125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97860718, 0.17095947, 0.11437988]), + 'left_gaze_origin': array([-2.98426223, 3.05165267, 0.0878067 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.268096923828125, + 'left_pupil_posn': array([ 0.17700076, -0.01192236]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98165894, 0.14749146, 0.12075806]), + 'right_gaze_origin': array([-3.11501312, -3.33425927, 0.0775879 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.096435546875, + 'right_pupil_posn': array([ 0.1584425 , -0.08686578]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08666646480560303, + 'throttle_input': 0.0, + 'timestamp': 418.58802796527743, + 'timestamp_carla': 418588, + 'timestamp_device': 4156805, + 'timestamp_stream': 418.58802796527743, + 'transform': [array([-2.53078794e+00, -1.53902960e+01, 9.78790224e-03]), + array([-0.07477008, 8.72250938, 0.01226808])]} +{'AngularVelocity': array([-0.00604795, -0.05715977, -3.17853546]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.726903915405273, + 'FR_Wheel_Angle': 21.24238395690918, + 'Location': array([ -2.23567557, -21.54910088, 0.17223743]), + 'Rotation': array([-0.08285702, 5.28092241, -0.00808716]), + 'Velocity': array([-0.43462306, -0.13923548, 0.0005348 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.25002289, 13.71142673, 2.18166924]), + 'camera_rotation': array([-9.28577137, -1.77083194, 3.17986274]), + 'current_gear_input': False, + 'focus_actor_dist': 1081.944091796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.30715942, -1827.87060547, 80.68212891]), + 'frame': 12731, + 'frame_number': 12731, + 'framesequence': 48948, + 'gaze_dir': array([0.98025513, 0.15963745, 0.11606598]), + 'gaze_origin': array([-3.05465341, -0.13963014, 0.08421784]), + 'gaze_valid': True, + 'gaze_vergence': 278.7850036621094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97885132, 0.17019653, 0.11340332]), + 'left_gaze_origin': array([-2.9918139 , 3.05348086, 0.09063416]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2436981201171875, + 'left_pupil_posn': array([ 0.1763947 , -0.01202595]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98165894, 0.14907837, 0.11872864]), + 'right_gaze_origin': array([-3.11749268, -3.33274078, 0.07780152]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.10546875, + 'right_pupil_posn': array([ 0.1571933 , -0.08749235]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.08419446647167206, + 'throttle_input': 0.0, + 'timestamp': 418.62061896547675, + 'timestamp_carla': 418621, + 'timestamp_device': 4156838, + 'timestamp_stream': 418.62061896547675, + 'transform': [array([-2.59022999e+00, -1.52980881e+01, 9.71355382e-03]), + array([-0.07317864, 8.89833641, 0.01290895])]} +{'AngularVelocity': array([ 0.08953827, -0.03871807, -3.27739811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.698026657104492, + 'FR_Wheel_Angle': 21.168872833251953, + 'Location': array([ -2.36790943, -21.58241081, 0.17234001]), + 'Rotation': array([-0.07721528, 4.377913 , -0.0123291 ]), + 'Velocity': array([-0.53461546, -0.14752471, 0.00056141]), + 'brake_input': 0.0, + 'camera_location': array([-4.25285339, 13.71542358, 2.19913125]), + 'camera_rotation': array([-9.17852402, -1.77026594, 3.22443342]), + 'current_gear_input': False, + 'focus_actor_dist': 1061.4951171875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.40994263, -1838.85632324, 81.04525757]), + 'frame': 12732, + 'frame_number': 12732, + 'framesequence': 48952, + 'gaze_dir': array([0.98071289, 0.15833282, 0.11397552]), + 'gaze_origin': array([-3.05465341, -0.13884735, 0.08401947]), + 'gaze_valid': True, + 'gaze_vergence': 276.8200378417969, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9793396 , 0.16888428, 0.11112976]), + 'left_gaze_origin': array([-2.9918139 , 3.05434585, 0.09051209]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.24456787109375, + 'left_pupil_posn': array([ 0.17535281, -0.01274538]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98208618, 0.14778137, 0.11682129]), + 'right_gaze_origin': array([-3.11749268, -3.33204055, 0.07752686]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.108978271484375, + 'right_pupil_posn': array([ 0.15623581, -0.08845246]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0811731368303299, + 'throttle_input': 0.0, + 'timestamp': 418.65416676551104, + 'timestamp_carla': 418654, + 'timestamp_device': 4156871, + 'timestamp_stream': 418.65416676551104, + 'transform': [array([-2.64943719e+00, -1.52045507e+01, 9.66041535e-03]), + array([-0.07149842, 9.07116604, 0.01342775])]} +{'AngularVelocity': array([-0.08684773, 0.10694338, -4.16247225]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.01081657409668, + 'FR_Wheel_Angle': 19.867094039916992, + 'Location': array([ -2.49049687, -21.61133194, 0.17242694]), + 'Rotation': array([-0.07464714, 3.5536387 , -0.01470947]), + 'Velocity': array([-6.40311122e-01, -1.62988544e-01, 4.76741785e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.25835514, 13.7164259 , 2.20626664]), + 'camera_rotation': array([-9.16881084, -1.78384757, 3.33104134]), + 'current_gear_input': False, + 'focus_actor_dist': 1047.7156982421875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.13424683, -1843.10119629, 81.40644836]), + 'frame': 12733, + 'frame_number': 12733, + 'framesequence': 48956, + 'gaze_dir': array([0.9809494 , 0.15692139, 0.11388397]), + 'gaze_origin': array([-3.05600905, -0.13777009, 0.08414841]), + 'gaze_valid': True, + 'gaze_vergence': 277.90179443359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97935486, 0.16795349, 0.11242676]), + 'left_gaze_origin': array([-2.99543476, 3.055794 , 0.0915268 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.244964599609375, + 'left_pupil_posn': array([ 0.17374969, -0.01318681]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98254395, 0.14588928, 0.11534119]), + 'right_gaze_origin': array([-3.11658335, -3.33133411, 0.07677002]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.114959716796875, + 'right_pupil_posn': array([ 0.15540266, -0.08832884]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07685171067714691, + 'throttle_input': 0.0, + 'timestamp': 418.68726206570864, + 'timestamp_carla': 418687, + 'timestamp_device': 4156905, + 'timestamp_stream': 418.68726206570864, + 'transform': [array([-2.70543027e+00, -1.51135740e+01, 9.64855216e-03]), + array([-0.06973623, 9.2318964 , 0.01379396])]} +{'AngularVelocity': array([ 0.05147169, -0.06970334, -4.13456154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.042268753051758, + 'FR_Wheel_Angle': 18.922056198120117, + 'Location': array([ -2.63724422, -21.64117432, 0.17255306]), + 'Rotation': array([-0.07623174, 2.66855145, -0.01501465]), + 'Velocity': array([-7.03285515e-01, -1.59921020e-01, 2.31389989e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.24771309, 13.69399834, 2.2076087 ]), + 'camera_rotation': array([-9.14981651, -1.85258305, 3.42142963]), + 'current_gear_input': False, + 'focus_actor_dist': 1036.0054931640625, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.27398682, -1845.15576172, 81.83235168]), + 'frame': 12734, + 'frame_number': 12734, + 'framesequence': 48960, + 'gaze_dir': array([0.98105621, 0.15435028, 0.11621857]), + 'gaze_origin': array([-3.04684687, -0.13397142, 0.07941056]), + 'gaze_valid': True, + 'gaze_vergence': 221.51577758789062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97969055, 0.16668701, 0.11138916]), + 'left_gaze_origin': array([-2.97943592, 3.06061125, 0.08326264]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2763214111328125, + 'left_pupil_posn': array([ 0.16901183, -0.01390457]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98242188, 0.14201355, 0.12104797]), + 'right_gaze_origin': array([-3.11425805, -3.32855392, 0.07555848]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.12109375, + 'right_pupil_posn': array([ 0.15298355, -0.08907974]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.07240211218595505, + 'throttle_input': 0.0, + 'timestamp': 418.7209095656872, + 'timestamp_carla': 418721, + 'timestamp_device': 4156938, + 'timestamp_stream': 418.7209095656872, + 'transform': [array([-2.75962329e+00, -1.50223532e+01, 9.65400692e-03]), + array([-0.06789891, 9.38438416, 0.01406862])]} +{'AngularVelocity': array([-0.05975854, -0.00836167, -2.61062551]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.661998748779297, + 'FR_Wheel_Angle': 19.72987174987793, + 'Location': array([ -2.78374434, -21.66903496, 0.17265961]), + 'Rotation': array([-0.05893087, 1.76961601, -0.02163696]), + 'Velocity': array([-3.60915720e-01, -8.81553441e-02, 6.15024546e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.2534008 , 13.6613884 , 2.20925331]), + 'camera_rotation': array([-9.16232967, -2.02873182, 3.47620654]), + 'current_gear_input': False, + 'focus_actor_dist': 1040.8475341796875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -472.8944397 , -1830.80102539, 84.16643524]), + 'frame': 12735, + 'frame_number': 12735, + 'framesequence': 48964, + 'gaze_dir': array([0.98109436, 0.15603638, 0.11358643]), + 'gaze_origin': array([-3.04781818, -0.13393708, 0.07985993]), + 'gaze_valid': True, + 'gaze_vergence': 231.59193420410156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97953796, 0.16850281, 0.10990906]), + 'left_gaze_origin': array([-2.98360753, 3.0598712 , 0.08529358]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.272979736328125, + 'left_pupil_posn': array([ 0.17006469, -0.01461637]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98265076, 0.14356995, 0.11726379]), + 'right_gaze_origin': array([-3.11202884, -3.3277452 , 0.07442627]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.16668701171875, + 'right_pupil_posn': array([ 0.15297413, -0.09004772]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06793420761823654, + 'throttle_input': 0.0, + 'timestamp': 418.75542356818914, + 'timestamp_carla': 418755, + 'timestamp_device': 4156971, + 'timestamp_stream': 418.75542356818914, + 'transform': [array([-2.81233215e+00, -1.49300842e+01, 9.68082435e-03]), + array([-0.06612989, 9.52935982, 0.01422121])]} +{'AngularVelocity': array([ 0.001611 , 0.03617028, -0.3957229 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.247237205505371, + 'FR_Wheel_Angle': 15.705754280090332, + 'Location': array([ -2.84336948, -21.68008423, 0.17273544]), + 'Rotation': array([-0.06051547, 1.41940069, -0.02093505]), + 'Velocity': array([-0.2196281 , -0.04189096, 0.0006725 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.25947094, 13.62158012, 2.18062496]), + 'camera_rotation': array([-9.19742298, -2.20390439, 3.35183764]), + 'current_gear_input': False, + 'focus_actor_dist': 1023.0317993164062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -470.88366699, -1838.99707031, 81.92480469]), + 'frame': 12736, + 'frame_number': 12736, + 'framesequence': 48968, + 'gaze_dir': array([0.9814682 , 0.15679169, 0.10923767]), + 'gaze_origin': array([-3.04981399, -0.13684312, 0.07803803]), + 'gaze_valid': True, + 'gaze_vergence': 232.57101440429688, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.979599 , 0.16989136, 0.10719299]), + 'left_gaze_origin': array([-2.97856164, 3.05730748, 0.08181611]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2069091796875, + 'left_pupil_posn': array([ 0.17183852, -0.01779461]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9833374 , 0.14369202, 0.11128235]), + 'right_gaze_origin': array([-3.12106657, -3.33099365, 0.07425995]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.24603271484375, + 'right_pupil_posn': array([ 0.15587842, -0.09290516]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06399732083082199, + 'throttle_input': 0.0, + 'timestamp': 418.7877654656768, + 'timestamp_carla': 418788, + 'timestamp_device': 4157005, + 'timestamp_stream': 418.7877654656768, + 'transform': [array([-2.85940242e+00, -1.48447895e+01, 9.73787252e-03]), + array([-0.06469555, 9.65613174, 0.01428224])]} +{'AngularVelocity': array([-0.06732374, 0.0207037 , -0.81646651]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.234432220458984, + 'FR_Wheel_Angle': 16.91901397705078, + 'Location': array([ -2.87931657, -21.68594933, 0.17276622]), + 'Rotation': array([-0.06390325, 1.25944471, -0.01818847]), + 'Velocity': array([-0.10843399, -0.02515193, -0.00015367]), + 'brake_input': 0.0, + 'camera_location': array([-4.23692417, 13.5688076 , 2.17847848]), + 'camera_rotation': array([-9.11036491, -2.29005718, 3.48338914]), + 'current_gear_input': False, + 'focus_actor_dist': 1008.6196899414062, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.38180542, -1843.49328613, 77.97904968]), + 'frame': 12737, + 'frame_number': 12737, + 'framesequence': 48972, + 'gaze_dir': array([0.98097229, 0.16091156, 0.10788727]), + 'gaze_origin': array([-3.05177021, -0.13738708, 0.0779831 ]), + 'gaze_valid': True, + 'gaze_vergence': 222.0791473388672, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97998047, 0.17124939, 0.10153198]), + 'left_gaze_origin': array([-2.97971058, 3.05717635, 0.0830536 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.30389404296875, + 'left_pupil_posn': array([ 0.17427289, -0.01647556]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98196411, 0.15057373, 0.11424255]), + 'right_gaze_origin': array([-3.12382984, -3.33195066, 0.0729126 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.202239990234375, + 'right_pupil_posn': array([ 0.15702558, -0.09630895]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06161687523126602, + 'throttle_input': 0.0, + 'timestamp': 418.8223758675158, + 'timestamp_carla': 418822, + 'timestamp_device': 4157038, + 'timestamp_stream': 418.8223758675158, + 'transform': [array([-2.90765691e+00, -1.47547894e+01, 9.77949146e-03]), + array([-0.06359589, 9.78353214, 0.01428224])]} +{'AngularVelocity': array([-0.06849629, 0.0158312 , -0.6893394 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.430871963500977, + 'FR_Wheel_Angle': 19.714927673339844, + 'Location': array([ -2.89743137, -21.68884468, 0.17281437]), + 'Rotation': array([-0.06679925, 1.15838289, -0.01574707]), + 'Velocity': array([-6.29130304e-02, -1.95986424e-02, 2.99167623e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.26101589, 13.53637314, 2.15954232]), + 'camera_rotation': array([-9.27118206, -2.36099458, 3.32866049]), + 'current_gear_input': False, + 'focus_actor_dist': 985.4464721679688, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -468.21606445, -1858.31982422, 78.96299744]), + 'frame': 12738, + 'frame_number': 12738, + 'framesequence': 48976, + 'gaze_dir': array([0.98171234, 0.15684509, 0.10696411]), + 'gaze_origin': array([-3.05317402, -0.1377594 , 0.08351365]), + 'gaze_valid': True, + 'gaze_vergence': 225.2562713623047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98017883, 0.1693573 , 0.10272217]), + 'left_gaze_origin': array([-2.99939299, 3.05776691, 0.09394532]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2987518310546875, + 'left_pupil_posn': array([ 0.17186534, -0.01378155]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98324585, 0.14433289, 0.11120605]), + 'right_gaze_origin': array([-3.10695505, -3.33328581, 0.07308197]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.251983642578125, + 'right_pupil_posn': array([ 0.15680408, -0.09273875]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06086612120270729, + 'throttle_input': 0.0, + 'timestamp': 418.8546516671777, + 'timestamp_carla': 418855, + 'timestamp_device': 4157071, + 'timestamp_stream': 418.8546516671777, + 'transform': [array([-2.95165753e+00, -1.46720610e+01, 9.84001160e-03]), + array([-0.06307679, 9.89859772, 0.0142212 ])]} +{'AngularVelocity': array([-0.06670695, 0.01009458, -0.62826347]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.523813247680664, + 'FR_Wheel_Angle': 21.073307037353516, + 'Location': array([ -2.90907311, -21.69091225, 0.17284042]), + 'Rotation': array([-0.06878683, 1.08460009, -0.0145874 ]), + 'Velocity': array([-0.04610709, -0.01721806, 0.00024314]), + 'brake_input': 0.0, + 'camera_location': array([-4.2965498 , 13.50217247, 2.17266846]), + 'camera_rotation': array([-9.3503437 , -2.286484 , 3.28418803]), + 'current_gear_input': False, + 'focus_actor_dist': 986.5100708007812, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -467.11859131, -1847.28137207, 75.81648254]), + 'frame': 12739, + 'frame_number': 12739, + 'framesequence': 48980, + 'gaze_dir': array([0.98196411, 0.15719604, 0.10360718]), + 'gaze_origin': array([-3.04564071, -0.13757402, 0.07637482]), + 'gaze_valid': True, + 'gaze_vergence': 152.48838806152344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98085022, 0.17073059, 0.09368896]), + 'left_gaze_origin': array([-2.97599649, 3.058043 , 0.08101349]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2486724853515625, + 'left_pupil_posn': array([ 0.1712662 , -0.01728749]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.983078 , 0.1436615 , 0.11352539]), + 'right_gaze_origin': array([-3.11528492, -3.33319116, 0.07173614]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.22991943359375, + 'right_pupil_posn': array([ 0.15739751, -0.09824395]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06086612120270729, + 'throttle_input': 0.0, + 'timestamp': 418.88712076842785, + 'timestamp_carla': 418887, + 'timestamp_device': 4157105, + 'timestamp_stream': 418.88712076842785, + 'transform': [array([-2.99530625e+00, -1.45900383e+01, 9.89803299e-03]), + array([-0.06295385, 10.01208687, 0.01409914])]} +{'AngularVelocity': array([-0.06774899, 0.00734781, -0.61281693]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.741849899291992, + 'FR_Wheel_Angle': 21.25558090209961, + 'Location': array([ -2.9182632 , -21.69260025, 0.17285442]), + 'Rotation': array([-0.06976355, 1.02322114, -0.0140686 ]), + 'Velocity': array([-4.02162150e-02, -1.62260309e-02, 7.82966599e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.28166008, 13.48153114, 2.23903203]), + 'camera_rotation': array([-9.11395168, -2.21198106, 3.00810623]), + 'current_gear_input': False, + 'focus_actor_dist': 955.067138671875, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -462.82629395, -1870.07910156, 73.37606049]), + 'frame': 12740, + 'frame_number': 12740, + 'framesequence': 48984, + 'gaze_dir': array([0.9821167 , 0.15636444, 0.10393524]), + 'gaze_origin': array([-3.05090189, -0.13721696, 0.07541657]), + 'gaze_valid': True, + 'gaze_vergence': 200.1318359375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98092651, 0.16833496, 0.09716797]), + 'left_gaze_origin': array([-2.9841218 , 3.05826283, 0.08129273]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.29052734375, + 'left_pupil_posn': array([ 0.17140305, -0.01963794]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98330688, 0.14439392, 0.11070251]), + 'right_gaze_origin': array([-3.11768198, -3.33269691, 0.0695404 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2439727783203125, + 'right_pupil_posn': array([ 0.15629411, -0.09896171]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06092105060815811, + 'throttle_input': 0.0, + 'timestamp': 418.92121186852455, + 'timestamp_carla': 418921, + 'timestamp_device': 4157138, + 'timestamp_stream': 418.92121186852455, + 'transform': [array([-3.04064083e+00, -1.45052147e+01, 9.94426664e-03]), + array([-0.06301532, 10.12947273, 0.01394655])]} +{'AngularVelocity': array([ 0.06692731, -0.00187393, 0.07719532]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.73862648010254, + 'FR_Wheel_Angle': 21.250564575195312, + 'Location': array([ -2.92720819, -21.69413948, 0.17286667]), + 'Rotation': array([-0.07043291, 0.96683854, -0.01419067]), + 'Velocity': array([-3.95086892e-02, -1.11291523e-03, -7.05719003e-07]), + 'brake_input': 0.0, + 'camera_location': array([-4.27301121, 13.48265648, 2.26469541]), + 'camera_rotation': array([-8.99312496, -2.15485501, 2.70664477]), + 'current_gear_input': False, + 'focus_actor_dist': 959.9591064453125, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -467.84771729, -1857.21166992, 78.08253479]), + 'frame': 12741, + 'frame_number': 12741, + 'framesequence': 48988, + 'gaze_dir': array([0.98223114, 0.15598297, 0.10338593]), + 'gaze_origin': array([-3.05089426, -0.13670503, 0.07452164]), + 'gaze_valid': True, + 'gaze_vergence': 204.9769744873047, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98094177, 0.16822815, 0.09716797]), + 'left_gaze_origin': array([-2.98357105, 3.05875707, 0.08055726]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.309173583984375, + 'left_pupil_posn': array([ 0.170838 , -0.02038288]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98352051, 0.14373779, 0.10960388]), + 'right_gaze_origin': array([-3.11821747, -3.33216715, 0.06848603]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2394866943359375, + 'right_pupil_posn': array([ 0.15590405, -0.09978211]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06090274080634117, + 'throttle_input': 0.0, + 'timestamp': 418.95440746843815, + 'timestamp_carla': 418954, + 'timestamp_device': 4157171, + 'timestamp_stream': 418.95440746843815, + 'transform': [array([-3.08436203e+00, -1.44238644e+01, 1.00057600e-02]), + array([-0.06313827, 10.24231625, 0.01376344])]} +{'AngularVelocity': array([ 0.06478251, -0.00403693, 0.02892868]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.736936569213867, + 'FR_Wheel_Angle': 21.24808120727539, + 'Location': array([ -2.93789029, -21.69603539, 0.17288299]), + 'Rotation': array([-0.07065147, 0.89358395, -0.0140686 ]), + 'Velocity': array([-0.0456918 , -0.00265818, 0.00012062]), + 'brake_input': 0.0, + 'camera_location': array([-4.29213238, 13.47711754, 2.26510906]), + 'camera_rotation': array([-8.96948624, -2.17863321, 2.58717752]), + 'current_gear_input': False, + 'focus_actor_dist': 951.6405639648438, + 'focus_actor_name': 'Vh_Car_NissanPatrolST22', + 'focus_actor_pt': array([ -469.18508911, -1856.87866211, 80.87270355]), + 'frame': 12742, + 'frame_number': 12742, + 'framesequence': 48992, + 'gaze_dir': array([0.98459625, 0.13925171, 0.10531616]), + 'gaze_origin': array([-3.08725524, -0.12195053, 0.09247056]), + 'gaze_valid': True, + 'gaze_vergence': 323.2625732421875, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98405457, 0.14637756, 0.10093689]), + 'left_gaze_origin': array([-3.0132525 , 3.07307291, 0.09659882]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2811279296875, + 'left_pupil_posn': array([ 0.15742087, -0.01480496]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98513794, 0.13212585, 0.10969543]), + 'right_gaze_origin': array([-3.16125822, -3.31697392, 0.08834229]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2063446044921875, + 'right_pupil_posn': array([ 0.13913572, -0.09238994]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.06053651496767998, + 'throttle_input': 0.0, + 'timestamp': 418.98722006753087, + 'timestamp_carla': 418987, + 'timestamp_device': 4157205, + 'timestamp_stream': 418.98722006753087, + 'transform': [array([-3.12705588e+00, -1.43446369e+01, 1.00774765e-02]), + array([-0.06320657, 10.35198689, 0.01354982])]} +{'AngularVelocity': array([ 0.06695653, -0.00498236, -0.00414336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.735219955444336, + 'FR_Wheel_Angle': 21.245376586914062, + 'Location': array([ -2.95005965, -21.69817352, 0.17288765]), + 'Rotation': array([-0.07073344, 0.81079245, -0.01400757]), + 'Velocity': array([-5.19074127e-02, -3.76972673e-03, 2.42233273e-05]), + 'brake_input': 0.0, + 'camera_location': array([-4.29811001, 13.46481323, 2.25557089]), + 'camera_rotation': array([-8.97432137, -2.28245306, 2.74324918]), + 'current_gear_input': False, + 'focus_actor_dist': 1837.2996826171875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-705.84411621, -995.63696289, 34.23441315]), + 'frame': 12743, + 'frame_number': 12743, + 'framesequence': 48996, + 'gaze_dir': array([0.98469543, 0.1401062 , 0.10301208]), + 'gaze_origin': array([-3.0686264 , -0.12282181, 0.08460084]), + 'gaze_valid': True, + 'gaze_vergence': 275.0157775878906, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98370361, 0.15002441, 0.09907532]), + 'left_gaze_origin': array([-3.00172734, 3.07215571, 0.08969422]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3343658447265625, + 'left_pupil_posn': array([ 0.15723634, -0.01836681]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98568726, 0.13018799, 0.10694885]), + 'right_gaze_origin': array([-3.1355257 , -3.31779933, 0.07950745]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.306121826171875, + 'right_pupil_posn': array([ 0.14020133, -0.0945946 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05943785235285759, + 'throttle_input': 0.0, + 'timestamp': 419.0210754685104, + 'timestamp_carla': 419021, + 'timestamp_device': 4157238, + 'timestamp_stream': 419.0210754685104, + 'transform': [array([-3.17025757e+00, -1.42640839e+01, 1.01509094e-02]), + array([-0.06311095, 10.46198845, 0.01330568])]} +{'AngularVelocity': array([-0.02835349, 0.07607638, -3.30420423]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.64426040649414, + 'FR_Wheel_Angle': 21.08074951171875, + 'Location': array([ -2.98110676, -21.70345116, 0.17299625]), + 'Rotation': array([-0.08358785, 0.60261291, -0.00506592]), + 'Velocity': array([-0.35557762, -0.0726342 , 0.00083165]), + 'brake_input': 0.0, + 'camera_location': array([-4.29217911, 13.44171047, 2.25363851]), + 'camera_rotation': array([-8.96776485, -2.49509859, 2.91048741]), + 'current_gear_input': False, + 'focus_actor_dist': 2073.024169921875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-776.05828857, -762.6315918 , 15.23406219]), + 'frame': 12744, + 'frame_number': 12744, + 'framesequence': 49000, + 'gaze_dir': array([0.98365021, 0.14226532, 0.10902405]), + 'gaze_origin': array([-3.03724766, -0.12687835, 0.07246476]), + 'gaze_valid': True, + 'gaze_vergence': 172.47372436523438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98219299, 0.15756226, 0.10221863]), + 'left_gaze_origin': array([-2.99065256, 3.06807876, 0.08455506]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2869415283203125, + 'left_pupil_posn': array([ 0.15885985, -0.01661777]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98510742, 0.12696838, 0.11582947]), + 'right_gaze_origin': array([-3.08384252, -3.32183552, 0.06037445]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3258819580078125, + 'right_pupil_posn': array([ 0.14413869, -0.09725237]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05705741047859192, + 'throttle_input': 0.0, + 'timestamp': 419.05439856648445, + 'timestamp_carla': 419054, + 'timestamp_device': 4157271, + 'timestamp_stream': 419.05439856648445, + 'transform': [array([-3.21150708e+00, -1.41859198e+01, 1.02442931e-02]), + array([-0.06274211, 10.56550026, 0.01303102])]} +{'AngularVelocity': array([ 0.03246803, -0.05719285, -3.32428551]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.636178970336914, + 'FR_Wheel_Angle': 21.13971519470215, + 'Location': array([ -3.1086843 , -21.72439384, 0.17310162]), + 'Rotation': array([-0.08010446, -0.24981688, -0.00787354]), + 'Velocity': array([-5.17466903e-01, -1.01760864e-01, 2.23054885e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.29144478, 13.42959785, 2.24609852]), + 'camera_rotation': array([-9.07714367, -2.7435832 , 2.98094034]), + 'current_gear_input': False, + 'focus_actor_dist': 2581.9189453125, + 'focus_actor_name': 'Road_Marking_Town05_132', + 'focus_actor_pt': array([-9.24003296e+02, -2.66903809e+02, -1.52587891e-05]), + 'frame': 12745, + 'frame_number': 12745, + 'framesequence': 49004, + 'gaze_dir': array([0.98394775, 0.1434021 , 0.10496521]), + 'gaze_origin': array([-3.03127527, -0.12780534, 0.07003555]), + 'gaze_valid': True, + 'gaze_vergence': 189.3243408203125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98249817, 0.15763855, 0.09907532]), + 'left_gaze_origin': array([-2.98570728, 3.06714201, 0.08271942]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.31341552734375, + 'left_pupil_posn': array([ 0.16016972, -0.01874101]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98539734, 0.12916565, 0.1108551 ]), + 'right_gaze_origin': array([-3.07684326, -3.32275248, 0.05735169]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.343902587890625, + 'right_pupil_posn': array([ 0.1445837 , -0.09904671]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.05390789732336998, + 'throttle_input': 0.0, + 'timestamp': 419.0885572656989, + 'timestamp_carla': 419088, + 'timestamp_device': 4157305, + 'timestamp_stream': 419.0885572656989, + 'transform': [array([-3.25201654e+00, -1.41068783e+01, 1.03453631e-02]), + array([-0.06210008, 10.66487598, 0.01272584])]} +{'AngularVelocity': array([-4.00416460e-03, 1.24083506e-02, -4.21368504e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.64322853088379, + 'FR_Wheel_Angle': 21.118392944335938, + 'Location': array([ -3.23756886, -21.74384308, 0.17321678]), + 'Rotation': array([-0.07760461, -1.11431897, -0.00845337]), + 'Velocity': array([-0.62909782, -0.11390572, 0.00085515]), + 'brake_input': 0.0, + 'camera_location': array([-4.26565647, 13.42246723, 2.23882341]), + 'camera_rotation': array([-9.09016895, -2.78407001, 2.98624063]), + 'current_gear_input': False, + 'focus_actor_dist': 2055.457763671875, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-773.70556641, -762.86071777, 15.23403931]), + 'frame': 12746, + 'frame_number': 12746, + 'framesequence': 49008, + 'gaze_dir': array([0.98369598, 0.14411926, 0.10640717]), + 'gaze_origin': array([-3.02242756, -0.12730637, 0.06602021]), + 'gaze_valid': True, + 'gaze_vergence': 177.92054748535156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9825592 , 0.15753174, 0.09873962]), + 'left_gaze_origin': array([-2.97704315, 3.06790018, 0.07888641]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.35894775390625, + 'left_pupil_posn': array([ 0.16010439, -0.01874101]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98483276, 0.13070679, 0.11407471]), + 'right_gaze_origin': array([-3.06781173, -3.3225131 , 0.053154 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.34716796875, + 'right_pupil_posn': array([ 0.14412212, -0.10035658]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.050337232649326324, + 'throttle_input': 0.0, + 'timestamp': 419.12262846529484, + 'timestamp_carla': 419123, + 'timestamp_device': 4157338, + 'timestamp_stream': 419.12262846529484, + 'transform': [array([-3.29049587e+00, -1.40290842e+01, 1.04531860e-02]), + array([-0.06130777, 10.7567234 , 0.01242067])]} +{'AngularVelocity': array([ 0.02568575, -0.04805625, -4.29318237]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.324569702148438, + 'FR_Wheel_Angle': 20.45595359802246, + 'Location': array([ -3.39764118, -21.76493073, 0.17334129]), + 'Rotation': array([-0.07440124, -2.17602539, -0.01065063]), + 'Velocity': array([-6.68022037e-01, -1.07192189e-01, 3.61528393e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.25095272, 13.43776798, 2.22845984]), + 'camera_rotation': array([-9.14023399, -2.76506257, 2.98204494]), + 'current_gear_input': False, + 'focus_actor_dist': 2360.08544921875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-8.65469482e+02, -4.64027344e+02, -1.52587891e-05]), + 'frame': 12747, + 'frame_number': 12747, + 'framesequence': 49012, + 'gaze_dir': array([0.98368073, 0.14378357, 0.10695648]), + 'gaze_origin': array([-3.02034235, -0.12684785, 0.06512146]), + 'gaze_valid': True, + 'gaze_vergence': 178.73680114746094, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98251343, 0.15734863, 0.09945679]), + 'left_gaze_origin': array([-2.97626352, 3.06833339, 0.07860108]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3829345703125, + 'left_pupil_posn': array([ 0.15962052, -0.01870716]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98484802, 0.13021851, 0.11445618]), + 'right_gaze_origin': array([-3.06442118, -3.32202911, 0.05164185]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.343353271484375, + 'right_pupil_posn': array([ 0.14364278, -0.10048902]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.046382032334804535, + 'throttle_input': 0.0, + 'timestamp': 419.1560354679823, + 'timestamp_carla': 419156, + 'timestamp_device': 4157371, + 'timestamp_stream': 419.1560354679823, + 'transform': [array([-3.32624745e+00, -1.39537888e+01, 1.05683133e-02]), + array([-0.060454 , 10.83939838, 0.01211549])]} +{'AngularVelocity': array([ 0.03521422, 0.00882333, -4.25034761]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.418676376342773, + 'FR_Wheel_Angle': 19.176280975341797, + 'Location': array([ -3.55645108, -21.78192902, 0.17351075]), + 'Rotation': array([-0.07495449, -3.16699219, -0.00994873]), + 'Velocity': array([-7.39143133e-01, -9.16287005e-02, 5.67560201e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.25631428, 13.43391323, 2.21264863]), + 'camera_rotation': array([-9.25248814, -2.72598267, 2.98350334]), + 'current_gear_input': False, + 'focus_actor_dist': 1797.2430419921875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-710.45812988, -995.64929199, 32.13247681]), + 'frame': 12748, + 'frame_number': 12748, + 'framesequence': 49016, + 'gaze_dir': array([0.98368835, 0.14407349, 0.10647583]), + 'gaze_origin': array([-3.02130222, -0.12590484, 0.06566315]), + 'gaze_valid': True, + 'gaze_vergence': 171.22471618652344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98269653, 0.15707397, 0.0980072 ]), + 'left_gaze_origin': array([-2.97580266, 3.06976485, 0.07855377]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.392669677734375, + 'left_pupil_posn': array([ 0.15894079, -0.01854813]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98468018, 0.131073 , 0.11494446]), + 'right_gaze_origin': array([-3.06680155, -3.32157469, 0.05277253]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3473663330078125, + 'right_pupil_posn': array([ 0.14329362, -0.1006583 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.0427747443318367, + 'throttle_input': 0.0, + 'timestamp': 419.18794186785817, + 'timestamp_carla': 419188, + 'timestamp_device': 4157405, + 'timestamp_stream': 419.18794186785817, + 'transform': [array([-3.35857773e+00, -1.38827629e+01, 1.06886094e-02]), + array([-0.05969585, 10.9116087 , 0.01181031])]} +{'AngularVelocity': array([-0.04158115, -0.00940346, -4.21642303]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.075396537780762, + 'FR_Wheel_Angle': 17.463153839111328, + 'Location': array([ -3.70500469, -21.79428101, 0.17363952]), + 'Rotation': array([-0.07140962, -4.04278708, -0.01159668]), + 'Velocity': array([-0.70402688, -0.07747035, 0.00087568]), + 'brake_input': 0.0, + 'camera_location': array([-4.25601864, 13.42379951, 2.20010448]), + 'camera_rotation': array([-9.3078804 , -2.75704408, 2.87567306]), + 'current_gear_input': False, + 'focus_actor_dist': 1790.6766357421875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-714.33416748, -995.70446777, 28.16970062]), + 'frame': 12749, + 'frame_number': 12749, + 'framesequence': 49020, + 'gaze_dir': array([0.98355103, 0.14458466, 0.10707092]), + 'gaze_origin': array([-3.02137685, -0.12522583, 0.06566315]), + 'gaze_valid': True, + 'gaze_vergence': 163.11505126953125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98269653, 0.1572876 , 0.09780884]), + 'left_gaze_origin': array([-2.97581935, 3.07066369, 0.07855377]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3930511474609375, + 'left_pupil_posn': array([ 0.15861559, -0.01808071]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98440552, 0.13188171, 0.11633301]), + 'right_gaze_origin': array([-3.06693435, -3.32111526, 0.05277253]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3588104248046875, + 'right_pupil_posn': array([ 0.14304936, -0.10078394]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03892941400408745, + 'throttle_input': 0.0, + 'timestamp': 419.22171556577086, + 'timestamp_carla': 419222, + 'timestamp_device': 4157438, + 'timestamp_stream': 419.22171556577086, + 'transform': [array([-3.39069819e+00, -1.38084974e+01, 1.07908435e-02]), + array([-0.05893087, 10.98016071, 0.01150514])]} +{'AngularVelocity': array([-0.02748881, 0.00416183, -3.5677948 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.189780235290527, + 'FR_Wheel_Angle': 12.271126747131348, + 'Location': array([ -3.86500382, -21.80303383, 0.17379761]), + 'Rotation': array([-0.07073344, -4.89914179, -0.01177978]), + 'Velocity': array([-6.94730103e-01, -4.79807407e-02, 6.45408640e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.23066235, 13.41130066, 2.19155002]), + 'camera_rotation': array([-9.30786037, -2.87435079, 2.82274723]), + 'current_gear_input': False, + 'focus_actor_dist': 1783.652587890625, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-715.72265625, -995.70874023, 28.43058014]), + 'frame': 12750, + 'frame_number': 12750, + 'framesequence': 49024, + 'gaze_dir': array([0.9835968 , 0.14433289, 0.10683441]), + 'gaze_origin': array([-3.02136564, -0.1251419 , 0.06566315]), + 'gaze_valid': True, + 'gaze_vergence': 158.71348571777344, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98268127, 0.15757751, 0.09738159]), + 'left_gaze_origin': array([-2.9757967 , 3.07066369, 0.07855377]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3833160400390625, + 'left_pupil_posn': array([ 0.1583457 , -0.01806331]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98451233, 0.13108826, 0.11628723]), + 'right_gaze_origin': array([-3.06693435, -3.32094717, 0.05277253]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.367156982421875, + 'right_pupil_posn': array([ 0.14303303, -0.1009469 ]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.03374737128615379, + 'throttle_input': 0.0, + 'timestamp': 419.2537247687578, + 'timestamp_carla': 419254, + 'timestamp_device': 4157471, + 'timestamp_stream': 419.2537247687578, + 'transform': [array([-3.41896915e+00, -1.37389393e+01, 1.09012024e-02]), + array([-0.05810441, 11.03706932, 0.01123048])]} +{'AngularVelocity': array([-0.01296882, -0.00146808, -1.35670972]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9299676418304443, + 'FR_Wheel_Angle': 2.865057945251465, + 'Location': array([ -4.02843332, -21.8013134 , 0.17396069]), + 'Rotation': array([-0.07177845, -5.41623259, -0.01629638]), + 'Velocity': array([-7.08778918e-01, 2.60979608e-02, 6.85615523e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.20990181, 13.39613152, 2.17202258]), + 'camera_rotation': array([-9.42291451, -2.9942143 , 2.90153337]), + 'current_gear_input': False, + 'focus_actor_dist': 1775.05810546875, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-712.83374023, -995.70043945, 28.78474426]), + 'frame': 12751, + 'frame_number': 12751, + 'framesequence': 49028, + 'gaze_dir': array([0.98361969, 0.1450119 , 0.10586548]), + 'gaze_origin': array([-3.02366114, -0.12519914, 0.06641388]), + 'gaze_valid': True, + 'gaze_vergence': 162.9958953857422, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.9828186 , 0.1572876 , 0.09646606]), + 'left_gaze_origin': array([-2.97630477, 3.07054901, 0.0792389 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.38287353515625, + 'left_pupil_posn': array([ 0.15899384, -0.01806331]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98442078, 0.13273621, 0.11526489]), + 'right_gaze_origin': array([-3.0710175 , -3.32094717, 0.05358887]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.373046875, + 'right_pupil_posn': array([ 0.14303303, -0.10146499]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.02682577073574066, + 'throttle_input': 0.0, + 'timestamp': 419.28784216567874, + 'timestamp_carla': 419288, + 'timestamp_device': 4157505, + 'timestamp_stream': 419.28784216567874, + 'transform': [array([-3.44597244e+00, -1.36655951e+01, 1.10014342e-02]), + array([-5.69432825e-02, 1.10858946e+01, 1.09558208e-02])]} +{'AngularVelocity': array([-0.01581583, -0.0078841 , 0.48544136]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.054414987564087, + 'FR_Wheel_Angle': -2.657876491546631, + 'Location': array([ -4.21540928, -21.7851696 , 0.17414497]), + 'Rotation': array([-0.07040559, -5.4792819 , -0.01467895]), + 'Velocity': array([-0.68669742, 0.08011614, 0.0009237 ]), + 'brake_input': 0.0, + 'camera_location': array([-4.21347809, 13.37890434, 2.13561749]), + 'camera_rotation': array([-9.58836269, -3.19498014, 3.00400567]), + 'current_gear_input': False, + 'focus_actor_dist': 1900.419189453125, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-749.71539307, -868.95336914, 15.10889435]), + 'frame': 12752, + 'frame_number': 12752, + 'framesequence': 49032, + 'gaze_dir': array([0.98338318, 0.14669037, 0.10569 ]), + 'gaze_origin': array([-3.02428293, -0.12550355, 0.06645203]), + 'gaze_valid': True, + 'gaze_vergence': 159.06753540039062, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98252869, 0.15930176, 0.09606934]), + 'left_gaze_origin': array([-2.97754836, 3.07005763, 0.07931519]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4018096923828125, + 'left_pupil_posn': array([ 0.15978312, -0.01827312]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98423767, 0.13407898, 0.11531067]), + 'right_gaze_origin': array([-3.0710175 , -3.32106495, 0.05358887]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.39208984375, + 'right_pupil_posn': array([ 0.14380217, -0.10166287]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.019244972616434097, + 'throttle_input': 0.0, + 'timestamp': 419.3209798671305, + 'timestamp_carla': 419321, + 'timestamp_device': 4157538, + 'timestamp_stream': 419.3209798671305, + 'transform': [array([-3.46355462e+00, -1.35945969e+01, 1.11707682e-02]), + array([-5.32276630e-02, 1.10997219e+01, 1.07116820e-02])]} +{'AngularVelocity': array([ 0.00877304, -0.00398867, 1.77732205]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.600598335266113, + 'FR_Wheel_Angle': -7.636880874633789, + 'Location': array([ -4.37179756, -21.76430321, 0.17429413]), + 'Rotation': array([-0.06924445, -5.22140789, -0.01296997]), + 'Velocity': array([-6.51756287e-01, 1.11565270e-01, 5.05456934e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.20669556, 13.36481857, 2.10429239]), + 'camera_rotation': array([-9.68456554, -3.46060061, 3.01631761]), + 'current_gear_input': False, + 'focus_actor_dist': 1781.65478515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-715.84448242, -975.01660156, 16.75527191]), + 'frame': 12753, + 'frame_number': 12753, + 'framesequence': 49036, + 'gaze_dir': array([0.98301697, 0.15203094, 0.10202026]), + 'gaze_origin': array([-3.02221775, -0.1290886 , 0.06565094]), + 'gaze_valid': True, + 'gaze_vergence': 213.0723419189453, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98240662, 0.16087341, 0.0947113 ]), + 'left_gaze_origin': array([-2.97016454, 3.06346607, 0.07583008]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4215087890625, + 'left_pupil_posn': array([ 0.16725218, -0.02150476]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98362732, 0.14318848, 0.10932922]), + 'right_gaze_origin': array([-3.07427096, -3.32164311, 0.0554718 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.410308837890625, + 'right_pupil_posn': array([ 0.14482152, -0.10146499]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.010876797139644623, + 'throttle_input': 0.0, + 'timestamp': 419.3542906679213, + 'timestamp_carla': 419354, + 'timestamp_device': 4157571, + 'timestamp_stream': 419.3542906679213, + 'transform': [array([-3.47783709e+00, -1.35239258e+01, 1.12816431e-02]), + array([-5.14176600e-02, 1.11012325e+01, 1.04980543e-02])]} +{'AngularVelocity': array([ 1.67535320e-02, -7.48054066e-04, 2.39438725e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.78563404083252, + 'FR_Wheel_Angle': -10.047740936279297, + 'Location': array([ -4.51937485, -21.74011421, 0.17444679]), + 'Rotation': array([-0.06894393, -4.76361275, -0.01040649]), + 'Velocity': array([-6.20792508e-01, 1.22731157e-01, 5.67960727e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.18712044, 13.35114384, 2.07189155]), + 'camera_rotation': array([-9.70310974, -3.70825076, 3.14373994]), + 'current_gear_input': False, + 'focus_actor_dist': 1640.4749755859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -678.12982178, -1103.85144043, 17.20398712]), + 'frame': 12754, + 'frame_number': 12754, + 'framesequence': 49040, + 'gaze_dir': array([0.98199463, 0.15470886, 0.10769653]), + 'gaze_origin': array([-3.02185845, -0.13033754, 0.06574021]), + 'gaze_valid': True, + 'gaze_vergence': 173.49346923828125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98179626, 0.1622467 , 0.09867859]), + 'left_gaze_origin': array([-2.96542978, 3.06280971, 0.07456513]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4303741455078125, + 'left_pupil_posn': array([ 0.16904247, -0.01908374]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98219299, 0.14717102, 0.11671448]), + 'right_gaze_origin': array([-3.07828689, -3.3234849 , 0.05691529]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.429534912109375, + 'right_pupil_posn': array([ 0.14667404, -0.10000658]), + 'right_pupil_posn_valid': True, + 'steering_input': 0.00018311107123736292, + 'throttle_input': 0.0, + 'timestamp': 419.38850486651063, + 'timestamp_carla': 419388, + 'timestamp_device': 4157605, + 'timestamp_stream': 419.38850486651063, + 'transform': [array([-3.49187684e+00, -1.34523191e+01, 1.13458820e-02]), + array([-5.14518134e-02, 1.11011972e+01, 1.02539156e-02])]} +{'AngularVelocity': array([ 2.07201485e-02, -3.90385481e-04, 2.51394629e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.3999662399292, + 'FR_Wheel_Angle': -10.279122352600098, + 'Location': array([ -4.66300678, -21.71551895, 0.17459583]), + 'Rotation': array([-0.06951766, -4.22992086, -0.00796509]), + 'Velocity': array([-6.11132503e-01, 1.19432449e-01, 4.54416266e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.20084572, 13.35211372, 2.0234983 ]), + 'camera_rotation': array([-9.84449482, -3.86121321, 3.12734628]), + 'current_gear_input': False, + 'focus_actor_dist': 1765.2744140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-713.61523438, -976.39575195, 16.81343079]), + 'frame': 12755, + 'frame_number': 12755, + 'framesequence': 49044, + 'gaze_dir': array([0.98158264, 0.15735626, 0.10787964]), + 'gaze_origin': array([-3.02860188, -0.13180238, 0.06847382]), + 'gaze_valid': True, + 'gaze_vergence': 226.07408142089844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98138428, 0.16334534, 0.10092163]), + 'left_gaze_origin': array([-2.96469736, 3.06304479, 0.07659912]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.35943603515625, + 'left_pupil_posn': array([ 0.17037737, -0.01807296]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98178101, 0.15136719, 0.11483765]), + 'right_gaze_origin': array([-3.09250641, -3.32664967, 0.06034851]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4404144287109375, + 'right_pupil_posn': array([ 0.14961731, -0.09957862]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.010528886690735817, + 'throttle_input': 0.0, + 'timestamp': 419.4203571677208, + 'timestamp_carla': 419420, + 'timestamp_device': 4157638, + 'timestamp_stream': 419.4203571677208, + 'transform': [array([-3.50481319e+00, -1.33865709e+01, 1.14038652e-02]), + array([-5.21826409e-02, 1.11014357e+01, 1.00402934e-02])]} +{'AngularVelocity': array([ 0.0211422 , -0.01381234, 2.31612086]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.402714729309082, + 'FR_Wheel_Angle': -10.281627655029297, + 'Location': array([ -4.80483675, -21.69248199, 0.17475547]), + 'Rotation': array([-0.06961329, -3.70275974, -0.00695801]), + 'Velocity': array([-0.59918737, 0.1106158 , 0.00111811]), + 'brake_input': 0.0, + 'camera_location': array([-4.18477726, 13.34747601, 2.00391078]), + 'camera_rotation': array([-9.81410027, -3.98860836, 3.1276896 ]), + 'current_gear_input': False, + 'focus_actor_dist': 1701.8089599609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -696.83996582, -1030.1862793 , 17.22897339]), + 'frame': 12756, + 'frame_number': 12756, + 'framesequence': 49048, + 'gaze_dir': array([0.98085785, 0.16000366, 0.11036682]), + 'gaze_origin': array([-3.03162551, -0.13190919, 0.06797715]), + 'gaze_valid': True, + 'gaze_vergence': 190.30796813964844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98074341, 0.16629028, 0.1022644 ]), + 'left_gaze_origin': array([-2.96469736, 3.06300998, 0.0748703 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.4099578857421875, + 'left_pupil_posn': array([ 0.17119503, -0.01813054]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98097229, 0.15371704, 0.11846924]), + 'right_gaze_origin': array([-3.09855366, -3.326828 , 0.06108399]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.425537109375, + 'right_pupil_posn': array([ 0.15094817, -0.09975278]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.016882840543985367, + 'throttle_input': 0.0, + 'timestamp': 419.45390106737614, + 'timestamp_carla': 419454, + 'timestamp_device': 4157671, + 'timestamp_stream': 419.45390106737614, + 'transform': [array([-3.51817989e+00, -1.33182783e+01, 1.14456555e-02]), + array([-5.31661883e-02, 1.11014042e+01, 9.79615282e-03])]} +{'AngularVelocity': array([2.88457684e-02, 8.48020660e-04, 2.45510817e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.371639251708984, + 'FR_Wheel_Angle': -10.202715873718262, + 'Location': array([ -4.92466784, -21.67406273, 0.17486744]), + 'Rotation': array([-0.06957913, -3.25543284, -0.00720215]), + 'Velocity': array([-5.97157359e-01, 1.06376007e-01, 4.38270567e-04]), + 'brake_input': 0.0, + 'camera_location': array([-4.16378307, 13.34292793, 2.0108192 ]), + 'camera_rotation': array([-9.85155678, -4.1596508 , 3.14223433]), + 'current_gear_input': False, + 'focus_actor_dist': 1809.68359375, + 'focus_actor_name': 'Road_Sidewalk_Town05_203', + 'focus_actor_pt': array([-730.05786133, -920.44519043, 14.97789764]), + 'frame': 12757, + 'frame_number': 12757, + 'framesequence': 49052, + 'gaze_dir': array([0.98092651, 0.16068268, 0.10863495]), + 'gaze_origin': array([-3.03333616, -0.13212968, 0.06838608]), + 'gaze_valid': True, + 'gaze_vergence': 152.8960418701172, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.980896 , 0.16749573, 0.09886169]), + 'left_gaze_origin': array([-2.9662323 , 3.06305718, 0.07533265]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.412841796875, + 'left_pupil_posn': array([ 0.17122722, -0.01813054]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98095703, 0.15386963, 0.1184082 ]), + 'right_gaze_origin': array([-3.10043955, -3.32731652, 0.06143952]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.4187164306640625, + 'right_pupil_posn': array([ 0.15173626, -0.10102725]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.02310861647129059, + 'throttle_input': 0.0, + 'timestamp': 419.4866599664092, + 'timestamp_carla': 419487, + 'timestamp_device': 4157705, + 'timestamp_stream': 419.4866599664092, + 'transform': [array([-3.52509522e+00, -1.32519732e+01, 1.15513038e-02]), + array([-5.13561890e-02, 1.10777874e+01, 9.61304177e-03])]} +{'AngularVelocity': array([0.03295179, 0.04943694, 2.24511456]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.126755714416504, + 'FR_Wheel_Angle': -8.055072784423828, + 'Location': array([ -5.06591892, -21.65427208, 0.17502746]), + 'Rotation': array([-0.07183993, -2.75921702, -0.00628662]), + 'Velocity': array([-0.65882176, 0.09784437, 0.00090487]), + 'brake_input': 0.0, + 'camera_location': array([-4.13930416, 13.30365181, 2.02683997]), + 'camera_rotation': array([-9.9955101 , -4.25370789, 3.40354538]), + 'current_gear_input': False, + 'focus_actor_dist': 1712.768310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -699.74279785, -1005.35852051, 17.3398819 ]), + 'frame': 12758, + 'frame_number': 12758, + 'framesequence': 49056, + 'gaze_dir': array([0.98042297, 0.16233826, 0.110672 ]), + 'gaze_origin': array([-3.03916264, -0.13235703, 0.06577302]), + 'gaze_valid': True, + 'gaze_vergence': 179.78558349609375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97999573, 0.17097473, 0.1018219 ]), + 'left_gaze_origin': array([-2.97308207, 3.0628159 , 0.07046204]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.316619873046875, + 'left_pupil_posn': array([ 0.17143321, -0.02212167]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98085022, 0.15370178, 0.11952209]), + 'right_gaze_origin': array([-3.10524321, -3.32753015, 0.06108399]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.418548583984375, + 'right_pupil_posn': array([ 0.1532495 , -0.10119689]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.027210304513573647, + 'throttle_input': 0.0, + 'timestamp': 419.5226536653936, + 'timestamp_carla': 419523, + 'timestamp_device': 4157738, + 'timestamp_stream': 419.5226536653936, + 'transform': [array([-3.52837396e+00, -1.31797981e+01, 1.16202543e-02]), + array([-4.99560013e-02, 1.10358601e+01, 9.42993723e-03])]} +{'AngularVelocity': array([2.39158794e-02, 2.84890237e-04, 1.86095262e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.014153480529785, + 'FR_Wheel_Angle': -7.439374923706055, + 'Location': array([ -5.21730375, -21.63698769, 0.17517288]), + 'Rotation': array([-0.07186725, -2.33654761, -0.00592041]), + 'Velocity': array([-0.66191542, 0.08332962, 0.00086366]), + 'brake_input': 0.0, + 'camera_location': array([-4.06075859, 13.23411465, 2.04289293]), + 'camera_rotation': array([-9.84252071, -4.34535122, 3.48772812]), + 'current_gear_input': False, + 'focus_actor_dist': 1684.7139892578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -693.29760742, -1025.83325195, 17.25659943]), + 'frame': 12759, + 'frame_number': 12759, + 'framesequence': 49060, + 'gaze_dir': array([0.98079681, 0.16486359, 0.10383606]), + 'gaze_origin': array([-3.04638004, -0.13047181, 0.06226654]), + 'gaze_valid': True, + 'gaze_vergence': 396.7061767578125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.97988892, 0.17185974, 0.1013031 ]), + 'left_gaze_origin': array([-2.99392247, 3.06585097, 0.0701767 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2246856689453125, + 'left_pupil_posn': array([ 0.17091286, -0.03072476]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98170471, 0.15786743, 0.10636902]), + 'right_gaze_origin': array([-3.09883738, -3.32679462, 0.05435639]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3716583251953125, + 'right_pupil_posn': array([ 0.15287113, -0.10468876]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.0317697711288929, + 'throttle_input': 0.0, + 'timestamp': 419.55725456774235, + 'timestamp_carla': 419557, + 'timestamp_device': 4157771, + 'timestamp_stream': 419.55725456774235, + 'transform': [array([-3.52967215e+00, -1.31112623e+01, 1.16784470e-02]), + array([-4.95940000e-02, 1.09893789e+01, 9.27735306e-03])]} +{'AngularVelocity': array([0.01898033, 0.01268075, 1.95372188]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.324272632598877, + 'FR_Wheel_Angle': -6.63629674911499, + 'Location': array([ -5.37926245, -21.62057877, 0.17534721]), + 'Rotation': array([-0.07345868, -1.91799963, -0.0067749 ]), + 'Velocity': array([-0.73552674, 0.08258475, 0.00092128]), + 'brake_input': 0.0, + 'camera_location': array([-4.01000309, 13.15669632, 1.97688603]), + 'camera_rotation': array([-9.89335728, -4.69194794, 3.12841463]), + 'current_gear_input': False, + 'focus_actor_dist': 1584.0296630859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -665.78417969, -1115.41564941, 17.19445038]), + 'frame': 12760, + 'frame_number': 12760, + 'framesequence': 49064, + 'gaze_dir': array([0.99110413, 0.016922 , 0.12850952]), + 'gaze_origin': array([-2.98318648, -0.02790833, 0.03880921]), + 'gaze_valid': True, + 'gaze_vergence': 89.79137420654297, + 'handbrake_input': False, + 'left_eye_openness': 0.9809143543243408, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99282837, 0.04168701, 0.11196899]), + 'left_gaze_origin': array([-2.81840372, 3.16904449, 0.00975494]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1883544921875, + 'left_pupil_posn': array([ 0.04452825, -0.02465177]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98937988, -0.00784302, 0.14505005]), + 'right_gaze_origin': array([-3.14796901, -3.22486115, 0.06786346]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2972412109375, + 'right_pupil_posn': array([ 0.03936481, -0.09879839]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.03643910214304924, + 'throttle_input': 0.0, + 'timestamp': 419.5904876664281, + 'timestamp_carla': 419590, + 'timestamp_device': 4157805, + 'timestamp_stream': 419.5904876664281, + 'transform': [array([-3.52920365e+00, -1.30462170e+01, 1.17383953e-02]), + array([-4.95666787e-02, 1.09389687e+01, 9.12476238e-03])]} +{'AngularVelocity': array([0.01331402, 0.02073869, 1.77177203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.39792013168335, + 'FR_Wheel_Angle': -4.7975358963012695, + 'Location': array([ -5.56459904, -21.60507011, 0.17554279]), + 'Rotation': array([-0.07602 , -1.51644897, -0.00595093]), + 'Velocity': array([-0.86093289, 0.07439742, 0.00092683]), + 'brake_input': 0.0, + 'camera_location': array([-3.9622879 , 13.05701256, 1.87322247]), + 'camera_rotation': array([-10.34921837, -5.34509659, 2.73481679]), + 'current_gear_input': False, + 'focus_actor_dist': 3036.3828125, + 'focus_actor_name': 'Road_Road_Town05_117', + 'focus_actor_pt': array([-6.21733521e+02, 3.83609863e+02, 1.52587891e-05]), + 'frame': 12761, + 'frame_number': 12761, + 'framesequence': 49068, + 'gaze_dir': array([ 0.99404907, -0.0448761 , 0.09892273]), + 'gaze_origin': array([-3.15212798, 0.03266754, 0.0953537 ]), + 'gaze_valid': True, + 'gaze_vergence': 446.2309265136719, + 'handbrake_input': False, + 'left_eye_openness': 0.9501193761825562, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99424744, -0.03793335, 0.10014343]), + 'left_gaze_origin': array([-3.11040664, 3.22574925, 0.11182252]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2308807373046875, + 'left_pupil_posn': array([-0.00945616, -0.02494371]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99385071, -0.05181885, 0.09770203]), + 'right_gaze_origin': array([-3.19384933, -3.16041422, 0.07888489]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3390045166015625, + 'right_pupil_posn': array([-0.03152001, -0.10316229]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.041602835059165955, + 'throttle_input': 0.0, + 'timestamp': 419.62269116565585, + 'timestamp_carla': 419623, + 'timestamp_device': 4157838, + 'timestamp_stream': 419.62269116565585, + 'transform': [array([-3.52696586e+00, -1.29838972e+01, 1.17931366e-02]), + array([-4.95666787e-02, 1.08840170e+01, 9.00269113e-03])]} +{'AngularVelocity': array([0.00297444, 0.00315908, 1.05297053]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.5972988605499268, + 'FR_Wheel_Angle': -2.138401508331299, + 'Location': array([ -5.77773237, -21.59241867, 0.17575206]), + 'Rotation': array([-0.07595853, -1.21182239, -0.00396729]), + 'Velocity': array([-0.95851392, 0.05129853, 0.00112649]), + 'brake_input': 0.0, + 'camera_location': array([-3.8686924 , 12.95587158, 1.79874825]), + 'camera_rotation': array([-10.6317215 , -6.19143105, 2.49820971]), + 'current_gear_input': False, + 'focus_actor_dist': 1506.9627685546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -304.15750122, -1116.54553223, 16.82888794]), + 'frame': 12762, + 'frame_number': 12762, + 'framesequence': 49072, + 'gaze_dir': array([ 0.99329376, -0.03908539, 0.1075058 ]), + 'gaze_origin': array([-3.11854577, 0.02160034, 0.08510285]), + 'gaze_valid': True, + 'gaze_vergence': 193.13723754882812, + 'handbrake_input': False, + 'left_eye_openness': 0.957636296749115, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99339294, -0.02391052, 0.11210632]), + 'left_gaze_origin': array([-3.0754962 , 3.21662617, 0.10201264]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1734161376953125, + 'left_pupil_posn': array([-0.00395113, -0.02327192]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99319458, -0.05426025, 0.10290527]), + 'right_gaze_origin': array([-3.16159534, -3.17342544, 0.06819306]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.40435791015625, + 'right_pupil_posn': array([-0.01823914, -0.10021865]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.04652852192521095, + 'throttle_input': 0.0, + 'timestamp': 419.6552243679762, + 'timestamp_carla': 419655, + 'timestamp_device': 4157871, + 'timestamp_stream': 419.6552243679762, + 'transform': [array([-3.52288938e+00, -1.29216547e+01, 1.18323518e-02]), + array([-4.95666787e-02, 1.08222466e+01, 8.91113561e-03])]} +{'AngularVelocity': array([ 0.00507554, -0.01006411, 0.20691469]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.3006051480770111, + 'FR_Wheel_Angle': -0.1443798840045929, + 'Location': array([ -6.01272583, -21.58447647, 0.17596766]), + 'Rotation': array([-0.07477008, -1.08883667, -0.00308227]), + 'Velocity': array([-1.02875030e+00, 2.65534222e-02, 9.65356827e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.75287628, 12.84776497, 1.76393843]), + 'camera_rotation': array([-10.85959721, -7.10747433, 2.64127445]), + 'current_gear_input': False, + 'focus_actor_dist': 1570.2191162109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -293.21234131, -1046.13366699, 16.79985046]), + 'frame': 12763, + 'frame_number': 12763, + 'framesequence': 49076, + 'gaze_dir': array([ 0.99330902, -0.02822113, 0.11115265]), + 'gaze_origin': array([-3.11042643, 0.01396027, 0.08479539]), + 'gaze_valid': True, + 'gaze_vergence': 230.00733947753906, + 'handbrake_input': False, + 'left_eye_openness': 0.9799098372459412, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99417114, -0.0161438 , 0.10653687]), + 'left_gaze_origin': array([-3.0419786 , 3.20937967, 0.09152222]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.3369140625, + 'left_pupil_posn': array([ 0.00592959, -0.02009809]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9924469 , -0.04029846, 0.11576843]), + 'right_gaze_origin': array([-3.17887449, -3.18145943, 0.07806855]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3720703125, + 'right_pupil_posn': array([-0.00978178, -0.09866095]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.051930297166109085, + 'throttle_input': 0.0238040741533041, + 'timestamp': 419.6889472678304, + 'timestamp_carla': 419689, + 'timestamp_device': 4157905, + 'timestamp_stream': 419.6889472678304, + 'transform': [array([-3.51651430e+00, -1.28583069e+01, 1.17395967e-02]), + array([-4.97101136e-02, 1.07508030e+01, 9.33838263e-03])]} +{'AngularVelocity': array([ 0.00899239, 0.00108811, -0.00678416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020084111019968987, + 'FR_Wheel_Angle': 0.02008483000099659, + 'Location': array([ -6.26296902, -21.57941818, 0.17623936]), + 'Rotation': array([-0.07550091, -1.08224475, -0.00479126]), + 'Velocity': array([-1.13384509e+00, 2.15677824e-02, 9.81054269e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.66999149, 12.73313999, 1.73551643]), + 'camera_rotation': array([-11.0905323 , -7.98077917, 2.88216925]), + 'current_gear_input': False, + 'focus_actor_dist': 1553.8419189453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -284.52374268, -1055.92089844, 16.79354858]), + 'frame': 12764, + 'frame_number': 12764, + 'framesequence': 49080, + 'gaze_dir': array([ 0.99269867, -0.01795959, 0.11808014]), + 'gaze_origin': array([-3.11060333, 0.00801621, 0.08157501]), + 'gaze_valid': True, + 'gaze_vergence': 162.86428833007812, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.99401855, -0.00439453, 0.10908508]), + 'left_gaze_origin': array([-3.03423023, 3.20408201, 0.083844 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2321624755859375, + 'left_pupil_posn': array([ 0.01254904, -0.01992941]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99137878, -0.03152466, 0.1270752 ]), + 'right_gaze_origin': array([-3.18697691, -3.18804932, 0.07930604]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.33978271484375, + 'right_pupil_posn': array([-0.00107837, -0.09839702]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.058284252882003784, + 'throttle_input': 0.0317387655377388, + 'timestamp': 419.7229252681136, + 'timestamp_carla': 419723, + 'timestamp_device': 4157938, + 'timestamp_stream': 419.7229252681136, + 'transform': [array([-3.50851989e+00, -1.27958832e+01, 1.15925027e-02]), + array([-4.98330593e-02, 1.06741505e+01, 1.00097721e-02])]} +{'AngularVelocity': array([ 0.00149016, -0.00290317, -0.01416133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03509353846311569, + 'FR_Wheel_Angle': 0.03509903699159622, + 'Location': array([ -6.53717279, -21.57419395, 0.17649712]), + 'Rotation': array([-0.0747086 , -1.08483887, -0.00582886]), + 'Velocity': array([-1.20584297e+00, 2.28314083e-02, 1.20064733e-03]), + 'brake_input': 0.0, + 'camera_location': array([-3.57177734, 12.57657623, 1.73378384]), + 'camera_rotation': array([-11.07758236, -8.91727257, 2.97501588]), + 'current_gear_input': False, + 'focus_actor_dist': 1603.6492919921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-278.94665527, -999.39404297, 16.88504028]), + 'frame': 12765, + 'frame_number': 12765, + 'framesequence': 49084, + 'gaze_dir': array([ 0.99337769, -0.00270081, 0.11438751]), + 'gaze_origin': array([-3.11370873, -0.00520782, 0.0790268 ]), + 'gaze_valid': True, + 'gaze_vergence': 318.16937255859375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99368286, 0.00672913, 0.11199951]), + 'left_gaze_origin': array([-3.04189777, 3.19093013, 0.08413392]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2205352783203125, + 'left_pupil_posn': array([ 0.02810395, -0.02470577]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.99307251, -0.01213074, 0.11677551]), + 'right_gaze_origin': array([-3.1855197 , -3.20134616, 0.07391968]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2835235595703125, + 'right_pupil_posn': array([ 0.0118314 , -0.10090542]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.06498611718416214, + 'throttle_input': 0.035706110298633575, + 'timestamp': 419.75663006678224, + 'timestamp_carla': 419757, + 'timestamp_device': 4157971, + 'timestamp_stream': 419.75663006678224, + 'transform': [array([-3.49850941e+00, -1.27351074e+01, 1.14885140e-02]), + array([-4.97715846e-02, 1.05911894e+01, 1.05285738e-02])]} +{'AngularVelocity': array([-0.001089 , 0.00637134, -0.01556481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03630264848470688, + 'FR_Wheel_Angle': 0.03631209954619408, + 'Location': array([ -6.86705256, -21.56790924, 0.17683883]), + 'Rotation': array([-0.07422366, -1.08874512, -0.00579834]), + 'Velocity': array([-1.28704333, 0.02446318, 0.00138168]), + 'brake_input': 0.0, + 'camera_location': array([-3.47918892, 12.40944099, 1.69417787]), + 'camera_rotation': array([-11.12085915, -10.01469803, 2.90519857]), + 'current_gear_input': False, + 'focus_actor_dist': 1517.717529296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -273.0480957 , -1079.21240234, 16.78790283]), + 'frame': 12766, + 'frame_number': 12766, + 'framesequence': 49088, + 'gaze_dir': array([0.99237061, 0.01059723, 0.12215424]), + 'gaze_origin': array([-3.10202885, -0.01576538, 0.0765297 ]), + 'gaze_valid': True, + 'gaze_vergence': 175.87118530273438, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99339294, 0.01863098, 0.11317444]), + 'left_gaze_origin': array([-3.031003 , 3.18220854, 0.08166199]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2339019775390625, + 'left_pupil_posn': array([ 0.03909838, -0.01955569]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99134827, 0.00256348, 0.13113403]), + 'right_gaze_origin': array([-3.1730547 , -3.21373892, 0.0713974 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.385009765625, + 'right_pupil_posn': array([ 0.02423418, -0.10031092]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07223731279373169, + 'throttle_input': 0.043656062334775925, + 'timestamp': 419.7887686677277, + 'timestamp_carla': 419789, + 'timestamp_device': 4158005, + 'timestamp_stream': 419.7887686677277, + 'transform': [array([-3.48688126e+00, -1.26780024e+01, 1.14751626e-02]), + array([-0.04953253, 10.50496006, 0.01071168])]} +{'AngularVelocity': array([-0.00173845, -0.00096195, -0.01590158]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03628047555685043, + 'FR_Wheel_Angle': 0.037537772208452225, + 'Location': array([ -7.12985563, -21.56289101, 0.17708172]), + 'Rotation': array([-0.07296008, -1.09185803, -0.0055542 ]), + 'Velocity': array([-1.31243944, 0.02502078, 0.00132476]), + 'brake_input': 0.0, + 'camera_location': array([-3.37374592, 12.24324417, 1.64857614]), + 'camera_rotation': array([-11.28171635, -10.98323917, 2.80153155]), + 'current_gear_input': False, + 'focus_actor_dist': 1594.9486083984375, + 'focus_actor_name': 'BP_RepSpline36', + 'focus_actor_pt': array([-265.3008728 , -995.12805176, 20.82686615]), + 'frame': 12767, + 'frame_number': 12767, + 'framesequence': 49092, + 'gaze_dir': array([0.99227142, 0.03022766, 0.11977386]), + 'gaze_origin': array([-3.08614898, -0.02451401, 0.06919938]), + 'gaze_valid': True, + 'gaze_vergence': 233.81480407714844, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99281311, 0.03878784, 0.11317444]), + 'left_gaze_origin': array([-3.00952911, 3.17243814, 0.07165528]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.240570068359375, + 'left_pupil_posn': array([ 0.05227935, -0.02395523]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99172974, 0.02166748, 0.12637329]), + 'right_gaze_origin': array([-3.16276884, -3.2214663 , 0.06674347]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.25860595703125, + 'right_pupil_posn': array([ 0.0363096, -0.1015538]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.07996460050344467, + 'throttle_input': 0.051590751856565475, + 'timestamp': 419.8216140680015, + 'timestamp_carla': 419821, + 'timestamp_device': 4158038, + 'timestamp_stream': 419.8216140680015, + 'transform': [array([-3.47271347e+00, -1.26204042e+01, 1.14956470e-02]), + array([-0.04919102, 10.40888214, 0.01071167])]} +{'AngularVelocity': array([-0.00196723, -0.00181029, -0.01680405]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.04375923052430153, + 'FR_Wheel_Angle': 0.04628140106797218, + 'Location': array([ -7.4441309 , -21.55687523, 0.17739013]), + 'Rotation': array([-0.07214729, -1.09573352, -0.00512695]), + 'Velocity': array([-1.34092939e+00, 2.56371759e-02, 1.21596339e-03]), + 'brake_input': 0.0, + 'camera_location': array([-3.30036354, 12.05811691, 1.58174288]), + 'camera_rotation': array([-11.44668579, -11.93669319, 2.83667326]), + 'current_gear_input': False, + 'focus_actor_dist': 1523.688232421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -265.50704956, -1061.23901367, 16.77566528]), + 'frame': 12768, + 'frame_number': 12768, + 'framesequence': 49096, + 'gaze_dir': array([0.9916153 , 0.04372406, 0.12104034]), + 'gaze_origin': array([-3.10563374, -0.03850555, 0.07596359]), + 'gaze_valid': True, + 'gaze_vergence': 296.3232116699219, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.99127197, 0.05438232, 0.1199646 ]), + 'left_gaze_origin': array([-3.04941106, 3.15736723, 0.08600159]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.28582763671875, + 'left_pupil_posn': array([ 0.06641424, -0.02311802]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99195862, 0.0330658 , 0.12211609]), + 'right_gaze_origin': array([-3.16185617, -3.23437834, 0.0659256 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.3136138916015625, + 'right_pupil_posn': array([ 0.05054796, -0.09982264]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.08741721510887146, + 'throttle_input': 0.0634927898645401, + 'timestamp': 419.855095166713, + 'timestamp_carla': 419855, + 'timestamp_device': 4158071, + 'timestamp_stream': 419.855095166713, + 'transform': [array([-3.45600939e+00, -1.25624371e+01, 1.15442276e-02]), + array([-0.04889732, 10.30308151, 0.01055909])]} +{'AngularVelocity': array([-0.00452725, -0.21614787, 0.00030758]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.67417145, -21.5524559 , 0.17725556]), + 'Rotation': array([-0.01458928, -1.09887683, -0.00491333]), + 'Velocity': array([ 0.02130645, -0.00040191, -0.00138525]), + 'brake_input': 0.0, + 'camera_location': array([-3.24866962, 11.88658714, 1.4535538 ]), + 'camera_rotation': array([-11.89385891, -12.88644505, 2.83999491]), + 'current_gear_input': False, + 'focus_actor_dist': 1482.0400390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -258.14620972, -1097.18322754, 16.77742004]), + 'frame': 12769, + 'frame_number': 12769, + 'framesequence': 49100, + 'gaze_dir': array([0.99035645, 0.05282593, 0.12702179]), + 'gaze_origin': array([-3.13339233, -0.05089493, 0.09823914]), + 'gaze_valid': True, + 'gaze_vergence': 198.30267333984375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98927307, 0.06863403, 0.12892151]), + 'left_gaze_origin': array([-3.11887217, 3.14216471, 0.1207367 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.21527099609375, + 'left_pupil_posn': array([ 0.07823837, -0.0114944 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.99143982, 0.03701782, 0.12512207]), + 'right_gaze_origin': array([-3.14791274, -3.24395442, 0.07574157]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.30975341796875, + 'right_pupil_posn': array([ 0.06186938, -0.08778465]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.09452193230390549, + 'throttle_input': 0.0952315554022789, + 'timestamp': 419.8865220658481, + 'timestamp_carla': 419886, + 'timestamp_device': 4158105, + 'timestamp_stream': 419.8865220658481, + 'transform': [array([-3.43833113e+00, -1.25085421e+01, 1.16549302e-02]), + array([-4.86172847e-02, 1.01967993e+01, 1.01928748e-02])]} +{'AngularVelocity': array([3.45160370e-03, 1.68011606e-01, 1.09758294e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.61160803, -21.55367851, 0.17736843]), + 'Rotation': array([-0.03689668, -1.09887671, -0.00491333]), + 'Velocity': array([ 0.355252 , -0.00692713, -0.00069968]), + 'brake_input': 0.0, + 'camera_location': array([-3.22155762, 11.72741985, 1.34439635]), + 'camera_rotation': array([-12.58071613, -13.61316967, 2.86850882]), + 'current_gear_input': False, + 'focus_actor_dist': 1443.3857421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -244.980896 , -1130.07397461, 16.77245331]), + 'frame': 12770, + 'frame_number': 12770, + 'framesequence': 49104, + 'gaze_dir': array([0.98852539, 0.06758881, 0.1342926 ]), + 'gaze_origin': array([-3.12246275, -0.05669098, 0.09737854]), + 'gaze_valid': True, + 'gaze_vergence': 212.04750061035156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98828125, 0.08084106, 0.12944031]), + 'left_gaze_origin': array([-3.0845902 , 3.13815475, 0.11364747]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.2094573974609375, + 'left_pupil_posn': array([ 0.08691931, -0.00541866]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98876953, 0.05433655, 0.1391449 ]), + 'right_gaze_origin': array([-3.16033483, -3.25153661, 0.08110962]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2790069580078125, + 'right_pupil_posn': array([ 0.07157564, -0.08640993]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.10063784569501877, + 'throttle_input': 0.1111009418964386, + 'timestamp': 419.9217221662402, + 'timestamp_carla': 419922, + 'timestamp_device': 4158138, + 'timestamp_stream': 419.9217221662402, + 'transform': [array([-3.41652036e+00, -1.24488192e+01, 1.17495721e-02]), + array([-4.84875105e-02, 1.00708704e+01, 9.73510835e-03])]} +{'AngularVelocity': array([3.10601015e-03, 1.65137768e-01, 1.26152781e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17147286236286163, + 'FR_Wheel_Angle': 0.17175814509391785, + 'Location': array([ -7.55788088, -21.55472374, 0.17753521]), + 'Rotation': array([-0.07546676, -1.09881592, -0.00494385]), + 'Velocity': array([ 1.16045740e-04, 7.40601308e-06, -1.87683327e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.16827488, 11.59702396, 1.30229962]), + 'camera_rotation': array([-12.78538227, -14.17389393, 2.64784503]), + 'current_gear_input': False, + 'focus_actor_dist': 1357.5322265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -245.31813049, -1210.99841309, 16.79348755]), + 'frame': 12771, + 'frame_number': 12771, + 'framesequence': 49108, + 'gaze_dir': array([0.98755646, 0.07387543, 0.13800049]), + 'gaze_origin': array([-3.13705254, -0.06524964, 0.09767533]), + 'gaze_valid': True, + 'gaze_vergence': 224.37591552734375, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98652649, 0.08802795, 0.13778687]), + 'left_gaze_origin': array([-3.122545 , 3.12916422, 0.12214051]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1991729736328125, + 'left_pupil_posn': array([ 0.09501767, -0.00690389]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.98858643, 0.0597229 , 0.13821411]), + 'right_gaze_origin': array([-3.15155935, -3.25966358, 0.07321015]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2854766845703125, + 'right_pupil_posn': array([ 0.07945895, -0.08741939]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1077425554394722, + 'throttle_input': 0.1269855797290802, + 'timestamp': 419.95405396819115, + 'timestamp_carla': 419954, + 'timestamp_device': 4158171, + 'timestamp_stream': 419.95405396819115, + 'transform': [array([-3.39457822e+00, -1.23943319e+01, 1.19096944e-02]), + array([-4.83372472e-02, 9.94849873e+00, 9.12475679e-03])]} +{'AngularVelocity': array([-4.17344767e-04, -2.42187232e-02, -1.50410892e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17147296667099, + 'FR_Wheel_Angle': 0.17175814509391785, + 'Location': array([ -7.5578723 , -21.55472374, 0.17750251]), + 'Rotation': array([-0.07458566, -1.0988158 , -0.00494385]), + 'Velocity': array([-1.51746899e-05, 1.12964444e-05, -7.53618369e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.15356159, 11.48442268, 1.24574471]), + 'camera_rotation': array([-12.99187946, -14.76860142, 2.44493699]), + 'current_gear_input': False, + 'focus_actor_dist': 1361.6239013671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -237.85144043, -1201.0135498 , 16.78342438]), + 'frame': 12772, + 'frame_number': 12772, + 'framesequence': 49112, + 'gaze_dir': array([0.98634338, 0.08643341, 0.13871765]), + 'gaze_origin': array([-3.10656214, -0.07064591, 0.09333878]), + 'gaze_valid': True, + 'gaze_vergence': 159.059814453125, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98431396, 0.10604858, 0.14091492]), + 'left_gaze_origin': array([-3.07415485, 3.12386632, 0.11134491]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.166259765625, + 'left_pupil_posn': array([ 0.10090995, -0.0060252 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([0.9883728 , 0.06681824, 0.13652039]), + 'right_gaze_origin': array([-3.13896942, -3.26515818, 0.07533265]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.333160400390625, + 'right_pupil_posn': array([ 0.08925593, -0.0827812 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11395001411437988, + 'throttle_input': 0.1428549587726593, + 'timestamp': 419.9878426678479, + 'timestamp_carla': 419988, + 'timestamp_device': 4158204, + 'timestamp_stream': 419.9878426678479, + 'transform': [array([-3.36969662e+00, -1.23376665e+01, 1.20888324e-02]), + array([-4.82143015e-02, 9.81370926e+00, 8.36182106e-03])]} +{'AngularVelocity': array([-1.29388791e-04, -6.16760645e-03, -1.18957050e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16380731761455536, + 'FR_Wheel_Angle': 0.16406749188899994, + 'Location': array([ -7.55784893, -21.55472565, 0.17751572]), + 'Rotation': array([-0.07143694, -1.0988158 , -0.00494385]), + 'Velocity': array([-1.69840632e-06, 5.37686844e-07, 1.74765562e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.18881607, 11.38031578, 1.15023625]), + 'camera_rotation': array([-13.41617107, -15.33315945, 2.43376017]), + 'current_gear_input': False, + 'focus_actor_dist': 1318.091552734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -237.60397339, -1239.44018555, 16.79289246]), + 'frame': 12773, + 'frame_number': 12773, + 'framesequence': 49116, + 'gaze_dir': array([ 0.98937988, -0.00952148, 0.14304352]), + 'gaze_origin': array([-3.09776163e+00, 5.72967576e-04, 8.13797042e-02]), + 'gaze_valid': True, + 'gaze_vergence': 134.69984436035156, + 'handbrake_input': False, + 'left_eye_openness': 1.0, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([0.98912048, 0.01374817, 0.14640808]), + 'left_gaze_origin': array([-3.0279603 , 3.20211649, 0.08497315]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.08331298828125, + 'left_pupil_posn': array([ 0.01347506, -0.01382494]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98963928, -0.03279114, 0.13967896]), + 'right_gaze_origin': array([-3.16756296, -3.20097065, 0.07778626]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1993408203125, + 'right_pupil_posn': array([ 0.01390994, -0.08306515]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.11984618753194809, + 'throttle_input': 0.15475699305534363, + 'timestamp': 420.0198585651815, + 'timestamp_carla': 420020, + 'timestamp_device': 4158238, + 'timestamp_stream': 420.0198585651815, + 'transform': [array([ -3.34434557, -12.28405285, 0.01231628]), + array([-4.80981879e-02, 9.67965031e+00, 7.44628813e-03])]} +{'AngularVelocity': array([-1.50471838e-04, -1.51216483e-03, -1.17848595e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.15741834044456482, + 'FR_Wheel_Angle': 0.13971373438835144, + 'Location': array([ -7.55784464, -21.55472565, 0.17751151]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([1.70683484e-06, 6.57026533e-07, 2.88436859e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.19915104, 11.2822094 , 1.08369613]), + 'camera_rotation': array([-13.67489815, -15.97389221, 2.33149529]), + 'current_gear_input': False, + 'focus_actor_dist': 1319.6170654296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -95.8795929 , -1238.98706055, 16.64940643]), + 'frame': 12774, + 'frame_number': 12774, + 'framesequence': 49119, + 'gaze_dir': array([ 0.98490143, -0.12884521, 0.11299896]), + 'gaze_origin': array([-3.16436934, 0.10414582, 0.08023835]), + 'gaze_valid': True, + 'gaze_vergence': 130.76861572265625, + 'handbrake_input': False, + 'left_eye_openness': 0.9821853041648865, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.98802185, -0.10476685, 0.11326599]), + 'left_gaze_origin': array([-3.09606647, 3.29825616, 0.0819748 ]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.0801544189453125, + 'left_pupil_posn': array([-0.09401202, -0.03749418]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.98178101, -0.15292358, 0.11273193]), + 'right_gaze_origin': array([-3.23267245, -3.08996439, 0.0785019 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.20391845703125, + 'right_pupil_posn': array([-0.10278916, -0.10536146]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.12572406232357025, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.0500327683985, + 'timestamp_carla': 420050, + 'timestamp_device': 4158263, + 'timestamp_stream': 420.0500327683985, + 'transform': [array([ -3.31874228, -12.23338699, 0.01258679]), + array([-4.78864536e-02, 9.54699612e+00, 6.37817709e-03])]} +{'AngularVelocity': array([-1.04035062e-04, -2.70913879e-04, -1.21674721e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.13696828484535217, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17749745]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([2.50279891e-06, 5.57930889e-07, 2.74625898e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.20734787, 11.18826294, 1.04099822]), + 'camera_rotation': array([-13.73223114, -16.88498878, 1.89221585]), + 'current_gear_input': False, + 'focus_actor_dist': 1007.67236328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ 5.83151245, -1568.55908203, 16.65155792]), + 'frame': 12775, + 'frame_number': 12775, + 'framesequence': 49123, + 'gaze_dir': array([ 0.95643616, -0.28010559, 0.08123016]), + 'gaze_origin': array([-3.15584946, 0.2204323 , 0.04088822]), + 'gaze_valid': True, + 'gaze_vergence': 245.9845428466797, + 'handbrake_input': False, + 'left_eye_openness': 0.887177586555481, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95999146, -0.26849365, 0.07936096]), + 'left_gaze_origin': array([-3.11502385, 3.40851927, 0.05405273]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.122650146484375, + 'left_pupil_posn': array([-0.21880537, -0.07204831]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95288086, -0.29171753, 0.08309937]), + 'right_gaze_origin': array([-3.1966753 , -2.96765447, 0.02772369]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.328521728515625, + 'right_pupil_posn': array([-0.2450673 , -0.14626706]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.13193151354789734, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.08406326547265, + 'timestamp_carla': 420084, + 'timestamp_device': 4158296, + 'timestamp_stream': 420.08406326547265, + 'transform': [array([ -3.28788352, -12.1762228 , 0.01281608]), + array([-4.76952083e-02, 9.39017868e+00, 5.34057710e-03])]} +{'AngularVelocity': array([ 1.42410217e-05, -6.93053880e-05, -1.19835950e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17751831]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([2.71137333e-06, 4.47177428e-07, 2.60597822e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.23894215, 11.04764557, 1.03388202]), + 'camera_rotation': array([-13.78509712, -18.3020649 , 1.81208706]), + 'current_gear_input': False, + 'focus_actor_dist': 854.322998046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 110.75460815, -1761.52246094, 16.61538696]), + 'frame': 12776, + 'frame_number': 12776, + 'framesequence': 49127, + 'gaze_dir': array([ 0.92987823, -0.36279297, 0.0565033 ]), + 'gaze_origin': array([-3.17486739, 0.26731113, 0.01988068]), + 'gaze_valid': True, + 'gaze_vergence': 131.75201416015625, + 'handbrake_input': False, + 'left_eye_openness': 0.8536186814308167, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.93740845, -0.34268188, 0.06178284]), + 'left_gaze_origin': array([-3.13460422, 3.45300627, 0.03365631]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.074310302734375, + 'left_pupil_posn': array([-0.28312898, -0.10308385]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.92234802, -0.38290405, 0.05122375]), + 'right_gaze_origin': array([-3.21513081, -2.91838384, 0.00610504]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2105712890625, + 'right_pupil_posn': array([-0.30645633, -0.17195547]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.14050112664699554, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.11641826853156, + 'timestamp_carla': 420116, + 'timestamp_device': 4158329, + 'timestamp_stream': 420.11641826853156, + 'transform': [array([ -3.25614429, -12.12174988, 0.01305177]), + array([-4.72102650e-02, 9.23219776e+00, 4.39453544e-03])]} +{'AngularVelocity': array([ 1.63302120e-05, -5.76478269e-05, -1.26282630e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17748573]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([2.38981102e-06, 4.06298199e-07, 5.27175907e-05]), + 'brake_input': 0.0, + 'camera_location': array([-3.2467165 , 10.90719414, 1.04809129]), + 'camera_rotation': array([-13.73945713, -19.69844055, 2.36800647]), + 'current_gear_input': False, + 'focus_actor_dist': 764.1189575195312, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 152.87831116, -1879.92578125, 16.61518097]), + 'frame': 12777, + 'frame_number': 12777, + 'framesequence': 49131, + 'gaze_dir': array([ 0.93564606, -0.34810638, 0.05422974]), + 'gaze_origin': array([-3.17140818, 0.26302186, 0.01917572]), + 'gaze_valid': True, + 'gaze_vergence': 141.59580993652344, + 'handbrake_input': False, + 'left_eye_openness': 0.8537804484367371, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.94297791, -0.32891846, 0.05084229]), + 'left_gaze_origin': array([-3.13182259, 3.44965672, 0.03345642]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1550445556640625, + 'left_pupil_posn': array([-0.27488518, -0.10013545]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.92831421, -0.36729431, 0.05761719]), + 'right_gaze_origin': array([-3.21099424, -2.92361307, 0.00489502]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.2418365478515625, + 'right_pupil_posn': array([-0.29785925, -0.17545033]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.150096133351326, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.1481476686895, + 'timestamp_carla': 420148, + 'timestamp_device': 4158363, + 'timestamp_stream': 420.1481476686895, + 'transform': [array([ -3.22225785, -12.06809425, 0.0132906 ]), + array([-4.64521125e-02, 9.06689358e+00, 3.47900949e-03])]} +{'AngularVelocity': array([ 5.72057834e-05, 3.18855709e-05, -1.26973619e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17750198]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([ 2.29485318e-06, 4.18737756e-07, -1.25219711e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.26400852, 10.78811264, 1.06069779]), + 'camera_rotation': array([-13.55931091, -20.77259445, 2.70064569]), + 'current_gear_input': False, + 'focus_actor_dist': 764.132568359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 159.37304688, -1878.77539062, 16.60836792]), + 'frame': 12778, + 'frame_number': 12778, + 'framesequence': 49135, + 'gaze_dir': array([ 0.93962097, -0.33799744, 0.05119324]), + 'gaze_origin': array([-3.16946054, 0.25818634, 0.01544953]), + 'gaze_valid': True, + 'gaze_vergence': 180.53883361816406, + 'handbrake_input': False, + 'left_eye_openness': 0.8708324432373047, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9438324 , -0.32525635, 0.05801392]), + 'left_gaze_origin': array([-3.12922668, 3.44889235, 0.02862854]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.246490478515625, + 'left_pupil_posn': array([-0.26837432, -0.10688603]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.93540955, -0.35073853, 0.04437256]), + 'right_gaze_origin': array([-3.20969415e+00, -2.93251967e+00, 2.27050786e-03]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.085113525390625, + 'right_pupil_posn': array([-0.29012716, -0.1747756 ]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.16067995131015778, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.18290196731687, + 'timestamp_carla': 420183, + 'timestamp_device': 4158396, + 'timestamp_stream': 420.18290196731687, + 'transform': [array([ -3.18180442, -12.00921345, 0.01346725]), + array([-4.55300398e-02, 8.87341881e+00, 2.74658622e-03])]} +{'AngularVelocity': array([ 9.51371476e-06, -3.58404468e-05, -1.27963967e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17749241]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([ 2.14589750e-06, 4.34317030e-07, -1.90000908e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.28450489, 10.65095234, 1.0816803 ]), + 'camera_rotation': array([-13.12894821, -21.83006477, 3.06434894]), + 'current_gear_input': False, + 'focus_actor_dist': 766.8672485351562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 167.19332886, -1875.38134766, 16.59940338]), + 'frame': 12779, + 'frame_number': 12779, + 'framesequence': 49139, + 'gaze_dir': array([ 0.94756317, -0.31554413, 0.04893494]), + 'gaze_origin': array([-3.16693234, 0.25233155, 0.00610504]), + 'gaze_valid': True, + 'gaze_vergence': 226.48574829101562, + 'handbrake_input': False, + 'left_eye_openness': 0.8803088665008545, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95077515, -0.30508423, 0.05427551]), + 'left_gaze_origin': array([-3.12698364, 3.44405842, 0.01807709]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.291107177734375, + 'left_pupil_posn': array([-0.25590616, -0.11344302]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.9443512 , -0.32600403, 0.04359436]), + 'right_gaze_origin': array([-3.20688033, -2.93939519, -0.005867 ]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.299407958984375, + 'right_pupil_posn': array([-0.2782132 , -0.18066013]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.17336955666542053, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.2153592668474, + 'timestamp_carla': 420215, + 'timestamp_device': 4158429, + 'timestamp_stream': 420.2153592668474, + 'transform': [array([ -3.14032125, -11.95401001, 0.01364841]), + array([-4.43757363e-02, 8.67881393e+00, 2.13623326e-03])]} +{'AngularVelocity': array([-4.35837319e-05, 2.00304585e-05, -1.23595573e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17749943]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([2.52156519e-06, 5.38664153e-07, 8.40434659e-05]), + 'brake_input': 0.0, + 'camera_location': array([-3.35316849, 10.4476862 , 1.07836246]), + 'camera_rotation': array([-12.89317703, -23.05559349, 3.35810375]), + 'current_gear_input': False, + 'focus_actor_dist': 786.668701171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 175.54927063, -1851.59863281, 16.58278656]), + 'frame': 12780, + 'frame_number': 12780, + 'framesequence': 49143, + 'gaze_dir': array([ 0.95011902, -0.30691528, 0.0539093 ]), + 'gaze_origin': array([-3.1639154 , 0.23915254, 0.0048111 ]), + 'gaze_valid': True, + 'gaze_vergence': 241.69248962402344, + 'handbrake_input': False, + 'left_eye_openness': 0.8856541514396667, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.95401001, -0.29492188, 0.05363464]), + 'left_gaze_origin': array([-3.12414408, 3.43164253, 0.01663055]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.258026123046875, + 'left_pupil_posn': array([-0.24471313, -0.11007404]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.94622803, -0.31890869, 0.05418396]), + 'right_gaze_origin': array([-3.20368671, -2.95333743, -0.00700836]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.24169921875, + 'right_pupil_posn': array([-0.26484525, -0.18097925]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.1862971931695938, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.2484861686826, + 'timestamp_carla': 420248, + 'timestamp_device': 4158463, + 'timestamp_stream': 420.2484861686826, + 'transform': [array([ -3.09395099, -11.89746666, 0.01380494]), + array([-4.30575088e-02, 8.46503544e+00, 1.61743315e-03])]} +{'AngularVelocity': array([-3.27809284e-05, 2.66915249e-05, -1.25509059e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17749865]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([ 2.37477934e-06, 4.35996895e-07, -4.50541957e-05]), + 'brake_input': 0.0, + 'camera_location': array([-3.44368172, 10.2311821 , 1.0480001 ]), + 'camera_rotation': array([-13.00304031, -24.30439758, 3.63125968]), + 'current_gear_input': False, + 'focus_actor_dist': 837.7466430664062, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 212.50190735, -1808.65087891, 16.53127289]), + 'frame': 12781, + 'frame_number': 12781, + 'framesequence': 49147, + 'gaze_dir': array([ 0.9596405 , -0.27640533, 0.04941559]), + 'gaze_origin': array([-3.15870976, 0.22724611, 0.01026001]), + 'gaze_valid': True, + 'gaze_vergence': 177.69732666015625, + 'handbrake_input': False, + 'left_eye_openness': 0.89754718542099, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96295166, -0.26356506, 0.05691528]), + 'left_gaze_origin': array([-3.11857772, 3.42217731, 0.02154236]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.239288330078125, + 'left_pupil_posn': array([-0.22740388, -0.1091218 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.95632935, -0.28924561, 0.04191589]), + 'right_gaze_origin': array([-3.19884205e+00, -2.96768498e+00, -1.02233887e-03]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0846405029296875, + 'right_pupil_posn': array([-0.24404645, -0.17357981]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.19949950277805328, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.2828140668571, + 'timestamp_carla': 420283, + 'timestamp_device': 4158496, + 'timestamp_stream': 420.2828140668571, + 'transform': [array([ -3.04159594, -11.83876801, 0.01391691]), + array([-4.18075845e-02, 8.22746658e+00, 1.25122350e-03])]} +{'AngularVelocity': array([ 7.70440165e-05, 2.30038677e-05, -1.21469666e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17750724]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([2.78164634e-06, 5.18748436e-07, 2.90816388e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.54068279, 10.02672005, 1.05835652]), + 'camera_rotation': array([-12.94273663, -25.31318283, 3.80823064]), + 'current_gear_input': False, + 'focus_actor_dist': 788.7769165039062, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 181.85180664, -1842.60473633, 16.57344055]), + 'frame': 12782, + 'frame_number': 12782, + 'framesequence': 49151, + 'gaze_dir': array([ 0.96360016, -0.26327515, 0.04511261]), + 'gaze_origin': array([-3.15564919, 0.21650927, 0.01068344]), + 'gaze_valid': True, + 'gaze_vergence': 304.29742431640625, + 'handbrake_input': False, + 'left_eye_openness': 0.8842987418174744, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.96629333, -0.2535553 , 0.04428101]), + 'left_gaze_origin': array([-3.11647367, 3.41260242, 0.02065735]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1787109375, + 'left_pupil_posn': array([-0.21502042, -0.1075021 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96090698, -0.272995 , 0.04594421]), + 'right_gaze_origin': array([-3.19482422e+00, -2.97958374e+00, 7.09533750e-04]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1284027099609375, + 'right_pupil_posn': array([-0.23206675, -0.17618883]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.21184119582176208, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.3141630664468, + 'timestamp_carla': 420314, + 'timestamp_device': 4158529, + 'timestamp_stream': 420.3141630664468, + 'transform': [array([ -2.98984122, -11.78495789, 0.01405859]), + array([-4.06532846e-02, 7.99579477e+00, 8.54496495e-04])]} +{'AngularVelocity': array([ 1.09811037e-04, -2.26425345e-06, -1.29519003e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17749016]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([ 2.14620491e-06, 3.08530275e-07, -2.07223959e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.59753323, 9.80822754, 1.14092195]), + 'camera_rotation': array([-12.65742588, -26.14385986, 3.9389627 ]), + 'current_gear_input': False, + 'focus_actor_dist': 768.0691528320312, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 176.03919983, -1858.22033691, 16.58468628]), + 'frame': 12783, + 'frame_number': 12783, + 'framesequence': 49155, + 'gaze_dir': array([ 0.96595001, -0.25450134, 0.04443359]), + 'gaze_origin': array([-3.15351033, 0.20638199, 0.00759506]), + 'gaze_valid': True, + 'gaze_vergence': 232.50430297851562, + 'handbrake_input': False, + 'left_eye_openness': 0.9090436100959778, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9691925 , -0.24183655, 0.04637146]), + 'left_gaze_origin': array([-3.11416483, 3.40200067, 0.01857758]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.15570068359375, + 'left_pupil_posn': array([-0.20568103, -0.10948849]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96270752, -0.26716614, 0.04249573]), + 'right_gaze_origin': array([-3.19285607, -2.98923659, -0.00338745]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.126007080078125, + 'right_pupil_posn': array([-0.22133332, -0.17769039]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.22108829021453857, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.348033066839, + 'timestamp_carla': 420348, + 'timestamp_device': 4158563, + 'timestamp_stream': 420.348033066839, + 'transform': [array([ -2.93034029, -11.72676277, 0.01413943]), + array([-3.98609824e-02, 7.73235607e+00, 5.79835614e-04])]} +{'AngularVelocity': array([-2.39029705e-05, -2.52576865e-05, -1.24434091e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17750442]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([ 2.39736391e-06, 4.94491530e-07, -6.21209529e-06]), + 'brake_input': 0.0, + 'camera_location': array([-3.65356159, 9.59282207, 1.22176027]), + 'camera_rotation': array([-12.3140583 , -26.80107117, 3.9660635 ]), + 'current_gear_input': False, + 'focus_actor_dist': 786.72265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 192.15562439, -1841.0300293 , 16.56272125]), + 'frame': 12784, + 'frame_number': 12784, + 'framesequence': 49159, + 'gaze_dir': array([ 0.96980286, -0.23981476, 0.04232025]), + 'gaze_origin': array([-3.15232229, 0.19874117, 0.00323334]), + 'gaze_valid': True, + 'gaze_vergence': 233.41969299316406, + 'handbrake_input': False, + 'left_eye_openness': 0.8877396583557129, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97251892, -0.2281189 , 0.04640198]), + 'left_gaze_origin': array([-3.11244369, 3.39532185, 0.01392822]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.136566162109375, + 'left_pupil_posn': array([-0.19553208, -0.1134702 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96708679, -0.25151062, 0.03823853]), + 'right_gaze_origin': array([-3.19220114, -2.99783945, -0.00746155]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1877288818359375, + 'right_pupil_posn': array([-0.21068245, -0.18004549]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.23097629845142365, + 'throttle_input': 0.1587243527173996, + 'timestamp': 420.3821845687926, + 'timestamp_carla': 420382, + 'timestamp_device': 4158596, + 'timestamp_stream': 420.3821845687926, + 'transform': [array([ -2.86685991, -11.66812515, 0.01417914]), + array([-3.93692069e-02, 7.45408964e+00, 4.57768445e-04])]} +{'AngularVelocity': array([ 6.84931001e-05, 1.79256767e-05, -1.24015123e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17749988]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([2.59442254e-06, 4.53229859e-07, 1.44629710e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.68172359, 9.40493393, 1.26601553]), + 'camera_rotation': array([-12.13656902, -27.31217575, 3.87468195]), + 'current_gear_input': False, + 'focus_actor_dist': 797.6378173828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 198.77406311, -1826.61938477, 16.55110168]), + 'frame': 12785, + 'frame_number': 12785, + 'framesequence': 49163, + 'gaze_dir': array([ 0.97170258, -0.23258209, 0.04038239]), + 'gaze_origin': array([-3.15146828, 0.19493409, 0.00330124]), + 'gaze_valid': True, + 'gaze_vergence': 433.9203186035156, + 'handbrake_input': False, + 'left_eye_openness': 0.8808773159980774, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.9733429 , -0.22561646, 0.0408783 ]), + 'left_gaze_origin': array([-3.11163354, 3.39100647, 0.01425476]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.014739990234375, + 'left_pupil_posn': array([-0.18841612, -0.1121155 ]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97006226, -0.23954773, 0.03988647]), + 'right_gaze_origin': array([-3.19130278, -3.00113845, -0.00765228]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.0899810791015625, + 'right_pupil_posn': array([-0.20746261, -0.18204951]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.23895993828773499, + 'throttle_input': 0.1745937317609787, + 'timestamp': 420.41439646854997, + 'timestamp_carla': 420414, + 'timestamp_device': 4158629, + 'timestamp_stream': 420.41439646854997, + 'transform': [array([ -2.80393362, -11.6127758 , 0.01424614]), + array([-3.90003771e-02, 7.18062449e+00, 2.74661288e-04])]} +{'AngularVelocity': array([-2.54624374e-05, -2.09866557e-05, -1.25566121e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17749466]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([ 2.34004096e-06, 5.20973686e-07, -3.96273899e-05]), + 'brake_input': 0.0, + 'camera_location': array([-3.70394421, 9.24451637, 1.28282857]), + 'camera_rotation': array([-12.12702084, -27.78673363, 3.65285635]), + 'current_gear_input': False, + 'focus_actor_dist': 797.1244506835938, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 202.89881897, -1824.27807617, 16.54624939]), + 'frame': 12786, + 'frame_number': 12786, + 'framesequence': 49167, + 'gaze_dir': array([ 0.97086334, -0.22781372, 0.07200623]), + 'gaze_origin': array([-3.14994907, 0.18060532, 0.02286835]), + 'gaze_valid': True, + 'gaze_vergence': 170.759765625, + 'handbrake_input': False, + 'left_eye_openness': 0.8776807188987732, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97486877, -0.2101593 , 0.0738678 ]), + 'left_gaze_origin': array([-3.11065388, 3.37406468, 0.03565369]), + 'left_gaze_valid': True, + 'left_pupil_diam': 3.1104736328125, + 'left_pupil_posn': array([-0.1786989 , -0.08727467]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.96685791, -0.24546814, 0.07014465]), + 'right_gaze_origin': array([-3.18924403, -3.01285434, 0.01008301]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.12420654296875, + 'right_pupil_posn': array([-0.19371063, -0.15777087]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.24496598541736603, + 'throttle_input': 0.1904631108045578, + 'timestamp': 420.443789165467, + 'timestamp_carla': 420444, + 'timestamp_device': 4158663, + 'timestamp_stream': 420.443789165467, + 'transform': [array([ -2.74687338, -11.56248474, 0.01419045]), + array([-3.90891694e-02, 6.93457842e+00, 3.35697783e-04])]} +{'AngularVelocity': array([-2.79265696e-05, -2.10566268e-05, -1.26032965e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ -7.55784369, -21.55472565, 0.17750537]), + 'Rotation': array([-0.07110909, -1.0988158 , -0.00494385]), + 'Velocity': array([ 2.21782352e-06, 4.88578223e-07, -1.65560297e-04]), + 'brake_input': 0.0, + 'camera_location': array([-3.7328043 , 9.11311531, 1.28651571]), + 'camera_rotation': array([-12.20318413, -28.22952271, 3.53725314]), + 'current_gear_input': False, + 'focus_actor_dist': 998.3272094726562, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 318.83007812, -1652.1628418 , 16.37130737]), + 'frame': 12787, + 'frame_number': 12787, + 'framesequence': 49171, + 'gaze_dir': array([ 0.97460938, -0.20667267, 0.08545685]), + 'gaze_origin': array([-3.14792514, 0.16880494, 0.03565674]), + 'gaze_valid': True, + 'gaze_vergence': 304.1374206542969, + 'handbrake_input': False, + 'left_eye_openness': 0.905061662197113, + 'left_eye_openness_valid': True, + 'left_gaze_dir': array([ 0.97642517, -0.19711304, 0.08790588]), + 'left_gaze_origin': array([-3.10872221, 3.36000204, 0.04984589]), + 'left_gaze_valid': True, + 'left_pupil_diam': 2.9951934814453125, + 'left_pupil_posn': array([-0.15876478, -0.07216334]), + 'left_pupil_posn_valid': True, + 'right_eye_openness': 1.0, + 'right_eye_openness_valid': True, + 'right_gaze_dir': array([ 0.97279358, -0.2162323 , 0.08300781]), + 'right_gaze_origin': array([-3.18712783, -3.02239251, 0.02146759]), + 'right_gaze_valid': True, + 'right_pupil_diam': 3.1207275390625, + 'right_pupil_posn': array([-0.1824193 , -0.14457655]), + 'right_pupil_posn_valid': True, + 'steering_input': -0.24989165365695953, + 'throttle_input': 0.21428243815898895, + 'timestamp': 420.4766815677285, + 'timestamp_carla': 420477, + 'timestamp_device': 4158696, + 'timestamp_stream': 420.4766815677285, + 'transform': [array([ -2.67800951, -11.50614738, 0.0142439 ]), + array([-3.91233228e-02, 6.63921738e+00, 2.13624793e-04])]} diff --git a/PythonAPI/data/trials/trial_v_equal_vx.txt b/PythonAPI/data/trials/trial_v_equal_vx.txt new file mode 100644 index 0000000..ff4a7d5 --- /dev/null +++ b/PythonAPI/data/trials/trial_v_equal_vx.txt @@ -0,0 +1,25632 @@ +{'AngularVelocity': array([ 6.43164603e-05, 3.80409183e-05, -1.56078613e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617442, -18.3298645 , 0.16717896]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.93484549e-06, 2.47542033e-07, 4.61575430e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.83837890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -111.9954071 , -1904.90673828, 16.88562012]), + 'frame': 13614, + 'frame_number': 13614, + 'framesequence': 13612, + 'gaze_dir': array([ 0.98058057, 0.10336377, -0.16666579]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.10336377, -0.16666579]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.10336377, -0.16666579]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.89655466005206, + 'timestamp_carla': 55896, + 'timestamp_device': 55533, + 'timestamp_stream': 55.89655466005206, + 'transform': [array([ 0.00987167, -0.00354858, 0.1648705 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([8.82176464e-05, 9.60377001e-05, 1.11959388e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617442, -18.3298645 , 0.1671949 ]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([5.18993465e-06, 4.33095266e-07, 6.62542705e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8385009765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -112.28208923, -1904.03955078, 16.88574219]), + 'frame': 13615, + 'frame_number': 13615, + 'framesequence': 13613, + 'gaze_dir': array([ 0.98058069, 0.10402987, -0.16625085]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10402987, -0.16625085]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10402987, -0.16625085]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.900854062289, + 'timestamp_carla': 55900, + 'timestamp_device': 55537, + 'timestamp_stream': 55.900854062289, + 'transform': [array([ 0.00987152, -0.00354858, 0.16487177]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.12060713e-05, 2.82163073e-05, -1.65458152e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617465, -18.3298645 , 0.16720557]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.43645740e-06, 1.29321123e-07, -2.49788245e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8387451171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -112.56555176, -1903.17053223, 16.88562012]), + 'frame': 13616, + 'frame_number': 13616, + 'framesequence': 13614, + 'gaze_dir': array([ 0.98058057, 0.10452788, -0.16593817]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.10452788, -0.16593817]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.10452788, -0.16593817]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.904292959719896, + 'timestamp_carla': 55904, + 'timestamp_device': 55540, + 'timestamp_stream': 55.904292959719896, + 'transform': [array([ 0.00987167, -0.00354858, 0.16487466]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.59888724e-05, -6.26693509e-05, -5.67886559e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617489, -18.3298645 , 0.16720745]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.57902661e-06, 2.36342885e-07, 1.20220306e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8388671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -112.77566528, -1902.51855469, 16.88574219]), + 'frame': 13617, + 'frame_number': 13617, + 'framesequence': 13615, + 'gaze_dir': array([ 0.98058057, 0.10519106, -0.16551857]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.10519106, -0.16551857]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.10519106, -0.16551857]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.90788105875254, + 'timestamp_carla': 55907, + 'timestamp_device': 55544, + 'timestamp_stream': 55.90788105875254, + 'transform': [array([ 0.00987152, -0.00354858, 0.16487673]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.68482317e-05, 3.92633083e-05, -2.51338724e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617477, -18.3298645 , 0.16720378]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.15271143e-06, -4.00166016e-08, -2.57375970e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.839111328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.05305481, -1901.64746094, 16.88562012]), + 'frame': 13618, + 'frame_number': 13618, + 'framesequence': 13616, + 'gaze_dir': array([ 0.98058057, 0.10585256, -0.16509631]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.10585256, -0.16509631]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.10585256, -0.16509631]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.91134615987539, + 'timestamp_carla': 55911, + 'timestamp_device': 55548, + 'timestamp_stream': 55.91134615987539, + 'transform': [array([ 0.00987167, -0.00354858, 0.16487932]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.60501615e-05, -6.32508600e-05, -2.72536937e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617525, -18.3298645 , 0.16720459]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.57936676e-06, 3.38065433e-07, 1.88371065e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.83935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.32693481, -1900.77539062, 16.88574219]), + 'frame': 13619, + 'frame_number': 13619, + 'framesequence': 13617, + 'gaze_dir': array([ 0.98058069, 0.1063471 , -0.16477819]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1063471 , -0.16477819]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1063471 , -0.16477819]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.915182661265135, + 'timestamp_carla': 55915, + 'timestamp_device': 55551, + 'timestamp_stream': 55.915182661265135, + 'transform': [array([ 0.00987152, -0.00354858, 0.16488084]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.83261319e-05, -6.45993932e-05, -1.02632328e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617549, -18.3298645 , 0.16720317]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.35077573e-06, 1.53800940e-07, -7.59476752e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.83984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.52989197, -1900.12121582, 16.88549805]), + 'frame': 13620, + 'frame_number': 13620, + 'framesequence': 13618, + 'gaze_dir': array([ 0.98058069, 0.10700563, -0.16435131]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10700563, -0.16435131]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10700563, -0.16435131]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.91904405876994, + 'timestamp_carla': 55919, + 'timestamp_device': 55555, + 'timestamp_stream': 55.91904405876994, + 'transform': [array([ 0.00987167, -0.00354858, 0.16488275]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.66948103e-05, 9.59815879e-05, -2.62644767e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617537, -18.3298645 , 0.16719063]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.26792531e-06, -3.09594910e-08, -1.81359181e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8399658203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.7976532 , -1899.24707031, 16.88549805]), + 'frame': 13621, + 'frame_number': 13621, + 'framesequence': 13619, + 'gaze_dir': array([ 0.98058069, 0.10766181, -0.16392222]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10766181, -0.16392222]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10766181, -0.16392222]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.92287985980511, + 'timestamp_carla': 55922, + 'timestamp_device': 55559, + 'timestamp_stream': 55.92287985980511, + 'transform': [array([ 0.00987152, -0.00354858, 0.16488405]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.00867216e-05, -1.98710541e-06, 1.21268414e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617585, -18.3298645 , 0.16719459]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.85324063e-06, 3.36278447e-07, 3.34947923e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8402099609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.0617218 , -1898.37280273, 16.88549805]), + 'frame': 13622, + 'frame_number': 13622, + 'framesequence': 13620, + 'gaze_dir': array([ 0.98058069, 0.10848024, -0.16338176]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10848024, -0.16338176]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10848024, -0.16338176]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.92748646065593, + 'timestamp_carla': 55927, + 'timestamp_device': 55564, + 'timestamp_stream': 55.92748646065593, + 'transform': [array([ 0.00987152, -0.00354858, 0.16488405]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.41241204e-05, 3.73814437e-05, -5.36590676e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617656, -18.3298645 , 0.16719635]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.63344622e-06, 1.62699720e-07, 9.96319941e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84033203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.38703918, -1897.27770996, 16.88549805]), + 'frame': 13623, + 'frame_number': 13623, + 'framesequence': 13621, + 'gaze_dir': array([ 0.98058069, 0.10913255, -0.16294676]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10913255, -0.16294676]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10913255, -0.16294676]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.931761760264635, + 'timestamp_carla': 55931, + 'timestamp_device': 55568, + 'timestamp_stream': 55.931761760264635, + 'transform': [array([ 0.00987152, -0.00354858, 0.16488405]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.36754417e-05, -5.82193206e-05, 3.42605766e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617656, -18.3298645 , 0.16719635]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.52811128e-06, 2.67833229e-07, 7.14327252e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84033203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.6431427 , -1896.40112305, 16.88549805]), + 'frame': 13624, + 'frame_number': 13624, + 'framesequence': 13622, + 'gaze_dir': array([ 0.98058069, 0.10978372, -0.16250874]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10978372, -0.16250874]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10978372, -0.16250874]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.934987761080265, + 'timestamp_carla': 55935, + 'timestamp_device': 55572, + 'timestamp_stream': 55.934987761080265, + 'transform': [array([ 0.00987167, -0.00354858, 0.16488644]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.64671856e-05, 3.59748738e-05, 1.61116205e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617632, -18.3298645 , 0.16719383]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.68928602e-06, 2.73744803e-07, 1.44233360e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8404541015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.89599609, -1895.52258301, 16.88537598]), + 'frame': 13625, + 'frame_number': 13625, + 'framesequence': 13623, + 'gaze_dir': array([ 0.98058057, 0.11043313, -0.16206813]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.11043313, -0.16206813]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.11043313, -0.16206813]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.94018306210637, + 'timestamp_carla': 55940, + 'timestamp_device': 55576, + 'timestamp_stream': 55.94018306210637, + 'transform': [array([ 0.00987152, -0.00354858, 0.16488394]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([9.28111258e-05, 1.03813858e-04, 3.10437827e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617656, -18.3298645 , 0.16718845]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.76470677e-06, 2.82245452e-07, 2.21001712e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8409423828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.14538574, -1894.64306641, 16.88513184]), + 'frame': 13626, + 'frame_number': 13626, + 'framesequence': 13624, + 'gaze_dir': array([ 0.98058069, 0.11108018, -0.16162536]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11108018, -0.16162536]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11108018, -0.16162536]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.943812761455774, + 'timestamp_carla': 55943, + 'timestamp_device': 55580, + 'timestamp_stream': 55.943812761455774, + 'transform': [array([ 0.00987167, -0.00354858, 0.164886 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.54365729e-05, -5.17757471e-05, 2.15331166e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617668, -18.3298645 , 0.16718948]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.57342685e-06, 2.52843591e-07, 8.86022826e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8406982421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.39094543, -1893.76342773, 16.88513184]), + 'frame': 13627, + 'frame_number': 13627, + 'framesequence': 13625, + 'gaze_dir': array([ 0.98058069, 0.1115649 , -0.16129114]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1115649 , -0.16129114]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1115649 , -0.16129114]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.94707655906677, + 'timestamp_carla': 55947, + 'timestamp_device': 55583, + 'timestamp_stream': 55.94707655906677, + 'transform': [array([ 0.00987152, -0.00354858, 0.16488776]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.48977737e-05, -5.13914238e-05, -2.02234241e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617692, -18.3298645 , 0.16717681]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.01598390e-06, 1.08121888e-07, -2.68563279e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.841064453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.57307434, -1893.10229492, 16.88500977]), + 'frame': 13628, + 'frame_number': 13628, + 'framesequence': 13626, + 'gaze_dir': array([ 0.98058057, 0.11220881, -0.16084383]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.11220881, -0.16084383]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.11220881, -0.16084383]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.950489562004805, + 'timestamp_carla': 55950, + 'timestamp_device': 55587, + 'timestamp_stream': 55.950489562004805, + 'transform': [array([ 0.00987167, -0.00354858, 0.16488981]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.27484291e-05, 6.23631468e-06, -5.03995443e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617716, -18.3298645 , 0.16716194]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 2.62625053e-06, -5.80421158e-07, -1.46609033e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8411865234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.81251526, -1892.22094727, 16.88500977]), + 'frame': 13629, + 'frame_number': 13629, + 'framesequence': 13627, + 'gaze_dir': array([ 0.98058069, 0.11269119, -0.16050625]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11269119, -0.16050625]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11269119, -0.16050625]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.953696358948946, + 'timestamp_carla': 55953, + 'timestamp_device': 55590, + 'timestamp_stream': 55.953696358948946, + 'transform': [array([ 0.00987152, -0.00354858, 0.16489141]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-9.27898054e-06, 4.25033504e-05, -4.32704013e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617764, -18.3298645 , 0.16716972]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.83899612e-06, 3.31936150e-07, 3.43279447e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8416748046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.99006653, -1891.55847168, 16.88476562]), + 'frame': 13630, + 'frame_number': 13630, + 'framesequence': 13628, + 'gaze_dir': array([ 0.98058057, 0.11333195, -0.16005443]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.11333195, -0.16005443]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.11333195, -0.16005443]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.95749966055155, + 'timestamp_carla': 55957, + 'timestamp_device': 55594, + 'timestamp_stream': 55.95749966055155, + 'transform': [array([ 0.00987167, -0.00354858, 0.16489278]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 9.39407764e-05, 1.03902821e-04, -1.68131464e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617775, -18.3298645 , 0.16715942]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.91482433e-06, 2.44987888e-07, 4.30605432e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8416748046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.2232666 , -1890.67553711, 16.8848877 ]), + 'frame': 13631, + 'frame_number': 13631, + 'framesequence': 13629, + 'gaze_dir': array([ 0.98058069, 0.11397152, -0.15959966]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11397152, -0.15959966]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11397152, -0.15959966]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.961988762021065, + 'timestamp_carla': 55962, + 'timestamp_device': 55598, + 'timestamp_stream': 55.961988762021065, + 'transform': [array([ 0.00987167, -0.00354858, 0.16489278]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 9.25372588e-05, 1.02524718e-04, -1.07164158e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617775, -18.3298645 , 0.16716877]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.78503034e-06, 2.74069606e-07, 3.19424726e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8419189453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.45323181, -1889.79077148, 16.88476562]), + 'frame': 13632, + 'frame_number': 13632, + 'framesequence': 13630, + 'gaze_dir': array([ 0.98058057, 0.11460866, -0.15914273]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.11460866, -0.15914273]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.11460866, -0.15914273]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.96551125869155, + 'timestamp_carla': 55965, + 'timestamp_device': 55602, + 'timestamp_stream': 55.96551125869155, + 'transform': [array([ 0.00987183, -0.00354858, 0.16489451]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([8.98324070e-05, 9.76802112e-05, 1.37987030e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617871, -18.3298645 , 0.16717987]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.92167874e-06, 2.48729492e-07, 3.15232581e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': True, + 'focus_actor_dist': 1164.842041015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.67941284, -1888.90588379, 16.88464355]), + 'frame': 13633, + 'frame_number': 13633, + 'framesequence': 13631, + 'gaze_dir': array([ 0.98058069, 0.11508592, -0.15879796]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11508592, -0.15879796]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11508592, -0.15879796]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.96890116110444, + 'timestamp_carla': 55968, + 'timestamp_device': 55605, + 'timestamp_stream': 55.96890116110444, + 'transform': [array([ 0.00987167, -0.00354858, 0.16489573]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.67262762e-05, -6.39669452e-05, -5.02322521e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617871, -18.3298645 , 0.16717312]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.76041578e-06, 3.14210780e-07, 2.78691616e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8421630859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.84695435, -1888.24084473, 16.88476562]), + 'frame': 13634, + 'frame_number': 13634, + 'framesequence': 13632, + 'gaze_dir': array([ 0.98058069, 0.11571984, -0.15833659]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11571984, -0.15833659]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11571984, -0.15833659]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.97251595929265, + 'timestamp_carla': 55972, + 'timestamp_device': 55609, + 'timestamp_stream': 55.97251595929265, + 'transform': [array([ 0.00987183, -0.00354858, 0.16489713]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.69364812e-05, 9.32688781e-05, -1.51947248e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617918, -18.3298645 , 0.16717678]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.66881329e-06, 1.64372608e-07, 8.48006239e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.842529296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.06695557, -1887.35449219, 16.88464355]), + 'frame': 13635, + 'frame_number': 13635, + 'framesequence': 13633, + 'gaze_dir': array([ 0.98058069, 0.11635251, -0.15787226]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11635251, -0.15787226]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11635251, -0.15787226]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.976601362228394, + 'timestamp_carla': 55976, + 'timestamp_device': 55613, + 'timestamp_stream': 55.976601362228394, + 'transform': [array([ 0.00987183, -0.00354858, 0.16489713]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.38256710e-05, 3.60305057e-05, -1.93441974e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617942, -18.3298645 , 0.16717048]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 3.99912233e-06, 7.59132632e-08, -3.52993055e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8427734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.28361511, -1886.46643066, 16.88439941]), + 'frame': 13636, + 'frame_number': 13636, + 'framesequence': 13634, + 'gaze_dir': array([ 0.98058069, 0.11698333, -0.15740541]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11698333, -0.15740541]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11698333, -0.15740541]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.98070386052132, + 'timestamp_carla': 55980, + 'timestamp_device': 55617, + 'timestamp_stream': 55.98070386052132, + 'transform': [array([ 0.00987183, -0.00354858, 0.16489713]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.96723795e-05, 9.81318371e-05, -3.54768713e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617942, -18.3298645 , 0.1671574 ]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 3.81639666e-06, -1.95944438e-07, -5.42714493e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8428955078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.4967041 , -1885.57739258, 16.88439941]), + 'frame': 13637, + 'frame_number': 13637, + 'framesequence': 13635, + 'gaze_dir': array([ 0.98058057, 0.11761165, -0.15693647]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.11761165, -0.15693647]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.11761165, -0.15693647]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.98493466153741, + 'timestamp_carla': 55984, + 'timestamp_device': 55621, + 'timestamp_stream': 55.98493466153741, + 'transform': [array([ 0.00987183, -0.00354858, 0.16489713]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.84795663e-05, 9.71918271e-05, -7.78731248e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617978, -18.3298645 , 0.16715893]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.85053488e-06, 2.21410289e-07, 2.99660751e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.843017578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.70602417, -1884.68847656, 16.88415527]), + 'frame': 13638, + 'frame_number': 13638, + 'framesequence': 13636, + 'gaze_dir': array([ 0.98058069, 0.11839504, -0.15634634]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11839504, -0.15634634]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11839504, -0.15634634]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.9892043620348, + 'timestamp_carla': 55989, + 'timestamp_device': 55626, + 'timestamp_stream': 55.9892043620348, + 'transform': [array([ 0.00987183, -0.00354858, 0.16489713]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.21857476e-05, -5.80036212e-05, -2.73151272e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03618014, -18.3298645 , 0.16716708]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.52942459e-06, 3.13546025e-07, 1.32838963e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.843017578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.96286011, -1883.57531738, 16.88415527]), + 'frame': 13639, + 'frame_number': 13639, + 'framesequence': 13637, + 'gaze_dir': array([ 0.98058069, 0.11886329, -0.15599063]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11886329, -0.15599063]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11886329, -0.15599063]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.99301785975695, + 'timestamp_carla': 55993, + 'timestamp_device': 55629, + 'timestamp_stream': 55.99301785975695, + 'transform': [array([ 0.00987183, -0.00354858, 0.16489713]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([6.61557569e-05, 3.94385606e-05, 3.48623047e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03618073, -18.3298645 , 0.16716872]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.76299556e-06, 2.60132367e-07, 2.16621745e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.843017578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.114151 , -1882.90722656, 16.88415527]), + 'frame': 13640, + 'frame_number': 13640, + 'framesequence': 13638, + 'gaze_dir': array([ 0.98058069, 0.11933105, -0.15563309]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11933105, -0.15563309]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11933105, -0.15563309]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.99618745967746, + 'timestamp_carla': 55996, + 'timestamp_device': 55632, + 'timestamp_stream': 55.99618745967746, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489889]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.47965213e-05, -6.17120677e-05, 6.92516835e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03618073, -18.3298645 , 0.16716476]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.64865934e-06, 3.66481260e-07, 2.00694849e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8431396484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.26365662, -1882.23791504, 16.8840332 ]), + 'frame': 13641, + 'frame_number': 13641, + 'framesequence': 13639, + 'gaze_dir': array([ 0.98058069, 0.11995229, -0.15515478]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11995229, -0.15515478]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11995229, -0.15515478]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.99950326234102, + 'timestamp_carla': 55999, + 'timestamp_device': 55636, + 'timestamp_stream': 55.99950326234102, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489889]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.35487527e-05, -5.96487262e-05, -2.64336080e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0361805 , -18.3298645 , 0.16716373]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.32001434e-06, 2.34954058e-07, -8.21857902e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8433837890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.45965576, -1881.34594727, 16.88391113]), + 'frame': 13642, + 'frame_number': 13642, + 'framesequence': 13640, + 'gaze_dir': array([ 0.98058069, 0.12041756, -0.15479396]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12041756, -0.15479396]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12041756, -0.15479396]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.00280275940895, + 'timestamp_carla': 56002, + 'timestamp_device': 55639, + 'timestamp_stream': 56.00280275940895, + 'transform': [array([ 0.00987213, -0.00354858, 0.16490038]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.61904845e-05, 3.42279891e-05, 4.93057826e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0361805 , -18.3298645 , 0.16716373]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.57592296e-06, 3.01355016e-07, 7.09790038e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8433837890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.60446167, -1880.67553711, 16.88391113]), + 'frame': 13643, + 'frame_number': 13643, + 'framesequence': 13641, + 'gaze_dir': array([ 0.98058057, 0.12118959, -0.15419027]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.12118959, -0.15419027]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.12118959, -0.15419027]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.007676761597395, + 'timestamp_carla': 56007, + 'timestamp_device': 55644, + 'timestamp_stream': 56.007676761597395, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489778]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.87435684e-05, -5.37308078e-05, 7.03593400e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0361805 , -18.3298645 , 0.16716373]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.55785312e-06, 3.43166761e-07, 1.13867143e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.84107971, -1879.55871582, 16.88366699]), + 'frame': 13644, + 'frame_number': 13644, + 'framesequence': 13642, + 'gaze_dir': array([ 0.98058069, 0.12180563, -0.15370409]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12180563, -0.15370409]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12180563, -0.15370409]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.01194475963712, + 'timestamp_carla': 56011, + 'timestamp_device': 55648, + 'timestamp_stream': 56.01194475963712, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489778]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.66575361e-05, 4.10300527e-05, -7.75110777e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03618073, -18.3298645 , 0.16715652]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.47654156e-06, 9.87434703e-08, -5.06946708e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.02648926, -1878.66357422, 16.88342285]), + 'frame': 13645, + 'frame_number': 13645, + 'framesequence': 13643, + 'gaze_dir': array([ 0.98058057, 0.12241971, -0.15321544]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.12241971, -0.15321544]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.12241971, -0.15321544]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.015470162034035, + 'timestamp_carla': 56015, + 'timestamp_device': 55652, + 'timestamp_stream': 56.015470162034035, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489778]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.66576519e-05, 3.50030896e-05, -3.17048659e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03618085, -18.3298645 , 0.16715549]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.46675813e-06, 2.31730510e-07, -1.48117188e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.20834351, -1877.7677002 , 16.88342285]), + 'frame': 13646, + 'frame_number': 13646, + 'framesequence': 13644, + 'gaze_dir': array([ 0.98058057, 0.12287856, -0.15284769]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.12287856, -0.15284769]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.12287856, -0.15284769]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.019005961716175, + 'timestamp_carla': 56019, + 'timestamp_device': 55655, + 'timestamp_stream': 56.019005961716175, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489901]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.65226980e-05, 4.27491941e-05, -1.62924346e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.020508436486124992, + 'Location': array([ 1.03618121, -18.3298645 , 0.16714981]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([ 4.12009194e-06, 4.98606800e-09, -3.11929267e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8438720703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.34225464, -1877.09594727, 16.88330078]), + 'frame': 13647, + 'frame_number': 13647, + 'framesequence': 13645, + 'gaze_dir': array([ 0.98058057, 0.1234892 , -0.15235476]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1234892 , -0.15235476]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1234892 , -0.15235476]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.02294595912099, + 'timestamp_carla': 56022, + 'timestamp_device': 55659, + 'timestamp_stream': 56.02294595912099, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489901]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00328402, -0.00291868, -0.00034869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050362527370453, + 'FR_Wheel_Angle': 0.02050776220858097, + 'Location': array([ 1.03616059, -18.32989311, 0.1671503 ]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([1.35256641e-03, 1.49008597e-03, 1.00779534e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8441162109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.51779175, -1876.19885254, 16.88330078]), + 'frame': 13648, + 'frame_number': 13648, + 'framesequence': 13646, + 'gaze_dir': array([ 0.98058069, 0.12409731, -0.15185988]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12409731, -0.15185988]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12409731, -0.15185988]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.026689659804106, + 'timestamp_carla': 56026, + 'timestamp_device': 55663, + 'timestamp_stream': 56.026689659804106, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489901]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00180955, -0.00162864, 0.00022463]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020503921434283257, + 'FR_Wheel_Angle': 0.02050723135471344, + 'Location': array([ 1.03616607, -18.32989311, 0.16714916]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([0.00083828, 0.00086774, 0.00010301]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8443603515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.68966675, -1875.30187988, 16.88305664]), + 'frame': 13649, + 'frame_number': 13649, + 'framesequence': 13647, + 'gaze_dir': array([ 0.98058069, 0.124704 , -0.15136206]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.124704 , -0.15136206]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.124704 , -0.15136206]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.03045916184783, + 'timestamp_carla': 56030, + 'timestamp_device': 55667, + 'timestamp_stream': 56.03045916184783, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489901]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.97910634e-03, 1.71582273e-03, -3.05107860e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020503684878349304, + 'FR_Wheel_Angle': 0.02050771377980709, + 'Location': array([ 1.03615022, -18.329916 , 0.16714798]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-1.11451279e-03, -1.46937929e-03, 3.51691233e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.844482421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.85801697, -1874.40332031, 16.88293457]), + 'frame': 13650, + 'frame_number': 13650, + 'framesequence': 13648, + 'gaze_dir': array([ 0.98058069, 0.12515727, -0.15098748]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12515727, -0.15098748]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12515727, -0.15098748]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.034063059836626, + 'timestamp_carla': 56034, + 'timestamp_device': 55670, + 'timestamp_stream': 56.034063059836626, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489901]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00220144, -0.00177913, 0.0005086 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020503995940089226, + 'FR_Wheel_Angle': 0.02050739899277687, + 'Location': array([ 1.03613806, -18.32993698, 0.16714886]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([7.06979190e-04, 7.09743763e-04, 3.06987749e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8446044921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.9818573 , -1873.72973633, 16.88269043]), + 'frame': 13651, + 'frame_number': 13651, + 'framesequence': 13649, + 'gaze_dir': array([ 0.98058069, 0.12576047, -0.15048544]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12576047, -0.15048544]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12576047, -0.15048544]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.03790866211057, + 'timestamp_carla': 56037, + 'timestamp_device': 55674, + 'timestamp_stream': 56.03790866211057, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489901]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00678543, 0.00565147, 0.00016984]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050110511481762, + 'FR_Wheel_Angle': 0.020506447181105614, + 'Location': array([ 1.03602517, -18.33007622, 0.16715114]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-0.00561328, -0.00682738, 0.00012168]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8448486328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.14396667, -1872.83007812, 16.88256836]), + 'frame': 13652, + 'frame_number': 13652, + 'framesequence': 13650, + 'gaze_dir': array([ 0.98058069, 0.1265109 , -0.14985511]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1265109 , -0.14985511]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1265109 , -0.14985511]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.04255826026201, + 'timestamp_carla': 56042, + 'timestamp_device': 55679, + 'timestamp_stream': 56.04255826026201, + 'transform': [array([ 0.00987228, -0.00354858, 0.16489755]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00038313, -0.00011777, 0.00038309]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050144225358963, + 'FR_Wheel_Angle': 0.020504212006926537, + 'Location': array([ 1.03577185, -18.3303833 , 0.16715251]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-5.02815284e-03, -6.12397771e-03, -2.62832637e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.844970703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.34132385, -1871.70556641, 16.88232422]), + 'frame': 13653, + 'frame_number': 13653, + 'framesequence': 13651, + 'gaze_dir': array([ 0.98058057, 0.12710954, -0.14934765]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.12710954, -0.14934765]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.12710954, -0.14934765]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.04645565897226, + 'timestamp_carla': 56046, + 'timestamp_device': 55683, + 'timestamp_stream': 56.04645565897226, + 'transform': [array([ 0.00987228, -0.00354858, 0.16489755]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.47252160e-03, 3.52195743e-03, 2.35671523e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020499011501669884, + 'FR_Wheel_Angle': 0.02050444856286049, + 'Location': array([ 1.03544855, -18.33077431, 0.16715485]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-9.25593264e-03, -1.11677619e-02, -6.54482792e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.844970703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.49528503, -1870.80456543, 16.88220215]), + 'frame': 13654, + 'frame_number': 13654, + 'framesequence': 13652, + 'gaze_dir': array([ 0.98058069, 0.12755677, -0.14896588]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12755677, -0.14896588]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12755677, -0.14896588]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.050265960395336, + 'timestamp_carla': 56050, + 'timestamp_device': 55686, + 'timestamp_stream': 56.050265960395336, + 'transform': [array([ 0.00987228, -0.00354858, 0.16489755]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0028996 , 0.00241459, 0.00021904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020498454570770264, + 'FR_Wheel_Angle': 0.02050391398370266, + 'Location': array([ 1.03507209, -18.33122826, 0.16715492]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-1.02333985e-02, -1.23304324e-02, -2.25305553e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.844970703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.60830688, -1870.12902832, 16.88220215]), + 'frame': 13655, + 'frame_number': 13655, + 'framesequence': 13653, + 'gaze_dir': array([ 0.98058069, 0.12830018, -0.14832608]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12830018, -0.14832608]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12830018, -0.14832608]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.054406460374594, + 'timestamp_carla': 56054, + 'timestamp_device': 55691, + 'timestamp_stream': 56.054406460374594, + 'transform': [array([ 0.00987228, -0.00354858, 0.16489755]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00158905, -0.00132192, 0.00042963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020498909056186676, + 'FR_Wheel_Angle': 0.020501578226685524, + 'Location': array([ 1.03461754, -18.33177567, 0.16715419]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-9.44048259e-03, -1.13788890e-02, 4.47487837e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8453369140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.79232788, -1869.00134277, 16.88183594]), + 'frame': 13656, + 'frame_number': 13656, + 'framesequence': 13654, + 'gaze_dir': array([ 0.98058069, 0.12889269, -0.1478115 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12889269, -0.1478115 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12889269, -0.1478115 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.0588750615716, + 'timestamp_carla': 56058, + 'timestamp_device': 55695, + 'timestamp_stream': 56.0588750615716, + 'transform': [array([ 0.00987228, -0.00354858, 0.16489755]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.14309914e-03, 2.66006892e-03, 5.09000238e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020496215671300888, + 'FR_Wheel_Angle': 0.020501626655459404, + 'Location': array([ 1.03401804, -18.33249664, 0.16715336]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-1.41302031e-02, -1.69750247e-02, 1.55162816e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.93557739, -1868.09851074, 16.88146973]), + 'frame': 13657, + 'frame_number': 13657, + 'framesequence': 13655, + 'gaze_dir': array([ 0.98058057, 0.1296297 , -0.14716554]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1296297 , -0.14716554]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1296297 , -0.14716554]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.063277158886194, + 'timestamp_carla': 56063, + 'timestamp_device': 55700, + 'timestamp_stream': 56.063277158886194, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489641]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.54423127e-03, 4.55014082e-03, -8.56863699e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049439586699009, + 'FR_Wheel_Angle': 0.02049953117966652, + 'Location': array([ 1.03339577, -18.33324432, 0.16715407]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-0.01730435, -0.0207533 , 0.00018911]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8458251953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.10925293, -1866.97021484, 16.88146973]), + 'frame': 13658, + 'frame_number': 13658, + 'framesequence': 13656, + 'gaze_dir': array([ 0.98058069, 0.13021758, -0.14664564]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13021758, -0.14664564]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13021758, -0.14664564]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.067764561623335, + 'timestamp_carla': 56067, + 'timestamp_device': 55704, + 'timestamp_stream': 56.067764561623335, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489641]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.81971136e-02, 1.52792055e-02, 5.03685515e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02048591896891594, + 'FR_Wheel_Angle': 0.0204918272793293, + 'Location': array([ 1.03235924, -18.33448601, 0.1671571 ]), + 'Rotation': array([-4.51953597e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-0.03207467, -0.03834884, 0.00011765]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.845947265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.24430847, -1866.06616211, 16.88122559]), + 'frame': 13659, + 'frame_number': 13659, + 'framesequence': 13657, + 'gaze_dir': array([ 0.98058069, 0.13094933, -0.14599258]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13094933, -0.14599258]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13094933, -0.14599258]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.07217786088586, + 'timestamp_carla': 56072, + 'timestamp_device': 55709, + 'timestamp_stream': 56.07217786088586, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489534]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00553309, -0.00471631, 0.0003597 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489441230893135, + 'FR_Wheel_Angle': 0.020492253825068474, + 'Location': array([ 1.03100777, -18.33610153, 0.16716373]), + 'Rotation': array([-4.51953597e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-0.02593555, -0.03102855, 0.00026662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84619140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.40800476, -1864.9354248 , 16.88098145]), + 'frame': 13660, + 'frame_number': 13660, + 'framesequence': 13658, + 'gaze_dir': array([ 0.98058057, 0.13153192, -0.14546789]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.13153192, -0.14546789]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.13153192, -0.14546789]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.076753959059715, + 'timestamp_carla': 56076, + 'timestamp_device': 55713, + 'timestamp_stream': 56.076753959059715, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489534]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 4.12498787e-03, -3.30446078e-03, -5.11776943e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489409565925598, + 'FR_Wheel_Angle': 0.020494883880019188, + 'Location': array([ 1.02976334, -18.33758926, 0.16716366]), + 'Rotation': array([-4.51953597e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-2.59941723e-02, -3.11072525e-02, 2.79879569e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8460693359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.534729 , -1864.03100586, 16.88098145]), + 'frame': 13661, + 'frame_number': 13661, + 'framesequence': 13659, + 'gaze_dir': array([ 0.98058069, 0.13211298, -0.14494041]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13211298, -0.14494041]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13211298, -0.14494041]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.080476861447096, + 'timestamp_carla': 56080, + 'timestamp_device': 55717, + 'timestamp_stream': 56.080476861447096, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489534]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.46289018e-03, -1.34097948e-03, -9.55388532e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02048954926431179, + 'FR_Wheel_Angle': 0.02049507014453411, + 'Location': array([ 1.02862251, -18.33895683, 0.16715916]), + 'Rotation': array([-4.51953597e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-0.02574358, -0.03081135, -0.00012252]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84619140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.65800476, -1863.12524414, 16.88085938]), + 'frame': 13662, + 'frame_number': 13662, + 'framesequence': 13660, + 'gaze_dir': array([ 0.98058057, 0.13269192, -0.14441057]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.13269192, -0.14441057]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.13269192, -0.14441057]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.084370259195566, + 'timestamp_carla': 56084, + 'timestamp_device': 55721, + 'timestamp_stream': 56.084370259195566, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489534]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00348206, -0.00288856, 0.00029999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490363240242004, + 'FR_Wheel_Angle': 0.02049315720796585, + 'Location': array([ 1.02745128, -18.34035873, 0.16716275]), + 'Rotation': array([-4.51953597e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-0.02433192, -0.02911753, 0.00025411]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.846435546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.7776947 , -1862.21887207, 16.88061523]), + 'frame': 13663, + 'frame_number': 13663, + 'framesequence': 13661, + 'gaze_dir': array([ 0.98058069, 0.13326818, -0.14387895]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13326818, -0.14387895]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13326818, -0.14387895]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.08853046223521, + 'timestamp_carla': 56088, + 'timestamp_device': 55725, + 'timestamp_stream': 56.08853046223521, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489534]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00422776, -0.00347783, 0.00031728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490558817982674, + 'FR_Wheel_Angle': 0.0204932764172554, + 'Location': array([ 1.02632737, -18.34170341, 0.16716488]), + 'Rotation': array([-4.51953597e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([-0.02399263, -0.02871329, 0.00017411]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8468017578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.89363098, -1861.31311035, 16.88024902]), + 'frame': 13664, + 'frame_number': 13664, + 'framesequence': 13662, + 'gaze_dir': array([ 0.98058069, 0.13384287, -0.14334452]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13384287, -0.14334452]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13384287, -0.14334452]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.0927263610065, + 'timestamp_carla': 56092, + 'timestamp_device': 55729, + 'timestamp_stream': 56.0927263610065, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489534]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02316289, 0.0194381 , -0.00031437]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020479926839470863, + 'FR_Wheel_Angle': 0.02048562467098236, + 'Location': array([ 1.02494299, -18.34335709, 0.16716214]), + 'Rotation': array([-4.54344153e-02, 4.99725304e+01, -3.72619666e-02]), + 'Velocity': array([-0.04251271, -0.05077756, 0.00034431]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8470458984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.006073 , -1860.40588379, 16.88000488]), + 'frame': 13665, + 'frame_number': 13665, + 'framesequence': 13663, + 'gaze_dir': array([ 0.98058069, 0.13441485, -0.14280829]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13441485, -0.14280829]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13441485, -0.14280829]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.09684615954757, + 'timestamp_carla': 56096, + 'timestamp_device': 55733, + 'timestamp_stream': 56.09684615954757, + 'transform': [array([ 0.00987198, -0.00354858, 0.16489534]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.17164128e-03, -8.41051631e-04, -7.48817911e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020484386011958122, + 'FR_Wheel_Angle': 0.02048729546368122, + 'Location': array([ 1.02302086, -18.34565353, 0.16717376]), + 'Rotation': array([-4.54344153e-02, 4.99725304e+01, -3.72619666e-02]), + 'Velocity': array([-0.03675231, -0.04392151, 0.00018854]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84716796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.11471558, -1859.49902344, 16.87988281]), + 'frame': 13666, + 'frame_number': 13666, + 'framesequence': 13664, + 'gaze_dir': array([ 0.98058069, 0.13512737, -0.14213429]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13512737, -0.14213429]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13512737, -0.14213429]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.10168036073446, + 'timestamp_carla': 56101, + 'timestamp_device': 55738, + 'timestamp_stream': 56.10168036073446, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489363]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00460694, -0.00372652, -0.00010442]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020484955981373787, + 'FR_Wheel_Angle': 0.020490411669015884, + 'Location': array([ 1.02150369, -18.34746361, 0.16717471]), + 'Rotation': array([-4.54344153e-02, 4.99725304e+01, -3.72619666e-02]), + 'Velocity': array([-0.03375134, -0.04034695, 0.0001802 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.847412109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.24559021, -1858.36413574, 16.87963867]), + 'frame': 13667, + 'frame_number': 13667, + 'framesequence': 13665, + 'gaze_dir': array([ 0.98058057, 0.13569504, -0.14159241]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.13569504, -0.14159241]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.13569504, -0.14159241]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.105713561177254, + 'timestamp_carla': 56105, + 'timestamp_device': 55742, + 'timestamp_stream': 56.105713561177254, + 'transform': [array([ 0.00987213, -0.00354858, 0.16489363]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0038322 , -0.00310376, 0.00022059]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02048121951520443, + 'FR_Wheel_Angle': 0.020483769476413727, + 'Location': array([ 1.01955986, -18.34978485, 0.16717021]), + 'Rotation': array([-4.54344153e-02, 4.99725304e+01, -3.72619666e-02]), + 'Velocity': array([-0.04026479, -0.04809867, -0.00026277]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.34616089, -1857.45544434, 16.87927246]), + 'frame': 13668, + 'frame_number': 13668, + 'framesequence': 13666, + 'gaze_dir': array([ 0.98058069, 0.13611898, -0.14118493]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13611898, -0.14118493]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13611898, -0.14118493]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.10935426130891, + 'timestamp_carla': 56109, + 'timestamp_device': 55745, + 'timestamp_stream': 56.10935426130891, + 'transform': [array([ 0.00987228, -0.00354858, 0.16489485]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.16111410e-02, 1.81221720e-02, -8.47761257e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020465120673179626, + 'FR_Wheel_Angle': 0.020471233874559402, + 'Location': array([ 1.0168525 , -18.35301399, 0.1671754 ]), + 'Rotation': array([-4.64521125e-02, 4.99726982e+01, -3.72619666e-02]), + 'Velocity': array([-0.06830396, -0.0815081 , 0.00044641]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8477783203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.41915894, -1856.77441406, 16.87915039]), + 'frame': 13669, + 'frame_number': 13669, + 'framesequence': 13667, + 'gaze_dir': array([ 0.98058069, 0.13668287, -0.14063911]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13668287, -0.14063911]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13668287, -0.14063911]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.11270426213741, + 'timestamp_carla': 56112, + 'timestamp_device': 55749, + 'timestamp_stream': 56.11270426213741, + 'transform': [array([ 0.00987228, -0.00354858, 0.16489485]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00766715, -0.00654962, -0.00053634]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020470857620239258, + 'FR_Wheel_Angle': 0.020476723089814186, + 'Location': array([ 1.01415312, -18.35623741, 0.16718887]), + 'Rotation': array([-4.64521125e-02, 4.99726982e+01, -3.72619666e-02]), + 'Velocity': array([-0.05831434, -0.0696087 , 0.0003056 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8480224609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.51339722, -1855.8651123 , 16.87902832]), + 'frame': 13670, + 'frame_number': 13670, + 'framesequence': 13668, + 'gaze_dir': array([ 0.98058057, 0.13710392, -0.14022864]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.13710392, -0.14022864]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.13710392, -0.14022864]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.116179559379816, + 'timestamp_carla': 56116, + 'timestamp_device': 55752, + 'timestamp_stream': 56.116179559379816, + 'transform': [array([ 0.00987244, -0.00354858, 0.16489615]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0186724 , -0.01565016, 0.00021885]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020477252081036568, + 'FR_Wheel_Angle': 0.020480284467339516, + 'Location': array([ 1.01167071, -18.35919952, 0.16719204]), + 'Rotation': array([-4.63564917e-02, 4.99727058e+01, -3.72619629e-02]), + 'Velocity': array([-0.0471753 , -0.05633331, 0.00025815]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8482666015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.58164978, -1855.18359375, 16.87878418]), + 'frame': 13671, + 'frame_number': 13671, + 'framesequence': 13669, + 'gaze_dir': array([ 0.98058069, 0.13766398, -0.1396789 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13766398, -0.1396789 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13766398, -0.1396789 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.119861759245396, + 'timestamp_carla': 56119, + 'timestamp_device': 55756, + 'timestamp_stream': 56.119861759245396, + 'transform': [array([ 0.00987244, -0.00354858, 0.16489615]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00840249, -0.00691381, -0.00027055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020478380843997, + 'FR_Wheel_Angle': 0.020483961328864098, + 'Location': array([ 1.00938439, -18.36193085, 0.1671894 ]), + 'Rotation': array([-4.63564917e-02, 4.99727058e+01, -3.72619629e-02]), + 'Velocity': array([-0.04520164, -0.05398964, 0.00020455]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8487548828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.66957092, -1854.27368164, 16.87841797]), + 'frame': 13672, + 'frame_number': 13672, + 'framesequence': 13670, + 'gaze_dir': array([ 0.98058069, 0.13822128, -0.13912743]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13822128, -0.13912743]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13822128, -0.13912743]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.123511761426926, + 'timestamp_carla': 56123, + 'timestamp_device': 55760, + 'timestamp_stream': 56.123511761426926, + 'transform': [array([ 0.00987244, -0.00354858, 0.16489615]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00216691, 0.00195243, -0.00030587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02046886458992958, + 'FR_Wheel_Angle': 0.020472055301070213, + 'Location': array([ 1.00652885, -18.36533928, 0.16719535]), + 'Rotation': array([-4.69985306e-02, 4.99727974e+01, -3.72619666e-02]), + 'Velocity': array([-0.06179075, -0.07374273, 0.0002756 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.848876953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.75372314, -1853.36425781, 16.8782959 ]), + 'frame': 13673, + 'frame_number': 13673, + 'framesequence': 13671, + 'gaze_dir': array([ 0.98058069, 0.13863835, -0.13871184]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13863835, -0.13871184]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13863835, -0.13871184]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.12673496082425, + 'timestamp_carla': 56126, + 'timestamp_device': 55763, + 'timestamp_stream': 56.12673496082425, + 'transform': [array([ 0.00987244, -0.00354858, 0.16489615]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00418297, -0.0036012 , -0.02375537]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02046973817050457, + 'FR_Wheel_Angle': 0.02047540247440338, + 'Location': array([ 1.00366175, -18.36876106, 0.1672041 ]), + 'Rotation': array([-4.69643772e-02, 4.99729004e+01, -3.72619666e-02]), + 'Velocity': array([-0.06027233, -0.07192342, 0.00017571]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.84912109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.81454468, -1852.68115234, 16.87805176]), + 'frame': 13674, + 'frame_number': 13674, + 'framesequence': 13672, + 'gaze_dir': array([ 0.98058069, 0.13905361, -0.13829553]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13905361, -0.13829553]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13905361, -0.13829553]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.130141261965036, + 'timestamp_carla': 56130, + 'timestamp_device': 55766, + 'timestamp_stream': 56.130141261965036, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00614045, -0.00525749, 0.00226781]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020472688600420952, + 'FR_Wheel_Angle': 0.020475754514336586, + 'Location': array([ 1.00107002, -18.37185478, 0.16720635]), + 'Rotation': array([-4.69643772e-02, 4.99729004e+01, -3.72619666e-02]), + 'Velocity': array([-0.05512863, -0.06580652, 0.00017029]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8492431640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.87321472, -1851.9987793 , 16.87792969]), + 'frame': 13675, + 'frame_number': 13675, + 'framesequence': 13673, + 'gaze_dir': array([ 0.98058069, 0.13960591, -0.13773799]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13960591, -0.13773799]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13960591, -0.13773799]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.13345365971327, + 'timestamp_carla': 56133, + 'timestamp_device': 55770, + 'timestamp_stream': 56.13345365971327, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00754662, -0.00648826, 0.00041132]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020475901663303375, + 'FR_Wheel_Angle': 0.02048206329345703, + 'Location': array([ 0.99865574, -18.37473679, 0.16720703]), + 'Rotation': array([-4.69643772e-02, 4.99729004e+01, -3.72619666e-02]), + 'Velocity': array([-4.95234802e-02, -5.91431186e-02, 8.18777044e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8494873046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.94831848, -1851.08764648, 16.87780762]), + 'frame': 13676, + 'frame_number': 13676, + 'framesequence': 13674, + 'gaze_dir': array([ 0.98058069, 0.14001827, -0.13731878]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14001827, -0.13731878]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14001827, -0.13731878]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.136898562312126, + 'timestamp_carla': 56136, + 'timestamp_device': 55773, + 'timestamp_stream': 56.136898562312126, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 9.55791865e-03, -7.99831096e-03, 4.08296501e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020479397848248482, + 'FR_Wheel_Angle': 0.020482398569583893, + 'Location': array([ 0.99642622, -18.37739754, 0.16720626]), + 'Rotation': array([-4.69643772e-02, 4.99729004e+01, -3.72619666e-02]), + 'Velocity': array([-0.04343842, -0.05188115, 0.00019258]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8497314453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.0022583 , -1850.40478516, 16.87756348]), + 'frame': 13677, + 'frame_number': 13677, + 'framesequence': 13675, + 'gaze_dir': array([ 0.98058069, 0.14056665, -0.13675739]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14056665, -0.13675739]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14056665, -0.13675739]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.14065445959568, + 'timestamp_carla': 56140, + 'timestamp_device': 55777, + 'timestamp_stream': 56.14065445959568, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00380333, -0.00343682, 0.0003461 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02047789841890335, + 'FR_Wheel_Angle': 0.020480994135141373, + 'Location': array([ 0.99427772, -18.37996101, 0.16720679]), + 'Rotation': array([-4.69643772e-02, 4.99729004e+01, -3.72619666e-02]), + 'Velocity': array([-0.04605217, -0.05499142, 0.00023526]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.849853515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.07098389, -1849.49328613, 16.87744141]), + 'frame': 13678, + 'frame_number': 13678, + 'framesequence': 13676, + 'gaze_dir': array([ 0.98058069, 0.14111225, -0.13619433]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14111225, -0.13619433]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14111225, -0.13619433]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.14434165880084, + 'timestamp_carla': 56144, + 'timestamp_device': 55781, + 'timestamp_stream': 56.14434165880084, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00148849, -0.00118044, -0.00016559]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02047944813966751, + 'FR_Wheel_Angle': 0.02047939971089363, + 'Location': array([ 0.99212044, -18.38253593, 0.16720505]), + 'Rotation': array([-4.69643772e-02, 4.99729004e+01, -3.72619666e-02]), + 'Velocity': array([-0.04334941, -0.05178672, -0.00056838]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8502197265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.13606262, -1848.58227539, 16.8770752 ]), + 'frame': 13679, + 'frame_number': 13679, + 'framesequence': 13677, + 'gaze_dir': array([ 0.98058057, 0.1416561 , -0.13562857]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1416561 , -0.13562857]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1416561 , -0.13562857]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.14832445979118, + 'timestamp_carla': 56148, + 'timestamp_device': 55785, + 'timestamp_stream': 56.14832445979118, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02215061, 0.01853365, 0.00217723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02046940289437771, + 'FR_Wheel_Angle': 0.020472465083003044, + 'Location': array([ 0.9897697 , -18.38534355, 0.16720547]), + 'Rotation': array([-4.71214727e-02, 4.99729309e+01, -3.72619666e-02]), + 'Velocity': array([-0.06085707, -0.07262088, 0.00033049]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8505859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.19754028, -1847.67028809, 16.87670898]), + 'frame': 13680, + 'frame_number': 13680, + 'framesequence': 13678, + 'gaze_dir': array([ 0.98058069, 0.14219721, -0.13506117]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14219721, -0.13506117]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14219721, -0.13506117]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.15253046154976, + 'timestamp_carla': 56152, + 'timestamp_device': 55789, + 'timestamp_stream': 56.15253046154976, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00175213, -0.00149666, -0.000279 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020473666489124298, + 'FR_Wheel_Angle': 0.020479613915085793, + 'Location': array([ 0.98709273, -18.38853836, 0.1672177 ]), + 'Rotation': array([-4.71214727e-02, 4.99729309e+01, -3.72619666e-02]), + 'Velocity': array([-0.05341825, -0.06377906, 0.00015983]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8509521484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.25532532, -1846.75878906, 16.87634277]), + 'frame': 13681, + 'frame_number': 13681, + 'framesequence': 13679, + 'gaze_dir': array([ 0.98058069, 0.14273651, -0.13449107]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14273651, -0.13449107]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14273651, -0.13449107]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.15568336099386, + 'timestamp_carla': 56155, + 'timestamp_device': 55793, + 'timestamp_stream': 56.15568336099386, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489732]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 7.30214221e-03, -6.05556462e-03, 4.66487691e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020477639511227608, + 'FR_Wheel_Angle': 0.020480545237660408, + 'Location': array([ 0.98479992, -18.39127541, 0.16722134]), + 'Rotation': array([-4.71214727e-02, 4.99729309e+01, -3.72619666e-02]), + 'Velocity': array([-0.04650173, -0.05552649, 0.00019132]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8511962890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.30949402, -1845.84619141, 16.87609863]), + 'frame': 13682, + 'frame_number': 13682, + 'framesequence': 13680, + 'gaze_dir': array([ 0.98058069, 0.14327306, -0.13391936]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14327306, -0.13391936]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14327306, -0.13391936]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.16057736054063, + 'timestamp_carla': 56160, + 'timestamp_device': 55797, + 'timestamp_stream': 56.16057736054063, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489473]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00478766, 0.00388891, -0.0026642 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020472032949328423, + 'FR_Wheel_Angle': 0.0204777829349041, + 'Location': array([ 0.98216426, -18.39442253, 0.16722785]), + 'Rotation': array([-4.71214727e-02, 4.99729309e+01, -3.72619666e-02]), + 'Velocity': array([-0.05626643, -0.06716716, 0.00026325]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.851318359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.35997009, -1844.93432617, 16.87597656]), + 'frame': 13683, + 'frame_number': 13683, + 'framesequence': 13681, + 'gaze_dir': array([ 0.98058069, 0.14367445, -0.13348863]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14367445, -0.13348863]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14367445, -0.13348863]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.16411016136408, + 'timestamp_carla': 56164, + 'timestamp_device': 55800, + 'timestamp_stream': 56.16411016136408, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489473]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00818203, -0.00677034, -0.00024179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02047370932996273, + 'FR_Wheel_Angle': 0.0204799622297287, + 'Location': array([ 0.97967029, -18.39739799, 0.16723029]), + 'Rotation': array([-4.71214727e-02, 4.99728127e+01, -3.72619666e-02]), + 'Velocity': array([-0.04954628, -0.05911789, -0.00053118]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.851318359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.39537048, -1844.24938965, 16.87573242]), + 'frame': 13684, + 'frame_number': 13684, + 'framesequence': 13682, + 'gaze_dir': array([ 0.98058057, 0.14420696, -0.13291317]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.14420696, -0.13291317]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.14420696, -0.13291317]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.16762176156044, + 'timestamp_carla': 56167, + 'timestamp_device': 55804, + 'timestamp_stream': 56.16762176156044, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489473]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02680039, 0.02466643, -0.23048821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02046034298837185, + 'FR_Wheel_Angle': 0.020465295761823654, + 'Location': array([ 0.97675788, -18.40080643, 0.16723785]), + 'Rotation': array([-4.78523038e-02, 4.99671936e+01, -3.72619666e-02]), + 'Velocity': array([-0.07696359, -0.09115741, 0.00022633]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.43945312, -1843.3371582 , 16.87561035]), + 'frame': 13685, + 'frame_number': 13685, + 'framesequence': 13683, + 'gaze_dir': array([ 0.98058069, 0.14473766, -0.13233507]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14473766, -0.13233507]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14473766, -0.13233507]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.171648658812046, + 'timestamp_carla': 56171, + 'timestamp_device': 55808, + 'timestamp_stream': 56.171648658812046, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489473]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01212704, 0.00934541, -0.28690177]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020459009334445, + 'FR_Wheel_Angle': 0.020467927679419518, + 'Location': array([ 0.97318757, -18.40499878, 0.16724831]), + 'Rotation': array([-4.84260395e-02, 4.99631004e+01, -3.72619666e-02]), + 'Velocity': array([-0.07916599, -0.09402976, 0.00025285]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.851806640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.47994995, -1842.4239502 , 16.87536621]), + 'frame': 13686, + 'frame_number': 13686, + 'framesequence': 13684, + 'gaze_dir': array([ 0.98058069, 0.14513381, -0.13190049]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14513381, -0.13190049]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14513381, -0.13190049]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.17527626082301, + 'timestamp_carla': 56175, + 'timestamp_device': 55811, + 'timestamp_stream': 56.17527626082301, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489473]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01564527, -0.01340327, 0.24497643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020465433597564697, + 'FR_Wheel_Angle': 0.020465116947889328, + 'Location': array([ 0.9697448 , -18.40907478, 0.16725335]), + 'Rotation': array([-4.83030938e-02, 4.99629517e+01, -3.72619666e-02]), + 'Velocity': array([-0.06798763, -0.08067233, 0.00016214]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8521728515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.50790405, -1841.73950195, 16.875 ]), + 'frame': 13687, + 'frame_number': 13687, + 'framesequence': 13685, + 'gaze_dir': array([ 0.98058069, 0.14566045, -0.13131866]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14566045, -0.13131866]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14566045, -0.13131866]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.17903796210885, + 'timestamp_carla': 56179, + 'timestamp_device': 55815, + 'timestamp_stream': 56.17903796210885, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489473]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00650114, 0.00434426, -0.00494625]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02045264095067978, + 'FR_Wheel_Angle': 0.02045714668929577, + 'Location': array([ 0.96558338, -18.41403198, 0.16725922]), + 'Rotation': array([-4.87402268e-02, 4.99620781e+01, -3.72619629e-02]), + 'Velocity': array([-8.91641974e-02, -1.06562689e-01, 4.77600079e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8524169921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.54197693, -1840.8260498 , 16.87475586]), + 'frame': 13688, + 'frame_number': 13688, + 'framesequence': 13686, + 'gaze_dir': array([ 0.98058057, 0.14618476, -0.13073473]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.14618476, -0.13073473]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.14618476, -0.13073473]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.18295066058636, + 'timestamp_carla': 56183, + 'timestamp_device': 55819, + 'timestamp_stream': 56.18295066058636, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489473]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01200824, -0.0093548 , -0.08264129]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020457666367292404, + 'FR_Wheel_Angle': 0.020461758598685265, + 'Location': array([ 0.96176475, -18.41859245, 0.16726132]), + 'Rotation': array([-4.84260395e-02, 4.99624367e+01, -3.72619666e-02]), + 'Velocity': array([-0.08133491, -0.09696216, 0.00031683]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8526611328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.5723877 , -1839.91235352, 16.87451172]), + 'frame': 13689, + 'frame_number': 13689, + 'framesequence': 13687, + 'gaze_dir': array([ 0.98058069, 0.14683627, -0.1300026 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14683627, -0.1300026 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14683627, -0.1300026 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.187344159930944, + 'timestamp_carla': 56187, + 'timestamp_device': 55824, + 'timestamp_stream': 56.187344159930944, + 'transform': [array([ 0.00987259, -0.00354858, 0.16489324]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01088029, -0.00932385, 0.01229734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020460061728954315, + 'FR_Wheel_Angle': 0.020464718341827393, + 'Location': array([ 0.95806342, -18.42300224, 0.16726002]), + 'Rotation': array([-4.78864536e-02, 4.99625931e+01, -3.72619666e-02]), + 'Velocity': array([-7.71448761e-02, -9.19940770e-02, -8.95547855e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.85302734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.60528564, -1838.77124023, 16.87414551]), + 'frame': 13690, + 'frame_number': 13690, + 'framesequence': 13688, + 'gaze_dir': array([ 0.98058069, 0.14748457, -0.12926663]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14748457, -0.12926663]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14748457, -0.12926663]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.19218276068568, + 'timestamp_carla': 56192, + 'timestamp_device': 55829, + 'timestamp_stream': 56.19218276068568, + 'transform': [array([ 0.00987274, -0.00354858, 0.16489099]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00401316, 0.0036528 , -0.08912364]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02045433595776558, + 'FR_Wheel_Angle': 0.020458349958062172, + 'Location': array([ 0.95420665, -18.42754555, 0.16726616]), + 'Rotation': array([-4.77908328e-02, 4.99583206e+01, -3.72619666e-02]), + 'Velocity': array([-0.08735048, -0.10369858, 0.00030876]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.853515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.63249207, -1837.62915039, 16.87353516]), + 'frame': 13691, + 'frame_number': 13691, + 'framesequence': 13689, + 'gaze_dir': array([ 0.98058057, 0.14800066, -0.12867542]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.14800066, -0.12867542]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.14800066, -0.12867542]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.1970268599689, + 'timestamp_carla': 56197, + 'timestamp_device': 55833, + 'timestamp_stream': 56.1970268599689, + 'transform': [array([ 0.00987259, -0.00354858, 0.16488835]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0062664 , -0.0060719 , 0.03488823]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020457347854971886, + 'FR_Wheel_Angle': 0.02046195976436138, + 'Location': array([ 0.95012516, -18.43239784, 0.16727367]), + 'Rotation': array([-4.75381128e-02, 4.99585228e+01, -3.72619666e-02]), + 'Velocity': array([-0.08191025, -0.0975951 , 0.00031427]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8533935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.65007019, -1836.71508789, 16.87341309]), + 'frame': 13692, + 'frame_number': 13692, + 'framesequence': 13690, + 'gaze_dir': array([ 0.98058057, 0.14864182, -0.12793422]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.14864182, -0.12793422]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.14864182, -0.12793422]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.20162716135383, + 'timestamp_carla': 56201, + 'timestamp_device': 55838, + 'timestamp_stream': 56.20162716135383, + 'transform': [array([ 0.00987274, -0.00354858, 0.16488725]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03542347, 0.0273634 , -0.46221665]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020433638244867325, + 'FR_Wheel_Angle': 0.020438190549612045, + 'Location': array([ 0.94504583, -18.43841743, 0.16729236]), + 'Rotation': array([-4.91910204e-02, 4.99564781e+01, -3.72619629e-02]), + 'Velocity': array([-0.12323196, -0.14679663, 0.00023823]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.853515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.66688538, -1835.5736084 , 16.87304688]), + 'frame': 13693, + 'frame_number': 13693, + 'framesequence': 13691, + 'gaze_dir': array([ 0.98058069, 0.14915259, -0.12733839]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14915259, -0.12733839]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14915259, -0.12733839]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.206048261374235, + 'timestamp_carla': 56206, + 'timestamp_device': 55842, + 'timestamp_stream': 56.206048261374235, + 'transform': [array([ 0.00987259, -0.00354858, 0.16488619]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0056429 , -0.00737891, -0.52170116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020438725128769875, + 'FR_Wheel_Angle': 0.02044331096112728, + 'Location': array([ 0.93990737, -18.44451714, 0.16730396]), + 'Rotation': array([-4.97101136e-02, 4.99555664e+01, -3.72619629e-02]), + 'Velocity': array([-1.14337206e-01, -1.36274487e-01, 9.16075660e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.853759765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.67630005, -1834.6595459 , 16.87268066]), + 'frame': 13694, + 'frame_number': 13694, + 'framesequence': 13692, + 'gaze_dir': array([ 0.98058069, 0.149914 , -0.12644111]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.149914 , -0.12644111]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.149914 , -0.12644111]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.211207661777735, + 'timestamp_carla': 56211, + 'timestamp_device': 55848, + 'timestamp_stream': 56.211207661777735, + 'transform': [array([ 0.00987274, -0.00354858, 0.16488329]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0139048 , -0.0124923 , 0.61705244]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0204426608979702, + 'FR_Wheel_Angle': 0.020445559173822403, + 'Location': array([ 0.93449455, -18.45100975, 0.16730319]), + 'Rotation': array([-4.88358513e-02, 4.99599724e+01, -3.72619629e-02]), + 'Velocity': array([-0.10733711, -0.12822039, -0.00016575]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8541259765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.68356323, -1833.28881836, 16.87219238]), + 'frame': 13695, + 'frame_number': 13695, + 'framesequence': 13693, + 'gaze_dir': array([ 0.98058069, 0.15041828, -0.12584077]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15041828, -0.12584077]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15041828, -0.12584077]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.21574405953288, + 'timestamp_carla': 56215, + 'timestamp_device': 55852, + 'timestamp_stream': 56.21574405953288, + 'transform': [array([ 0.00987259, -0.00354858, 0.16488218]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00560004, -0.0031542 , -0.42731091]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02043907530605793, + 'FR_Wheel_Angle': 0.02043953351676464, + 'Location': array([ 0.92987853, -18.45651817, 0.16730903]), + 'Rotation': array([-4.86172847e-02, 4.99592705e+01, -3.72619629e-02]), + 'Velocity': array([-0.11371066, -0.13556407, 0.000337 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8541259765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.68377686, -1832.37548828, 16.87182617]), + 'frame': 13696, + 'frame_number': 13696, + 'framesequence': 13694, + 'gaze_dir': array([ 0.98058069, 0.15104574, -0.12508696]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15104574, -0.12508696]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15104574, -0.12508696]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.22027476131916, + 'timestamp_carla': 56220, + 'timestamp_device': 55857, + 'timestamp_stream': 56.22027476131916, + 'transform': [array([ 0.00987259, -0.00354858, 0.16488218]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02559797, 0.02263886, -0.25556332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020414631813764572, + 'FR_Wheel_Angle': 0.020416300743818283, + 'Location': array([ 0.92265546, -18.46519661, 0.16732226]), + 'Rotation': array([-5.05365655e-02, 4.99652519e+01, -3.72924767e-02]), + 'Velocity': array([-0.15627354, -0.18632112, 0.00059716]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8544921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.6789856 , -1831.23303223, 16.87145996]), + 'frame': 13697, + 'frame_number': 13697, + 'framesequence': 13695, + 'gaze_dir': array([ 0.98058057, 0.15154506, -0.12448151]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.15154506, -0.12448151]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.15154506, -0.12448151]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.224549259990454, + 'timestamp_carla': 56224, + 'timestamp_device': 55861, + 'timestamp_stream': 56.224549259990454, + 'transform': [array([ 0.00987259, -0.00354858, 0.16488218]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00473505, -0.00320483, 0.00273765]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020413564518094063, + 'FR_Wheel_Angle': 0.020417137071490288, + 'Location': array([ 0.9151364 , -18.47418976, 0.16733189]), + 'Rotation': array([-5.11786044e-02, 4.99698677e+01, -3.72924767e-02]), + 'Velocity': array([-0.15824161, -0.18844379, 0.00049035]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8548583984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.67103577, -1830.31884766, 16.87109375]), + 'frame': 13698, + 'frame_number': 13698, + 'framesequence': 13696, + 'gaze_dir': array([ 0.98058069, 0.15204151, -0.12387469]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15204151, -0.12387469]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15204151, -0.12387469]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.228738360106945, + 'timestamp_carla': 56228, + 'timestamp_device': 55865, + 'timestamp_stream': 56.228738360106945, + 'transform': [array([ 0.00987259, -0.00354858, 0.16488218]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02607816, -0.02207343, 0.000853 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02042115479707718, + 'FR_Wheel_Angle': 0.020426195114850998, + 'Location': array([ 0.90774703, -18.48298836, 0.16734439]), + 'Rotation': array([-5.05024157e-02, 4.99697685e+01, -3.72924767e-02]), + 'Velocity': array([-0.1449407 , -0.17274621, 0.00037148]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8551025390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.65942383, -1829.40563965, 16.87097168]), + 'frame': 13699, + 'frame_number': 13699, + 'framesequence': 13697, + 'gaze_dir': array([ 0.98058069, 0.152536 , -0.12326529]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.152536 , -0.12326529]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.152536 , -0.12326529]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.23292616009712, + 'timestamp_carla': 56232, + 'timestamp_device': 55869, + 'timestamp_stream': 56.23292616009712, + 'transform': [array([ 0.00987259, -0.00354858, 0.16488218]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01168303, -0.0097845 , -0.00496217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020421750843524933, + 'FR_Wheel_Angle': 0.02042725682258606, + 'Location': array([ 0.90143424, -18.49051476, 0.16734882]), + 'Rotation': array([-4.95052077e-02, 4.99698029e+01, -3.72924767e-02]), + 'Velocity': array([-0.14390706, -0.17151433, 0.00033847]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8553466796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.64416504, -1828.49169922, 16.87060547]), + 'frame': 13700, + 'frame_number': 13700, + 'framesequence': 13698, + 'gaze_dir': array([ 0.98058069, 0.15302756, -0.12265449]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15302756, -0.12265449]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15302756, -0.12265449]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.23634685948491, + 'timestamp_carla': 56236, + 'timestamp_device': 55873, + 'timestamp_stream': 56.23634685948491, + 'transform': [array([ 0.00987274, -0.00354858, 0.16488385]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00127262, 0.00105248, -0.0019007 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02041957527399063, + 'FR_Wheel_Angle': 0.020423393696546555, + 'Location': array([ 0.89481854, -18.49839401, 0.16734996]), + 'Rotation': array([-4.93481122e-02, 4.99698029e+01, -3.72924805e-02]), + 'Velocity': array([-0.14770767, -0.17601873, 0.0003201 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.85595703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.62528992, -1827.57861328, 16.86999512]), + 'frame': 13701, + 'frame_number': 13701, + 'framesequence': 13699, + 'gaze_dir': array([ 0.98058069, 0.15351716, -0.12204116]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15351716, -0.12204116]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15351716, -0.12204116]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.2407426610589, + 'timestamp_carla': 56240, + 'timestamp_device': 55877, + 'timestamp_stream': 56.2407426610589, + 'transform': [array([ 0.00987274, -0.00354858, 0.16488385]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00867779, -0.00754083, -0.00124444]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02042318694293499, + 'FR_Wheel_Angle': 0.02042856626212597, + 'Location': array([ 0.88801038, -18.50650787, 0.16736393]), + 'Rotation': array([-4.93481122e-02, 4.99698029e+01, -3.72924805e-02]), + 'Velocity': array([-0.14140151, -0.16853096, 0.00026825]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8564453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.60275269, -1826.66467285, 16.86962891]), + 'frame': 13702, + 'frame_number': 13702, + 'framesequence': 13700, + 'gaze_dir': array([ 0.98058069, 0.15400429, -0.12142586]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15400429, -0.12142586]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15400429, -0.12142586]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.2444774620235, + 'timestamp_carla': 56244, + 'timestamp_device': 55881, + 'timestamp_stream': 56.2444774620235, + 'transform': [array([ 0.00987289, -0.00354858, 0.16488507]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0200084 , 0.01687583, -0.00140953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02041541039943695, + 'FR_Wheel_Angle': 0.020419053733348846, + 'Location': array([ 0.88109505, -18.51475143, 0.16737102]), + 'Rotation': array([-4.93822657e-02, 4.99698334e+01, -3.72924805e-02]), + 'Velocity': array([-0.15496273, -0.18466121, 0.0003502 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8568115234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.57652283, -1825.75085449, 16.8692627 ]), + 'frame': 13703, + 'frame_number': 13703, + 'framesequence': 13701, + 'gaze_dir': array([ 0.98058069, 0.15436767, -0.12096356]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15436767, -0.12096356]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15436767, -0.12096356]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.24795566126704, + 'timestamp_carla': 56248, + 'timestamp_device': 55884, + 'timestamp_stream': 56.24795566126704, + 'transform': [array([ 0.00987289, -0.00354858, 0.16488507]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0030044 , 0.00253412, -0.00692519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020412085577845573, + 'FR_Wheel_Angle': 0.020415782928466797, + 'Location': array([ 0.87366486, -18.52360535, 0.16738708]), + 'Rotation': array([-5.00789434e-02, 4.99698753e+01, -3.72924805e-02]), + 'Velocity': array([-0.1607527 , -0.19156599, 0.00028069]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8568115234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.55439758, -1825.06628418, 16.86938477]), + 'frame': 13704, + 'frame_number': 13704, + 'framesequence': 13702, + 'gaze_dir': array([ 0.98058069, 0.15485048, -0.12034487]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15485048, -0.12034487]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15485048, -0.12034487]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.25214705988765, + 'timestamp_carla': 56252, + 'timestamp_device': 55888, + 'timestamp_stream': 56.25214705988765, + 'transform': [array([ 0.00987289, -0.00354858, 0.16488507]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0183566 , -0.01552161, -0.02929772]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020418288186192513, + 'FR_Wheel_Angle': 0.020420102402567863, + 'Location': array([ 0.8665297 , -18.53210449, 0.16739449]), + 'Rotation': array([-4.98672090e-02, 4.99693947e+01, -3.72924805e-02]), + 'Velocity': array([-1.49938136e-01, -1.78689539e-01, -7.83348078e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.857177734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.52180481, -1824.15270996, 16.86901855]), + 'frame': 13705, + 'frame_number': 13705, + 'framesequence': 13703, + 'gaze_dir': array([ 0.98058069, 0.15533036, -0.11972485]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15533036, -0.11972485]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15533036, -0.11972485]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.255582459270954, + 'timestamp_carla': 56255, + 'timestamp_device': 55892, + 'timestamp_stream': 56.255582459270954, + 'transform': [array([ 0.00987289, -0.00354858, 0.16488507]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00771368, 0.00670416, -0.00077265]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020413625985383987, + 'FR_Wheel_Angle': 0.020416967570781708, + 'Location': array([ 0.85961723, -18.54034233, 0.16739978]), + 'Rotation': array([-4.98330593e-02, 4.99696236e+01, -3.72924767e-02]), + 'Velocity': array([-0.15807542, -0.18835521, 0.00050309]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.857666015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.48558044, -1823.2401123 , 16.86853027]), + 'frame': 13706, + 'frame_number': 13706, + 'framesequence': 13704, + 'gaze_dir': array([ 0.98058069, 0.15568909, -0.11925799]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15568909, -0.11925799]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15568909, -0.11925799]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.25928916037083, + 'timestamp_carla': 56259, + 'timestamp_device': 55895, + 'timestamp_stream': 56.25928916037083, + 'transform': [array([ 0.00987305, -0.00354858, 0.16488615]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00196623, 0.00171275, -0.00261031]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020412836223840714, + 'FR_Wheel_Angle': 0.020418060943484306, + 'Location': array([ 0.85202473, -18.54939079, 0.1674142 ]), + 'Rotation': array([-4.98330593e-02, 4.99696236e+01, -3.72924767e-02]), + 'Velocity': array([-0.15944827, -0.18999982, 0.00039246]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.85791015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.45596313, -1822.55493164, 16.86828613]), + 'frame': 13707, + 'frame_number': 13707, + 'framesequence': 13705, + 'gaze_dir': array([ 0.98058069, 0.15616462, -0.11863463]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15616462, -0.11863463]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15616462, -0.11863463]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.26269166171551, + 'timestamp_carla': 56262, + 'timestamp_device': 55899, + 'timestamp_stream': 56.26269166171551, + 'transform': [array([ 0.00987305, -0.00354858, 0.16488615]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01083461, -0.00919187, -0.00116241]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020417798310518265, + 'FR_Wheel_Angle': 0.02042231336236, + 'Location': array([ 0.84503299, -18.55772209, 0.16742149]), + 'Rotation': array([-4.98330593e-02, 4.99696236e+01, -3.72924767e-02]), + 'Velocity': array([-0.15079705, -0.17971298, 0.00035655]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8587646484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.41343689, -1821.6427002 , 16.86767578]), + 'frame': 13708, + 'frame_number': 13708, + 'framesequence': 13706, + 'gaze_dir': array([ 0.98058069, 0.15652007, -0.11816526]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15652007, -0.11816526]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15652007, -0.11816526]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.26632545888424, + 'timestamp_carla': 56266, + 'timestamp_device': 55902, + 'timestamp_stream': 56.26632545888424, + 'transform': [array([ 0.0098732 , -0.00354858, 0.16488722]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03139094, 0.02631478, -0.00152084]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020399371162056923, + 'FR_Wheel_Angle': 0.020404640585184097, + 'Location': array([ 0.83705115, -18.56723022, 0.16743098]), + 'Rotation': array([-5.06868325e-02, 4.99702072e+01, -3.72924767e-02]), + 'Velocity': array([-0.18082161, -0.21532045, 0.00047957]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.85888671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.37898254, -1820.9576416 , 16.86755371]), + 'frame': 13709, + 'frame_number': 13709, + 'framesequence': 13707, + 'gaze_dir': array([ 0.98058057, 0.1571086 , -0.1173816 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1571086 , -0.1173816 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1571086 , -0.1173816 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.270320761948824, + 'timestamp_carla': 56270, + 'timestamp_device': 55907, + 'timestamp_stream': 56.270320761948824, + 'transform': [array([ 0.0098732 , -0.00354858, 0.16488722]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00605195, -0.00520552, -0.00747506]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020406104624271393, + 'FR_Wheel_Angle': 0.020410066470503807, + 'Location': array([ 0.82927799, -18.57649422, 0.16744934]), + 'Rotation': array([-5.08439243e-02, 4.99706535e+01, -3.72924767e-02]), + 'Velocity': array([-0.17117515, -0.20397897, 0.00027491]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8594970703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.31719971, -1819.81774902, 16.86706543]), + 'frame': 13710, + 'frame_number': 13710, + 'framesequence': 13708, + 'gaze_dir': array([ 0.98058057, 0.15746029, -0.11690941]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.15746029, -0.11690941]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.15746029, -0.11690941]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.273842461407185, + 'timestamp_carla': 56273, + 'timestamp_device': 55910, + 'timestamp_stream': 56.273842461407185, + 'transform': [array([ 0.00987335, -0.00354858, 0.16488835]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01176671, -0.00986679, -0.00882063]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02040908858180046, + 'FR_Wheel_Angle': 0.02041413076221943, + 'Location': array([ 0.82078177, -18.58662033, 0.16745979]), + 'Rotation': array([-5.08439243e-02, 4.99706535e+01, -3.72924767e-02]), + 'Velocity': array([-0.16422239, -0.19569747, 0.00022573]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.85986328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.27729797, -1819.13305664, 16.86669922]), + 'frame': 13711, + 'frame_number': 13711, + 'framesequence': 13709, + 'gaze_dir': array([ 0.98058069, 0.15781014, -0.11643678]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15781014, -0.11643678]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15781014, -0.11643678]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.27721365913749, + 'timestamp_carla': 56277, + 'timestamp_device': 55913, + 'timestamp_stream': 56.27721365913749, + 'transform': [array([ 0.00987335, -0.00354858, 0.16488835]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01619475, 0.01540923, 0.08359959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020404141396284103, + 'FR_Wheel_Angle': 0.020402036607265472, + 'Location': array([ 0.8135584 , -18.5952282 , 0.16746685]), + 'Rotation': array([-5.08097745e-02, 4.99709358e+01, -3.72924767e-02]), + 'Velocity': array([-0.17474163, -0.20793027, 0.00036849]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.860107421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.2354126 , -1818.44934082, 16.86657715]), + 'frame': 13712, + 'frame_number': 13712, + 'framesequence': 13710, + 'gaze_dir': array([ 0.98058069, 0.15827481, -0.11580434]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15827481, -0.11580434]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15827481, -0.11580434]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.28098816052079, + 'timestamp_carla': 56281, + 'timestamp_device': 55917, + 'timestamp_stream': 56.28098816052079, + 'transform': [array([ 0.00987335, -0.00354858, 0.16488835]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00875077, 0.00848277, 0.03796616]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020390117540955544, + 'FR_Wheel_Angle': 0.020394491031765938, + 'Location': array([ 0.80354893, -18.60716248, 0.16749538]), + 'Rotation': array([-5.28520010e-02, 4.99704514e+01, -3.72924767e-02]), + 'Velocity': array([-0.19839951, -0.23646283, 0.00035978]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8604736328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.17633057, -1817.53710938, 16.86621094]), + 'frame': 13713, + 'frame_number': 13713, + 'framesequence': 13711, + 'gaze_dir': array([ 0.98058069, 0.15873651, -0.11517067]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15873651, -0.11517067]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15873651, -0.11517067]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.28454716131091, + 'timestamp_carla': 56284, + 'timestamp_device': 55921, + 'timestamp_stream': 56.28454716131091, + 'transform': [array([ 0.00987335, -0.00354858, 0.16488835]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00062938, 0.000897 , -0.00059061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020388459786772728, + 'FR_Wheel_Angle': 0.020391244441270828, + 'Location': array([ 0.79433399, -18.61814499, 0.16750339]), + 'Rotation': array([-5.28861508e-02, 4.99711304e+01, -3.72924730e-02]), + 'Velocity': array([-0.20407414, -0.24317785, 0.00052321]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.86083984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.1136322 , -1816.62597656, 16.86584473]), + 'frame': 13714, + 'frame_number': 13714, + 'framesequence': 13712, + 'gaze_dir': array([ 0.98058069, 0.15931049, -0.11437538]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15931049, -0.11437538]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15931049, -0.11437538]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.2895925603807, + 'timestamp_carla': 56289, + 'timestamp_device': 55926, + 'timestamp_stream': 56.2895925603807, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488546]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01853817, -0.01536548, -0.00186136]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02039351873099804, + 'FR_Wheel_Angle': 0.020397024229168892, + 'Location': array([ 0.7849195 , -18.62936401, 0.16751018]), + 'Rotation': array([-5.27632087e-02, 4.99711227e+01, -3.72924767e-02]), + 'Velocity': array([-1.94012001e-01, -2.31185660e-01, 1.96824069e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8614501953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -123.03012085, -1815.48657227, 16.86523438]), + 'frame': 13715, + 'frame_number': 13715, + 'framesequence': 13713, + 'gaze_dir': array([ 0.98058069, 0.15965271, -0.1138972 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15965271, -0.1138972 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15965271, -0.1138972 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.29302155971527, + 'timestamp_carla': 56293, + 'timestamp_device': 55929, + 'timestamp_stream': 56.29302155971527, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488546]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02924117, -0.02477987, -0.00138803]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020402831956744194, + 'FR_Wheel_Angle': 0.020409785211086273, + 'Location': array([ 0.77679902, -18.63903809, 0.16750434]), + 'Rotation': array([-5.12400754e-02, 4.99712219e+01, -3.72924767e-02]), + 'Velocity': array([-1.76865667e-01, -2.10782051e-01, 1.07378961e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.861083984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.97715759, -1814.80371094, 16.8651123 ]), + 'frame': 13716, + 'frame_number': 13716, + 'framesequence': 13714, + 'gaze_dir': array([ 0.98058057, 0.15999392, -0.11341738]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.15999392, -0.11341738]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.15999392, -0.11341738]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.296255860477686, + 'timestamp_carla': 56296, + 'timestamp_device': 55932, + 'timestamp_stream': 56.296255860477686, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488688]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00786865, -0.00667243, -0.00044353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020405840128660202, + 'FR_Wheel_Angle': 0.02040899358689785, + 'Location': array([ 0.76826322, -18.64920998, 0.16752133]), + 'Rotation': array([-5.02975099e-02, 4.99712791e+01, -3.72924767e-02]), + 'Velocity': array([-0.17316826, -0.20634855, 0.00046169]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8614501953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.92224121, -1814.11999512, 16.86474609]), + 'frame': 13717, + 'frame_number': 13717, + 'framesequence': 13715, + 'gaze_dir': array([ 0.98058057, 0.16044605, -0.11277685]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16044605, -0.11277685]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16044605, -0.11277685]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.299642361700535, + 'timestamp_carla': 56299, + 'timestamp_device': 55936, + 'timestamp_stream': 56.299642361700535, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488688]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00607702, 0.00491726, -0.00157943]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020401332527399063, + 'FR_Wheel_Angle': 0.020406486466526985, + 'Location': array([ 0.76031345, -18.65868378, 0.16753292]), + 'Rotation': array([-5.02975099e-02, 4.99712791e+01, -3.72924767e-02]), + 'Velocity': array([-0.1794972 , -0.21388587, 0.00042586]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8621826171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.84593201, -1813.20996094, 16.86437988]), + 'frame': 13718, + 'frame_number': 13718, + 'framesequence': 13716, + 'gaze_dir': array([ 0.98058069, 0.16078393, -0.11229466]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16078393, -0.11229466]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16078393, -0.11229466]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.303127858787775, + 'timestamp_carla': 56303, + 'timestamp_device': 55939, + 'timestamp_stream': 56.303127858787775, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.04819286, 0.04010193, -0.30637383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020386621356010437, + 'FR_Wheel_Angle': 0.02038498781621456, + 'Location': array([ 0.75146139, -18.66921806, 0.16754803]), + 'Rotation': array([-5.07483035e-02, 4.99701614e+01, -3.72924767e-02]), + 'Velocity': array([-0.20514584, -0.24440588, 0.00035555]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.862548828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.78623962, -1812.52661133, 16.86401367]), + 'frame': 13719, + 'frame_number': 13719, + 'framesequence': 13717, + 'gaze_dir': array([ 0.98058069, 0.16123158, -0.11165098]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16123158, -0.11165098]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16123158, -0.11165098]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.3068023622036, + 'timestamp_carla': 56306, + 'timestamp_device': 55943, + 'timestamp_stream': 56.3068023622036, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00533989, 0.00453351, 0.00321203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038693241775036, + 'FR_Wheel_Angle': 0.020391814410686493, + 'Location': array([ 0.7421369 , -18.68034935, 0.16757183]), + 'Rotation': array([-5.22782654e-02, 4.99719887e+01, -3.72924767e-02]), + 'Velocity': array([-0.20456174, -0.24378343, 0.00049288]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8629150390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.70355225, -1811.6171875 , 16.86376953]), + 'frame': 13720, + 'frame_number': 13720, + 'framesequence': 13718, + 'gaze_dir': array([ 0.98058069, 0.16167706, -0.11100491]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16167706, -0.11100491]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16167706, -0.11100491]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.310495261102915, + 'timestamp_carla': 56310, + 'timestamp_device': 55947, + 'timestamp_stream': 56.310495261102915, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0055847 , -0.00443546, -0.00202334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02039187401533127, + 'FR_Wheel_Angle': 0.020393935963511467, + 'Location': array([ 0.73221898, -18.69216537, 0.16758792]), + 'Rotation': array([-5.22782654e-02, 4.99719887e+01, -3.72924767e-02]), + 'Velocity': array([-0.19939731, -0.23758595, 0.00045346]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8634033203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.61714172, -1810.70703125, 16.86315918]), + 'frame': 13721, + 'frame_number': 13721, + 'framesequence': 13719, + 'gaze_dir': array([ 0.98058069, 0.16200916, -0.11051965]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16200916, -0.11051965]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16200916, -0.11051965]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.31368016079068, + 'timestamp_carla': 56313, + 'timestamp_device': 55950, + 'timestamp_stream': 56.31368016079068, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00104681, 0.00083657, -0.00185367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020388390868902206, + 'FR_Wheel_Angle': 0.02039361372590065, + 'Location': array([ 0.72326785, -18.70282745, 0.16759562]), + 'Rotation': array([-5.21553233e-02, 4.99719963e+01, -3.72924767e-02]), + 'Velocity': array([-0.20204939, -0.24074134, 0.00025788]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.86376953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.55000305, -1810.02539062, 16.86279297]), + 'frame': 13722, + 'frame_number': 13722, + 'framesequence': 13720, + 'gaze_dir': array([ 0.98058069, 0.16234024, -0.11003277]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16234024, -0.11003277]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16234024, -0.11003277]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.31710606068373, + 'timestamp_carla': 56317, + 'timestamp_device': 55953, + 'timestamp_stream': 56.31710606068373, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00883383, -0.00721758, -0.00124565]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02039238065481186, + 'FR_Wheel_Angle': 0.020395992323756218, + 'Location': array([ 0.71400398, -18.71386719, 0.16760826]), + 'Rotation': array([-5.21553233e-02, 4.99719963e+01, -3.72924767e-02]), + 'Velocity': array([-0.19509785, -0.23245223, 0.00040663]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8641357421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.48072815, -1809.34301758, 16.86254883]), + 'frame': 13723, + 'frame_number': 13723, + 'framesequence': 13721, + 'gaze_dir': array([ 0.98058057, 0.16277923, -0.10938226]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16277923, -0.10938226]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16277923, -0.10938226]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.320491559803486, + 'timestamp_carla': 56320, + 'timestamp_device': 55957, + 'timestamp_stream': 56.320491559803486, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00761778, -0.00633464, -0.00161245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020395034924149513, + 'FR_Wheel_Angle': 0.02039944753050804, + 'Location': array([ 0.70488739, -18.72473145, 0.16761775]), + 'Rotation': array([-5.21553233e-02, 4.99719963e+01, -3.72924767e-02]), + 'Velocity': array([-0.19046798, -0.22694707, 0.00037521]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.864501953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.38520813, -1808.43395996, 16.86218262]), + 'frame': 13724, + 'frame_number': 13724, + 'framesequence': 13722, + 'gaze_dir': array([ 0.98058069, 0.16321522, -0.10873064]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16321522, -0.10873064]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16321522, -0.10873064]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.32466785982251, + 'timestamp_carla': 56324, + 'timestamp_device': 55961, + 'timestamp_stream': 56.32466785982251, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00485557, -0.00388727, -0.00073923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02039625495672226, + 'FR_Wheel_Angle': 0.020399006083607674, + 'Location': array([ 0.69597256, -18.73534966, 0.16762863]), + 'Rotation': array([-5.21553233e-02, 4.99719963e+01, -3.72924767e-02]), + 'Velocity': array([-1.88352183e-01, -2.24417314e-01, 1.96962355e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8648681640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.28613281, -1807.52600098, 16.86181641]), + 'frame': 13725, + 'frame_number': 13725, + 'framesequence': 13723, + 'gaze_dir': array([ 0.98058057, 0.1635409 , -0.10824014]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1635409 , -0.10824014]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1635409 , -0.10824014]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.32797846198082, + 'timestamp_carla': 56328, + 'timestamp_device': 55964, + 'timestamp_stream': 56.32797846198082, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00474643, -0.00394909, 0.01420697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02039850316941738, + 'FR_Wheel_Angle': 0.020401159301400185, + 'Location': array([ 0.68790722, -18.74496269, 0.16761513]), + 'Rotation': array([-5.20596988e-02, 4.99720039e+01, -3.72924767e-02]), + 'Velocity': array([-0.18442893, -0.21974868, 0.00059951]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8653564453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.20942688, -1806.84448242, 16.86132812]), + 'frame': 13726, + 'frame_number': 13726, + 'framesequence': 13724, + 'gaze_dir': array([ 0.98058057, 0.1639723 , -0.10758547]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1639723 , -0.10758547]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1639723 , -0.10758547]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.33201586082578, + 'timestamp_carla': 56332, + 'timestamp_device': 55968, + 'timestamp_stream': 56.33201586082578, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03946755, 0.03217382, -0.51408851]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02036796137690544, + 'FR_Wheel_Angle': 0.02037162333726883, + 'Location': array([ 0.67705846, -18.75785065, 0.16765815]), + 'Rotation': array([-5.49283773e-02, 4.99693108e+01, -3.72924730e-02]), + 'Velocity': array([-0.23774481, -0.28305516, 0.00043202]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.86572265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -122.10395813, -1805.93725586, 16.86096191]), + 'frame': 13727, + 'frame_number': 13727, + 'framesequence': 13725, + 'gaze_dir': array([ 0.98058069, 0.16440153, -0.10692847]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16440153, -0.10692847]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16440153, -0.10692847]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.33609655871987, + 'timestamp_carla': 56336, + 'timestamp_device': 55972, + 'timestamp_stream': 56.33609655871987, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00935251, -0.00709699, 0.50401521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02037384733557701, + 'FR_Wheel_Angle': 0.0203788373619318, + 'Location': array([ 0.66579223, -18.77130318, 0.16768363]), + 'Rotation': array([-5.54543026e-02, 4.99725761e+01, -3.72924730e-02]), + 'Velocity': array([-0.22737564, -0.27092749, 0.00032835]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.865966796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.99478149, -1805.02966309, 16.86071777]), + 'frame': 13728, + 'frame_number': 13728, + 'framesequence': 13726, + 'gaze_dir': array([ 0.98058057, 0.16482769, -0.10627037]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16482769, -0.10627037]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16482769, -0.10627037]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.33979795873165, + 'timestamp_carla': 56339, + 'timestamp_device': 55976, + 'timestamp_stream': 56.33979795873165, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01825231, -0.01440168, 0.37683165]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020378977060317993, + 'FR_Wheel_Angle': 0.020383013412356377, + 'Location': array([ 0.65629154, -18.78262711, 0.16769718]), + 'Rotation': array([-5.45049049e-02, 4.99726753e+01, -3.72924767e-02]), + 'Velocity': array([-0.21845354, -0.26027724, 0.00054001]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.866455078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.88214111, -1804.12329102, 16.86022949]), + 'frame': 13729, + 'frame_number': 13729, + 'framesequence': 13727, + 'gaze_dir': array([ 0.98058069, 0.16514599, -0.10577504]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16514599, -0.10577504]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16514599, -0.10577504]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.34300746023655, + 'timestamp_carla': 56343, + 'timestamp_device': 55979, + 'timestamp_stream': 56.34300746023655, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00526796, -0.00358185, -0.01453663]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020373618230223656, + 'FR_Wheel_Angle': 0.020377038046717644, + 'Location': array([ 0.64532423, -18.7957325 , 0.16771011]), + 'Rotation': array([-5.42863421e-02, 4.99759979e+01, -3.72924730e-02]), + 'Velocity': array([-0.22778524, -0.27139747, 0.0005228 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8668212890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.79515076, -1803.44299316, 16.85986328]), + 'frame': 13730, + 'frame_number': 13730, + 'framesequence': 13728, + 'gaze_dir': array([ 0.98058069, 0.1654624 , -0.10527942]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1654624 , -0.10527942]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1654624 , -0.10527942]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.34633485972881, + 'timestamp_carla': 56346, + 'timestamp_device': 55982, + 'timestamp_stream': 56.34633485972881, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01664542, -0.01377084, -0.00383042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020379748195409775, + 'FR_Wheel_Angle': 0.020383669063448906, + 'Location': array([ 0.63457417, -18.80853844, 0.16772136]), + 'Rotation': array([-5.41702285e-02, 4.99759979e+01, -3.72924693e-02]), + 'Velocity': array([-0.21727741, -0.25889337, 0.00029254]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.70626831, -1802.76391602, 16.85949707]), + 'frame': 13731, + 'frame_number': 13731, + 'framesequence': 13729, + 'gaze_dir': array([ 0.98058069, 0.16588236, -0.10461645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16588236, -0.10461645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16588236, -0.10461645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.349773760885, + 'timestamp_carla': 56349, + 'timestamp_device': 55986, + 'timestamp_stream': 56.349773760885, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01754761, -0.01464662, -0.00177029]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0203856211155653, + 'FR_Wheel_Angle': 0.020390689373016357, + 'Location': array([ 0.62452304, -18.82051277, 0.16772941]), + 'Rotation': array([-5.40746041e-02, 4.99759979e+01, -3.72924693e-02]), + 'Velocity': array([-2.05052078e-01, -2.44325519e-01, 1.86862948e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8675537109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.58441162, -1801.85778809, 16.85913086]), + 'frame': 13732, + 'frame_number': 13732, + 'framesequence': 13730, + 'gaze_dir': array([ 0.98058057, 0.16619527, -0.1041186 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16619527, -0.1041186 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16619527, -0.1041186 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.35303546115756, + 'timestamp_carla': 56353, + 'timestamp_device': 55989, + 'timestamp_stream': 56.35303546115756, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00305398, 0.00268525, -0.00158762]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038249373435974, + 'FR_Wheel_Angle': 0.02038615569472313, + 'Location': array([ 0.61528027, -18.8315239 , 0.16774102]), + 'Rotation': array([-5.40746041e-02, 4.99759979e+01, -3.72924693e-02]), + 'Velocity': array([-0.21232277, -0.25298214, 0.00043505]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.867919921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.49075317, -1801.17932129, 16.85876465]), + 'frame': 13733, + 'frame_number': 13733, + 'framesequence': 13731, + 'gaze_dir': array([ 0.98058057, 0.1666106 , -0.10345272]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1666106 , -0.10345272]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1666106 , -0.10345272]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.35657665878534, + 'timestamp_carla': 56356, + 'timestamp_device': 55993, + 'timestamp_stream': 56.35657665878534, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00452968, -0.00383037, -0.0019479 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020385926589369774, + 'FR_Wheel_Angle': 0.02039075270295143, + 'Location': array([ 0.6053502 , -18.84335709, 0.16775462]), + 'Rotation': array([-5.40746041e-02, 4.99759979e+01, -3.72924693e-02]), + 'Velocity': array([-0.20633672, -0.24586371, 0.00033776]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8682861328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.36257935, -1800.27416992, 16.85839844]), + 'frame': 13734, + 'frame_number': 13734, + 'framesequence': 13732, + 'gaze_dir': array([ 0.98058057, 0.16692004, -0.1029527 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16692004, -0.1029527 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16692004, -0.1029527 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.360054060816765, + 'timestamp_carla': 56360, + 'timestamp_device': 55996, + 'timestamp_stream': 56.360054060816765, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488791]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00597738, -0.00514082, -0.00188612]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020391004160046577, + 'FR_Wheel_Angle': 0.020395517349243164, + 'Location': array([ 0.59646231, -18.85394669, 0.16776298]), + 'Rotation': array([-5.40746041e-02, 4.99759979e+01, -3.72924693e-02]), + 'Velocity': array([-0.19748685, -0.23532261, 0.00038705]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.868896484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.26423645, -1799.59631348, 16.85778809]), + 'frame': 13735, + 'frame_number': 13735, + 'framesequence': 13733, + 'gaze_dir': array([ 0.98058057, 0.16733067, -0.10228393]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16733067, -0.10228393]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16733067, -0.10228393]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.36411926150322, + 'timestamp_carla': 56364, + 'timestamp_device': 56000, + 'timestamp_stream': 56.36411926150322, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03994695, 0.03337552, 0.0056958 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020372824743390083, + 'FR_Wheel_Angle': 0.02037659101188183, + 'Location': array([ 0.5866679 , -18.86562157, 0.16777405]), + 'Rotation': array([-5.52357361e-02, 4.99766769e+01, -3.72924693e-02]), + 'Velocity': array([-0.22915074, -0.27307197, 0.00042751]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.869140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -121.12969971, -1798.69213867, 16.85766602]), + 'frame': 13736, + 'frame_number': 13736, + 'framesequence': 13734, + 'gaze_dir': array([ 0.98058069, 0.16783972, -0.10144646]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16783972, -0.10144646]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16783972, -0.10144646]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.36817375943065, + 'timestamp_carla': 56368, + 'timestamp_device': 56005, + 'timestamp_stream': 56.36817375943065, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00048232, -0.00027174, -0.0020017 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02037818916141987, + 'FR_Wheel_Angle': 0.020383507013320923, + 'Location': array([ 0.57607859, -18.87824059, 0.16779903]), + 'Rotation': array([-5.59050962e-02, 4.99767876e+01, -3.72924767e-02]), + 'Velocity': array([-0.21981756, -0.26192689, 0.00044065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8697509765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.95664978, -1797.5637207 , 16.85681152]), + 'frame': 13737, + 'frame_number': 13737, + 'framesequence': 13735, + 'gaze_dir': array([ 0.98058057, 0.16814353, -0.10094212]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16814353, -0.10094212]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16814353, -0.10094212]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.37165496125817, + 'timestamp_carla': 56371, + 'timestamp_device': 56008, + 'timestamp_stream': 56.37165496125817, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01239759, -0.01031112, -0.00172214]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020383261144161224, + 'FR_Wheel_Angle': 0.020387988537549973, + 'Location': array([ 0.56591457, -18.89035034, 0.16781299]), + 'Rotation': array([-5.59050962e-02, 4.99767876e+01, -3.72924767e-02]), + 'Velocity': array([-0.20975757, -0.24993335, 0.00047567]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8702392578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.85002136, -1796.8861084 , 16.85644531]), + 'frame': 13738, + 'frame_number': 13738, + 'framesequence': 13736, + 'gaze_dir': array([ 0.98058069, 0.16844544, -0.10043752]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16844544, -0.10043752]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16844544, -0.10043752]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.37502636015415, + 'timestamp_carla': 56375, + 'timestamp_device': 56011, + 'timestamp_stream': 56.37502636015415, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00679967, -0.00569476, -0.00199942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038632519543171, + 'FR_Wheel_Angle': 0.020390819758176804, + 'Location': array([ 0.5560481 , -18.90210724, 0.16782399]), + 'Rotation': array([-5.58163039e-02, 4.99767914e+01, -3.72924805e-02]), + 'Velocity': array([-0.20563902, -0.24503429, 0.00029879]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.870361328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.74139404, -1796.20983887, 16.85632324]), + 'frame': 13739, + 'frame_number': 13739, + 'framesequence': 13737, + 'gaze_dir': array([ 0.98058057, 0.16884598, -0.09976266]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16884598, -0.09976266]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16884598, -0.09976266]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.378637962043285, + 'timestamp_carla': 56378, + 'timestamp_device': 56015, + 'timestamp_stream': 56.378637962043285, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00244812, 0.00205864, -0.00157778]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020384525880217552, + 'FR_Wheel_Angle': 0.02038712240755558, + 'Location': array([ 0.54609585, -18.91396523, 0.16783668]), + 'Rotation': array([-5.58163039e-02, 4.99767914e+01, -3.72924805e-02]), + 'Velocity': array([-0.20877965, -0.24876447, 0.00049896]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.870849609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.59335327, -1795.30773926, 16.85571289]), + 'frame': 13740, + 'frame_number': 13740, + 'framesequence': 13738, + 'gaze_dir': array([ 0.98058069, 0.16914436, -0.09925596]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16914436, -0.09925596]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16914436, -0.09925596]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.38231835886836, + 'timestamp_carla': 56382, + 'timestamp_device': 56018, + 'timestamp_stream': 56.38231835886836, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01640322, 0.01375454, -0.00217201]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020377356559038162, + 'FR_Wheel_Angle': 0.02038353867828846, + 'Location': array([ 0.53639376, -18.92552376, 0.16784862]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-2.21269786e-01, -2.63649911e-01, 1.81112278e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.871337890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.48008728, -1794.63220215, 16.85534668]), + 'frame': 13741, + 'frame_number': 13741, + 'framesequence': 13739, + 'gaze_dir': array([ 0.98058069, 0.16954018, -0.09857832]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16954018, -0.09857832]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16954018, -0.09857832]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.38548235967755, + 'timestamp_carla': 56385, + 'timestamp_device': 56022, + 'timestamp_stream': 56.38548235967755, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01214714, 0.01015623, -0.00209024]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020377011969685555, + 'FR_Wheel_Angle': 0.02038084901869297, + 'Location': array([ 0.52586323, -18.9380703 , 0.1678651 ]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.22187194, -0.26435286, 0.00043691]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8717041015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.32572937, -1793.73120117, 16.85498047]), + 'frame': 13742, + 'frame_number': 13742, + 'framesequence': 13740, + 'gaze_dir': array([ 0.98058057, 0.16983499, -0.09806953]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16983499, -0.09806953]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16983499, -0.09806953]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.38892376050353, + 'timestamp_carla': 56388, + 'timestamp_device': 56025, + 'timestamp_stream': 56.38892376050353, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00486047, -0.00421037, -0.00163538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038060873746872, + 'FR_Wheel_Angle': 0.02038564346730709, + 'Location': array([ 0.51558656, -18.95031738, 0.16788417]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.21559896, -0.256899 , 0.00037021]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8721923828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.2077179 , -1793.05639648, 16.85449219]), + 'frame': 13743, + 'frame_number': 13743, + 'framesequence': 13741, + 'gaze_dir': array([ 0.98058069, 0.17012866, -0.09755921]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17012866, -0.09755921]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17012866, -0.09755921]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.3922127597034, + 'timestamp_carla': 56392, + 'timestamp_device': 56028, + 'timestamp_stream': 56.3922127597034, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00276009, -0.00227781, -0.00169549]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020382650196552277, + 'FR_Wheel_Angle': 0.020387468859553337, + 'Location': array([ 0.50618428, -18.96151733, 0.16789481]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.2120425 , -0.25265685, 0.00042659]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8724365234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -120.08750916, -1792.38122559, 16.85424805]), + 'frame': 13744, + 'frame_number': 13744, + 'framesequence': 13742, + 'gaze_dir': array([ 0.98058069, 0.17051731, -0.0968783 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17051731, -0.0968783 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17051731, -0.0968783 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.39565595984459, + 'timestamp_carla': 56395, + 'timestamp_device': 56032, + 'timestamp_stream': 56.39565595984459, + 'transform': [array([ 0.00987366, -0.00354858, 0.16488683]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00509146, -0.00413039, -0.00191367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020385317504405975, + 'FR_Wheel_Angle': 0.020388171076774597, + 'Location': array([ 0.49637613, -18.97320557, 0.16790816]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.20740101, -0.24711999, 0.00050208]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8729248046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.92428589, -1791.48266602, 16.85375977]), + 'frame': 13745, + 'frame_number': 13745, + 'framesequence': 13743, + 'gaze_dir': array([ 0.98058069, 0.17090362, -0.09619518]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17090362, -0.09619518]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17090362, -0.09619518]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.39981555938721, + 'timestamp_carla': 56399, + 'timestamp_device': 56036, + 'timestamp_stream': 56.39981555938721, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488539]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00656528, -0.00558387, -0.00202228]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020388655364513397, + 'FR_Wheel_Angle': 0.02039339579641819, + 'Location': array([ 0.4865135 , -18.98495674, 0.16791889]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.20157516, -0.24019331, 0.00036246]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.873291015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.75730896, -1790.5838623 , 16.85339355]), + 'frame': 13746, + 'frame_number': 13746, + 'framesequence': 13744, + 'gaze_dir': array([ 0.98058057, 0.17119126, -0.09568231]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17119126, -0.09568231]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17119126, -0.09568231]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.40311826020479, + 'timestamp_carla': 56403, + 'timestamp_device': 56039, + 'timestamp_stream': 56.40311826020479, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488539]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00309114, -0.00258281, -0.00188925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02039026841521263, + 'FR_Wheel_Angle': 0.020393026992678642, + 'Location': array([ 0.47714484, -18.99612045, 0.16793193]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.19877192, -0.23684277, 0.00032486]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.87353515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.62983704, -1789.9107666 , 16.85302734]), + 'frame': 13747, + 'frame_number': 13747, + 'framesequence': 13745, + 'gaze_dir': array([ 0.98058069, 0.17157279, -0.09499651]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17157279, -0.09499651]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17157279, -0.09499651]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.40683436021209, + 'timestamp_carla': 56406, + 'timestamp_device': 56043, + 'timestamp_stream': 56.40683436021209, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488539]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00355132, -0.00310196, -0.00170583]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020390117540955544, + 'FR_Wheel_Angle': 0.020394111052155495, + 'Location': array([ 0.46786842, -19.00717163, 0.16794261]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.19903612, -0.2371648 , 0.00025724]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8739013671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.45658875, -1789.01318359, 16.85266113]), + 'frame': 13748, + 'frame_number': 13748, + 'framesequence': 13746, + 'gaze_dir': array([ 0.98058069, 0.17195119, -0.09430984]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17195119, -0.09430984]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17195119, -0.09430984]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.41083465889096, + 'timestamp_carla': 56410, + 'timestamp_device': 56047, + 'timestamp_stream': 56.41083465889096, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488539]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00818589, -0.00682249, -0.00147516]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020395979285240173, + 'FR_Wheel_Angle': 0.0203991886228323, + 'Location': array([ 0.45883715, -19.0179348 , 0.16794987]), + 'Rotation': array([-5.60621880e-02, 4.99768105e+01, -3.72924805e-02]), + 'Velocity': array([-0.1888174 , -0.22499543, 0.00044312]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8743896484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.27992249, -1788.1171875 , 16.85205078]), + 'frame': 13749, + 'frame_number': 13749, + 'framesequence': 13747, + 'gaze_dir': array([ 0.98058069, 0.17223355, -0.09379318]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17223355, -0.09379318]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17223355, -0.09379318]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.41423895955086, + 'timestamp_carla': 56414, + 'timestamp_device': 56050, + 'timestamp_stream': 56.41423895955086, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488539]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01603235, 0.01354021, -0.02030304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020386818796396255, + 'FR_Wheel_Angle': 0.020391928032040596, + 'Location': array([ 0.449462 , -19.02910423, 0.16796905]), + 'Rotation': array([-5.62739260e-02, 4.99771118e+01, -3.72924730e-02]), + 'Velocity': array([-0.20479347, -0.24399444, 0.00036849]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.874755859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -119.14489746, -1787.44470215, 16.85180664]), + 'frame': 13750, + 'frame_number': 13750, + 'framesequence': 13748, + 'gaze_dir': array([ 0.98058069, 0.17260714, -0.09310388]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17260714, -0.09310388]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17260714, -0.09310388]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.41795055940747, + 'timestamp_carla': 56418, + 'timestamp_device': 56054, + 'timestamp_stream': 56.41795055940747, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488539]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0134116 , 0.01123629, 0.00223709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020384177565574646, + 'FR_Wheel_Angle': 0.020389344543218613, + 'Location': array([ 0.44034758, -19.03996277, 0.16798553]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.20937838, -0.24949174, 0.00037728]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8753662109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.96199036, -1786.54992676, 16.85119629]), + 'frame': 13751, + 'frame_number': 13751, + 'framesequence': 13749, + 'gaze_dir': array([ 0.98058057, 0.17297831, -0.09241243]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17297831, -0.09241243]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17297831, -0.09241243]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.42180746048689, + 'timestamp_carla': 56421, + 'timestamp_device': 56058, + 'timestamp_stream': 56.42180746048689, + 'transform': [array([ 0.0098735 , -0.00354858, 0.16488539]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00338644, 0.00296223, -0.00184162]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038528397679329, + 'FR_Wheel_Angle': 0.02038966864347458, + 'Location': array([ 0.43001845, -19.05227089, 0.16800487]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.20745924, -0.24719259, 0.00042812]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8758544921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.77528381, -1785.6550293 , 16.85070801]), + 'frame': 13752, + 'frame_number': 13752, + 'framesequence': 13750, + 'gaze_dir': array([ 0.98058069, 0.17352973, -0.09137282]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17352973, -0.09137282]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17352973, -0.09137282]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.42746336013079, + 'timestamp_carla': 56427, + 'timestamp_device': 56064, + 'timestamp_stream': 56.42746336013079, + 'transform': [array([ 0.00987366, -0.00354858, 0.16487893]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01944693, 0.01630343, -0.00238643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020380118861794472, + 'FR_Wheel_Angle': 0.02038523554801941, + 'Location': array([ 0.42023894, -19.06392097, 0.16800827]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.21645617, -0.25790867, 0.00049212]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.876708984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.48869324, -1784.31445312, 16.84985352]), + 'frame': 13753, + 'frame_number': 13753, + 'framesequence': 13751, + 'gaze_dir': array([ 0.98058057, 0.1738029 , -0.09085209]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.1738029 , -0.09085209]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.1738029 , -0.09085209]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.430968560278416, + 'timestamp_carla': 56431, + 'timestamp_device': 56067, + 'timestamp_stream': 56.430968560278416, + 'transform': [array([ 0.00987366, -0.00354858, 0.16487893]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00331921, -0.00284075, -0.00178315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038324996829033, + 'FR_Wheel_Angle': 0.020388111472129822, + 'Location': array([ 0.41105667, -19.07485962, 0.16802928]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.21100433, -0.25141308, 0.00048694]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.87646484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.34228516, -1783.64538574, 16.84960938]), + 'frame': 13754, + 'frame_number': 13754, + 'framesequence': 13752, + 'gaze_dir': array([ 0.98058069, 0.17407487, -0.09032991]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17407487, -0.09032991]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17407487, -0.09032991]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.43427485972643, + 'timestamp_carla': 56434, + 'timestamp_device': 56070, + 'timestamp_stream': 56.43427485972643, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00865045, -0.00748118, -0.0017131 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020387370139360428, + 'FR_Wheel_Angle': 0.020389745011925697, + 'Location': array([ 0.400996 , -19.08684731, 0.16804191]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.20382489, -0.24285831, 0.00040289]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8768310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -118.19384766, -1782.97570801, 16.84924316]), + 'frame': 13755, + 'frame_number': 13755, + 'framesequence': 13753, + 'gaze_dir': array([ 0.98058069, 0.17443462, -0.08963327]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17443462, -0.08963327]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17443462, -0.08963327]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.43782636150718, + 'timestamp_carla': 56437, + 'timestamp_device': 56074, + 'timestamp_stream': 56.43782636150718, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01084243, 0.00924363, -0.00148012]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038346789777279, + 'FR_Wheel_Angle': 0.020385967567563057, + 'Location': array([ 0.3908374 , -19.09894943, 0.16805458]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.21327898, -0.25412324, 0.00053456]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8775634765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.99313354, -1782.08483887, 16.84863281]), + 'frame': 13756, + 'frame_number': 13756, + 'framesequence': 13754, + 'gaze_dir': array([ 0.98058069, 0.1747919 , -0.08893453]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1747919 , -0.08893453]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1747919 , -0.08893453]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.441603660583496, + 'timestamp_carla': 56441, + 'timestamp_device': 56078, + 'timestamp_stream': 56.441603660583496, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00274018, 0.00229908, -0.00236422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020383017137646675, + 'FR_Wheel_Angle': 0.020388154312968254, + 'Location': array([ 0.38154909, -19.11001396, 0.16807038]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.21140645, -0.2518945 , 0.00032362]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8780517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.78857422, -1781.19384766, 16.84814453]), + 'frame': 13757, + 'frame_number': 13757, + 'framesequence': 13755, + 'gaze_dir': array([ 0.98058069, 0.17505777, -0.08841005]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17505777, -0.08841005]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17505777, -0.08841005]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.44494055956602, + 'timestamp_carla': 56445, + 'timestamp_device': 56081, + 'timestamp_stream': 56.44494055956602, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 5.61652123e-05, -6.54512478e-05, -1.81277725e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038266696035862, + 'FR_Wheel_Angle': 0.020385760813951492, + 'Location': array([ 0.37131384, -19.12220955, 0.16808407]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.21202131, -0.25261706, 0.0004812 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.87841796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.63298035, -1780.5267334 , 16.84777832]), + 'frame': 13758, + 'frame_number': 13758, + 'framesequence': 13756, + 'gaze_dir': array([ 0.98058069, 0.1753224 , -0.0878841 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1753224 , -0.0878841 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1753224 , -0.0878841 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.44821656122804, + 'timestamp_carla': 56448, + 'timestamp_device': 56084, + 'timestamp_stream': 56.44821656122804, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01304691, -0.01096269, -0.00174415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020387178286910057, + 'FR_Wheel_Angle': 0.02039085514843464, + 'Location': array([ 0.36189976, -19.13343048, 0.16809647]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-2.04162389e-01, -2.43260652e-01, 1.56762602e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.87890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.47518921, -1779.85925293, 16.84729004]), + 'frame': 13759, + 'frame_number': 13759, + 'framesequence': 13757, + 'gaze_dir': array([ 0.98058069, 0.17567234, -0.08718249]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17567234, -0.08718249]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17567234, -0.08718249]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.45181056112051, + 'timestamp_carla': 56451, + 'timestamp_device': 56088, + 'timestamp_stream': 56.45181056112051, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00731344, -0.00603873, -0.00185217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020391104742884636, + 'FR_Wheel_Angle': 0.020394396036863327, + 'Location': array([ 0.35190615, -19.14533615, 0.16810569]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.19859172, -0.23663387, 0.00033934]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.87939453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.26193237, -1778.97119141, 16.84680176]), + 'frame': 13760, + 'frame_number': 13760, + 'framesequence': 13758, + 'gaze_dir': array([ 0.98058069, 0.1760198 , -0.08647882]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1760198 , -0.08647882]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1760198 , -0.08647882]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.455322559922934, + 'timestamp_carla': 56455, + 'timestamp_device': 56092, + 'timestamp_stream': 56.455322559922934, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00313994, 0.00259684, 0.00127224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020394865423440933, + 'FR_Wheel_Angle': 0.020395247265696526, + 'Location': array([ 0.34287879, -19.15608978, 0.168115 ]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.19711088, -0.2348731 , 0.00050019]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8798828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -117.04495239, -1778.08312988, 16.84631348]), + 'frame': 13761, + 'frame_number': 13761, + 'framesequence': 13759, + 'gaze_dir': array([ 0.98058069, 0.17627831, -0.08595067]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17627831, -0.08595067]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17627831, -0.08595067]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.45888965949416, + 'timestamp_carla': 56458, + 'timestamp_device': 56095, + 'timestamp_stream': 56.45888965949416, + 'transform': [array([ 0.00987381, -0.00354858, 0.16488001]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00488711, -0.00441428, -0.00265893]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020394761115312576, + 'FR_Wheel_Angle': 0.020398709923028946, + 'Location': array([ 0.33477768, -19.16574097, 0.16812706]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.19094644, -0.22752425, 0.00022759]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8802490234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.88000488, -1777.41833496, 16.84606934]), + 'frame': 13762, + 'frame_number': 13762, + 'framesequence': 13760, + 'gaze_dir': array([ 0.98058057, 0.17653553, -0.08542106]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17653553, -0.08542106]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17653553, -0.08542106]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.4620469622314, + 'timestamp_carla': 56462, + 'timestamp_device': 56098, + 'timestamp_stream': 56.4620469622314, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00069828, 0.00339828, -0.00082632]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020395198836922646, + 'FR_Wheel_Angle': 0.02039872482419014, + 'Location': array([ 0.326184 , -19.17598152, 0.16811618]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.19015387, -0.22663268, 0.00064294]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.880615234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.71290588, -1776.75317383, 16.84570312]), + 'frame': 13763, + 'frame_number': 13763, + 'framesequence': 13761, + 'gaze_dir': array([ 0.98058069, 0.17679088, -0.08489136]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17679088, -0.08489136]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17679088, -0.08489136]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.465306758880615, + 'timestamp_carla': 56465, + 'timestamp_device': 56101, + 'timestamp_stream': 56.465306758880615, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00213509, 0.00412318, -0.00127102]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020395521074533463, + 'FR_Wheel_Angle': 0.02040018141269684, + 'Location': array([ 0.316412 , -19.18762589, 0.16814129]), + 'Rotation': array([-5.65198138e-02, 4.99773788e+01, -3.72924767e-02]), + 'Velocity': array([-0.18959564, -0.2259621 , 0.00069394]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8812255859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.54400635, -1776.08935547, 16.84509277]), + 'frame': 13764, + 'frame_number': 13764, + 'framesequence': 13762, + 'gaze_dir': array([ 0.98058069, 0.17712915, -0.08418324]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17712915, -0.08418324]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17712915, -0.08418324]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.4690660610795, + 'timestamp_carla': 56469, + 'timestamp_device': 56105, + 'timestamp_stream': 56.4690660610795, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02908586, 0.02723926, 0.00082821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020384585484862328, + 'FR_Wheel_Angle': 0.020389094948768616, + 'Location': array([ 0.3076005 , -19.19812775, 0.16816032]), + 'Rotation': array([-5.67930192e-02, 4.99774170e+01, -3.72924767e-02]), + 'Velocity': array([-0.20865637, -0.24865535, 0.00060348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8818359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.31549072, -1775.20422363, 16.84460449]), + 'frame': 13765, + 'frame_number': 13765, + 'framesequence': 13763, + 'gaze_dir': array([ 0.98058069, 0.17746429, -0.08347444]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17746429, -0.08347444]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17746429, -0.08347444]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.47274085879326, + 'timestamp_carla': 56472, + 'timestamp_device': 56109, + 'timestamp_stream': 56.47274085879326, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0141632, 0.0142365, 0.0025537]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038203924894333, + 'FR_Wheel_Angle': 0.020386913791298866, + 'Location': array([ 0.29811954, -19.20942497, 0.16818264]), + 'Rotation': array([-5.70389070e-02, 4.99774780e+01, -3.72924805e-02]), + 'Velocity': array([-0.21309242, -0.25394225, 0.00052979]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8824462890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -116.0836792 , -1774.32080078, 16.84399414]), + 'frame': 13766, + 'frame_number': 13766, + 'framesequence': 13764, + 'gaze_dir': array([ 0.98058057, 0.17771408, -0.08294128]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17771408, -0.08294128]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17771408, -0.08294128]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.47598605975509, + 'timestamp_carla': 56476, + 'timestamp_device': 56112, + 'timestamp_stream': 56.47598605975509, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00929272, -0.004636 , -0.00159463]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020383190363645554, + 'FR_Wheel_Angle': 0.020389452576637268, + 'Location': array([ 0.28762108, -19.22193146, 0.16819045]), + 'Rotation': array([-5.70389070e-02, 4.99774780e+01, -3.72924805e-02]), + 'Velocity': array([-0.20719412, -0.24690209, -0.00154717]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.90727234, -1773.65795898, 16.84362793]), + 'frame': 13767, + 'frame_number': 13767, + 'framesequence': 13765, + 'gaze_dir': array([ 0.98058057, 0.17796196, -0.08240806]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17796196, -0.08240806]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17796196, -0.08240806]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.479206562042236, + 'timestamp_carla': 56479, + 'timestamp_device': 56115, + 'timestamp_stream': 56.479206562042236, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00722652, -0.00288075, -0.00133539]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020377736538648605, + 'FR_Wheel_Angle': 0.020383259281516075, + 'Location': array([ 0.27712145, -19.23443985, 0.16821487]), + 'Rotation': array([-5.70389070e-02, 4.99774780e+01, -3.72924805e-02]), + 'Velocity': array([-2.17981428e-01, -2.59750515e-01, -1.37538911e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8831787109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.72904968, -1772.99658203, 16.84326172]), + 'frame': 13768, + 'frame_number': 13768, + 'framesequence': 13766, + 'gaze_dir': array([ 0.98058069, 0.17829032, -0.08169527]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17829032, -0.08169527]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17829032, -0.08169527]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.482484359294176, + 'timestamp_carla': 56482, + 'timestamp_device': 56119, + 'timestamp_stream': 56.482484359294176, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00523953, -0.00191539, -0.00185843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02037755772471428, + 'FR_Wheel_Angle': 0.02038247138261795, + 'Location': array([ 0.26692185, -19.24659348, 0.16823258]), + 'Rotation': array([-5.70389070e-02, 4.99774780e+01, -3.72924805e-02]), + 'Velocity': array([-0.22090544, -0.26323554, 0.00040337]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8836669921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.48817444, -1772.11474609, 16.84277344]), + 'frame': 13769, + 'frame_number': 13769, + 'framesequence': 13767, + 'gaze_dir': array([ 0.98058057, 0.17853445, -0.08116032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17853445, -0.08116032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17853445, -0.08116032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.48578945919871, + 'timestamp_carla': 56485, + 'timestamp_device': 56122, + 'timestamp_stream': 56.48578945919871, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01525171, 0.01599481, -0.00142906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020372899249196053, + 'FR_Wheel_Angle': 0.02037595584988594, + 'Location': array([ 0.25688362, -19.25855255, 0.16823563]), + 'Rotation': array([-5.69091327e-02, 4.99775047e+01, -3.72924805e-02]), + 'Velocity': array([-0.22903112, -0.27290714, 0.00059802]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8841552734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.3053894 , -1771.45458984, 16.84228516]), + 'frame': 13770, + 'frame_number': 13770, + 'framesequence': 13768, + 'gaze_dir': array([ 0.98058069, 0.1788578 , -0.08044525]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1788578 , -0.08044525]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1788578 , -0.08044525]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.48992856219411, + 'timestamp_carla': 56489, + 'timestamp_device': 56126, + 'timestamp_stream': 56.48992856219411, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.032102 , 0.02994151, -0.00253655]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020354991778731346, + 'FR_Wheel_Angle': 0.020360268652439117, + 'Location': array([ 0.24568973, -19.27188873, 0.1682584 ]), + 'Rotation': array([-5.82615100e-02, 4.99775352e+01, -3.72924730e-02]), + 'Velocity': array([-0.26023108, -0.3100625 , 0.00056121]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8848876953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -115.05836487, -1770.57446289, 16.84155273]), + 'frame': 13771, + 'frame_number': 13771, + 'framesequence': 13769, + 'gaze_dir': array([ 0.98058057, 0.17917797, -0.07972957]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17917797, -0.07972957]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17917797, -0.07972957]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.493860360234976, + 'timestamp_carla': 56493, + 'timestamp_device': 56130, + 'timestamp_stream': 56.493860360234976, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01892915, -0.01277667, -0.00158945]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02036382630467415, + 'FR_Wheel_Angle': 0.02036789059638977, + 'Location': array([ 0.23363847, -19.28624725, 0.16827835]), + 'Rotation': array([-5.84664159e-02, 4.99775429e+01, -3.72924767e-02]), + 'Velocity': array([-0.24483779, -0.29173359, 0.00044334]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.88525390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.80799866, -1769.69604492, 16.84118652]), + 'frame': 13772, + 'frame_number': 13772, + 'framesequence': 13770, + 'gaze_dir': array([ 0.98058057, 0.17941652, -0.07919129]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17941652, -0.07919129]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17941652, -0.07919129]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.497292559593916, + 'timestamp_carla': 56497, + 'timestamp_device': 56133, + 'timestamp_stream': 56.497292559593916, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01570233, -0.01063566, -0.00204093]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020366506651043892, + 'FR_Wheel_Angle': 0.020371247082948685, + 'Location': array([ 0.22241928, -19.29961586, 0.16828933]), + 'Rotation': array([-5.83776236e-02, 4.99775429e+01, -3.72924730e-02]), + 'Velocity': array([-0.24016941, -0.28617251, 0.00037591]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8856201171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.6177063 , -1769.03710938, 16.84082031]), + 'frame': 13773, + 'frame_number': 13773, + 'framesequence': 13771, + 'gaze_dir': array([ 0.98058069, 0.17973168, -0.0784734 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17973168, -0.0784734 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17973168, -0.0784734 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.50062905997038, + 'timestamp_carla': 56500, + 'timestamp_device': 56137, + 'timestamp_stream': 56.50062905997038, + 'transform': [array([ 0.00987396, -0.00354858, 0.16488104]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01218598, -0.00769692, -0.00179259]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020369958132505417, + 'FR_Wheel_Angle': 0.02037508226931095, + 'Location': array([ 0.21181177, -19.31225586, 0.1682943 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.23415174, -0.27901256, 0.00039626]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.88623046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -114.36123657, -1768.16064453, 16.84020996]), + 'frame': 13774, + 'frame_number': 13774, + 'framesequence': 13772, + 'gaze_dir': array([ 0.98058069, 0.18019934, -0.0773935 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18019934, -0.0773935 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18019934, -0.0773935 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.50639196112752, + 'timestamp_carla': 56506, + 'timestamp_device': 56143, + 'timestamp_stream': 56.50639196112752, + 'transform': [array([ 0.00987411, -0.00354858, 0.16487394]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0025025 , 0.00021099, -0.00118749]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0203693974763155, + 'FR_Wheel_Angle': 0.020375244319438934, + 'Location': array([ 0.20136052, -19.32470703, 0.16830203]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.23512714, -0.28017703, 0.00028744]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.88720703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.9697113 , -1766.84692383, 16.8392334 ]), + 'frame': 13775, + 'frame_number': 13775, + 'framesequence': 13773, + 'gaze_dir': array([ 0.98058069, 0.18043087, -0.07685217]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18043087, -0.07685217]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18043087, -0.07685217]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.50989156216383, + 'timestamp_carla': 56509, + 'timestamp_device': 56146, + 'timestamp_stream': 56.50989156216383, + 'transform': [array([ 0.00987411, -0.00354858, 0.16487394]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 3.87624896e-05, 2.39945948e-03, -1.71498687e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020370692014694214, + 'FR_Wheel_Angle': 0.020373249426484108, + 'Location': array([ 0.18998365, -19.33826256, 0.1683152 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.23286967, -0.2774812 , 0.0004452 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.88671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.77072144, -1766.19055176, 16.83898926]), + 'frame': 13776, + 'frame_number': 13776, + 'framesequence': 13774, + 'gaze_dir': array([ 0.98058069, 0.18066049, -0.07631083]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18066049, -0.07631083]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18066049, -0.07631083]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.51302186027169, + 'timestamp_carla': 56513, + 'timestamp_device': 56149, + 'timestamp_stream': 56.51302186027169, + 'transform': [array([ 0.00987427, -0.00354858, 0.16487519]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00571029, -0.00173469, -0.00159942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020370204001665115, + 'FR_Wheel_Angle': 0.02037482149899006, + 'Location': array([ 0.17814817, -19.35236359, 0.16833176]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.23268373, -0.27725121, 0.00042781]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.88720703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.57014465, -1765.53552246, 16.83850098]), + 'frame': 13777, + 'frame_number': 13777, + 'framesequence': 13775, + 'gaze_dir': array([ 0.98058069, 0.18088877, -0.07576811]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18088877, -0.07576811]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18088877, -0.07576811]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.51613786071539, + 'timestamp_carla': 56516, + 'timestamp_device': 56152, + 'timestamp_stream': 56.51613786071539, + 'transform': [array([ 0.00987427, -0.00354858, 0.16487519]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00172584, 0.00180004, -0.00150799]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020369406789541245, + 'FR_Wheel_Angle': 0.02037346176803112, + 'Location': array([ 0.16802707, -19.36442375, 0.16834541]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-2.35122204e-01, -2.80149490e-01, 2.36408712e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8878173828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.36738586, -1764.88037109, 16.8380127 ]), + 'frame': 13778, + 'frame_number': 13778, + 'framesequence': 13776, + 'gaze_dir': array([ 0.98058069, 0.18126515, -0.07486323]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18126515, -0.07486323]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18126515, -0.07486323]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.52052826061845, + 'timestamp_carla': 56520, + 'timestamp_device': 56157, + 'timestamp_stream': 56.52052826061845, + 'transform': [array([ 0.00987442, -0.00354858, 0.16487405]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01022625, 0.0120832 , -0.00157955]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02036336250603199, + 'FR_Wheel_Angle': 0.020366905257105827, + 'Location': array([ 0.15658537, -19.37805557, 0.168349 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.2456536 , -0.29269633, 0.00059825]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8885498046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -113.02549744, -1763.7911377 , 16.83728027]), + 'frame': 13779, + 'frame_number': 13779, + 'framesequence': 13777, + 'gaze_dir': array([ 0.98058069, 0.18163727, -0.07395577]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18163727, -0.07395577]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18163727, -0.07395577]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.5256756618619, + 'timestamp_carla': 56525, + 'timestamp_device': 56162, + 'timestamp_stream': 56.5256756618619, + 'transform': [array([ 0.00987427, -0.00354858, 0.16486986]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00166198, 0.00407767, -0.00203937]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020362243056297302, + 'FR_Wheel_Angle': 0.02036668173968792, + 'Location': array([ 0.14482431, -19.39206696, 0.1683725 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.24760108, -0.29501972, 0.00050408]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.88916015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -112.6778717 , -1762.70275879, 16.83666992]), + 'frame': 13780, + 'frame_number': 13780, + 'framesequence': 13778, + 'gaze_dir': array([ 0.98058069, 0.18193175, -0.07322834]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18193175, -0.07322834]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18193175, -0.07322834]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.53014586120844, + 'timestamp_carla': 56530, + 'timestamp_device': 56166, + 'timestamp_stream': 56.53014586120844, + 'transform': [array([ 0.00987427, -0.00354858, 0.16486986]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00176194, 0.00188153, -0.00158946]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020361173897981644, + 'FR_Wheel_Angle': 0.02036353200674057, + 'Location': array([ 0.13320617, -19.40590477, 0.16839172]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.24946922, -0.29723093, 0.00044574]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.889404296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -112.39575195, -1761.83325195, 16.8359375 ]), + 'frame': 13781, + 'frame_number': 13781, + 'framesequence': 13779, + 'gaze_dir': array([ 0.98058069, 0.18229543, -0.07231827]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18229543, -0.07231827]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18229543, -0.07231827]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.53441796079278, + 'timestamp_carla': 56534, + 'timestamp_device': 56171, + 'timestamp_stream': 56.53441796079278, + 'transform': [array([ 0.00987427, -0.00354858, 0.16486986]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([0.00341831, 0.00042825, 0.0010284 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020359454676508904, + 'FR_Wheel_Angle': 0.020362399518489838, + 'Location': array([ 0.12181675, -19.41947556, 0.16840492]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.25246277, -0.30080682, 0.00040297]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.889892578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -112.03862 , -1760.74890137, 16.83544922]), + 'frame': 13782, + 'frame_number': 13782, + 'framesequence': 13780, + 'gaze_dir': array([ 0.98058057, 0.18258333, -0.0715882 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.18258333, -0.0715882 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.18258333, -0.0715882 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.53819276019931, + 'timestamp_carla': 56538, + 'timestamp_device': 56175, + 'timestamp_stream': 56.53819276019931, + 'transform': [array([ 0.00987427, -0.00354858, 0.16486986]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00054627, 0.00329018, -0.00073619]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020355703309178352, + 'FR_Wheel_Angle': 0.020360067486763, + 'Location': array([ 0.10978595, -19.43380737, 0.168423 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-2.58994550e-01, -3.08588684e-01, 2.52845290e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -111.74880981, -1759.88183594, 16.8347168 ]), + 'frame': 13783, + 'frame_number': 13783, + 'framesequence': 13781, + 'gaze_dir': array([ 0.98058069, 0.18286808, -0.07085771]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18286808, -0.07085771]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18286808, -0.07085771]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.54268226027489, + 'timestamp_carla': 56542, + 'timestamp_device': 56179, + 'timestamp_stream': 56.54268226027489, + 'transform': [array([ 0.00987411, -0.00354858, 0.16486837]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0053761 , -0.00122803, -0.00152216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020354365929961205, + 'FR_Wheel_Angle': 0.020356979221105576, + 'Location': array([ 0.09715588, -19.44885445, 0.16843784]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.26133066, -0.31136078, 0.00035227]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8912353515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -111.45573425, -1759.0168457 , 16.83410645]), + 'frame': 13784, + 'frame_number': 13784, + 'framesequence': 13782, + 'gaze_dir': array([ 0.98058069, 0.18307999, -0.07030839]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18307999, -0.07030839]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18307999, -0.07030839]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.546277359128, + 'timestamp_carla': 56546, + 'timestamp_device': 56182, + 'timestamp_stream': 56.546277359128, + 'transform': [array([ 0.00987427, -0.00354858, 0.1648694 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00489013, 0.00710784, -0.00242248]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020348699763417244, + 'FR_Wheel_Angle': 0.020353222265839577, + 'Location': array([ 0.08487467, -19.46348572, 0.16845661]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.27120882, -0.32311726, 0.0004868 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8914794921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -111.23338318, -1758.36804199, 16.83374023]), + 'frame': 13785, + 'frame_number': 13785, + 'framesequence': 13783, + 'gaze_dir': array([ 0.98058069, 0.18349859, -0.06920856]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18349859, -0.06920856]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18349859, -0.06920856]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.55168415978551, + 'timestamp_carla': 56551, + 'timestamp_device': 56188, + 'timestamp_stream': 56.55168415978551, + 'transform': [array([ 0.00987411, -0.00354858, 0.16486463]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00135541, 0.00246787, -0.00212351]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034611813724041, + 'FR_Wheel_Angle': 0.020348677411675453, + 'Location': array([ 0.07204366, -19.47877121, 0.16847378]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.2757073 , -0.32847041, 0.00043538]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.892578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -110.78320312, -1757.07324219, 16.83276367]), + 'frame': 13786, + 'frame_number': 13786, + 'framesequence': 13784, + 'gaze_dir': array([ 0.98058057, 0.18377379, -0.06847441]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.18377379, -0.06847441]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.18377379, -0.06847441]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.55541095882654, + 'timestamp_carla': 56555, + 'timestamp_device': 56192, + 'timestamp_stream': 56.55541095882654, + 'transform': [array([ 0.00987427, -0.00354858, 0.1648657 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00114192, 0.00211908, -0.00259568]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020342791453003883, + 'FR_Wheel_Angle': 0.02034706436097622, + 'Location': array([ 0.05891699, -19.49440575, 0.16849056]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.28150582, -0.33538127, 0.00042432]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8927001953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -110.47885132, -1756.21203613, 16.83215332]), + 'frame': 13787, + 'frame_number': 13787, + 'framesequence': 13785, + 'gaze_dir': array([ 0.98058069, 0.18404633, -0.06773848]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18404633, -0.06773848]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18404633, -0.06773848]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.55971886217594, + 'timestamp_carla': 56559, + 'timestamp_device': 56196, + 'timestamp_stream': 56.55971886217594, + 'transform': [array([ 0.00987427, -0.00354858, 0.1648657 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00662196, -0.00192008, -0.00201131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020341161638498306, + 'FR_Wheel_Angle': 0.020344100892543793, + 'Location': array([ 0.04556652, -19.51030922, 0.16850635]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-2.84349352e-01, -3.38758260e-01, 1.47826664e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.893310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -110.1708374 , -1755.35131836, 16.83166504]), + 'frame': 13788, + 'frame_number': 13788, + 'framesequence': 13786, + 'gaze_dir': array([ 0.98058069, 0.18431567, -0.06700216]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18431567, -0.06700216]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18431567, -0.06700216]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.563884660601616, + 'timestamp_carla': 56563, + 'timestamp_device': 56200, + 'timestamp_stream': 56.563884660601616, + 'transform': [array([ 0.00987427, -0.00354858, 0.1648657 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00344511, 0.00031083, -0.0026189 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033943124115467, + 'FR_Wheel_Angle': 0.020342553034424782, + 'Location': array([ 0.03181963, -19.52668571, 0.1685213 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.2889024 , -0.34418601, 0.00039177]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.89404296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -109.85972595, -1754.49267578, 16.83093262]), + 'frame': 13789, + 'frame_number': 13789, + 'framesequence': 13787, + 'gaze_dir': array([ 0.98058069, 0.18458229, -0.06626406]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18458229, -0.06626406]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18458229, -0.06626406]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.56762836128473, + 'timestamp_carla': 56567, + 'timestamp_device': 56204, + 'timestamp_stream': 56.56762836128473, + 'transform': [array([ 0.00987427, -0.00354858, 0.1648657 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00811345, -0.00352402, -0.00268029]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020340753719210625, + 'FR_Wheel_Angle': 0.02034592255949974, + 'Location': array([ 1.88860707e-02, -1.95420914e+01, 1.68532714e-01]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.28505582, -0.33960539, 0.00046119]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8946533203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -109.54483032, -1753.63439941, 16.83044434]), + 'frame': 13790, + 'frame_number': 13790, + 'framesequence': 13788, + 'gaze_dir': array([ 0.98058069, 0.18484598, -0.06552491]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18484598, -0.06552491]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18484598, -0.06552491]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.57231825962663, + 'timestamp_carla': 56572, + 'timestamp_device': 56208, + 'timestamp_stream': 56.57231825962663, + 'transform': [array([ 0.00987442, -0.00354858, 0.16486451]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0037289 , 0.00058362, -0.00226329]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033832296729088, + 'FR_Wheel_Angle': 0.020341234281659126, + 'Location': array([ 5.26031479e-03, -1.95583210e+01, 1.68550074e-01]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.28929934, -0.34464744, 0.00041884]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8951416015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -109.22650146, -1752.77746582, 16.82995605]), + 'frame': 13791, + 'frame_number': 13791, + 'framesequence': 13789, + 'gaze_dir': array([ 0.98058069, 0.18517113, -0.06460037]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18517113, -0.06460037]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18517113, -0.06460037]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.5764931589365, + 'timestamp_carla': 56576, + 'timestamp_device': 56213, + 'timestamp_stream': 56.5764931589365, + 'transform': [array([ 0.00987442, -0.00354858, 0.16486451]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01686493, -0.01065789, -0.00189289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034151554107666, + 'FR_Wheel_Angle': 0.020343778654932976, + 'Location': array([-8.30335449e-03, -1.95744801e+01, 1.68561131e-01]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.2837294 , -0.33802775, 0.00035579]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.89599609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -108.82420349, -1751.70898438, 16.82885742]), + 'frame': 13792, + 'frame_number': 13792, + 'framesequence': 13790, + 'gaze_dir': array([ 0.98058069, 0.18549187, -0.06367351]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18549187, -0.06367351]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18549187, -0.06367351]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.58127735927701, + 'timestamp_carla': 56581, + 'timestamp_device': 56218, + 'timestamp_stream': 56.58127735927701, + 'transform': [array([ 0.00987457, -0.00354858, 0.16486318]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00679864, 0.00896029, -0.00275468]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020333582535386086, + 'FR_Wheel_Angle': 0.020337853580713272, + 'Location': array([ -0.02195833, -19.59074593, 0.16858143]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.29755992, -0.354489 , 0.00052409]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8968505859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -108.41625977, -1750.6418457 , 16.828125 ]), + 'frame': 13793, + 'frame_number': 13793, + 'framesequence': 13791, + 'gaze_dir': array([ 0.98058069, 0.1858706 , -0.06255933]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1858706 , -0.06255933]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1858706 , -0.06255933]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.58769366145134, + 'timestamp_carla': 56587, + 'timestamp_device': 56224, + 'timestamp_stream': 56.58769366145134, + 'transform': [array([ 0.00987442, -0.00354858, 0.1648535 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00142805, 0.00449455, -0.00285789]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033146470785141, + 'FR_Wheel_Angle': 0.02033720538020134, + 'Location': array([ -0.03508417, -19.60638046, 0.16860057]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.30125085, -0.35888407, 0.00044649]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.897705078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -107.91967773, -1749.36401367, 16.82714844]), + 'frame': 13794, + 'frame_number': 13794, + 'framesequence': 13792, + 'gaze_dir': array([ 0.98058069, 0.18624264, -0.06144289]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18624264, -0.06144289]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18624264, -0.06144289]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.59341746196151, + 'timestamp_carla': 56593, + 'timestamp_device': 56230, + 'timestamp_stream': 56.59341746196151, + 'transform': [array([ 0.00987457, -0.00354858, 0.16484934]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00250976, 0.00168294, -0.0023529 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02032933570444584, + 'FR_Wheel_Angle': 0.020332282409071922, + 'Location': array([ -0.04964367, -19.62372208, 0.16861987]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.30496725, -0.36329788, 0.00047367]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.897705078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -107.41537476, -1748.08935547, 16.82617188]), + 'frame': 13795, + 'frame_number': 13795, + 'framesequence': 13793, + 'gaze_dir': array([ 0.98058057, 0.18648678, -0.06069783]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.18648678, -0.06069783]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.18648678, -0.06069783]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.59751205891371, + 'timestamp_carla': 56597, + 'timestamp_device': 56234, + 'timestamp_stream': 56.59751205891371, + 'transform': [array([ 0.00987457, -0.00354858, 0.16484934]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00344012, 0.00657665, -0.00299436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020324092358350754, + 'FR_Wheel_Angle': 0.020328352227807045, + 'Location': array([ -0.06401704, -19.64084053, 0.16864109]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.31410068, -0.37417555, 0.00042425]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8978271484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -107.0750885 , -1747.24182129, 16.82568359]), + 'frame': 13796, + 'frame_number': 13796, + 'framesequence': 13794, + 'gaze_dir': array([ 0.98058069, 0.18666817, -0.0601377 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18666817, -0.0601377 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18666817, -0.0601377 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.60086686164141, + 'timestamp_carla': 56600, + 'timestamp_device': 56237, + 'timestamp_stream': 56.60086686164141, + 'transform': [array([ 0.00987472, -0.00354858, 0.16485177]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00226995, 0.00220085, -0.00265747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020322555676102638, + 'FR_Wheel_Angle': 0.020325245335698128, + 'Location': array([ -0.07873028, -19.65836525, 0.16866004]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.31678566, -0.37736419, 0.00048466]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8983154296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -106.81739807, -1746.60620117, 16.82519531]), + 'frame': 13797, + 'frame_number': 13797, + 'framesequence': 13795, + 'gaze_dir': array([ 0.98058069, 0.18684766, -0.05957774]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18684766, -0.05957774]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18684766, -0.05957774]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.60401206091046, + 'timestamp_carla': 56604, + 'timestamp_device': 56240, + 'timestamp_stream': 56.60401206091046, + 'transform': [array([ 0.00987457, -0.00354858, 0.16485372]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00547975, -0.00120005, 0.00403214]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020320985466241837, + 'FR_Wheel_Angle': 0.020325254648923874, + 'Location': array([ -0.09400821, -19.67656136, 0.1686766 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.31951272, -0.38063166, 0.00047012]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.8990478515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -106.55821228, -1745.9720459 , 16.82470703]), + 'frame': 13798, + 'frame_number': 13798, + 'framesequence': 13796, + 'gaze_dir': array([ 0.98058069, 0.18708456, -0.05882956]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18708456, -0.05882956]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18708456, -0.05882956]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.60754765942693, + 'timestamp_carla': 56607, + 'timestamp_device': 56244, + 'timestamp_stream': 56.60754765942693, + 'transform': [array([ 0.00987472, -0.00354858, 0.16485578]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00657922, -0.00202595, -0.00013428]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02032112143933773, + 'FR_Wheel_Angle': 0.02032550796866417, + 'Location': array([ -0.10810353, -19.69334984, 0.16869149]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.31928504, -0.38034236, 0.00052735]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.89990234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -106.20930481, -1745.1270752 , 16.82409668]), + 'frame': 13799, + 'frame_number': 13799, + 'framesequence': 13797, + 'gaze_dir': array([ 0.98058069, 0.18731825, -0.05808117]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18731825, -0.05808117]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18731825, -0.05808117]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.611866261810064, + 'timestamp_carla': 56611, + 'timestamp_device': 56248, + 'timestamp_stream': 56.611866261810064, + 'transform': [array([ 0.00987472, -0.00354858, 0.16485578]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00922029, -0.00429696, -0.00289688]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020321909338235855, + 'FR_Wheel_Angle': 0.020326117053627968, + 'Location': array([ -0.12248089, -19.71047783, 0.1687056 ]), + 'Rotation': array([-5.80156222e-02, 4.99775505e+01, -3.72924767e-02]), + 'Velocity': array([-0.31789976, -0.37870395, 0.00050219]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9007568359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -105.85739136, -1744.28430176, 16.82336426]), + 'frame': 13800, + 'frame_number': 13800, + 'framesequence': 13798, + 'gaze_dir': array([ 0.98058069, 0.18754917, -0.05733113]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18754917, -0.05733113]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18754917, -0.05733113]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.61577896028757, + 'timestamp_carla': 56615, + 'timestamp_device': 56252, + 'timestamp_stream': 56.61577896028757, + 'transform': [array([ 0.00987488, -0.00354858, 0.16485724]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02207349, 0.02292266, -0.00281634]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02030964568257332, + 'FR_Wheel_Angle': 0.02031291462481022, + 'Location': array([ -0.138099 , -19.72907829, 0.16870171]), + 'Rotation': array([-5.78926802e-02, 4.99775505e+01, -3.73229980e-02]), + 'Velocity': array([-0.33928287, -0.40416014, 0.00108236]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9014892578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -105.50170898, -1743.44213867, 16.82263184]), + 'frame': 13801, + 'frame_number': 13801, + 'framesequence': 13799, + 'gaze_dir': array([ 0.98058069, 0.18772022, -0.05676854]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18772022, -0.05676854]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18772022, -0.05676854]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.619223061949015, + 'timestamp_carla': 56619, + 'timestamp_device': 56255, + 'timestamp_stream': 56.619223061949015, + 'transform': [array([ 0.00987472, -0.00354858, 0.16485868]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00706863, -0.00236534, -0.00327038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020313022658228874, + 'FR_Wheel_Angle': 0.02031748741865158, + 'Location': array([ -0.15446888, -19.74857712, 0.16873932]), + 'Rotation': array([-5.78926802e-02, 4.99775505e+01, -3.73229980e-02]), + 'Velocity': array([-0.33339545, -0.39714894, 0.00074183]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.902099609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -105.23297119, -1742.81201172, 16.82226562]), + 'frame': 13802, + 'frame_number': 13802, + 'framesequence': 13800, + 'gaze_dir': array([ 0.98058069, 0.18794589, -0.0560169 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18794589, -0.0560169 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18794589, -0.0560169 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.622669361531734, + 'timestamp_carla': 56622, + 'timestamp_device': 56259, + 'timestamp_stream': 56.622669361531734, + 'transform': [array([ 0.00987488, -0.00354858, 0.16486059]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01189693, -0.00571131, -0.00256457]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020314296707510948, + 'FR_Wheel_Angle': 0.020317083224654198, + 'Location': array([ -0.17023201, -19.76735115, 0.16876632]), + 'Rotation': array([-5.78926802e-02, 4.99775505e+01, -3.73229980e-02]), + 'Velocity': array([-0.33118278, -0.39450052, 0.00063265]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.90283203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -104.87145996, -1741.97241211, 16.82165527]), + 'frame': 13803, + 'frame_number': 13803, + 'framesequence': 13801, + 'gaze_dir': array([ 0.98058069, 0.18822369, -0.05507628]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18822369, -0.05507628]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18822369, -0.05507628]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.628153860569, + 'timestamp_carla': 56628, + 'timestamp_device': 56264, + 'timestamp_stream': 56.628153860569, + 'transform': [array([ 0.00987472, -0.00354858, 0.16485643]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01445456, -0.00801352, -0.00256075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02031577378511429, + 'FR_Wheel_Angle': 0.02031869627535343, + 'Location': array([ -0.18502174, -19.78496742, 0.16878505]), + 'Rotation': array([-5.78926802e-02, 4.99775505e+01, -3.73229980e-02]), + 'Velocity': array([-0.32860851, -0.39143646, 0.00054213]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.904052734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -104.41491699, -1740.92504883, 16.82067871]), + 'frame': 13804, + 'frame_number': 13804, + 'framesequence': 13802, + 'gaze_dir': array([ 0.98058069, 0.18844235, -0.05432335]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18844235, -0.05432335]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18844235, -0.05432335]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.631813161075115, + 'timestamp_carla': 56631, + 'timestamp_device': 56268, + 'timestamp_stream': 56.631813161075115, + 'transform': [array([ 0.00987488, -0.00354858, 0.16485822]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00813102, -0.00318411, -0.00327831]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02031494304537773, + 'FR_Wheel_Angle': 0.020319897681474686, + 'Location': array([ -0.20081398, -19.80377579, 0.16880447]), + 'Rotation': array([-5.78926802e-02, 4.99775505e+01, -3.73229980e-02]), + 'Velocity': array([-3.30053806e-01, -3.93162072e-01, 3.16228863e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9041748046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -104.04605103, -1740.08959961, 16.82006836]), + 'frame': 13805, + 'frame_number': 13805, + 'framesequence': 13803, + 'gaze_dir': array([ 0.98058069, 0.18860459, -0.05375737]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18860459, -0.05375737]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18860459, -0.05375737]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.635144259780645, + 'timestamp_carla': 56635, + 'timestamp_device': 56271, + 'timestamp_stream': 56.635144259780645, + 'transform': [array([ 0.00987472, -0.00354858, 0.16485974]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00897493, 0.01183141, -0.00260063]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02030900865793228, + 'FR_Wheel_Angle': 0.02031368389725685, + 'Location': array([ -0.21624212, -19.82215118, 0.16881458]), + 'Rotation': array([-5.77355847e-02, 4.99775543e+01, -3.73535119e-02]), + 'Velocity': array([-0.33921695, -0.40406063, 0.0006307 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9049072265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -103.76696777, -1739.4630127 , 16.81958008]), + 'frame': 13806, + 'frame_number': 13806, + 'framesequence': 13804, + 'gaze_dir': array([ 0.98058069, 0.18881801, -0.05300294]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18881801, -0.05300294]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18881801, -0.05300294]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.63886396214366, + 'timestamp_carla': 56638, + 'timestamp_device': 56275, + 'timestamp_stream': 56.63886396214366, + 'transform': [array([ 0.00987488, -0.00354858, 0.16486128]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00181648, 0.0030658 , -0.00267726]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020309504121541977, + 'FR_Wheel_Angle': 0.020312273874878883, + 'Location': array([ -0.23120943, -19.83997726, 0.16884007]), + 'Rotation': array([-5.77355847e-02, 4.99775543e+01, -3.73535119e-02]), + 'Velocity': array([-0.33953848, -0.40444005, 0.00052464]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9056396484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -103.39239502, -1738.63000488, 16.81896973]), + 'frame': 13807, + 'frame_number': 13807, + 'framesequence': 13805, + 'gaze_dir': array([ 0.98058069, 0.18908072, -0.05205799]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18908072, -0.05205799]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18908072, -0.05205799]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.64339216053486, + 'timestamp_carla': 56643, + 'timestamp_device': 56280, + 'timestamp_stream': 56.64339216053486, + 'transform': [array([ 0.00987488, -0.00354858, 0.16486128]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00722998, -0.00239122, -0.00334905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02031034044921398, + 'FR_Wheel_Angle': 0.020314738154411316, + 'Location': array([ -0.24759464, -19.85949135, 0.16886166]), + 'Rotation': array([-5.77355847e-02, 4.99775543e+01, -3.73535119e-02]), + 'Velocity': array([-0.33807987, -0.40271139, 0.00053005]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9066162109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -102.91911316, -1737.59008789, 16.81811523]), + 'frame': 13808, + 'frame_number': 13808, + 'framesequence': 13806, + 'gaze_dir': array([ 0.98058069, 0.18928751, -0.05130095]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18928751, -0.05130095]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18928751, -0.05130095]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.64788645878434, + 'timestamp_carla': 56647, + 'timestamp_device': 56284, + 'timestamp_stream': 56.64788645878434, + 'transform': [array([ 0.00987488, -0.00354858, 0.16486128]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00538833, 0.00890165, -0.04859763]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020305151119828224, + 'FR_Wheel_Angle': 0.020309824496507645, + 'Location': array([ -0.26274121, -19.87752914, 0.16886631]), + 'Rotation': array([-5.78312092e-02, 4.99773788e+01, -3.73840295e-02]), + 'Velocity': array([-3.47126067e-01, -4.13476706e-01, 3.13315395e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9072265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -102.53666687, -1736.75976562, 16.81762695]), + 'frame': 13809, + 'frame_number': 13809, + 'framesequence': 13807, + 'gaze_dir': array([ 0.98058069, 0.18949109, -0.05054381]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18949109, -0.05054381]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18949109, -0.05054381]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.65156375989318, + 'timestamp_carla': 56651, + 'timestamp_device': 56288, + 'timestamp_stream': 56.65156375989318, + 'transform': [array([ 0.00987472, -0.00354858, 0.16486235]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02728646, -0.01983738, -0.0048852 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02031903900206089, + 'FR_Wheel_Angle': 0.02159539796411991, + 'Location': array([ -0.27840313, -19.89617348, 0.16888019]), + 'Rotation': array([-5.70389070e-02, 4.99771957e+01, -3.74145471e-02]), + 'Velocity': array([-0.32292098, -0.38465339, 0.0004385 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.907958984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -102.15127563, -1735.9317627 , 16.81689453]), + 'frame': 13810, + 'frame_number': 13810, + 'framesequence': 13808, + 'gaze_dir': array([ 0.98058069, 0.18964197, -0.0499747 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18964197, -0.0499747 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18964197, -0.0499747 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.655154161155224, + 'timestamp_carla': 56655, + 'timestamp_device': 56291, + 'timestamp_stream': 56.655154161155224, + 'transform': [array([ 0.00987488, -0.00354858, 0.16486399]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00789973, -0.00561909, -0.01902923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.17881688475608826, + 'FR_Wheel_Angle': 0.20326776802539825, + 'Location': array([ -0.29331207, -19.91393852, 0.16889851]), + 'Rotation': array([-5.60621880e-02, 4.99772148e+01, -3.74145508e-02]), + 'Velocity': array([-0.31663296, -0.37779489, 0.00068264]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.90869140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -101.85972595, -1735.31091309, 16.81628418]), + 'frame': 13811, + 'frame_number': 13811, + 'framesequence': 13809, + 'gaze_dir': array([ 0.98058069, 0.18988934, -0.04902639]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18988934, -0.04902639]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18988934, -0.04902639]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.65970106050372, + 'timestamp_carla': 56659, + 'timestamp_device': 56296, + 'timestamp_stream': 56.65970106050372, + 'transform': [array([ 0.00987488, -0.00354858, 0.16486399]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00492834, 0.00289311, -0.06297657]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4603014290332794, + 'FR_Wheel_Angle': 0.4852326214313507, + 'Location': array([ -0.308676 , -19.93229866, 0.16892502]), + 'Rotation': array([-5.62124550e-02, 4.99757652e+01, -3.74145471e-02]), + 'Velocity': array([-0.32018742, -0.3839767 , 0.00061814]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.909912109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -101.37026978, -1734.27954102, 16.81530762]), + 'frame': 13812, + 'frame_number': 13812, + 'framesequence': 13810, + 'gaze_dir': array([ 0.98058069, 0.19022787, -0.04769598]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19022787, -0.04769598]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19022787, -0.04769598]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.66692655906081, + 'timestamp_carla': 56666, + 'timestamp_device': 56303, + 'timestamp_stream': 56.66692655906081, + 'transform': [array([ 0.00987503, -0.00354858, 0.164849 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00236248, 0.00451054, -0.0889317 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5596544146537781, + 'FR_Wheel_Angle': 0.5702922344207764, + 'Location': array([ -0.32363012, -19.950243 , 0.16894463]), + 'Rotation': array([-5.64583391e-02, 4.99721107e+01, -3.74145508e-02]), + 'Velocity': array([-0.32041869, -0.38556513, 0.00047307]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9110107421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -100.67593384, -1732.83898926, 16.81420898]), + 'frame': 13813, + 'frame_number': 13813, + 'framesequence': 13811, + 'gaze_dir': array([ 0.98058069, 0.19041722, -0.04693438]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19041722, -0.04693438]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19041722, -0.04693438]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.67073646187782, + 'timestamp_carla': 56670, + 'timestamp_device': 56307, + 'timestamp_stream': 56.67073646187782, + 'transform': [array([ 0.00987488, -0.00354858, 0.16485071]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00175401, 0.00301961, -0.10119435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.6813976168632507, + 'FR_Wheel_Angle': 0.7036948800086975, + 'Location': array([ -0.33843681, -19.96803284, 0.16896507]), + 'Rotation': array([-5.66086061e-02, 4.99678345e+01, -3.74145471e-02]), + 'Velocity': array([-0.31968409, -0.38524491, 0.00047182]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9100341796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -100.27416992, -1732.0177002 , 16.81359863]), + 'frame': 13814, + 'frame_number': 13814, + 'framesequence': 13812, + 'gaze_dir': array([ 0.98058069, 0.19064955, -0.04598151]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19064955, -0.04598151]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19064955, -0.04598151]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.675114061683416, + 'timestamp_carla': 56675, + 'timestamp_device': 56312, + 'timestamp_stream': 56.675114061683416, + 'transform': [array([ 0.00987503, -0.00354858, 0.16485186]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00857175, -0.00271209, -0.1296135 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.9015171527862549, + 'FR_Wheel_Angle': 0.9375362396240234, + 'Location': array([ -0.35420424, -19.9870224 , 0.16897228]), + 'Rotation': array([-5.65198138e-02, 4.99618683e+01, -3.74450684e-02]), + 'Velocity': array([-0.31498143, -0.38088655, -0.00130366]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9110107421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -99.76789856, -1730.99353027, 16.81286621]), + 'frame': 13815, + 'frame_number': 13815, + 'framesequence': 13813, + 'gaze_dir': array([ 0.98058069, 0.19087695, -0.04502821]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19087695, -0.04502821]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19087695, -0.04502821]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.68055506050587, + 'timestamp_carla': 56680, + 'timestamp_device': 56317, + 'timestamp_stream': 56.68055506050587, + 'transform': [array([ 0.00987488, -0.00354858, 0.164849 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00293673, -0.00045808, -0.18582462]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2123857736587524, + 'FR_Wheel_Angle': 1.2508735656738281, + 'Location': array([ -0.36958766, -20.00562096, 0.16900146]), + 'Rotation': array([-5.73462658e-02, 4.99539680e+01, -3.74450646e-02]), + 'Velocity': array([-0.32524386, -0.39554337, 0.00061694]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9122314453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -99.25689697, -1729.97253418, 16.81176758]), + 'frame': 13816, + 'frame_number': 13816, + 'framesequence': 13814, + 'gaze_dir': array([ 0.98058069, 0.19105561, -0.04426404]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19105561, -0.04426404]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19105561, -0.04426404]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.68457046151161, + 'timestamp_carla': 56684, + 'timestamp_device': 56321, + 'timestamp_stream': 56.68457046151161, + 'transform': [array([ 0.00987503, -0.00354858, 0.16485098]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00698476, -0.00201114, -0.22844514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.4067473411560059, + 'FR_Wheel_Angle': 1.4337244033813477, + 'Location': array([ -0.38441956, -20.02362633, 0.16902527]), + 'Rotation': array([-5.72847947e-02, 4.99440308e+01, -3.74450721e-02]), + 'Velocity': array([-0.32437077, -0.39629149, 0.00052781]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9124755859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -98.84393311, -1729.15698242, 16.8112793 ]), + 'frame': 13817, + 'frame_number': 13817, + 'framesequence': 13815, + 'gaze_dir': array([ 0.98058069, 0.19123119, -0.04349915]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19123119, -0.04349915]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19123119, -0.04349915]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.68896505981684, + 'timestamp_carla': 56689, + 'timestamp_device': 56325, + 'timestamp_stream': 56.68896505981684, + 'transform': [array([ 0.00987503, -0.00354858, 0.16485098]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00746151, -0.00393691, -0.26689407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.5289627313613892, + 'FR_Wheel_Angle': 1.5608538389205933, + 'Location': array([ -0.40051123, -20.04320908, 0.16904697]), + 'Rotation': array([-5.70662282e-02, 4.99317589e+01, -3.75671349e-02]), + 'Velocity': array([-0.32279271, -0.39591303, 0.00039838]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9134521484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -98.42779541, -1728.34301758, 16.8104248 ]), + 'frame': 13818, + 'frame_number': 13818, + 'framesequence': 13816, + 'gaze_dir': array([ 0.98058069, 0.19144619, -0.04254299]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19144619, -0.04254299]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19144619, -0.04254299]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.69329036027193, + 'timestamp_carla': 56693, + 'timestamp_device': 56330, + 'timestamp_stream': 56.69329036027193, + 'transform': [array([ 0.00987518, -0.00354858, 0.16485223]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00471093, -0.00271755, -0.29300809]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.7000524997711182, + 'FR_Wheel_Angle': 1.7437773942947388, + 'Location': array([ -0.41522515, -20.06115341, 0.16906506]), + 'Rotation': array([-5.68271726e-02, 4.99197121e+01, -3.77502441e-02]), + 'Velocity': array([-0.32152697, -0.39552751, 0.00046697]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9144287109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -97.90354919, -1727.32885742, 16.80957031]), + 'frame': 13819, + 'frame_number': 13819, + 'framesequence': 13817, + 'gaze_dir': array([ 0.98058069, 0.19157304, -0.04196804]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19157304, -0.04196804]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19157304, -0.04196804]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.69711346179247, + 'timestamp_carla': 56697, + 'timestamp_device': 56333, + 'timestamp_stream': 56.69711346179247, + 'transform': [array([ 0.00987503, -0.00354858, 0.1648538 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00242062, 0.00147077, -0.35555774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9645607471466064, + 'FR_Wheel_Angle': 2.0345046520233154, + 'Location': array([ -0.42965207, -20.07879066, 0.16908416]), + 'Rotation': array([-5.67656979e-02, 4.99062881e+01, -3.79333496e-02]), + 'Velocity': array([-0.32392332, -0.40001464, 0.00053483]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9149169921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -97.58612061, -1726.7208252 , 16.8092041 ]), + 'frame': 13820, + 'frame_number': 13820, + 'framesequence': 13818, + 'gaze_dir': array([ 0.98058069, 0.19173929, -0.04120184]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19173929, -0.04120184]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19173929, -0.04120184]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.70107835903764, + 'timestamp_carla': 56701, + 'timestamp_device': 56337, + 'timestamp_stream': 56.70107835903764, + 'transform': [array([ 0.00987518, -0.00354858, 0.16485558]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00293549, -0.00441372, -0.38510901]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.2170279026031494, + 'FR_Wheel_Angle': 2.283632755279541, + 'Location': array([ -0.44464645, -20.09719276, 0.16910091]), + 'Rotation': array([-5.67656979e-02, 4.98901482e+01, -3.80248986e-02]), + 'Velocity': array([-3.20879698e-01, -3.98525119e-01, 2.32458115e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9158935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -97.16069031, -1725.91259766, 16.80834961]), + 'frame': 13821, + 'frame_number': 13821, + 'framesequence': 13819, + 'gaze_dir': array([ 0.98058057, 0.19194292, -0.04024242]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.19194292, -0.04024242]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.19194292, -0.04024242]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.70525725930929, + 'timestamp_carla': 56705, + 'timestamp_device': 56342, + 'timestamp_stream': 56.70525725930929, + 'transform': [array([ 0.00987518, -0.00354858, 0.16485558]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.87464795e-04, -1.14936222e-04, -4.24492836e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.4088785648345947, + 'FR_Wheel_Angle': 2.4905354976654053, + 'Location': array([ -0.45945457, -20.11542511, 0.16911693]), + 'Rotation': array([-5.64310215e-02, 4.98720055e+01, -3.81469727e-02]), + 'Velocity': array([-0.31917599, -0.39777318, 0.00058465]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9169921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -96.62391663, -1724.90405273, 16.80749512]), + 'frame': 13822, + 'frame_number': 13822, + 'framesequence': 13820, + 'gaze_dir': array([ 0.98058057, 0.19210243, -0.03947402]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.19210243, -0.03947402]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.19210243, -0.03947402]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.709792260080576, + 'timestamp_carla': 56709, + 'timestamp_device': 56346, + 'timestamp_stream': 56.709792260080576, + 'transform': [array([ 0.00987518, -0.00354858, 0.16485558]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.08834249e-04, -1.95734552e-03, -4.76593703e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.727790594100952, + 'FR_Wheel_Angle': 2.8336281776428223, + 'Location': array([ -0.4742198 , -20.13366127, 0.16913421]), + 'Rotation': array([-5.63353971e-02, 4.98522606e+01, -3.83300707e-02]), + 'Velocity': array([-0.31726038, -0.39738756, 0.00045342]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.917724609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -96.19076538, -1724.09887695, 16.8067627 ]), + 'frame': 13823, + 'frame_number': 13823, + 'framesequence': 13821, + 'gaze_dir': array([ 0.98058069, 0.19225872, -0.03870572]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19225872, -0.03870572]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19225872, -0.03870572]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.713360361754894, + 'timestamp_carla': 56713, + 'timestamp_device': 56350, + 'timestamp_stream': 56.713360361754894, + 'transform': [array([ 0.00987503, -0.00354858, 0.16485724]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00115303, 0.0037233 , -0.51399559]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.0505034923553467, + 'FR_Wheel_Angle': 3.1583316326141357, + 'Location': array([ -0.49017721, -20.15345573, 0.16915439]), + 'Rotation': array([-5.63353971e-02, 4.98277397e+01, -3.84216271e-02]), + 'Velocity': array([-0.31791589, -0.39963332, 0.00046096]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9185791015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -95.75480652, -1723.29638672, 16.8059082 ]), + 'frame': 13824, + 'frame_number': 13824, + 'framesequence': 13822, + 'gaze_dir': array([ 0.98058069, 0.19237405, -0.03812835]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19237405, -0.03812835]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19237405, -0.03812835]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.717016860842705, + 'timestamp_carla': 56717, + 'timestamp_device': 56353, + 'timestamp_stream': 56.717016860842705, + 'transform': [array([ 0.00987518, -0.00354858, 0.16485922]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00396898, 0.00447942, -0.53969681]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.253237247467041, + 'FR_Wheel_Angle': 3.3829290866851807, + 'Location': array([ -0.50465912, -20.17150116, 0.16917515]), + 'Rotation': array([-5.65812849e-02, 4.98034401e+01, -3.85436974e-02]), + 'Velocity': array([-0.31946713, -0.40327474, 0.00059847]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.919189453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -95.425354 , -1722.69482422, 16.80541992]), + 'frame': 13825, + 'frame_number': 13825, + 'framesequence': 13823, + 'gaze_dir': array([ 0.98058069, 0.19252495, -0.03735898]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19252495, -0.03735898]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19252495, -0.03735898]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.72083995863795, + 'timestamp_carla': 56720, + 'timestamp_device': 56357, + 'timestamp_stream': 56.72083995863795, + 'transform': [array([ 0.00987503, -0.00354858, 0.16486032]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00522188, 0.0034509 , -0.58597249]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.5335135459899902, + 'FR_Wheel_Angle': 3.6889431476593018, + 'Location': array([ -0.51926243, -20.18974876, 0.16919456]), + 'Rotation': array([-5.66086061e-02, 4.97771721e+01, -3.87268029e-02]), + 'Velocity': array([-0.31968096, -0.40518188, 0.00055669]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.920166015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -94.98384094, -1721.89526367, 16.80480957]), + 'frame': 13826, + 'frame_number': 13826, + 'framesequence': 13824, + 'gaze_dir': array([ 0.98058069, 0.19267289, -0.03658827]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19267289, -0.03658827]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19267289, -0.03658827]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.72516546025872, + 'timestamp_carla': 56725, + 'timestamp_device': 56361, + 'timestamp_stream': 56.72516546025872, + 'transform': [array([ 0.00987503, -0.00354858, 0.16486032]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0035453 , 0.00405254, -0.64142007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.801504611968994, + 'FR_Wheel_Angle': 3.9729087352752686, + 'Location': array([ -0.53430551, -20.20862198, 0.16921085]), + 'Rotation': array([-5.66086061e-02, 4.97475319e+01, -3.88793908e-02]), + 'Velocity': array([-0.32066742, -0.40862566, 0.00060979]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9210205078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -94.53866577, -1721.09680176, 16.80407715]), + 'frame': 13827, + 'frame_number': 13827, + 'framesequence': 13825, + 'gaze_dir': array([ 0.98058069, 0.19281763, -0.03581771]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19281763, -0.03581771]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19281763, -0.03581771]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.72902075946331, + 'timestamp_carla': 56729, + 'timestamp_device': 56365, + 'timestamp_stream': 56.72902075946331, + 'transform': [array([ 0.00987503, -0.00354858, 0.16486032]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0027874, -0.0034753, -0.7460236]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.047327995300293, + 'FR_Wheel_Angle': 4.248047351837158, + 'Location': array([ -0.55046171, -20.22896004, 0.16923149]), + 'Rotation': array([-5.65198138e-02, 4.97127838e+01, -3.90624925e-02]), + 'Velocity': array([-0.31780702, -0.40815821, 0.00050168]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9217529296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -94.09072876, -1720.30078125, 16.80334473]), + 'frame': 13828, + 'frame_number': 13828, + 'framesequence': 13826, + 'gaze_dir': array([ 0.98058069, 0.19295941, -0.03504584]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19295941, -0.03504584]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19295941, -0.03504584]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.73288765922189, + 'timestamp_carla': 56732, + 'timestamp_device': 56369, + 'timestamp_stream': 56.73288765922189, + 'transform': [array([ 0.00987518, -0.00354858, 0.16486174]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01528087, -0.00254986, -0.70165378]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.357170581817627, + 'FR_Wheel_Angle': 4.596984386444092, + 'Location': array([ -0.56447524, -20.24665451, 0.16924271]), + 'Rotation': array([-5.58163039e-02, 4.96810303e+01, -3.93371508e-02]), + 'Velocity': array([-0.30778947, -0.39544976, 0.00045798]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9224853515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -93.6391449 , -1719.50585938, 16.8026123 ]), + 'frame': 13829, + 'frame_number': 13829, + 'framesequence': 13827, + 'gaze_dir': array([ 0.98058069, 0.19306363, -0.03446713]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19306363, -0.03446713]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19306363, -0.03446713]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.73630056157708, + 'timestamp_carla': 56736, + 'timestamp_device': 56372, + 'timestamp_stream': 56.73630056157708, + 'transform': [array([ 0.00987503, -0.00354858, 0.16486314]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01340515, -0.0011969 , -0.7435813 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.730799198150635, + 'FR_Wheel_Angle': 4.993156433105469, + 'Location': array([ -0.57976121, -20.26605797, 0.16925323]), + 'Rotation': array([-5.50240017e-02, 4.96431999e+01, -3.94897424e-02]), + 'Velocity': array([-0.29870316, -0.38628408, 0.00054351]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9232177734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -93.29875183, -1718.91149902, 16.80200195]), + 'frame': 13830, + 'frame_number': 13830, + 'framesequence': 13828, + 'gaze_dir': array([ 0.98058069, 0.19319999, -0.03369429]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19319999, -0.03369429]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19319999, -0.03369429]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.74012766033411, + 'timestamp_carla': 56740, + 'timestamp_device': 56376, + 'timestamp_stream': 56.74012766033411, + 'transform': [array([ 0.00987518, -0.00354858, 0.16486448]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00384868, 0.00316577, -0.81347257]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.1515212059021, + 'FR_Wheel_Angle': 5.457655429840088, + 'Location': array([ -0.59337676, -20.28342819, 0.16927688]), + 'Rotation': array([-5.49625307e-02, 4.96065712e+01, -3.94897461e-02]), + 'Velocity': array([-0.29845965, -0.38878632, 0.0005892 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.924072265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -92.84165955, -1718.11975098, 16.80126953]), + 'frame': 13831, + 'frame_number': 13831, + 'framesequence': 13829, + 'gaze_dir': array([ 0.98058069, 0.19333316, -0.03292165]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19333316, -0.03292165]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19333316, -0.03292165]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.74402866140008, + 'timestamp_carla': 56744, + 'timestamp_device': 56380, + 'timestamp_stream': 56.74402866140008, + 'transform': [array([ 0.00987518, -0.00354858, 0.16486448]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01707346, -0.00270438, -0.86414897]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.581415176391602, + 'FR_Wheel_Angle': 5.934542179107666, + 'Location': array([ -0.60712051, -20.30106163, 0.16929539]), + 'Rotation': array([-5.46893217e-02, 4.95662727e+01, -3.94897386e-02]), + 'Velocity': array([-0.28829706, -0.3783384 , 0.00038484]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9248046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -92.38182068, -1717.33056641, 16.80065918]), + 'frame': 13832, + 'frame_number': 13832, + 'framesequence': 13830, + 'gaze_dir': array([ 0.98058069, 0.19346334, -0.03214774]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19346334, -0.03214774]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19346334, -0.03214774]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.74746125936508, + 'timestamp_carla': 56747, + 'timestamp_device': 56384, + 'timestamp_stream': 56.74746125936508, + 'transform': [array([ 0.00987534, -0.00354858, 0.16486619]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01045575, -0.01860058, -0.99052292]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.986813068389893, + 'FR_Wheel_Angle': 6.413870811462402, + 'Location': array([ -0.62004864, -20.31776619, 0.16929886]), + 'Rotation': array([-5.40131330e-02, 4.95240746e+01, -3.95202599e-02]), + 'Velocity': array([-0.2740247 , -0.36621913, -0.00079937]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9256591796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -91.91838074, -1716.54248047, 16.79980469]), + 'frame': 13833, + 'frame_number': 13833, + 'framesequence': 13831, + 'gaze_dir': array([ 0.98058069, 0.19355887, -0.03156752]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19355887, -0.03156752]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19355887, -0.03156752]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.75115706026554, + 'timestamp_carla': 56751, + 'timestamp_device': 56387, + 'timestamp_stream': 56.75115706026554, + 'transform': [array([ 0.00987534, -0.00354858, 0.16486619]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03258016, -0.00666535, -0.87973416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.392390251159668, + 'FR_Wheel_Angle': 6.845297336578369, + 'Location': array([ -0.63367188, -20.33545685, 0.16930495]), + 'Rotation': array([-5.31320386e-02, 4.94778061e+01, -3.97643968e-02]), + 'Velocity': array([-0.25824547, -0.34401911, 0.00048576]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9261474609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -91.56906128, -1715.95324707, 16.79956055]), + 'frame': 13834, + 'frame_number': 13834, + 'framesequence': 13832, + 'gaze_dir': array([ 0.98058069, 0.19368364, -0.03079272]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19368364, -0.03079272]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19368364, -0.03079272]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.754765160381794, + 'timestamp_carla': 56754, + 'timestamp_device': 56391, + 'timestamp_stream': 56.754765160381794, + 'transform': [array([ 0.00987549, -0.00354858, 0.16486757]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.83390062e-02, -4.74854867e-04, -9.14873898e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.700502872467041, + 'FR_Wheel_Angle': 7.190009117126465, + 'Location': array([ -0.64580101, -20.35129166, 0.16932277]), + 'Rotation': array([-5.20596988e-02, 4.94331169e+01, -4.01000902e-02]), + 'Velocity': array([-0.24501279, -0.32855967, 0.00068173]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9268798828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -91.10012817, -1715.16845703, 16.79882812]), + 'frame': 13835, + 'frame_number': 13835, + 'framesequence': 13833, + 'gaze_dir': array([ 0.98058069, 0.19380531, -0.03001743]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19380531, -0.03001743]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19380531, -0.03001743]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.75848476216197, + 'timestamp_carla': 56758, + 'timestamp_device': 56395, + 'timestamp_stream': 56.75848476216197, + 'transform': [array([ 0.00987549, -0.00354858, 0.16486757]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 4.13396519e-05, -6.38979580e-03, -1.00217223e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.997116565704346, + 'FR_Wheel_Angle': 7.5528106689453125, + 'Location': array([ -0.65623814, -20.36497688, 0.16933765]), + 'Rotation': array([-5.15132844e-02, 4.93921051e+01, -4.03137170e-02]), + 'Velocity': array([-0.23314935, -0.31704262, 0.00063607]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.927978515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -90.62811279, -1714.38562012, 16.79797363]), + 'frame': 13836, + 'frame_number': 13836, + 'framesequence': 13834, + 'gaze_dir': array([ 0.98058057, 0.19389443, -0.0294362 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.19389443, -0.0294362 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.19389443, -0.0294362 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.762036960572004, + 'timestamp_carla': 56762, + 'timestamp_device': 56398, + 'timestamp_stream': 56.762036960572004, + 'transform': [array([ 0.00987564, -0.00354858, 0.16486891]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01487256, 0.00457539, -0.88867426]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.368975639343262, + 'FR_Wheel_Angle': 7.971280097961426, + 'Location': array([ -0.66780937, -20.38022614, 0.16935234]), + 'Rotation': array([-5.10010198e-02, 4.93438873e+01, -4.06188928e-02]), + 'Velocity': array([-0.21699512, -0.29413393, 0.00055732]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.928466796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -90.27233887, -1713.8001709 , 16.79748535]), + 'frame': 13837, + 'frame_number': 13837, + 'framesequence': 13835, + 'gaze_dir': array([ 0.98058069, 0.19401067, -0.02866008]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19401067, -0.02866008]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19401067, -0.02866008]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.76547636091709, + 'timestamp_carla': 56765, + 'timestamp_device': 56402, + 'timestamp_stream': 56.76547636091709, + 'transform': [array([ 0.00987564, -0.00354858, 0.16486891]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00934609, 0.0130195 , -0.9212712 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7843194007873535, + 'FR_Wheel_Angle': 8.453553199768066, + 'Location': array([ -0.67789567, -20.39356613, 0.16935249]), + 'Rotation': array([-5.10829836e-02, 4.93003387e+01, -4.07104418e-02]), + 'Velocity': array([-0.21693809, -0.29523823, 0.00077365]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.929443359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -89.7947998 , -1713.02062988, 16.79663086]), + 'frame': 13838, + 'frame_number': 13838, + 'framesequence': 13836, + 'gaze_dir': array([ 0.98058069, 0.19409575, -0.02807824]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19409575, -0.02807824]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19409575, -0.02807824]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.76903326064348, + 'timestamp_carla': 56769, + 'timestamp_device': 56405, + 'timestamp_stream': 56.76903326064348, + 'transform': [array([ 0.00987579, -0.00354858, 0.16487008]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.04344781, 0.00276394, -1.11829042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.156023025512695, + 'FR_Wheel_Angle': 8.889448165893555, + 'Location': array([ -0.68816411, -20.40722084, 0.16937171]), + 'Rotation': array([-5.17045297e-02, 4.92530937e+01, -4.05273438e-02]), + 'Velocity': array([-0.2178368 , -0.30333415, 0.00039305]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9300537109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -89.43495178, -1712.43774414, 16.79602051]), + 'frame': 13839, + 'frame_number': 13839, + 'framesequence': 13837, + 'gaze_dir': array([ 0.98058069, 0.19420655, -0.02730132]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19420655, -0.02730132]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19420655, -0.02730132]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.77246246114373, + 'timestamp_carla': 56772, + 'timestamp_device': 56409, + 'timestamp_stream': 56.77246246114373, + 'transform': [array([ 0.00987579, -0.00354858, 0.16487008]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01823441, 0.0039398 , -0.94843829]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.519111633300781, + 'FR_Wheel_Angle': 9.33053207397461, + 'Location': array([ -0.69728422, -20.41944695, 0.1693885 ]), + 'Rotation': array([-5.19709066e-02, 4.92094574e+01, -4.04357798e-02]), + 'Velocity': array([-0.19909225, -0.27535129, 0.00062302]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.930908203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -88.95195007, -1711.66149902, 16.79541016]), + 'frame': 13840, + 'frame_number': 13840, + 'framesequence': 13838, + 'gaze_dir': array([ 0.98058057, 0.19428751, -0.02671889]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.19428751, -0.02671889]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.19428751, -0.02671889]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.77581445872784, + 'timestamp_carla': 56775, + 'timestamp_device': 56412, + 'timestamp_stream': 56.77581445872784, + 'transform': [array([ 0.00987595, -0.00354858, 0.16487142]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02933772, -0.003735 , -1.12285733]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.870816230773926, + 'FR_Wheel_Angle': 9.731943130493164, + 'Location': array([ -0.70648617, -20.4318409 , 0.16939712]), + 'Rotation': array([-5.15132844e-02, 4.91628799e+01, -4.06188928e-02]), + 'Velocity': array([-0.19558869, -0.27675122, 0.00034046]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9315185546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -88.58805847, -1711.08117676, 16.79467773]), + 'frame': 13841, + 'frame_number': 13841, + 'framesequence': 13839, + 'gaze_dir': array([ 0.98058069, 0.19436677, -0.02613623]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19436677, -0.02613623]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19436677, -0.02613623]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.779260359704494, + 'timestamp_carla': 56779, + 'timestamp_device': 56415, + 'timestamp_stream': 56.779260359704494, + 'transform': [array([ 0.00987595, -0.00354858, 0.16487142]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00307701, -0.0105858 , -1.03914905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.205594062805176, + 'FR_Wheel_Angle': 10.134635925292969, + 'Location': array([ -0.71529961, -20.4437809 , 0.16941047]), + 'Rotation': array([-5.13288677e-02, 4.91160126e+01, -4.06799279e-02]), + 'Velocity': array([-0.1765569 , -0.25150269, 0.00046927]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.932373046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -88.22241211, -1710.50183105, 16.79406738]), + 'frame': 13842, + 'frame_number': 13842, + 'framesequence': 13840, + 'gaze_dir': array([ 0.98058069, 0.19446979, -0.02535824]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19446979, -0.02535824]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19446979, -0.02535824]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.7827667593956, + 'timestamp_carla': 56782, + 'timestamp_device': 56419, + 'timestamp_stream': 56.7827667593956, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16487245]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01503906, 0.01967793, -0.86005664]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.534377098083496, + 'FR_Wheel_Angle': 10.52432918548584, + 'Location': array([ -0.72377372, -20.45526505, 0.16941127]), + 'Rotation': array([-5.17045297e-02, 4.90698776e+01, -4.07104418e-02]), + 'Velocity': array([-0.18028124, -0.25026941, -0.00145968]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.93310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -87.73170471, -1709.73059082, 16.79333496]), + 'frame': 13843, + 'frame_number': 13843, + 'framesequence': 13841, + 'gaze_dir': array([ 0.98058069, 0.19454496, -0.02477504]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19454496, -0.02477504]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19454496, -0.02477504]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.786012660712004, + 'timestamp_carla': 56786, + 'timestamp_device': 56422, + 'timestamp_stream': 56.786012660712004, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16487245]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01946362, 0.00622361, -0.94371617]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.88715648651123, + 'FR_Wheel_Angle': 10.953537940979004, + 'Location': array([ -0.73275745, -20.46752739, 0.16943318]), + 'Rotation': array([-5.20596988e-02, 4.90185699e+01, -4.05273438e-02]), + 'Velocity': array([-1.71769410e-01, -2.42720544e-01, 1.53231624e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9337158203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -87.36199951, -1709.15380859, 16.79272461]), + 'frame': 13844, + 'frame_number': 13844, + 'framesequence': 13842, + 'gaze_dir': array([ 0.98058069, 0.19464253, -0.02399635]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19464253, -0.02399635]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19464253, -0.02399635]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.78974765911698, + 'timestamp_carla': 56789, + 'timestamp_device': 56426, + 'timestamp_stream': 56.78974765911698, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16487245]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02847501, -0.00715131, -1.17734885]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.23552417755127, + 'FR_Wheel_Angle': 11.382341384887695, + 'Location': array([ -0.74092156, -20.47874451, 0.16943821]), + 'Rotation': array([-5.18138111e-02, 4.89692688e+01, -4.06188890e-02]), + 'Velocity': array([-0.16918768, -0.24653301, 0.0003675 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9344482421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -86.86584473, -1708.38598633, 16.79211426]), + 'frame': 13845, + 'frame_number': 13845, + 'framesequence': 13843, + 'gaze_dir': array([ 0.98058069, 0.19471361, -0.02341264]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19471361, -0.02341264]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19471361, -0.02341264]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.79305826127529, + 'timestamp_carla': 56793, + 'timestamp_device': 56429, + 'timestamp_stream': 56.79305826127529, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16487245]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00610043, -0.01109163, -1.09529066]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.567854881286621, + 'FR_Wheel_Angle': 11.804762840270996, + 'Location': array([ -0.74849057, -20.48919678, 0.16945061]), + 'Rotation': array([-5.19094355e-02, 4.89224663e+01, -4.06188890e-02]), + 'Velocity': array([-0.15617187, -0.22912025, 0.00042284]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.93505859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -86.49209595, -1707.81188965, 16.79150391]), + 'frame': 13846, + 'frame_number': 13846, + 'framesequence': 13844, + 'gaze_dir': array([ 0.98058069, 0.19480576, -0.02263329]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19480576, -0.02263329]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19480576, -0.02263329]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.79671835899353, + 'timestamp_carla': 56796, + 'timestamp_device': 56433, + 'timestamp_stream': 56.79671835899353, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16487245]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01603148, 0.01489808, -0.91727501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.917501449584961, + 'FR_Wheel_Angle': 12.24091625213623, + 'Location': array([ -0.75619781, -20.49989891, 0.16944027]), + 'Rotation': array([-5.23397364e-02, 4.88726501e+01, -4.04357836e-02]), + 'Velocity': array([-0.15664877, -0.22496498, 0.00044395]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.935791015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -85.99064636, -1707.04748535, 16.79077148]), + 'frame': 13847, + 'frame_number': 13847, + 'framesequence': 13845, + 'gaze_dir': array([ 0.98058057, 0.19491649, -0.02165877]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.19491649, -0.02165877]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.19491649, -0.02165877]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.80195505917072, + 'timestamp_carla': 56802, + 'timestamp_device': 56438, + 'timestamp_stream': 56.80195505917072, + 'transform': [array([ 0.00987595, -0.00354858, 0.16486795]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02077481, 0.00689618, -1.60901546]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.245983123779297, + 'FR_Wheel_Angle': 12.636836051940918, + 'Location': array([ -0.76403403, -20.51078415, 0.16945831]), + 'Rotation': array([-5.30705675e-02, 4.88198586e+01, -4.03137170e-02]), + 'Velocity': array([-0.16422674, -0.24009658, 0.00056023]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.936767578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -85.35966492, -1706.0949707 , 16.78979492]), + 'frame': 13848, + 'frame_number': 13848, + 'framesequence': 13846, + 'gaze_dir': array([ 0.98058069, 0.19500153, -0.02087936]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19500153, -0.02087936]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19500153, -0.02087936]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.805890161544085, + 'timestamp_carla': 56805, + 'timestamp_device': 56442, + 'timestamp_stream': 56.805890161544085, + 'transform': [array([ 0.00987595, -0.00354858, 0.16486795]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01430028, 0.00744365, -1.06672716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.572321891784668, + 'FR_Wheel_Angle': 13.039649963378906, + 'Location': array([ -0.77174741, -20.52160835, 0.16948096]), + 'Rotation': array([-5.35281897e-02, 4.87714729e+01, -4.01306152e-02]), + 'Velocity': array([-0.15781017, -0.23023109, 0.00058043]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.93701171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -84.85171509, -1705.3359375 , 16.7890625 ]), + 'frame': 13849, + 'frame_number': 13849, + 'framesequence': 13847, + 'gaze_dir': array([ 0.98058069, 0.1951035 , -0.01990389]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1951035 , -0.01990389]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1951035 , -0.01990389]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.81120575964451, + 'timestamp_carla': 56811, + 'timestamp_device': 56447, + 'timestamp_stream': 56.81120575964451, + 'transform': [array([ 0.00987579, -0.00354858, 0.16486345]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03052365, 0.0050873 , -0.96754235]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.887328147888184, + 'FR_Wheel_Angle': 13.455154418945312, + 'Location': array([ -0.77869588, -20.53140068, 0.16949199]), + 'Rotation': array([-5.27358875e-02, 4.87211113e+01, -4.04663011e-02]), + 'Velocity': array([-0.14280605, -0.20907976, 0.00022279]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.93798828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -84.21212769, -1704.38916016, 16.78820801]), + 'frame': 13850, + 'frame_number': 13850, + 'framesequence': 13848, + 'gaze_dir': array([ 0.98058069, 0.19520059, -0.01892792]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19520059, -0.01892792]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19520059, -0.01892792]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.81509196013212, + 'timestamp_carla': 56815, + 'timestamp_device': 56452, + 'timestamp_stream': 56.81509196013212, + 'transform': [array([ 0.00987579, -0.00354858, 0.16486345]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02289748, 0.01117179, -1.12043726]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.2004976272583, + 'FR_Wheel_Angle': 13.855680465698242, + 'Location': array([ -0.78533316, -20.54079819, 0.1694936 ]), + 'Rotation': array([-5.25787920e-02, 4.86730576e+01, -4.04968187e-02]), + 'Velocity': array([-0.15098421, -0.22325222, 0.00058187]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9385986328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -83.56781006, -1703.44555664, 16.78710938]), + 'frame': 13851, + 'frame_number': 13851, + 'framesequence': 13849, + 'gaze_dir': array([ 0.98058069, 0.19525647, -0.01834255]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19525647, -0.01834255]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19525647, -0.01834255]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.81898295879364, + 'timestamp_carla': 56819, + 'timestamp_device': 56455, + 'timestamp_stream': 56.81898295879364, + 'transform': [array([ 0.00987579, -0.00354858, 0.16486345]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01084407, -0.01416352, -1.24651158]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.569985389709473, + 'FR_Wheel_Angle': 14.340909004211426, + 'Location': array([ -0.79336005, -20.55220604, 0.1695087 ]), + 'Rotation': array([-5.33096232e-02, 4.86116066e+01, -4.01000902e-02]), + 'Velocity': array([-0.14338495, -0.21989052, 0.00031177]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9393310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -83.17930603, -1702.88134766, 16.78637695]), + 'frame': 13852, + 'frame_number': 13852, + 'framesequence': 13850, + 'gaze_dir': array([ 0.98058069, 0.1953283 , -0.01756107]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1953283 , -0.01756107]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1953283 , -0.01756107]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.82246705889702, + 'timestamp_carla': 56822, + 'timestamp_device': 56459, + 'timestamp_stream': 56.82246705889702, + 'transform': [array([ 0.00987595, -0.00354858, 0.16486467]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02746304, 0.01158047, -0.92382061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.904748916625977, + 'FR_Wheel_Angle': 14.744349479675293, + 'Location': array([ -0.79945457, -20.56091499, 0.16949962]), + 'Rotation': array([-5.27905300e-02, 4.85644379e+01, -4.04052697e-02]), + 'Velocity': array([-0.13566381, -0.20124105, -0.0003819 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9400634765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -82.65812683, -1702.13024902, 16.78564453]), + 'frame': 13853, + 'frame_number': 13853, + 'framesequence': 13851, + 'gaze_dir': array([ 0.98058069, 0.19538008, -0.01697532]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19538008, -0.01697532]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19538008, -0.01697532]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.82600326091051, + 'timestamp_carla': 56826, + 'timestamp_device': 56462, + 'timestamp_stream': 56.82600326091051, + 'transform': [array([ 0.00987595, -0.00354858, 0.16486467]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02070073, 0.00864513, -1.09417355]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.337552070617676, + 'FR_Wheel_Angle': 15.31835651397705, + 'Location': array([ -0.80607694, -20.57044411, 0.16949898]), + 'Rotation': array([-5.24968319e-02, 4.85084229e+01, -4.04357836e-02]), + 'Velocity': array([-0.12907046, -0.19412191, 0.00056102]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9407958984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -82.26565552, -1701.56884766, 16.78503418]), + 'frame': 13854, + 'frame_number': 13854, + 'framesequence': 13852, + 'gaze_dir': array([ 0.98058069, 0.19546252, -0.01599801]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19546252, -0.01599801]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19546252, -0.01599801]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.8303962610662, + 'timestamp_carla': 56830, + 'timestamp_device': 56467, + 'timestamp_stream': 56.8303962610662, + 'transform': [array([ 0.00987595, -0.00354858, 0.16486467]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00303746, -0.01638659, -1.1740787 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.8079252243042, + 'FR_Wheel_Angle': 15.942160606384277, + 'Location': array([ -0.81242019, -20.57965469, 0.16952182]), + 'Rotation': array([-5.19982278e-02, 4.84530258e+01, -4.04968187e-02]), + 'Velocity': array([-0.1166572 , -0.18471654, 0.00048447]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.941650390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -81.60723877, -1700.63500977, 16.78417969]), + 'frame': 13855, + 'frame_number': 13855, + 'framesequence': 13853, + 'gaze_dir': array([ 0.98058069, 0.19550964, -0.01541187]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19550964, -0.01541187]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19550964, -0.01541187]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.833553459495306, + 'timestamp_carla': 56833, + 'timestamp_device': 56470, + 'timestamp_stream': 56.833553459495306, + 'transform': [array([ 0.00987595, -0.00354858, 0.16486467]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00142403, -0.01788058, -1.11050224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.312795639038086, + 'FR_Wheel_Angle': 16.611303329467773, + 'Location': array([ -0.8178643 , -20.58762741, 0.16953136]), + 'Rotation': array([-5.15747555e-02, 4.84033470e+01, -4.05883752e-02]), + 'Velocity': array([-0.10500553, -0.16912416, 0.00028327]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9422607421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -81.21031189, -1700.07678223, 16.78356934]), + 'frame': 13856, + 'frame_number': 13856, + 'framesequence': 13854, + 'gaze_dir': array([ 0.98058069, 0.19555502, -0.01482485]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19555502, -0.01482485]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19555502, -0.01482485]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.8367303609848, + 'timestamp_carla': 56836, + 'timestamp_device': 56473, + 'timestamp_stream': 56.8367303609848, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16486612]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01370853, 0.01064027, -1.35852396]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.783074378967285, + 'FR_Wheel_Angle': 17.24310874938965, + 'Location': array([ -0.82275623, -20.59482574, 0.16952923]), + 'Rotation': array([-5.11444546e-02, 4.83577652e+01, -4.08935472e-02]), + 'Velocity': array([-1.07387684e-01, -1.66193634e-01, 1.09071727e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.94287109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -80.81117249, -1699.51904297, 16.78295898]), + 'frame': 13857, + 'frame_number': 13857, + 'framesequence': 13855, + 'gaze_dir': array([ 0.98058069, 0.19559859, -0.01423844]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19559859, -0.01423844]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19559859, -0.01423844]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.84017286077142, + 'timestamp_carla': 56840, + 'timestamp_device': 56476, + 'timestamp_stream': 56.84017286077142, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16486612]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.08040723, 0.01483446, -0.96765357]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.222250938415527, + 'FR_Wheel_Angle': 17.815534591674805, + 'Location': array([ -0.82777131, -20.6022625 , 0.16954224]), + 'Rotation': array([-5.16362265e-02, 4.83106918e+01, -4.04968187e-02]), + 'Velocity': array([-0.12198074, -0.19238216, 0.00042306]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9434814453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -80.4108429 , -1698.96313477, 16.78259277]), + 'frame': 13858, + 'frame_number': 13858, + 'framesequence': 13856, + 'gaze_dir': array([ 0.98058069, 0.19565399, -0.01345562]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19565399, -0.01345562]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19565399, -0.01345562]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.84380115941167, + 'timestamp_carla': 56843, + 'timestamp_device': 56480, + 'timestamp_stream': 56.84380115941167, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16486612]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01892566, 0.00287413, -1.25512207]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.639791488647461, + 'FR_Wheel_Angle': 18.391921997070312, + 'Location': array([ -0.83351004, -20.61078835, 0.16956215]), + 'Rotation': array([-5.33710942e-02, 4.82500763e+01, -3.94287072e-02]), + 'Velocity': array([-0.11677276, -0.18851247, 0.00030461]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9443359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -79.87405396, -1698.22302246, 16.78161621]), + 'frame': 13859, + 'frame_number': 13859, + 'framesequence': 13857, + 'gaze_dir': array([ 0.98058069, 0.19569346, -0.01286892]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19569346, -0.01286892]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19569346, -0.01286892]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.84739466011524, + 'timestamp_carla': 56847, + 'timestamp_device': 56483, + 'timestamp_stream': 56.84739466011524, + 'transform': [array([ 0.0098761 , -0.00354858, 0.16486612]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00398593, 0.0168504 , -1.1510582 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.08974838256836, + 'FR_Wheel_Angle': 19.002561569213867, + 'Location': array([ -0.83920234, -20.6192894 , 0.16956531]), + 'Rotation': array([-5.37672453e-02, 4.81908379e+01, -3.94592173e-02]), + 'Velocity': array([-0.11872643, -0.18705614, 0.00028104]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.945068359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -79.46989441, -1697.66992188, 16.78100586]), + 'frame': 13860, + 'frame_number': 13860, + 'framesequence': 13858, + 'gaze_dir': array([ 0.98058069, 0.19574338, -0.01208573]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19574338, -0.01208573]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19574338, -0.01208573]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.850724160671234, + 'timestamp_carla': 56850, + 'timestamp_device': 56487, + 'timestamp_stream': 56.850724160671234, + 'transform': [array([ 0.00987625, -0.00354858, 0.16486722]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0140663 , 0.00158875, -0.986664 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.472881317138672, + 'FR_Wheel_Angle': 19.5257568359375, + 'Location': array([ -0.84551823, -20.62880516, 0.16958034]), + 'Rotation': array([-5.49283773e-02, 4.81213188e+01, -3.85742113e-02]), + 'Velocity': array([-0.12824894, -0.20990199, 0.00029518]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9456787109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -78.92784119, -1696.93371582, 16.78039551]), + 'frame': 13861, + 'frame_number': 13861, + 'framesequence': 13859, + 'gaze_dir': array([ 0.98058069, 0.19577874, -0.01149877]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19577874, -0.01149877]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19577874, -0.01149877]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.85388195887208, + 'timestamp_carla': 56853, + 'timestamp_device': 56490, + 'timestamp_stream': 56.85388195887208, + 'transform': [array([ 0.00987625, -0.00354858, 0.16486722]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01661635, -0.00447092, -1.81107986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.853303909301758, + 'FR_Wheel_Angle': 20.05565071105957, + 'Location': array([ -0.85164684, -20.63814354, 0.16958934]), + 'Rotation': array([-5.44434339e-02, 4.80537643e+01, -3.88488732e-02]), + 'Velocity': array([-0.11582972, -0.19190913, 0.00042907]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9466552734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -78.51986694, -1696.38354492, 16.77954102]), + 'frame': 13862, + 'frame_number': 13862, + 'framesequence': 13860, + 'gaze_dir': array([ 0.98058069, 0.19582319, -0.01071525]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19582319, -0.01071525]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19582319, -0.01071525]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.857489459216595, + 'timestamp_carla': 56857, + 'timestamp_device': 56494, + 'timestamp_stream': 56.857489459216595, + 'transform': [array([ 0.00987625, -0.00354858, 0.16486722]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02073974, 0.00663425, -1.15037906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.282827377319336, + 'FR_Wheel_Angle': 20.665185928344727, + 'Location': array([ -0.85779601, -20.64757347, 0.16958953]), + 'Rotation': array([-5.45936972e-02, 4.79890251e+01, -3.87267955e-02]), + 'Velocity': array([-0.1305605 , -0.21352127, 0.00053089]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.947265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -77.97268677, -1695.65112305, 16.77893066]), + 'frame': 13863, + 'frame_number': 13863, + 'framesequence': 13861, + 'gaze_dir': array([ 0.98058069, 0.19585443, -0.01012805]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19585443, -0.01012805]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19585443, -0.01012805]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.86100045964122, + 'timestamp_carla': 56861, + 'timestamp_device': 56497, + 'timestamp_stream': 56.86100045964122, + 'transform': [array([ 0.00987625, -0.00354858, 0.16486722]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01774218, -0.00713147, -0.96930742]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.806316375732422, + 'FR_Wheel_Angle': 21.393352508544922, + 'Location': array([ -0.86377645, -20.65675163, 0.16959789]), + 'Rotation': array([-5.43819629e-02, 4.79187660e+01, -3.87573205e-02]), + 'Velocity': array([-0.11588136, -0.19543619, 0.00020667]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.947998046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -77.56082153, -1695.10375977, 16.77819824]), + 'frame': 13864, + 'frame_number': 13864, + 'framesequence': 13862, + 'gaze_dir': array([ 0.98058069, 0.19588396, -0.00954002]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19588396, -0.00954002]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19588396, -0.00954002]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.86419026181102, + 'timestamp_carla': 56864, + 'timestamp_device': 56500, + 'timestamp_stream': 56.86419026181102, + 'transform': [array([ 0.0098764 , -0.00354858, 0.16486832]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02206795, -0.00479022, -1.85998273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.27936363220215, + 'FR_Wheel_Angle': 22.077789306640625, + 'Location': array([ -0.8694675 , -20.6656189 , 0.16960526]), + 'Rotation': array([-5.36784530e-02, 4.78477783e+01, -3.90624925e-02]), + 'Velocity': array([-0.10794542, -0.1843012 , 0.00026631]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9486083984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -77.14677429, -1694.55688477, 16.77758789]), + 'frame': 13865, + 'frame_number': 13865, + 'framesequence': 13863, + 'gaze_dir': array([ 0.98058069, 0.19592054, -0.00875684]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19592054, -0.00875684]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19592054, -0.00875684]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.86743376031518, + 'timestamp_carla': 56867, + 'timestamp_device': 56504, + 'timestamp_stream': 56.86743376031518, + 'transform': [array([ 0.0098764 , -0.00354858, 0.16486832]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01900661, -0.00579896, -0.93120724]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.70751190185547, + 'FR_Wheel_Angle': 22.68670654296875, + 'Location': array([ -0.87462354, -20.67376328, 0.16960846]), + 'Rotation': array([-5.27905300e-02, 4.77831078e+01, -3.94897424e-02]), + 'Velocity': array([-9.84269157e-02, -1.70828626e-01, 1.66633123e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.949462890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -76.59288025, -1693.83068848, 16.77685547]), + 'frame': 13866, + 'frame_number': 13866, + 'framesequence': 13864, + 'gaze_dir': array([ 0.98058069, 0.19594593, -0.00816862]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19594593, -0.00816862]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19594593, -0.00816862]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.87096866220236, + 'timestamp_carla': 56871, + 'timestamp_device': 56507, + 'timestamp_stream': 56.87096866220236, + 'transform': [array([ 0.0098764 , -0.00354858, 0.16486832]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0322991 , -0.01633533, -1.6701268 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.102365493774414, + 'FR_Wheel_Angle': 23.26067352294922, + 'Location': array([ -0.87942803, -20.68136406, 0.16960926]), + 'Rotation': array([-5.24968319e-02, 4.77168999e+01, -3.94897424e-02]), + 'Velocity': array([-0.1006161 , -0.17980139, 0.00019827]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9500732421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -76.17498779, -1693.28674316, 16.77624512]), + 'frame': 13867, + 'frame_number': 13867, + 'framesequence': 13865, + 'gaze_dir': array([ 0.98058069, 0.19597703, -0.0073852 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19597703, -0.0073852 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19597703, -0.0073852 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.87448466196656, + 'timestamp_carla': 56874, + 'timestamp_device': 56511, + 'timestamp_stream': 56.87448466196656, + 'transform': [array([ 0.0098764 , -0.00354858, 0.16486832]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01674535, -0.01783895, -1.56839144]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.54722785949707, + 'FR_Wheel_Angle': 23.903501510620117, + 'Location': array([ -0.88411927, -20.68884277, 0.16961741]), + 'Rotation': array([-5.26744165e-02, 4.76500931e+01, -3.91540453e-02]), + 'Velocity': array([-0.0950845 , -0.17403536, 0.00024768]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9508056640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -75.61601257, -1692.56445312, 16.7755127 ]), + 'frame': 13868, + 'frame_number': 13868, + 'framesequence': 13866, + 'gaze_dir': array([ 0.98058069, 0.19601151, -0.00640502]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19601151, -0.00640502]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19601151, -0.00640502]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.87987196072936, + 'timestamp_carla': 56879, + 'timestamp_device': 56516, + 'timestamp_stream': 56.87987196072936, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02081638, 0.01570455, -1.22027683]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.961652755737305, + 'FR_Wheel_Angle': 24.511192321777344, + 'Location': array([ -0.8888762 , -20.69651985, 0.16962093]), + 'Rotation': array([-5.23670577e-02, 4.75826607e+01, -3.94897424e-02]), + 'Velocity': array([-0.09192743, -0.15908591, 0.00025272]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9520263671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -74.91271973, -1691.66394043, 16.77441406]), + 'frame': 13869, + 'frame_number': 13869, + 'framesequence': 13867, + 'gaze_dir': array([ 0.98058069, 0.19602983, -0.00581728]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19602983, -0.00581728]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19602983, -0.00581728]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.88301946222782, + 'timestamp_carla': 56883, + 'timestamp_device': 56519, + 'timestamp_stream': 56.88301946222782, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.09261214e-02, -1.72745742e-04, -1.32335651e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.370651245117188, + 'FR_Wheel_Angle': 25.11436653137207, + 'Location': array([ -0.89403099, -20.70480919, 0.16963145]), + 'Rotation': array([-5.37399240e-02, 4.75051880e+01, -3.82995605e-02]), + 'Velocity': array([-0.10722898, -0.19305353, 0.00028322]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9521484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -74.48880005, -1691.12585449, 16.77380371]), + 'frame': 13870, + 'frame_number': 13870, + 'framesequence': 13868, + 'gaze_dir': array([ 0.98058069, 0.19605154, -0.0050328 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19605154, -0.0050328 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19605154, -0.0050328 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.886765759438276, + 'timestamp_carla': 56886, + 'timestamp_device': 56523, + 'timestamp_stream': 56.886765759438276, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 2.29845638e-03, -4.30270622e-04, -1.12131274e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.779855728149414, + 'FR_Wheel_Angle': 25.720712661743164, + 'Location': array([ -0.8991493 , -20.7131691 , 0.16963935]), + 'Rotation': array([-5.40472828e-02, 4.74296074e+01, -3.81164476e-02]), + 'Velocity': array([-1.02019921e-01, -1.85840487e-01, 2.32458115e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -73.92068481, -1690.4095459 , 16.77282715]), + 'frame': 13871, + 'frame_number': 13871, + 'framesequence': 13869, + 'gaze_dir': array([ 0.98058069, 0.19607012, -0.00424823]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19607012, -0.00424823]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19607012, -0.00424823]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.890444561839104, + 'timestamp_carla': 56890, + 'timestamp_device': 56527, + 'timestamp_stream': 56.890444561839104, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03488973, -0.02439034, -2.09254479]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.21337127685547, + 'FR_Wheel_Angle': 26.37731170654297, + 'Location': array([ -0.90500891, -20.72278214, 0.16964664]), + 'Rotation': array([-5.49283773e-02, 4.73414116e+01, -3.72619629e-02]), + 'Velocity': array([-1.10584535e-01, -2.11210966e-01, 1.84192657e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.953857421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -73.34967041, -1689.69555664, 16.77209473]), + 'frame': 13872, + 'frame_number': 13872, + 'framesequence': 13870, + 'gaze_dir': array([ 0.98058069, 0.19608553, -0.00346435]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19608553, -0.00346435]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19608553, -0.00346435]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.894353460520506, + 'timestamp_carla': 56894, + 'timestamp_device': 56531, + 'timestamp_stream': 56.894353460520506, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.50939655e-02, 2.05353182e-03, -2.10849261e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.59774398803711, + 'FR_Wheel_Angle': 26.974334716796875, + 'Location': array([ -0.91069156, -20.7321167 , 0.16965938]), + 'Rotation': array([-5.53245284e-02, 4.72499886e+01, -3.69262658e-02]), + 'Velocity': array([-0.1207772 , -0.22158122, 0.00044166]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9547119140625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -72.77635193, -1688.98461914, 16.77124023]), + 'frame': 13873, + 'frame_number': 13873, + 'framesequence': 13871, + 'gaze_dir': array([ 0.98058069, 0.19609503, -0.00287566]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19609503, -0.00287566]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19609503, -0.00287566]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.89791176095605, + 'timestamp_carla': 56897, + 'timestamp_device': 56534, + 'timestamp_stream': 56.89791176095605, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.84739176e-02, 1.63263257e-03, -2.00339675e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.019174575805664, + 'FR_Wheel_Angle': 27.59012794494629, + 'Location': array([ -0.91632724, -20.74146843, 0.16966812]), + 'Rotation': array([-5.51469438e-02, 4.71579018e+01, -3.70483361e-02]), + 'Velocity': array([-0.1142189 , -0.21198022, 0.00031509]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9554443359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -72.34397888, -1688.45214844, 16.77050781]), + 'frame': 13874, + 'frame_number': 13874, + 'framesequence': 13872, + 'gaze_dir': array([ 0.98058069, 0.19610278, -0.00228768]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19610278, -0.00228768]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19610278, -0.00228768]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.90121316164732, + 'timestamp_carla': 56901, + 'timestamp_device': 56537, + 'timestamp_stream': 56.90121316164732, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.05546838, -0.00873779, -2.31191683]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.515840530395508, + 'FR_Wheel_Angle': 28.362802505493164, + 'Location': array([ -0.92217654, -20.75128365, 0.16966766]), + 'Rotation': array([-5.47234714e-02, 4.70604591e+01, -3.71398851e-02]), + 'Velocity': array([-0.12550882, -0.23582406, 0.00037274]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.955810546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -71.91047668, -1687.92163086, 16.7701416 ]), + 'frame': 13875, + 'frame_number': 13875, + 'framesequence': 13873, + 'gaze_dir': array([ 0.98058069, 0.19610876, -0.00169969]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19610876, -0.00169969]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19610876, -0.00169969]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.904251761734486, + 'timestamp_carla': 56904, + 'timestamp_device': 56540, + 'timestamp_stream': 56.904251761734486, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03538783, 0.02306822, -2.06565666]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.03744125366211, + 'FR_Wheel_Angle': 29.161746978759766, + 'Location': array([ -0.92834473, -20.7618084 , 0.16967781]), + 'Rotation': array([-5.50513230e-02, 4.69523468e+01, -3.64990197e-02]), + 'Velocity': array([-0.11935422, -0.22220853, 0.00038193]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9566650390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -71.47549438, -1687.39257812, 16.76928711]), + 'frame': 13876, + 'frame_number': 13876, + 'framesequence': 13874, + 'gaze_dir': array([ 9.80580688e-01, 1.96113989e-01, -9.14923847e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, 1.96113989e-01, -9.14923847e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, 1.96113989e-01, -9.14923847e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.90777286142111, + 'timestamp_carla': 56907, + 'timestamp_device': 56544, + 'timestamp_stream': 56.90777286142111, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02797961, 0.01600295, -2.14811349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.485023498535156, + 'FR_Wheel_Angle': 29.849714279174805, + 'Location': array([ -0.93388075, -20.77127075, 0.16968659]), + 'Rotation': array([-5.45322262e-02, 4.68525314e+01, -3.69873010e-02]), + 'Velocity': array([-0.11684293, -0.22022262, 0.0004326 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9573974609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -70.89242554, -1686.68835449, 16.76855469]), + 'frame': 13877, + 'frame_number': 13877, + 'framesequence': 13875, + 'gaze_dir': array([9.80580688e-01, 1.96116120e-01, 6.58629506e-05]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([9.80580688e-01, 1.96116120e-01, 6.58629506e-05]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([9.80580688e-01, 1.96116120e-01, 6.58629506e-05]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.91172305867076, + 'timestamp_carla': 56911, + 'timestamp_device': 56549, + 'timestamp_stream': 56.91172305867076, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02635306, 0.01847573, -2.1340189 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.941808700561523, + 'FR_Wheel_Angle': 30.578041076660156, + 'Location': array([ -0.93959194, -20.78108406, 0.16969211]), + 'Rotation': array([-5.41702285e-02, 4.67477798e+01, -3.71704064e-02]), + 'Velocity': array([-0.11649123, -0.22021262, 0.00024448]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.95849609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -70.15977478, -1685.81152344, 16.76745605]), + 'frame': 13878, + 'frame_number': 13878, + 'framesequence': 13876, + 'gaze_dir': array([9.80580688e-01, 1.96115047e-01, 6.53886935e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([9.80580688e-01, 1.96115047e-01, 6.53886935e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([9.80580688e-01, 1.96115047e-01, 6.53886935e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.91613046079874, + 'timestamp_carla': 56916, + 'timestamp_device': 56552, + 'timestamp_stream': 56.91613046079874, + 'transform': [array([ 0.00987671, -0.00354858, 0.16486204]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.04674686, 0.02749884, -2.08914471]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.50425148010254, + 'FR_Wheel_Angle': 31.465118408203125, + 'Location': array([ -0.9453932 , -20.79117203, 0.16969302]), + 'Rotation': array([-5.37672453e-02, 4.66366463e+01, -3.73535082e-02]), + 'Velocity': array([-1.11647636e-01, -2.11972028e-01, -6.68478024e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.958984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -69.71839905, -1685.28771973, 16.76708984]), + 'frame': 13879, + 'frame_number': 13879, + 'framesequence': 13877, + 'gaze_dir': array([0.98058069, 0.19611084, 0.00143866]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19611084, 0.00143866]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19611084, 0.00143866]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.91972906142473, + 'timestamp_carla': 56919, + 'timestamp_device': 56556, + 'timestamp_stream': 56.91972906142473, + 'transform': [array([ 0.00987671, -0.00354858, 0.16486204]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03918656, 0.02833404, -2.14878035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.05507469177246, + 'FR_Wheel_Angle': 32.374237060546875, + 'Location': array([ -0.95083237, -20.8007679 , 0.16969962]), + 'Rotation': array([-5.35555109e-02, 4.65273209e+01, -3.72619592e-02]), + 'Velocity': array([-1.10443570e-01, -2.13437080e-01, 3.19194769e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9598388671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -69.12690735, -1684.59057617, 16.76611328]), + 'frame': 13880, + 'frame_number': 13880, + 'framesequence': 13878, + 'gaze_dir': array([0.98058069, 0.19610353, 0.00222266]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19610353, 0.00222266]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19610353, 0.00222266]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.92393945902586, + 'timestamp_carla': 56923, + 'timestamp_device': 56560, + 'timestamp_stream': 56.92393945902586, + 'transform': [array([ 0.00987671, -0.00354858, 0.16486204]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01389128, 0.02503844, -2.37581348]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.62894630432129, + 'FR_Wheel_Angle': 33.25138854980469, + 'Location': array([ -0.95686311, -20.81144333, 0.16970593]), + 'Rotation': array([-5.39926440e-02, 4.64035187e+01, -3.67126428e-02]), + 'Velocity': array([-1.18090376e-01, -2.30411351e-01, 1.29013060e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9608154296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -68.53326416, -1683.89648438, 16.76513672]), + 'frame': 13881, + 'frame_number': 13881, + 'framesequence': 13879, + 'gaze_dir': array([0.98058069, 0.19609305, 0.00300737]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19609305, 0.00300737]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19609305, 0.00300737]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.928045962005854, + 'timestamp_carla': 56928, + 'timestamp_device': 56564, + 'timestamp_stream': 56.928045962005854, + 'transform': [array([ 0.00987671, -0.00354858, 0.16486204]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.08414507, -0.01963077, -3.10432911]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.187108993530273, + 'FR_Wheel_Angle': 34.1383171081543, + 'Location': array([ -0.96353978, -20.8233757 , 0.1697208 ]), + 'Rotation': array([-5.47439642e-02, 4.62636223e+01, -3.55834924e-02]), + 'Velocity': array([-0.13185319, -0.27352607, 0.00035201]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.961669921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -67.93621826, -1683.20410156, 16.76428223]), + 'frame': 13882, + 'frame_number': 13882, + 'framesequence': 13880, + 'gaze_dir': array([0.98058069, 0.19607557, 0.003988 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19607557, 0.003988 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19607557, 0.003988 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.93233796209097, + 'timestamp_carla': 56932, + 'timestamp_device': 56569, + 'timestamp_stream': 56.93233796209097, + 'transform': [array([ 0.00987671, -0.00354858, 0.16486204]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.08143927, -0.01898407, -3.76838255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.659637451171875, + 'FR_Wheel_Angle': 34.86261749267578, + 'Location': array([ -0.97006232, -20.83509445, 0.16973926]), + 'Rotation': array([-5.58436252e-02, 4.61206131e+01, -3.41186523e-02]), + 'Velocity': array([-0.14197247, -0.29815891, 0.00042556]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.962646484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -67.18615723, -1682.34216309, 16.76330566]), + 'frame': 13883, + 'frame_number': 13883, + 'framesequence': 13881, + 'gaze_dir': array([0.98058069, 0.19605806, 0.00477184]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19605806, 0.00477184]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19605806, 0.00477184]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.93661976233125, + 'timestamp_carla': 56936, + 'timestamp_device': 56573, + 'timestamp_stream': 56.93661976233125, + 'transform': [array([ 0.00987656, -0.00354858, 0.16486079]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02103599, 0.02328417, -3.44487858]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.15806007385254, + 'FR_Wheel_Angle': 35.72133255004883, + 'Location': array([ -0.97787982, -20.84921074, 0.16975963]), + 'Rotation': array([-5.71276993e-02, 4.59453621e+01, -3.26538049e-02]), + 'Velocity': array([-1.47960633e-01, -3.04952949e-01, 2.23746290e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9635009765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -66.58349609, -1681.65576172, 16.76257324]), + 'frame': 13884, + 'frame_number': 13884, + 'framesequence': 13882, + 'gaze_dir': array([0.98058069, 0.19603175, 0.00575227]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19603175, 0.00575227]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19603175, 0.00575227]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.94182335957885, + 'timestamp_carla': 56941, + 'timestamp_device': 56578, + 'timestamp_stream': 56.94182335957885, + 'transform': [array([ 0.00987671, -0.00354858, 0.16485707]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.18749465e-03, -2.70786136e-02, -3.90136075e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.632394790649414, + 'FR_Wheel_Angle': 36.44986343383789, + 'Location': array([ -0.98518687, -20.8626442 , 0.16976376]), + 'Rotation': array([-5.66700771e-02, 4.57633781e+01, -3.29894982e-02]), + 'Velocity': array([-0.13766523, -0.30799517, 0.00036218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9642333984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -65.82571411, -1680.80065918, 16.76171875]), + 'frame': 13885, + 'frame_number': 13885, + 'framesequence': 13883, + 'gaze_dir': array([0.98058069, 0.19600053, 0.00673257]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19600053, 0.00673257]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19600053, 0.00673257]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.94648015871644, + 'timestamp_carla': 56946, + 'timestamp_device': 56583, + 'timestamp_stream': 56.94648015871644, + 'transform': [array([ 0.00987656, -0.00354858, 0.16485514]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.66299227e-03, -2.40445118e-02, -4.03789282e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.137907028198242, + 'FR_Wheel_Angle': 37.324283599853516, + 'Location': array([ -0.99282575, -20.87687683, 0.16977054]), + 'Rotation': array([-5.60963415e-02, 4.55920486e+01, -3.32641602e-02]), + 'Velocity': array([-0.13843969, -0.31248197, 0.00033082]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.965087890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -65.06367493, -1679.94934082, 16.76049805]), + 'frame': 13886, + 'frame_number': 13886, + 'framesequence': 13884, + 'gaze_dir': array([0.98058069, 0.19596444, 0.00771194]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19596444, 0.00771194]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19596444, 0.00771194]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.951297361403704, + 'timestamp_carla': 56951, + 'timestamp_device': 56588, + 'timestamp_stream': 56.951297361403704, + 'transform': [array([ 0.00987671, -0.00354858, 0.16485333]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02299399, -0.0388446 , -4.20496798]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.65174102783203, + 'FR_Wheel_Angle': 38.16571044921875, + 'Location': array([ -1.00017488, -20.89067268, 0.16977359]), + 'Rotation': array([-5.55430949e-02, 4.54111938e+01, -3.36608887e-02]), + 'Velocity': array([-1.36816740e-01, -3.17390651e-01, -2.13541978e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9658203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -64.29795837, -1679.10253906, 16.75952148]), + 'frame': 13887, + 'frame_number': 13887, + 'framesequence': 13885, + 'gaze_dir': array([0.98058069, 0.19593199, 0.00849605]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19593199, 0.00849605]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19593199, 0.00849605]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.95601665973663, + 'timestamp_carla': 56956, + 'timestamp_device': 56592, + 'timestamp_stream': 56.95601665973663, + 'transform': [array([ 0.00987656, -0.00354858, 0.16485147]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01734425, -0.02365882, -4.26793766]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.129417419433594, + 'FR_Wheel_Angle': 38.96295166015625, + 'Location': array([ -1.00732028, -20.90422249, 0.16978206]), + 'Rotation': array([-5.51742651e-02, 4.52289963e+01, -3.37524377e-02]), + 'Velocity': array([-0.13974847, -0.32235679, 0.00033377]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9666748046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -63.68173218, -1678.42712402, 16.75854492]), + 'frame': 13888, + 'frame_number': 13888, + 'framesequence': 13886, + 'gaze_dir': array([0.98058069, 0.19587748, 0.00967159]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19587748, 0.00967159]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19587748, 0.00967159]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.96111265942454, + 'timestamp_carla': 56961, + 'timestamp_device': 56598, + 'timestamp_stream': 56.96111265942454, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.05936923, -0.03476631, -4.74003792]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.632217407226562, + 'FR_Wheel_Angle': 39.79807662963867, + 'Location': array([ -1.01519489, -20.91914558, 0.16979203]), + 'Rotation': array([-5.55430949e-02, 4.50253105e+01, -3.30810510e-02]), + 'Velocity': array([-1.50620461e-01, -3.49882662e-01, 2.35335829e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9676513671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -62.75265503, -1677.41906738, 16.75732422]), + 'frame': 13889, + 'frame_number': 13889, + 'framesequence': 13887, + 'gaze_dir': array([0.98058069, 0.19583726, 0.01045459]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19583726, 0.01045459]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19583726, 0.01045459]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.96564856171608, + 'timestamp_carla': 56965, + 'timestamp_device': 56602, + 'timestamp_stream': 56.96564856171608, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0464554 , -0.03087728, -5.04588747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.09378433227539, + 'FR_Wheel_Angle': 40.56816101074219, + 'Location': array([ -1.02314997, -20.93432617, 0.16980854]), + 'Rotation': array([-5.61509803e-02, 4.48127365e+01, -3.19824144e-02]), + 'Velocity': array([-0.15643089, -0.36736175, 0.00039854]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.96826171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -62.13031006, -1676.75048828, 16.7565918 ]), + 'frame': 13890, + 'frame_number': 13890, + 'framesequence': 13888, + 'gaze_dir': array([0.98058069, 0.19578254, 0.01143385]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19578254, 0.01143385]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19578254, 0.01143385]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.97022366151214, + 'timestamp_carla': 56970, + 'timestamp_device': 56607, + 'timestamp_stream': 56.97022366151214, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.96820638e-02, 5.52178733e-03, -5.68934584e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.59272003173828, + 'FR_Wheel_Angle': 41.40908432006836, + 'Location': array([ -1.03203595, -20.95135498, 0.16982147]), + 'Rotation': array([-5.70662282e-02, 4.45673256e+01, -3.05175763e-02]), + 'Velocity': array([-0.18285905, -0.4097431 , 0.00053828]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9693603515625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -61.34809875, -1675.91760254, 16.75549316]), + 'frame': 13891, + 'frame_number': 13891, + 'framesequence': 13889, + 'gaze_dir': array([0.98058069, 0.19573522, 0.0122172 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19573522, 0.0122172 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19573522, 0.0122172 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.97457145899534, + 'timestamp_carla': 56974, + 'timestamp_device': 56611, + 'timestamp_stream': 56.97457145899534, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.05636895, -0.02708833, -6.22225285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.786252975463867, + 'FR_Wheel_Angle': 41.66433334350586, + 'Location': array([ -1.04182267, -20.9702282 , 0.16984725]), + 'Rotation': array([-5.83503023e-02, 4.42908363e+01, -2.84728985e-02]), + 'Velocity': array([-1.86031818e-01, -4.40248013e-01, 4.00042511e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.97021484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -60.71917725, -1675.25402832, 16.75463867]), + 'frame': 13892, + 'frame_number': 13892, + 'framesequence': 13890, + 'gaze_dir': array([0.98058069, 0.19568481, 0.01299961]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19568481, 0.01299961]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19568481, 0.01299961]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.97879835963249, + 'timestamp_carla': 56978, + 'timestamp_device': 56615, + 'timestamp_stream': 56.97879835963249, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0101065 , 0.02548117, -6.07788801]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.775772094726562, + 'FR_Wheel_Angle': 41.649044036865234, + 'Location': array([ -1.05193973, -20.98965836, 0.16986667]), + 'Rotation': array([-5.88693954e-02, 4.40071678e+01, -2.81066913e-02]), + 'Velocity': array([-2.03586683e-01, -4.57061142e-01, 2.60972971e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.970947265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -60.08822632, -1674.59362793, 16.75390625]), + 'frame': 13893, + 'frame_number': 13893, + 'framesequence': 13891, + 'gaze_dir': array([0.98058069, 0.19563121, 0.01378256]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19563121, 0.01378256]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19563121, 0.01378256]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.98311195895076, + 'timestamp_carla': 56983, + 'timestamp_device': 56619, + 'timestamp_stream': 56.98311195895076, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0172869 , -0.01819469, -6.79336548]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.768129348754883, + 'FR_Wheel_Angle': 41.633968353271484, + 'Location': array([ -1.06272876, -21.01019287, 0.16988236]), + 'Rotation': array([-5.91084547e-02, 4.37053413e+01, -2.81066876e-02]), + 'Velocity': array([-2.07194299e-01, -4.79407400e-01, 3.74612806e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.971923828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -59.45404053, -1673.93518066, 16.75292969]), + 'frame': 13894, + 'frame_number': 13894, + 'framesequence': 13892, + 'gaze_dir': array([0.98058069, 0.19555983, 0.01476075]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19555983, 0.01476075]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19555983, 0.01476075]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.98765965923667, + 'timestamp_carla': 56987, + 'timestamp_device': 56624, + 'timestamp_stream': 56.98765965923667, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.04810727, 0.03219746, -6.5522871 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76233673095703, + 'FR_Wheel_Angle': 41.625274658203125, + 'Location': array([ -1.07425606, -21.03181839, 0.16989493]), + 'Rotation': array([-5.90538122e-02, 4.33881264e+01, -2.86865253e-02]), + 'Velocity': array([-2.22426653e-01, -4.86290663e-01, 2.55672931e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.972900390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -58.65771484, -1673.11572266, 16.75195312]), + 'frame': 13895, + 'frame_number': 13895, + 'framesequence': 13893, + 'gaze_dir': array([0.98058069, 0.19548362, 0.01573782]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19548362, 0.01573782]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19548362, 0.01573782]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.9927703589201, + 'timestamp_carla': 56992, + 'timestamp_device': 56629, + 'timestamp_stream': 56.9927703589201, + 'transform': [array([ 0.00987656, -0.00354858, 0.16484629]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03971872, 0.02666947, -6.77620506]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.755544662475586, + 'FR_Wheel_Angle': 41.61611557006836, + 'Location': array([ -1.08525789, -21.05224037, 0.16990581]), + 'Rotation': array([-5.86849824e-02, 4.30870819e+01, -2.93273907e-02]), + 'Velocity': array([-2.30642736e-01, -4.98699397e-01, 3.63628846e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9742431640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -57.85800171, -1672.30090332, 16.75061035]), + 'frame': 13896, + 'frame_number': 13896, + 'framesequence': 13894, + 'gaze_dir': array([0.98058069, 0.19541909, 0.01651995]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19541909, 0.01651995]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19541909, 0.01651995]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 56.99656106159091, + 'timestamp_carla': 56996, + 'timestamp_device': 56633, + 'timestamp_stream': 56.99656106159091, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484778]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.05730456, 0.03836624, -6.86899948]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.750675201416016, + 'FR_Wheel_Angle': 41.60944366455078, + 'Location': array([ -1.09757721, -21.07488441, 0.16990916]), + 'Rotation': array([-5.83503023e-02, 4.27506638e+01, -2.97851562e-02]), + 'Velocity': array([-2.39012599e-01, -5.07453442e-01, 2.26750373e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9747314453125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -57.21461487, -1671.65136719, 16.74987793]), + 'frame': 13897, + 'frame_number': 13897, + 'framesequence': 13895, + 'gaze_dir': array([0.98058069, 0.19535148, 0.01730106]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19535148, 0.01730106]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19535148, 0.01730106]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.00055116042495, + 'timestamp_carla': 57000, + 'timestamp_device': 56637, + 'timestamp_stream': 57.00055116042495, + 'transform': [array([ 0.00987671, -0.00354858, 0.16484778]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.07221161, 0.03467055, -6.77912235]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754751205444336, + 'FR_Wheel_Angle': 41.61219024658203, + 'Location': array([ -1.11026299, -21.09788132, 0.16991821]), + 'Rotation': array([-5.73462658e-02, 4.24084663e+01, -3.13110314e-02]), + 'Velocity': array([-2.38267899e-01, -4.99807775e-01, 3.64048465e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.975830078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -56.56929016, -1671.00488281, 16.74890137]), + 'frame': 13898, + 'frame_number': 13898, + 'framesequence': 13896, + 'gaze_dir': array([0.98058069, 0.19528069, 0.01808264]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19528069, 0.01808264]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19528069, 0.01808264]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.00437096133828, + 'timestamp_carla': 57004, + 'timestamp_device': 56641, + 'timestamp_stream': 57.00437096133828, + 'transform': [array([ 0.00987686, -0.00354858, 0.1648491 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01050936, -0.02541506, -7.37986088]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.750446319580078, + 'FR_Wheel_Angle': 41.603729248046875, + 'Location': array([ -1.12154043, -21.11805344, 0.16993237]), + 'Rotation': array([-5.67315482e-02, 4.21065292e+01, -3.20129395e-02]), + 'Velocity': array([-2.37851426e-01, -5.13092637e-01, 3.18956358e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9766845703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -55.92077637, -1670.3605957 , 16.74816895]), + 'frame': 13899, + 'frame_number': 13899, + 'framesequence': 13897, + 'gaze_dir': array([0.98058069, 0.19520676, 0.01886393]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19520676, 0.01886393]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19520676, 0.01886393]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.008414659649134, + 'timestamp_carla': 57008, + 'timestamp_device': 56645, + 'timestamp_stream': 57.008414659649134, + 'transform': [array([ 0.00987686, -0.00354858, 0.1648491 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00979172, 0.01712251, -7.24262953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.740415573120117, + 'FR_Wheel_Angle': 41.58754348754883, + 'Location': array([ -1.13493228, -21.14157677, 0.16995364]), + 'Rotation': array([-5.66700771e-02, 4.17563744e+01, -3.21350060e-02]), + 'Velocity': array([-0.25816062, -0.52598041, 0.0005934 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.977783203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -55.26968384, -1669.71875 , 16.74719238]), + 'frame': 13900, + 'frame_number': 13900, + 'framesequence': 13898, + 'gaze_dir': array([0.98058069, 0.19514933, 0.01944915]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19514933, 0.01944915]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19514933, 0.01944915]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.01214746013284, + 'timestamp_carla': 57012, + 'timestamp_device': 56648, + 'timestamp_stream': 57.01214746013284, + 'transform': [array([ 0.00987701, -0.00354858, 0.16485047]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03509755, 0.03474233, -7.39435816]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73271369934082, + 'FR_Wheel_Angle': 41.57503128051758, + 'Location': array([ -1.14855731, -21.16523552, 0.16996315]), + 'Rotation': array([-5.70389070e-02, 4.14011688e+01, -3.11584435e-02]), + 'Velocity': array([-0.2702648 , -0.54031503, 0.00064992]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9783935546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -54.78015137, -1669.23950195, 16.74658203]), + 'frame': 13901, + 'frame_number': 13901, + 'framesequence': 13899, + 'gaze_dir': array([0.98058069, 0.19506994, 0.0202299 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19506994, 0.0202299 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19506994, 0.0202299 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.015767361968756, + 'timestamp_carla': 57015, + 'timestamp_device': 56652, + 'timestamp_stream': 57.015767361968756, + 'transform': [array([ 0.00987701, -0.00354858, 0.16485047]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02075057, -0.01397103, -8.12683392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.724742889404297, + 'FR_Wheel_Angle': 41.56281661987305, + 'Location': array([ -1.16302097, -21.18994904, 0.16999088]), + 'Rotation': array([-5.73462658e-02, 4.10290718e+01, -3.09143048e-02]), + 'Velocity': array([-2.76217878e-01, -5.62812328e-01, 4.67298029e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9796142578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -54.12460327, -1668.60217285, 16.74560547]), + 'frame': 13902, + 'frame_number': 13902, + 'framesequence': 13900, + 'gaze_dir': array([0.98058069, 0.19496641, 0.02120446]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19496641, 0.02120446]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19496641, 0.02120446]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.020426359027624, + 'timestamp_carla': 57020, + 'timestamp_device': 56657, + 'timestamp_stream': 57.020426359027624, + 'transform': [array([ 0.00987701, -0.00354858, 0.16485047]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01586601, 0.02469002, -7.90674591]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72089195251465, + 'FR_Wheel_Angle': 41.55352020263672, + 'Location': array([ -1.17841375, -21.2158165 , 0.17000785]), + 'Rotation': array([-5.72233200e-02, 4.06382179e+01, -3.17382850e-02]), + 'Velocity': array([-2.91522354e-01, -5.67197382e-01, 5.04860887e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9805908203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -53.30232239, -1667.81005859, 16.74462891]), + 'frame': 13903, + 'frame_number': 13903, + 'framesequence': 13901, + 'gaze_dir': array([0.98058069, 0.19490188, 0.02178968]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19490188, 0.02178968]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19490188, 0.02178968]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.023810759186745, + 'timestamp_carla': 57023, + 'timestamp_device': 56660, + 'timestamp_stream': 57.023810759186745, + 'transform': [array([ 0.00987686, -0.00354858, 0.1648517 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 5.09329329e-05, -1.42456694e-02, -8.31783581e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.721277236938477, + 'FR_Wheel_Angle': 41.557395935058594, + 'Location': array([ -1.19240022, -21.23904991, 0.17001724]), + 'Rotation': array([-5.71003780e-02, 4.02831917e+01, -3.22265625e-02]), + 'Velocity': array([-2.86358923e-01, -5.67788303e-01, 1.67875289e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.981201171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -52.80645752, -1667.33618164, 16.74414062]), + 'frame': 13904, + 'frame_number': 13904, + 'framesequence': 13902, + 'gaze_dir': array([0.98058069, 0.19483568, 0.02237397]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19483568, 0.02237397]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19483568, 0.02237397]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.02711546048522, + 'timestamp_carla': 57027, + 'timestamp_device': 56663, + 'timestamp_stream': 57.02711546048522, + 'transform': [array([ 0.00987701, -0.00354858, 0.16485345]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.07240389, 0.03361754, -7.60876179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.728458404541016, + 'FR_Wheel_Angle': 41.5701789855957, + 'Location': array([ -1.20741713, -21.26363945, 0.1700169 ]), + 'Rotation': array([-5.60348704e-02, 3.99078140e+01, -3.43017541e-02]), + 'Velocity': array([-2.88065642e-01, -5.43322623e-01, 4.09314613e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.98193359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -52.30979919, -1666.86437988, 16.74353027]), + 'frame': 13905, + 'frame_number': 13905, + 'framesequence': 13903, + 'gaze_dir': array([0.98058069, 0.19474459, 0.02315345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19474459, 0.02315345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19474459, 0.02315345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.03072455897927, + 'timestamp_carla': 57030, + 'timestamp_device': 56667, + 'timestamp_stream': 57.03072455897927, + 'transform': [array([ 0.00987701, -0.00354858, 0.16485345]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00810992, 0.02468144, -7.91492367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.717660903930664, + 'FR_Wheel_Angle': 41.55138397216797, + 'Location': array([ -1.22193968, -21.28703117, 0.17003627]), + 'Rotation': array([-5.59392460e-02, 3.95492210e+01, -3.46374512e-02]), + 'Velocity': array([-3.04337412e-01, -5.63743770e-01, 3.70483380e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.983154296875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -51.64477539, -1666.23706055, 16.74243164]), + 'frame': 13906, + 'frame_number': 13906, + 'framesequence': 13904, + 'gaze_dir': array([0.98058069, 0.19467427, 0.02373725]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19467427, 0.02373725]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19467427, 0.02373725]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.03423495963216, + 'timestamp_carla': 57034, + 'timestamp_device': 56670, + 'timestamp_stream': 57.03423495963216, + 'transform': [array([ 0.00987717, -0.00354858, 0.16485487]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 4.68687667e-03, 2.18161959e-02, -8.08448219e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.712568283081055, + 'FR_Wheel_Angle': 41.54426193237305, + 'Location': array([ -1.23756301, -21.31181335, 0.17005298]), + 'Rotation': array([-5.63968681e-02, 3.91683197e+01, -3.45153771e-02]), + 'Velocity': array([-3.13502461e-01, -5.73028505e-01, 4.29103355e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9837646484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -51.14479065, -1665.76879883, 16.74182129]), + 'frame': 13907, + 'frame_number': 13907, + 'framesequence': 13905, + 'gaze_dir': array([0.98058069, 0.19457774, 0.02451607]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19457774, 0.02451607]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19457774, 0.02451607]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.03804435953498, + 'timestamp_carla': 57038, + 'timestamp_device': 56674, + 'timestamp_stream': 57.03804435953498, + 'transform': [array([ 0.00987717, -0.00354858, 0.16485487]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03080761, -0.01283872, -8.64436817]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.707767486572266, + 'FR_Wheel_Angle': 41.53367614746094, + 'Location': array([ -1.25475967, -21.33871078, 0.1700718 ]), + 'Rotation': array([-5.68886437e-02, 3.87519951e+01, -3.40576172e-02]), + 'Velocity': array([-3.18935782e-01, -5.88122189e-01, 5.10876183e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9847412109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -50.4753418 , -1665.14599609, 16.7409668 ]), + 'frame': 13908, + 'frame_number': 13908, + 'framesequence': 13906, + 'gaze_dir': array([0.98058069, 0.19447817, 0.02529376]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19447817, 0.02529376]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19447817, 0.02529376]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.041878059506416, + 'timestamp_carla': 57041, + 'timestamp_device': 56678, + 'timestamp_stream': 57.041878059506416, + 'transform': [array([ 0.00987717, -0.00354858, 0.16485487]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.04267607, -0.01622566, -8.898489 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.698068618774414, + 'FR_Wheel_Angle': 41.51554870605469, + 'Location': array([ -1.27112663, -21.36383247, 0.17008933]), + 'Rotation': array([-5.75853214e-02, 3.83633537e+01, -3.37524377e-02]), + 'Velocity': array([-3.33922952e-01, -6.05005682e-01, 5.62624948e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.985595703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -49.80407715, -1664.52661133, 16.7401123 ]), + 'frame': 13909, + 'frame_number': 13909, + 'framesequence': 13907, + 'gaze_dir': array([0.98058069, 0.19440134, 0.0258775 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19440134, 0.0258775 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19440134, 0.0258775 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.04502446204424, + 'timestamp_carla': 57045, + 'timestamp_device': 56681, + 'timestamp_stream': 57.04502446204424, + 'transform': [array([ 0.00987701, -0.00354858, 0.16485597]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 4.46860772e-03, 2.26499792e-02, -8.85153389e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68806266784668, + 'FR_Wheel_Angle': 41.50102615356445, + 'Location': array([ -1.2887876 , -21.39052773, 0.17011364]), + 'Rotation': array([-5.83776236e-02, 3.79485512e+01, -3.32946777e-02]), + 'Velocity': array([-3.54930371e-01, -6.17527843e-01, 4.13122179e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9864501953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -49.2983551 , -1664.06323242, 16.73925781]), + 'frame': 13910, + 'frame_number': 13910, + 'framesequence': 13908, + 'gaze_dir': array([0.98058069, 0.19432288, 0.02646027]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19432288, 0.02646027]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19432288, 0.02646027]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.04828706011176, + 'timestamp_carla': 57048, + 'timestamp_device': 56684, + 'timestamp_stream': 57.04828706011176, + 'transform': [array([ 0.00987717, -0.00354858, 0.16485746]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02098562, -0.01286012, -9.40695381]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68337631225586, + 'FR_Wheel_Angle': 41.49146270751953, + 'Location': array([ -1.30729246, -21.41812897, 0.1701334 ]), + 'Rotation': array([-5.88079244e-02, 3.75148048e+01, -3.30505446e-02]), + 'Velocity': array([-3.59922528e-01, -6.31538153e-01, 4.11722664e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9873046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -48.79191589, -1663.60192871, 16.73852539]), + 'frame': 13911, + 'frame_number': 13911, + 'framesequence': 13909, + 'gaze_dir': array([0.98058069, 0.19421546, 0.02723766]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19421546, 0.02723766]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19421546, 0.02723766]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.051912158727646, + 'timestamp_carla': 57051, + 'timestamp_device': 56688, + 'timestamp_stream': 57.051912158727646, + 'transform': [array([ 0.00987717, -0.00354858, 0.16485746]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03809759, 0.02575151, -9.15435219]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67959976196289, + 'FR_Wheel_Angle': 41.487308502197266, + 'Location': array([ -1.32655382, -21.44639397, 0.17015025]), + 'Rotation': array([-5.88079244e-02, 3.70687866e+01, -3.36303711e-02]), + 'Velocity': array([-3.74056399e-01, -6.30470157e-01, 3.79626756e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.98828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -48.11383057, -1662.98864746, 16.73779297]), + 'frame': 13912, + 'frame_number': 13912, + 'framesequence': 13910, + 'gaze_dir': array([0.98058069, 0.194105 , 0.02801388]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.194105 , 0.02801388]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.194105 , 0.02801388]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.05533766001463, + 'timestamp_carla': 57055, + 'timestamp_device': 56692, + 'timestamp_stream': 57.05533766001463, + 'transform': [array([ 0.00987732, -0.00354858, 0.16485864]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03526249, 0.02473573, -9.25644779]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.676170349121094, + 'FR_Wheel_Angle': 41.482017517089844, + 'Location': array([ -1.34480357, -21.47275352, 0.17016487]), + 'Rotation': array([-5.86849824e-02, 3.66496696e+01, -3.43322791e-02]), + 'Velocity': array([-3.82986367e-01, -6.34708881e-01, 4.00598045e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9891357421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -47.4339447 , -1662.37878418, 16.73681641]), + 'frame': 13913, + 'frame_number': 13913, + 'framesequence': 13911, + 'gaze_dir': array([0.98058069, 0.19402002, 0.02859649]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19402002, 0.02859649]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19402002, 0.02859649]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.05901686102152, + 'timestamp_carla': 57059, + 'timestamp_device': 56695, + 'timestamp_stream': 57.05901686102152, + 'transform': [array([ 0.00987732, -0.00354858, 0.16485864]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01278656, -0.01344008, -9.70311737]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.673107147216797, + 'FR_Wheel_Angle': 41.473793029785156, + 'Location': array([ -1.36469877, -21.5010376 , 0.17018284]), + 'Rotation': array([-5.86849824e-02, 3.61988220e+01, -3.47595178e-02]), + 'Velocity': array([-3.87143344e-01, -6.44353271e-01, 3.15737707e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.989990234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -46.92176819, -1661.92248535, 16.73620605]), + 'frame': 13914, + 'frame_number': 13914, + 'framesequence': 13912, + 'gaze_dir': array([0.98058069, 0.19390415, 0.02937191]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19390415, 0.02937191]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19390415, 0.02937191]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.06239866092801, + 'timestamp_carla': 57062, + 'timestamp_device': 56699, + 'timestamp_stream': 57.06239866092801, + 'transform': [array([ 0.00987747, -0.00354858, 0.16485979]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-9.13764536e-03, -1.43098654e-02, -9.67255783e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.6728515625, + 'FR_Wheel_Angle': 41.47446823120117, + 'Location': array([ -1.38507807, -21.52944565, 0.17019039]), + 'Rotation': array([-0.05840494, 35.74753952, -0.03588868]), + 'Velocity': array([-0.39330605, -0.64074194, 0.00069807]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.99072265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -46.23760986, -1661.31738281, 16.73547363]), + 'frame': 13915, + 'frame_number': 13915, + 'framesequence': 13913, + 'gaze_dir': array([0.98058069, 0.1938151 , 0.02995391]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1938151 , 0.02995391]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1938151 , 0.02995391]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.066110260784626, + 'timestamp_carla': 57066, + 'timestamp_device': 56702, + 'timestamp_stream': 57.066110260784626, + 'transform': [array([ 0.00987747, -0.00354858, 0.16485979]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03016618, 0.01748948, -9.29913425]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.672834396362305, + 'FR_Wheel_Angle': 41.47488021850586, + 'Location': array([ -1.4037863 , -21.55508423, 0.17020473]), + 'Rotation': array([-0.05801562, 35.33634949, -0.03689576]), + 'Velocity': array([-4.02270734e-01, -6.31795049e-01, 5.71022043e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9915771484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -45.72227478, -1660.86462402, 16.73474121]), + 'frame': 13916, + 'frame_number': 13916, + 'framesequence': 13914, + 'gaze_dir': array([0.98058069, 0.19372441, 0.0305349 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19372441, 0.0305349 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19372441, 0.0305349 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.069381061941385, + 'timestamp_carla': 57069, + 'timestamp_device': 56705, + 'timestamp_stream': 57.069381061941385, + 'transform': [array([ 0.00987762, -0.00354858, 0.16486101]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02443544, -0.01301608, -9.80356598]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66834259033203, + 'FR_Wheel_Angle': 41.46632385253906, + 'Location': array([ -1.42441428, -21.58301926, 0.17023136]), + 'Rotation': array([-0.05810441, 34.88439178, -0.03665161]), + 'Velocity': array([-4.08511460e-01, -6.44288242e-01, 4.90868057e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9923095703125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -45.20623779, -1660.4140625 , 16.73400879]), + 'frame': 13917, + 'frame_number': 13917, + 'framesequence': 13915, + 'gaze_dir': array([0.98058069, 0.19360068, 0.03130986]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19360068, 0.03130986]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19360068, 0.03130986]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.072702560573816, + 'timestamp_carla': 57072, + 'timestamp_device': 56709, + 'timestamp_stream': 57.072702560573816, + 'transform': [array([ 0.00987762, -0.00354858, 0.16486101]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01318086, 0.01812074, -9.62800789]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.664365768432617, + 'FR_Wheel_Angle': 41.4633903503418, + 'Location': array([ -1.44581187, -21.61148834, 0.17025439]), + 'Rotation': array([-0.05828883, 34.42146683, -0.03686523]), + 'Velocity': array([-0.42274374, -0.64346379, 0.0006464 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9932861328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -44.51541138, -1659.81518555, 16.7331543 ]), + 'frame': 13918, + 'frame_number': 13918, + 'framesequence': 13916, + 'gaze_dir': array([0.98058069, 0.19350591, 0.0318902 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19350591, 0.0318902 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19350591, 0.0318902 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.07600776106119, + 'timestamp_carla': 57076, + 'timestamp_device': 56712, + 'timestamp_stream': 57.07600776106119, + 'transform': [array([ 0.00987778, -0.00354858, 0.16486208]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02113005, 0.01765966, -9.64634418]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66343879699707, + 'FR_Wheel_Angle': 41.45924758911133, + 'Location': array([ -1.46665895, -21.63876724, 0.17027214]), + 'Rotation': array([-0.0583503 , 33.97532272, -0.03723144]), + 'Velocity': array([-4.29050475e-01, -6.41907692e-01, 6.27944479e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.993896484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -43.99621582, -1659.36828613, 16.73254395]), + 'frame': 13919, + 'frame_number': 13919, + 'framesequence': 13917, + 'gaze_dir': array([0.98058069, 0.19337676, 0.03266428]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19337676, 0.03266428]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19337676, 0.03266428]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.07953516021371, + 'timestamp_carla': 57079, + 'timestamp_device': 56716, + 'timestamp_stream': 57.07953516021371, + 'transform': [array([ 0.00987778, -0.00354858, 0.16486208]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.12447943, 0.02810809, -8.57388687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69004249572754, + 'FR_Wheel_Angle': 41.50367736816406, + 'Location': array([ -1.49253821, -21.67222404, 0.17022289]), + 'Rotation': array([-0.05639687, 33.43094254, -0.04040527]), + 'Velocity': array([-3.99722427e-01, -5.83772480e-01, 4.79955663e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9951171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -43.30123901, -1658.77429199, 16.73144531]), + 'frame': 13920, + 'frame_number': 13920, + 'framesequence': 13918, + 'gaze_dir': array([0.98058069, 0.19327797, 0.03324395]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19327797, 0.03324395]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19327797, 0.03324395]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.083261761814356, + 'timestamp_carla': 57083, + 'timestamp_device': 56719, + 'timestamp_stream': 57.083261761814356, + 'transform': [array([ 0.00987778, -0.00354858, 0.16486208]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01207617, 0.0176291 , -9.04588318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.680519104003906, + 'FR_Wheel_Angle': 41.488468170166016, + 'Location': array([ -1.5132817 , -21.69854736, 0.17027263]), + 'Rotation': array([-0.05569336, 32.99622345, -0.0411377 ]), + 'Velocity': array([-0.41733074, -0.59940952, 0.00119695]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9957275390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -42.77894592, -1658.33093262, 16.73095703]), + 'frame': 13921, + 'frame_number': 13921, + 'framesequence': 13919, + 'gaze_dir': array([0.98058069, 0.19314338, 0.0340171 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19314338, 0.0340171 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19314338, 0.0340171 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.08653016015887, + 'timestamp_carla': 57086, + 'timestamp_device': 56723, + 'timestamp_stream': 57.08653016015887, + 'transform': [array([ 0.00987778, -0.00354858, 0.16486208]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01332265, 0.02426467, -9.15586281]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67823600769043, + 'FR_Wheel_Angle': 41.486446380615234, + 'Location': array([ -1.53468716, -21.72518349, 0.17031479]), + 'Rotation': array([-0.05667008, 32.55292892, -0.03988647]), + 'Velocity': array([-0.42496952, -0.60091686, 0.00089909]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.996826171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -42.07981873, -1657.74182129, 16.7298584 ]), + 'frame': 13922, + 'frame_number': 13922, + 'framesequence': 13920, + 'gaze_dir': array([0.98058069, 0.19300583, 0.03478898]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19300583, 0.03478898]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19300583, 0.03478898]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.09112736210227, + 'timestamp_carla': 57091, + 'timestamp_device': 56727, + 'timestamp_stream': 57.09112736210227, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01856261, 0.02134104, -9.40031147]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67001724243164, + 'FR_Wheel_Angle': 41.47032928466797, + 'Location': array([ -1.5556035 , -21.75078773, 0.17035122]), + 'Rotation': array([-0.05743506, 32.12334824, -0.03915405]), + 'Velocity': array([-0.44100168, -0.61380237, 0.00074259]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9976806640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -41.37896729, -1657.15600586, 16.72900391]), + 'frame': 13923, + 'frame_number': 13923, + 'framesequence': 13921, + 'gaze_dir': array([0.98058069, 0.19286509, 0.03556103]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19286509, 0.03556103]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19286509, 0.03556103]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.09452576190233, + 'timestamp_carla': 57094, + 'timestamp_device': 56731, + 'timestamp_stream': 57.09452576190233, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.24839349e-02, -4.05740039e-03, -9.95039654e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.661951065063477, + 'FR_Wheel_Angle': 41.45505142211914, + 'Location': array([ -1.5781219 , -21.77791405, 0.17038688]), + 'Rotation': array([-0.05868498, 31.66592026, -0.03778076]), + 'Velocity': array([-0.45387957, -0.63156635, 0.00067313]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9984130859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -40.67512512, -1656.57250977, 16.72814941]), + 'frame': 13924, + 'frame_number': 13924, + 'framesequence': 13922, + 'gaze_dir': array([0.98058069, 0.19275759, 0.03613915]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19275759, 0.03613915]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19275759, 0.03613915]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.09784606099129, + 'timestamp_carla': 57097, + 'timestamp_device': 56734, + 'timestamp_stream': 57.09784606099129, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 9.43860412e-03, 2.18365062e-02, -9.80409145e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.658668518066406, + 'FR_Wheel_Angle': 41.44950485229492, + 'Location': array([ -1.60189605, -21.80606079, 0.17041492]), + 'Rotation': array([-0.05951143, 31.18782425, -0.03723145]), + 'Velocity': array([-4.68875885e-01, -6.31648421e-01, 5.47440024e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.9990234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -40.14620972, -1656.13720703, 16.72753906]), + 'frame': 13925, + 'frame_number': 13925, + 'framesequence': 13923, + 'gaze_dir': array([0.98058069, 0.19264823, 0.03671768]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19264823, 0.03671768]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19264823, 0.03671768]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.101348761469126, + 'timestamp_carla': 57101, + 'timestamp_device': 56737, + 'timestamp_stream': 57.101348761469126, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01652696, 0.0201439 , -9.9042263 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.65382957458496, + 'FR_Wheel_Angle': 41.44717025756836, + 'Location': array([ -1.62436759, -21.8322506 , 0.17043681]), + 'Rotation': array([-0.05981879, 30.73980331, -0.03720093]), + 'Velocity': array([-4.78916883e-01, -6.34539783e-01, 4.36034199e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.999755859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -39.61535645, -1655.70275879, 16.72680664]), + 'frame': 13926, + 'frame_number': 13926, + 'framesequence': 13924, + 'gaze_dir': array([0.98058069, 0.19249989, 0.03748755]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19249989, 0.03748755]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19249989, 0.03748755]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.10460935905576, + 'timestamp_carla': 57104, + 'timestamp_device': 56741, + 'timestamp_stream': 57.10460935905576, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02708274, 0.01613005, -9.83846474]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.65544891357422, + 'FR_Wheel_Angle': 41.44807052612305, + 'Location': array([ -1.64832389, -21.85970879, 0.17045265]), + 'Rotation': array([-0.05960023, 30.26789665, -0.03793335]), + 'Velocity': array([-4.81868654e-01, -6.27280653e-01, 5.92849217e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.000732421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -38.90638733, -1655.12683105, 16.72595215]), + 'frame': 13927, + 'frame_number': 13927, + 'framesequence': 13925, + 'gaze_dir': array([0.98058069, 0.19238648, 0.0380653 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19238648, 0.0380653 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19238648, 0.0380653 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.10814215987921, + 'timestamp_carla': 57108, + 'timestamp_device': 56744, + 'timestamp_stream': 57.10814215987921, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02648829, 0.01568402, -9.92192173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.65399932861328, + 'FR_Wheel_Angle': 41.44411087036133, + 'Location': array([ -1.6717093 , -21.8860817 , 0.17047432]), + 'Rotation': array([-0.05951143, 29.80993462, -0.03805542]), + 'Velocity': array([-4.88704175e-01, -6.26697302e-01, 5.99219813e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0013427734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -38.3724823 , -1654.69628906, 16.72521973]), + 'frame': 13928, + 'frame_number': 13928, + 'framesequence': 13926, + 'gaze_dir': array([0.98058069, 0.19223276, 0.03883412]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19223276, 0.03883412]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19223276, 0.03883412]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.1116664595902, + 'timestamp_carla': 57111, + 'timestamp_device': 56748, + 'timestamp_stream': 57.1116664595902, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.82032564e-02, -9.40847304e-03, -1.03664780e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64959144592285, + 'FR_Wheel_Angle': 41.43400192260742, + 'Location': array([ -1.69637895, -21.91346169, 0.1705014 ]), + 'Rotation': array([-0.05963438, 29.33009338, -0.03787231]), + 'Velocity': array([-4.97219771e-01, -6.36807323e-01, 6.14495249e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0023193359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -37.65953064, -1654.12536621, 16.72436523]), + 'frame': 13929, + 'frame_number': 13929, + 'framesequence': 13927, + 'gaze_dir': array([0.98058069, 0.19211532, 0.03941106]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19211532, 0.03941106]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19211532, 0.03941106]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.115024361759424, + 'timestamp_carla': 57115, + 'timestamp_device': 56751, + 'timestamp_stream': 57.115024361759424, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03390336, 0.0176091 , -10.13630009]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.648326873779297, + 'FR_Wheel_Angle': 41.434165954589844, + 'Location': array([ -1.72227371, -21.94171333, 0.17052528]), + 'Rotation': array([-0.05969585, 28.83165359, -0.03790284]), + 'Velocity': array([-5.07750332e-01, -6.29215598e-01, 5.83689194e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0030517578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -37.12263489, -1653.69848633, 16.72363281]), + 'frame': 13930, + 'frame_number': 13930, + 'framesequence': 13928, + 'gaze_dir': array([0.98058069, 0.19199629, 0.03998691]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19199629, 0.03998691]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19199629, 0.03998691]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.1183199621737, + 'timestamp_carla': 57118, + 'timestamp_device': 56754, + 'timestamp_stream': 57.1183199621737, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.04453399, 0.0148554 , -10.08436966]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.650253295898438, + 'FR_Wheel_Angle': 41.43938064575195, + 'Location': array([ -1.74748635, -21.96875381, 0.17054412]), + 'Rotation': array([-0.05944996, 28.34971237, -0.03842163]), + 'Velocity': array([-5.09910882e-01, -6.21643424e-01, 5.62620175e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.003662109375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -36.58514404, -1653.27368164, 16.72302246]), + 'frame': 13931, + 'frame_number': 13931, + 'framesequence': 13929, + 'gaze_dir': array([0.98058069, 0.19183473, 0.04075488]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19183473, 0.04075488]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19183473, 0.04075488]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.12155266106129, + 'timestamp_carla': 57121, + 'timestamp_device': 56758, + 'timestamp_stream': 57.12155266106129, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ -0.02925161, -0.01063628, -10.4957695 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.645652770996094, + 'FR_Wheel_Angle': 41.430721282958984, + 'Location': array([ -1.77328837, -21.99598885, 0.17057197]), + 'Rotation': array([-0.05944996, 27.86042213, -0.03857422]), + 'Velocity': array([-5.18396378e-01, -6.30731404e-01, 5.96492260e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.004638671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -35.86579895, -1652.70935059, 16.7220459 ]), + 'frame': 13932, + 'frame_number': 13932, + 'framesequence': 13930, + 'gaze_dir': array([0.98058069, 0.19167028, 0.04152147]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19167028, 0.04152147]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19167028, 0.04152147]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.12541786208749, + 'timestamp_carla': 57125, + 'timestamp_device': 56762, + 'timestamp_stream': 57.12541786208749, + 'transform': [array([ 0.00987793, -0.00354858, 0.16486028]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ -0.01326414, -0.01050137, -10.49060917]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.646814346313477, + 'FR_Wheel_Angle': 41.43006134033203, + 'Location': array([ -1.79840255, -22.02203751, 0.17059451]), + 'Rotation': array([-0.05951143, 27.38873672, -0.03869629]), + 'Velocity': array([-5.22517025e-01, -6.25302136e-01, 5.95071295e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0054931640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -35.14489746, -1652.1484375 , 16.72119141]), + 'frame': 13933, + 'frame_number': 13933, + 'framesequence': 13931, + 'gaze_dir': array([0.98058069, 0.19146024, 0.0424795 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19146024, 0.0424795 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19146024, 0.0424795 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.1306697614491, + 'timestamp_carla': 57130, + 'timestamp_device': 56767, + 'timestamp_stream': 57.1306697614491, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485524]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01056198, 0.01466299, -10.27871895]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64328956604004, + 'FR_Wheel_Angle': 41.423648834228516, + 'Location': array([ -1.82496607, -22.04908943, 0.17062256]), + 'Rotation': array([-0.05957291, 26.89655495, -0.03894042]), + 'Velocity': array([-0.53890026, -0.62295312, 0.00069982]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.006591796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -34.23995972, -1651.45092773, 16.72009277]), + 'frame': 13934, + 'frame_number': 13934, + 'framesequence': 13932, + 'gaze_dir': array([0.98058069, 0.19133183, 0.04305411]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19133183, 0.04305411]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19133183, 0.04305411]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.13390025869012, + 'timestamp_carla': 57133, + 'timestamp_device': 56770, + 'timestamp_stream': 57.13390025869012, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.60477502e-03, -1.65203474e-02, -1.05564518e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64710235595703, + 'FR_Wheel_Angle': 41.42985534667969, + 'Location': array([ -1.84953773, -22.07378387, 0.17063941]), + 'Rotation': array([-0.05942264, 26.44091988, -0.03894043]), + 'Velocity': array([-5.31518519e-01, -6.17709160e-01, 4.49995976e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0069580078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -33.69500732, -1651.03430176, 16.71923828]), + 'frame': 13935, + 'frame_number': 13935, + 'framesequence': 13933, + 'gaze_dir': array([0.98058069, 0.19120188, 0.04362759]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19120188, 0.04362759]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19120188, 0.04362759]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.137332059443, + 'timestamp_carla': 57137, + 'timestamp_device': 56773, + 'timestamp_stream': 57.137332059443, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02973728, 0.01512352, -10.22625065]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.645280838012695, + 'FR_Wheel_Angle': 41.42778778076172, + 'Location': array([ -1.87718117, -22.10106087, 0.17066841]), + 'Rotation': array([-0.05932702, 25.93505287, -0.03939819]), + 'Velocity': array([-5.45161426e-01, -6.09754324e-01, 5.52678073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.007568359375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -33.14950562, -1650.61987305, 16.71862793]), + 'frame': 13936, + 'frame_number': 13936, + 'framesequence': 13934, + 'gaze_dir': array([0.98058069, 0.19102578, 0.04439236]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19102578, 0.04439236]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19102578, 0.04439236]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.14098985865712, + 'timestamp_carla': 57141, + 'timestamp_device': 56777, + 'timestamp_stream': 57.14098985865712, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.03409286e-02, -6.86444482e-03, -1.06440659e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.640636444091797, + 'FR_Wheel_Angle': 41.42152786254883, + 'Location': array([ -1.90430248, -22.12737274, 0.17069954]), + 'Rotation': array([-0.05960023, 25.44235229, -0.03921508]), + 'Velocity': array([-0.5535984 , -0.61754513, 0.00072257]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.008544921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -32.41960144, -1650.06933594, 16.71777344]), + 'frame': 13937, + 'frame_number': 13937, + 'framesequence': 13935, + 'gaze_dir': array([0.98058069, 0.1908918 , 0.04496492]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1908918 , 0.04496492]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1908918 , 0.04496492]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.14433196187019, + 'timestamp_carla': 57144, + 'timestamp_device': 56780, + 'timestamp_stream': 57.14433196187019, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ -0.02750482, -0.01117912, -10.72662735]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639209747314453, + 'FR_Wheel_Angle': 41.417423248291016, + 'Location': array([ -1.93027997, -22.15213585, 0.17072666]), + 'Rotation': array([-0.05992808, 24.97482491, -0.03887939]), + 'Velocity': array([-5.60522616e-01, -6.16840065e-01, 3.48782545e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.00927734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -31.87123108, -1649.65869141, 16.71704102]), + 'frame': 13938, + 'frame_number': 13938, + 'framesequence': 13936, + 'gaze_dir': array([0.98058069, 0.19071035, 0.04572843]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19071035, 0.04572843]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19071035, 0.04572843]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.14754065871239, + 'timestamp_carla': 57147, + 'timestamp_device': 56784, + 'timestamp_stream': 57.14754065871239, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.09668981, 0.03774889, -9.82693958]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64079475402832, + 'FR_Wheel_Angle': 41.42329406738281, + 'Location': array([ -1.95725429, -22.17734337, 0.17072582]), + 'Rotation': array([-0.05990076, 24.49894142, -0.03997803]), + 'Velocity': array([-0.56968784, -0.59469306, -0.00260283]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.01025390625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -31.13748169, -1649.11328125, 16.71606445]), + 'frame': 13939, + 'frame_number': 13939, + 'framesequence': 13937, + 'gaze_dir': array([0.98058069, 0.19057238, 0.04630005]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19057238, 0.04630005]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19057238, 0.04630005]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.15081785991788, + 'timestamp_carla': 57150, + 'timestamp_device': 56787, + 'timestamp_stream': 57.15081785991788, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03828163, 0.01316551, -9.77184391]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63846206665039, + 'FR_Wheel_Angle': 41.41234588623047, + 'Location': array([ -1.98604381, -22.20372772, 0.17076984]), + 'Rotation': array([-0.06018079, 24.00842476, -0.04006957]), + 'Velocity': array([-0.57775944, -0.5958392 , 0.00063927]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0108642578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -30.58625793, -1648.70654297, 16.7154541 ]), + 'frame': 13940, + 'frame_number': 13940, + 'framesequence': 13938, + 'gaze_dir': array([0.98058069, 0.1904327 , 0.04687124]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1904327 , 0.04687124]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1904327 , 0.04687124]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.154017560184, + 'timestamp_carla': 57154, + 'timestamp_device': 56790, + 'timestamp_stream': 57.154017560184, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.23292911e-02, -2.49909027e-03, -1.04191160e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.632566452026367, + 'FR_Wheel_Angle': 41.41116714477539, + 'Location': array([ -2.01519775, -22.22982407, 0.17080803]), + 'Rotation': array([-0.06033789, 23.522995 , -0.04003906]), + 'Velocity': array([-0.59165126, -0.60347766, 0.00074212]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0115966796875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -30.03381348, -1648.3013916 , 16.71472168]), + 'frame': 13941, + 'frame_number': 13941, + 'framesequence': 13939, + 'gaze_dir': array([0.98058069, 0.19024362, 0.0476329 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19024362, 0.0476329 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19024362, 0.0476329 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.15727065876126, + 'timestamp_carla': 57157, + 'timestamp_device': 56794, + 'timestamp_stream': 57.15727065876126, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.64072374e-03, -9.54961497e-03, -1.06446848e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639728546142578, + 'FR_Wheel_Angle': 41.41921615600586, + 'Location': array([ -2.043432 , -22.25462532, 0.17082943]), + 'Rotation': array([-0.06005785, 23.05258179, -0.04025268]), + 'Velocity': array([-0.58453083, -0.58614999, 0.00081347]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.012451171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -29.29463196, -1647.76330566, 16.71386719]), + 'frame': 13942, + 'frame_number': 13942, + 'framesequence': 13940, + 'gaze_dir': array([0.98058069, 0.19009994, 0.0482031 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19009994, 0.0482031 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19009994, 0.0482031 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.161320459097624, + 'timestamp_carla': 57161, + 'timestamp_device': 56797, + 'timestamp_stream': 57.161320459097624, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.45826484e-02, -4.05447371e-03, -1.03483248e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.637805938720703, + 'FR_Wheel_Angle': 41.41743087768555, + 'Location': array([ -2.07331395, -22.28059578, 0.17085575]), + 'Rotation': array([-0.0600237 , 22.54046059, -0.03918456]), + 'Velocity': array([-0.59143466, -0.58800089, 0.00077986]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0133056640625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -28.73939514, -1647.36206055, 16.71313477]), + 'frame': 13943, + 'frame_number': 13943, + 'framesequence': 13941, + 'gaze_dir': array([0.98058069, 0.18990552, 0.04896342]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18990552, 0.04896342]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18990552, 0.04896342]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.16456786170602, + 'timestamp_carla': 57164, + 'timestamp_device': 56801, + 'timestamp_stream': 57.16456786170602, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.50377508e-02, -2.29860377e-03, -1.03193378e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.638591766357422, + 'FR_Wheel_Angle': 41.41818618774414, + 'Location': array([ -2.10154271, -22.3047142 , 0.17088172]), + 'Rotation': array([-0.06036521, 22.0553112 , -0.03823853]), + 'Velocity': array([-5.94607294e-01, -5.82730412e-01, 3.34887503e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.01416015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -27.9964447 , -1646.82922363, 16.71228027]), + 'frame': 13944, + 'frame_number': 13944, + 'framesequence': 13942, + 'gaze_dir': array([0.98058069, 0.18975785, 0.0495326 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18975785, 0.0495326 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18975785, 0.0495326 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.167684558779, + 'timestamp_carla': 57167, + 'timestamp_device': 56804, + 'timestamp_stream': 57.167684558779, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-9.64872912e-03, -1.41644478e-03, -1.02326097e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639284133911133, + 'FR_Wheel_Angle': 41.419376373291016, + 'Location': array([ -2.13006425, -22.32867432, 0.17090492]), + 'Rotation': array([-0.060454 , 21.56600952, -0.0378418 ]), + 'Velocity': array([-5.98322868e-01, -5.76552510e-01, 2.76021950e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.014892578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -27.43838501, -1646.43188477, 16.71154785]), + 'frame': 13945, + 'frame_number': 13945, + 'framesequence': 13943, + 'gaze_dir': array([0.98058069, 0.18960831, 0.05010207]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18960831, 0.05010207]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18960831, 0.05010207]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.17101275920868, + 'timestamp_carla': 57171, + 'timestamp_device': 56807, + 'timestamp_stream': 57.17101275920868, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.32175757e-03, 3.07578780e-03, -1.08573427e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.6387996673584, + 'FR_Wheel_Angle': 41.416141510009766, + 'Location': array([ -2.16046023, -22.35375023, 0.1709327 ]), + 'Rotation': array([-0.06066574, 21.04801559, -0.03744507]), + 'Velocity': array([-0.60474062, -0.57093632, 0.00069459]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -26.87846375, -1646.0357666 , 16.71081543]), + 'frame': 13946, + 'frame_number': 13946, + 'framesequence': 13944, + 'gaze_dir': array([0.98058069, 0.18940648, 0.05085968]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18940648, 0.05085968]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18940648, 0.05085968]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.17476946115494, + 'timestamp_carla': 57174, + 'timestamp_device': 56811, + 'timestamp_stream': 57.17476946115494, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.25814262e-03, 1.89852214e-03, -1.08799038e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639001846313477, + 'FR_Wheel_Angle': 41.417686462402344, + 'Location': array([ -2.18915582, -22.37700653, 0.17095688]), + 'Rotation': array([-0.06094578, 20.56351852, -0.03701783]), + 'Velocity': array([-0.60912925, -0.56563348, 0.00065981]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0166015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -26.13093567, -1645.51074219, 16.70983887]), + 'frame': 13947, + 'frame_number': 13947, + 'framesequence': 13945, + 'gaze_dir': array([0.98058069, 0.18920144, 0.0516172 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18920144, 0.0516172 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18920144, 0.0516172 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.178382862359285, + 'timestamp_carla': 57178, + 'timestamp_device': 56815, + 'timestamp_stream': 57.178382862359285, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.49936562e-02, 3.88113712e-03, -1.04464617e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.636795043945312, + 'FR_Wheel_Angle': 41.412986755371094, + 'Location': array([ -2.21980023, -22.40141487, 0.17098576]), + 'Rotation': array([-0.06121898, 20.05109406, -0.03640747]), + 'Velocity': array([-0.62006158, -0.56585079, 0.00063072]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0174560546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -25.38061523, -1644.98828125, 16.70898438]), + 'frame': 13948, + 'frame_number': 13948, + 'framesequence': 13946, + 'gaze_dir': array([0.98058069, 0.18904583, 0.05218426]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18904583, 0.05218426]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18904583, 0.05218426]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.181697960942984, + 'timestamp_carla': 57181, + 'timestamp_device': 56818, + 'timestamp_stream': 57.181697960942984, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.85011163e-03, -3.11610266e-03, -1.07050009e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.641292572021484, + 'FR_Wheel_Angle': 41.420989990234375, + 'Location': array([ -2.24824405, -22.42366982, 0.17100212]), + 'Rotation': array([-0.06125313, 19.57829666, -0.03622437]), + 'Velocity': array([-6.14465117e-01, -5.51904380e-01, 5.25104988e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.018310546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -24.81706238, -1644.59887695, 16.70812988]), + 'frame': 13949, + 'frame_number': 13949, + 'framesequence': 13947, + 'gaze_dir': array([0.98058069, 0.18888833, 0.05275157]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18888833, 0.05275157]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18888833, 0.05275157]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.18490235880017, + 'timestamp_carla': 57184, + 'timestamp_device': 56821, + 'timestamp_stream': 57.18490235880017, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.40979493e-02, 3.06179561e-03, -1.03668756e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63796615600586, + 'FR_Wheel_Angle': 41.4167366027832, + 'Location': array([ -2.27979994, -22.44798279, 0.17103088]), + 'Rotation': array([-0.06121898, 19.06259918, -0.03582764]), + 'Velocity': array([-0.62547612, -0.55150372, 0.00078959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0189208984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -24.25160217, -1644.21057129, 16.7076416 ]), + 'frame': 13950, + 'frame_number': 13950, + 'framesequence': 13948, + 'gaze_dir': array([0.98058069, 0.18867572, 0.05350701]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18867572, 0.05350701]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18867572, 0.05350701]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.188115160912275, + 'timestamp_carla': 57188, + 'timestamp_device': 56825, + 'timestamp_stream': 57.188115160912275, + 'transform': [array([ 0.00987793, -0.00354858, 0.16485631]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 2.00574696e-02, -6.76988438e-03, -1.07379761e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64559555053711, + 'FR_Wheel_Angle': 41.431602478027344, + 'Location': array([ -2.30982614, -22.47063637, 0.17104587]), + 'Rotation': array([-0.06103457, 18.56699944, -0.03579712]), + 'Velocity': array([-0.61415482, -0.5328902 , 0.00062934]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0198974609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -23.49610901, -1643.69567871, 16.70654297]), + 'frame': 13951, + 'frame_number': 13951, + 'framesequence': 13949, + 'gaze_dir': array([0.98058069, 0.18851443, 0.05407248]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18851443, 0.05407248]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18851443, 0.05407248]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.19204406067729, + 'timestamp_carla': 57192, + 'timestamp_device': 56828, + 'timestamp_stream': 57.19204406067729, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.64324138e-02, -1.15581737e-04, -1.00502586e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.647228240966797, + 'FR_Wheel_Angle': 41.43286895751953, + 'Location': array([ -2.33781409, -22.49147606, 0.17107113]), + 'Rotation': array([-0.06069306, 18.11303902, -0.03594971]), + 'Velocity': array([-0.61737818, -0.52708137, 0.00089828]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0206298828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -22.92865753, -1643.31176758, 16.70581055]), + 'frame': 13952, + 'frame_number': 13952, + 'framesequence': 13950, + 'gaze_dir': array([0.98058069, 0.18835145, 0.05463747]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18835145, 0.05463747]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18835145, 0.05463747]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.19527995958924, + 'timestamp_carla': 57195, + 'timestamp_device': 56831, + 'timestamp_stream': 57.19527995958924, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.34886664e-02, 9.68171936e-03, -1.02710943e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.6411075592041, + 'FR_Wheel_Angle': 41.422027587890625, + 'Location': array([ -2.36639857, -22.51231575, 0.17110671]), + 'Rotation': array([-0.06127362, 17.65081787, -0.03491211]), + 'Velocity': array([-0.63327879, -0.5304262 , 0.00078352]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.021484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -22.36011505, -1642.9296875 , 16.70507812]), + 'frame': 13953, + 'frame_number': 13953, + 'framesequence': 13951, + 'gaze_dir': array([0.98058069, 0.1881313 , 0.05539075]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1881313 , 0.05539075]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1881313 , 0.05539075]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.19897396117449, + 'timestamp_carla': 57199, + 'timestamp_device': 56835, + 'timestamp_stream': 57.19897396117449, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.57664058e-02, 4.00755554e-03, -1.06592989e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64181900024414, + 'FR_Wheel_Angle': 41.417972564697266, + 'Location': array([ -2.39976311, -22.53616714, 0.17113419]), + 'Rotation': array([-0.0621274 , 17.11246681, -0.03366089]), + 'Velocity': array([-0.64245015, -0.52978319, 0.00083081]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0223388671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -21.59949493, -1642.42236328, 16.70422363]), + 'frame': 13954, + 'frame_number': 13954, + 'framesequence': 13952, + 'gaze_dir': array([0.98058069, 0.18796439, 0.05595458]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18796439, 0.05595458]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18796439, 0.05595458]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.20220426097512, + 'timestamp_carla': 57202, + 'timestamp_device': 56838, + 'timestamp_stream': 57.20220426097512, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.86349303e-02, 7.42128212e-03, -1.03451967e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63473129272461, + 'FR_Wheel_Angle': 41.41230773925781, + 'Location': array([ -2.43050528, -22.55767822, 0.17116877]), + 'Rotation': array([-0.06301532, 16.63964081, -0.03298949]), + 'Velocity': array([-0.65559483, -0.52511823, 0.00087962]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.02294921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -21.02825165, -1642.04418945, 16.70361328]), + 'frame': 13955, + 'frame_number': 13955, + 'framesequence': 13953, + 'gaze_dir': array([0.98058069, 0.18773897, 0.05670629]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18773897, 0.05670629]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18773897, 0.05670629]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.2055031619966, + 'timestamp_carla': 57205, + 'timestamp_device': 56842, + 'timestamp_stream': 57.2055031619966, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.96235920e-02, 9.03774417e-05, -1.06927586e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.634796142578125, + 'FR_Wheel_Angle': 41.426082611083984, + 'Location': array([ -2.46048522, -22.57840538, 0.1711864 ]), + 'Rotation': array([-0.06323389, 16.17343712, -0.03222656]), + 'Velocity': array([-6.58500195e-01, -5.23872256e-01, 2.79283529e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.02392578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -20.26407623, -1641.54223633, 16.70263672]), + 'frame': 13956, + 'frame_number': 13956, + 'framesequence': 13954, + 'gaze_dir': array([0.98058069, 0.1875681 , 0.05726894]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1875681 , 0.05726894]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1875681 , 0.05726894]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.208924259990454, + 'timestamp_carla': 57208, + 'timestamp_device': 56845, + 'timestamp_stream': 57.208924259990454, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.04231360e-03, -5.50820353e-03, -1.07953720e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.642959594726562, + 'FR_Wheel_Angle': 41.42493438720703, + 'Location': array([ -2.49232244, -22.59994316, 0.17121682]), + 'Rotation': array([-0.06286506, 15.68443871, -0.0326538 ]), + 'Velocity': array([-0.64784378, -0.50476426, 0.00072465]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0245361328125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -19.69020081, -1641.16809082, 16.70202637]), + 'frame': 13957, + 'frame_number': 13957, + 'framesequence': 13955, + 'gaze_dir': array([0.98058069, 0.18739533, 0.05783179]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18739533, 0.05783179]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18739533, 0.05783179]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.21214206144214, + 'timestamp_carla': 57212, + 'timestamp_device': 56848, + 'timestamp_stream': 57.21214206144214, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.74725335e-02, 3.07174562e-03, -1.08220139e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639984130859375, + 'FR_Wheel_Angle': 41.41781234741211, + 'Location': array([ -2.52266908, -22.62013626, 0.17125122]), + 'Rotation': array([-0.06317241, 15.20719147, -0.03170776]), + 'Velocity': array([-0.65757561, -0.50420982, 0.00080061]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0252685546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -19.11449432, -1640.79516602, 16.70129395]), + 'frame': 13958, + 'frame_number': 13958, + 'framesequence': 13956, + 'gaze_dir': array([0.98058069, 0.18722108, 0.05839341]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18722108, 0.05839341]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18722108, 0.05839341]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.215286161750555, + 'timestamp_carla': 57215, + 'timestamp_device': 56851, + 'timestamp_stream': 57.215286161750555, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.85314631e-02, -3.94106377e-03, -1.06953125e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63791847229004, + 'FR_Wheel_Angle': 41.41437530517578, + 'Location': array([ -2.55519485, -22.64139175, 0.17127292]), + 'Rotation': array([-0.06350709, 14.69968605, -0.03076171]), + 'Velocity': array([-0.66461128, -0.50664204, 0.00100902]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0260009765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -18.53835297, -1640.42456055, 16.70068359]), + 'frame': 13959, + 'frame_number': 13959, + 'framesequence': 13957, + 'gaze_dir': array([0.98058069, 0.18698591, 0.05914213]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18698591, 0.05914213]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18698591, 0.05914213]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.2188919596374, + 'timestamp_carla': 57218, + 'timestamp_device': 56855, + 'timestamp_stream': 57.2188919596374, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.04904129e-02, -2.64635962e-03, -1.07839842e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.636425018310547, + 'FR_Wheel_Angle': 41.412235260009766, + 'Location': array([ -2.58625913, -22.6614418 , 0.17131114]), + 'Rotation': array([-0.0639374 , 14.2203064 , -0.02975463]), + 'Velocity': array([-0.67143577, -0.50427681, 0.00084302]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.02685546875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -17.76774597, -1639.93249512, 16.69970703]), + 'frame': 13960, + 'frame_number': 13960, + 'framesequence': 13958, + 'gaze_dir': array([0.98058069, 0.18674798, 0.05988919]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18674798, 0.05988919]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18674798, 0.05988919]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.22289435938001, + 'timestamp_carla': 57222, + 'timestamp_device': 56859, + 'timestamp_stream': 57.22289435938001, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.67567711e-02, 7.04925694e-03, -1.05152035e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.634281158447266, + 'FR_Wheel_Angle': 41.41019821166992, + 'Location': array([ -2.61925745, -22.68232536, 0.17133655]), + 'Rotation': array([-0.0642994 , 13.71677208, -0.02935791]), + 'Velocity': array([-0.68131691, -0.49611315, 0.00082326]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.02783203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -16.99589539, -1639.4440918 , 16.69885254]), + 'frame': 13961, + 'frame_number': 13961, + 'framesequence': 13959, + 'gaze_dir': array([0.98058069, 0.18656734, 0.06044956]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18656734, 0.06044956]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18656734, 0.06044956]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.22630786150694, + 'timestamp_carla': 57226, + 'timestamp_device': 56862, + 'timestamp_stream': 57.22630786150694, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 3.08193592e-03, 3.80565925e-03, -1.04528761e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63532257080078, + 'FR_Wheel_Angle': 41.41286849975586, + 'Location': array([ -2.65038347, -22.70163918, 0.17137252]), + 'Rotation': array([-0.06454528, 13.24615192, -0.02902222]), + 'Velocity': array([-0.68359196, -0.48792613, 0.00077658]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0286865234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -16.41501617, -1639.07922363, 16.69799805]), + 'frame': 13962, + 'frame_number': 13962, + 'framesequence': 13960, + 'gaze_dir': array([0.98058069, 0.18632418, 0.06119494]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18632418, 0.06119494]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18632418, 0.06119494]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.22980646044016, + 'timestamp_carla': 57229, + 'timestamp_device': 56866, + 'timestamp_stream': 57.22980646044016, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.58395350e-03, 3.77065269e-04, -1.03589334e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63847541809082, + 'FR_Wheel_Angle': 41.420719146728516, + 'Location': array([ -2.68267608, -22.72129631, 0.1714001 ]), + 'Rotation': array([-0.06442234, 12.7606039 , -0.02914428]), + 'Velocity': array([-0.68146086, -0.47790751, 0.00085741]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.029541015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -15.63977051, -1638.59619141, 16.69714355]), + 'frame': 13963, + 'frame_number': 13963, + 'framesequence': 13961, + 'gaze_dir': array([0.98058069, 0.18613963, 0.06175404]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18613963, 0.06175404]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18613963, 0.06175404]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.23311756178737, + 'timestamp_carla': 57233, + 'timestamp_device': 56869, + 'timestamp_stream': 57.23311756178737, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.38374006e-02, 2.46160571e-03, -1.05000181e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.637893676757812, + 'FR_Wheel_Angle': 41.41541290283203, + 'Location': array([ -2.71653366, -22.74149513, 0.17143321]), + 'Rotation': array([-0.06451114, 12.25430584, -0.02874756]), + 'Velocity': array([-0.68657243, -0.47378752, 0.00075969]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0302734375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -15.05635071, -1638.23547363, 16.69641113]), + 'frame': 13964, + 'frame_number': 13964, + 'framesequence': 13962, + 'gaze_dir': array([0.98058069, 0.18595363, 0.06231187]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18595363, 0.06231187]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18595363, 0.06231187]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.23637596145272, + 'timestamp_carla': 57236, + 'timestamp_device': 56872, + 'timestamp_stream': 57.23637596145272, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.00828828e-02, -4.44781361e-03, -1.02186003e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.641555786132812, + 'FR_Wheel_Angle': 41.42152786254883, + 'Location': array([ -2.74734855, -22.75952148, 0.17145011]), + 'Rotation': array([-0.06469555, 11.79693699, -0.02822875]), + 'Velocity': array([-0.68311965, -0.46286365, 0.00084721]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.031005859375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -14.47255707, -1637.87695312, 16.69567871]), + 'frame': 13965, + 'frame_number': 13965, + 'framesequence': 13963, + 'gaze_dir': array([0.98058069, 0.18570279, 0.06305549]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18570279, 0.06305549]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18570279, 0.06305549]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.23976185917854, + 'timestamp_carla': 57239, + 'timestamp_device': 56876, + 'timestamp_stream': 57.23976185917854, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.62445217e-03, -1.39746610e-02, -1.02712259e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.646644592285156, + 'FR_Wheel_Angle': 41.43315124511719, + 'Location': array([ -2.77796721, -22.77713394, 0.17147678]), + 'Rotation': array([-0.06454528, 11.34357738, -0.02816772]), + 'Velocity': array([-6.76091671e-01, -4.52972740e-01, 5.26938413e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.031982421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -13.69179535, -1637.40124512, 16.69470215]), + 'frame': 13966, + 'frame_number': 13966, + 'framesequence': 13964, + 'gaze_dir': array([0.98058069, 0.1855129 , 0.06361201]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1855129 , 0.06361201]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1855129 , 0.06361201]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.2431357614696, + 'timestamp_carla': 57243, + 'timestamp_device': 56879, + 'timestamp_stream': 57.2431357614696, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.13095166e-02, 4.78002010e-03, -1.01401501e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.645435333251953, + 'FR_Wheel_Angle': 41.430667877197266, + 'Location': array([ -2.81370664, -22.79728127, 0.17150874]), + 'Rotation': array([-0.06448381, 10.81889629, -0.02822876]), + 'Velocity': array([-0.68333513, -0.44482961, 0.00090804]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.03271484375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -13.10553741, -1637.046875 , 16.69396973]), + 'frame': 13967, + 'frame_number': 13967, + 'framesequence': 13965, + 'gaze_dir': array([0.98058069, 0.18532108, 0.06416866]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18532108, 0.06416866]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18532108, 0.06416866]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.24639306217432, + 'timestamp_carla': 57246, + 'timestamp_device': 56882, + 'timestamp_stream': 57.24639306217432, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.65373944e-02, -1.47875631e-03, -1.01644611e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64927101135254, + 'FR_Wheel_Angle': 41.43451690673828, + 'Location': array([ -2.84420705, -22.81413269, 0.17153811]), + 'Rotation': array([-0.06451114, 10.3710556 , -0.02780151]), + 'Velocity': array([-0.67858839, -0.4367713 , 0.00083014]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0333251953125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -12.51743317, -1636.69372559, 16.69348145]), + 'frame': 13968, + 'frame_number': 13968, + 'framesequence': 13966, + 'gaze_dir': array([0.98058069, 0.18506308, 0.06490903]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18506308, 0.06490903]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18506308, 0.06490903]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.25013316050172, + 'timestamp_carla': 57250, + 'timestamp_device': 56886, + 'timestamp_stream': 57.25013316050172, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.81189699e-02, 5.72576746e-03, -1.01533403e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.648195266723633, + 'FR_Wheel_Angle': 41.432960510253906, + 'Location': array([ -2.87704086, -22.83192062, 0.17156917]), + 'Rotation': array([-0.06476385, 9.89239502, -0.02716065]), + 'Velocity': array([-0.68454587, -0.43169969, 0.00083593]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.034423828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -11.73271942, -1636.22619629, 16.69238281]), + 'frame': 13969, + 'frame_number': 13969, + 'framesequence': 13967, + 'gaze_dir': array([0.98058069, 0.18480185, 0.06564905]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18480185, 0.06564905]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18480185, 0.06564905]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.25379166007042, + 'timestamp_carla': 57253, + 'timestamp_device': 56890, + 'timestamp_stream': 57.25379166007042, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.80906113e-02, 9.70164780e-03, -1.01671085e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.644981384277344, + 'FR_Wheel_Angle': 41.428157806396484, + 'Location': array([ -2.9113214 , -22.85007668, 0.17160873]), + 'Rotation': array([-0.06552883, 9.39507961, -0.02597046]), + 'Velocity': array([-6.95136487e-01, -4.28161740e-01, 6.87134278e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0352783203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -10.94534302, -1635.76147461, 16.69152832]), + 'frame': 13970, + 'frame_number': 13970, + 'framesequence': 13968, + 'gaze_dir': array([0.98058069, 0.18453792, 0.06638733]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18453792, 0.06638733]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18453792, 0.06638733]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.25743145868182, + 'timestamp_carla': 57257, + 'timestamp_device': 56894, + 'timestamp_stream': 57.25743145868182, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.55901246e-03, 6.23283815e-03, -1.01596041e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.644472122192383, + 'FR_Wheel_Angle': 41.42777633666992, + 'Location': array([ -2.94388962, -22.86698914, 0.17164008]), + 'Rotation': array([-0.0660411 , 8.92420101, -0.02505493]), + 'Velocity': array([-6.99685514e-01, -4.23020929e-01, 5.07655146e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0362548828125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -10.15688324, -1635.30029297, 16.69055176]), + 'frame': 13971, + 'frame_number': 13971, + 'framesequence': 13969, + 'gaze_dir': array([0.98058069, 0.18433779, 0.06694104]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18433779, 0.06694104]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18433779, 0.06694104]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.260877162218094, + 'timestamp_carla': 57260, + 'timestamp_device': 56897, + 'timestamp_stream': 57.260877162218094, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.20517677e-03, 2.94387201e-03, -1.01444368e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.646175384521484, + 'FR_Wheel_Angle': 41.43202209472656, + 'Location': array([ -2.97708273, -22.8839016 , 0.1716693 ]), + 'Rotation': array([-0.06610256, 8.44523048, -0.02462769]), + 'Velocity': array([-0.69956791, -0.41572371, 0.00087804]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.036865234375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -9.56355286, -1634.95617676, 16.68994141]), + 'frame': 13972, + 'frame_number': 13972, + 'framesequence': 13970, + 'gaze_dir': array([0.98058069, 0.18413624, 0.06749345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18413624, 0.06749345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18413624, 0.06749345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.264086961746216, + 'timestamp_carla': 57264, + 'timestamp_device': 56900, + 'timestamp_stream': 57.264086961746216, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.52590051e-02, 8.69646389e-03, -1.02242537e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.642812728881836, + 'FR_Wheel_Angle': 41.423484802246094, + 'Location': array([ -3.00886345, -22.89974594, 0.17170326]), + 'Rotation': array([-0.0664031 , 7.98931265, -0.02389526]), + 'Velocity': array([-0.70994145, -0.41364509, 0.00084422]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0377197265625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -8.9699707 , -1634.61413574, 16.68908691]), + 'frame': 13973, + 'frame_number': 13973, + 'framesequence': 13971, + 'gaze_dir': array([0.98058069, 0.18386468, 0.06822975]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18386468, 0.06822975]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18386468, 0.06822975]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.26782996207476, + 'timestamp_carla': 57267, + 'timestamp_device': 56904, + 'timestamp_stream': 57.26782996207476, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.34070998e-02, 3.92526761e-03, -1.04072084e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.641267776489258, + 'FR_Wheel_Angle': 41.42182159423828, + 'Location': array([ -3.04386139, -22.91683006, 0.17173873]), + 'Rotation': array([-0.0668334 , 7.48907042, -0.02294922]), + 'Velocity': array([-7.16500580e-01, -4.11204517e-01, 6.77645206e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0386962890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -8.17619324, -1634.16040039, 16.68811035]), + 'frame': 13974, + 'frame_number': 13974, + 'framesequence': 13972, + 'gaze_dir': array([0.98058069, 0.18359046, 0.06896426]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18359046, 0.06896426]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18359046, 0.06896426]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.271545462310314, + 'timestamp_carla': 57271, + 'timestamp_device': 56908, + 'timestamp_stream': 57.271545462310314, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.02269200e-02, 2.77476804e-03, -1.04399767e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.640056610107422, + 'FR_Wheel_Angle': 41.41952133178711, + 'Location': array([ -3.07623863, -22.93230438, 0.17177013]), + 'Rotation': array([-0.06716808, 7.02823591, -0.02230835]), + 'Velocity': array([-7.22334266e-01, -4.06839043e-01, 6.33659365e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.03955078125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -7.38134766, -1633.71032715, 16.68737793]), + 'frame': 13975, + 'frame_number': 13975, + 'framesequence': 13973, + 'gaze_dir': array([0.98058069, 0.18338259, 0.06951512]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18338259, 0.06951512]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18338259, 0.06951512]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.27510325983167, + 'timestamp_carla': 57275, + 'timestamp_device': 56911, + 'timestamp_stream': 57.27510325983167, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.74642168e-02, 8.02695751e-03, -1.08713446e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63640594482422, + 'FR_Wheel_Angle': 41.4156379699707, + 'Location': array([ -3.11150599, -22.94874954, 0.17178825]), + 'Rotation': array([-0.06744128, 6.52802181, -0.02185058]), + 'Velocity': array([-0.73213774, -0.40141737, 0.00092562]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.040283203125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -6.78327179, -1633.37438965, 16.68664551]), + 'frame': 13976, + 'frame_number': 13976, + 'framesequence': 13974, + 'gaze_dir': array([0.98058069, 0.18317331, 0.07006465]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18317331, 0.07006465]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18317331, 0.07006465]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.27833876013756, + 'timestamp_carla': 57278, + 'timestamp_device': 56914, + 'timestamp_stream': 57.27833876013756, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.00736113e-02, 3.05228354e-03, -1.03186207e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639020919799805, + 'FR_Wheel_Angle': 41.420127868652344, + 'Location': array([ -3.14370441, -22.96345139, 0.17182167]), + 'Rotation': array([-0.06744128, 6.06924152, -0.02148437]), + 'Velocity': array([-0.73129147, -0.39531654, 0.00097204]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.041015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -6.18493652, -1633.04077148, 16.68591309]), + 'frame': 13977, + 'frame_number': 13977, + 'framesequence': 13975, + 'gaze_dir': array([0.98058069, 0.18289149, 0.07079707]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18289149, 0.07079707]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18289149, 0.07079707]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.281904961913824, + 'timestamp_carla': 57281, + 'timestamp_device': 56918, + 'timestamp_stream': 57.281904961913824, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 9.83717293e-03, 1.14373500e-02, -1.00022764e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63645362854004, + 'FR_Wheel_Angle': 41.4107551574707, + 'Location': array([ -3.17865896, -22.97900391, 0.17185283]), + 'Rotation': array([-0.06765302, 5.5711689 , -0.02105713]), + 'Velocity': array([-0.74074894, -0.38593721, 0.00102821]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0421142578125, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -5.38490295, -1632.59814453, 16.68481445]), + 'frame': 13978, + 'frame_number': 13978, + 'framesequence': 13976, + 'gaze_dir': array([0.98058069, 0.18267839, 0.07134513]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18267839, 0.07134513]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18267839, 0.07134513]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.28528006002307, + 'timestamp_carla': 57285, + 'timestamp_device': 56921, + 'timestamp_stream': 57.28528006002307, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.39385032e-03, 9.29137599e-03, -1.00376768e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63139533996582, + 'FR_Wheel_Angle': 41.402523040771484, + 'Location': array([ -3.21260428, -22.99371529, 0.17189652]), + 'Rotation': array([-0.06829505, 5.11076403, -0.02026367]), + 'Velocity': array([-0.75481755, -0.38362995, 0.00083577]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.042724609375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -4.78423309, -1632.26867676, 16.6842041 ]), + 'frame': 13979, + 'frame_number': 13979, + 'framesequence': 13977, + 'gaze_dir': array([0.98058069, 0.18239143, 0.07207556]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18239143, 0.07207556]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18239143, 0.07207556]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.28844406083226, + 'timestamp_carla': 57288, + 'timestamp_device': 56925, + 'timestamp_stream': 57.28844406083226, + 'transform': [array([ 0.00987778, -0.00354858, 0.16485529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.66550521e-02, -3.97857791e-03, -1.04053555e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.632966995239258, + 'FR_Wheel_Angle': 41.41104507446289, + 'Location': array([ -3.25021482, -23.00961113, 0.17193466]), + 'Rotation': array([-0.06839068, 4.6045351 , -0.02001953]), + 'Velocity': array([-7.54539847e-01, -3.78443569e-01, 7.29513180e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.043701171875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -3.98110199, -1631.83178711, 16.68322754]), + 'frame': 13980, + 'frame_number': 13980, + 'framesequence': 13978, + 'gaze_dir': array([0.98058069, 0.1820287 , 0.07298681]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1820287 , 0.07298681]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1820287 , 0.07298681]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.29415636137128, + 'timestamp_carla': 57294, + 'timestamp_device': 56930, + 'timestamp_stream': 57.29415636137128, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.78876948e-02, -7.09723495e-03, -1.02724209e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63650131225586, + 'FR_Wheel_Angle': 41.42198181152344, + 'Location': array([ -3.2839849 , -23.02354431, 0.17196555]), + 'Rotation': array([-0.06789891, 4.15266085, -0.02026367]), + 'Velocity': array([-0.74989063, -0.36848289, 0.00085165]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.044921875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -2.97489166, -1631.2902832 , 16.68200684]), + 'frame': 13981, + 'frame_number': 13981, + 'framesequence': 13979, + 'gaze_dir': array([0.98058069, 0.18173547, 0.07371394]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18173547, 0.07371394]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18173547, 0.07371394]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.29753226041794, + 'timestamp_carla': 57297, + 'timestamp_device': 56934, + 'timestamp_stream': 57.29753226041794, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.63358599e-02, -8.38832650e-03, -1.00249739e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63959503173828, + 'FR_Wheel_Angle': 41.42142868041992, + 'Location': array([ -3.3210361 , -23.03844643, 0.171997 ]), + 'Rotation': array([-0.06756423, 3.65550327, -0.02008056]), + 'Velocity': array([-0.74634922, -0.35900143, 0.0009544 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.045166015625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -2.16855621, -1630.86108398, 16.68115234]), + 'frame': 13982, + 'frame_number': 13982, + 'framesequence': 13980, + 'gaze_dir': array([0.98058069, 0.18151334, 0.07425921]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18151334, 0.07425921]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18151334, 0.07425921]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.30111476033926, + 'timestamp_carla': 57301, + 'timestamp_device': 56937, + 'timestamp_stream': 57.30111476033926, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.09369157e-02, -7.02943467e-03, -1.02247810e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.643396377563477, + 'FR_Wheel_Angle': 41.427406311035156, + 'Location': array([ -3.35448909, -23.0516758 , 0.17202644]), + 'Rotation': array([-0.06713393, 3.18905973, -0.01931763]), + 'Velocity': array([-0.74072164, -0.3535426 , 0.00083213]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0457763671875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-1.56192780e+00, -1.63054089e+03, 1.66804199e+01]), + 'frame': 13983, + 'frame_number': 13983, + 'framesequence': 13981, + 'gaze_dir': array([0.98058069, 0.181215 , 0.07498427]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.181215 , 0.07498427]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.181215 , 0.07498427]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.3044102601707, + 'timestamp_carla': 57304, + 'timestamp_device': 56941, + 'timestamp_stream': 57.3044102601707, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.06138478e-03, -1.06472652e-02, -1.06442986e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.649259567260742, + 'FR_Wheel_Angle': 41.434959411621094, + 'Location': array([ -3.39130545, -23.06591988, 0.17205779]), + 'Rotation': array([-0.06677192, 2.67061806, -0.01898193]), + 'Velocity': array([-7.31084287e-01, -3.40767562e-01, 6.05700014e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.046875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-7.52662659e-01, -1.63011719e+03, 1.66793213e+01]), + 'frame': 13984, + 'frame_number': 13984, + 'framesequence': 13982, + 'gaze_dir': array([0.98058069, 0.18098907, 0.07552797]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18098907, 0.07552797]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18098907, 0.07552797]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.3078749589622, + 'timestamp_carla': 57307, + 'timestamp_device': 56944, + 'timestamp_stream': 57.3078749589622, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.15874687e-02, 4.84497752e-03, -1.00941505e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.649497985839844, + 'FR_Wheel_Angle': 41.43448257446289, + 'Location': array([ -3.42589593, -23.07896996, 0.17209347]), + 'Rotation': array([-0.0666763 , 2.18576598, -0.01864624]), + 'Velocity': array([-0.73583442, -0.33569923, 0.00088483]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.047607421875, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([-1.43814087e-01, -1.62980127e+03, 1.66787109e+01]), + 'frame': 13985, + 'frame_number': 13985, + 'framesequence': 13983, + 'gaze_dir': array([0.98058069, 0.18068568, 0.07625092]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18068568, 0.07625092]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18068568, 0.07625092]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.31180366128683, + 'timestamp_carla': 57311, + 'timestamp_device': 56948, + 'timestamp_stream': 57.31180366128683, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.81114022e-02, 3.35904513e-03, -1.00056467e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.65089225769043, + 'FR_Wheel_Angle': 41.44007110595703, + 'Location': array([ -3.45862031, -23.09101105, 0.17212462]), + 'Rotation': array([-0.06671046, 1.72925544, -0.01815796]), + 'Velocity': array([-0.73297673, -0.32764933, 0.00078463]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.048583984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ 6.68380737e-01, -1.62938330e+03, 1.66777344e+01]), + 'frame': 13986, + 'frame_number': 13986, + 'framesequence': 13984, + 'gaze_dir': array([0.98058069, 0.18037912, 0.07697334]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18037912, 0.07697334]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18037912, 0.07697334]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.31543346121907, + 'timestamp_carla': 57315, + 'timestamp_device': 56952, + 'timestamp_stream': 57.31543346121907, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.80074063e-03, -7.24469428e-04, -1.04546652e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.653263092041016, + 'FR_Wheel_Angle': 41.44355010986328, + 'Location': array([ -3.49345016, -23.10347557, 0.1721593 ]), + 'Rotation': array([-0.06679925, 1.24222159, -0.01760864]), + 'Velocity': array([-0.72939008, -0.31795633, 0.00079534]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0494384765625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ 1.48304749e+00, -1.62896826e+03, 1.66768799e+01]), + 'frame': 13987, + 'frame_number': 13987, + 'framesequence': 13985, + 'gaze_dir': array([0.98058069, 0.1801475 , 0.07751384]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1801475 , 0.07751384]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1801475 , 0.07751384]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.318861559033394, + 'timestamp_carla': 57318, + 'timestamp_device': 56955, + 'timestamp_stream': 57.318861559033394, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.10751849e-03, -2.39440706e-03, -1.03562641e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.65771484375, + 'FR_Wheel_Angle': 41.44953155517578, + 'Location': array([ -3.52636409, -23.11499023, 0.17218807]), + 'Rotation': array([-0.06671046, 0.78582466, -0.01742553]), + 'Velocity': array([-0.72315609, -0.30842698, 0.00073474]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0501708984375, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ 2.09454346, -1628.65942383, 16.67614746]), + 'frame': 13988, + 'frame_number': 13988, + 'framesequence': 13986, + 'gaze_dir': array([0.98058069, 0.17983589, 0.07823409]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17983589, 0.07823409]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17983589, 0.07823409]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.322530660778284, + 'timestamp_carla': 57322, + 'timestamp_device': 56959, + 'timestamp_stream': 57.322530660778284, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.48804029e-02, 1.42849909e-04, -9.69660664e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.660099029541016, + 'FR_Wheel_Angle': 41.455753326416016, + 'Location': array([ -3.56160784, -23.12698746, 0.17222111]), + 'Rotation': array([-0.0666763 , 0.29863262, -0.01693725]), + 'Velocity': array([-7.20446885e-01, -3.01074982e-01, 6.37333374e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.051025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 2.91208649, -1628.25 , 16.67541504]), + 'frame': 13989, + 'frame_number': 13989, + 'framesequence': 13987, + 'gaze_dir': array([0.98058069, 0.17952169, 0.07895242]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17952169, 0.07895242]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17952169, 0.07895242]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.32638465985656, + 'timestamp_carla': 57326, + 'timestamp_device': 56963, + 'timestamp_stream': 57.32638465985656, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.18667344e-02, -2.61794403e-03, -9.57368183e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.664751052856445, + 'FR_Wheel_Angle': 41.46343994140625, + 'Location': array([ -3.59416866, -23.13776779, 0.1722504 ]), + 'Rotation': array([-0.06652604, -0.15182495, -0.0166626 ]), + 'Velocity': array([-0.71240985, -0.29141915, 0.00075233]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.052001953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 3.73045349, -1627.84423828, 16.67431641]), + 'frame': 13990, + 'frame_number': 13990, + 'framesequence': 13988, + 'gaze_dir': array([0.98058069, 0.17928384, 0.07949101]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17928384, 0.07949101]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17928384, 0.07949101]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 57.330186162143946, + 'timestamp_carla': 57330, + 'timestamp_device': 56966, + 'timestamp_stream': 57.330186162143946, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.24626996e-02, 5.82736731e-03, -9.57100391e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.665071487426758, + 'FR_Wheel_Angle': 41.46622848510742, + 'Location': array([ -3.62563229, -23.14791679, 0.1722831 ]), + 'Rotation': array([-0.06652604, -0.5863952 , -0.01611328]), + 'Velocity': array([-0.71387815, -0.28512686, 0.00072094]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0526123046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 4.34613037, -1627.54174805, 16.67382812]), + 'frame': 13991, + 'frame_number': 13991, + 'framesequence': 13989, + 'gaze_dir': array([0.98058069, 0.17896463, 0.08020712]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17896463, 0.08020712]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17896463, 0.08020712]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.01190203707665205, + 'timestamp': 57.33399026095867, + 'timestamp_carla': 57334, + 'timestamp_device': 56970, + 'timestamp_stream': 57.33399026095867, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.05134808e-02, -4.63029277e-03, -9.30329227e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.6709041595459, + 'FR_Wheel_Angle': 41.47484588623047, + 'Location': array([ -3.65827632, -23.15815926, 0.17231247]), + 'Rotation': array([-0.06646457, -1.03646851, -0.015625 ]), + 'Velocity': array([-7.03012049e-01, -2.75371939e-01, 5.86833921e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0535888671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 5.16732788, -1627.1418457 , 16.67285156]), + 'frame': 13992, + 'frame_number': 13992, + 'framesequence': 13990, + 'gaze_dir': array([0.98058069, 0.17864223, 0.08092262]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17864223, 0.08092262]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17864223, 0.08092262]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.01190203707665205, + 'timestamp': 57.337777461856604, + 'timestamp_carla': 57337, + 'timestamp_device': 56974, + 'timestamp_stream': 57.337777461856604, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.66357122e-03, -4.54059057e-03, -9.76948357e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.676143646240234, + 'FR_Wheel_Angle': 41.47979736328125, + 'Location': array([ -3.69281244, -23.16870308, 0.17234443]), + 'Rotation': array([-0.06622551, -1.51202393, -0.01535034]), + 'Velocity': array([-0.69342899, -0.26371574, 0.00080327]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0548095703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 5.99090576, -1626.74475098, 16.67163086]), + 'frame': 13993, + 'frame_number': 13993, + 'framesequence': 13991, + 'gaze_dir': array([0.98058069, 0.17831698, 0.08163683]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17831698, 0.08163683]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17831698, 0.08163683]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.01190203707665205, + 'timestamp': 57.34143786132336, + 'timestamp_carla': 57341, + 'timestamp_device': 56978, + 'timestamp_stream': 57.34143786132336, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.82630343e-03, -1.83934730e-03, -9.62159634e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.680200576782227, + 'FR_Wheel_Angle': 41.486183166503906, + 'Location': array([ -3.72487974, -23.17823219, 0.17237285]), + 'Rotation': array([-0.06606842, -1.94964623, -0.01495361]), + 'Velocity': array([-0.68626732, -0.25510812, 0.00087808]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0556640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 6.81609344, -1626.35095215, 16.67077637]), + 'frame': 13994, + 'frame_number': 13994, + 'framesequence': 13992, + 'gaze_dir': array([0.98058069, 0.17807141, 0.08217112]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17807141, 0.08217112]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17807141, 0.08217112]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.01190203707665205, + 'timestamp': 57.34512446075678, + 'timestamp_carla': 57345, + 'timestamp_device': 56981, + 'timestamp_stream': 57.34512446075678, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 3.97728616e-03, -4.26721899e-03, -9.66181564e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.683198928833008, + 'FR_Wheel_Angle': 41.49211883544922, + 'Location': array([ -3.75675964, -23.18742561, 0.17240302]), + 'Rotation': array([-0.06616404, -2.38409424, -0.01425171]), + 'Velocity': array([-6.81348622e-01, -2.46686056e-01, 2.20160480e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0562744140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 7.4354248 , -1626.05810547, 16.67016602]), + 'frame': 13995, + 'frame_number': 13995, + 'framesequence': 13993, + 'gaze_dir': array([0.98058069, 0.17774117, 0.08288303]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17774117, 0.08288303]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17774117, 0.08288303]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.01190203707665205, + 'timestamp': 57.34859795868397, + 'timestamp_carla': 57348, + 'timestamp_device': 56985, + 'timestamp_stream': 57.34859795868397, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.40115917e-02, 5.42013021e-03, -9.51702785e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.684106826782227, + 'FR_Wheel_Angle': 41.49470901489258, + 'Location': array([ -3.7869556 , -23.19589233, 0.17243728]), + 'Rotation': array([-0.06619136, -2.79629564, -0.01367187]), + 'Velocity': array([-0.68104386, -0.24118617, 0.00088622]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0572509765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 8.26332855, -1625.67016602, 16.66918945]), + 'frame': 13996, + 'frame_number': 13996, + 'framesequence': 13994, + 'gaze_dir': array([0.98058069, 0.17749186, 0.08341559]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17749186, 0.08341559]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17749186, 0.08341559]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.01190203707665205, + 'timestamp': 57.352098260074854, + 'timestamp_carla': 57352, + 'timestamp_device': 56988, + 'timestamp_stream': 57.352098260074854, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.92100089e-02, 4.19636397e-03, -8.71638203e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68764877319336, + 'FR_Wheel_Angle': 41.502357482910156, + 'Location': array([ -3.82101464, -23.20519066, 0.17247017]), + 'Rotation': array([-0.06619136, -3.25650072, -0.01293945]), + 'Velocity': array([-6.74968183e-01, -2.34136716e-01, 4.80494491e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0579833984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 8.8846817 , -1625.3815918 , 16.66845703]), + 'frame': 13997, + 'frame_number': 13997, + 'framesequence': 13995, + 'gaze_dir': array([0.98058069, 0.17724094, 0.0839474 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17724094, 0.0839474 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17724094, 0.0839474 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.35524696111679, + 'timestamp_carla': 57355, + 'timestamp_device': 56991, + 'timestamp_stream': 57.35524696111679, + 'transform': [array([ 0.00987793, -0.00354858, 0.16484807]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.87570117e-02, 3.54316621e-03, -8.59830284e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.689435958862305, + 'FR_Wheel_Angle': 41.505184173583984, + 'Location': array([ -3.85212326, -23.21343231, 0.17249969]), + 'Rotation': array([-0.06637578, -3.67389035, -0.01208496]), + 'Velocity': array([-6.72597051e-01, -2.28118092e-01, 4.41980344e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.05859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 9.50693512, -1625.0949707 , 16.66796875]), + 'frame': 13998, + 'frame_number': 13998, + 'framesequence': 13996, + 'gaze_dir': array([0.98058069, 0.17681891, 0.08483274]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17681891, 0.08483274]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17681891, 0.08483274]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.3595025613904, + 'timestamp_carla': 57359, + 'timestamp_device': 56996, + 'timestamp_stream': 57.3595025613904, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.01894825, -0.01884026, -9.03760719]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.699947357177734, + 'FR_Wheel_Angle': 41.52418518066406, + 'Location': array([ -3.882617 , -23.22132111, 0.17252235]), + 'Rotation': array([-0.06585668, -4.08313084, -0.01223755]), + 'Velocity': array([-6.46305919e-01, -2.13836417e-01, 5.23376453e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0599365234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 10.54664612, -1624.62084961, 16.66662598]), + 'frame': 13999, + 'frame_number': 13999, + 'framesequence': 13997, + 'gaze_dir': array([0.98058069, 0.17656343, 0.08536319]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17656343, 0.08536319]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17656343, 0.08536319]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.36302665993571, + 'timestamp_carla': 57363, + 'timestamp_device': 56999, + 'timestamp_stream': 57.36302665993571, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02423467, 0.00874517, -8.37378597]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.702009201049805, + 'FR_Wheel_Angle': 41.52714538574219, + 'Location': array([ -3.91004062, -23.22821426, 0.17255165]), + 'Rotation': array([-0.06546053, -4.44967794, -0.01223755]), + 'Velocity': array([-0.64672202, -0.20914713, 0.00072707]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0604248046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 11.17196655, -1624.33886719, 16.66601562]), + 'frame': 14000, + 'frame_number': 14000, + 'framesequence': 13998, + 'gaze_dir': array([0.98058069, 0.17630668, 0.08589222]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17630668, 0.08589222]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17630668, 0.08589222]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.36634996160865, + 'timestamp_carla': 57366, + 'timestamp_device': 57002, + 'timestamp_stream': 57.36634996160865, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.09483290e-03, 2.56182929e-03, -8.98325825e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70519256591797, + 'FR_Wheel_Angle': 41.528377532958984, + 'Location': array([ -3.94250274, -23.23603439, 0.17258742]), + 'Rotation': array([-0.06569958, -4.88983393, -0.01119995]), + 'Velocity': array([-6.40900552e-01, -2.00759441e-01, 4.17618750e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0614013671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 11.79729462, -1624.05908203, 16.66503906]), + 'frame': 14001, + 'frame_number': 14001, + 'framesequence': 13999, + 'gaze_dir': array([0.98058069, 0.17596157, 0.08659703]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17596157, 0.08659703]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17596157, 0.08659703]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.369688760489225, + 'timestamp_carla': 57369, + 'timestamp_device': 57006, + 'timestamp_stream': 57.369688760489225, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01789968, 0.01049568, -8.97711754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70341682434082, + 'FR_Wheel_Angle': 41.526023864746094, + 'Location': array([ -3.97110128, -23.24270248, 0.17262222]), + 'Rotation': array([-0.06616404, -5.27670574, -0.0100708 ]), + 'Velocity': array([-0.64633971, -0.19772527, 0.00073449]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0621337890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 12.63317871, -1623.68859863, 16.66430664]), + 'frame': 14002, + 'frame_number': 14002, + 'framesequence': 14000, + 'gaze_dir': array([0.98058069, 0.17570113, 0.08712424]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17570113, 0.08712424]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17570113, 0.08712424]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.37317106127739, + 'timestamp_carla': 57373, + 'timestamp_device': 57009, + 'timestamp_stream': 57.37317106127739, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.28847629e-03, -5.54754515e-04, -8.77646732e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70806121826172, + 'FR_Wheel_Angle': 41.533111572265625, + 'Location': array([ -4.00176907, -23.24964523, 0.1726487 ]), + 'Rotation': array([-0.06625966, -5.69174528, -0.00933838]), + 'Velocity': array([-0.63708073, -0.19044657, 0.0007904 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0628662109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 13.26045227, -1623.41308594, 16.66369629]), + 'frame': 14003, + 'frame_number': 14003, + 'framesequence': 14001, + 'gaze_dir': array([0.98058069, 0.17535107, 0.08782663]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17535107, 0.08782663]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17535107, 0.08782663]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.3768472597003, + 'timestamp_carla': 57376, + 'timestamp_device': 57013, + 'timestamp_stream': 57.3768472597003, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.02238269e-03, 2.19324930e-03, -8.85470295e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.708778381347656, + 'FR_Wheel_Angle': 41.53485870361328, + 'Location': array([ -4.03089666, -23.25601768, 0.17268085]), + 'Rotation': array([-0.06637578, -6.08414173, -0.00866699]), + 'Velocity': array([-6.36648595e-01, -1.85010493e-01, 5.95693593e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0638427734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 14.09893036, -1623.04846191, 16.66259766]), + 'frame': 14004, + 'frame_number': 14004, + 'framesequence': 14002, + 'gaze_dir': array([0.98058069, 0.17499857, 0.08852694]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17499857, 0.08852694]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17499857, 0.08852694]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.38039856031537, + 'timestamp_carla': 57380, + 'timestamp_device': 57017, + 'timestamp_stream': 57.38039856031537, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.86770521e-02, 3.77626019e-03, -8.05712700e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7097110748291, + 'FR_Wheel_Angle': 41.53883361816406, + 'Location': array([ -4.06219482, -23.26265526, 0.17271465]), + 'Rotation': array([-0.06649872, -6.50229359, -0.0078125 ]), + 'Velocity': array([-6.35995328e-01, -1.81346625e-01, 5.94370358e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0648193359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 14.93803406, -1622.6875 , 16.66174316]), + 'frame': 14005, + 'frame_number': 14005, + 'framesequence': 14003, + 'gaze_dir': array([0.98058069, 0.174732 , 0.08905192]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.174732 , 0.08905192]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.174732 , 0.08905192]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.38404805958271, + 'timestamp_carla': 57384, + 'timestamp_device': 57020, + 'timestamp_stream': 57.38404805958271, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.26560628e-02, -1.53259048e-03, -7.95677614e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71169090270996, + 'FR_Wheel_Angle': 41.54208755493164, + 'Location': array([ -4.09163189, -23.26868629, 0.17274272]), + 'Rotation': array([-0.06656019, -6.89435387, -0.00714111]), + 'Velocity': array([-6.31405413e-01, -1.75704822e-01, 5.66499250e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0657958984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 15.56907654, -1622.4185791 , 16.6607666 ]), + 'frame': 14006, + 'frame_number': 14006, + 'framesequence': 14004, + 'gaze_dir': array([0.98058069, 0.1743746 , 0.08974975]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1743746 , 0.08974975]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1743746 , 0.08974975]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.38758106157184, + 'timestamp_carla': 57387, + 'timestamp_device': 57024, + 'timestamp_stream': 57.38758106157184, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02892897, 0.01546465, -8.22891998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70911979675293, + 'FR_Wheel_Angle': 41.539405822753906, + 'Location': array([ -4.11945105, -23.27418137, 0.17277527]), + 'Rotation': array([-6.66489825e-02, -7.26691294e+00, -6.50024507e-03]), + 'Velocity': array([-0.63961875, -0.1723208 , 0.00079599]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0665283203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 16.4107132 , -1622.06359863, 16.66003418]), + 'frame': 14007, + 'frame_number': 14007, + 'framesequence': 14005, + 'gaze_dir': array([0.98058069, 0.17410436, 0.09027284]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17410436, 0.09027284]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17410436, 0.09027284]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.39119886234403, + 'timestamp_carla': 57391, + 'timestamp_device': 57027, + 'timestamp_stream': 57.39119886234403, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02460999, 0.01166301, -8.12372875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7103328704834, + 'FR_Wheel_Angle': 41.54358673095703, + 'Location': array([ -4.14894438, -23.27980423, 0.17280234]), + 'Rotation': array([-6.68607205e-02, -7.66004229e+00, -5.76782133e-03]), + 'Velocity': array([-0.63798654, -0.16739438, 0.00079066]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0673828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 17.04364777, -1621.79907227, 16.65917969]), + 'frame': 14008, + 'frame_number': 14008, + 'framesequence': 14006, + 'gaze_dir': array([0.98058069, 0.17374209, 0.09096815]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17374209, 0.09096815]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17374209, 0.09096815]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0158693827688694, + 'timestamp': 57.39465546235442, + 'timestamp_carla': 57394, + 'timestamp_device': 57031, + 'timestamp_stream': 57.39465546235442, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02340009, 0.00889425, -8.07633781]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71190643310547, + 'FR_Wheel_Angle': 41.54281997680664, + 'Location': array([ -4.17832708, -23.2851963 , 0.17283081]), + 'Rotation': array([-6.69221878e-02, -8.05088139e+00, -5.15747070e-03]), + 'Velocity': array([-0.63549638, -0.16254517, 0.00083831]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0682373046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 17.88772583, -1621.44995117, 16.6583252 ]), + 'frame': 14009, + 'frame_number': 14009, + 'framesequence': 14007, + 'gaze_dir': array([0.98058069, 0.1734682 , 0.09148934]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1734682 , 0.09148934]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1734682 , 0.09148934]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.39779416099191, + 'timestamp_carla': 57397, + 'timestamp_device': 57034, + 'timestamp_stream': 57.39779416099191, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.27619542e-02, -1.15651102e-03, -7.92787457e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.718042373657227, + 'FR_Wheel_Angle': 41.553199768066406, + 'Location': array([ -4.20780563, -23.29043198, 0.17285797]), + 'Rotation': array([-6.65875077e-02, -8.44281864e+00, -5.09643508e-03]), + 'Velocity': array([-0.62229574, -0.15510386, 0.00096658]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0689697265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 18.52251434, -1621.18994141, 16.65759277]), + 'frame': 14010, + 'frame_number': 14010, + 'framesequence': 14008, + 'gaze_dir': array([0.98058069, 0.1731931 , 0.09200906]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1731931 , 0.09200906]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1731931 , 0.09200906]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.40107785910368, + 'timestamp_carla': 57401, + 'timestamp_device': 57037, + 'timestamp_stream': 57.40107785910368, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02808009, 0.01561045, -8.036726 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71452522277832, + 'FR_Wheel_Angle': 41.54987335205078, + 'Location': array([ -4.23522091, -23.29506302, 0.17289104]), + 'Rotation': array([-6.67719245e-02, -8.80890942e+00, -4.42504836e-03]), + 'Velocity': array([-0.63133836, -0.15189351, 0.00064853]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0699462890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 19.15725708, -1620.93212891, 16.65673828]), + 'frame': 14011, + 'frame_number': 14011, + 'framesequence': 14009, + 'gaze_dir': array([0.98058069, 0.17282352, 0.09270138]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17282352, 0.09270138]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17282352, 0.09270138]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.404431361705065, + 'timestamp_carla': 57404, + 'timestamp_device': 57041, + 'timestamp_stream': 57.404431361705065, + 'transform': [array([ 0.00987808, -0.00354858, 0.16484705]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0250153 , 0.01283376, -8.01681328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71487045288086, + 'FR_Wheel_Angle': 41.548065185546875, + 'Location': array([ -4.26333666, -23.29961586, 0.17292133]), + 'Rotation': array([-6.69904947e-02, -9.18564987e+00, -3.66211007e-03]), + 'Velocity': array([-0.6315484 , -0.14777592, 0.00070507]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.07080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 20.00561523, -1620.59118652, 16.65588379]), + 'frame': 14012, + 'frame_number': 14012, + 'framesequence': 14010, + 'gaze_dir': array([0.98058069, 0.17235813, 0.09356385]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17235813, 0.09356385]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17235813, 0.09356385]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.409671761095524, + 'timestamp_carla': 57409, + 'timestamp_device': 57046, + 'timestamp_stream': 57.409671761095524, + 'transform': [array([ 0.00987823, -0.00354858, 0.16484243]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-8.96225590e-03, 4.76967078e-03, -8.59865189e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.714969635009766, + 'FR_Wheel_Angle': 41.54534149169922, + 'Location': array([ -4.29341221, -23.30428696, 0.17295414]), + 'Rotation': array([-6.72910213e-02, -9.58662224e+00, -2.80761695e-03]), + 'Velocity': array([-0.63218606, -0.14248262, 0.00068891]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.072021484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 21.06692505, -1620.17004395, 16.65454102]), + 'frame': 14013, + 'frame_number': 14013, + 'framesequence': 14011, + 'gaze_dir': array([0.98058069, 0.17207645, 0.09408087]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17207645, 0.09408087]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17207645, 0.09408087]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.41299965977669, + 'timestamp_carla': 57413, + 'timestamp_device': 57049, + 'timestamp_stream': 57.41299965977669, + 'transform': [array([ 0.00987823, -0.00354858, 0.16484243]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.55987533e-03, 2.14681402e-03, -8.58090115e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.715919494628906, + 'FR_Wheel_Angle': 41.5463981628418, + 'Location': array([ -4.3215313 , -23.30846786, 0.1729819 ]), + 'Rotation': array([-6.72910213e-02, -9.96067810e+00, -2.31933594e-03]), + 'Velocity': array([-0.63087368, -0.13789986, 0.00068942]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.072265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 21.70558167, -1619.91967773, 16.65393066]), + 'frame': 14014, + 'frame_number': 14014, + 'framesequence': 14012, + 'gaze_dir': array([0.98058069, 0.17169897, 0.09476805]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17169897, 0.09476805]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17169897, 0.09476805]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.41659105941653, + 'timestamp_carla': 57416, + 'timestamp_device': 57053, + 'timestamp_stream': 57.41659105941653, + 'transform': [array([ 0.00987823, -0.00354858, 0.16484243]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.64977107e-02, 4.63817874e-03, -7.94360590e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.715686798095703, + 'FR_Wheel_Angle': 41.54706954956055, + 'Location': array([ -4.35158539, -23.3127346 , 0.17301276]), + 'Rotation': array([-6.72910213e-02, -1.03595428e+01, -1.73950195e-03]), + 'Velocity': array([-6.32567167e-01, -1.34726003e-01, 5.95173799e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0732421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 22.55711365, -1619.58911133, 16.6529541 ]), + 'frame': 14015, + 'frame_number': 14015, + 'framesequence': 14013, + 'gaze_dir': array([0.98058069, 0.17141367, 0.09528309]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17141367, 0.09528309]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17141367, 0.09528309]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.4198358617723, + 'timestamp_carla': 57419, + 'timestamp_device': 57056, + 'timestamp_stream': 57.4198358617723, + 'transform': [array([ 0.00987823, -0.00354858, 0.16484243]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.51711363e-03, -7.46786781e-03, -7.59180355e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72022819519043, + 'FR_Wheel_Angle': 41.55626678466797, + 'Location': array([ -4.38129663, -23.31679344, 0.17303497]), + 'Rotation': array([-6.69904947e-02, -1.07484598e+01, -1.61743222e-03]), + 'Velocity': array([-6.21868908e-01, -1.28543675e-01, 1.52163499e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.073974609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 23.19747925, -1619.34313965, 16.65222168]), + 'frame': 14016, + 'frame_number': 14016, + 'framesequence': 14014, + 'gaze_dir': array([0.98058069, 0.17112722, 0.09579661]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17112722, 0.09579661]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17112722, 0.09579661]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.42320905998349, + 'timestamp_carla': 57423, + 'timestamp_device': 57059, + 'timestamp_stream': 57.42320905998349, + 'transform': [array([ 0.00987823, -0.00354858, 0.16484243]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.63742639e-02, 4.14557615e-03, -7.81208563e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.720928192138672, + 'FR_Wheel_Angle': 41.558319091796875, + 'Location': array([ -4.40905714, -23.32038307, 0.17306404]), + 'Rotation': array([-6.67719245e-02, -1.11153126e+01, -1.46484340e-03]), + 'Velocity': array([-0.62192827, -0.12412862, 0.00075205]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.07470703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 23.8377533 , -1619.0994873 , 16.65148926]), + 'frame': 14017, + 'frame_number': 14017, + 'framesequence': 14015, + 'gaze_dir': array([0.98058069, 0.1707425 , 0.09648064]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1707425 , 0.09648064]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1707425 , 0.09648064]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.42657046020031, + 'timestamp_carla': 57426, + 'timestamp_device': 57063, + 'timestamp_stream': 57.42657046020031, + 'transform': [array([ 0.00987823, -0.00354858, 0.16484243]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.68530159e-02, 4.05693473e-03, -7.79058743e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.722118377685547, + 'FR_Wheel_Angle': 41.5579833984375, + 'Location': array([ -4.43677807, -23.32376671, 0.17309295]), + 'Rotation': array([-6.67719245e-02, -1.14821653e+01, -1.03759742e-03]), + 'Velocity': array([-0.61992443, -0.11972386, 0.00076725]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0755615234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 24.69340515, -1618.77722168, 16.65063477]), + 'frame': 14018, + 'frame_number': 14018, + 'framesequence': 14016, + 'gaze_dir': array([0.98058069, 0.17035542, 0.09716246]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17035542, 0.09716246]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17035542, 0.09716246]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.4308401606977, + 'timestamp_carla': 57430, + 'timestamp_device': 57067, + 'timestamp_stream': 57.4308401606977, + 'transform': [array([ 0.00987839, -0.00354858, 0.16484137]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.70635717e-03, 3.13993427e-03, -8.41139126e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.721403121948242, + 'FR_Wheel_Angle': 41.557735443115234, + 'Location': array([ -4.46642733, -23.32716751, 0.17312507]), + 'Rotation': array([-6.68333992e-02, -1.18752317e+01, -3.96728166e-04]), + 'Velocity': array([-0.62188107, -0.11435943, 0.00070946]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0765380859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 25.54949951, -1618.45861816, 16.64978027]), + 'frame': 14019, + 'frame_number': 14019, + 'framesequence': 14017, + 'gaze_dir': array([0.98058069, 0.17006296, 0.09767345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17006296, 0.09767345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17006296, 0.09767345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.019836727529764175, + 'timestamp': 57.43408006057143, + 'timestamp_carla': 57434, + 'timestamp_device': 57070, + 'timestamp_stream': 57.43408006057143, + 'transform': [array([ 0.00987839, -0.00354858, 0.16484137]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 2.35617836e-03, -1.66630484e-02, -7.31260824e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.727516174316406, + 'FR_Wheel_Angle': 41.568119049072266, + 'Location': array([ -4.49362659, -23.33013535, 0.17314373]), + 'Rotation': array([-6.66763037e-02, -1.22327147e+01, -1.52587949e-04]), + 'Velocity': array([-6.08761072e-01, -1.10010080e-01, -7.61938063e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0772705078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 26.19325256, -1618.22167969, 16.64892578]), + 'frame': 14020, + 'frame_number': 14020, + 'framesequence': 14018, + 'gaze_dir': array([0.98058069, 0.16967112, 0.09835254]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16967112, 0.09835254]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16967112, 0.09835254]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.027771420776844025, + 'timestamp': 57.43742845952511, + 'timestamp_carla': 57437, + 'timestamp_device': 57074, + 'timestamp_stream': 57.43742845952511, + 'transform': [array([ 0.00987945, -0.00354736, 0.16484213]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.58495635e-03, -1.50445662e-03, -8.24584484e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.727191925048828, + 'FR_Wheel_Angle': 41.565155029296875, + 'Location': array([ -4.52332258, -23.33318329, 0.17317601]), + 'Rotation': array([-6.64030984e-02, -1.26258421e+01, 6.42898594e-05]), + 'Velocity': array([-0.60982007, -0.1039277 , 0.00072069]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 27.05158997, -1617.90905762, 16.64807129]), + 'frame': 14021, + 'frame_number': 14021, + 'framesequence': 14019, + 'gaze_dir': array([0.98058069, 0.16937509, 0.09886149]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16937509, 0.09886149]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16937509, 0.09886149]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.027771420776844025, + 'timestamp': 57.44110506027937, + 'timestamp_carla': 57441, + 'timestamp_device': 57077, + 'timestamp_stream': 57.44110506027937, + 'transform': [array([ 0.00987862, -0.00354858, 0.16484205]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-8.18720646e-03, 3.06139840e-03, -8.19924545e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72723388671875, + 'FR_Wheel_Angle': 41.56657791137695, + 'Location': array([ -4.55119944, -23.33586884, 0.17320472]), + 'Rotation': array([-6.64372444e-02, -1.29904356e+01, 6.35601114e-04]), + 'Velocity': array([-0.61044908, -0.100378 , 0.00088329]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0791015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 27.69703674, -1617.6763916 , 16.6472168 ]), + 'frame': 14022, + 'frame_number': 14022, + 'framesequence': 14020, + 'gaze_dir': array([0.98058069, 0.16897851, 0.09953782]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16897851, 0.09953782]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16897851, 0.09953782]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.027771420776844025, + 'timestamp': 57.44449296221137, + 'timestamp_carla': 57444, + 'timestamp_device': 57081, + 'timestamp_stream': 57.44449296221137, + 'transform': [array([ 0.00987091, -0.00355835, 0.16484258]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.70404017e-02, 5.55751380e-03, -7.56642866e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.727394104003906, + 'FR_Wheel_Angle': 41.567047119140625, + 'Location': array([ -4.57679653, -23.33815193, 0.17323169]), + 'Rotation': array([-6.64987192e-02, -1.33267412e+01, 1.14261208e-03]), + 'Velocity': array([-0.61085504, -0.09760724, 0.00068863]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 28.55744934, -1617.36999512, 16.64624023]), + 'frame': 14023, + 'frame_number': 14023, + 'framesequence': 14021, + 'gaze_dir': array([0.98058069, 0.16867892, 0.10004468]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16867892, 0.10004468]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16867892, 0.10004468]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0317387655377388, + 'timestamp': 57.44787026196718, + 'timestamp_carla': 57447, + 'timestamp_device': 57084, + 'timestamp_stream': 57.44787026196718, + 'transform': [array([ 0.00987091, -0.00355835, 0.16484258]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.40645826e-03, 2.28139828e-03, -8.14140987e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72796058654785, + 'FR_Wheel_Angle': 41.56795883178711, + 'Location': array([ -4.60803413, -23.34072495, 0.17326079]), + 'Rotation': array([-6.65601864e-02, -1.37381191e+01, 1.78297656e-03]), + 'Velocity': array([-0.61083096, -0.09203772, 0.00094992]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.08056640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 29.20367432, -1617.14306641, 16.64575195]), + 'frame': 14024, + 'frame_number': 14024, + 'framesequence': 14022, + 'gaze_dir': array([0.98058069, 0.16827761, 0.10071822]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16827761, 0.10071822]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16827761, 0.10071822]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0317387655377388, + 'timestamp': 57.45203096047044, + 'timestamp_carla': 57452, + 'timestamp_device': 57088, + 'timestamp_stream': 57.45203096047044, + 'transform': [array([ 0.00986076, -0.00357056, 0.16484162]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.62151508e-03, 2.35248520e-03, -8.13208008e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72760581970215, + 'FR_Wheel_Angle': 41.56610870361328, + 'Location': array([ -4.63629246, -23.34283829, 0.17328903]), + 'Rotation': array([-6.65875077e-02, -1.41132383e+01, 2.29191338e-03]), + 'Velocity': array([-0.61128819, -0.08780459, 0.00075917]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0816650390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 30.06628418, -1616.8425293 , 16.64465332]), + 'frame': 14025, + 'frame_number': 14025, + 'framesequence': 14023, + 'gaze_dir': array([0.98058069, 0.16787323, 0.10139079]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16787323, 0.10139079]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16787323, 0.10139079]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.035706110298633575, + 'timestamp': 57.455811358988285, + 'timestamp_carla': 57455, + 'timestamp_device': 57092, + 'timestamp_stream': 57.455811358988285, + 'transform': [array([ 0.00986206, -0.00356934, 0.16484128]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.29495757e-04, -3.81060992e-03, -8.16080379e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.729583740234375, + 'FR_Wheel_Angle': 41.57004165649414, + 'Location': array([ -4.66386271, -23.34473991, 0.17332053]), + 'Rotation': array([-6.64645657e-02, -1.44767933e+01, 2.66073621e-03]), + 'Velocity': array([-0.60710979, -0.08329821, 0.00067989]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.08251953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 30.92990112, -1616.54638672, 16.64379883]), + 'frame': 14026, + 'frame_number': 14026, + 'framesequence': 14024, + 'gaze_dir': array([0.98058069, 0.16746616, 0.10206174]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16746616, 0.10206174]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16746616, 0.10206174]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.035706110298633575, + 'timestamp': 57.459601160138845, + 'timestamp_carla': 57459, + 'timestamp_device': 57096, + 'timestamp_stream': 57.459601160138845, + 'transform': [array([ 0.00985481, -0.00357788, 0.1648412 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.14708862e-03, -1.47586528e-04, -8.16973495e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730443954467773, + 'FR_Wheel_Angle': 41.5722770690918, + 'Location': array([ -4.69126272, -23.34644508, 0.17334957]), + 'Rotation': array([-6.63211346e-02, -1.48398914e+01, 2.94558494e-03]), + 'Velocity': array([-0.60554308, -0.07907689, 0.00069715]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0836181640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 31.79582214, -1616.25231934, 16.6427002 ]), + 'frame': 14027, + 'frame_number': 14027, + 'framesequence': 14025, + 'gaze_dir': array([0.98058069, 0.16715939, 0.10256341]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16715939, 0.10256341]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16715939, 0.10256341]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.035706110298633575, + 'timestamp': 57.462970461696386, + 'timestamp_carla': 57463, + 'timestamp_device': 57099, + 'timestamp_stream': 57.462970461696386, + 'transform': [array([ 0.00985687, -0.00357544, 0.16484162]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0232597 , 0.01434181, -7.65353394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7276611328125, + 'FR_Wheel_Angle': 41.568912506103516, + 'Location': array([ -4.71993065, -23.34805679, 0.17338379]), + 'Rotation': array([-6.63484558e-02, -1.52169056e+01, 3.65964836e-03]), + 'Velocity': array([-0.61296344, -0.07686254, 0.00077125]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.084228515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 32.44462585, -1616.03527832, 16.64196777]), + 'frame': 14028, + 'frame_number': 14028, + 'framesequence': 14026, + 'gaze_dir': array([0.98058069, 0.16685112, 0.10306415]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16685112, 0.10306415]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16685112, 0.10306415]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.043656062334775925, + 'timestamp': 57.466383662074804, + 'timestamp_carla': 57466, + 'timestamp_device': 57102, + 'timestamp_stream': 57.466383662074804, + 'transform': [array([ 0.00985207, -0.00358154, 0.16484208]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.58491991e-02, 5.04360069e-03, -7.56633806e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.728151321411133, + 'FR_Wheel_Angle': 41.56930923461914, + 'Location': array([ -4.74731588, -23.34942055, 0.17341186]), + 'Rotation': array([-6.65601864e-02, -1.55762491e+01, 4.37965384e-03]), + 'Velocity': array([-0.61244267, -0.07354698, 0.00066664]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0850830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 33.09498596, -1615.8190918 , 16.64123535]), + 'frame': 14029, + 'frame_number': 14029, + 'framesequence': 14027, + 'gaze_dir': array([0.98058069, 0.16643736, 0.103731 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16643736, 0.103731 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16643736, 0.103731 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.043656062334775925, + 'timestamp': 57.47017436102033, + 'timestamp_carla': 57470, + 'timestamp_device': 57106, + 'timestamp_stream': 57.47017436102033, + 'transform': [array([ 0.0098568 , -0.00357666, 0.16484174]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.41827721e-03, -4.79324581e-03, -7.43624830e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.729990005493164, + 'FR_Wheel_Angle': 41.572853088378906, + 'Location': array([ -4.77473783, -23.35061455, 0.17343852]), + 'Rotation': array([-6.64987192e-02, -1.59369345e+01, 4.75506671e-03]), + 'Velocity': array([-6.08545959e-01, -6.93917274e-02, 4.78150847e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0860595703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 33.96321869, -1615.53442383, 16.64038086]), + 'frame': 14030, + 'frame_number': 14030, + 'framesequence': 14028, + 'gaze_dir': array([0.98058069, 0.16602093, 0.10439618]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16602093, 0.10439618]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16602093, 0.10439618]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.043656062334775925, + 'timestamp': 57.473767559975386, + 'timestamp_carla': 57473, + 'timestamp_device': 57110, + 'timestamp_stream': 57.473767559975386, + 'transform': [array([ 0.0098529 , -0.00358154, 0.16484189]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.39992021e-03, -9.09833703e-03, -8.21124268e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730743408203125, + 'FR_Wheel_Angle': 41.572776794433594, + 'Location': array([ -4.80420732, -23.35169792, 0.17346705]), + 'Rotation': array([-6.64030984e-02, -1.63256664e+01, 5.03137847e-03]), + 'Velocity': array([-6.06639028e-01, -6.31766692e-02, 2.41184229e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0870361328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 34.83354187, -1615.25219727, 16.63928223]), + 'frame': 14031, + 'frame_number': 14031, + 'framesequence': 14029, + 'gaze_dir': array([0.98058069, 0.16560225, 0.10505906]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16560225, 0.10505906]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16560225, 0.10505906]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.051590751856565475, + 'timestamp': 57.47739056125283, + 'timestamp_carla': 57477, + 'timestamp_device': 57114, + 'timestamp_stream': 57.47739056125283, + 'transform': [array([ 0.00985786, -0.00357666, 0.16484186]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01393186, -0.0082228 , -7.3158536 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.735206604003906, + 'FR_Wheel_Angle': 41.58203125, + 'Location': array([ -4.83056831, -23.35250282, 0.17348373]), + 'Rotation': array([-6.59796223e-02, -1.66746330e+01, 4.94920136e-03]), + 'Velocity': array([-0.59725153, -0.06160536, 0.00062437]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.087890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 35.70328522, -1614.97473145, 16.6385498 ]), + 'frame': 14032, + 'frame_number': 14032, + 'framesequence': 14030, + 'gaze_dir': array([0.98058069, 0.16518052, 0.1057209 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16518052, 0.1057209 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16518052, 0.1057209 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.051590751856565475, + 'timestamp': 57.48122366145253, + 'timestamp_carla': 57481, + 'timestamp_device': 57118, + 'timestamp_stream': 57.48122366145253, + 'transform': [array([ 0.00985359, -0.00358276, 0.16484159]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0186172 , 0.00778073, -7.43315172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.733659744262695, + 'FR_Wheel_Angle': 41.57781982421875, + 'Location': array([ -4.85746527, -23.35316849, 0.17351474]), + 'Rotation': array([-6.58566803e-02, -1.70271721e+01, 5.21224923e-03]), + 'Velocity': array([-0.600784 , -0.05648839, 0.00082215]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0889892578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 36.57585144, -1614.69946289, 16.63745117]), + 'frame': 14033, + 'frame_number': 14033, + 'framesequence': 14031, + 'gaze_dir': array([0.98058069, 0.16486278, 0.1062157 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16486278, 0.1062157 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16486278, 0.1062157 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.051590751856565475, + 'timestamp': 57.484913159161806, + 'timestamp_carla': 57484, + 'timestamp_device': 57121, + 'timestamp_stream': 57.484913159161806, + 'transform': [array([ 0.00985886, -0.00357666, 0.1648414 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01256026, 0.01064664, -8.05454254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731801986694336, + 'FR_Wheel_Angle': 41.572818756103516, + 'Location': array([ -4.88588858, -23.35367393, 0.17354946]), + 'Rotation': array([-6.60410970e-02, -1.74012871e+01, 5.93004562e-03]), + 'Velocity': array([-0.60515678, -0.05151645, 0.00081918]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.089599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 37.22960663, -1614.49645996, 16.63684082]), + 'frame': 14034, + 'frame_number': 14034, + 'framesequence': 14032, + 'gaze_dir': array([0.98058069, 0.16443644, 0.10687456]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16443644, 0.10687456]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16443644, 0.10687456]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.05555810034275055, + 'timestamp': 57.488350961357355, + 'timestamp_carla': 57488, + 'timestamp_device': 57125, + 'timestamp_stream': 57.488350961357355, + 'transform': [array([ 0.00985596, -0.00358032, 0.16484179]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.84686252e-03, 1.52225082e-03, -8.09134197e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731529235839844, + 'FR_Wheel_Angle': 41.57271194458008, + 'Location': array([ -4.91314745, -23.35399055, 0.17357773]), + 'Rotation': array([-6.62596598e-02, -1.77581902e+01, 6.73164008e-03]), + 'Velocity': array([-0.60625148, -0.0482092 , 0.00072858]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.090576171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 38.1040802 , -1614.22717285, 16.63586426]), + 'frame': 14035, + 'frame_number': 14035, + 'framesequence': 14033, + 'gaze_dir': array([0.98058069, 0.16411525, 0.10736712]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16411525, 0.10736712]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16411525, 0.10736712]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.05555810034275055, + 'timestamp': 57.49223206192255, + 'timestamp_carla': 57492, + 'timestamp_device': 57128, + 'timestamp_stream': 57.49223206192255, + 'transform': [array([ 0.00986259, -0.003573 , 0.1648412 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-9.52512841e-04, -2.92109419e-03, -8.12389183e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731571197509766, + 'FR_Wheel_Angle': 41.57475280761719, + 'Location': array([ -4.93982744, -23.35412598, 0.17360722]), + 'Rotation': array([-6.62596598e-02, -1.81099644e+01, 7.19731301e-03]), + 'Velocity': array([-0.60641479, -0.04440998, 0.00061384]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.09130859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 38.75935364, -1614.02856445, 16.63513184]), + 'frame': 14036, + 'frame_number': 14036, + 'framesequence': 14034, + 'gaze_dir': array([0.98058069, 0.16368429, 0.10802298]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16368429, 0.10802298]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16368429, 0.10802298]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.05555810034275055, + 'timestamp': 57.495611261576414, + 'timestamp_carla': 57495, + 'timestamp_device': 57132, + 'timestamp_stream': 57.495611261576414, + 'transform': [array([ 0.00986031, -0.00357666, 0.16484171]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02236938, -0.02405069, -8.2108326 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.735456466674805, + 'FR_Wheel_Angle': 41.58564376831055, + 'Location': array([ -4.96921206, -23.35411072, 0.17362174]), + 'Rotation': array([-6.58225268e-02, -1.84960079e+01, 6.98955171e-03]), + 'Velocity': array([-0.59083503, -0.03854239, -0.00098898]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.09228515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 39.63587952, -1613.76525879, 16.63415527]), + 'frame': 14037, + 'frame_number': 14037, + 'framesequence': 14035, + 'gaze_dir': array([0.98058069, 0.16325113, 0.1086765 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16325113, 0.1086765 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16325113, 0.1086765 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0634927898645401, + 'timestamp': 57.499551959335804, + 'timestamp_carla': 57499, + 'timestamp_device': 57136, + 'timestamp_stream': 57.499551959335804, + 'transform': [array([ 0.00986702, -0.00356934, 0.16484103]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.09336917e-03, 1.32407155e-03, -7.97691679e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73525619506836, + 'FR_Wheel_Angle': 41.58141326904297, + 'Location': array([ -4.99626255, -23.35393715, 0.17365544]), + 'Rotation': array([-6.57952055e-02, -1.88486671e+01, 7.35384319e-03]), + 'Velocity': array([-0.59729916, -0.03587108, 0.000801 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.09326171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 40.5116806 , -1613.50683594, 16.63317871]), + 'frame': 14038, + 'frame_number': 14038, + 'framesequence': 14036, + 'gaze_dir': array([0.98058069, 0.16292413, 0.10916612]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16292413, 0.10916612]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16292413, 0.10916612]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0634927898645401, + 'timestamp': 57.50330176204443, + 'timestamp_carla': 57503, + 'timestamp_device': 57139, + 'timestamp_stream': 57.50330176204443, + 'transform': [array([ 0.00986336, -0.00357422, 0.16484091]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-8.74241162e-03, 5.99788129e-03, -8.01963902e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.734130859375, + 'FR_Wheel_Angle': 41.57851791381836, + 'Location': array([ -5.02247715, -23.35357094, 0.17368838]), + 'Rotation': array([-6.58566803e-02, -1.91942158e+01, 7.95487687e-03]), + 'Velocity': array([-0.60091007, -0.03239973, 0.00080567]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0941162109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 41.17088699, -1613.31396484, 16.63232422]), + 'frame': 14039, + 'frame_number': 14039, + 'framesequence': 14037, + 'gaze_dir': array([0.98058069, 0.1624864 , 0.10981658]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1624864 , 0.10981658]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1624864 , 0.10981658]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0634927898645401, + 'timestamp': 57.506951458752155, + 'timestamp_carla': 57506, + 'timestamp_device': 57143, + 'timestamp_stream': 57.506951458752155, + 'transform': [array([ 0.00986786, -0.00356934, 0.16484086]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 4.46223933e-03, -9.18538403e-03, -8.00978851e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73650550842285, + 'FR_Wheel_Angle': 41.58244705200195, + 'Location': array([ -5.04963541, -23.35303879, 0.17371628]), + 'Rotation': array([-6.58840016e-02, -1.95509644e+01, 8.42756126e-03]), + 'Velocity': array([-5.95466554e-01, -2.86136307e-02, 3.96256451e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.09521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 42.04834747, -1613.06176758, 16.63122559]), + 'frame': 14040, + 'frame_number': 14040, + 'framesequence': 14038, + 'gaze_dir': array([0.98058069, 0.16204567, 0.11046591]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16204567, 0.11046591]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16204567, 0.11046591]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.07539482414722443, + 'timestamp': 57.51101205870509, + 'timestamp_carla': 57511, + 'timestamp_device': 57147, + 'timestamp_stream': 57.51101205870509, + 'transform': [array([ 0.00986168, -0.00357666, 0.16484022]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 3.43087665e-03, -1.02896830e-02, -7.85561085e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.739948272705078, + 'FR_Wheel_Angle': 41.588558197021484, + 'Location': array([ -5.07647038, -23.35237312, 0.1737421 ]), + 'Rotation': array([-6.55561537e-02, -1.99026775e+01, 8.37598369e-03]), + 'Velocity': array([-0.58743423, -0.02488284, 0.00063151]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.095947265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 42.92848969, -1612.81201172, 16.63061523]), + 'frame': 14041, + 'frame_number': 14041, + 'framesequence': 14039, + 'gaze_dir': array([0.98058069, 0.16160275, 0.11111285]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16160275, 0.11111285]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16160275, 0.11111285]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.07539482414722443, + 'timestamp': 57.51474805921316, + 'timestamp_carla': 57514, + 'timestamp_device': 57151, + 'timestamp_stream': 57.51474805921316, + 'transform': [array([ 0.00986534, -0.003573 , 0.1648401 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.83235055e-03, -2.28091818e-03, -7.79945230e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.741483688354492, + 'FR_Wheel_Angle': 41.59133529663086, + 'Location': array([ -5.10264874, -23.35154724, 0.17376827]), + 'Rotation': array([-6.52419627e-02, -2.02470055e+01, 8.42375867e-03]), + 'Velocity': array([-0.58374453, -0.02088617, 0.00069356]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0970458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 43.8076973 , -1612.56713867, 16.62939453]), + 'frame': 14042, + 'frame_number': 14042, + 'framesequence': 14040, + 'gaze_dir': array([0.98058069, 0.16126844, 0.1115975 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16126844, 0.1115975 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16126844, 0.1115975 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0793621763586998, + 'timestamp': 57.518295262008905, + 'timestamp_carla': 57518, + 'timestamp_device': 57154, + 'timestamp_stream': 57.518295262008905, + 'transform': [array([ 0.00986031, -0.0035791 , 0.16484044]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.23951803e-03, -2.55990587e-03, -7.76003981e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742874145507812, + 'FR_Wheel_Angle': 41.59182357788086, + 'Location': array([ -5.12922668, -23.35054588, 0.17379345]), + 'Rotation': array([-6.52146414e-02, -2.05957584e+01, 8.83819815e-03]), + 'Velocity': array([-0.58061659, -0.01748878, 0.00069994]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0975341796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 44.46942902, -1612.38464355, 16.62878418]), + 'frame': 14043, + 'frame_number': 14043, + 'framesequence': 14041, + 'gaze_dir': array([0.98058069, 0.16082101, 0.11224134]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16082101, 0.11224134]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16082101, 0.11224134]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0793621763586998, + 'timestamp': 57.52175835892558, + 'timestamp_carla': 57521, + 'timestamp_device': 57158, + 'timestamp_stream': 57.52175835892558, + 'transform': [array([ 0.00986328, -0.00357666, 0.16484071]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01943369, 0.01183183, -7.19521618]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.740238189697266, + 'FR_Wheel_Angle': 41.5897216796875, + 'Location': array([ -5.15699768, -23.34932518, 0.17382514]), + 'Rotation': array([-6.53375834e-02, -2.09587002e+01, 9.62303951e-03]), + 'Velocity': array([-0.58744216, -0.01492663, 0.0006857 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0987548828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 45.35044479, -1612.14575195, 16.62768555]), + 'frame': 14044, + 'frame_number': 14044, + 'framesequence': 14042, + 'gaze_dir': array([0.98058069, 0.16037057, 0.11288399]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16037057, 0.11288399]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16037057, 0.11288399]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0793621763586998, + 'timestamp': 57.52626026049256, + 'timestamp_carla': 57526, + 'timestamp_device': 57162, + 'timestamp_stream': 57.52626026049256, + 'transform': [array([ 0.00985397, -0.00358765, 0.16483895]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 5.33081917e-03, 1.44945560e-02, -7.35367918e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.736225128173828, + 'FR_Wheel_Angle': 41.58515548706055, + 'Location': array([ -5.18416119, -23.34788704, 0.1738425 ]), + 'Rotation': array([-6.54946789e-02, -2.13209438e+01, 1.00895884e-02]), + 'Velocity': array([-0.5948745 , -0.0054407 , 0.00104156]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.0994873046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 46.23409271, -1611.90942383, 16.6270752 ]), + 'frame': 14045, + 'frame_number': 14045, + 'framesequence': 14043, + 'gaze_dir': array([0.98058069, 0.15991758, 0.11352481]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15991758, 0.11352481]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15991758, 0.11352481]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.08729686588048935, + 'timestamp': 57.529930759221315, + 'timestamp_carla': 57529, + 'timestamp_device': 57166, + 'timestamp_stream': 57.529930759221315, + 'transform': [array([ 0.00985641, -0.0035852 , 0.164839 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03584018, -0.01116689, -7.43547392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.748249053955078, + 'FR_Wheel_Angle': 41.603328704833984, + 'Location': array([ -5.21055841, -23.34646225, 0.17386752]), + 'Rotation': array([-6.52146414e-02, -2.16636524e+01, 1.04986336e-02]), + 'Velocity': array([-5.70886612e-01, -1.40910977e-02, 5.02119074e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1007080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 47.11739349, -1611.67785645, 16.62561035]), + 'frame': 14046, + 'frame_number': 14046, + 'framesequence': 14044, + 'gaze_dir': array([0.98058069, 0.15957646, 0.1140038 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15957646, 0.1140038 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15957646, 0.1140038 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.08729686588048935, + 'timestamp': 57.53332486003637, + 'timestamp_carla': 57533, + 'timestamp_device': 57169, + 'timestamp_stream': 57.53332486003637, + 'transform': [array([ 0.00985138, -0.00359131, 0.16483961]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03452756, -0.03081949, -6.79987001]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7547664642334, + 'FR_Wheel_Angle': 41.61631393432617, + 'Location': array([ -5.23516083, -23.34501839, 0.17389137]), + 'Rotation': array([-6.42379224e-02, -2.19825897e+01, 9.61641595e-03]), + 'Velocity': array([-0.55140322, -0.00131807, 0.0008197 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.101318359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 47.78083038, -1611.50561523, 16.62512207]), + 'frame': 14047, + 'frame_number': 14047, + 'framesequence': 14045, + 'gaze_dir': array([0.98058069, 0.15911898, 0.11464144]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15911898, 0.11464144]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15911898, 0.11464144]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.08729686588048935, + 'timestamp': 57.53661726042628, + 'timestamp_carla': 57536, + 'timestamp_device': 57173, + 'timestamp_stream': 57.53661726042628, + 'transform': [array([ 0.00985413, -0.00358887, 0.16484018]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00745142, 0.00921478, -6.98425627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.749332427978516, + 'FR_Wheel_Angle': 41.60594177246094, + 'Location': array([ -5.26059198, -23.34336662, 0.17392379]), + 'Rotation': array([-6.42379224e-02, -2.23131542e+01, 1.02944151e-02]), + 'Velocity': array([-0.56429845, 0.00235311, 0.00082573]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1024169921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 48.66618729, -1611.27978516, 16.62414551]), + 'frame': 14048, + 'frame_number': 14048, + 'framesequence': 14046, + 'gaze_dir': array([0.98058069, 0.15877454, 0.11511802]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15877454, 0.11511802]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15877454, 0.11511802]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0952315554022789, + 'timestamp': 57.54017096012831, + 'timestamp_carla': 57540, + 'timestamp_device': 57176, + 'timestamp_stream': 57.54017096012831, + 'transform': [array([ 0.00984909, -0.00359497, 0.16484052]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.04943036, -0.02445808, -6.69507217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.751361846923828, + 'FR_Wheel_Angle': 41.60919952392578, + 'Location': array([ -5.28708553, -23.34148216, 0.17395233]), + 'Rotation': array([-6.4606756e-02, -2.2656168e+01, 1.1094301e-02]), + 'Velocity': array([-5.56789100e-01, 8.09393357e-03, 3.45706940e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.10302734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 49.33082581, -1611.11218262, 16.62341309]), + 'frame': 14049, + 'frame_number': 14049, + 'framesequence': 14047, + 'gaze_dir': array([0.98058069, 0.1583126 , 0.11575245]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1583126 , 0.11575245]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1583126 , 0.11575245]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0952315554022789, + 'timestamp': 57.54387865960598, + 'timestamp_carla': 57543, + 'timestamp_device': 57180, + 'timestamp_stream': 57.54387865960598, + 'transform': [array([ 0.00985336, -0.00359009, 0.16484042]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03449083, -0.0097529 , -6.99598885]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.763809204101562, + 'FR_Wheel_Angle': 41.62877655029297, + 'Location': array([ -5.310256 , -23.33978271, 0.17395602]), + 'Rotation': array([-6.39032498e-02, -2.29568920e+01, 1.07536791e-02]), + 'Velocity': array([-0.53394145, -0.00257487, 0.00084138]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.10400390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 50.21776581, -1610.89257812, 16.62255859]), + 'frame': 14050, + 'frame_number': 14050, + 'framesequence': 14048, + 'gaze_dir': array([0.98058069, 0.1578486 , 0.11638443]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1578486 , 0.11638443]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1578486 , 0.11638443]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0952315554022789, + 'timestamp': 57.54801996052265, + 'timestamp_carla': 57548, + 'timestamp_device': 57184, + 'timestamp_stream': 57.54801996052265, + 'transform': [array([ 0.00984695, -0.00359863, 0.16483957]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.61946858e-02, 5.63427527e-03, -6.85633755e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.767948150634766, + 'FR_Wheel_Angle': 41.63338851928711, + 'Location': array([ -5.33571577, -23.33775139, 0.17398925]), + 'Rotation': array([-6.32953569e-02, -2.32888260e+01, 1.04978522e-02]), + 'Velocity': array([-0.52335221, 0.00180444, 0.000913 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1051025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 51.10564423, -1610.67565918, 16.62145996]), + 'frame': 14051, + 'frame_number': 14051, + 'framesequence': 14049, + 'gaze_dir': array([0.98058069, 0.15738159, 0.11701515]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15738159, 0.11701515]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15738159, 0.11701515]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0952315554022789, + 'timestamp': 57.55159205943346, + 'timestamp_carla': 57551, + 'timestamp_device': 57188, + 'timestamp_stream': 57.55159205943346, + 'transform': [array([ 0.00985062, -0.00359497, 0.16483976]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.05640236, 0.03799302, -6.97479725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.763429641723633, + 'FR_Wheel_Angle': 41.62594223022461, + 'Location': array([ -5.35930634, -23.33572006, 0.17402534]), + 'Rotation': array([-6.35070950e-02, -2.35971165e+01, 1.13238906e-02]), + 'Velocity': array([-0.5339734 , 0.00543935, 0.00073619]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1060791015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 51.99419022, -1610.46337891, 16.6204834 ]), + 'frame': 14052, + 'frame_number': 14052, + 'framesequence': 14050, + 'gaze_dir': array([0.98058069, 0.15703005, 0.1174865 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15703005, 0.1174865 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15703005, 0.1174865 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0952315554022789, + 'timestamp': 57.55512876063585, + 'timestamp_carla': 57555, + 'timestamp_device': 57191, + 'timestamp_stream': 57.55512876063585, + 'transform': [array([ 0.00984619, -0.00360107, 0.16484015]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.06743772, 0.03314247, -7.09331989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76177978515625, + 'FR_Wheel_Angle': 41.62598419189453, + 'Location': array([ -5.3846488 , -23.33336639, 0.17405407]), + 'Rotation': array([-6.42379224e-02, -2.39266758e+01, 1.28029156e-02]), + 'Velocity': array([-5.39082646e-01, 5.98258665e-03, -1.35989190e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.106689453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 52.66134644, -1610.30566406, 16.61987305]), + 'frame': 14053, + 'frame_number': 14053, + 'framesequence': 14051, + 'gaze_dir': array([0.98058069, 0.15655865, 0.11811394]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15655865, 0.11811394]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15655865, 0.11811394]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.55894336104393, + 'timestamp_carla': 57558, + 'timestamp_device': 57195, + 'timestamp_stream': 57.55894336104393, + 'transform': [array([ 0.00985138, -0.00359497, 0.16483988]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.04471839, 0.02953777, -7.01733875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76129150390625, + 'FR_Wheel_Angle': 41.62346267700195, + 'Location': array([ -5.40867519, -23.33102226, 0.17408469]), + 'Rotation': array([-6.43608719e-02, -2.42412491e+01, 1.31844701e-02]), + 'Velocity': array([-0.53864938, 0.01246413, 0.00071162]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.107666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 53.55155563, -1610.09936523, 16.61901855]), + 'frame': 14054, + 'frame_number': 14054, + 'framesequence': 14052, + 'gaze_dir': array([0.98058069, 0.15608521, 0.11873888]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15608521, 0.11873888]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15608521, 0.11873888]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.56286945939064, + 'timestamp_carla': 57562, + 'timestamp_device': 57199, + 'timestamp_stream': 57.56286945939064, + 'transform': [array([ 0.00984642, -0.00360107, 0.16483954]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03156751, 0.01239837, -6.96423769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.763368606567383, + 'FR_Wheel_Angle': 41.627098083496094, + 'Location': array([ -5.43346405, -23.32848358, 0.17411044]), + 'Rotation': array([-6.45452812e-02, -2.45670509e+01, 1.39806308e-02]), + 'Velocity': array([-0.53395277, 0.01450134, 0.00069834]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.108642578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 54.44266891, -1609.89562988, 16.61791992]), + 'frame': 14055, + 'frame_number': 14055, + 'framesequence': 14053, + 'gaze_dir': array([0.98058069, 0.1556088 , 0.11936253]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1556088 , 0.11936253]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1556088 , 0.11936253]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.56664425879717, + 'timestamp_carla': 57566, + 'timestamp_device': 57203, + 'timestamp_stream': 57.56664425879717, + 'transform': [array([ 0.00985146, -0.00359619, 0.16483937]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.06110682, 0.05818792, -7.2094779 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754711151123047, + 'FR_Wheel_Angle': 41.61338424682617, + 'Location': array([ -5.45797348, -23.32578278, 0.17413612]), + 'Rotation': array([-6.47296980e-02, -2.48862972e+01, 1.43089006e-02]), + 'Velocity': array([-0.55351907, 0.02100688, 0.00089687]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.109619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 55.33446121, -1609.6965332 , 16.61706543]), + 'frame': 14056, + 'frame_number': 14056, + 'framesequence': 14054, + 'gaze_dir': array([0.98058069, 0.15525022, 0.11982856]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15525022, 0.11982856]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15525022, 0.11982856]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.570306561887264, + 'timestamp_carla': 57570, + 'timestamp_device': 57206, + 'timestamp_stream': 57.570306561887264, + 'transform': [array([ 0.00984741, -0.00360107, 0.16483954]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.04627825, 0.02637351, -7.2132268 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754898071289062, + 'FR_Wheel_Angle': 41.61501693725586, + 'Location': array([ -5.48267984, -23.32291603, 0.17416881]), + 'Rotation': array([-6.53375834e-02, -2.52085018e+01, 1.56175522e-02]), + 'Velocity': array([-0.55261934, 0.02174914, 0.00071269]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1103515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 56.00403976, -1609.54870605, 16.61621094]), + 'frame': 14057, + 'frame_number': 14057, + 'framesequence': 14055, + 'gaze_dir': array([0.98058069, 0.15476947, 0.12044885]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15476947, 0.12044885]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15476947, 0.12044885]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.57400755956769, + 'timestamp_carla': 57574, + 'timestamp_device': 57210, + 'timestamp_stream': 57.57400755956769, + 'transform': [array([ 0.00985237, -0.00359619, 0.16483949]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.04416543, -0.02525139, -6.63044357]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.756193161010742, + 'FR_Wheel_Angle': 41.61806869506836, + 'Location': array([ -5.50550938, -23.32013321, 0.17419307]), + 'Rotation': array([-6.53034374e-02, -2.55065384e+01, 1.58319399e-02]), + 'Velocity': array([-5.45989692e-01, 3.45607847e-02, 1.50856969e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1112060546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 56.89728928, -1609.35571289, 16.61547852]), + 'frame': 14058, + 'frame_number': 14058, + 'framesequence': 14056, + 'gaze_dir': array([0.98058069, 0.15428624, 0.1210672 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15428624, 0.1210672 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15428624, 0.1210672 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.57779736071825, + 'timestamp_carla': 57577, + 'timestamp_device': 57214, + 'timestamp_stream': 57.57779736071825, + 'transform': [array([ 0.00984772, -0.00360229, 0.16483946]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03934574, 0.01483992, -7.18300486]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75611114501953, + 'FR_Wheel_Angle': 41.61404037475586, + 'Location': array([ -5.53202724, -23.31678963, 0.17422126]), + 'Rotation': array([-6.51531741e-02, -2.58538589e+01, 1.62273999e-02]), + 'Velocity': array([-0.55085021, 0.02781918, 0.00066674]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1124267578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 57.79218674, -1609.1652832 , 16.61437988]), + 'frame': 14059, + 'frame_number': 14059, + 'framesequence': 14057, + 'gaze_dir': array([0.98058069, 0.15380101, 0.12168305]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15380101, 0.12168305]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15380101, 0.12168305]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.58146595954895, + 'timestamp_carla': 57581, + 'timestamp_device': 57218, + 'timestamp_stream': 57.58146595954895, + 'transform': [array([ 0.00985222, -0.00359741, 0.16483949]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0402615 , 0.01940178, -7.2804594 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754131317138672, + 'FR_Wheel_Angle': 41.611724853515625, + 'Location': array([ -5.55601835, -23.31363297, 0.17424877]), + 'Rotation': array([-6.51804954e-02, -2.61699944e+01, 1.67560764e-02]), + 'Velocity': array([-0.55558908, 0.03090297, 0.00071048]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1134033203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 58.68604279, -1608.97973633, 16.61328125]), + 'frame': 14060, + 'frame_number': 14060, + 'framesequence': 14058, + 'gaze_dir': array([0.98058069, 0.15343501, 0.12214424]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15343501, 0.12214424]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15343501, 0.12214424]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.584946759045124, + 'timestamp_carla': 57584, + 'timestamp_device': 57221, + 'timestamp_stream': 57.584946759045124, + 'transform': [array([ 0.0098481 , -0.00360229, 0.16483998]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02524126, -0.01442022, -6.79354048]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.756271362304688, + 'FR_Wheel_Angle': 41.614830017089844, + 'Location': array([ -5.58265018, -23.30994797, 0.17427455]), + 'Rotation': array([-6.48526400e-02, -2.65193901e+01, 1.66409537e-02]), + 'Velocity': array([-0.54828995, 0.0423427 , 0.00061561]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1142578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 59.35855103, -1608.8416748 , 16.61254883]), + 'frame': 14061, + 'frame_number': 14061, + 'framesequence': 14059, + 'gaze_dir': array([0.98058069, 0.15294546, 0.12275666]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15294546, 0.12275666]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15294546, 0.12275666]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.58824336156249, + 'timestamp_carla': 57588, + 'timestamp_device': 57225, + 'timestamp_stream': 57.58824336156249, + 'transform': [array([ 0.0098513 , -0.00359863, 0.16484052]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.72712016e-02, 3.97458294e-04, -7.13282204e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.760387420654297, + 'FR_Wheel_Angle': 41.62340545654297, + 'Location': array([ -5.60580778, -23.30665016, 0.1742934 ]), + 'Rotation': array([-6.45726025e-02, -2.68260937e+01, 1.68625247e-02]), + 'Velocity': array([-5.41066468e-01, 3.42795029e-02, 2.02260009e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.114990234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 60.25376129, -1608.66235352, 16.61181641]), + 'frame': 14062, + 'frame_number': 14062, + 'framesequence': 14060, + 'gaze_dir': array([0.98058069, 0.15245302, 0.1233677 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15245302, 0.1233677 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15245302, 0.1233677 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.59251996129751, + 'timestamp_carla': 57592, + 'timestamp_device': 57229, + 'timestamp_stream': 57.59251996129751, + 'transform': [array([ 0.00984337, -0.0036084 , 0.16483942]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.05801032, -0.05826799, -6.16408348]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.771650314331055, + 'FR_Wheel_Angle': 41.64408493041992, + 'Location': array([ -5.62994003, -23.30305672, 0.17430457]), + 'Rotation': array([-6.33909851e-02, -2.71427116e+01, 1.54084805e-02]), + 'Velocity': array([-5.08052409e-01, 4.62010615e-02, 3.27348709e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1158447265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 61.15123367, -1608.48547363, 16.61096191]), + 'frame': 14063, + 'frame_number': 14063, + 'framesequence': 14061, + 'gaze_dir': array([0.98058069, 0.15208243, 0.12382427]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15208243, 0.12382427]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15208243, 0.12382427]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.596342261880636, + 'timestamp_carla': 57596, + 'timestamp_device': 57232, + 'timestamp_stream': 57.596342261880636, + 'transform': [array([ 0.00984673, -0.00360474, 0.16483919]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.83855572e-02, -3.16693308e-03, -6.51084852e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.778411865234375, + 'FR_Wheel_Angle': 41.651145935058594, + 'Location': array([ -5.65206575, -23.29969978, 0.17432277]), + 'Rotation': array([-6.24074340e-02, -2.74352894e+01, 1.49012357e-02]), + 'Velocity': array([-0.49662673, 0.03759343, 0.00084076]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1165771484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 61.82314682, -1608.35656738, 16.61022949]), + 'frame': 14064, + 'frame_number': 14064, + 'framesequence': 14062, + 'gaze_dir': array([0.98058069, 0.15158571, 0.12443185]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15158571, 0.12443185]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15158571, 0.12443185]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.600062660872936, + 'timestamp_carla': 57600, + 'timestamp_device': 57236, + 'timestamp_stream': 57.600062660872936, + 'transform': [array([ 0.00984062, -0.00361206, 0.1648393 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.05243077, 0.03913471, -6.67753553]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77315902709961, + 'FR_Wheel_Angle': 41.642337799072266, + 'Location': array([ -5.67440701, -23.29611588, 0.17435379]), + 'Rotation': array([-6.25030547e-02, -2.77289658e+01, 1.55324163e-02]), + 'Velocity': array([-0.50853723, 0.04229537, 0.00068058]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1175537109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 62.72186661, -1608.18603516, 16.60913086]), + 'frame': 14065, + 'frame_number': 14065, + 'framesequence': 14063, + 'gaze_dir': array([0.98058069, 0.15108705, 0.12503685]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15108705, 0.12503685]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15108705, 0.12503685]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.60344396159053, + 'timestamp_carla': 57603, + 'timestamp_device': 57240, + 'timestamp_stream': 57.60344396159053, + 'transform': [array([ 0.00984299, -0.00360962, 0.1648398 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 5.13494806e-03, 2.24233158e-02, -6.49157763e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.764923095703125, + 'FR_Wheel_Angle': 41.631778717041016, + 'Location': array([ -5.69851685, -23.29208183, 0.17438984]), + 'Rotation': array([-6.34183064e-02, -2.80451260e+01, 1.71292853e-02]), + 'Velocity': array([-0.52362794, 0.05540584, 0.00059712]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1185302734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 63.61944962, -1608.02026367, 16.6081543 ]), + 'frame': 14066, + 'frame_number': 14066, + 'framesequence': 14064, + 'gaze_dir': array([0.98058069, 0.15071099, 0.12548988]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15071099, 0.12548988]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15071099, 0.12548988]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.607204761356115, + 'timestamp_carla': 57607, + 'timestamp_device': 57243, + 'timestamp_stream': 57.607204761356115, + 'transform': [array([ 0.00983604, -0.00361816, 0.16483983]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02788062, -0.00951643, -6.52595806]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.763952255249023, + 'FR_Wheel_Angle': 41.630680084228516, + 'Location': array([ -5.7221384 , -23.28805351, 0.17441711]), + 'Rotation': array([-6.41559660e-02, -2.83578110e+01, 1.87094621e-02]), + 'Velocity': array([-0.52613515, 0.05758421, 0.00060925]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1192626953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 64.2946167 , -1607.89746094, 16.60754395]), + 'frame': 14067, + 'frame_number': 14067, + 'framesequence': 14065, + 'gaze_dir': array([0.98058069, 0.15020812, 0.12609139]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15020812, 0.12609139]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15020812, 0.12609139]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.61086506024003, + 'timestamp_carla': 57610, + 'timestamp_device': 57247, + 'timestamp_stream': 57.61086506024003, + 'transform': [array([ 0.00983849, -0.00361572, 0.16483988]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.04232146, -0.03336886, -6.36646891]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.767131805419922, + 'FR_Wheel_Angle': 41.63642120361328, + 'Location': array([ -5.74669743, -23.2837162 , 0.17444031]), + 'Rotation': array([-6.39988706e-02, -2.86821861e+01, 1.87718607e-02]), + 'Velocity': array([-5.17730951e-01, 6.05525784e-02, 4.79674316e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1204833984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 65.19326019, -1607.73803711, 16.60632324]), + 'frame': 14068, + 'frame_number': 14068, + 'framesequence': 14066, + 'gaze_dir': array([0.98058069, 0.14982888, 0.12654176]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14982888, 0.12654176]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14982888, 0.12654176]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.614336758852005, + 'timestamp_carla': 57614, + 'timestamp_device': 57250, + 'timestamp_stream': 57.614336758852005, + 'transform': [array([ 0.00983269, -0.00362305, 0.16484033]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.14513089e-02, -3.83086223e-03, -6.60248899e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.776105880737305, + 'FR_Wheel_Angle': 41.649879455566406, + 'Location': array([ -5.76775885, -23.27986336, 0.17444271]), + 'Rotation': array([-6.32065684e-02, -2.89575100e+01, 1.79276522e-02]), + 'Velocity': array([-5.01460195e-01, 5.05490378e-02, 4.86264209e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.12109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 65.86929321, -1607.61987305, 16.60571289]), + 'frame': 14069, + 'frame_number': 14069, + 'framesequence': 14067, + 'gaze_dir': array([0.98058069, 0.14932179, 0.12713973]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14932179, 0.12713973]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14932179, 0.12713973]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.617977160960436, + 'timestamp_carla': 57618, + 'timestamp_device': 57254, + 'timestamp_stream': 57.617977160960436, + 'transform': [array([ 0.00983528, -0.00362061, 0.16484042]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03076394, -0.03323445, -5.86258125]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.784347534179688, + 'FR_Wheel_Angle': 41.66218948364258, + 'Location': array([ -5.79112911, -23.27547836, 0.1744619 ]), + 'Rotation': array([-6.20386042e-02, -2.92638512e+01, 1.69046130e-02]), + 'Velocity': array([-0.47814444, 0.0608613 , 0.00071417]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1219482421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 66.76915741, -1607.46679688, 16.6048584 ]), + 'frame': 14070, + 'frame_number': 14070, + 'framesequence': 14068, + 'gaze_dir': array([0.98058069, 0.14881183, 0.12773626]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14881183, 0.12773626]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14881183, 0.12773626]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.621545162051916, + 'timestamp_carla': 57621, + 'timestamp_device': 57258, + 'timestamp_stream': 57.621545162051916, + 'transform': [array([ 0.00982902, -0.00362793, 0.16484071]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.06988443, 0.07887747, -6.84404325]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.767831802368164, + 'FR_Wheel_Angle': 41.6335563659668, + 'Location': array([ -5.8124609 , -23.27131462, 0.17449489]), + 'Rotation': array([-6.25986829e-02, -2.95460510e+01, 1.84721090e-02]), + 'Velocity': array([-0.51859188, 0.06195473, 0.00090452]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1229248046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 67.67133331, -1607.31616211, 16.60400391]), + 'frame': 14071, + 'frame_number': 14071, + 'framesequence': 14069, + 'gaze_dir': array([0.98058069, 0.14842817, 0.12818187]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14842817, 0.12818187]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14842817, 0.12818187]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.625317461788654, + 'timestamp_carla': 57625, + 'timestamp_device': 57261, + 'timestamp_stream': 57.625317461788654, + 'transform': [array([ 0.00983162, -0.00362549, 0.16484049]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.88095197e-02, 2.14885478e-03, -6.43270445e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.765987396240234, + 'FR_Wheel_Angle': 41.63173294067383, + 'Location': array([ -5.83708382, -23.26635933, 0.17453915]), + 'Rotation': array([-6.36915118e-02, -2.98720112e+01, 2.04163939e-02]), + 'Velocity': array([-0.52032739, 0.07219667, 0.00063596]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.12353515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 68.34689331, -1607.20654297, 16.60351562]), + 'frame': 14072, + 'frame_number': 14072, + 'framesequence': 14070, + 'gaze_dir': array([0.98058069, 0.14791405, 0.12877479]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14791405, 0.12877479]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14791405, 0.12877479]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.62867255881429, + 'timestamp_carla': 57628, + 'timestamp_device': 57265, + 'timestamp_stream': 57.62867255881429, + 'transform': [array([ 0.00982574, -0.00363281, 0.1648411 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0384139 , 0.06803393, -6.8955617 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.750823974609375, + 'FR_Wheel_Angle': 41.60708999633789, + 'Location': array([ -5.86012554, -23.26152992, 0.17455986]), + 'Rotation': array([-6.43881932e-02, -3.01707230e+01, 2.12427378e-02]), + 'Velocity': array([-0.5547812 , 0.07963448, 0.00097819]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.12451171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 69.25008392, -1607.06225586, 16.60241699]), + 'frame': 14073, + 'frame_number': 14073, + 'framesequence': 14071, + 'gaze_dir': array([0.98058069, 0.14739805, 0.12936509]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14739805, 0.12936509]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14739805, 0.12936509]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.63314815983176, + 'timestamp_carla': 57633, + 'timestamp_device': 57269, + 'timestamp_stream': 57.63314815983176, + 'transform': [array([ 0.00982979, -0.00362915, 0.16483919]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.37314880e-02, 2.89233611e-03, -6.99603367e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754663467407227, + 'FR_Wheel_Angle': 41.61199188232422, + 'Location': array([ -5.88442326, -23.25631523, 0.17459869]), + 'Rotation': array([-6.48867935e-02, -3.04891129e+01, 2.25842651e-02]), + 'Velocity': array([-0.54741639, 0.0775843 , 0.00071146]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.12548828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 70.15214539, -1606.92272949, 16.6015625 ]), + 'frame': 14074, + 'frame_number': 14074, + 'framesequence': 14072, + 'gaze_dir': array([0.98058069, 0.147009 , 0.12980703]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.147009 , 0.12980703]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.147009 , 0.12980703]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.636341258883476, + 'timestamp_carla': 57636, + 'timestamp_device': 57272, + 'timestamp_stream': 57.636341258883476, + 'transform': [array([ 0.00982269, -0.0036377 , 0.16484007]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.26103899e-02, 3.74537427e-03, -7.04528475e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.753150939941406, + 'FR_Wheel_Angle': 41.60918045043945, + 'Location': array([ -5.90820599, -23.25112343, 0.17462741]), + 'Rotation': array([-6.45452812e-02, -3.08035069e+01, 2.26543378e-02]), + 'Velocity': array([-0.55046409, 0.08133385, 0.00076997]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.126220703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 70.83078003, -1606.81921387, 16.60058594]), + 'frame': 14075, + 'frame_number': 14075, + 'framesequence': 14073, + 'gaze_dir': array([0.98058069, 0.146358 , 0.13054061]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.146358 , 0.13054061]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.146358 , 0.13054061]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.64046346023679, + 'timestamp_carla': 57640, + 'timestamp_device': 57277, + 'timestamp_stream': 57.64046346023679, + 'transform': [array([ 0.00981972, -0.00364136, 0.16483927]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.75482845e-03, -1.28273116e-02, -6.98733139e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.755191802978516, + 'FR_Wheel_Angle': 41.61259460449219, + 'Location': array([ -5.93346167, -23.24544716, 0.17464946]), + 'Rotation': array([-6.42379224e-02, -3.11373997e+01, 2.26384327e-02]), + 'Velocity': array([-5.45487642e-01, 8.31692964e-02, 4.29630280e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.12744140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 71.96054077, -1606.65307617, 16.5994873 ]), + 'frame': 14076, + 'frame_number': 14076, + 'framesequence': 14074, + 'gaze_dir': array([0.98058069, 0.14596593, 0.13097885]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14596593, 0.13097885]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14596593, 0.13097885]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.644264958798885, + 'timestamp_carla': 57644, + 'timestamp_device': 57280, + 'timestamp_stream': 57.644264958798885, + 'transform': [array([ 0.00980537, -0.00365845, 0.16483934]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01380285, 0.00836114, -7.12692547]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.750158309936523, + 'FR_Wheel_Angle': 41.604183197021484, + 'Location': array([ -5.95842981, -23.23968506, 0.17467345]), + 'Rotation': array([-6.39988706e-02, -3.14682789e+01, 2.28659622e-02]), + 'Velocity': array([-0.55648386, 0.0890552 , 0.00057863]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.128173828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 72.63839722, -1606.5559082 , 16.59863281]), + 'frame': 14077, + 'frame_number': 14077, + 'framesequence': 14075, + 'gaze_dir': array([0.98058069, 0.14544064, 0.13156191]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14544064, 0.13156191]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14544064, 0.13156191]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.647668059915304, + 'timestamp_carla': 57647, + 'timestamp_device': 57284, + 'timestamp_stream': 57.647668059915304, + 'transform': [array([ 0.00979805, -0.00366699, 0.16483998]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01624064, 0.01444469, -7.23843956]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74643325805664, + 'FR_Wheel_Angle': 41.59877395629883, + 'Location': array([ -5.98354292, -23.23372459, 0.17470162]), + 'Rotation': array([-6.39032498e-02, -3.18012218e+01, 2.32550018e-02]), + 'Velocity': array([-0.56471801, 0.09393775, 0.00079338]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.129150390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 73.54249573, -1606.43078613, 16.59777832]), + 'frame': 14078, + 'frame_number': 14078, + 'framesequence': 14076, + 'gaze_dir': array([0.98058069, 0.14504552, 0.13199739]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14504552, 0.13199739]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14504552, 0.13199739]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.650938760489225, + 'timestamp_carla': 57650, + 'timestamp_device': 57287, + 'timestamp_stream': 57.650938760489225, + 'transform': [array([ 0.00978287, -0.00368652, 0.16484083]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 5.31335641e-03, 1.45498030e-02, -7.35045004e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73592758178711, + 'FR_Wheel_Angle': 41.580833435058594, + 'Location': array([ -6.0080328 , -23.22774124, 0.17472793]), + 'Rotation': array([-6.44223392e-02, -3.21268158e+01, 2.44409405e-02]), + 'Velocity': array([-0.58687353, 0.10505424, 0.00080294]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.130126953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 74.2205658 , -1606.33886719, 16.59692383]), + 'frame': 14079, + 'frame_number': 14079, + 'framesequence': 14077, + 'gaze_dir': array([0.98058069, 0.14451616, 0.13257675]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14451616, 0.13257675]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14451616, 0.13257675]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.654326260089874, + 'timestamp_carla': 57654, + 'timestamp_device': 57291, + 'timestamp_stream': 57.654326260089874, + 'transform': [array([ 0.00977325, -0.00369873, 0.16484144]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03570454, 0.0269742 , -7.9724884 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.729745864868164, + 'FR_Wheel_Angle': 41.56843185424805, + 'Location': array([ -6.03630829, -23.22074699, 0.17476586]), + 'Rotation': array([-6.49414361e-02, -3.25069466e+01, 2.59967949e-02]), + 'Velocity': array([-0.60608518, 0.10335007, 0.00075518]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.130859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 75.1254425 , -1606.22021484, 16.59631348]), + 'frame': 14080, + 'frame_number': 14080, + 'framesequence': 14078, + 'gaze_dir': array([0.98058069, 0.144118 , 0.13300946]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.144118 , 0.13300946]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.144118 , 0.13300946]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.65802885964513, + 'timestamp_carla': 57658, + 'timestamp_device': 57294, + 'timestamp_stream': 57.65802885964513, + 'transform': [array([ 0.00975311, -0.00372314, 0.16484167]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.80532504e-02, -4.80290997e-04, -7.84245110e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72147560119629, + 'FR_Wheel_Angle': 41.55520248413086, + 'Location': array([ -6.06486177, -23.21346855, 0.17480193]), + 'Rotation': array([-6.52761161e-02, -3.28897018e+01, 2.66182907e-02]), + 'Velocity': array([-0.62368417, 0.11907833, 0.00070827]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.131591796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 75.80393219, -1606.13354492, 16.59558105]), + 'frame': 14081, + 'frame_number': 14081, + 'framesequence': 14079, + 'gaze_dir': array([0.98058069, 0.14358458, 0.13358511]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14358458, 0.13358511]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14358458, 0.13358511]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.66150926053524, + 'timestamp_carla': 57661, + 'timestamp_device': 57298, + 'timestamp_stream': 57.66150926053524, + 'transform': [array([ 0.00974174, -0.00373657, 0.16484208]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.91462727e-03, 1.55034512e-02, -8.15307140e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.712156295776367, + 'FR_Wheel_Angle': 41.54303741455078, + 'Location': array([ -6.09227228, -23.20622063, 0.17482246]), + 'Rotation': array([-6.55288324e-02, -3.32548409e+01, 2.68699285e-02]), + 'Velocity': array([-0.64222133, 0.12553392, 0.00078258]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1324462890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 76.70915985, -1606.02172852, 16.59484863]), + 'frame': 14082, + 'frame_number': 14082, + 'framesequence': 14080, + 'gaze_dir': array([0.98058069, 0.14318341, 0.13401502]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14318341, 0.13401502]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14318341, 0.13401502]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.6649450622499, + 'timestamp_carla': 57664, + 'timestamp_device': 57301, + 'timestamp_stream': 57.6649450622499, + 'transform': [array([ 0.00972237, -0.00375977, 0.16484269]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 3.21124098e-03, -9.92503297e-03, -8.21716213e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71028709411621, + 'FR_Wheel_Angle': 41.538963317871094, + 'Location': array([ -6.12035036, -23.19861031, 0.174859 ]), + 'Rotation': array([-6.53375834e-02, -3.36299591e+01, 2.71111336e-02]), + 'Velocity': array([-0.64608961, 0.1301837 , 0.00083991]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1334228515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 77.38804626, -1605.93994141, 16.59387207]), + 'frame': 14083, + 'frame_number': 14083, + 'framesequence': 14081, + 'gaze_dir': array([0.98058069, 0.14264598, 0.13458692]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14264598, 0.13458692]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14264598, 0.13458692]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.66852895915508, + 'timestamp_carla': 57668, + 'timestamp_device': 57305, + 'timestamp_stream': 57.66852895915508, + 'transform': [array([ 0.00971008, -0.00377441, 0.16484289]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.15540856, 0.37167299, -8.41001892]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.707965850830078, + 'FR_Wheel_Angle': 41.53630447387695, + 'Location': array([ -6.15154171, -23.18996811, 0.17522807]), + 'Rotation': array([ -0.078916 , -34.04689407, 0.05229051]), + 'Velocity': array([-0.64829183, 0.13611357, 0.00560292]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.134521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 78.29411316, -1605.83435059, 16.59277344]), + 'frame': 14084, + 'frame_number': 14084, + 'framesequence': 14082, + 'gaze_dir': array([0.98058069, 0.14224181, 0.135014 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14224181, 0.135014 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14224181, 0.135014 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.67192976176739, + 'timestamp_carla': 57671, + 'timestamp_device': 57308, + 'timestamp_stream': 57.67192976176739, + 'transform': [array([ 0.00969025, -0.00379883, 0.16484345]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02271267, 0.09873953, -8.55324841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70265769958496, + 'FR_Wheel_Angle': 41.524471282958984, + 'Location': array([ -6.17973995, -23.18186378, 0.17544776]), + 'Rotation': array([ -0.08446895, -34.42506027, 0.05925163]), + 'Velocity': array([-0.66250992, 0.14253956, 0.00318225]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.135009765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 78.97350311, -1605.75744629, 16.59240723]), + 'frame': 14085, + 'frame_number': 14085, + 'framesequence': 14083, + 'gaze_dir': array([0.98058069, 0.14170039, 0.13558212]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14170039, 0.13558212]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14170039, 0.13558212]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.675508961081505, + 'timestamp_carla': 57675, + 'timestamp_device': 57312, + 'timestamp_stream': 57.675508961081505, + 'transform': [array([ 0.0096772 , -0.0038147 , 0.16484365]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 1.97852086e-02, 3.39272292e-03, -8.59488964e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69486427307129, + 'FR_Wheel_Angle': 41.51378631591797, + 'Location': array([ -6.20984793, -23.17297745, 0.17555176]), + 'Rotation': array([ -0.08606038, -34.82801056, 0.06040602]), + 'Velocity': array([-0.67773908, 0.15427703, 0.00179735]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.13623046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 79.88024902, -1605.6583252 , 16.59130859]), + 'frame': 14086, + 'frame_number': 14086, + 'framesequence': 14084, + 'gaze_dir': array([0.98058069, 0.14129323, 0.13600637]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14129323, 0.13600637]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14129323, 0.13600637]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.6788743622601, + 'timestamp_carla': 57678, + 'timestamp_device': 57315, + 'timestamp_stream': 57.6788743622601, + 'transform': [array([ 0.00965675, -0.00383911, 0.16484426]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02974863, -0.03920606, -8.74967289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.692060470581055, + 'FR_Wheel_Angle': 41.507530212402344, + 'Location': array([ -6.23998785, -23.16394997, 0.17560543]), + 'Rotation': array([ -0.08584864, -35.2374649 , 0.06033351]), + 'Velocity': array([-0.68447495, 0.15882885, 0.00086898]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.13671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 80.56010437, -1605.58630371, 16.59082031]), + 'frame': 14087, + 'frame_number': 14087, + 'framesequence': 14085, + 'gaze_dir': array([0.98058069, 0.14088428, 0.13642995]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14088428, 0.13642995]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14088428, 0.13642995]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.68223826214671, + 'timestamp_carla': 57682, + 'timestamp_device': 57318, + 'timestamp_stream': 57.68223826214671, + 'transform': [array([ 0.00964302, -0.0038562 , 0.16484472]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02618435, -0.03869902, -8.93693829]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.685941696166992, + 'FR_Wheel_Angle': 41.5002326965332, + 'Location': array([ -6.26949835, -23.15491486, 0.17563346]), + 'Rotation': array([ -0.08520661, -35.6395874 , 0.0597856 ]), + 'Velocity': array([-6.97991252e-01, 1.66624710e-01, 6.51664741e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.137451171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 81.24029541, -1605.51696777, 16.59008789]), + 'frame': 14088, + 'frame_number': 14088, + 'framesequence': 14086, + 'gaze_dir': array([0.98058069, 0.14033774, 0.13699208]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14033774, 0.13699208]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14033774, 0.13699208]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.685823161154985, + 'timestamp_carla': 57685, + 'timestamp_device': 57322, + 'timestamp_stream': 57.685823161154985, + 'transform': [array([ 0.00961945, -0.00388428, 0.16484499]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02278103, -0.01256719, -9.46636295]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.682689666748047, + 'FR_Wheel_Angle': 41.49015426635742, + 'Location': array([ -6.30252695, -23.14454269, 0.17564945]), + 'Rotation': array([ -0.08423672, -36.09136581, 0.05904463]), + 'Velocity': array([-7.09198833e-01, 1.67227134e-01, 4.33320994e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1385498046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 82.14775085, -1605.42626953, 16.58911133]), + 'frame': 14089, + 'frame_number': 14089, + 'framesequence': 14087, + 'gaze_dir': array([0.98058069, 0.13978843, 0.13755257]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13978843, 0.13755257]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13978843, 0.13755257]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.68976965919137, + 'timestamp_carla': 57689, + 'timestamp_device': 57326, + 'timestamp_stream': 57.68976965919137, + 'transform': [array([ 0.00960335, -0.00390381, 0.16484438]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.0266718 , -0.03822029, -9.18738747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.676498413085938, + 'FR_Wheel_Angle': 41.48106384277344, + 'Location': array([ -6.33551645, -23.13387871, 0.17566226]), + 'Rotation': array([ -0.0831234 , -36.54277039, 0.0579897 ]), + 'Velocity': array([-7.16947436e-01, 1.83741510e-01, 3.57079494e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1396484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 83.05544281, -1605.34033203, 16.5880127 ]), + 'frame': 14090, + 'frame_number': 14090, + 'framesequence': 14088, + 'gaze_dir': array([0.98058069, 0.1392374 , 0.13811032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1392374 , 0.13811032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1392374 , 0.13811032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.693369060754776, + 'timestamp_carla': 57693, + 'timestamp_device': 57330, + 'timestamp_stream': 57.693369060754776, + 'transform': [array([ 0.00957939, -0.00393311, 0.16484465]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03744159, -0.0600321 , -9.27447987]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.674800872802734, + 'FR_Wheel_Angle': 41.47960662841797, + 'Location': array([ -6.36725044, -23.12336159, 0.17567168]), + 'Rotation': array([ -0.08230378, -36.97801208, 0.0575005 ]), + 'Velocity': array([-7.19735682e-01, 1.89888448e-01, 4.18241019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 83.96339417, -1605.25720215, 16.5871582 ]), + 'frame': 14091, + 'frame_number': 14091, + 'framesequence': 14089, + 'gaze_dir': array([0.98058069, 0.13882215, 0.13852771]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13882215, 0.13852771]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13882215, 0.13852771]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.696684058755636, + 'timestamp_carla': 57696, + 'timestamp_device': 57333, + 'timestamp_stream': 57.696684058755636, + 'transform': [array([ 0.00956383, -0.00395142, 0.16484514]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.02819641, -0.04407592, -9.37193108]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.670303344726562, + 'FR_Wheel_Angle': 41.473140716552734, + 'Location': array([ -6.39844847, -23.11274529, 0.17568572]), + 'Rotation': array([ -0.08136121, -37.40577316, 0.05651245]), + 'Velocity': array([-7.28471816e-01, 1.98458150e-01, 2.51379010e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1412353515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 84.64421844, -1605.19873047, 16.58654785]), + 'frame': 14092, + 'frame_number': 14092, + 'framesequence': 14090, + 'gaze_dir': array([0.98058069, 0.13826722, 0.13908158]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13826722, 0.13908158]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13826722, 0.13908158]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.70032516121864, + 'timestamp_carla': 57700, + 'timestamp_device': 57337, + 'timestamp_stream': 57.70032516121864, + 'transform': [array([ 0.00953781, -0.00398437, 0.16484529]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03742695, -0.06533499, -9.31956387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.671663284301758, + 'FR_Wheel_Angle': 41.476097106933594, + 'Location': array([ -6.43182611, -23.10109901, 0.17569664]), + 'Rotation': array([ -0.0802957 , -37.86527252, 0.05551922]), + 'Velocity': array([-7.23560631e-01, 2.03596056e-01, 1.89471248e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1422119140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 85.55279541, -1605.12182617, 16.58557129]), + 'frame': 14093, + 'frame_number': 14093, + 'framesequence': 14091, + 'gaze_dir': array([0.98058069, 0.13784906, 0.13949606]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13784906, 0.13949606]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13784906, 0.13949606]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.703911662101746, + 'timestamp_carla': 57703, + 'timestamp_device': 57340, + 'timestamp_stream': 57.703911662101746, + 'transform': [array([ 0.00952049, -0.00400513, 0.16484536]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.04140306, -0.08864444, -8.92010021]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.682239532470703, + 'FR_Wheel_Angle': 41.4915885925293, + 'Location': array([ -6.46263647, -23.09009552, 0.17569701]), + 'Rotation': array([ -0.07849253, -38.28806305, 0.05336298]), + 'Velocity': array([-6.97526991e-01, 2.01933518e-01, 4.44250094e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.142822265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 86.23384857, -1605.06848145, 16.58496094]), + 'frame': 14094, + 'frame_number': 14094, + 'framesequence': 14092, + 'gaze_dir': array([0.98058069, 0.13729028, 0.14004603]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13729028, 0.14004603]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13729028, 0.14004603]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.7081759609282, + 'timestamp_carla': 57708, + 'timestamp_device': 57344, + 'timestamp_stream': 57.7081759609282, + 'transform': [array([ 0.00948784, -0.00404419, 0.16484419]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.19820444, -0.56100523, -9.62863827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.672557830810547, + 'FR_Wheel_Angle': 41.47147750854492, + 'Location': array([ -6.49584961, -23.07789421, 0.17557056]), + 'Rotation': array([ -0.07076759, -38.74710846, 0.0397005 ]), + 'Velocity': array([-0.72468519, 0.20613104, -0.00488737]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.143798828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 87.14276123, -1604.99829102, 16.58398438]), + 'frame': 14095, + 'frame_number': 14095, + 'framesequence': 14093, + 'gaze_dir': array([0.98058069, 0.13672878, 0.14059429]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13672878, 0.14059429]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13672878, 0.14059429]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.71190845966339, + 'timestamp_carla': 57711, + 'timestamp_device': 57348, + 'timestamp_stream': 57.71190845966339, + 'transform': [array([ 0.00946907, -0.00406738, 0.16484407]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.03723073, -0.16391957, -9.34619617]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66912841796875, + 'FR_Wheel_Angle': 41.46837615966797, + 'Location': array([ -6.52766275, -23.065979 , 0.17536144]), + 'Rotation': array([-6.22844920e-02, -3.91856804e+01, 2.80449260e-02]), + 'Velocity': array([-0.72497463, 0.22145367, -0.00180243]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1446533203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 88.05128479, -1604.93347168, 16.58312988]), + 'frame': 14096, + 'frame_number': 14096, + 'framesequence': 14094, + 'gaze_dir': array([0.98058069, 0.1363066 , 0.14100362]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1363066 , 0.14100362]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1363066 , 0.14100362]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.71523606032133, + 'timestamp_carla': 57715, + 'timestamp_device': 57351, + 'timestamp_stream': 57.71523606032133, + 'transform': [array([ 0.00944473, -0.00409668, 0.16484472]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03682436, -0.03788114, -9.74327183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67341423034668, + 'FR_Wheel_Angle': 41.4764289855957, + 'Location': array([ -6.55916405, -23.05392075, 0.17529407]), + 'Rotation': array([-5.93884923e-02, -3.96245308e+01, 2.62387414e-02]), + 'Velocity': array([-7.19750285e-01, 2.16244757e-01, -5.92422497e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1455078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 88.73278809, -1604.88659668, 16.58215332]), + 'frame': 14097, + 'frame_number': 14097, + 'framesequence': 14095, + 'gaze_dir': array([0.98058069, 0.13574128, 0.14154793]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13574128, 0.14154793]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13574128, 0.14154793]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.718918561935425, + 'timestamp_carla': 57718, + 'timestamp_device': 57355, + 'timestamp_stream': 57.718918561935425, + 'transform': [array([ 0.00942665, -0.00411865, 0.16484465]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.04293114, 0.03249668, -9.91286945]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.665607452392578, + 'FR_Wheel_Angle': 41.464820861816406, + 'Location': array([ -6.59036922, -23.04165649, 0.17529784]), + 'Rotation': array([-5.85278869e-02, -4.00597763e+01, 2.63572820e-02]), + 'Velocity': array([-7.34469891e-01, 2.29279548e-01, 5.21821959e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.146484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 89.64259338, -1604.82727051, 16.5814209 ]), + 'frame': 14098, + 'frame_number': 14098, + 'framesequence': 14096, + 'gaze_dir': array([0.98058069, 0.13531625, 0.14195429]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13531625, 0.14195429]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13531625, 0.14195429]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.722237061709166, + 'timestamp_carla': 57722, + 'timestamp_device': 57358, + 'timestamp_stream': 57.722237061709166, + 'transform': [array([ 0.00940254, -0.00414795, 0.16484526]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.70218388e-03, 5.11058699e-03, -9.68827248e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66118812561035, + 'FR_Wheel_Angle': 41.45705032348633, + 'Location': array([ -6.62468529, -23.02777481, 0.17532527]), + 'Rotation': array([-5.88079244e-02, -4.05329933e+01, 2.72971112e-02]), + 'Velocity': array([-0.73835617, 0.24370693, 0.00095329]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1470947265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 90.32449341, -1604.78515625, 16.58068848]), + 'frame': 14099, + 'frame_number': 14099, + 'framesequence': 14097, + 'gaze_dir': array([0.98058069, 0.13474713, 0.14249465]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13474713, 0.14249465]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13474713, 0.14249465]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.72593675926328, + 'timestamp_carla': 57725, + 'timestamp_device': 57362, + 'timestamp_stream': 57.72593675926328, + 'transform': [array([ 0.00938393, -0.00417114, 0.16484518]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01411725, 0.01255658, -9.89536381]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.65817642211914, + 'FR_Wheel_Angle': 41.45044708251953, + 'Location': array([ -6.65892267, -23.0136013 , 0.17537457]), + 'Rotation': array([-5.89035489e-02, -4.10097084e+01, 2.80595571e-02]), + 'Velocity': array([-0.74406648, 0.25112391, 0.00095243]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1480712890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 91.2347641 , -1604.73205566, 16.57983398]), + 'frame': 14100, + 'frame_number': 14100, + 'framesequence': 14098, + 'gaze_dir': array([0.98058069, 0.13417637, 0.14303219]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13417637, 0.14303219]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13417637, 0.14303219]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.72935286164284, + 'timestamp_carla': 57729, + 'timestamp_device': 57366, + 'timestamp_stream': 57.72935286164284, + 'transform': [array([ 0.00935829, -0.00420166, 0.16484563]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.66243660e-03, 1.17194112e-02, -9.89803982e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.653606414794922, + 'FR_Wheel_Angle': 41.442752838134766, + 'Location': array([ -6.69276667, -22.99925041, 0.17542502]), + 'Rotation': array([-5.89035489e-02, -4.14820023e+01, 2.87158322e-02]), + 'Velocity': array([-0.75088096, 0.26255789, 0.0011354 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.149169921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 92.14492035, -1604.68212891, 16.57873535]), + 'frame': 14101, + 'frame_number': 14101, + 'framesequence': 14099, + 'gaze_dir': array([0.98058069, 0.13374637, 0.14343438]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13374637, 0.14343438]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13374637, 0.14343438]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.73306746035814, + 'timestamp_carla': 57733, + 'timestamp_device': 57369, + 'timestamp_stream': 57.73306746035814, + 'transform': [array([ 0.0093383 , -0.00422607, 0.16484544]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.70812819e-03, -2.96660396e-03, -9.93891716e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.652435302734375, + 'FR_Wheel_Angle': 41.4405403137207, + 'Location': array([ -6.72488832, -22.98532104, 0.17546928]), + 'Rotation': array([-5.88079244e-02, -4.19320831e+01, 2.93516666e-02]), + 'Velocity': array([-0.75181568, 0.26899254, 0.00103981]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.14990234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 92.82737732, -1604.64831543, 16.578125 ]), + 'frame': 14102, + 'frame_number': 14102, + 'framesequence': 14100, + 'gaze_dir': array([0.98058069, 0.13317189, 0.14396791]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13317189, 0.14396791]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13317189, 0.14396791]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.73673316091299, + 'timestamp_carla': 57736, + 'timestamp_device': 57373, + 'timestamp_stream': 57.73673316091299, + 'transform': [array([ 0.00930893, -0.00426147, 0.1648456 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-4.52529592e-03, 9.70325782e-04, -1.00394945e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.649255752563477, + 'FR_Wheel_Angle': 41.43611145019531, + 'Location': array([ -6.7562604 , -22.97142792, 0.17551261]), + 'Rotation': array([-5.87191321e-02, -4.23733406e+01, 2.97961775e-02]), + 'Velocity': array([-0.75685692, 0.27746481, 0.00113231]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.15087890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 93.73773956, -1604.6048584 , 16.57714844]), + 'frame': 14103, + 'frame_number': 14103, + 'framesequence': 14101, + 'gaze_dir': array([0.98058069, 0.13259472, 0.14449967]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13259472, 0.14449967]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13259472, 0.14449967]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.7403901591897, + 'timestamp_carla': 57740, + 'timestamp_device': 57377, + 'timestamp_stream': 57.7403901591897, + 'transform': [array([ 0.00928764, -0.00428711, 0.16484553]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.37191610e-02, 7.00834161e-03, -1.02177248e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64734649658203, + 'FR_Wheel_Angle': 41.431396484375, + 'Location': array([ -6.79054785, -22.95591736, 0.17555721]), + 'Rotation': array([-5.85961901e-02, -4.28575554e+01, 3.01720295e-02]), + 'Velocity': array([-0.75989819, 0.28427655, 0.00103221]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1517333984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 94.64821625, -1604.56616211, 16.57641602]), + 'frame': 14104, + 'frame_number': 14104, + 'framesequence': 14102, + 'gaze_dir': array([0.98058069, 0.13216086, 0.14489658]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13216086, 0.14489658]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13216086, 0.14489658]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.74393646046519, + 'timestamp_carla': 57743, + 'timestamp_device': 57380, + 'timestamp_stream': 57.74393646046519, + 'transform': [array([ 0.00925804, -0.00432251, 0.16484582]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 8.42299371e-04, -2.17053201e-02, -1.00447493e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.649202346801758, + 'FR_Wheel_Angle': 41.437164306640625, + 'Location': array([ -6.82637024, -22.93934059, 0.17559668]), + 'Rotation': array([-5.82273602e-02, -4.33650246e+01, 3.02752294e-02]), + 'Velocity': array([-7.52321482e-01, 2.90298074e-01, 6.70447364e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.15234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 95.33059692, -1604.53955078, 16.57580566]), + 'frame': 14105, + 'frame_number': 14105, + 'framesequence': 14103, + 'gaze_dir': array([0.98058069, 0.13157998, 0.14542428]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13157998, 0.14542428]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13157998, 0.14542428]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.74741156026721, + 'timestamp_carla': 57747, + 'timestamp_device': 57384, + 'timestamp_stream': 57.74741156026721, + 'transform': [array([ 0.00923622, -0.00434937, 0.16484609]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.86715187e-03, -7.91562372e-04, -1.06444635e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.646697998046875, + 'FR_Wheel_Angle': 41.43053436279297, + 'Location': array([ -6.85831976, -22.92416191, 0.17562754]), + 'Rotation': array([-5.77970594e-02, -4.38253059e+01, 3.02536283e-02]), + 'Velocity': array([-0.75530249, 0.29883197, 0.00108877]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1533203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 96.24132538, -1604.50708008, 16.57470703]), + 'frame': 14106, + 'frame_number': 14106, + 'framesequence': 14104, + 'gaze_dir': array([0.98058069, 0.13114336, 0.14581814]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13114336, 0.14581814]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13114336, 0.14581814]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.751198660582304, + 'timestamp_carla': 57751, + 'timestamp_device': 57387, + 'timestamp_stream': 57.751198660582304, + 'transform': [array([ 0.00920265, -0.00438965, 0.16484594]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-8.08502641e-03, -1.31183369e-02, -1.05195217e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64873695373535, + 'FR_Wheel_Angle': 41.435760498046875, + 'Location': array([ -6.89282131, -22.90743065, 0.17566466]), + 'Rotation': array([-5.72847947e-02, -4.43268509e+01, 3.04410309e-02]), + 'Velocity': array([-0.74825728, 0.30211481, 0.0010399 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1541748046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 96.92383575, -1604.48535156, 16.57397461]), + 'frame': 14107, + 'frame_number': 14107, + 'framesequence': 14105, + 'gaze_dir': array([0.98058069, 0.13055879, 0.14634177]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13055879, 0.14634177]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13055879, 0.14634177]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.75443125888705, + 'timestamp_carla': 57754, + 'timestamp_device': 57391, + 'timestamp_stream': 57.75443125888705, + 'transform': [array([ 0.00918083, -0.0044165 , 0.16484651]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.26438767e-03, -7.17773987e-03, -1.07089100e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.645854949951172, + 'FR_Wheel_Angle': 41.42869186401367, + 'Location': array([ -6.92511177, -22.89142799, 0.17570618]), + 'Rotation': array([-5.70662282e-02, -4.47988052e+01, 3.07488199e-02]), + 'Velocity': array([-7.51783907e-01, 3.12624097e-01, 4.49104293e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.155029296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 97.83442688, -1604.45996094, 16.57312012]), + 'frame': 14108, + 'frame_number': 14108, + 'framesequence': 14106, + 'gaze_dir': array([0.98058069, 0.13011943, 0.14673257]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13011943, 0.14673257]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13011943, 0.14673257]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.75820245966315, + 'timestamp_carla': 57758, + 'timestamp_device': 57394, + 'timestamp_stream': 57.75820245966315, + 'transform': [array([ 0.00914574, -0.00445923, 0.16484639]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.03532076e-02, -5.56788919e-03, -9.60305119e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64580726623535, + 'FR_Wheel_Angle': 41.43057632446289, + 'Location': array([ -6.9574461 , -22.87513542, 0.17573306]), + 'Rotation': array([-5.68271726e-02, -4.52642365e+01, 3.11760269e-02]), + 'Velocity': array([-7.50929952e-01, 3.17160994e-01, -6.69145549e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1558837890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 98.51708221, -1604.44287109, 16.57226562]), + 'frame': 14109, + 'frame_number': 14109, + 'framesequence': 14107, + 'gaze_dir': array([0.98058069, 0.12953122, 0.14725208]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12953122, 0.14725208]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12953122, 0.14725208]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.761681258678436, + 'timestamp_carla': 57761, + 'timestamp_device': 57398, + 'timestamp_stream': 57.761681258678436, + 'transform': [array([ 0.00912186, -0.00448853, 0.16484658]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.22472374e-02, 4.66264691e-03, -1.01309557e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64397621154785, + 'FR_Wheel_Angle': 41.42716979980469, + 'Location': array([ -6.99070358, -22.85800934, 0.17577712]), + 'Rotation': array([-5.64583391e-02, -4.57514191e+01, 3.14408913e-02]), + 'Velocity': array([-0.75216126, 0.32538036, 0.00105847]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.15673828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 99.42767334, -1604.42407227, 16.57141113]), + 'frame': 14110, + 'frame_number': 14110, + 'framesequence': 14108, + 'gaze_dir': array([0.98058069, 0.12894094, 0.14776924]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12894094, 0.14776924]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12894094, 0.14776924]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.765564762055874, + 'timestamp_carla': 57765, + 'timestamp_device': 57402, + 'timestamp_stream': 57.765564762055874, + 'transform': [array([ 0.00908493, -0.00453247, 0.16484629]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.27071131e-03, 4.42489097e-03, -1.08383474e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639854431152344, + 'FR_Wheel_Angle': 41.418148040771484, + 'Location': array([ -7.02507496, -22.83986855, 0.17582473]), + 'Rotation': array([-5.63968681e-02, -4.62612305e+01, 3.20057161e-02]), + 'Velocity': array([-0.75701946, 0.33732307, 0.00092232]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1573486328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 100.33947754, -1604.40771484, 16.57080078]), + 'frame': 14111, + 'frame_number': 14111, + 'framesequence': 14109, + 'gaze_dir': array([0.98058069, 0.12849729, 0.14815518]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12849729, 0.14815518]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12849729, 0.14815518]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.76898195967078, + 'timestamp_carla': 57769, + 'timestamp_device': 57405, + 'timestamp_stream': 57.76898195967078, + 'transform': [array([ 0.00906052, -0.00456177, 0.16484658]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.84849918e-03, -2.83711054e-03, -1.08434448e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639188766479492, + 'FR_Wheel_Angle': 41.416351318359375, + 'Location': array([ -7.05797577, -22.82217407, 0.17586158]), + 'Rotation': array([-5.62124550e-02, -4.67466049e+01, 3.24549638e-02]), + 'Velocity': array([-0.75609475, 0.34392601, 0.00105245]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.158203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 101.02082825, -1604.39990234, 16.56994629]), + 'frame': 14112, + 'frame_number': 14112, + 'framesequence': 14110, + 'gaze_dir': array([0.98058069, 0.12790342, 0.14866818]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12790342, 0.14866818]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12790342, 0.14866818]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.09919890016317368, + 'timestamp': 57.77277876064181, + 'timestamp_carla': 57772, + 'timestamp_device': 57409, + 'timestamp_stream': 57.77277876064181, + 'transform': [array([ 0.00902328, -0.00460693, 0.16484644]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.43045346e-03, -1.10777300e-02, -1.08849783e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.639049530029297, + 'FR_Wheel_Angle': 41.41693115234375, + 'Location': array([ -7.08959293, -22.80480576, 0.17590022]), + 'Rotation': array([-5.59392460e-02, -4.72187347e+01, 3.26988101e-02]), + 'Velocity': array([-0.75355208, 0.35028145, 0.00094219]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.159423828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 101.93266296, -1604.38977051, 16.56884766]), + 'frame': 14113, + 'frame_number': 14113, + 'framesequence': 14111, + 'gaze_dir': array([0.98058069, 0.12730804, 0.14917834]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12730804, 0.14917834]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12730804, 0.14917834]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.776441261172295, + 'timestamp_carla': 57776, + 'timestamp_device': 57413, + 'timestamp_stream': 57.776441261172295, + 'transform': [array([ 0.00899673, -0.00463867, 0.16484636]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-2.82543874e-03, -3.29646058e-02, -1.08311148e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64383316040039, + 'FR_Wheel_Angle': 41.42570114135742, + 'Location': array([ -7.12275076, -22.78623962, 0.17593227]), + 'Rotation': array([-5.52972071e-02, -4.77163429e+01, 3.25350352e-02]), + 'Velocity': array([-7.40552485e-01, 3.51425737e-01, 5.89580508e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.160400390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 102.84243011, -1604.3848877 , 16.56774902]), + 'frame': 14114, + 'frame_number': 14114, + 'framesequence': 14112, + 'gaze_dir': array([0.98058069, 0.12671007, 0.14968657]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12671007, 0.14968657]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12671007, 0.14968657]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.78062045946717, + 'timestamp_carla': 57780, + 'timestamp_device': 57417, + 'timestamp_stream': 57.78062045946717, + 'transform': [array([ 0.0089547 , -0.00468872, 0.16484541]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.03286887e-02, -5.03608445e-03, -1.01419945e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.644779205322266, + 'FR_Wheel_Angle': 41.429439544677734, + 'Location': array([ -7.15693569, -22.76671982, 0.17596871]), + 'Rotation': array([-5.43819629e-02, -4.82318230e+01, 3.21589410e-02]), + 'Velocity': array([-0.73561704, 0.35679951, 0.00080568]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1611328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 103.75415039, -1604.38244629, 16.56713867]), + 'frame': 14115, + 'frame_number': 14115, + 'framesequence': 14113, + 'gaze_dir': array([0.98058069, 0.12626068, 0.15006582]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12626068, 0.15006582]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12626068, 0.15006582]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.78425845876336, + 'timestamp_carla': 57784, + 'timestamp_device': 57420, + 'timestamp_stream': 57.78425845876336, + 'transform': [array([ 0.00892731, -0.00472168, 0.16484544]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.70384329e-02, 6.04022481e-03, -1.00666285e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64615249633789, + 'FR_Wheel_Angle': 41.43165969848633, + 'Location': array([ -7.18920565, -22.7479248 , 0.17599705]), + 'Rotation': array([-5.37399240e-02, -4.87176628e+01, 3.22734937e-02]), + 'Velocity': array([-0.72967952, 0.36148596, 0.00102436]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1614990234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 104.43509674, -1604.38562012, 16.56665039]), + 'frame': 14116, + 'frame_number': 14116, + 'framesequence': 14114, + 'gaze_dir': array([0.98058069, 0.12565917, 0.15056987]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12565917, 0.15056987]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12565917, 0.15056987]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.78763486072421, + 'timestamp_carla': 57787, + 'timestamp_device': 57424, + 'timestamp_stream': 57.78763486072421, + 'transform': [array([ 0.00889351, -0.00476196, 0.16484602]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.74678992e-02, -1.89925521e-03, -1.00366459e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.648406982421875, + 'FR_Wheel_Angle': 41.43625259399414, + 'Location': array([ -7.21980858, -22.7297287 , 0.17603256]), + 'Rotation': array([-5.33437729e-02, -4.91837044e+01, 3.27113904e-02]), + 'Velocity': array([-0.72206283, 0.36480007, 0.00076549]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.162353515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 105.34674835, -1604.38964844, 16.5657959 ]), + 'frame': 14117, + 'frame_number': 14117, + 'framesequence': 14115, + 'gaze_dir': array([0.98058069, 0.12505621, 0.15107103]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12505621, 0.15107103]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12505621, 0.15107103]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.79166726022959, + 'timestamp_carla': 57791, + 'timestamp_device': 57428, + 'timestamp_stream': 57.79166726022959, + 'transform': [array([ 0.00886421, -0.00479736, 0.16484521]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 4.10793675e-03, -4.72683758e-02, -9.53644753e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.656051635742188, + 'FR_Wheel_Angle': 41.43735885620117, + 'Location': array([ -7.25185204, -22.71027946, 0.17605403]), + 'Rotation': array([-5.24353608e-02, -4.96773643e+01, 3.24659459e-02]), + 'Velocity': array([-0.6996119 , 0.36501807, 0.00073898]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1636962890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 106.25689697, -1604.39794922, 16.5645752 ]), + 'frame': 14118, + 'frame_number': 14118, + 'framesequence': 14116, + 'gaze_dir': array([0.98058069, 0.12460212, 0.15144579]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12460212, 0.15144579]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12460212, 0.15144579]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.794994961470366, + 'timestamp_carla': 57795, + 'timestamp_device': 57431, + 'timestamp_stream': 57.794994961470366, + 'transform': [array([ 0.00883209, -0.00483643, 0.16484582]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02160615, 0.01518291, -9.58774185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.650827407836914, + 'FR_Wheel_Angle': 41.441219329833984, + 'Location': array([ -7.28148985, -22.69189072, 0.17609198]), + 'Rotation': array([-5.21553233e-02, -5.01120033e+01, 3.27374227e-02]), + 'Velocity': array([-0.70716083, 0.37685215, 0.00088247]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 106.93995667, -1604.40722656, 16.56408691]), + 'frame': 14119, + 'frame_number': 14119, + 'framesequence': 14117, + 'gaze_dir': array([0.98058069, 0.12399567, 0.1519427 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12399567, 0.1519427 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12399567, 0.1519427 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.79824326187372, + 'timestamp_carla': 57798, + 'timestamp_device': 57435, + 'timestamp_stream': 57.79824326187372, + 'transform': [array([ 0.00880692, -0.00486694, 0.16484639]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.91357620e-02, 4.12161695e-04, -1.03549128e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.656089782714844, + 'FR_Wheel_Angle': 41.44611358642578, + 'Location': array([ -7.31262016, -22.67227936, 0.17612655]), + 'Rotation': array([-5.14518134e-02, -5.05922279e+01, 3.36218961e-02]), + 'Velocity': array([-0.69523674, 0.37475833, 0.00090346]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1650390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 107.85019684, -1604.421875 , 16.56335449]), + 'frame': 14120, + 'frame_number': 14120, + 'framesequence': 14118, + 'gaze_dir': array([0.98058069, 0.12353895, 0.15231428]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12353895, 0.15231428]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12353895, 0.15231428]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10316624492406845, + 'timestamp': 57.8019158616662, + 'timestamp_carla': 57801, + 'timestamp_device': 57438, + 'timestamp_stream': 57.8019158616662, + 'transform': [array([ 0.0087693 , -0.00491211, 0.16484648]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.88623630e-02, 3.58412333e-04, -9.65687466e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66124725341797, + 'FR_Wheel_Angle': 41.457157135009766, + 'Location': array([ -7.34378147, -22.65233803, 0.17615649]), + 'Rotation': array([-5.06595112e-02, -5.10790863e+01, 3.39644440e-02]), + 'Velocity': array([-6.82320714e-01, 3.73715550e-01, 6.74898620e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1658935546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 108.53363037, -1604.4354248 , 16.56237793]), + 'frame': 14121, + 'frame_number': 14121, + 'framesequence': 14119, + 'gaze_dir': array([0.98058069, 0.12292904, 0.15280694]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12292904, 0.15280694]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12292904, 0.15280694]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.8056352622807, + 'timestamp_carla': 57805, + 'timestamp_device': 57442, + 'timestamp_stream': 57.8056352622807, + 'transform': [array([ 0.00874039, -0.00494751, 0.16484655]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.74934771e-02, -8.85956048e-04, -9.56316566e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.666406631469727, + 'FR_Wheel_Angle': 41.466217041015625, + 'Location': array([ -7.37195826, -22.63402367, 0.17618302]), + 'Rotation': array([-4.99218516e-02, -5.15192413e+01, 3.41159292e-02]), + 'Velocity': array([-0.66881502, 0.37268114, 0.00085176]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1666259765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 109.44322968, -1604.45703125, 16.56176758]), + 'frame': 14122, + 'frame_number': 14122, + 'framesequence': 14120, + 'gaze_dir': array([0.98058069, 0.12231658, 0.15329763]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12231658, 0.15329763]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12231658, 0.15329763]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.80943946167827, + 'timestamp_carla': 57809, + 'timestamp_device': 57446, + 'timestamp_stream': 57.80943946167827, + 'transform': [array([ 0.00870064, -0.00499512, 0.16484614]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.02046173, -0.00951697, -9.20974064]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.675357818603516, + 'FR_Wheel_Angle': 41.480552673339844, + 'Location': array([ -7.40095758, -22.61480331, 0.17620136]), + 'Rotation': array([-4.90680747e-02, -5.19797173e+01, 3.39859724e-02]), + 'Velocity': array([-0.64785916, 0.36673766, 0.00085874]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.167724609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 110.35449982, -1604.48144531, 16.56066895]), + 'frame': 14123, + 'frame_number': 14123, + 'framesequence': 14121, + 'gaze_dir': array([0.98058069, 0.1218564 , 0.15366369]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1218564 , 0.15366369]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1218564 , 0.15366369]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.81296256184578, + 'timestamp_carla': 57813, + 'timestamp_device': 57449, + 'timestamp_stream': 57.81296256184578, + 'transform': [array([ 0.00867241, -0.0050293 , 0.16484658]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00981817, -0.01463081, -9.70020866]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68105697631836, + 'FR_Wheel_Angle': 41.48892593383789, + 'Location': array([ -7.4300518 , -22.59520531, 0.17623264]), + 'Rotation': array([-4.82416227e-02, -5.24420319e+01, 3.40810195e-02]), + 'Velocity': array([-6.31134868e-01, 3.66488129e-01, 4.70647792e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1683349609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 111.03543854, -1604.50415039, 16.56005859]), + 'frame': 14124, + 'frame_number': 14124, + 'framesequence': 14122, + 'gaze_dir': array([0.98058069, 0.12139452, 0.15402883]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12139452, 0.15402883]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12139452, 0.15402883]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.81632686033845, + 'timestamp_carla': 57816, + 'timestamp_device': 57452, + 'timestamp_stream': 57.81632686033845, + 'transform': [array([ 0.00863716, -0.00507324, 0.16484685]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.28294425e-02, -6.47683162e-03, -9.44136906e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.687744140625, + 'FR_Wheel_Angle': 41.49999237060547, + 'Location': array([ -7.45654106, -22.57708168, 0.17625873]), + 'Rotation': array([-4.74834740e-02, -5.28647270e+01, 3.42195183e-02]), + 'Velocity': array([-0.61505318, 0.36254925, 0.00084407]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1689453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 111.71834564, -1604.52770996, 16.55944824]), + 'frame': 14125, + 'frame_number': 14125, + 'framesequence': 14123, + 'gaze_dir': array([0.98058069, 0.12077778, 0.15451291]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12077778, 0.15451291]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12077778, 0.15451291]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.819662760943174, + 'timestamp_carla': 57819, + 'timestamp_device': 57456, + 'timestamp_stream': 57.819662760943174, + 'transform': [array([ 0.00860962, -0.00510498, 0.16484754]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.21395905e-02, -4.83582774e-03, -9.28211308e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.692874908447266, + 'FR_Wheel_Angle': 41.50825119018555, + 'Location': array([ -7.48191833, -22.55941772, 0.17628521]), + 'Rotation': array([-4.69985306e-02, -5.32732315e+01, 3.46463546e-02]), + 'Velocity': array([-0.60173619, 0.36064938, 0.00071789]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.170166015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 112.62786102, -1604.56201172, 16.55847168]), + 'frame': 14126, + 'frame_number': 14126, + 'framesequence': 14124, + 'gaze_dir': array([0.98058069, 0.12015851, 0.15499498]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12015851, 0.15499498]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12015851, 0.15499498]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.823561761528254, + 'timestamp_carla': 57823, + 'timestamp_device': 57460, + 'timestamp_stream': 57.823561761528254, + 'transform': [array([ 0.00856682, -0.00515747, 0.1648469 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.01657275, 0.01542547, -8.62724781]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69538116455078, + 'FR_Wheel_Angle': 41.514888763427734, + 'Location': array([ -7.50873947, -22.54050064, 0.17631306]), + 'Rotation': array([-4.66296971e-02, -5.37019653e+01, 3.53956074e-02]), + 'Velocity': array([-0.59441131, 0.36158594, 0.00069933]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1710205078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 113.53890228, -1604.59875488, 16.55749512]), + 'frame': 14127, + 'frame_number': 14127, + 'framesequence': 14125, + 'gaze_dir': array([0.98058069, 0.11953732, 0.15547457]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11953732, 0.15547457]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11953732, 0.15547457]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.827911760658026, + 'timestamp_carla': 57827, + 'timestamp_device': 57464, + 'timestamp_stream': 57.827911760658026, + 'transform': [array([ 0.00853226, -0.00519775, 0.16484553]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.16403727e-02, -6.70879308e-05, -8.99879646e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.701309204101562, + 'FR_Wheel_Angle': 41.52279281616211, + 'Location': array([ -7.53450584, -22.52200317, 0.17634174]), + 'Rotation': array([-4.62335497e-02, -5.41205788e+01, 3.60030383e-02]), + 'Velocity': array([-0.57907093, 0.35877776, 0.00074372]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.172119140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 114.44826508, -1604.64123535, 16.55651855]), + 'frame': 14128, + 'frame_number': 14128, + 'framesequence': 14126, + 'gaze_dir': array([0.98058069, 0.11891481, 0.1559512 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11891481, 0.1559512 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11891481, 0.1559512 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.10713358968496323, + 'timestamp': 57.83141776174307, + 'timestamp_carla': 57831, + 'timestamp_device': 57468, + 'timestamp_stream': 57.83141776174307, + 'transform': [array([ 0.0084951 , -0.0052417 , 0.16484563]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-1.58482399e-02, 6.74459443e-04, -8.07085609e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70842933654785, + 'FR_Wheel_Angle': 41.537296295166016, + 'Location': array([ -7.56020308, -22.50329971, 0.17636608]), + 'Rotation': array([-4.56256606e-02, -5.45376854e+01, 3.63674015e-02]), + 'Velocity': array([-5.62799573e-01, 3.53206217e-01, 2.80780776e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1724853515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 115.35740662, -1604.6862793 , 16.55603027]), + 'frame': 14129, + 'frame_number': 14129, + 'framesequence': 14127, + 'gaze_dir': array([0.98058069, 0.11844609, 0.15630752]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11844609, 0.15630752]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11844609, 0.15630752]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.83487455919385, + 'timestamp_carla': 57834, + 'timestamp_device': 57471, + 'timestamp_stream': 57.83487455919385, + 'transform': [array([ 0.00846581, -0.0052771 , 0.16484621]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.0157831 , 0.01055406, -8.06902885]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.712696075439453, + 'FR_Wheel_Angle': 41.54814147949219, + 'Location': array([ -7.58266687, -22.48673248, 0.1763895 ]), + 'Rotation': array([-4.51680385e-02, -5.49031334e+01, 3.67641896e-02]), + 'Velocity': array([-0.55168587, 0.35137019, 0.00058516]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.17333984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 116.03892517, -1604.72375488, 16.55517578]), + 'frame': 14130, + 'frame_number': 14130, + 'framesequence': 14128, + 'gaze_dir': array([0.98058069, 0.11797688, 0.15666196]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11797688, 0.15666196]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11797688, 0.15666196]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.8380983620882, + 'timestamp_carla': 57838, + 'timestamp_device': 57474, + 'timestamp_stream': 57.8380983620882, + 'transform': [array([ 0.0084304 , -0.00531982, 0.16484666]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-5.07671793e-04, -5.90155972e-03, -7.90390635e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.718442916870117, + 'FR_Wheel_Angle': 41.554779052734375, + 'Location': array([ -7.60625267, -22.46902084, 0.17640297]), + 'Rotation': array([-4.46421131e-02, -5.52914047e+01, 3.69224325e-02]), + 'Velocity': array([-0.53402066, 0.35009474, 0.00088377]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.174072265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 116.72026062, -1604.7623291 , 16.55444336]), + 'frame': 14131, + 'frame_number': 14131, + 'framesequence': 14129, + 'gaze_dir': array([0.98058069, 0.11734904, 0.15713279]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11734904, 0.15713279]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11734904, 0.15713279]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.842115461826324, + 'timestamp_carla': 57842, + 'timestamp_device': 57478, + 'timestamp_stream': 57.842115461826324, + 'transform': [array([ 0.00839561, -0.00536255, 0.16484614]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03454831, 0.02066142, -7.99957609]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.728120803833008, + 'FR_Wheel_Angle': 41.57022476196289, + 'Location': array([ -7.6303997 , -22.45077896, 0.17642951]), + 'Rotation': array([-4.40410562e-02, -5.56849174e+01, 3.76455411e-02]), + 'Velocity': array([-0.51848972, 0.33441374, 0.00075901]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1748046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 117.62973022, -1604.81677246, 16.55371094]), + 'frame': 14132, + 'frame_number': 14132, + 'framesequence': 14130, + 'gaze_dir': array([0.98058069, 0.11671992, 0.15760069]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11671992, 0.15760069]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11671992, 0.15760069]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.846121560782194, + 'timestamp_carla': 57846, + 'timestamp_device': 57482, + 'timestamp_stream': 57.846121560782194, + 'transform': [array([ 0.00834885, -0.00541992, 0.16484536]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 4.90315165e-03, -2.03838609e-02, -7.54316998e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73444175720215, + 'FR_Wheel_Angle': 41.57817459106445, + 'Location': array([ -7.65269327, -22.43372726, 0.17645606]), + 'Rotation': array([-4.34604920e-02, -5.60510750e+01, 3.81097309e-02]), + 'Velocity': array([-0.50040346, 0.33578354, 0.00069434]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1759033203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 118.53823853, -1604.87463379, 16.5526123 ]), + 'frame': 14133, + 'frame_number': 14133, + 'framesequence': 14131, + 'gaze_dir': array([0.98058069, 0.11608833, 0.15806648]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11608833, 0.15806648]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11608833, 0.15806648]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.849747858941555, + 'timestamp_carla': 57849, + 'timestamp_device': 57486, + 'timestamp_stream': 57.849747858941555, + 'transform': [array([ 0.00831482, -0.00546021, 0.16484575]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.60620350e-03, -2.48156693e-02, -7.23343277e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.741228103637695, + 'FR_Wheel_Angle': 41.59410858154297, + 'Location': array([ -7.67305708, -22.41794395, 0.17647636]), + 'Rotation': array([-4.29413952e-02, -5.63872490e+01, 3.82055677e-02]), + 'Velocity': array([-0.48266029, 0.32884353, 0.00053871]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1763916015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 119.4461441 , -1604.93786621, 16.55212402]), + 'frame': 14134, + 'frame_number': 14134, + 'framesequence': 14132, + 'gaze_dir': array([0.98058069, 0.11561386, 0.15841384]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11561386, 0.15841384]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11561386, 0.15841384]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.85313446074724, + 'timestamp_carla': 57853, + 'timestamp_device': 57489, + 'timestamp_stream': 57.85313446074724, + 'transform': [array([ 0.00827438, -0.00551025, 0.16484609]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 6.04785886e-03, -3.45092304e-02, -6.95983362e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.751279830932617, + 'FR_Wheel_Angle': 41.61150360107422, + 'Location': array([ -7.69284391, -22.40244293, 0.17649421]), + 'Rotation': array([-4.23813201e-02, -5.67155571e+01, 3.83776240e-02]), + 'Velocity': array([-0.46142927, 0.3174836 , 0.00060763]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1773681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 120.12640381, -1604.98718262, 16.55114746]), + 'frame': 14135, + 'frame_number': 14135, + 'framesequence': 14133, + 'gaze_dir': array([0.98058069, 0.11497904, 0.15887521]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11497904, 0.15887521]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11497904, 0.15887521]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.85726036131382, + 'timestamp_carla': 57857, + 'timestamp_device': 57493, + 'timestamp_stream': 57.85726036131382, + 'transform': [array([ 0.00823509, -0.00555664, 0.16484541]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03559013, 0.0282498 , -7.06893253]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7613468170166, + 'FR_Wheel_Angle': 41.62565231323242, + 'Location': array([ -7.71328783, -22.3862648 , 0.17651279]), + 'Rotation': array([-4.16846424e-02, -5.70555801e+01, 3.85086127e-02]), + 'Velocity': array([-4.47402447e-01, 3.01303923e-01, 3.57861514e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1781005859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 121.03453827, -1605.0559082 , 16.55041504]), + 'frame': 14136, + 'frame_number': 14136, + 'framesequence': 14134, + 'gaze_dir': array([0.98058069, 0.11434297, 0.1593336 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11434297, 0.1593336 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11434297, 0.1593336 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.86090566217899, + 'timestamp_carla': 57860, + 'timestamp_device': 57497, + 'timestamp_stream': 57.86090566217899, + 'transform': [array([ 0.00818977, -0.00561157, 0.16484544]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 0.00815688, -0.02935501, -6.33096027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.770164489746094, + 'FR_Wheel_Angle': 41.64187240600586, + 'Location': array([ -7.73222876, -22.37104988, 0.17653167]), + 'Rotation': array([-4.11109067e-02, -5.73710709e+01, 3.83717977e-02]), + 'Velocity': array([-0.41934812, 0.29730329, 0.00046982]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1790771484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 121.94165802, -1605.12792969, 16.54943848]), + 'frame': 14137, + 'frame_number': 14137, + 'framesequence': 14135, + 'gaze_dir': array([0.98058069, 0.11386409, 0.15967618]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11386409, 0.15967618]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11386409, 0.15967618]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.864286959171295, + 'timestamp_carla': 57864, + 'timestamp_device': 57500, + 'timestamp_stream': 57.864286959171295, + 'transform': [array([ 0.00815407, -0.0056543 , 0.16484621]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([ 5.81305753e-03, -3.16660553e-02, -6.05085135e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.780447006225586, + 'FR_Wheel_Angle': 41.65876770019531, + 'Location': array([ -7.74897194, -22.35746765, 0.17654759]), + 'Rotation': array([-4.06191312e-02, -5.76511307e+01, 3.85101736e-02]), + 'Velocity': array([-0.3981176 , 0.28471318, 0.00058896]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 122.6211319 , -1605.18640137, 16.54882812]), + 'frame': 14138, + 'frame_number': 14138, + 'framesequence': 14136, + 'gaze_dir': array([0.98058069, 0.11322483, 0.1601301 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11322483, 0.1601301 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11322483, 0.1601301 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.86763396114111, + 'timestamp_carla': 57867, + 'timestamp_device': 57504, + 'timestamp_stream': 57.86763396114111, + 'transform': [array([ 0.00811012, -0.00570679, 0.16484663]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.048089 , 0.04635694, -6.27803183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79180335998535, + 'FR_Wheel_Angle': 41.674739837646484, + 'Location': array([ -7.76630211, -22.34333038, 0.17655967]), + 'Rotation': array([-4.00727168e-02, -5.79439468e+01, 3.90991606e-02]), + 'Velocity': array([-0.38601702, 0.26351234, -0.00069352]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 123.52811432, -1605.2644043 , 16.54797363]), + 'frame': 14139, + 'frame_number': 14139, + 'framesequence': 14137, + 'gaze_dir': array([0.98058069, 0.11258316, 0.1605819 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11258316, 0.1605819 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11258316, 0.1605819 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.87157076224685, + 'timestamp_carla': 57871, + 'timestamp_device': 57508, + 'timestamp_stream': 57.87157076224685, + 'transform': [array([ 0.0080674 , -0.00575806, 0.16484639]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03751514, 0.0213261 , -5.68628931]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80484390258789, + 'FR_Wheel_Angle': 41.69928741455078, + 'Location': array([ -7.78151846, -22.33075905, 0.17657146]), + 'Rotation': array([-3.94238494e-02, -5.81986504e+01, 3.86781469e-02]), + 'Velocity': array([-3.56344849e-01, 2.48654470e-01, 1.78098671e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1815185546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 124.43482971, -1605.3470459 , 16.54711914]), + 'frame': 14140, + 'frame_number': 14140, + 'framesequence': 14138, + 'gaze_dir': array([0.98058069, 0.11194029, 0.16103069]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11194029, 0.16103069]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11194029, 0.16103069]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.87576046213508, + 'timestamp_carla': 57875, + 'timestamp_device': 57512, + 'timestamp_stream': 57.87576046213508, + 'transform': [array([ 0.00800941, -0.00582764, 0.16484533]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.03470103, 0.01839592, -5.28544092]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.820110321044922, + 'FR_Wheel_Angle': 41.72519302368164, + 'Location': array([ -7.79555321, -22.31916237, 0.17656963]), + 'Rotation': array([-3.84198129e-02, -5.84347382e+01, 3.83427106e-02]), + 'Velocity': array([-0.32626945, 0.22796512, 0.00054395]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.182373046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 125.34049988, -1605.43322754, 16.54638672]), + 'frame': 14141, + 'frame_number': 14141, + 'framesequence': 14139, + 'gaze_dir': array([0.98058069, 0.11145633, 0.16136603]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11145633, 0.16136603]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11145633, 0.16136603]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.87930665910244, + 'timestamp_carla': 57879, + 'timestamp_device': 57515, + 'timestamp_stream': 57.87930665910244, + 'transform': [array([ 0.00796883, -0.00587646, 0.16484587]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00949853, 0.01530986, -5.23681545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82223129272461, + 'FR_Wheel_Angle': 41.72764205932617, + 'Location': array([ -7.81044912, -22.30652618, 0.17658816]), + 'Rotation': array([-3.86383794e-02, -5.86872978e+01, 3.92353646e-02]), + 'Velocity': array([-0.31473196, 0.23025635, 0.00084261]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1829833984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 126.01782227, -1605.50341797, 16.54553223]), + 'frame': 14142, + 'frame_number': 14142, + 'framesequence': 14140, + 'gaze_dir': array([0.98058069, 0.11081034, 0.16181032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11081034, 0.16181032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11081034, 0.16181032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.882991660386324, + 'timestamp_carla': 57883, + 'timestamp_device': 57519, + 'timestamp_stream': 57.882991660386324, + 'transform': [array([ 0.0079171 , -0.00593872, 0.1648459 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-7.02603627e-03, -4.74200444e-03, -4.91383505e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.833749771118164, + 'FR_Wheel_Angle': 41.7490119934082, + 'Location': array([ -7.82327127, -22.29564095, 0.17660983]), + 'Rotation': array([-3.84198129e-02, -5.89067726e+01, 3.96869071e-02]), + 'Velocity': array([-0.29139134, 0.21498884, 0.00061999]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1839599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 126.92311096, -1605.59558105, 16.54467773]), + 'frame': 14143, + 'frame_number': 14143, + 'framesequence': 14141, + 'gaze_dir': array([0.98058069, 0.11016195, 0.16225246]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11016195, 0.16225246]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11016195, 0.16225246]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.886806059628725, + 'timestamp_carla': 57886, + 'timestamp_device': 57523, + 'timestamp_stream': 57.886806059628725, + 'transform': [array([ 0.00787338, -0.00599121, 0.16484597]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-6.17765449e-03, -2.19678695e-04, -4.58565426e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.844032287597656, + 'FR_Wheel_Angle': 41.765350341796875, + 'Location': array([ -7.83508873, -22.28555298, 0.17662518]), + 'Rotation': array([-3.80236618e-02, -5.91085014e+01, 3.98268625e-02]), + 'Velocity': array([-0.27050403, 0.201308 , 0.00046734]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.184814453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 127.82781982, -1605.69287109, 16.54382324]), + 'frame': 14144, + 'frame_number': 14144, + 'framesequence': 14142, + 'gaze_dir': array([0.98058069, 0.10951179, 0.16269198]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.10951179, 0.16269198]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.10951179, 0.16269198]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.89098056033254, + 'timestamp_carla': 57891, + 'timestamp_device': 57527, + 'timestamp_stream': 57.89098056033254, + 'transform': [array([ 0.00781364, -0.00606323, 0.16484499]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00971025, 0.01859128, -3.69518042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.85193634033203, + 'FR_Wheel_Angle': 41.779518127441406, + 'Location': array([ -7.84640646, -22.27585411, 0.17664279]), + 'Rotation': array([-3.78392451e-02, -5.92993584e+01, 4.03634459e-02]), + 'Velocity': array([-0.25567755, 0.19008586, 0.00047048]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1856689453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 128.73294067, -1605.79284668, 16.54309082]), + 'frame': 14145, + 'frame_number': 14145, + 'framesequence': 14143, + 'gaze_dir': array([0.98058069, 0.10886052, 0.16312848]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.10886052, 0.16312848]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.10886052, 0.16312848]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.8948782607913, + 'timestamp_carla': 57894, + 'timestamp_device': 57531, + 'timestamp_stream': 57.8948782607913, + 'transform': [array([ 0.00776863, -0.00611816, 0.16484499]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-3.84290656e-03, 9.19226464e-03, -4.06358147e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.860841751098633, + 'FR_Wheel_Angle': 41.7938232421875, + 'Location': array([ -7.85707808, -22.26662254, 0.17665587]), + 'Rotation': array([-3.78119238e-02, -5.94817085e+01, 4.08803932e-02]), + 'Velocity': array([-0.23674108, 0.1786226 , 0.00031019]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1864013671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 129.63519287, -1605.8984375 , 16.54223633]), + 'frame': 14146, + 'frame_number': 14146, + 'framesequence': 14144, + 'gaze_dir': array([0.98058069, 0.10820687, 0.16356279]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.10820687, 0.16356279]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.10820687, 0.16356279]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.89864645898342, + 'timestamp_carla': 57898, + 'timestamp_device': 57535, + 'timestamp_stream': 57.89864645898342, + 'transform': [array([ 0.00771523, -0.00618164, 0.16484492]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- +{'AngularVelocity': array([-0.00958912, 0.03111077, -3.61589074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.865070343017578, + 'FR_Wheel_Angle': 41.80097198486328, + 'Location': array([ -7.86727667, -22.25761986, 0.17666698]), + 'Rotation': array([-3.80851328e-02, -5.96564522e+01, 4.14913893e-02]), + 'Velocity': array([-0.22738895, 0.17356044, 0.00040406]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.187255859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 130.53939819, -1606.00585938, 16.54138184]), + 'frame': 14147, + 'frame_number': 14147, + 'framesequence': 14145, + 'gaze_dir': array([0.98058069, 0.10771596, 0.1638865 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.10771596, 0.1638865 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.10771596, 0.1638865 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.1111009418964386, + 'timestamp': 57.90216366201639, + 'timestamp_carla': 57902, + 'timestamp_device': 57538, + 'timestamp_stream': 57.90216366201639, + 'transform': [array([ 0.00767387, -0.00623169, 0.16484556]), + array([-0.0574214 , -0.02758213, 0.01046066])]} +---------------------- \ No newline at end of file diff --git a/PythonAPI/data/trials/trial_vx_const.txt b/PythonAPI/data/trials/trial_vx_const.txt new file mode 100644 index 0000000..5557e9b --- /dev/null +++ b/PythonAPI/data/trials/trial_vx_const.txt @@ -0,0 +1,13968 @@ +{'AngularVelocity': array([-5.02542025e-05, -6.16663310e-05, -1.45835736e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03633523, -18.32970047, 0.16739699]), + 'Rotation': array([-4.45533209e-02, 4.99705849e+01, -3.80554199e-02]), + 'Velocity': array([4.47819912e-06, 2.26026160e-07, 1.03856968e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3089599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 242.28588867, -1650.23352051, 16.44641113]), + 'frame': 8836, + 'frame_number': 8836, + 'framesequence': 8834, + 'gaze_dir': array([0.98058069, 0.0095876 , 0.19588162]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.0095876 , 0.19588162]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.0095876 , 0.19588162]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.54496895894408, + 'timestamp_carla': 39544, + 'timestamp_device': 39221, + 'timestamp_stream': 39.54496895894408, + 'transform': [array([ 0.01063606, -0.00334961, 0.16534814]), + array([-0.05779706, -0.02947373, 0.00967011])]} +---------------------- +{'AngularVelocity': array([-1.53589499, -1.91157985, 0.03771443]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0176754 , -18.33627129, 0.16739494]), + 'Rotation': array([-4.34878133e-02, 4.99714165e+01, 1.64789408e-02]), + 'Velocity': array([-4.97696668e-01, -3.55581552e-01, 2.87935720e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3095703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 243.01461792, -1650.7845459 , 16.44592285]), + 'frame': 8837, + 'frame_number': 8837, + 'framesequence': 8835, + 'gaze_dir': array([0.98058069, 0.00880368, 0.19591843]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00880368, 0.19591843]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00880368, 0.19591843]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.548724956810474, + 'timestamp_carla': 39548, + 'timestamp_device': 39225, + 'timestamp_stream': 39.548724956810474, + 'transform': [array([ 0.01063606, -0.00334961, 0.16534814]), + array([-0.05779706, -0.02947373, 0.00967011])]} +---------------------- +{'AngularVelocity': array([-1.72529483, -2.16318679, 0.07694051]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 0.99295735, -18.3499527 , 0.16737756]), + 'Rotation': array([-4.06191312e-02, 4.99734001e+01, 1.13837928e-01]), + 'Velocity': array([-5.69891393e-01, -3.17112446e-01, 3.46057408e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3101806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 243.74185181, -1651.33898926, 16.44519043]), + 'frame': 8838, + 'frame_number': 8838, + 'framesequence': 8836, + 'gaze_dir': array([0.98058069, 0.00802037, 0.19595204]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00802037, 0.19595204]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00802037, 0.19595204]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.552578158676624, + 'timestamp_carla': 39552, + 'timestamp_device': 39229, + 'timestamp_stream': 39.552578158676624, + 'transform': [array([ 0.01063622, -0.00334961, 0.16534925]), + array([-0.05779706, -0.02947373, 0.00967011])]} +---------------------- +{'AngularVelocity': array([-1.52519453, -1.91686833, 0.08368525]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 0.96539158, -18.36513138, 0.16737089]), + 'Rotation': array([-3.73201519e-02, 4.99763985e+01, 2.19669953e-01]), + 'Velocity': array([-5.47536314e-01, -3.32490087e-01, 3.36122495e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3106689453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 244.46614075, -1651.89599609, 16.44482422]), + 'frame': 8839, + 'frame_number': 8839, + 'framesequence': 8837, + 'gaze_dir': array([0.98058069, 0.00723618, 0.19598258]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00723618, 0.19598258]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00723618, 0.19598258]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.55689875781536, + 'timestamp_carla': 39556, + 'timestamp_device': 39233, + 'timestamp_stream': 39.55689875781536, + 'transform': [array([ 0.01063622, -0.00334961, 0.16534925]), + array([-0.05779706, -0.02947373, 0.00967011])]} +---------------------- +{'AngularVelocity': array([-1.3084836 , -1.64257181, 0.06470376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2794767618179321, + 'FR_Wheel_Angle': 1.6088588237762451, + 'Location': array([ 0.9400118 , -18.37899399, 0.16736849]), + 'Rotation': array([-3.46632078e-02, 4.99789009e+01, 2.96504855e-01]), + 'Velocity': array([-5.92067599e-01, -3.01457196e-01, 4.15918825e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3114013671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 245.18896484, -1652.45617676, 16.44421387]), + 'frame': 8840, + 'frame_number': 8840, + 'framesequence': 8838, + 'gaze_dir': array([0.98058069, 0.00645188, 0.19600996]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00645188, 0.19600996]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00645188, 0.19600996]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.560320258140564, + 'timestamp_carla': 39560, + 'timestamp_device': 39237, + 'timestamp_stream': 39.560320258140564, + 'transform': [array([ 0.01063637, -0.00334961, 0.16535093]), + array([-0.05779706, -0.02947373, 0.00967011])]} +---------------------- +{'AngularVelocity': array([-1.18534088, -1.50138974, -0.3171325 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.5415616035461426, + 'FR_Wheel_Angle': 2.654147148132324, + 'Location': array([ 0.91363716, -18.39305115, 0.16736504]), + 'Rotation': array([-3.21633592e-02, 4.99685974e+01, 3.68427515e-01]), + 'Velocity': array([-5.62802732e-01, -3.09902251e-01, -3.70473863e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3118896484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 245.9094696 , -1653.01940918, 16.44372559]), + 'frame': 8841, + 'frame_number': 8841, + 'framesequence': 8839, + 'gaze_dir': array([0.98058069, 0.00586415, 0.19602844]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00586415, 0.19602844]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00586415, 0.19602844]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.56362495943904, + 'timestamp_carla': 39563, + 'timestamp_device': 39240, + 'timestamp_stream': 39.56362495943904, + 'transform': [array([ 0.01063622, -0.00334961, 0.16535215]), + array([-0.05779706, -0.02947373, 0.00967011])]} +---------------------- +{'AngularVelocity': array([-0.90388006, -1.16299188, -0.54954326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.5127370357513428, + 'FR_Wheel_Angle': 3.7191286087036133, + 'Location': array([ 0.88566512, -18.40800667, 0.16736722]), + 'Rotation': array([-2.94449441e-02, 4.99459839e+01, 4.34627265e-01]), + 'Velocity': array([-4.87906635e-01, -3.52295876e-01, 2.79607775e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3123779296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 246.44789124, -1653.4432373 , 16.44335938]), + 'frame': 8842, + 'frame_number': 8842, + 'framesequence': 8840, + 'gaze_dir': array([0.98058069, 0.00507967, 0.19605032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00507967, 0.19605032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00507967, 0.19605032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.56765615940094, + 'timestamp_carla': 39567, + 'timestamp_device': 39244, + 'timestamp_stream': 39.56765615940094, + 'transform': [array([ 0.01063622, -0.00334961, 0.16535215]), + array([-0.05779706, -0.02947373, 0.00967011])]} +---------------------- +{'AngularVelocity': array([-0.73924065, -0.96058613, -0.69653893]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.357574462890625, + 'FR_Wheel_Angle': 4.615684509277344, + 'Location': array([ 0.85987067, -18.422472 , 0.16736279]), + 'Rotation': array([-2.71226801e-02, 4.99154015e+01, 4.68103796e-01]), + 'Velocity': array([-5.36848605e-01, -3.15923542e-01, 3.27863672e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3131103515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 247.16444397, -1654.01147461, 16.44274902]), + 'frame': 8843, + 'frame_number': 8843, + 'framesequence': 8841, + 'gaze_dir': array([0.98058069, 0.0040999 , 0.19607326]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.0040999 , 0.19607326]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.0040999 , 0.19607326]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.57230515778065, + 'timestamp_carla': 39572, + 'timestamp_device': 39249, + 'timestamp_stream': 39.57230515778065, + 'transform': [array([ 0.00650764, -0.00369629, 0.16446042]), + array([-0.05455272, -0.02946786, 0.01226779])]} +---------------------- +{'AngularVelocity': array([-0.705037 , -0.91734773, -0.83942193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.049478530883789, + 'FR_Wheel_Angle': 5.372513294219971, + 'Location': array([ 0.83369184, -18.43626404, 0.16735907]), + 'Rotation': array([-2.48345658e-02, 4.98787651e+01, 5.06261408e-01]), + 'Velocity': array([-5.04922390e-01, -3.32145423e-01, 4.44903359e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.313720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 248.05607605, -1654.72509766, 16.44213867]), + 'frame': 8844, + 'frame_number': 8844, + 'framesequence': 8842, + 'gaze_dir': array([0.98058069, 0.00331526, 0.19608811]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00331526, 0.19608811]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00331526, 0.19608811]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.57648755982518, + 'timestamp_carla': 39576, + 'timestamp_device': 39253, + 'timestamp_stream': 39.57648755982518, + 'transform': [array([ 0.00316849, -0.0043042 , 0.16310836]), + array([-0.0496623 , -0.029411 , 0.01621524])]} +---------------------- +{'AngularVelocity': array([-0.62472439, -0.81573743, -0.9432925 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.6235785484313965, + 'FR_Wheel_Angle': 6.004334926605225, + 'Location': array([ 0.80847156, -18.44958687, 0.16736399]), + 'Rotation': array([-2.27650199e-02, 4.98377419e+01, 5.33169150e-01]), + 'Velocity': array([-5.23601830e-01, -3.16942722e-01, 4.48827719e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.313720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 248.28210449, -1655.27587891, 16.4420166 ]), + 'frame': 8845, + 'frame_number': 8845, + 'framesequence': 8843, + 'gaze_dir': array([0.98058069, 0.00253131, 0.19609979]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00253131, 0.19609979]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00253131, 0.19609979]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.58059145882726, + 'timestamp_carla': 39580, + 'timestamp_device': 39257, + 'timestamp_stream': 39.58059145882726, + 'transform': [array([ 0.00022102, -0.00516235, 0.16137491]), + array([-0.04339219, -0.02927542, 0.02127705])]} +---------------------- +{'AngularVelocity': array([-0.56692016, -0.74249637, -1.05430377]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.26564359664917, + 'FR_Wheel_Angle': 6.711528301239014, + 'Location': array([ 0.782462 , -18.46342659, 0.16736844]), + 'Rotation': array([-2.08115857e-02, 4.97900162e+01, 5.56381345e-01]), + 'Velocity': array([-5.13249576e-01, -3.19960594e-01, -8.16202155e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.313720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 248.54870605, -1655.8248291 , 16.44189453]), + 'frame': 8846, + 'frame_number': 8846, + 'framesequence': 8844, + 'gaze_dir': array([0.98058069, 0.00174658, 0.19610836]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00174658, 0.19610836]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00174658, 0.19610836]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.58432575687766, + 'timestamp_carla': 39584, + 'timestamp_device': 39261, + 'timestamp_stream': 39.58432575687766, + 'transform': [array([-0.00220734, -0.00614014, 0.15956889]), + array([-0.03686253, -0.02912222, 0.02655465])]} +---------------------- +{'AngularVelocity': array([-0.52174598, -0.68444628, -1.14981413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.8205485343933105, + 'FR_Wheel_Angle': 7.353399276733398, + 'Location': array([ 0.75740498, -18.47649193, 0.1673792 ]), + 'Rotation': array([-1.91381890e-02, 4.97395020e+01, 5.74676156e-01]), + 'Velocity': array([-5.25615811e-01, -3.09050947e-01, 5.21080510e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3135986328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 248.82409668, -1656.37658691, 16.4420166 ]), + 'frame': 8847, + 'frame_number': 8847, + 'framesequence': 8845, + 'gaze_dir': array([9.80580688e-01, 9.61813552e-04, 1.96113780e-01]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([9.80580688e-01, 9.61813552e-04, 1.96113780e-01]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([9.80580688e-01, 9.61813552e-04, 1.96113780e-01]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.58819545805454, + 'timestamp_carla': 39588, + 'timestamp_device': 39265, + 'timestamp_stream': 39.58819545805454, + 'transform': [array([-0.00448311, -0.00732666, 0.15754175]), + array([-0.02952008, -0.02895129, 0.03247582])]} +---------------------- +{'AngularVelocity': array([-0.48748103, -0.64081317, -1.24528277]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.357680797576904, + 'FR_Wheel_Angle': 7.970518589019775, + 'Location': array([ 0.73192704, -18.48973274, 0.16738653]), + 'Rotation': array([-1.74852833e-02, 4.96835480e+01, 5.91360629e-01]), + 'Velocity': array([-5.18218935e-01, -3.10649186e-01, 2.81760673e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3138427734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 249.14395142, -1656.93774414, 16.44177246]), + 'frame': 8848, + 'frame_number': 8848, + 'framesequence': 8846, + 'gaze_dir': array([9.80580688e-01, 3.73791991e-04, 1.96115777e-01]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([9.80580688e-01, 3.73791991e-04, 1.96115777e-01]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([9.80580688e-01, 3.73791991e-04, 1.96115777e-01]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.59203225746751, + 'timestamp_carla': 39591, + 'timestamp_device': 39268, + 'timestamp_stream': 39.59203225746751, + 'transform': [array([-0.00654381, -0.0086438 , 0.15548259]), + array([-0.02206151, -0.02877275, 0.03849063])]} +---------------------- +{'AngularVelocity': array([-0.45583037, -0.60060126, -1.33599162]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.856771469116211, + 'FR_Wheel_Angle': 8.568253517150879, + 'Location': array([ 0.70655984, -18.50275993, 0.16739534]), + 'Rotation': array([-1.58938486e-02, 4.96238518e+01, 6.07048333e-01]), + 'Velocity': array([-5.02698720e-01, -3.17382544e-01, 3.27615737e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.31396484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 249.2832489 , -1657.36120605, 16.44177246]), + 'frame': 8849, + 'frame_number': 8849, + 'framesequence': 8847, + 'gaze_dir': array([ 9.80580688e-01, -4.10989247e-04, 1.96115687e-01]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, -4.10989247e-04, 1.96115687e-01]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, -4.10989247e-04, 1.96115687e-01]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.595557659864426, + 'timestamp_carla': 39595, + 'timestamp_device': 39272, + 'timestamp_stream': 39.595557659864426, + 'transform': [array([-0.00829658, -0.00993896, 0.15362878]), + array([-0.01533377, -0.02862437, 0.04390587])]} +---------------------- +{'AngularVelocity': array([-0.35543999, -0.47225735, -1.38700068]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.280486106872559, + 'FR_Wheel_Angle': 9.034223556518555, + 'Location': array([ 0.68165761, -18.51659584, 0.1674051 ]), + 'Rotation': array([-1.47122266e-02, 4.95586891e+01, 6.08695507e-01]), + 'Velocity': array([-0.55020708, -0.28626499, 0.00071513]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3135986328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 249.61595154, -1657.94421387, 16.44189453]), + 'frame': 8850, + 'frame_number': 8850, + 'framesequence': 8848, + 'gaze_dir': array([ 0.98058069, -0.00099901, 0.19611359]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00099901, 0.19611359]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00099901, 0.19611359]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.599107056856155, + 'timestamp_carla': 39598, + 'timestamp_device': 39275, + 'timestamp_stream': 39.599107056856155, + 'transform': [array([-0.00994835, -0.01131226, 0.15184085]), + array([-0.0088246 , -0.02848226, 0.04912762])]} +---------------------- +{'AngularVelocity': array([-0.35894921, -0.47253162, -1.45001221]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.697103500366211, + 'FR_Wheel_Angle': 9.533251762390137, + 'Location': array([ 0.65613538, -18.53065681, 0.16742189]), + 'Rotation': array([-1.35852452e-02, 4.94886246e+01, 6.10015929e-01]), + 'Velocity': array([-0.56412083, -0.27591816, 0.0009796 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3138427734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 249.81762695, -1658.39331055, 16.44165039]), + 'frame': 8851, + 'frame_number': 8851, + 'framesequence': 8849, + 'gaze_dir': array([ 0.98058069, -0.00178377, 0.19610803]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00178377, 0.19610803]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00178377, 0.19610803]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.602714259177446, + 'timestamp_carla': 39602, + 'timestamp_device': 39279, + 'timestamp_stream': 39.602714259177446, + 'transform': [array([-0.01153427, -0.01275146, 0.15015087]), + array([-0.00261596, -0.02834993, 0.05405955])]} +---------------------- +{'AngularVelocity': array([-0.42075124, -0.55051661, -1.56095302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.15229320526123, + 'FR_Wheel_Angle': 10.084376335144043, + 'Location': array([ 0.6296975 , -18.54398727, 0.16743955]), + 'Rotation': array([-1.21509060e-02, 4.94158936e+01, 6.26459181e-01]), + 'Velocity': array([-0.48051837, -0.32383379, 0.00058291]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3138427734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 250.20733643, -1659.00463867, 16.44152832]), + 'frame': 8852, + 'frame_number': 8852, + 'framesequence': 8850, + 'gaze_dir': array([ 0.98058069, -0.00256776, 0.19609931]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00256776, 0.19609931]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00256776, 0.19609931]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.606355760246515, + 'timestamp_carla': 39606, + 'timestamp_device': 39283, + 'timestamp_stream': 39.606355760246515, + 'transform': [array([-0.01305992, -0.01423706, 0.14860108]), + array([ 0.00315555, -0.02824805, 0.05857845])]} +---------------------- +{'AngularVelocity': array([-0.34235451, -0.45194623, -1.61581397]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.584680557250977, + 'FR_Wheel_Angle': 10.573997497558594, + 'Location': array([ 0.60466653, -18.55727768, 0.1674526 ]), + 'Rotation': array([-1.10170944e-02, 4.93412514e+01, 6.30085468e-01]), + 'Velocity': array([-0.50144166, -0.30928534, 0.00056287]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3140869140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 250.60704041, -1659.63146973, 16.44128418]), + 'frame': 8853, + 'frame_number': 8853, + 'framesequence': 8851, + 'gaze_dir': array([ 0.98058069, -0.00315647, 0.19609073]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00315647, 0.19609073]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00315647, 0.19609073]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.609921257942915, + 'timestamp_carla': 39609, + 'timestamp_device': 39286, + 'timestamp_stream': 39.609921257942915, + 'transform': [array([-0.01449936, -0.01570801, 0.14723577]), + array([ 0.00823038, -0.0281598 , 0.06255978])]} +---------------------- +{'AngularVelocity': array([-0.37852889, -0.49498922, -1.67045081]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.914741516113281, + 'FR_Wheel_Angle': 10.995377540588379, + 'Location': array([ 0.58024061, -18.56955147, 0.16746728]), + 'Rotation': array([-9.95158497e-03, 4.92673149e+01, 6.36382103e-01]), + 'Velocity': array([-5.11831582e-01, -3.01493138e-01, 3.62310413e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.313720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 250.84812927, -1660.12597656, 16.44140625]), + 'frame': 8854, + 'frame_number': 8854, + 'framesequence': 8852, + 'gaze_dir': array([ 0.98058069, -0.00394037, 0.19607654]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00394037, 0.19607654]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00394037, 0.19607654]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.61337376013398, + 'timestamp_carla': 39613, + 'timestamp_device': 39290, + 'timestamp_stream': 39.61337376013398, + 'transform': [array([-0.01585281, -0.01714355, 0.14606728]), + array([ 0.01262219, -0.02807847, 0.06596494])]} +---------------------- +{'AngularVelocity': array([-0.31482092, -0.41637304, -1.74957216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.20146369934082, + 'FR_Wheel_Angle': 11.340673446655273, + 'Location': array([ 0.55377316, -18.58325958, 0.16748209]), + 'Rotation': array([-8.66751000e-03, 4.91832047e+01, 6.45187259e-01]), + 'Velocity': array([-4.55831468e-01, -3.32347244e-01, 3.74603260e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.314208984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 251.28305054, -1660.78234863, 16.4407959 ]), + 'frame': 8855, + 'frame_number': 8855, + 'framesequence': 8853, + 'gaze_dir': array([ 0.98058069, -0.00472496, 0.1960592 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00472496, 0.1960592 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00472496, 0.1960592 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.61744146049023, + 'timestamp_carla': 39617, + 'timestamp_device': 39294, + 'timestamp_stream': 39.61744146049023, + 'transform': [array([-0.01739983, -0.01883423, 0.1448914 ]), + array([ 0.01712328, -0.02801049, 0.06938351])]} +---------------------- +{'AngularVelocity': array([-0.31235114, -0.41296932, -1.80361187]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.514036178588867, + 'FR_Wheel_Angle': 11.724313735961914, + 'Location': array([ 0.5297184 , -18.594944 , 0.16748591]), + 'Rotation': array([-7.50637753e-03, 4.91068764e+01, 6.56842470e-01]), + 'Velocity': array([-0.44256306, -0.33858722, 0.00058019]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.314208984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 251.73986816, -1661.45092773, 16.4407959 ]), + 'frame': 8856, + 'frame_number': 8856, + 'framesequence': 8854, + 'gaze_dir': array([ 0.98058069, -0.00550873, 0.19603874]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00550873, 0.19603874]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00550873, 0.19603874]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.62163955718279, + 'timestamp_carla': 39621, + 'timestamp_device': 39298, + 'timestamp_stream': 39.62163955718279, + 'transform': [array([-0.02120232, -0.0191687 , 0.14317112]), + array([ 0.02352317, -0.02786898, 0.07439526])]} +---------------------- +{'AngularVelocity': array([-0.23672955, -0.31464067, -1.83202183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.862103462219238, + 'FR_Wheel_Angle': 12.156705856323242, + 'Location': array([ 0.50431561, -18.60891533, 0.16749261]), + 'Rotation': array([-6.80969842e-03, 4.90182648e+01, 6.50286496e-01]), + 'Velocity': array([-0.46481821, -0.3247394 , -0.00128085]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3140869140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 252.17181396, -1662.1472168 , 16.44067383]), + 'frame': 8857, + 'frame_number': 8857, + 'framesequence': 8855, + 'gaze_dir': array([ 0.98058069, -0.00648906, 0.19600874]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00648906, 0.19600874]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00648906, 0.19600874]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.62630805745721, + 'timestamp_carla': 39626, + 'timestamp_device': 39303, + 'timestamp_stream': 39.62630805745721, + 'transform': [array([-0.02498611, -0.019906 , 0.14080067]), + array([ 0.03223166, -0.02759842, 0.08130376])]} +---------------------- +{'AngularVelocity': array([-0.27768055, -0.36148778, -1.87621999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.197578430175781, + 'FR_Wheel_Angle': 12.585803031921387, + 'Location': array([ 0.47961321, -18.62190628, 0.16751565]), + 'Rotation': array([-6.19498128e-03, 4.89315033e+01, 6.46332741e-01]), + 'Velocity': array([-0.48792639, -0.31002703, 0.00066236]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1463623046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 253.19561768, -1664.60217285, 16.44042969]), + 'frame': 8858, + 'frame_number': 8858, + 'framesequence': 8856, + 'gaze_dir': array([ 0.98058069, -0.00707748, 0.19598839]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00707748, 0.19598839]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00707748, 0.19598839]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.62980445846915, + 'timestamp_carla': 39629, + 'timestamp_device': 39306, + 'timestamp_stream': 39.62980445846915, + 'transform': [array([-0.02758041, -0.02064697, 0.13888183]), + array([ 0.03928041, -0.02734903, 0.08690478])]} +---------------------- +{'AngularVelocity': array([-0.3379761 , -0.43507767, -1.91736352]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.526713371276855, + 'FR_Wheel_Angle': 12.99384880065918, + 'Location': array([ 0.45553279, -18.63396454, 0.16753908]), + 'Rotation': array([-5.46415104e-03, 4.88462639e+01, 6.47717237e-01]), + 'Velocity': array([-0.51159585, -0.29496866, 0.00057755]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.14404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 253.36602783, -1665.20239258, 16.44030762]), + 'frame': 8859, + 'frame_number': 8859, + 'framesequence': 8857, + 'gaze_dir': array([ 0.98058069, -0.00825263, 0.19594242]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00825263, 0.19594242]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00825263, 0.19594242]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.0, + 'timestamp': 39.635903757065535, + 'timestamp_carla': 39635, + 'timestamp_device': 39312, + 'timestamp_stream': 39.635903757065535, + 'transform': [array([-0.03145142, -0.0224292 , 0.13514581]), + array([ 0.05291347, -0.02686239, 0.09778427])]} +---------------------- +{'AngularVelocity': array([-0.31063598, -0.40461278, -2.00530195]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.890398979187012, + 'FR_Wheel_Angle': 13.447943687438965, + 'Location': array([ 0.42949939, -18.647089 , 0.16755778]), + 'Rotation': array([-4.39864164e-03, 4.87511215e+01, 6.56029284e-01]), + 'Velocity': array([-0.45285693, -0.32668865, 0.00061519]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.153076171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 254.1242218 , -1666.16271973, 16.44018555]), + 'frame': 8860, + 'frame_number': 8860, + 'framesequence': 8858, + 'gaze_dir': array([ 0.98058069, -0.00903665, 0.19590783]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00903665, 0.19590783]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00903665, 0.19590783]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00012817775132134557, + 'throttle_input': 0.0, + 'timestamp': 39.63968085870147, + 'timestamp_carla': 39639, + 'timestamp_device': 39316, + 'timestamp_stream': 39.63968085870147, + 'transform': [array([-0.03364021, -0.02368408, 0.13291726]), + array([ 0.06109604, -0.026548 , 0.1042895 ])]} +---------------------- +{'AngularVelocity': array([-0.27091488, -0.35161966, -2.0095942 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.209534645080566, + 'FR_Wheel_Angle': 13.835931777954102, + 'Location': array([ 0.4053838 , -18.65978622, 0.16758153]), + 'Rotation': array([-3.78392451e-03, 4.86582565e+01, 6.50420070e-01]), + 'Velocity': array([-0.50859493, -0.29393175, 0.00078907]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.15966796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 254.4347229 , -1666.95800781, 16.44006348]), + 'frame': 8861, + 'frame_number': 8861, + 'framesequence': 8859, + 'gaze_dir': array([ 0.98058069, -0.00982052, 0.1958701 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00982052, 0.1958701 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00982052, 0.1958701 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.0, + 'timestamp': 39.64405865967274, + 'timestamp_carla': 39643, + 'timestamp_device': 39320, + 'timestamp_stream': 39.64405865967274, + 'transform': [array([-0.03593559, -0.02529419, 0.13042769]), + array([ 0.07022117, -0.02620398, 0.11155203])]} +---------------------- +{'AngularVelocity': array([-0.26223803, -0.34466815, -2.11898017]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.546095848083496, + 'FR_Wheel_Angle': 14.288741111755371, + 'Location': array([ 0.37882131, -18.67339134, 0.16760255]), + 'Rotation': array([-2.77988683e-03, 4.85550079e+01, 6.57611787e-01]), + 'Velocity': array([-0.42684436, -0.3379578 , 0.00059515]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1728515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 254.82653809, -1667.57995605, 16.44006348]), + 'frame': 8862, + 'frame_number': 8862, + 'framesequence': 8860, + 'gaze_dir': array([ 0.98058069, -0.01079921, 0.19581857]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01079921, 0.19581857]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01079921, 0.19581857]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 39.64816835895181, + 'timestamp_carla': 39648, + 'timestamp_device': 39325, + 'timestamp_stream': 39.64816835895181, + 'transform': [array([-0.03791992, -0.02689575, 0.12827641]), + array([ 0.07813736, -0.0259427 , 0.11782987])]} +---------------------- +{'AngularVelocity': array([-0.247036 , -0.3192682 , -2.07304692]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.849108695983887, + 'FR_Wheel_Angle': 14.67261028289795, + 'Location': array([ 0.35623994, -18.68532753, 0.1676285 ]), + 'Rotation': array([-2.47252826e-03, 4.84628563e+01, 6.47589087e-01]), + 'Velocity': array([-5.42408645e-01, -2.72146881e-01, 4.16088093e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.176025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 255.47781372, -1668.57263184, 16.43981934]), + 'frame': 8863, + 'frame_number': 8863, + 'framesequence': 8861, + 'gaze_dir': array([ 0.98058069, -0.01138704, 0.19578527]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01138704, 0.19578527]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01138704, 0.19578527]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 39.651812460273504, + 'timestamp_carla': 39651, + 'timestamp_device': 39328, + 'timestamp_stream': 39.651812460273504, + 'transform': [array([-0.03956901, -0.02836548, 0.12655829]), + array([ 0.08448943, -0.02576854, 0.12284364])]} +---------------------- +{'AngularVelocity': array([-0.27773815, -0.3544341 , -2.09279799]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.137585639953613, + 'FR_Wheel_Angle': 15.047614097595215, + 'Location': array([ 0.3328937 , -18.697649 , 0.16764933]), + 'Rotation': array([-1.91928307e-03, 4.83656616e+01, 6.43900871e-01]), + 'Velocity': array([-0.59696996, -0.23973396, 0.00070298]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.17919921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 255.82330322, -1669.25268555, 16.43969727]), + 'frame': 8864, + 'frame_number': 8864, + 'framesequence': 8862, + 'gaze_dir': array([ 0.98058069, -0.01216965, 0.19573818]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01216965, 0.19573818]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01216965, 0.19573818]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0006408886983990669, + 'throttle_input': 0.0, + 'timestamp': 39.65554025769234, + 'timestamp_carla': 39655, + 'timestamp_device': 39332, + 'timestamp_stream': 39.65554025769234, + 'transform': [array([-0.04117576, -0.029906 , 0.12501308]), + array([ 0.09028827, -0.0256051 , 0.12734747])]} +---------------------- +{'AngularVelocity': array([-0.35398072, -0.45311275, -2.23950696]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.435455322265625, + 'FR_Wheel_Angle': 15.433669090270996, + 'Location': array([ 0.3052932 , -18.71112061, 0.16767327]), + 'Rotation': array([-6.42037718e-04, 4.82533417e+01, 6.57696486e-01]), + 'Velocity': array([-0.45132965, -0.32085821, 0.00054218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1859130859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 256.31088257, -1670.00219727, 16.43945312]), + 'frame': 8865, + 'frame_number': 8865, + 'framesequence': 8863, + 'gaze_dir': array([ 0.98058069, -0.01295283, 0.19568792]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01295283, 0.19568792]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01295283, 0.19568792]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.001043733092956245, + 'throttle_input': 0.0, + 'timestamp': 39.659929256886244, + 'timestamp_carla': 39659, + 'timestamp_device': 39336, + 'timestamp_stream': 39.659929256886244, + 'transform': [array([-0.04296776, -0.03174438, 0.1234777 ]), + array([ 0.09608027, -0.02548905, 0.13181683])]} +---------------------- +{'AngularVelocity': array([-0.31440946, -0.40552115, -2.27812195]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.763296127319336, + 'FR_Wheel_Angle': 15.868943214416504, + 'Location': array([ 0.2812053 , -18.72278214, 0.1676943 ]), + 'Rotation': array([4.09811328e-04, 4.81530571e+01, 6.64958239e-01]), + 'Velocity': array([-0.45193079, -0.31939912, 0.00080432]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1907958984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 256.83853149, -1670.81481934, 16.43908691]), + 'frame': 8866, + 'frame_number': 8866, + 'framesequence': 8864, + 'gaze_dir': array([ 0.98058069, -0.01393131, 0.1956207 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01393131, 0.1956207 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01393131, 0.1956207 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0016113773453980684, + 'throttle_input': 0.0, + 'timestamp': 39.664291359484196, + 'timestamp_carla': 39664, + 'timestamp_device': 39341, + 'timestamp_stream': 39.664291359484196, + 'transform': [array([-0.04468552, -0.03358032, 0.1222455 ]), + array([ 0.10083408, -0.02539848, 0.13539848])]} +---------------------- +{'AngularVelocity': array([-0.21723165, -0.28559819, -2.3303802 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.133999824523926, + 'FR_Wheel_Angle': 16.361757278442383, + 'Location': array([ 0.25574696, -18.73641777, 0.16771112]), + 'Rotation': array([1.19528302e-03, 4.80388794e+01, 6.63101912e-01]), + 'Velocity': array([-0.4367111 , -0.32629099, 0.00105891]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.1990966796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 257.46081543, -1671.75280762, 16.43896484]), + 'frame': 8867, + 'frame_number': 8867, + 'framesequence': 8865, + 'gaze_dir': array([ 0.98058069, -0.01471325, 0.19556345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01471325, 0.19556345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01471325, 0.19556345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0022522660437971354, + 'throttle_input': 0.0, + 'timestamp': 39.66874975711107, + 'timestamp_carla': 39668, + 'timestamp_device': 39345, + 'timestamp_stream': 39.66874975711107, + 'transform': [array([-0.04871918, -0.03395874, 0.12048862]), + array([ 0.10740472, -0.02516735, 0.14051458])]} +---------------------- +{'AngularVelocity': array([-0.25385335, -0.32490557, -2.32972121]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.465072631835938, + 'FR_Wheel_Angle': 16.801286697387695, + 'Location': array([ 0.2320753 , -18.7485733 , 0.16773878]), + 'Rotation': array([1.60509441e-03, 4.79319763e+01, 6.54978752e-01]), + 'Velocity': array([-0.49933004, -0.29058516, 0.00055808]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.2083740234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 257.87536621, -1672.47546387, 16.4387207 ]), + 'frame': 8868, + 'frame_number': 8868, + 'framesequence': 8866, + 'gaze_dir': array([ 0.98058069, -0.0154957 , 0.195503 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0154957 , 0.195503 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0154957 , 0.195503 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0034241769462823868, + 'throttle_input': 0.0, + 'timestamp': 39.672882959246635, + 'timestamp_carla': 39672, + 'timestamp_device': 39349, + 'timestamp_stream': 39.672882959246635, + 'transform': [array([-0.05211052, -0.03459595, 0.11856893]), + array([ 0.11449446, -0.0248696 , 0.14611295])]} +---------------------- +{'AngularVelocity': array([-0.28988358, -0.37170899, -2.43262625]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.878308296203613, + 'FR_Wheel_Angle': 17.365737915039062, + 'Location': array([ 0.20625207, -18.76160049, 0.16776003]), + 'Rotation': array([2.45203776e-03, 4.78139420e+01, 6.57183468e-01]), + 'Velocity': array([-0.45166555, -0.31488964, 0.00071956]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.21240234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 258.18875122, -1673.22631836, 16.43884277]), + 'frame': 8869, + 'frame_number': 8869, + 'framesequence': 8867, + 'gaze_dir': array([ 0.98058069, -0.01627715, 0.19543949]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01627715, 0.19543949]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01627715, 0.19543949]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.004339732229709625, + 'throttle_input': 0.0, + 'timestamp': 39.6768531575799, + 'timestamp_carla': 39676, + 'timestamp_device': 39353, + 'timestamp_stream': 39.6768531575799, + 'transform': [array([-0.05506798, -0.03544922, 0.11654014]), + array([ 0.12198034, -0.02450201, 0.15203251])]} +---------------------- +{'AngularVelocity': array([-0.29745108, -0.38128832, -2.46389437]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.327431678771973, + 'FR_Wheel_Angle': 17.975505828857422, + 'Location': array([ 0.1823082 , -18.77365685, 0.16777994]), + 'Rotation': array([3.17603769e-03, 4.77009850e+01, 6.55325234e-01]), + 'Velocity': array([-4.85528052e-01, -2.94477016e-01, 5.43785100e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.2198486328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 258.50546265, -1673.92504883, 16.43859863]), + 'frame': 8870, + 'frame_number': 8870, + 'framesequence': 8868, + 'gaze_dir': array([ 0.98058069, -0.0170591 , 0.19537278]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0170591 , 0.19537278]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0170591 , 0.19537278]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.005310220643877983, + 'throttle_input': 0.0, + 'timestamp': 39.68065585941076, + 'timestamp_carla': 39680, + 'timestamp_device': 39357, + 'timestamp_stream': 39.68065585941076, + 'transform': [array([-0.05764046, -0.03646362, 0.11450206]), + array([ 0.12945257, -0.02410972, 0.15798287])]} +---------------------- +{'AngularVelocity': array([-0.27249834, -0.35505265, -2.57370448]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.800390243530273, + 'FR_Wheel_Angle': 18.609777450561523, + 'Location': array([ 0.15650235, -18.78710365, 0.16779847]), + 'Rotation': array([4.17324528e-03, 4.75735779e+01, 6.56598091e-01]), + 'Velocity': array([-4.39871967e-01, -3.16701144e-01, 1.15547176e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.227294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 258.88024902, -1674.66674805, 16.43847656]), + 'frame': 8871, + 'frame_number': 8871, + 'framesequence': 8869, + 'gaze_dir': array([ 0.98058069, -0.01784002, 0.19530302]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01784002, 0.19530302]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01784002, 0.19530302]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.005713065154850483, + 'throttle_input': 0.0, + 'timestamp': 39.684458158910275, + 'timestamp_carla': 39684, + 'timestamp_device': 39361, + 'timestamp_stream': 39.684458158910275, + 'transform': [array([-0.05997917, -0.03764526, 0.11245121]), + array([ 0.13696578, -0.02372679, 0.16397057])]} +---------------------- +{'AngularVelocity': array([-0.31803885, -0.41134328, -2.61949897]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.205581665039062, + 'FR_Wheel_Angle': 19.165884017944336, + 'Location': array([ 0.133274 , -18.7982235 , 0.16781358]), + 'Rotation': array([5.25241531e-03, 4.74607468e+01, 6.60793841e-01]), + 'Velocity': array([-0.46196148, -0.30310863, 0.00073568]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.2354736328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 259.2845459 , -1675.41784668, 16.43811035]), + 'frame': 8872, + 'frame_number': 8872, + 'framesequence': 8870, + 'gaze_dir': array([ 0.98058069, -0.0186214 , 0.19523008]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0186214 , 0.19523008]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0186214 , 0.19523008]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.006775109563022852, + 'throttle_input': 0.0, + 'timestamp': 39.688275657594204, + 'timestamp_carla': 39688, + 'timestamp_device': 39365, + 'timestamp_stream': 39.688275657594204, + 'transform': [array([-0.0621215 , -0.03897095, 0.11045698]), + array([ 0.14428774, -0.02335382, 0.16979253])]} +---------------------- +{'AngularVelocity': array([-0.27094632, -0.35726416, -2.70833445]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.729101181030273, + 'FR_Wheel_Angle': 19.908611297607422, + 'Location': array([ 0.10823398, -18.81067276, 0.16783369]), + 'Rotation': array([6.43403782e-03, 4.73331146e+01, 6.63632452e-01]), + 'Velocity': array([-0.43924895, -0.31254122, 0.00068034]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.2442626953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 259.65258789, -1676.12084961, 16.43835449]), + 'frame': 8873, + 'frame_number': 8873, + 'framesequence': 8871, + 'gaze_dir': array([ 0.98058069, -0.01920669, 0.19517335]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01920669, 0.19517335]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01920669, 0.19517335]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.007818842306733131, + 'throttle_input': 0.0, + 'timestamp': 39.692146860063076, + 'timestamp_carla': 39692, + 'timestamp_device': 39368, + 'timestamp_stream': 39.692146860063076, + 'transform': [array([-0.06411064, -0.04041992, 0.10856935]), + array([ 0.15123405, -0.02303573, 0.17530276])]} +---------------------- +{'AngularVelocity': array([-0.26402366, -0.34732339, -2.73515797]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.26466178894043, + 'FR_Wheel_Angle': 20.622478485107422, + 'Location': array([ 0.08474208, -18.82243729, 0.16785577]), + 'Rotation': array([7.27415085e-03, 4.72087708e+01, 6.58943772e-01]), + 'Velocity': array([-0.49132076, -0.282345 , 0.00075211]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.2513427734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 259.95928955, -1676.77539062, 16.43811035]), + 'frame': 8874, + 'frame_number': 8874, + 'framesequence': 8872, + 'gaze_dir': array([ 0.98058069, -0.01998754, 0.19509496]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01998754, 0.19509496]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01998754, 0.19509496]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.008825953118503094, + 'throttle_input': 0.0, + 'timestamp': 39.69616585969925, + 'timestamp_carla': 39696, + 'timestamp_device': 39372, + 'timestamp_stream': 39.69616585969925, + 'transform': [array([-0.06602158, -0.04200561, 0.1068086 ]), + array([ 0.15772955, -0.022766 , 0.18043916])]} +---------------------- +{'AngularVelocity': array([-0.30994672, -0.40529796, -2.78839374]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.756471633911133, + 'FR_Wheel_Angle': 21.351221084594727, + 'Location': array([ 0.0617305 , -18.8339119 , 0.16785631]), + 'Rotation': array([8.40796251e-03, 4.70841026e+01, 6.60184920e-01]), + 'Velocity': array([-0.51706362, -0.26636708, -0.00077798]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.259765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 260.41946411, -1677.58532715, 16.43811035]), + 'frame': 8875, + 'frame_number': 8875, + 'framesequence': 8873, + 'gaze_dir': array([ 0.98058069, -0.02076807, 0.1950134 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02076807, 0.1950134 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02076807, 0.1950134 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.009997864253818989, + 'throttle_input': 0.0, + 'timestamp': 39.69981225952506, + 'timestamp_carla': 39699, + 'timestamp_device': 39376, + 'timestamp_stream': 39.69981225952506, + 'transform': [array([-0.06765427, -0.04348877, 0.10542244]), + array([ 0.16292733, -0.0225779 , 0.18448195])]} +---------------------- +{'AngularVelocity': array([-0.30014607, -0.40057653, -2.94103575]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.304025650024414, + 'FR_Wheel_Angle': 22.129619598388672, + 'Location': array([ 0.03610387, -18.84608269, 0.16788073]), + 'Rotation': array([1.01906415e-02, 4.69447021e+01, 6.69636190e-01]), + 'Velocity': array([-0.43093342, -0.30822647, 0.00069188]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.26806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 260.8848877 , -1678.41308594, 16.43798828]), + 'frame': 8876, + 'frame_number': 8876, + 'framesequence': 8874, + 'gaze_dir': array([ 0.98058069, -0.02154753, 0.19492881]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02154753, 0.19492881]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02154753, 0.19492881]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.011188086122274399, + 'throttle_input': 0.0, + 'timestamp': 39.70331835746765, + 'timestamp_carla': 39703, + 'timestamp_device': 39380, + 'timestamp_stream': 39.70331835746765, + 'transform': [array([-0.06914932, -0.04494262, 0.10428307]), + array([ 0.16722351, -0.02243637, 0.18780369])]} +---------------------- +{'AngularVelocity': array([-0.22603762, -0.31041953, -2.99487329]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.894182205200195, + 'FR_Wheel_Angle': 22.98630142211914, + 'Location': array([ 1.14818681e-02, -1.88584499e+01, 1.67903423e-01]), + 'Rotation': array([1.13859251e-02, 4.68020172e+01, 6.66106880e-01]), + 'Velocity': array([-0.43889225, -0.30106109, 0.00058771]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.276611328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 261.3583374 , -1679.21655273, 16.43762207]), + 'frame': 8877, + 'frame_number': 8877, + 'framesequence': 8875, + 'gaze_dir': array([ 0.98058069, -0.02232739, 0.19484103]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02232739, 0.19484103]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02232739, 0.19484103]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.012396618723869324, + 'throttle_input': 0.0, + 'timestamp': 39.70795715972781, + 'timestamp_carla': 39707, + 'timestamp_device': 39384, + 'timestamp_stream': 39.70795715972781, + 'transform': [array([-0.07102859, -0.04688599, 0.10310633]), + array([ 0.1717246 , -0.02230775, 0.19122417])]} +---------------------- +{'AngularVelocity': array([-0.2734803 , -0.37046096, -3.04481149]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.50404930114746, + 'FR_Wheel_Angle': 23.870601654052734, + 'Location': array([-1.23064788e-02, -1.88694687e+01, 1.67920128e-01]), + 'Rotation': array([1.29295476e-02, 4.66672325e+01, 6.70656979e-01]), + 'Velocity': array([-0.42421442, -0.30494446, 0.00081408]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.2843017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 261.84719849, -1680.02612305, 16.43737793]), + 'frame': 8878, + 'frame_number': 8878, + 'framesequence': 8876, + 'gaze_dir': array([ 0.98058069, -0.02330152, 0.19472694]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02330152, 0.19472694]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02330152, 0.19472694]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.013623462989926338, + 'throttle_input': 0.0, + 'timestamp': 39.712387558072805, + 'timestamp_carla': 39712, + 'timestamp_device': 39389, + 'timestamp_stream': 39.712387558072805, + 'transform': [array([-0.07275344, -0.04875244, 0.1022947 ]), + array([ 0.17495528, -0.02223047, 0.19357689])]} +---------------------- +{'AngularVelocity': array([-0.24724774, -0.33747616, -3.03878713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.067352294921875, + 'FR_Wheel_Angle': 24.697885513305664, + 'Location': array([ -0.03555438, -18.88074112, 0.16793859]), + 'Rotation': array([1.41043402e-02, 4.65281868e+01, 6.67029500e-01]), + 'Velocity': array([-4.69820172e-01, -2.78920203e-01, 3.69043351e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.29345703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 262.40979004, -1681.00854492, 16.43725586]), + 'frame': 8879, + 'frame_number': 8879, + 'framesequence': 8877, + 'gaze_dir': array([ 0.98058069, -0.02407981, 0.19463223]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02407981, 0.19463223]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02407981, 0.19463223]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.014923552051186562, + 'throttle_input': 0.0, + 'timestamp': 39.71701296046376, + 'timestamp_carla': 39716, + 'timestamp_device': 39393, + 'timestamp_stream': 39.71701296046376, + 'transform': [array([-0.07692879, -0.04915039, 0.10090723]), + array([ 0.18019404, -0.02200695, 0.19761337])]} +---------------------- +{'AngularVelocity': array([-0.30183175, -0.40354359, -3.05417728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.613773345947266, + 'FR_Wheel_Angle': 25.508392333984375, + 'Location': array([ -0.05837344, -18.89106941, 0.16795512]), + 'Rotation': array([1.55318491e-02, 4.63935966e+01, 6.68632150e-01]), + 'Velocity': array([-4.99684483e-01, -2.61199862e-01, 4.97961009e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.30126953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 262.89407349, -1681.89453125, 16.43664551]), + 'frame': 8880, + 'frame_number': 8880, + 'framesequence': 8878, + 'gaze_dir': array([ 0.98058069, -0.02485845, 0.19453432]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02485845, 0.19453432]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02485845, 0.19453432]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.016846217215061188, + 'throttle_input': 0.0, + 'timestamp': 39.72081146016717, + 'timestamp_carla': 39720, + 'timestamp_device': 39397, + 'timestamp_stream': 39.72081146016717, + 'transform': [array([-0.08006103, -0.04971801, 0.09952455]), + array([ 0.18533035, -0.0217491 , 0.20164743])]} +---------------------- +{'AngularVelocity': array([-0.270161 , -0.37096384, -3.17516255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.20737648010254, + 'FR_Wheel_Angle': 26.351856231689453, + 'Location': array([ -0.08359978, -18.90291977, 0.16796786]), + 'Rotation': array([1.74989440e-02, 4.62391548e+01, 6.74525619e-01]), + 'Velocity': array([-0.42895809, -0.29277563, 0.00073696]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3096923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 263.10580444, -1682.60327148, 16.43688965]), + 'frame': 8881, + 'frame_number': 8881, + 'framesequence': 8879, + 'gaze_dir': array([ 0.98058069, -0.02563596, 0.19443338]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02563596, 0.19443338]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02563596, 0.19443338]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.01807306334376335, + 'throttle_input': 0.0, + 'timestamp': 39.725074257701635, + 'timestamp_carla': 39724, + 'timestamp_device': 39401, + 'timestamp_stream': 39.725074257701635, + 'transform': [array([-0.083227 , -0.05063354, 0.09773532]), + array([ 0.19193514, -0.02137699, 0.2068672 ])]} +---------------------- +{'AngularVelocity': array([-0.22595543, -0.31288508, -3.14877295]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.72684669494629, + 'FR_Wheel_Angle': 27.173166275024414, + 'Location': array([ -0.10696307, -18.91423225, 0.16798559]), + 'Rotation': array([1.87488683e-02, 4.60896568e+01, 6.69697821e-01]), + 'Velocity': array([-0.46654788, -0.27198246, 0.00072045]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.318359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 263.40802002, -1683.31799316, 16.43688965]), + 'frame': 8882, + 'frame_number': 8882, + 'framesequence': 8880, + 'gaze_dir': array([ 0.98058069, -0.02660801, 0.19430272]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02660801, 0.19430272]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02660801, 0.19430272]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.019373148679733276, + 'throttle_input': 0.0, + 'timestamp': 39.7291652597487, + 'timestamp_carla': 39729, + 'timestamp_device': 39406, + 'timestamp_stream': 39.7291652597487, + 'transform': [array([-0.08596786, -0.05174438, 0.09590854]), + array([ 0.19862872, -0.02096293, 0.21220122])]} +---------------------- +{'AngularVelocity': array([-0.25123417, -0.35180363, -3.29414177]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.274024963378906, + 'FR_Wheel_Angle': 28.00328254699707, + 'Location': array([ -0.13142161, -18.92518425, 0.16799185]), + 'Rotation': array([2.08730567e-02, 4.59392281e+01, 6.79013669e-01]), + 'Velocity': array([-3.87115121e-01, -3.06258649e-01, 1.11718175e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.329345703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 263.84255981, -1684.21862793, 16.43688965]), + 'frame': 8883, + 'frame_number': 8883, + 'framesequence': 8881, + 'gaze_dir': array([ 0.98058069, -0.02719048, 0.19422209]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02719048, 0.19422209]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02719048, 0.19422209]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.02059999480843544, + 'throttle_input': 0.0, + 'timestamp': 39.73295205831528, + 'timestamp_carla': 39732, + 'timestamp_device': 39409, + 'timestamp_stream': 39.73295205831528, + 'transform': [array([-0.08824684, -0.05293213, 0.09421438]), + array([ 0.20485102, -0.02066252, 0.21714778])]} +---------------------- +{'AngularVelocity': array([-0.16775531, -0.24427922, -3.27925634]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.858394622802734, + 'FR_Wheel_Angle': 28.87369728088379, + 'Location': array([ -0.15539099, -18.93702126, 0.16801603]), + 'Rotation': array([2.19180752e-02, 4.57777939e+01, 6.70101285e-01]), + 'Velocity': array([-0.41727829, -0.28919798, 0.00079645]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3388671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 264.0592041 , -1684.85498047, 16.43688965]), + 'frame': 8884, + 'frame_number': 8884, + 'framesequence': 8882, + 'gaze_dir': array([ 0.98058069, -0.02796746, 0.19411172]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02796746, 0.19411172]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02796746, 0.19411172]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.021881772205233574, + 'throttle_input': 0.0, + 'timestamp': 39.73665065690875, + 'timestamp_carla': 39736, + 'timestamp_device': 39413, + 'timestamp_stream': 39.73665065690875, + 'transform': [array([-0.09020615, -0.05421387, 0.09261107]), + array([ 0.21071815, -0.02061206, 0.22183242])]} +---------------------- +{'AngularVelocity': array([-0.22141506, -0.30311799, -3.21558738]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.37981414794922, + 'FR_Wheel_Angle': 29.749574661254883, + 'Location': array([ -0.17825094, -18.94778061, 0.16803701]), + 'Rotation': array([2.28196606e-02, 4.56250076e+01, 6.62765801e-01]), + 'Velocity': array([-4.69655782e-01, -2.61936754e-01, 3.45382694e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3489990234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 264.44146729, -1685.64099121, 16.43676758]), + 'frame': 8885, + 'frame_number': 8885, + 'framesequence': 8883, + 'gaze_dir': array([ 0.98058069, -0.02893788, 0.19396944]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02893788, 0.19396944]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02893788, 0.19396944]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.023236792534589767, + 'throttle_input': 0.0, + 'timestamp': 39.74109835922718, + 'timestamp_carla': 39740, + 'timestamp_device': 39418, + 'timestamp_stream': 39.74109835922718, + 'transform': [array([-0.0922232 , -0.05589111, 0.09084404]), + array([ 0.21724099, -0.02094143, 0.2269858 ])]} +---------------------- +{'AngularVelocity': array([-0.26640558, -0.36261806, -3.28121185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.03762435913086, + 'FR_Wheel_Angle': 30.754638671875, + 'Location': array([ -0.20228879, -18.95884705, 0.16804647]), + 'Rotation': array([2.45067179e-02, 4.54656868e+01, 6.65133178e-01]), + 'Velocity': array([-0.43364939, -0.27516705, 0.00060725]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3607177734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 265.00170898, -1686.61584473, 16.43664551]), + 'frame': 8886, + 'frame_number': 8886, + 'framesequence': 8884, + 'gaze_dir': array([ 0.98058069, -0.02971309, 0.1938522 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02971309, 0.1938522 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02971309, 0.1938522 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.02466506138443947, + 'throttle_input': 0.0, + 'timestamp': 39.74532435834408, + 'timestamp_carla': 39745, + 'timestamp_device': 39422, + 'timestamp_stream': 39.74532435834408, + 'transform': [array([-0.09388359, -0.05756225, 0.08939867]), + array([ 0.22263683, -0.02157824, 0.2312002 ])]} +---------------------- +{'AngularVelocity': array([-0.18250287, -0.27837402, -3.49573469]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.789443969726562, + 'FR_Wheel_Angle': 31.940752029418945, + 'Location': array([ -0.22697705, -18.96997452, 0.1680591 ]), + 'Rotation': array([2.69246046e-02, 4.53016701e+01, 6.74115062e-01]), + 'Velocity': array([-0.35155657, -0.30621839, 0.00080487]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.37158203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 265.40158081, -1687.47558594, 16.43676758]), + 'frame': 8887, + 'frame_number': 8887, + 'framesequence': 8885, + 'gaze_dir': array([ 0.98058069, -0.03048858, 0.19373174]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03048858, 0.19373174]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03048858, 0.19373174]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.02611163631081581, + 'throttle_input': 0.0, + 'timestamp': 39.749416057020426, + 'timestamp_carla': 39749, + 'timestamp_device': 39426, + 'timestamp_stream': 39.749416057020426, + 'transform': [array([-0.09530593, -0.05922607, 0.08824482]), + array([ 0.22698084, -0.02245758, 0.23456335])]} +---------------------- +{'AngularVelocity': array([-0.15782832, -0.24243918, -3.40371013]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.403844833374023, + 'FR_Wheel_Angle': 32.90788650512695, + 'Location': array([ -0.25011981, -18.98077774, 0.16807142]), + 'Rotation': array([2.83316225e-02, 4.51387672e+01, 6.68443441e-01]), + 'Velocity': array([-0.38385978, -0.2882745 , 0.00075878]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3829345703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 265.84585571, -1688.36035156, 16.43640137]), + 'frame': 8888, + 'frame_number': 8888, + 'framesequence': 8886, + 'gaze_dir': array([ 0.98058057, -0.03106931, 0.19363946]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.03106931, 0.19363946]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.03106931, 0.19363946]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.027430037036538124, + 'throttle_input': 0.0, + 'timestamp': 39.75285715982318, + 'timestamp_carla': 39752, + 'timestamp_device': 39429, + 'timestamp_stream': 39.75285715982318, + 'transform': [array([-0.09640595, -0.06064331, 0.0874692 ]), + array([ 0.2299588 , -0.02332121, 0.23682511])]} +---------------------- +{'AngularVelocity': array([-0.17247045, -0.24971098, -3.25856757]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.03118324279785, + 'FR_Wheel_Angle': 33.92349624633789, + 'Location': array([ -0.27302569, -18.99178123, 0.16809362]), + 'Rotation': array([2.91990563e-02, 4.49707527e+01, 6.56648934e-01]), + 'Velocity': array([-0.44183075, -0.25964519, 0.00081268]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.3907470703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 266.09973145, -1689.01855469, 16.43640137]), + 'frame': 8889, + 'frame_number': 8889, + 'framesequence': 8887, + 'gaze_dir': array([ 0.98058069, -0.03203733, 0.19348167]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03203733, 0.19348167]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03203733, 0.19348167]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.028839992359280586, + 'throttle_input': 0.0, + 'timestamp': 39.75731235742569, + 'timestamp_carla': 39757, + 'timestamp_device': 39434, + 'timestamp_stream': 39.75731235742569, + 'transform': [array([-0.09768821, -0.06249512, 0.08677173]), + array([ 0.23275918, -0.02467398, 0.23884679])]} +---------------------- +{'AngularVelocity': array([-0.24319097, -0.34134114, -3.32846379]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.727031707763672, + 'FR_Wheel_Angle': 35.056087493896484, + 'Location': array([ -0.2969901 , -19.00241089, 0.16811708]), + 'Rotation': array([3.10022272e-02, 4.48030472e+01, 6.56749845e-01]), + 'Velocity': array([-0.41061461, -0.26855937, 0.00067936]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.40185546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 266.73825073, -1690.0579834 , 16.43603516]), + 'frame': 8890, + 'frame_number': 8890, + 'framesequence': 8888, + 'gaze_dir': array([ 0.98058069, -0.03281131, 0.19335191]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03281131, 0.19335191]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03281131, 0.19335191]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.030286571010947227, + 'throttle_input': 0.0, + 'timestamp': 39.76167035847902, + 'timestamp_carla': 39761, + 'timestamp_device': 39438, + 'timestamp_stream': 39.76167035847902, + 'transform': [array([-0.10119888, -0.06281128, 0.08563408]), + array([ 0.23703487, -0.02587398, 0.24215958])]} +---------------------- +{'AngularVelocity': array([-0.19964173, -0.28324592, -3.10376549]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.382099151611328, + 'FR_Wheel_Angle': 36.075374603271484, + 'Location': array([ -0.31851581, -19.01239777, 0.16812681]), + 'Rotation': array([3.22180018e-02, 4.46419373e+01, 6.49739981e-01]), + 'Velocity': array([-0.50862038, -0.22346593, 0.00058893]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.40966796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.1307373 , -1690.90942383, 16.43591309]), + 'frame': 8891, + 'frame_number': 8891, + 'framesequence': 8889, + 'gaze_dir': array([ 0.98058069, -0.03358402, 0.19321918]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03358402, 0.19321918]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03358402, 0.19321918]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.03162328153848648, + 'throttle_input': 0.0, + 'timestamp': 39.76520016044378, + 'timestamp_carla': 39765, + 'timestamp_device': 39442, + 'timestamp_stream': 39.76520016044378, + 'transform': [array([-0.10377548, -0.06327149, 0.08451315]), + array([ 0.24121495, -0.026794 , 0.24543075])]} +---------------------- +{'AngularVelocity': array([-0.28795609, -0.4037663 , -3.25345683]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.07484245300293, + 'FR_Wheel_Angle': 37.26225280761719, + 'Location': array([ -0.34316161, -19.02260399, 0.16814055]), + 'Rotation': array([3.49364169e-02, 4.44758492e+01, 6.58214211e-01]), + 'Velocity': array([-0.40888295, -0.26024315, 0.00075277]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.4200439453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.34841919, -1691.65612793, 16.43603516]), + 'frame': 8892, + 'frame_number': 8892, + 'framesequence': 8890, + 'gaze_dir': array([ 0.98058069, -0.03435694, 0.19308327]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03435694, 0.19308327]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03435694, 0.19308327]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.03259376809000969, + 'throttle_input': 0.0, + 'timestamp': 39.76899965852499, + 'timestamp_carla': 39768, + 'timestamp_device': 39446, + 'timestamp_stream': 39.76899965852499, + 'transform': [array([-0.10623199, -0.06398804, 0.08311985]), + array([ 0.24639224, -0.02779187, 0.24949628])]} +---------------------- +{'AngularVelocity': array([-0.21686564, -0.31313077, -3.06262922]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.768754959106445, + 'FR_Wheel_Angle': 38.4209098815918, + 'Location': array([ -0.36515075, -19.03224373, 0.16816209]), + 'Rotation': array([3.67464162e-02, 4.43142662e+01, 6.54906273e-01]), + 'Velocity': array([-0.47729427, -0.22880451, 0.00074161]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.4305419921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.65838623, -1692.41137695, 16.43579102]), + 'frame': 8893, + 'frame_number': 8893, + 'framesequence': 8891, + 'gaze_dir': array([ 0.98058069, -0.03512858, 0.19294438]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03512858, 0.19294438]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03512858, 0.19294438]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.03426007926464081, + 'throttle_input': 0.0, + 'timestamp': 39.773887757211924, + 'timestamp_carla': 39773, + 'timestamp_device': 39450, + 'timestamp_stream': 39.773887757211924, + 'transform': [array([-0.10890968, -0.06523559, 0.08113196]), + array([ 0.25372785, -0.02913938, 0.25528973])]} +---------------------- +{'AngularVelocity': array([-0.23420672, -0.34430501, -3.17716026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.45753288269043, + 'FR_Wheel_Angle': 39.50738525390625, + 'Location': array([ -0.38947818, -19.04248047, 0.16817957]), + 'Rotation': array([3.93760391e-02, 4.41448212e+01, 6.59202456e-01]), + 'Velocity': array([-0.40034199, -0.25388065, 0.00084042]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.44189453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.97412109, -1693.19470215, 16.43603516]), + 'frame': 8894, + 'frame_number': 8894, + 'framesequence': 8892, + 'gaze_dir': array([ 0.98058069, -0.03609306, 0.19276626]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03609306, 0.19276626]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03609306, 0.19276626]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.03557848185300827, + 'throttle_input': 0.0, + 'timestamp': 39.77910055965185, + 'timestamp_carla': 39778, + 'timestamp_device': 39455, + 'timestamp_stream': 39.77910055965185, + 'transform': [array([-0.11125968, -0.06687012, 0.07901312]), + array([ 0.26155525, -0.03074028, 0.26146269])]} +---------------------- +{'AngularVelocity': array([-0.2322055 , -0.35475197, -3.19623256]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.121341705322266, + 'FR_Wheel_Angle': 40.66690444946289, + 'Location': array([ -0.41185182, -19.05107117, 0.16817808]), + 'Rotation': array([4.25110944e-02, 4.40012512e+01, 6.69153035e-01]), + 'Velocity': array([-0.36685252, -0.26137465, 0.00046146]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.4560546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 268.36920166, -1694.17932129, 16.43591309]), + 'frame': 8895, + 'frame_number': 8895, + 'framesequence': 8893, + 'gaze_dir': array([ 0.98058069, -0.03686415, 0.19262029]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03686415, 0.19262029]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03686415, 0.19262029]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.037629324942827225, + 'throttle_input': 0.0, + 'timestamp': 39.78260385990143, + 'timestamp_carla': 39782, + 'timestamp_device': 39459, + 'timestamp_stream': 39.78260385990143, + 'transform': [array([-0.11264618, -0.06807251, 0.07769684]), + array([ 0.26646614, -0.03191543, 0.26530439])]} +---------------------- +{'AngularVelocity': array([-0.13237873, -0.22032082, -3.03280783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77507209777832, + 'FR_Wheel_Angle': 41.668819427490234, + 'Location': array([ -0.43451849, -19.06098747, 0.16820288]), + 'Rotation': array([ 0.04412985, 43.83125305, 0.65995789]), + 'Velocity': array([-0.41508219, -0.2398183 , 0.00067637]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.470458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 268.66964722, -1695.06005859, 16.43591309]), + 'frame': 8896, + 'frame_number': 8896, + 'framesequence': 8894, + 'gaze_dir': array([ 0.98058069, -0.03763391, 0.19247139]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03763391, 0.19247139]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03763391, 0.19247139]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.038325145840644836, + 'throttle_input': 0.0, + 'timestamp': 39.78629956021905, + 'timestamp_carla': 39786, + 'timestamp_device': 39463, + 'timestamp_stream': 39.78629956021905, + 'transform': [array([-0.1139167 , -0.06942871, 0.07644232]), + array([ 0.27116531, -0.0332961 , 0.26896575])]} +---------------------- +{'AngularVelocity': array([-0.1802218 , -0.27049103, -3.06656361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78005027770996, + 'FR_Wheel_Angle': 41.678192138671875, + 'Location': array([ -0.45777056, -19.07051659, 0.16821863]), + 'Rotation': array([ 0.0460423 , 43.67023087, 0.65811998]), + 'Velocity': array([-0.39153728, -0.2479246 , 0.00057358]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.482666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.08279419, -1695.90490723, 16.43603516]), + 'frame': 8897, + 'frame_number': 8897, + 'framesequence': 8895, + 'gaze_dir': array([ 0.98058069, -0.0384038 , 0.19231924]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0384038 , 0.19231924]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0384038 , 0.19231924]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.03962523117661476, + 'throttle_input': 0.0, + 'timestamp': 39.79022146016359, + 'timestamp_carla': 39790, + 'timestamp_device': 39467, + 'timestamp_stream': 39.79022146016359, + 'transform': [array([-0.11509536, -0.07093506, 0.0753094 ]), + array([ 0.2754342 , -0.03490375, 0.27226871])]} +---------------------- +{'AngularVelocity': array([-0.18482848, -0.25678489, -2.97916555]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77122688293457, + 'FR_Wheel_Angle': 41.66573715209961, + 'Location': array([ -0.47996849, -19.07987976, 0.16822843]), + 'Rotation': array([ 0.04733321, 43.51099396, 0.6534186 ]), + 'Velocity': array([-0.42972881, -0.23592882, 0.00081422]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.495849609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.50604248, -1696.77478027, 16.43554688]), + 'frame': 8898, + 'frame_number': 8898, + 'framesequence': 8896, + 'gaze_dir': array([ 0.98058057, -0.03898026, 0.19220322]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.03898026, 0.19220322]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.03898026, 0.19220322]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04094363749027252, + 'throttle_input': 0.0, + 'timestamp': 39.79420926049352, + 'timestamp_carla': 39794, + 'timestamp_device': 39470, + 'timestamp_stream': 39.79420926049352, + 'transform': [array([-0.11615982, -0.07251465, 0.07440026]), + array([ 0.27891758, -0.03664439, 0.27491659])]} +---------------------- +{'AngularVelocity': array([-0.21266499, -0.2775279 , -3.12755394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.588457107543945, + 'FR_Wheel_Angle': 41.35496139526367, + 'Location': array([ -0.50357038, -19.08966064, 0.16825098]), + 'Rotation': array([ 0.04862411, 43.34530258, 0.65296042]), + 'Velocity': array([-0.39808252, -0.25023961, 0.00068688]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.5052490234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.7494812 , -1697.44848633, 16.4354248 ]), + 'frame': 8899, + 'frame_number': 8899, + 'framesequence': 8897, + 'gaze_dir': array([ 0.98058069, -0.03974908, 0.1920457 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03974908, 0.1920457 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03974908, 0.1920457 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04217047989368439, + 'throttle_input': 0.0, + 'timestamp': 39.79773036018014, + 'timestamp_carla': 39797, + 'timestamp_device': 39474, + 'timestamp_stream': 39.79773036018014, + 'transform': [array([-0.11700965, -0.07393067, 0.07380107]), + array([ 0.28128767, -0.03828052, 0.27666122])]} +---------------------- +{'AngularVelocity': array([-0.21203844, -0.25469249, -2.95804238]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63567543029785, + 'FR_Wheel_Angle': 41.459964752197266, + 'Location': array([ -0.52515906, -19.09867096, 0.1682778 ]), + 'Rotation': array([ 0.04901344, 43.18690109, 0.64720684]), + 'Velocity': array([-0.48204178, -0.22072336, 0.00071285]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.5159912109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 270.17028809, -1698.34008789, 16.43579102]), + 'frame': 8900, + 'frame_number': 8900, + 'framesequence': 8898, + 'gaze_dir': array([ 0.98058069, -0.04051652, 0.19188526]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04051652, 0.19188526]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04051652, 0.19188526]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04352549836039543, + 'throttle_input': 0.0, + 'timestamp': 39.80158335715532, + 'timestamp_carla': 39801, + 'timestamp_device': 39478, + 'timestamp_stream': 39.80158335715532, + 'transform': [array([-0.11785378, -0.07549439, 0.07338133]), + array([ 0.2830157 , -0.04016871, 0.2778793 ])]} +---------------------- +{'AngularVelocity': array([-0.23697159, -0.2908636 , -3.2289238 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.764841079711914, + 'FR_Wheel_Angle': 41.65288162231445, + 'Location': array([ -0.54981053, -19.108881 , 0.16829965]), + 'Rotation': array([ 0.05016091, 43.01537704, 0.65151101]), + 'Velocity': array([-0.38960898, -0.2554723 , 0.00086198]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.5260009765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 270.60327148, -1699.20788574, 16.43554688]), + 'frame': 8901, + 'frame_number': 8901, + 'framesequence': 8899, + 'gaze_dir': array([ 0.98058069, -0.04147564, 0.19168025]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04147564, 0.19168025]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04147564, 0.19168025]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.044807277619838715, + 'throttle_input': 0.0, + 'timestamp': 39.80619525909424, + 'timestamp_carla': 39806, + 'timestamp_device': 39483, + 'timestamp_stream': 39.80619525909424, + 'transform': [array([-0.1212706 , -0.07581542, 0.07239738]), + array([ 0.28679278, -0.04232442, 0.28073251])]} +---------------------- +{'AngularVelocity': array([-0.25916952, -0.31081316, -3.15769339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7724666595459, + 'FR_Wheel_Angle': 41.66425704956055, + 'Location': array([ -0.57204336, -19.1174984 , 0.16831793]), + 'Rotation': array([ 0.05115812, 42.86357117, 0.65470594]), + 'Velocity': array([-4.12364423e-01, -2.48548314e-01, 2.38227833e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.5364990234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.16436768, -1700.2722168 , 16.43566895]), + 'frame': 8902, + 'frame_number': 8902, + 'framesequence': 8900, + 'gaze_dir': array([ 0.98058069, -0.04205018, 0.19155502]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04205018, 0.19155502]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04205018, 0.19155502]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0459975004196167, + 'throttle_input': 0.0, + 'timestamp': 39.80994085967541, + 'timestamp_carla': 39809, + 'timestamp_device': 39486, + 'timestamp_stream': 39.80994085967541, + 'transform': [array([-0.12374267, -0.07630493, 0.07138171]), + array([ 0.29065186, -0.04400138, 0.2836892 ])]} +---------------------- +{'AngularVelocity': array([-0.22545749, -0.26172537, -3.17682481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.768518447875977, + 'FR_Wheel_Angle': 41.66260528564453, + 'Location': array([ -0.59505272, -19.12700081, 0.16834082]), + 'Rotation': array([ 0.05161574, 42.69690323, 0.6532141 ]), + 'Velocity': array([-0.42742664, -0.24479112, 0.00046412]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.5457763671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.17572021, -1700.85388184, 16.43566895]), + 'frame': 8903, + 'frame_number': 8903, + 'framesequence': 8901, + 'gaze_dir': array([ 0.98058069, -0.04281637, 0.19138524]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04281637, 0.19138524]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04281637, 0.19138524]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.047114480286836624, + 'throttle_input': 0.0, + 'timestamp': 39.81358325853944, + 'timestamp_carla': 39813, + 'timestamp_device': 39490, + 'timestamp_stream': 39.81358325853944, + 'transform': [array([-0.12586112, -0.07698242, 0.07023335]), + array([ 0.29496855, -0.04563842, 0.28703517])]} +---------------------- +{'AngularVelocity': array([-0.21173331, -0.2399148 , -3.28284264]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77132225036621, + 'FR_Wheel_Angle': 41.66306686401367, + 'Location': array([ -0.61882126, -19.13710213, 0.16836405]), + 'Rotation': array([ 0.05174551, 42.52099228, 0.65059429]), + 'Velocity': array([-0.41118804, -0.25274098, 0.00056722]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.557861328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.4420166 , -1701.64086914, 16.43579102]), + 'frame': 8904, + 'frame_number': 8904, + 'framesequence': 8902, + 'gaze_dir': array([ 0.98058069, -0.04358187, 0.19121236]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04358187, 0.19121236]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04358187, 0.19121236]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04826807975769043, + 'throttle_input': 0.0, + 'timestamp': 39.817439660429955, + 'timestamp_carla': 39817, + 'timestamp_device': 39494, + 'timestamp_stream': 39.817439660429955, + 'transform': [array([-0.12779456, -0.07790527, 0.06890083]), + array([ 0.29993409, -0.04738827, 0.29091975])]} +---------------------- +{'AngularVelocity': array([-0.22924629, -0.25131524, -3.24343348]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76506233215332, + 'FR_Wheel_Angle': 41.65531921386719, + 'Location': array([ -0.6417951 , -19.14666939, 0.16839597]), + 'Rotation': array([ 0.05160891, 42.35050201, 0.64691699]), + 'Velocity': array([-0.43717128, -0.24457711, 0.0007087 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.5699462890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.72579956, -1702.43286133, 16.43554688]), + 'frame': 8905, + 'frame_number': 8905, + 'framesequence': 8903, + 'gaze_dir': array([ 0.98058069, -0.04434595, 0.19103661]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04434595, 0.19103661]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04434595, 0.19103661]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04938505217432976, + 'throttle_input': 0.0, + 'timestamp': 39.82113825902343, + 'timestamp_carla': 39821, + 'timestamp_device': 39498, + 'timestamp_stream': 39.82113825902343, + 'transform': [array([-0.12938362, -0.07895263, 0.06759235]), + array([ 0.30476984, -0.04916562, 0.29473782])]} +---------------------- +{'AngularVelocity': array([-0.25047806, -0.27668151, -3.32218122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.767824172973633, + 'FR_Wheel_Angle': 41.65673828125, + 'Location': array([ -0.66532159, -19.15628052, 0.16842005]), + 'Rotation': array([ 0.05186163, 42.18031693, 0.64800394]), + 'Velocity': array([-0.42153555, -0.25214601, 0.00064516]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.5838623046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.04373169, -1703.27416992, 16.4354248 ]), + 'frame': 8906, + 'frame_number': 8906, + 'framesequence': 8904, + 'gaze_dir': array([ 0.98058069, -0.04511005, 0.19085762]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04511005, 0.19085762]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04511005, 0.19085762]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05068514123558998, + 'throttle_input': 0.0, + 'timestamp': 39.82502906024456, + 'timestamp_carla': 39824, + 'timestamp_device': 39502, + 'timestamp_stream': 39.82502906024456, + 'transform': [array([-0.1307901 , -0.08020263, 0.06626657]), + array([ 0.30970809, -0.05112667, 0.29860276])]} +---------------------- +{'AngularVelocity': array([-0.21582375, -0.22636467, -3.25782299]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.757030487060547, + 'FR_Wheel_Angle': 41.63871383666992, + 'Location': array([ -0.68816221, -19.16629219, 0.16844518]), + 'Rotation': array([ 0.05138351, 42.00156021, 0.64159948]), + 'Velocity': array([-0.46810943, -0.23597427, 0.00068272]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.595458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.35116577, -1704.08935547, 16.4354248 ]), + 'frame': 8907, + 'frame_number': 8907, + 'framesequence': 8905, + 'gaze_dir': array([ 0.98058069, -0.04568211, 0.19072151]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04568211, 0.19072151]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04568211, 0.19072151]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.051893673837184906, + 'throttle_input': 0.0, + 'timestamp': 39.82872475683689, + 'timestamp_carla': 39828, + 'timestamp_device': 39505, + 'timestamp_stream': 39.82872475683689, + 'transform': [array([-0.13192397, -0.08149048, 0.0651232 ]), + array([ 0.3140111 , -0.05310758, 0.3019357 ])]} +---------------------- +{'AngularVelocity': array([-0.24333671, -0.26821744, -3.53431392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.761075973510742, + 'FR_Wheel_Angle': 41.6463623046875, + 'Location': array([ -0.71310788, -19.17655373, 0.16848135]), + 'Rotation': array([ 0.05177966, 41.82060242, 0.64569187]), + 'Velocity': array([-0.38729537, -0.26866591, 0.00084352]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.6087646484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.58496094, -1704.79602051, 16.43530273]), + 'frame': 8908, + 'frame_number': 8908, + 'framesequence': 8906, + 'gaze_dir': array([ 0.98058069, -0.04644493, 0.19053718]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04644493, 0.19053718]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04644493, 0.19053718]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05249794200062752, + 'throttle_input': 0.0, + 'timestamp': 39.832120560109615, + 'timestamp_carla': 39831, + 'timestamp_device': 39509, + 'timestamp_stream': 39.832120560109615, + 'transform': [array([-0.13282265, -0.08273803, 0.06420733]), + array([ 0.31748083, -0.05502744, 0.3046048 ])]} +---------------------- +{'AngularVelocity': array([-0.24444734, -0.26623881, -3.49521875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.769088745117188, + 'FR_Wheel_Angle': 41.65801239013672, + 'Location': array([ -0.73596162, -19.18584633, 0.16850092]), + 'Rotation': array([ 0.05208019, 41.65198517, 0.64716756]), + 'Velocity': array([-0.40666184, -0.26331693, 0.00067403]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.6221923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.96054077, -1705.67297363, 16.4354248 ]), + 'frame': 8909, + 'frame_number': 8909, + 'framesequence': 8907, + 'gaze_dir': array([ 0.98058069, -0.04720629, 0.19034997]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04720629, 0.19034997]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04720629, 0.19034997]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.053688161075115204, + 'throttle_input': 0.0, + 'timestamp': 39.836506359279156, + 'timestamp_carla': 39836, + 'timestamp_device': 39513, + 'timestamp_stream': 39.836506359279156, + 'transform': [array([-0.13380019, -0.08442505, 0.06328978]), + array([ 0.32103252, -0.05762993, 0.30726922])]} +---------------------- +{'AngularVelocity': array([-0.20718443, -0.21205051, -3.37122488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754905700683594, + 'FR_Wheel_Angle': 41.6427001953125, + 'Location': array([ -0.75842518, -19.19587326, 0.16851874]), + 'Rotation': array([ 0.05151328, 41.47233963, 0.64057761]), + 'Velocity': array([-0.46826547, -0.2410519 , 0.00057905]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.63330078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 273.34371948, -1706.53552246, 16.43566895]), + 'frame': 8910, + 'frame_number': 8910, + 'framesequence': 8908, + 'gaze_dir': array([ 0.98058069, -0.04815765, 0.1901115 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04815765, 0.1901115 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04815765, 0.1901115 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05550096556544304, + 'throttle_input': 0.0, + 'timestamp': 39.84193215891719, + 'timestamp_carla': 39841, + 'timestamp_device': 39518, + 'timestamp_stream': 39.84193215891719, + 'transform': [array([-0.13478035, -0.08657715, 0.06260913]), + array([ 0.32379192, -0.06108335, 0.30922732])]} +---------------------- +{'AngularVelocity': array([-0.22525632, -0.22363117, -3.32902002]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.744319915771484, + 'FR_Wheel_Angle': 41.620887756347656, + 'Location': array([ -0.78118593, -19.20594978, 0.16854735]), + 'Rotation': array([ 0.05084392, 41.28970337, 0.63440168]), + 'Velocity': array([-0.51455551, -0.22350655, 0.0005831 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.6480712890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 273.83966064, -1707.64086914, 16.43505859]), + 'frame': 8911, + 'frame_number': 8911, + 'framesequence': 8909, + 'gaze_dir': array([ 0.98058069, -0.04891801, 0.18991728]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04891801, 0.18991728]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04891801, 0.18991728]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.056672874838113785, + 'throttle_input': 0.0, + 'timestamp': 39.84588285908103, + 'timestamp_carla': 39845, + 'timestamp_device': 39522, + 'timestamp_stream': 39.84588285908103, + 'transform': [array([-0.13541564, -0.08815796, 0.06236707]), + array([ 0.32490525, -0.06366362, 0.3099229 ])]} +---------------------- +{'AngularVelocity': array([-0.31900901, -0.33903947, -3.50531459]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.761579513549805, + 'FR_Wheel_Angle': 41.646087646484375, + 'Location': array([ -0.80587006, -19.21562767, 0.16857442]), + 'Rotation': array([ 0.05154743, 41.11396027, 0.64233029]), + 'Velocity': array([-0.43230778, -0.25840741, 0.00053598]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.65869140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.17504883, -1708.61755371, 16.43554688]), + 'frame': 8912, + 'frame_number': 8912, + 'framesequence': 8910, + 'gaze_dir': array([ 0.98058069, -0.04967687, 0.18972021]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04967687, 0.18972021]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04967687, 0.18972021]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05775322765111923, + 'throttle_input': 0.0, + 'timestamp': 39.84947365894914, + 'timestamp_carla': 39849, + 'timestamp_device': 39526, + 'timestamp_stream': 39.84947365894914, + 'transform': [array([-0.13594368, -0.08959839, 0.06234943]), + array([ 0.32519212, -0.0660499 , 0.30996582])]} +---------------------- +{'AngularVelocity': array([-0.26741096, -0.27625927, -3.42535233]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.747703552246094, + 'FR_Wheel_Angle': 41.62688446044922, + 'Location': array([ -0.82822537, -19.22485924, 0.16859971]), + 'Rotation': array([ 0.05168404, 40.94158173, 0.64215183]), + 'Velocity': array([-4.92612898e-01, -2.35701457e-01, 3.23324202e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.667724609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.5519104 , -1709.51953125, 16.43505859]), + 'frame': 8913, + 'frame_number': 8913, + 'framesequence': 8911, + 'gaze_dir': array([ 0.98058069, -0.05043566, 0.18951991]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05043566, 0.18951991]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05043566, 0.18951991]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.058833587914705276, + 'throttle_input': 0.0, + 'timestamp': 39.85336245968938, + 'timestamp_carla': 39853, + 'timestamp_device': 39530, + 'timestamp_stream': 39.85336245968938, + 'transform': [array([-0.13645111, -0.09115844, 0.06255498]), + array([ 0.32470718, -0.06872698, 0.30935457])]} +---------------------- +{'AngularVelocity': array([-0.26188147, -0.27758336, -3.66667342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.763566970825195, + 'FR_Wheel_Angle': 41.64988327026367, + 'Location': array([ -0.85320157, -19.23512077, 0.16862352]), + 'Rotation': array([ 0.05233974, 40.75494385, 0.64762044]), + 'Velocity': array([-0.41721347, -0.26829049, 0.00065574]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.676513671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.96511841, -1710.43103027, 16.43505859]), + 'frame': 8914, + 'frame_number': 8914, + 'framesequence': 8912, + 'gaze_dir': array([ 0.98058069, -0.05119292, 0.18931676]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05119292, 0.18931676]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05119292, 0.18931676]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059913940727710724, + 'throttle_input': 0.0, + 'timestamp': 39.85774005949497, + 'timestamp_carla': 39857, + 'timestamp_device': 39534, + 'timestamp_stream': 39.85774005949497, + 'transform': [array([-0.13948005, -0.09140747, 0.06227363]), + array([ 0.32594344, -0.07157981, 0.31015709])]} +---------------------- +{'AngularVelocity': array([-0.21559244, -0.21777971, -3.61534142]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754093170166016, + 'FR_Wheel_Angle': 41.635738372802734, + 'Location': array([ -0.87637365, -19.24515724, 0.16864859]), + 'Rotation': array([ 0.05205287, 40.56900406, 0.64350945]), + 'Velocity': array([-0.45658138, -0.25444546, 0.0007576 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.6842041015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.36450195, -1711.35412598, 16.43469238]), + 'frame': 8915, + 'frame_number': 8915, + 'framesequence': 8913, + 'gaze_dir': array([ 0.98058069, -0.05195008, 0.18911038]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05195008, 0.18911038]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05195008, 0.18911038]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06088443100452423, + 'throttle_input': 0.0, + 'timestamp': 39.861632257699966, + 'timestamp_carla': 39861, + 'timestamp_device': 39538, + 'timestamp_stream': 39.861632257699966, + 'transform': [array([-0.1418438 , -0.09187866, 0.06172604]), + array([ 0.32812226, -0.07405218, 0.31174463])]} +---------------------- +{'AngularVelocity': array([-0.186225 , -0.20077194, -3.97759676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.773887634277344, + 'FR_Wheel_Angle': 41.66252517700195, + 'Location': array([ -0.90157408, -19.25560379, 0.16866751]), + 'Rotation': array([ 0.05266758, 40.37821198, 0.64963734]), + 'Velocity': array([-0.36607364, -0.29219151, 0.00064255]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.6934814453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.50335693, -1712.15002441, 16.43505859]), + 'frame': 8916, + 'frame_number': 8916, + 'framesequence': 8914, + 'gaze_dir': array([ 0.98058069, -0.05270641, 0.18890098]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05270641, 0.18890098]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05270641, 0.18890098]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06194647401571274, + 'throttle_input': 0.0, + 'timestamp': 39.865225460380316, + 'timestamp_carla': 39865, + 'timestamp_device': 39542, + 'timestamp_stream': 39.865225460380316, + 'transform': [array([-0.14374085, -0.09250976, 0.06102365]), + array([ 0.33084068, -0.07631678, 0.31378746])]} +---------------------- +{'AngularVelocity': array([-0.11485952, -0.09256437, -3.61487699]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.739988327026367, + 'FR_Wheel_Angle': 41.611907958984375, + 'Location': array([ -0.9237954 , -19.2661705 , 0.16870321]), + 'Rotation': array([ 0.05059121, 40.17763138, 0.62899083]), + 'Velocity': array([-0.51470482, -0.23329456, 0.0007288 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.69851685, -1712.94921875, 16.43530273]), + 'frame': 8917, + 'frame_number': 8917, + 'framesequence': 8915, + 'gaze_dir': array([ 0.98058069, -0.05327256, 0.18874212]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05327256, 0.18874212]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05327256, 0.18874212]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06302683055400848, + 'throttle_input': 0.0, + 'timestamp': 39.86880225688219, + 'timestamp_carla': 39868, + 'timestamp_device': 39545, + 'timestamp_stream': 39.86880225688219, + 'transform': [array([-0.14535239, -0.09331665, 0.06018671]), + array([ 0.33403039, -0.07861298, 0.31622481])]} +---------------------- +{'AngularVelocity': array([-0.31040302, -0.30965596, -3.75564981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754667282104492, + 'FR_Wheel_Angle': 41.636173248291016, + 'Location': array([ -0.94866276, -19.27601242, 0.1687319 ]), + 'Rotation': array([ 0.05059121, 39.99097443, 0.63293862]), + 'Velocity': array([-0.445265 , -0.26437408, 0.00068091]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7125244140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.82159424, -1713.58251953, 16.4354248 ]), + 'frame': 8918, + 'frame_number': 8918, + 'framesequence': 8916, + 'gaze_dir': array([ 0.98058069, -0.0540274 , 0.18852742]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0540274 , 0.18852742]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0540274 , 0.18852742]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06408887356519699, + 'throttle_input': 0.0, + 'timestamp': 39.872581358999014, + 'timestamp_carla': 39872, + 'timestamp_device': 39549, + 'timestamp_stream': 39.872581358999014, + 'transform': [array([-0.146772 , -0.09434082, 0.05922787]), + array([ 0.33769137, -0.08110822, 0.31901586])]} +---------------------- +{'AngularVelocity': array([-0.24460033, -0.24586767, -3.90663481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.758426666259766, + 'FR_Wheel_Angle': 41.641780853271484, + 'Location': array([ -0.97341126, -19.28676224, 0.16876119]), + 'Rotation': array([ 0.05066634, 39.78886032, 0.63376981]), + 'Velocity': array([-0.42480791, -0.27536693, 0.00087173]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7252197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.1088562 , -1714.43444824, 16.4354248 ]), + 'frame': 8919, + 'frame_number': 8919, + 'framesequence': 8917, + 'gaze_dir': array([ 0.98058069, -0.05459244, 0.18836458]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05459244, 0.18836458]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05459244, 0.18836458]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0646015852689743, + 'throttle_input': 0.0, + 'timestamp': 39.876181557774544, + 'timestamp_carla': 39876, + 'timestamp_device': 39552, + 'timestamp_stream': 39.876181557774544, + 'transform': [array([-0.14789268, -0.09545044, 0.05831453]), + array([ 0.34114745, -0.08356664, 0.32167807])]} +---------------------- +{'AngularVelocity': array([-0.07434469, -0.0461102 , -3.67716265]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.717653274536133, + 'FR_Wheel_Angle': 41.580787658691406, + 'Location': array([ -0.99448806, -19.29744911, 0.16878846]), + 'Rotation': array([ 0.04884268, 39.58688354, 0.61551774]), + 'Velocity': array([-6.08696342e-01, -1.95367396e-01, 4.89544880e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.73583984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.26446533, -1715.10754395, 16.43554688]), + 'frame': 8920, + 'frame_number': 8920, + 'framesequence': 8918, + 'gaze_dir': array([ 0.98058069, -0.05534576, 0.18814462]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05534576, 0.18814462]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05534576, 0.18814462]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06568193435668945, + 'throttle_input': 0.0, + 'timestamp': 39.87954155728221, + 'timestamp_carla': 39879, + 'timestamp_device': 39556, + 'timestamp_stream': 39.87954155728221, + 'transform': [array([-0.14875466, -0.09657715, 0.0575238 ]), + array([ 0.34417322, -0.08597255, 0.32398131])]} +---------------------- +{'AngularVelocity': array([-0.38490301, -0.37856534, -3.74322867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.743141174316406, + 'FR_Wheel_Angle': 41.618289947509766, + 'Location': array([ -1.02028453, -19.30731392, 0.16881739]), + 'Rotation': array([ 0.04932079, 39.39628983, 0.62389767]), + 'Velocity': array([-0.48792157, -0.25160873, 0.00084518]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.749755859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.59143066, -1715.99487305, 16.43518066]), + 'frame': 8921, + 'frame_number': 8921, + 'framesequence': 8919, + 'gaze_dir': array([ 0.98058069, -0.05609748, 0.18792184]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05609748, 0.18792184]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05609748, 0.18792184]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06663411855697632, + 'throttle_input': 0.0, + 'timestamp': 39.88333925977349, + 'timestamp_carla': 39883, + 'timestamp_device': 39560, + 'timestamp_stream': 39.88333925977349, + 'transform': [array([-0.14955245, -0.09793823, 0.05675766]), + array([ 0.34716484, -0.08877486, 0.32620808])]} +---------------------- +{'AngularVelocity': array([-0.31493077, -0.31643039, -3.93463922]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75022315979004, + 'FR_Wheel_Angle': 41.62606430053711, + 'Location': array([ -1.04503357, -19.31752968, 0.1688461 ]), + 'Rotation': array([ 0.05023604, 39.19951248, 0.63150084]), + 'Velocity': array([-0.45277983, -0.26909363, 0.00080418]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7625732421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.94317627, -1716.88598633, 16.4354248 ]), + 'frame': 8922, + 'frame_number': 8922, + 'framesequence': 8920, + 'gaze_dir': array([ 0.98058069, -0.0566614 , 0.18775259]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0566614 , 0.18775259]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0566614 , 0.18775259]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06760460883378983, + 'throttle_input': 0.0, + 'timestamp': 39.88688595965505, + 'timestamp_carla': 39886, + 'timestamp_device': 39563, + 'timestamp_stream': 39.88688595965505, + 'transform': [array([-0.15016502, -0.09926147, 0.05619483]), + array([ 0.34939831, -0.09148537, 0.32784453])]} +---------------------- +{'AngularVelocity': array([-0.25761548, -0.25357026, -3.99776626]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.747665405273438, + 'FR_Wheel_Angle': 41.62224197387695, + 'Location': array([ -1.06936109, -19.32788849, 0.16887698]), + 'Rotation': array([ 0.0505229 , 38.99765015, 0.63193291]), + 'Velocity': array([-0.46083617, -0.26777485, 0.0008173 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7728271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.150177 , -1717.60302734, 16.43554688]), + 'frame': 8923, + 'frame_number': 8923, + 'framesequence': 8921, + 'gaze_dir': array([ 0.98058057, -0.05741154, 0.18752456]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05741154, 0.18752456]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05741154, 0.18752456]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06857509166002274, + 'throttle_input': 0.0, + 'timestamp': 39.890782959759235, + 'timestamp_carla': 39890, + 'timestamp_device': 39567, + 'timestamp_stream': 39.890782959759235, + 'transform': [array([-0.15071365, -0.1007605 , 0.05578573]), + array([ 0.35109219, -0.09455393, 0.32902795])]} +---------------------- +{'AngularVelocity': array([-0.23756383, -0.23390755, -4.10599756]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.751230239868164, + 'FR_Wheel_Angle': 41.627140045166016, + 'Location': array([ -1.09435213, -19.33861923, 0.16890314]), + 'Rotation': array([ 0.05062536, 38.78864288, 0.63163477]), + 'Velocity': array([-0.44183508, -0.2782532 , 0.00057118]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7843017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.50268555, -1718.5098877 , 16.43530273]), + 'frame': 8924, + 'frame_number': 8924, + 'framesequence': 8922, + 'gaze_dir': array([ 0.98058069, -0.05816148, 0.18729332]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05816148, 0.18729332]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05816148, 0.18729332]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0696188285946846, + 'throttle_input': 0.0, + 'timestamp': 39.89427435770631, + 'timestamp_carla': 39894, + 'timestamp_device': 39571, + 'timestamp_stream': 39.89427435770631, + 'transform': [array([-0.15113731, -0.10212769, 0.0556031 ]), + array([ 0.35195962, -0.09732977, 0.3295534 ])]} +---------------------- +{'AngularVelocity': array([-0.23147403, -0.22145849, -4.14566231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.736902236938477, + 'FR_Wheel_Angle': 41.60557556152344, + 'Location': array([ -1.11899757, -19.34923935, 0.16893193]), + 'Rotation': array([ 0.05046827, 38.58017349, 0.62966329]), + 'Velocity': array([-0.44480923, -0.27901977, 0.00075987]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7938232421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.83996582, -1719.43139648, 16.43554688]), + 'frame': 8925, + 'frame_number': 8925, + 'framesequence': 8923, + 'gaze_dir': array([ 0.98058069, -0.05890978, 0.18705931]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05890978, 0.18705931]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05890978, 0.18705931]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07011322677135468, + 'throttle_input': 0.0, + 'timestamp': 39.89820696040988, + 'timestamp_carla': 39898, + 'timestamp_device': 39575, + 'timestamp_stream': 39.89820696040988, + 'transform': [array([-0.15153144, -0.10367797, 0.05563019]), + array([ 0.35208941, -0.1005467 , 0.32946315])]} +---------------------- +{'AngularVelocity': array([-0.27172694, -0.26555595, -4.13022375]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74626922607422, + 'FR_Wheel_Angle': 41.62214660644531, + 'Location': array([ -1.14276874, -19.35890579, 0.16895677]), + 'Rotation': array([ 0.05073464, 38.38608932, 0.6313951 ]), + 'Velocity': array([-0.45808116, -0.27492011, 0.00073221]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8048095703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.2237854 , -1720.36682129, 16.4354248 ]), + 'frame': 8926, + 'frame_number': 8926, + 'framesequence': 8924, + 'gaze_dir': array([ 0.98058069, -0.05965784, 0.18682207]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05965784, 0.18682207]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05965784, 0.18682207]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07106540352106094, + 'throttle_input': 0.0, + 'timestamp': 39.90219435840845, + 'timestamp_carla': 39902, + 'timestamp_device': 39579, + 'timestamp_stream': 39.90219435840845, + 'transform': [array([-0.15415229, -0.10387329, 0.05527713]), + array([ 0.35358521, -0.10367776, 0.33047971])]} +---------------------- +{'AngularVelocity': array([-0.16866706, -0.1757784 , -4.45104599]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76218605041504, + 'FR_Wheel_Angle': 41.64326858520508, + 'Location': array([ -1.16868174, -19.37002182, 0.16897978]), + 'Rotation': array([ 0.05154743, 38.17006683, 0.63659608]), + 'Velocity': array([-0.38633856, -0.30831304, 0.0007779 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8135986328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.58575439, -1721.31848145, 16.4354248 ]), + 'frame': 8927, + 'frame_number': 8927, + 'framesequence': 8925, + 'gaze_dir': array([ 0.98058057, -0.0605914 , 0.18652138]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0605914 , 0.18652138]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0605914 , 0.18652138]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07243873178958893, + 'throttle_input': 0.0, + 'timestamp': 39.90815415978432, + 'timestamp_carla': 39908, + 'timestamp_device': 39584, + 'timestamp_stream': 39.90815415978432, + 'transform': [array([-0.15729736, -0.10472168, 0.0541225 ]), + array([ 0.35798386, -0.1082207 , 0.33381504])]} +---------------------- +{'AngularVelocity': array([-0.14298943, -0.12952957, -4.29736805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74785041809082, + 'FR_Wheel_Angle': 41.621456146240234, + 'Location': array([ -1.19312 , -19.3814621 , 0.16901243]), + 'Rotation': array([ 0.05039996, 37.94564056, 0.62331164]), + 'Velocity': array([-4.44143027e-01, -2.86220908e-01, -3.43470572e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.82568359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.83529663, -1722.31860352, 16.43530273]), + 'frame': 8928, + 'frame_number': 8928, + 'framesequence': 8926, + 'gaze_dir': array([ 0.98058069, -0.06133659, 0.18627767]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06133659, 0.18627767]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06133659, 0.18627767]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07333598285913467, + 'throttle_input': 0.0, + 'timestamp': 39.91163135692477, + 'timestamp_carla': 39911, + 'timestamp_device': 39588, + 'timestamp_stream': 39.91163135692477, + 'transform': [array([-0.15886116, -0.10539917, 0.05334044]), + array([ 0.3609823 , -0.11088226, 0.33609372])]} +---------------------- +{'AngularVelocity': array([-0.22854081, -0.21105468, -4.33319426]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.744890213012695, + 'FR_Wheel_Angle': 41.61859893798828, + 'Location': array([ -1.21784151, -19.39209175, 0.16905202]), + 'Rotation': array([ 0.04986038, 37.73174286, 0.61910862]), + 'Velocity': array([-0.45460582, -0.28321317, 0.00079729]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.841064453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.87524414, -1723.20898438, 16.43566895]), + 'frame': 8929, + 'frame_number': 8929, + 'framesequence': 8927, + 'gaze_dir': array([ 0.98058069, -0.06208151, 0.18603075]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06208151, 0.18603075]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06208151, 0.18603075]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07410504668951035, + 'throttle_input': 0.0, + 'timestamp': 39.91570995748043, + 'timestamp_carla': 39915, + 'timestamp_device': 39592, + 'timestamp_stream': 39.91570995748043, + 'transform': [array([-0.16035263, -0.10641113, 0.05230429]), + array([ 0.36490968, -0.11406114, 0.33911109])]} +---------------------- +{'AngularVelocity': array([-0.24374692, -0.2250313 , -4.36125326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74214744567871, + 'FR_Wheel_Angle': 41.612953186035156, + 'Location': array([ -1.24283099, -19.40296745, 0.16908319]), + 'Rotation': array([ 0.04958717, 37.51220703, 0.61637163]), + 'Velocity': array([-0.46357119, -0.28125 , 0.00072275]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.853271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.10992432, -1724.05944824, 16.43591309]), + 'frame': 8930, + 'frame_number': 8930, + 'framesequence': 8928, + 'gaze_dir': array([ 0.98058069, -0.06282473, 0.18578106]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06282473, 0.18578106]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06282473, 0.18578106]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07492905110120773, + 'throttle_input': 0.0, + 'timestamp': 39.9193711578846, + 'timestamp_carla': 39919, + 'timestamp_device': 39596, + 'timestamp_stream': 39.9193711578846, + 'transform': [array([-0.16143349, -0.10746582, 0.05136393]), + array([ 0.3684682 , -0.11698908, 0.34185317])]} +---------------------- +{'AngularVelocity': array([-0.25244245, -0.23392506, -4.42143202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74257469177246, + 'FR_Wheel_Angle': 41.61248016357422, + 'Location': array([ -1.26807868, -19.41388702, 0.16911009]), + 'Rotation': array([ 0.04957351, 37.29109573, 0.61561418]), + 'Velocity': array([-0.45877656, -0.28560331, 0.00065615]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8687744140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.34542847, -1724.95874023, 16.43566895]), + 'frame': 8931, + 'frame_number': 8931, + 'framesequence': 8929, + 'gaze_dir': array([ 0.98058069, -0.06338219, 0.18559162]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06338219, 0.18559162]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06338219, 0.18559162]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07577136158943176, + 'throttle_input': 0.0, + 'timestamp': 39.923058956861496, + 'timestamp_carla': 39922, + 'timestamp_device': 39599, + 'timestamp_stream': 39.923058956861496, + 'transform': [array([-0.16229691, -0.10864868, 0.0504723 ]), + array([ 0.37184915, -0.12004417, 0.34445298])]} +---------------------- +{'AngularVelocity': array([-0.2388958 , -0.21851961, -4.4415226 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.740036010742188, + 'FR_Wheel_Angle': 41.6082878112793, + 'Location': array([ -1.2930789 , -19.42510414, 0.1691277 ]), + 'Rotation': array([ 0.04940959, 37.0671463 , 0.61338663]), + 'Velocity': array([-0.46664977, -0.28423876, 0.00078908]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.88134765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.5078125 , -1725.66748047, 16.43603516]), + 'frame': 8932, + 'frame_number': 8932, + 'framesequence': 8930, + 'gaze_dir': array([ 0.98058057, -0.06412363, 0.18533674]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06412363, 0.18533674]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06412363, 0.18533674]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07663198560476303, + 'throttle_input': 0.0, + 'timestamp': 39.926791559904814, + 'timestamp_carla': 39926, + 'timestamp_device': 39603, + 'timestamp_stream': 39.926791559904814, + 'transform': [array([-0.16297592, -0.10994384, 0.04968882]), + array([ 0.37485442, -0.12323451, 0.34673485])]} +---------------------- +{'AngularVelocity': array([-0.27991143, -0.25036404, -4.35379887]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72693634033203, + 'FR_Wheel_Angle': 41.591251373291016, + 'Location': array([ -1.31680417, -19.43516159, 0.16916159]), + 'Rotation': array([ 0.04925249, 36.8579216 , 0.61113787]), + 'Velocity': array([-0.52117556, -0.25989595, 0.00076073]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.89599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.80255127, -1726.58605957, 16.43591309]), + 'frame': 8933, + 'frame_number': 8933, + 'framesequence': 8931, + 'gaze_dir': array([ 0.98058057, -0.06486477, 0.18507865]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06486477, 0.18507865]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06486477, 0.18507865]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07754753530025482, + 'throttle_input': 0.0, + 'timestamp': 39.93090835958719, + 'timestamp_carla': 39930, + 'timestamp_device': 39607, + 'timestamp_stream': 39.93090835958719, + 'transform': [array([-0.16354172, -0.11144897, 0.04903225]), + array([ 0.37745672, -0.1268609 , 0.34864208])]} +---------------------- +{'AngularVelocity': array([-0.28041986, -0.26664099, -4.61749792]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.746952056884766, + 'FR_Wheel_Angle': 41.62135696411133, + 'Location': array([ -1.34264874, -19.44596481, 0.16916521]), + 'Rotation': array([ 0.05046143, 36.64123917, 0.6218425 ]), + 'Velocity': array([-0.43189287, -0.30446568, 0.00072622]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7392578125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 280.0713501 , -1727.5267334 , 16.60241699]), + 'frame': 8934, + 'frame_number': 8934, + 'framesequence': 8932, + 'gaze_dir': array([ 0.98058057, -0.06560415, 0.18481787]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06560415, 0.18481787]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06560415, 0.18481787]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07840815931558609, + 'throttle_input': 0.0, + 'timestamp': 39.9343255572021, + 'timestamp_carla': 39934, + 'timestamp_device': 39611, + 'timestamp_stream': 39.9343255572021, + 'transform': [array([-0.16391739, -0.11274169, 0.04865519]), + array([ 0.37900034, -0.12990911, 0.34973779])]} +---------------------- +{'AngularVelocity': array([-0.17602125, -0.14877027, -4.504632 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.729110717773438, + 'FR_Wheel_Angle': 41.590972900390625, + 'Location': array([ -1.36746299, -19.45767403, 0.16920087]), + 'Rotation': array([ 0.04947789, 36.40301132, 0.60956448]), + 'Velocity': array([-0.50508302, -0.27219281, 0.00053404]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7520751953125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 280.36901855, -1728.48156738, 16.60253906]), + 'frame': 8935, + 'frame_number': 8935, + 'framesequence': 8933, + 'gaze_dir': array([ 0.98058057, -0.06615871, 0.18462008]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06615871, 0.18462008]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06615871, 0.18462008]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07888424396514893, + 'throttle_input': 0.0, + 'timestamp': 39.93800915777683, + 'timestamp_carla': 39937, + 'timestamp_device': 39614, + 'timestamp_stream': 39.93800915777683, + 'transform': [array([-0.16423286, -0.11416015, 0.04845967]), + array([ 0.3799156 , -0.1332684 , 0.35030252])]} +---------------------- +{'AngularVelocity': array([-0.29148209, -0.24827558, -4.37135172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.709754943847656, + 'FR_Wheel_Angle': 41.580848693847656, + 'Location': array([ -1.39001584, -19.46698189, 0.16923013]), + 'Rotation': array([ 0.04915687, 36.20386124, 0.60721558]), + 'Velocity': array([-5.88116348e-01, -2.31387556e-01, 4.79648093e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7620849609375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 280.59326172, -1729.22436523, 16.60241699]), + 'frame': 8936, + 'frame_number': 8936, + 'framesequence': 8934, + 'gaze_dir': array([ 0.98058069, -0.06689626, 0.18435411]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06689626, 0.18435411]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06689626, 0.18435411]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07972655445337296, + 'throttle_input': 0.0, + 'timestamp': 39.941500660032034, + 'timestamp_carla': 39941, + 'timestamp_device': 39618, + 'timestamp_stream': 39.941500660032034, + 'transform': [array([-0.16447295, -0.11551879, 0.04846415]), + array([ 0.38007951, -0.13647816, 0.35028344])]} +---------------------- +{'AngularVelocity': array([-0.21589451, -0.20247909, -4.88580179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.749095916748047, + 'FR_Wheel_Angle': 41.620338439941406, + 'Location': array([ -1.41936135, -19.47966957, 0.16924833]), + 'Rotation': array([ 0.05024287, 35.94659805, 0.61749941]), + 'Velocity': array([-0.41496265, -0.31945339, 0.00079635]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.7708740234375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 280.90408325, -1730.15942383, 16.60253906]), + 'frame': 8937, + 'frame_number': 8937, + 'framesequence': 8935, + 'gaze_dir': array([ 0.98058069, -0.06763344, 0.18408495]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06763344, 0.18408495]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06763344, 0.18408495]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08045900613069534, + 'throttle_input': 0.0, + 'timestamp': 39.94538505747914, + 'timestamp_carla': 39945, + 'timestamp_device': 39622, + 'timestamp_stream': 39.94538505747914, + 'transform': [array([-0.16468354, -0.11703979, 0.04871045]), + array([ 0.3794443 , -0.14008205, 0.34955329])]} +---------------------- +{'AngularVelocity': array([-0.18740565, -0.15429731, -4.59143925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.721155166625977, + 'FR_Wheel_Angle': 41.5890007019043, + 'Location': array([ -1.44272006, -19.49032784, 0.16927999]), + 'Rotation': array([ 0.04928664, 35.72351837, 0.60645515]), + 'Velocity': array([-0.53047359, -0.26572159, 0.00071415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.779541015625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 281.23797607, -1731.1027832 , 16.60241699]), + 'frame': 8938, + 'frame_number': 8938, + 'framesequence': 8936, + 'gaze_dir': array([ 0.98058069, -0.06836953, 0.18381284]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06836953, 0.18381284]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06836953, 0.18381284]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08130131661891937, + 'throttle_input': 0.0, + 'timestamp': 39.949569057673216, + 'timestamp_carla': 39949, + 'timestamp_device': 39626, + 'timestamp_stream': 39.949569057673216, + 'transform': [array([-0.16727501, -0.11723877, 0.04853636]), + array([ 0.38027075, -0.14383456, 0.35004729])]} +---------------------- +{'AngularVelocity': array([-0.18448406, -0.14030324, -4.56630754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.687833786010742, + 'FR_Wheel_Angle': 41.53516387939453, + 'Location': array([ -1.46782815, -19.50258064, 0.16931254]), + 'Rotation': array([ 0.04787963, 35.47426987, 0.59406829]), + 'Velocity': array([-0.58421981, -0.2396711 , 0.00064219]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.788330078125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 281.57653809, -1732.08251953, 16.60253906]), + 'frame': 8939, + 'frame_number': 8939, + 'framesequence': 8937, + 'gaze_dir': array([ 0.98058069, -0.06892036, 0.18360701]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06892036, 0.18360701]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06892036, 0.18360701]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08216193318367004, + 'throttle_input': 0.0, + 'timestamp': 39.95315985754132, + 'timestamp_carla': 39953, + 'timestamp_device': 39629, + 'timestamp_stream': 39.95315985754132, + 'transform': [array([-0.16921127, -0.11761963, 0.04814987]), + array([ 0.38184172, -0.14698844, 0.35116675])]} +---------------------- +{'AngularVelocity': array([-0.36799732, -0.31167734, -4.64353085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71676254272461, + 'FR_Wheel_Angle': 41.57470703125, + 'Location': array([ -1.49344146, -19.51331329, 0.16935018]), + 'Rotation': array([ 0.04801623, 35.24633026, 0.59822553]), + 'Velocity': array([-0.54348522, -0.26294509, 0.00128116]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.794677734375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 281.52792358, -1732.70605469, 16.60253906]), + 'frame': 8940, + 'frame_number': 8940, + 'framesequence': 8938, + 'gaze_dir': array([ 0.98058057, -0.06965452, 0.18332975]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06965452, 0.18332975]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06965452, 0.18332975]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08298593014478683, + 'throttle_input': 0.0, + 'timestamp': 39.956991259008646, + 'timestamp_carla': 39956, + 'timestamp_device': 39633, + 'timestamp_stream': 39.956991259008646, + 'transform': [array([-0.17094962, -0.11824585, 0.04752228]), + array([ 0.38430056, -0.15034895, 0.35298961])]} +---------------------- +{'AngularVelocity': array([-0.31587443, -0.26602682, -4.66515064]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70853614807129, + 'FR_Wheel_Angle': 41.55931854248047, + 'Location': array([ -1.51808822, -19.52397728, 0.16939348]), + 'Rotation': array([ 0.04823479, 35.01815796, 0.59987855]), + 'Velocity': array([-0.57625455, -0.2474838 , 0.00082468]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8082275390625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 281.71020508, -1733.58032227, 16.60253906]), + 'frame': 8941, + 'frame_number': 8941, + 'framesequence': 8939, + 'gaze_dir': array([ 0.98058057, -0.07038688, 0.18304981]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07038688, 0.18304981]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07038688, 0.18304981]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08370006829500198, + 'throttle_input': 0.0, + 'timestamp': 39.96097315847874, + 'timestamp_carla': 39960, + 'timestamp_device': 39637, + 'timestamp_stream': 39.96097315847874, + 'transform': [array([-0.17241417, -0.11911865, 0.04671726]), + array([ 0.38742197, -0.15387635, 0.35532933])]} +---------------------- +{'AngularVelocity': array([-0.32397157, -0.2837373 , -4.9150424 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72955894470215, + 'FR_Wheel_Angle': 41.59052276611328, + 'Location': array([ -1.54550016, -19.53515816, 0.16942187]), + 'Rotation': array([ 0.04934811, 34.77685928, 0.60921496]), + 'Velocity': array([-0.48325568, -0.29825306, 0.00067973]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.821533203125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 281.87710571, -1734.45617676, 16.60253906]), + 'frame': 8942, + 'frame_number': 8942, + 'framesequence': 8940, + 'gaze_dir': array([ 0.98058057, -0.07111881, 0.18276669]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07111881, 0.18276669]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07111881, 0.18276669]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08456069231033325, + 'throttle_input': 0.0, + 'timestamp': 39.96514206007123, + 'timestamp_carla': 39965, + 'timestamp_device': 39641, + 'timestamp_stream': 39.96514206007123, + 'transform': [array([-0.17358665, -0.12024047, 0.04579887]), + array([ 0.39093268, -0.15769158, 0.35800052])]} +---------------------- +{'AngularVelocity': array([-0.23694414, -0.20438816, -5.008255 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.729019165039062, + 'FR_Wheel_Angle': 41.5900993347168, + 'Location': array([ -1.57156551, -19.54635811, 0.16944627]), + 'Rotation': array([ 0.04969645, 34.5349884 , 0.60976565]), + 'Velocity': array([-0.48243538, -0.30135262, 0.00065696]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8363037109375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 282.06893921, -1735.36584473, 16.60241699]), + 'frame': 8943, + 'frame_number': 8943, + 'framesequence': 8941, + 'gaze_dir': array([ 0.98058069, -0.07184891, 0.18248093]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07184891, 0.18248093]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07184891, 0.18248093]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08538468182086945, + 'throttle_input': 0.0, + 'timestamp': 39.96862795948982, + 'timestamp_carla': 39968, + 'timestamp_device': 39645, + 'timestamp_stream': 39.96862795948982, + 'transform': [array([-0.17435309, -0.12129638, 0.04505737]), + array([ 0.39378771, -0.16094351, 0.36016011])]} +---------------------- +{'AngularVelocity': array([-0.22733507, -0.19776976, -5.13311434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.735248565673828, + 'FR_Wheel_Angle': 41.60091018676758, + 'Location': array([ -1.59727979, -19.55727959, 0.16944918]), + 'Rotation': array([ 0.05027019, 34.29983139, 0.61368102]), + 'Velocity': array([-0.4537417 , -0.31857085, 0.00094955]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8507080078125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 282.26358032, -1736.2902832 , 16.60241699]), + 'frame': 8944, + 'frame_number': 8944, + 'framesequence': 8942, + 'gaze_dir': array([ 0.98058069, -0.07257855, 0.18219194]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07257855, 0.18219194]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07257855, 0.18219194]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08584246784448624, + 'throttle_input': 0.0, + 'timestamp': 39.97257635742426, + 'timestamp_carla': 39972, + 'timestamp_device': 39649, + 'timestamp_stream': 39.97257635742426, + 'transform': [array([-0.17499115, -0.12261108, 0.04430695]), + array([ 0.39668369, -0.1647348 , 0.36234441])]} +---------------------- +{'AngularVelocity': array([-0.17413327, -0.1378891 , -5.0429554 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.721946716308594, + 'FR_Wheel_Angle': 41.57790756225586, + 'Location': array([ -1.62275863, -19.56893539, 0.16948107]), + 'Rotation': array([ 0.04941642, 34.05061722, 0.60443157]), + 'Velocity': array([-0.50640142, -0.29370674, 0.00091686]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8653564453125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 282.52508545, -1737.21948242, 16.60241699]), + 'frame': 8945, + 'frame_number': 8945, + 'framesequence': 8943, + 'gaze_dir': array([ 0.98058057, -0.07330703, 0.18190004]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07330703, 0.18190004]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07330703, 0.18190004]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08666646480560303, + 'throttle_input': 0.0, + 'timestamp': 39.97662355750799, + 'timestamp_carla': 39976, + 'timestamp_device': 39653, + 'timestamp_stream': 39.97662355750799, + 'transform': [array([-0.1754483 , -0.12405517, 0.04371075]), + array([ 0.39902645, -0.16871025, 0.36407608])]} +---------------------- +{'AngularVelocity': array([-0.22840714, -0.18622006, -5.18059397]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.727970123291016, + 'FR_Wheel_Angle': 41.58636474609375, + 'Location': array([ -1.64953244, -19.58034325, 0.16951291]), + 'Rotation': array([ 0.049232 , 33.80055237, 0.60343248]), + 'Velocity': array([-0.47877303, -0.310516 , 0.00070838]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8797607421875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 282.77938843, -1738.17822266, 16.60253906]), + 'frame': 8946, + 'frame_number': 8946, + 'framesequence': 8944, + 'gaze_dir': array([ 0.98058069, -0.07403364, 0.18160555]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07403364, 0.18160555]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07403364, 0.18160555]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08802148699760437, + 'throttle_input': 0.0, + 'timestamp': 39.98070515692234, + 'timestamp_carla': 39980, + 'timestamp_device': 39657, + 'timestamp_stream': 39.98070515692234, + 'transform': [array([-0.17575897, -0.12556885, 0.04333729]), + array([ 0.40059739, -0.1728099 , 0.36515626])]} +---------------------- +{'AngularVelocity': array([-0.1973107 , -0.15842363, -5.26082182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.726612091064453, + 'FR_Wheel_Angle': 41.58393096923828, + 'Location': array([ -1.67632377, -19.59218407, 0.16954409]), + 'Rotation': array([ 0.04877438, 33.54160309, 0.59908432]), + 'Velocity': array([-0.48148733, -0.31185791, 0.00073487]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.8931884765625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 283.04138184, -1739.15100098, 16.60253906]), + 'frame': 8947, + 'frame_number': 8947, + 'framesequence': 8945, + 'gaze_dir': array([ 0.98058069, -0.07475977, 0.18130784]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07475977, 0.18130784]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07475977, 0.18130784]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08882717788219452, + 'throttle_input': 0.0, + 'timestamp': 39.98429325968027, + 'timestamp_carla': 39984, + 'timestamp_device': 39661, + 'timestamp_stream': 39.98429325968027, + 'transform': [array([-0.17593826, -0.12693359, 0.04319796]), + array([ 0.40127358, -0.17647079, 0.36555859])]} +---------------------- +{'AngularVelocity': array([-0.22745501, -0.17672481, -5.2228241 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.718637466430664, + 'FR_Wheel_Angle': 41.57419967651367, + 'Location': array([ -1.7024858 , -19.60363197, 0.16957742]), + 'Rotation': array([ 0.04804355, 33.28691864, 0.59285504]), + 'Velocity': array([-0.51189077, -0.29792565, 0.00067321]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.903076171875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 283.29187012, -1740.11486816, 16.60253906]), + 'frame': 8948, + 'frame_number': 8948, + 'framesequence': 8946, + 'gaze_dir': array([ 0.98058069, -0.07530305, 0.18108287]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07530305, 0.18108287]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07530305, 0.18108287]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08928495645523071, + 'throttle_input': 0.0, + 'timestamp': 39.988100457936525, + 'timestamp_carla': 39987, + 'timestamp_device': 39664, + 'timestamp_stream': 39.988100457936525, + 'transform': [array([-0.17606163, -0.12840088, 0.04327848]), + array([ 0.40117115, -0.18038912, 0.36531609])]} +---------------------- +{'AngularVelocity': array([-0.26327506, -0.20668928, -5.24932528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.715932846069336, + 'FR_Wheel_Angle': 41.56803512573242, + 'Location': array([ -1.72864938, -19.61497688, 0.169606 ]), + 'Rotation': array([ 0.04772936, 33.03500748, 0.59112656]), + 'Velocity': array([-0.52036411, -0.29570639, 0.00107118]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.9129638671875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 283.49578857, -1740.89440918, 16.60253906]), + 'frame': 8949, + 'frame_number': 8949, + 'framesequence': 8947, + 'gaze_dir': array([ 0.98058069, -0.07620771, 0.180704 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07620771, 0.180704 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07620771, 0.180704 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09016388654708862, + 'throttle_input': 0.0, + 'timestamp': 39.99227345734835, + 'timestamp_carla': 39992, + 'timestamp_device': 39669, + 'timestamp_stream': 39.99227345734835, + 'transform': [array([-0.17611976, -0.13001709, 0.04363604]), + array([ 0.40010563, -0.18474707, 0.36426097])]} +---------------------- +{'AngularVelocity': array([-0.28012371, -0.21913299, -5.28235006]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.712860107421875, + 'FR_Wheel_Angle': 41.563175201416016, + 'Location': array([ -1.75490415, -19.62625313, 0.16964285]), + 'Rotation': array([ 0.04756543, 32.78112793, 0.59006673]), + 'Velocity': array([-0.53036237, -0.2925491 , 0.00067461]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.92333984375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 283.88598633, -1742.07629395, 16.60241699]), + 'frame': 8950, + 'frame_number': 8950, + 'framesequence': 8948, + 'gaze_dir': array([ 0.98058069, -0.07674918, 0.1804747 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07674918, 0.1804747 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07674918, 0.1804747 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09100620448589325, + 'throttle_input': 0.0, + 'timestamp': 39.99612945690751, + 'timestamp_carla': 39996, + 'timestamp_device': 39672, + 'timestamp_stream': 39.99612945690751, + 'transform': [array([-0.17840637, -0.1301709 , 0.04359679]), + array([ 0.40046763, -0.18861836, 0.36436361])]} +---------------------- +{'AngularVelocity': array([-0.28523973, -0.22631492, -5.39279699]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71666717529297, + 'FR_Wheel_Angle': 41.56904983520508, + 'Location': array([ -1.78171229, -19.63739967, 0.16967589]), + 'Rotation': array([ 0.04787279, 32.5262146 , 0.59260172]), + 'Velocity': array([-0.51220506, -0.3049075 , 0.00079818]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.9278564453125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 284.06091309, -1742.87414551, 16.60241699]), + 'frame': 8951, + 'frame_number': 8951, + 'framesequence': 8949, + 'gaze_dir': array([ 0.98058069, -0.07747076, 0.18016614]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07747076, 0.18016614]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07747076, 0.18016614]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09188513457775116, + 'throttle_input': 0.0, + 'timestamp': 39.999851658940315, + 'timestamp_carla': 39999, + 'timestamp_device': 39676, + 'timestamp_stream': 39.999851658940315, + 'transform': [array([-0.18030868, -0.130542 , 0.04329445]), + array([ 0.40174487, -0.19228251, 0.36523792])]} +---------------------- +{'AngularVelocity': array([-0.23810948, -0.18703215, -5.49284315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71889305114746, + 'FR_Wheel_Angle': 41.571006774902344, + 'Location': array([ -1.80902243, -19.64915276, 0.16970384]), + 'Rotation': array([ 0.04788645, 32.25907898, 0.59210414]), + 'Velocity': array([-0.50031489, -0.31429547, 0.00075338]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.937255859375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 284.12835693, -1743.72839355, 16.60241699]), + 'frame': 8952, + 'frame_number': 8952, + 'framesequence': 8950, + 'gaze_dir': array([ 0.98058069, -0.0781904 , 0.17985497]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0781904 , 0.17985497]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0781904 , 0.17985497]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09278237819671631, + 'throttle_input': 0.0, + 'timestamp': 40.00328275933862, + 'timestamp_carla': 40003, + 'timestamp_device': 39680, + 'timestamp_stream': 40.00328275933862, + 'transform': [array([-0.18179984, -0.13106444, 0.04283891]), + array([ 0.40356171, -0.19563597, 0.36656225])]} +---------------------- +{'AngularVelocity': array([-0.21882707, -0.16831762, -5.54870462]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.705249786376953, + 'FR_Wheel_Angle': 41.551456451416016, + 'Location': array([ -1.83616292, -19.66089439, 0.16973436]), + 'Rotation': array([ 0.04763374, 31.99126816, 0.58940625]), + 'Velocity': array([-0.50232673, -0.31573302, 0.0007188 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.9490966796875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 284.23910522, -1744.60412598, 16.60241699]), + 'frame': 8953, + 'frame_number': 8953, + 'framesequence': 8951, + 'gaze_dir': array([ 0.98058069, -0.07890949, 0.17954066]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07890949, 0.17954066]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07890949, 0.17954066]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09355144202709198, + 'throttle_input': 0.0, + 'timestamp': 40.007265258580446, + 'timestamp_carla': 40007, + 'timestamp_device': 39684, + 'timestamp_stream': 40.007265258580446, + 'transform': [array([-0.18318047, -0.13188842, 0.04213613]), + array([ 0.40628695, -0.19957139, 0.36860713])]} +---------------------- +{'AngularVelocity': array([-0.27560046, -0.21418869, -5.58063889]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71647834777832, + 'FR_Wheel_Angle': 41.56733703613281, + 'Location': array([ -1.86196697, -19.67121696, 0.16975893]), + 'Rotation': array([ 0.04796842, 31.7467556 , 0.59255815]), + 'Velocity': array([-0.50550455, -0.31615818, 0.00083403]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.961669921875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 284.39358521, -1745.49389648, 16.60241699]), + 'frame': 8954, + 'frame_number': 8954, + 'framesequence': 8952, + 'gaze_dir': array([ 0.98058057, -0.07962731, 0.17922345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07962731, 0.17922345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07962731, 0.17922345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09448530524969101, + 'throttle_input': 0.0, + 'timestamp': 40.011291056871414, + 'timestamp_carla': 40011, + 'timestamp_device': 39688, + 'timestamp_stream': 40.011291056871414, + 'transform': [array([-0.18422873, -0.13292359, 0.04134064]), + array([ 0.40932637, -0.20365492, 0.37092325])]} +---------------------- +{'AngularVelocity': array([-0.20068076, -0.15262283, -5.67095184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.716854095458984, + 'FR_Wheel_Angle': 41.56658172607422, + 'Location': array([ -1.88962245, -19.68327522, 0.16978891]), + 'Rotation': array([ 0.047784 , 31.4698143 , 0.58982503]), + 'Velocity': array([-0.50130242, -0.32147166, 0.00082338]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.9752197265625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 284.52960205, -1746.40869141, 16.60241699]), + 'frame': 8955, + 'frame_number': 8955, + 'framesequence': 8953, + 'gaze_dir': array([ 0.98058057, -0.08052193, 0.17882329]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08052193, 0.17882329]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08052193, 0.17882329]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09534592926502228, + 'throttle_input': 0.0, + 'timestamp': 40.016002260148525, + 'timestamp_carla': 40015, + 'timestamp_device': 39693, + 'timestamp_stream': 40.016002260148525, + 'transform': [array([-0.185056 , -0.13435425, 0.0404244 ]), + array([ 0.41283026, -0.20857231, 0.37358522])]} +---------------------- +{'AngularVelocity': array([-0.19026957, -0.14894517, -5.80478764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.722820281982422, + 'FR_Wheel_Angle': 41.576026916503906, + 'Location': array([ -1.91681802, -19.69441223, 0.16981427]), + 'Rotation': array([ 0.04807087, 31.20671654, 0.59267825]), + 'Velocity': array([-0.47580999, -0.33798388, 0.00078725]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1165.99267578125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 284.80123901, -1747.56542969, 16.60266113]), + 'frame': 8956, + 'frame_number': 8956, + 'framesequence': 8954, + 'gaze_dir': array([ 0.98058069, -0.08105843, 0.17858076]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08105843, 0.17858076]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08105843, 0.17858076]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09626149386167526, + 'throttle_input': 0.0, + 'timestamp': 40.02002825960517, + 'timestamp_carla': 40019, + 'timestamp_device': 39696, + 'timestamp_stream': 40.02002825960517, + 'transform': [array([-0.18552269, -0.13569702, 0.03976063]), + array([ 0.41541892, -0.21289074, 0.37551692])]} +---------------------- +{'AngularVelocity': array([-0.14497697, -0.10306525, -5.79739523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71451187133789, + 'FR_Wheel_Angle': 41.56621170043945, + 'Location': array([ -1.94456053, -19.70687866, 0.16985007]), + 'Rotation': array([ 0.04708049, 30.91927147, 0.58247018]), + 'Velocity': array([-0.50576198, -0.32448253, 0.00066555]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.0074462890625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 284.86834717, -1748.35351562, 16.60241699]), + 'frame': 8957, + 'frame_number': 8957, + 'framesequence': 8955, + 'gaze_dir': array([ 0.98058069, -0.08177171, 0.17825527]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08177171, 0.17825527]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08177171, 0.17825527]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09686575829982758, + 'throttle_input': 0.0, + 'timestamp': 40.0240860581398, + 'timestamp_carla': 40023, + 'timestamp_device': 39700, + 'timestamp_stream': 40.0240860581398, + 'transform': [array([-0.18580116, -0.13713989, 0.03926823]), + array([ 0.41736552, -0.21733932, 0.37694991])]} +---------------------- +{'AngularVelocity': array([-0.18839057, -0.12123629, -5.64242172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.692401885986328, + 'FR_Wheel_Angle': 41.53392028808594, + 'Location': array([ -1.97056901, -19.71882439, 0.16989636]), + 'Rotation': array([ 0.04540027, 30.64317703, 0.56831372]), + 'Velocity': array([-0.59236497, -0.27520171, 0.00097173]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.0213623046875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 285.07635498, -1749.33044434, 16.60253906]), + 'frame': 8958, + 'frame_number': 8958, + 'framesequence': 8956, + 'gaze_dir': array([ 0.98058069, -0.08248436, 0.17792663]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08248436, 0.17792663]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08248436, 0.17792663]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0977080687880516, + 'throttle_input': 0.0, + 'timestamp': 40.02772345766425, + 'timestamp_carla': 40027, + 'timestamp_device': 39704, + 'timestamp_stream': 40.02772345766425, + 'transform': [array([-0.1859336 , -0.13847899, 0.039009 ]), + array([ 0.41845152, -0.22138338, 0.37770361])]} +---------------------- +{'AngularVelocity': array([-0.30860063, -0.22150619, -5.83383369]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.705841064453125, + 'FR_Wheel_Angle': 41.55166244506836, + 'Location': array([ -1.99941373, -19.73075294, 0.16993982]), + 'Rotation': array([ 0.04530464, 30.35703659, 0.57034653]), + 'Velocity': array([-0.53574085, -0.3119652 , 0.00073363]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.0340576171875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 285.29846191, -1750.32312012, 16.60253906]), + 'frame': 8959, + 'frame_number': 8959, + 'framesequence': 8957, + 'gaze_dir': array([ 0.98058069, -0.08319502, 0.17759545]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08319502, 0.17759545]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08319502, 0.17759545]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09880673140287399, + 'throttle_input': 0.0, + 'timestamp': 40.031180158257484, + 'timestamp_carla': 40031, + 'timestamp_device': 39708, + 'timestamp_stream': 40.031180158257484, + 'transform': [array([-0.18597694, -0.13978271, 0.03894817]), + array([ 0.41884768, -0.22528495, 0.37787756])]} +---------------------- +{'AngularVelocity': array([-0.29416448, -0.20712304, -5.79128027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.693809509277344, + 'FR_Wheel_Angle': 41.53844451904297, + 'Location': array([ -2.02575994, -19.74194717, 0.16998002]), + 'Rotation': array([ 0.04507925, 30.08713913, 0.568012 ]), + 'Velocity': array([-0.58143777, -0.28661165, 0.00111657]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.04541015625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 285.54797363, -1751.30725098, 16.60253906]), + 'frame': 8960, + 'frame_number': 8960, + 'framesequence': 8958, + 'gaze_dir': array([ 0.98058069, -0.08372781, 0.17734489]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08372781, 0.17734489]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08372781, 0.17734489]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09966734796762466, + 'throttle_input': 0.0, + 'timestamp': 40.03466895967722, + 'timestamp_carla': 40034, + 'timestamp_device': 39711, + 'timestamp_stream': 40.03466895967722, + 'transform': [array([-0.18595488, -0.14111084, 0.03907987]), + array([ 0.41857445, -0.22925563, 0.37748772])]} +---------------------- +{'AngularVelocity': array([-0.32338274, -0.23109387, -5.8869772 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.699024200439453, + 'FR_Wheel_Angle': 41.54071807861328, + 'Location': array([ -2.05360389, -19.75345421, 0.17001344]), + 'Rotation': array([ 0.04543442, 29.80731583, 0.57104981]), + 'Velocity': array([-5.58056533e-01, -3.03613245e-01, 5.52864047e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.2197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.74243164, -1752.0690918 , 16.43908691]), + 'frame': 8961, + 'frame_number': 8961, + 'framesequence': 8959, + 'gaze_dir': array([ 0.98058069, -0.08443613, 0.17700873]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08443613, 0.17700873]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08443613, 0.17700873]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10012513399124146, + 'throttle_input': 0.0, + 'timestamp': 40.03873885795474, + 'timestamp_carla': 40038, + 'timestamp_device': 39715, + 'timestamp_stream': 40.03873885795474, + 'transform': [array([-0.18586898, -0.14267334, 0.03948324]), + array([ 0.41730404, -0.23392922, 0.37630275])]} +---------------------- +{'AngularVelocity': array([-0.23116796, -0.16846387, -6.09033871]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.709686279296875, + 'FR_Wheel_Angle': 41.556339263916016, + 'Location': array([ -2.08286738, -19.76589012, 0.17004105]), + 'Rotation': array([ 0.0458374 , 29.50781631, 0.57355088]), + 'Velocity': array([-5.13809443e-01, -3.33412766e-01, 2.89220799e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.23046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.02105713, -1753.07104492, 16.43896484]), + 'frame': 8962, + 'frame_number': 8962, + 'framesequence': 8960, + 'gaze_dir': array([ 0.98058069, -0.0853203 , 0.17658426]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0853203 , 0.17658426]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0853203 , 0.17658426]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10135197639465332, + 'throttle_input': 0.0, + 'timestamp': 40.04328855872154, + 'timestamp_carla': 40043, + 'timestamp_device': 39720, + 'timestamp_stream': 40.04328855872154, + 'transform': [array([-0.18835266, -0.1428894 , 0.03944082]), + array([ 0.41766605, -0.23894788, 0.37640938])]} +---------------------- +{'AngularVelocity': array([-0.20205753, -0.1391792 , -6.10070801]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70313262939453, + 'FR_Wheel_Angle': 41.54433059692383, + 'Location': array([ -2.11094642, -19.77801895, 0.17007414]), + 'Rotation': array([ 0.04533879, 29.21317863, 0.56762213]), + 'Velocity': array([-0.53699797, -0.32228854, 0.00056129]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.2364501953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.34155273, -1754.28173828, 16.43884277]), + 'frame': 8963, + 'frame_number': 8963, + 'framesequence': 8961, + 'gaze_dir': array([ 0.98058069, -0.08585006, 0.17632733]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08585006, 0.17632733]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08585006, 0.17632733]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10206610709428787, + 'throttle_input': 0.0, + 'timestamp': 40.04706745967269, + 'timestamp_carla': 40046, + 'timestamp_device': 39723, + 'timestamp_stream': 40.04706745967269, + 'transform': [array([-0.19009566, -0.14329712, 0.03914518]), + array([ 0.41887498, -0.24305259, 0.37726635])]} +---------------------- +{'AngularVelocity': array([-0.22163649, -0.15134294, -6.16739845]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.704315185546875, + 'FR_Wheel_Angle': 41.547752380371094, + 'Location': array([ -2.13958573, -19.79018974, 0.17010565]), + 'Rotation': array([ 0.04501778, 28.91497993, 0.56459695]), + 'Velocity': array([-0.53036606, -0.32906136, 0.00065938]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.24365234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.22589111, -1754.96362305, 16.43969727]), + 'frame': 8964, + 'frame_number': 8964, + 'framesequence': 8962, + 'gaze_dir': array([ 0.98058069, -0.08655429, 0.1759827 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08655429, 0.1759827 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08655429, 0.1759827 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10278024524450302, + 'throttle_input': 0.0, + 'timestamp': 40.05061775818467, + 'timestamp_carla': 40050, + 'timestamp_device': 39727, + 'timestamp_stream': 40.05061775818467, + 'transform': [array([-0.19145012, -0.14386718, 0.03868879]), + array([ 0.42065084, -0.24690105, 0.37859571])]} +---------------------- +{'AngularVelocity': array([-0.20561241, -0.12720786, -6.03260279]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.679296493530273, + 'FR_Wheel_Angle': 41.508216857910156, + 'Location': array([ -2.16572905, -19.80188942, 0.17013434]), + 'Rotation': array([ 0.04382932, 28.63060379, 0.55333662]), + 'Velocity': array([-0.62643582, -0.26985297, 0.00073766]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.25634765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.30511475, -1755.87097168, 16.43969727]), + 'frame': 8965, + 'frame_number': 8965, + 'framesequence': 8963, + 'gaze_dir': array([ 0.98058069, -0.08725781, 0.17563494]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08725781, 0.17563494]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08725781, 0.17563494]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10312815010547638, + 'throttle_input': 0.0, + 'timestamp': 40.054174259305, + 'timestamp_carla': 40054, + 'timestamp_device': 39731, + 'timestamp_stream': 40.054174259305, + 'transform': [array([-0.19252709, -0.14461547, 0.03811329]), + array([ 0.42288432, -0.25078759, 0.38027233])]} +---------------------- +{'AngularVelocity': array([-0.35671446, -0.23838092, -6.15286636]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.688335418701172, + 'FR_Wheel_Angle': 41.53144836425781, + 'Location': array([ -2.19419265, -19.81319618, 0.17015997]), + 'Rotation': array([ 0.04403423, 28.3419838 , 0.55677843]), + 'Velocity': array([-0.58835572, -0.29733881, 0.00076951]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.2667236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.39978027, -1756.76916504, 16.43994141]), + 'frame': 8966, + 'frame_number': 8966, + 'framesequence': 8964, + 'gaze_dir': array([ 0.98058069, -0.08778403, 0.17537251]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08778403, 0.17537251]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08778403, 0.17537251]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10384228080511093, + 'throttle_input': 0.0, + 'timestamp': 40.057949259877205, + 'timestamp_carla': 40057, + 'timestamp_device': 39734, + 'timestamp_stream': 40.057949259877205, + 'transform': [array([-0.19337173, -0.14557739, 0.03743622]), + array([ 0.42552075, -0.25499952, 0.38224211])]} +---------------------- +{'AngularVelocity': array([-0.31686419, -0.21115604, -6.20786524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.686058044433594, + 'FR_Wheel_Angle': 41.51812744140625, + 'Location': array([ -2.2220962 , -19.82471848, 0.17018385]), + 'Rotation': array([ 0.04432109, 28.05052376, 0.55828494]), + 'Velocity': array([-5.94933748e-01, -2.95627505e-01, 5.05571370e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.2796630859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.4569397 , -1757.5045166 , 16.44042969]), + 'frame': 8967, + 'frame_number': 8967, + 'framesequence': 8965, + 'gaze_dir': array([ 0.98058069, -0.0884851 , 0.17501985]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0884851 , 0.17501985]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0884851 , 0.17501985]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10459303855895996, + 'throttle_input': 0.0, + 'timestamp': 40.06145055964589, + 'timestamp_carla': 40061, + 'timestamp_device': 39738, + 'timestamp_stream': 40.06145055964589, + 'transform': [array([-0.19392249, -0.14659424, 0.03681267]), + array([ 0.42792499, -0.25900438, 0.38405976])]} +---------------------- +{'AngularVelocity': array([-0.25171918, -0.17268422, -6.41897202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.701486587524414, + 'FR_Wheel_Angle': 41.5402946472168, + 'Location': array([ -2.25224662, -19.83708382, 0.17021482]), + 'Rotation': array([ 0.04496313, 27.73715973, 0.56288934]), + 'Velocity': array([-5.33531070e-01, -3.38283539e-01, 4.63623990e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.2943115234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.60134888, -1758.46154785, 16.44055176]), + 'frame': 8968, + 'frame_number': 8968, + 'framesequence': 8966, + 'gaze_dir': array([ 0.98058069, -0.08900947, 0.17475374]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08900947, 0.17475374]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08900947, 0.17475374]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10538042336702347, + 'throttle_input': 0.0, + 'timestamp': 40.06486235931516, + 'timestamp_carla': 40064, + 'timestamp_device': 39741, + 'timestamp_stream': 40.06486235931516, + 'transform': [array([-0.19427314, -0.14768066, 0.0362674 ]), + array([ 0.43005601, -0.2629768 , 0.38564914])]} +---------------------- +{'AngularVelocity': array([-0.20603803, -0.12760794, -6.33648157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.684951782226562, + 'FR_Wheel_Angle': 41.517784118652344, + 'Location': array([ -2.28005934, -19.84918594, 0.17025477]), + 'Rotation': array([ 0.04406838, 27.4335556 , 0.55319405]), + 'Velocity': array([-0.59454918, -0.30135474, 0.00083109]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.3077392578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.69720459, -1759.21899414, 16.44042969]), + 'frame': 8969, + 'frame_number': 8969, + 'framesequence': 8967, + 'gaze_dir': array([ 0.98058069, -0.08970805, 0.17439616]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08970805, 0.17439616]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08970805, 0.17439616]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1061311736702919, + 'throttle_input': 0.0, + 'timestamp': 40.068845458328724, + 'timestamp_carla': 40068, + 'timestamp_device': 39745, + 'timestamp_stream': 40.068845458328724, + 'transform': [array([-0.19448066, -0.14904785, 0.03577001]), + array([ 0.43201628, -0.26771522, 0.38709474])]} +---------------------- +{'AngularVelocity': array([-0.24605402, -0.15998565, -6.518682 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69731330871582, + 'FR_Wheel_Angle': 41.536529541015625, + 'Location': array([ -2.3100872 , -19.86141586, 0.17028867]), + 'Rotation': array([ 0.044164 , 27.11876678, 0.55475491]), + 'Velocity': array([-0.5456062 , -0.33641726, 0.00094381]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.3223876953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.90145874, -1760.19885254, 16.44067383]), + 'frame': 8970, + 'frame_number': 8970, + 'framesequence': 8968, + 'gaze_dir': array([ 0.98058069, -0.09057843, 0.1739457 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09057843, 0.1739457 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09057843, 0.1739457 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10695517063140869, + 'throttle_input': 0.0, + 'timestamp': 40.07323445752263, + 'timestamp_carla': 40073, + 'timestamp_device': 39750, + 'timestamp_stream': 40.07323445752263, + 'transform': [array([-0.1945156 , -0.15063843, 0.03547328]), + array([ 0.43332085, -0.27303866, 0.38794979])]} +---------------------- +{'AngularVelocity': array([-0.2375422 , -0.14557698, -6.45560837]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68250846862793, + 'FR_Wheel_Angle': 41.51304626464844, + 'Location': array([ -2.33774614, -19.8730793 , 0.17032716]), + 'Rotation': array([ 0.04351513, 26.81877518, 0.54809135]), + 'Velocity': array([-0.59969372, -0.30319479, 0.00088872]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.33740234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.16729736, -1761.41052246, 16.4407959 ]), + 'frame': 8971, + 'frame_number': 8971, + 'framesequence': 8969, + 'gaze_dir': array([ 0.98058057, -0.09127376, 0.17358182]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09127376, 0.17358182]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09127376, 0.17358182]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10777917504310608, + 'throttle_input': 0.0, + 'timestamp': 40.07716975733638, + 'timestamp_carla': 40077, + 'timestamp_device': 39754, + 'timestamp_stream': 40.07716975733638, + 'transform': [array([-0.19443642, -0.15210205, 0.03543011]), + array([ 0.43364868, -0.27786613, 0.38806927])]} +---------------------- +{'AngularVelocity': array([-0.22066109, -0.14305915, -6.67342234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.698482513427734, + 'FR_Wheel_Angle': 41.53485870361328, + 'Location': array([ -2.36849761, -19.8856163 , 0.17035593]), + 'Rotation': array([ 0.04379517, 26.49318886, 0.55120909]), + 'Velocity': array([-0.53796715, -0.34721962, 0.00072193]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.349609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.34988403, -1762.44689941, 16.44091797]), + 'frame': 8972, + 'frame_number': 8972, + 'framesequence': 8970, + 'gaze_dir': array([ 0.98058069, -0.09179448, 0.17330703]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09179448, 0.17330703]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09179448, 0.17330703]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10849330574274063, + 'throttle_input': 0.0, + 'timestamp': 40.080855559557676, + 'timestamp_carla': 40080, + 'timestamp_device': 39757, + 'timestamp_stream': 40.080855559557676, + 'transform': [array([-0.19428703, -0.15349364, 0.03559973]), + array([ 0.43319789, -0.28243557, 0.38757065])]} +---------------------- +{'AngularVelocity': array([-0.21877645, -0.13132048, -6.60898733]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.682491302490234, + 'FR_Wheel_Angle': 41.51788330078125, + 'Location': array([ -2.39641905, -19.89733124, 0.17039239]), + 'Rotation': array([ 0.04308483, 26.18749428, 0.54353535]), + 'Velocity': array([-0.59558988, -0.3117049 , 0.00065987]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.357177734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.46875 , -1763.2578125 , 16.44104004]), + 'frame': 8973, + 'frame_number': 8973, + 'framesequence': 8971, + 'gaze_dir': array([ 0.98058057, -0.09248658, 0.17293866]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09248658, 0.17293866]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09248658, 0.17293866]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1092623695731163, + 'throttle_input': 0.0, + 'timestamp': 40.08475685864687, + 'timestamp_carla': 40084, + 'timestamp_device': 39761, + 'timestamp_stream': 40.08475685864687, + 'transform': [array([-0.19406945, -0.15497558, 0.03601833]), + array([ 0.43187967, -0.2873044 , 0.38634136])]} +---------------------- +{'AngularVelocity': array([-0.23901352, -0.14418603, -6.69058943]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.685640335083008, + 'FR_Wheel_Angle': 41.51594161987305, + 'Location': array([ -2.42647171, -19.90997124, 0.17041914]), + 'Rotation': array([ 0.042716 , 25.86001396, 0.54051256]), + 'Velocity': array([-0.58202469, -0.32383963, 0.00088677]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.3643798828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.68292236, -1764.26806641, 16.44140625]), + 'frame': 8974, + 'frame_number': 8974, + 'framesequence': 8972, + 'gaze_dir': array([ 0.98058069, -0.09317788, 0.1725672 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09317788, 0.1725672 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09317788, 0.1725672 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11008637398481369, + 'throttle_input': 0.0, + 'timestamp': 40.08893276005983, + 'timestamp_carla': 40088, + 'timestamp_device': 39765, + 'timestamp_stream': 40.08893276005983, + 'transform': [array([-0.19625892, -0.15514281, 0.03604857]), + array([ 0.43194798, -0.29231459, 0.38623983])]} +---------------------- +{'AngularVelocity': array([-0.22759268, -0.13820183, -6.81142139]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.677324295043945, + 'FR_Wheel_Angle': 41.502647399902344, + 'Location': array([ -2.45677614, -19.92242432, 0.17045538]), + 'Rotation': array([ 0.04251109, 25.53027344, 0.53861243]), + 'Velocity': array([-0.56854343, -0.33607185, 0.00082364]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.367919921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.87902832, -1765.28283691, 16.44165039]), + 'frame': 8975, + 'frame_number': 8975, + 'framesequence': 8973, + 'gaze_dir': array([ 0.98058069, -0.09386703, 0.17219332]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09386703, 0.17219332]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09386703, 0.17219332]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11091037839651108, + 'throttle_input': 0.0, + 'timestamp': 40.092772260308266, + 'timestamp_carla': 40092, + 'timestamp_device': 39769, + 'timestamp_stream': 40.092772260308266, + 'transform': [array([-0.19794975, -0.15552978, 0.03580767]), + array([ 0.43296567, -0.29682338, 0.38693532])]} +---------------------- +{'AngularVelocity': array([-0.22769745, -0.14112213, -6.90324354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69148063659668, + 'FR_Wheel_Angle': 41.52311325073242, + 'Location': array([ -2.48599792, -19.93399048, 0.17048441]), + 'Rotation': array([ 0.04277747, 25.2162075 , 0.54066288]), + 'Velocity': array([-0.55749983, -0.34643871, 0.00092886]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.3775634765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.84579468, -1766.18432617, 16.44152832]), + 'frame': 8976, + 'frame_number': 8976, + 'framesequence': 8974, + 'gaze_dir': array([ 0.98058069, -0.09455533, 0.17181632]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09455533, 0.17181632]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09455533, 0.17181632]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11167943477630615, + 'throttle_input': 0.0, + 'timestamp': 40.09673035889864, + 'timestamp_carla': 40096, + 'timestamp_device': 39773, + 'timestamp_stream': 40.09673035889864, + 'transform': [array([-0.19933586, -0.15615845, 0.03534 ]), + array([ 0.43481666, -0.30147365, 0.38829228])]} +---------------------- +{'AngularVelocity': array([-0.17955522, -0.10553662, -6.93046904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.686689376831055, + 'FR_Wheel_Angle': 41.51565933227539, + 'Location': array([ -2.51616669, -19.94656754, 0.17052224]), + 'Rotation': array([ 0.04227887, 24.8812294 , 0.53476614]), + 'Velocity': array([-0.5733732 , -0.33868763, 0.00084928]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.88568115, -1767.11608887, 16.44213867]), + 'frame': 8977, + 'frame_number': 8977, + 'framesequence': 8975, + 'gaze_dir': array([ 0.98058069, -0.09524145, 0.17143694]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09524145, 0.17143694]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09524145, 0.17143694]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1124851256608963, + 'throttle_input': 0.0, + 'timestamp': 40.10043915733695, + 'timestamp_carla': 40100, + 'timestamp_device': 39777, + 'timestamp_stream': 40.10043915733695, + 'transform': [array([-0.20032966, -0.15693848, 0.03477371]), + array([ 0.43701598, -0.30587232, 0.38994005])]} +---------------------- +{'AngularVelocity': array([-0.21705522, -0.12550621, -6.97953415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68421745300293, + 'FR_Wheel_Angle': 41.511070251464844, + 'Location': array([ -2.54600787, -19.9585743 , 0.17055704]), + 'Rotation': array([ 0.04186906, 24.55362129, 0.53108174]), + 'Velocity': array([-0.58094162, -0.33634546, 0.00064368]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.4031982421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.92626953, -1768.0534668 , 16.44250488]), + 'frame': 8978, + 'frame_number': 8978, + 'framesequence': 8976, + 'gaze_dir': array([ 0.98058069, -0.0957557 , 0.17115024]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0957557 , 0.17115024]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0957557 , 0.17115024]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1128513440489769, + 'throttle_input': 0.0, + 'timestamp': 40.10387045890093, + 'timestamp_carla': 40103, + 'timestamp_device': 39780, + 'timestamp_stream': 40.10387045890093, + 'transform': [array([-0.20099273, -0.15779907, 0.03419992]), + array([ 0.43924946, -0.31002828, 0.39161155])]} +---------------------- +{'AngularVelocity': array([-0.2630201 , -0.14755636, -6.96064758]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67377281188965, + 'FR_Wheel_Angle': 41.4977912902832, + 'Location': array([ -2.5746901 , -19.97005272, 0.17059 ]), + 'Rotation': array([ 0.04142509, 24.23710251, 0.52674419]), + 'Velocity': array([-0.617356 , -0.31304684, 0.00064498]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.4146728515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.92834473, -1768.78991699, 16.44250488]), + 'frame': 8979, + 'frame_number': 8979, + 'framesequence': 8977, + 'gaze_dir': array([ 0.98058069, -0.09643916, 0.17076606]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09643916, 0.17076606]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09643916, 0.17076606]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11356548219919205, + 'throttle_input': 0.0, + 'timestamp': 40.10779415816069, + 'timestamp_carla': 40107, + 'timestamp_device': 39784, + 'timestamp_stream': 40.10779415816069, + 'transform': [array([-0.20146865, -0.15893799, 0.03354368]), + array([ 0.44176978, -0.31488582, 0.39352262])]} +---------------------- +{'AngularVelocity': array([-0.24274085, -0.14147905, -7.11494017]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68386459350586, + 'FR_Wheel_Angle': 41.510826110839844, + 'Location': array([ -2.60578322, -19.98226166, 0.17062174]), + 'Rotation': array([ 0.0416983 , 23.89759064, 0.52921319]), + 'Velocity': array([-0.57966363, -0.34308434, 0.00089381]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.43017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.06393433, -1769.76428223, 16.44287109]), + 'frame': 8980, + 'frame_number': 8980, + 'framesequence': 8978, + 'gaze_dir': array([ 0.98058069, -0.0969514 , 0.17047577]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0969514 , 0.17047577]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0969514 , 0.17047577]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11429792642593384, + 'throttle_input': 0.0, + 'timestamp': 40.111216858029366, + 'timestamp_carla': 40111, + 'timestamp_device': 39787, + 'timestamp_stream': 40.111216858029366, + 'transform': [array([-0.20169953, -0.1600244 , 0.03304514]), + array([ 0.44373006, -0.31918338, 0.39497441])]} +---------------------- +{'AngularVelocity': array([-0.18941905, -0.10725466, -7.17383528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.682605743408203, + 'FR_Wheel_Angle': 41.507205963134766, + 'Location': array([ -2.63662505, -19.99473381, 0.17065786]), + 'Rotation': array([ 0.04143193, 23.55302048, 0.52554828]), + 'Velocity': array([-5.82852781e-01, -3.43998283e-01, 2.47244840e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.4405517578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.08758545, -1770.53149414, 16.4432373 ]), + 'frame': 8981, + 'frame_number': 8981, + 'framesequence': 8979, + 'gaze_dir': array([ 0.98058069, -0.09763215, 0.1700868 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09763215, 0.1700868 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09763215, 0.1700868 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11503037065267563, + 'throttle_input': 0.0, + 'timestamp': 40.11509095877409, + 'timestamp_carla': 40114, + 'timestamp_device': 39791, + 'timestamp_stream': 40.11509095877409, + 'transform': [array([-0.2017623 , -0.16134644, 0.0326202 ]), + array([ 0.44543758, -0.3241725 , 0.39620918])]} +---------------------- +{'AngularVelocity': array([-0.23773012, -0.12759843, -7.15108967]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67152976989746, + 'FR_Wheel_Angle': 41.492332458496094, + 'Location': array([ -2.66579318, -20.00634766, 0.17069231]), + 'Rotation': array([ 0.04085136, 23.22691154, 0.51982599]), + 'Velocity': array([-0.62094945, -0.31907189, 0.0006802 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.455322265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.25 , -1771.52612305, 16.44311523]), + 'frame': 8982, + 'frame_number': 8982, + 'framesequence': 8980, + 'gaze_dir': array([ 0.98058057, -0.09831198, 0.16969475]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09831198, 0.16969475]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09831198, 0.16969475]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11583605408668518, + 'throttle_input': 0.0, + 'timestamp': 40.11865985766053, + 'timestamp_carla': 40118, + 'timestamp_device': 39795, + 'timestamp_stream': 40.11865985766053, + 'transform': [array([-0.2016954 , -0.16262084, 0.03239014]), + array([ 0.44642797, -0.32881457, 0.3968766 ])]} +---------------------- +{'AngularVelocity': array([-0.26898614, -0.14534678, -7.233006 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.673336029052734, + 'FR_Wheel_Angle': 41.494117736816406, + 'Location': array([ -2.69647169, -20.01841164, 0.1707205 ]), + 'Rotation': array([ 0.04069427, 22.88539696, 0.51838923]), + 'Velocity': array([-6.13202751e-01, -3.27847421e-01, -4.61692805e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.468994140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.40432739, -1772.54736328, 16.44335938]), + 'frame': 8983, + 'frame_number': 8983, + 'framesequence': 8981, + 'gaze_dir': array([ 0.98058069, -0.09899025, 0.16929999]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09899025, 0.16929999]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09899025, 0.16929999]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11620228737592697, + 'throttle_input': 0.0, + 'timestamp': 40.12228985875845, + 'timestamp_carla': 40122, + 'timestamp_device': 39799, + 'timestamp_stream': 40.12228985875845, + 'transform': [array([-0.20152298, -0.16395508, 0.03235248]), + array([ 0.44674215, -0.33359766, 0.39698198])]} +---------------------- +{'AngularVelocity': array([-0.17842793, -0.09928383, -7.38450384]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.682235717773438, + 'FR_Wheel_Angle': 41.505706787109375, + 'Location': array([ -2.72883725, -20.03128624, 0.17075193]), + 'Rotation': array([ 0.04072842, 22.52209854, 0.51810044]), + 'Velocity': array([-5.81175685e-01, -3.54352474e-01, -1.89676284e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.478759765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.56732178, -1773.55517578, 16.44396973]), + 'frame': 8984, + 'frame_number': 8984, + 'framesequence': 8982, + 'gaze_dir': array([ 0.98058069, -0.09949742, 0.16900243]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09949742, 0.16900243]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09949742, 0.16900243]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11702627688646317, + 'throttle_input': 0.0, + 'timestamp': 40.12593195959926, + 'timestamp_carla': 40125, + 'timestamp_device': 39802, + 'timestamp_stream': 40.12593195959926, + 'transform': [array([-0.20127617, -0.16531494, 0.0325167 ]), + array([ 0.44630504, -0.3384369 , 0.39649838])]} +---------------------- +{'AngularVelocity': array([-0.19469579, -0.10100216, -7.37743807]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.673059463500977, + 'FR_Wheel_Angle': 41.49317932128906, + 'Location': array([ -2.75918055, -20.04325485, 0.17079282]), + 'Rotation': array([ 0.04010687, 22.17899323, 0.51172572]), + 'Velocity': array([-0.61198181, -0.33468089, 0.00085213]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.4864501953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.66619873, -1774.3626709 , 16.44396973]), + 'frame': 8985, + 'frame_number': 8985, + 'framesequence': 8983, + 'gaze_dir': array([ 0.98058057, -0.1001729 , 0.16860291]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1001729 , 0.16860291]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1001729 , 0.16860291]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11779534816741943, + 'throttle_input': 0.0, + 'timestamp': 40.12996115908027, + 'timestamp_carla': 40129, + 'timestamp_device': 39806, + 'timestamp_stream': 40.12996115908027, + 'transform': [array([-0.20093673, -0.16683349, 0.0329547 ]), + array([ 0.44491848, -0.34380853, 0.39521098])]} +---------------------- +{'AngularVelocity': array([-0.21452759, -0.11087897, -7.45326328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67330551147461, + 'FR_Wheel_Angle': 41.492218017578125, + 'Location': array([ -2.79064012, -20.05552292, 0.17083433]), + 'Rotation': array([ 0.03971072, 21.82420731, 0.50824249]), + 'Velocity': array([-0.61013764, -0.33916444, 0.0009795 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.495361328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.85247803, -1775.39648438, 16.44421387]), + 'frame': 8986, + 'frame_number': 8986, + 'framesequence': 8984, + 'gaze_dir': array([ 0.98058057, -0.10084614, 0.16820109]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10084614, 0.16820109]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10084614, 0.16820109]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11858272552490234, + 'throttle_input': 0.0, + 'timestamp': 40.133876759558916, + 'timestamp_carla': 40133, + 'timestamp_device': 39810, + 'timestamp_stream': 40.133876759558916, + 'transform': [array([-0.20290565, -0.16696776, 0.03301086]), + array([ 0.44485703, -0.34884334, 0.39503908])]} +---------------------- +{'AngularVelocity': array([-0.2557663 , -0.12878612, -7.45590687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.664979934692383, + 'FR_Wheel_Angle': 41.47907638549805, + 'Location': array([ -2.82064533, -20.06708527, 0.1708716 ]), + 'Rotation': array([ 0.03929408, 21.48512268, 0.50428748]), + 'Velocity': array([-6.37919128e-01, -3.20722789e-01, 5.15060441e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.499755859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.01229858, -1776.43811035, 16.44396973]), + 'frame': 8987, + 'frame_number': 8987, + 'framesequence': 8985, + 'gaze_dir': array([ 0.98058069, -0.10151842, 0.16779621]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10151842, 0.16779621]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10151842, 0.16779621]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11931516975164413, + 'throttle_input': 0.0, + 'timestamp': 40.13752285763621, + 'timestamp_carla': 40137, + 'timestamp_device': 39814, + 'timestamp_stream': 40.13752285763621, + 'transform': [array([-0.20445029, -0.16730224, 0.03282776]), + array([ 0.44567665, -0.35343868, 0.39556646])]} +---------------------- +{'AngularVelocity': array([-0.18239486, -0.09683839, -7.62435961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.677064895629883, + 'FR_Wheel_Angle': 41.49724578857422, + 'Location': array([ -2.85370541, -20.07981682, 0.17090498]), + 'Rotation': array([ 0.03947849, 21.11212921, 0.50574797]), + 'Velocity': array([-0.59593636, -0.35584545, 0.00066221]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.5086669921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.96121216, -1777.35205078, 16.44445801]), + 'frame': 8988, + 'frame_number': 8988, + 'framesequence': 8986, + 'gaze_dir': array([ 0.98058069, -0.10218842, 0.16738902]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10218842, 0.16738902]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10218842, 0.16738902]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12002930790185928, + 'throttle_input': 0.0, + 'timestamp': 40.14153655990958, + 'timestamp_carla': 40141, + 'timestamp_device': 39818, + 'timestamp_stream': 40.14153655990958, + 'transform': [array([-0.2057872 , -0.16790771, 0.03239613]), + array([ 0.44740468, -0.35847205, 0.39681914])]} +---------------------- +{'AngularVelocity': array([-0.17843112, -0.08759972, -7.62516117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.668838500976562, + 'FR_Wheel_Angle': 41.485504150390625, + 'Location': array([ -2.88501644, -20.09200287, 0.17094831]), + 'Rotation': array([ 0.03884329, 20.7532177 , 0.49896982]), + 'Velocity': array([-0.62295598, -0.33842966, 0.00085698]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.51904296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.95535278, -1778.27709961, 16.44506836]), + 'frame': 8989, + 'frame_number': 8989, + 'framesequence': 8987, + 'gaze_dir': array([ 0.98058069, -0.10285742, 0.16697876]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10285742, 0.16697876]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10285742, 0.16697876]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12061525881290436, + 'throttle_input': 0.0, + 'timestamp': 40.14545875787735, + 'timestamp_carla': 40145, + 'timestamp_device': 39822, + 'timestamp_stream': 40.14545875787735, + 'transform': [array([-0.20674148, -0.16871338, 0.0318257 ]), + array([ 0.44961765, -0.3634645 , 0.39847854])]} +---------------------- +{'AngularVelocity': array([-0.24385503, -0.11596752, -7.63204098]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.660120010375977, + 'FR_Wheel_Angle': 41.47251510620117, + 'Location': array([ -2.91554856, -20.10363197, 0.17098364]), + 'Rotation': array([ 0.03825589, 20.40478516, 0.49365303]), + 'Velocity': array([-0.65170777, -0.31858981, 0.00068328]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.5318603515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.95162964, -1779.23388672, 16.44555664]), + 'frame': 8990, + 'frame_number': 8990, + 'framesequence': 8988, + 'gaze_dir': array([ 0.98058069, -0.10352415, 0.16656624]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10352415, 0.16656624]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10352415, 0.16656624]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12123783677816391, + 'throttle_input': 0.0, + 'timestamp': 40.14983945712447, + 'timestamp_carla': 40149, + 'timestamp_device': 39826, + 'timestamp_stream': 40.14983945712447, + 'transform': [array([-0.20740181, -0.16983519, 0.03110849]), + array([ 0.45238391, -0.36915347, 0.40056252])]} +---------------------- +{'AngularVelocity': array([-0.24152508, -0.11346256, -7.71124887]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.64862823486328, + 'FR_Wheel_Angle': 41.45545196533203, + 'Location': array([ -2.94834733, -20.11638451, 0.17101385]), + 'Rotation': array([ 0.03775045, 20.0263176 , 0.489043 ]), + 'Velocity': array([-0.64838141, -0.32446793, 0.00083725]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.5460205078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.98297119, -1780.20703125, 16.44580078]), + 'frame': 8991, + 'frame_number': 8991, + 'framesequence': 8989, + 'gaze_dir': array([ 0.98058069, -0.10418985, 0.16615063]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10418985, 0.16615063]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10418985, 0.16615063]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12195196747779846, + 'throttle_input': 0.0, + 'timestamp': 40.15386025980115, + 'timestamp_carla': 40153, + 'timestamp_device': 39830, + 'timestamp_stream': 40.15386025980115, + 'transform': [array([-0.20770958, -0.17102417, 0.03048068]), + array([ 0.45480177, -0.37450305, 0.40239146])]} +---------------------- +{'AngularVelocity': array([-0.27103594, -0.13416618, -7.8213501 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66649627685547, + 'FR_Wheel_Angle': 41.480045318603516, + 'Location': array([ -2.97923064, -20.12731361, 0.1710465 ]), + 'Rotation': array([ 0.03825589, 19.68153954, 0.493698 ]), + 'Velocity': array([-0.62904561, -0.34256703, 0.00095935]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.5626220703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.02380371, -1781.2253418 , 16.44604492]), + 'frame': 8992, + 'frame_number': 8992, + 'framesequence': 8990, + 'gaze_dir': array([ 0.98058069, -0.10501947, 0.16562749]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10501947, 0.16562749]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10501947, 0.16562749]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12266610562801361, + 'throttle_input': 0.0, + 'timestamp': 40.15896765887737, + 'timestamp_carla': 40158, + 'timestamp_device': 39835, + 'timestamp_stream': 40.15896765887737, + 'transform': [array([-0.20771743, -0.17271972, 0.0298715 ]), + array([ 0.45718551, -0.38146141, 0.40415451])]} +---------------------- +{'AngularVelocity': array([-0.14935932, -0.07391871, -7.90374422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66881561279297, + 'FR_Wheel_Angle': 41.4860954284668, + 'Location': array([ -3.01242757, -20.13991928, 0.17108133]), + 'Rotation': array([ 0.03820125, 19.29864502, 0.49142045]), + 'Velocity': array([-0.62106115, -0.35203648, 0.0008116 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.57861328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.16043091, -1782.45117188, 16.44592285]), + 'frame': 8993, + 'frame_number': 8993, + 'framesequence': 8991, + 'gaze_dir': array([ 0.98058069, -0.10568078, 0.16520633]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10568078, 0.16520633]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10568078, 0.16520633]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12363658845424652, + 'throttle_input': 0.0, + 'timestamp': 40.16274346038699, + 'timestamp_carla': 40162, + 'timestamp_device': 39839, + 'timestamp_stream': 40.16274346038699, + 'transform': [array([-0.20756888, -0.17404297, 0.02959696]), + array([ 0.45833299, -0.38667598, 0.40495411])]} +---------------------- +{'AngularVelocity': array([-0.16453272, -0.06393152, -7.78270483]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.641414642333984, + 'FR_Wheel_Angle': 41.44481658935547, + 'Location': array([ -3.04247379, -20.15184593, 0.17112245]), + 'Rotation': array([ 0.03663713, 18.94160843, 0.47602114]), + 'Velocity': array([-0.71156973, -0.27897668, 0.00073803]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.5955810546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.23077393, -1783.54516602, 16.44641113]), + 'frame': 8994, + 'frame_number': 8994, + 'framesequence': 8992, + 'gaze_dir': array([ 0.98058069, -0.10634103, 0.16478212]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10634103, 0.16478212]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10634103, 0.16478212]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12425916641950607, + 'throttle_input': 0.0, + 'timestamp': 40.16704525798559, + 'timestamp_carla': 40166, + 'timestamp_device': 39843, + 'timestamp_stream': 40.16704525798559, + 'transform': [array([-0.2072483 , -0.17560913, 0.02955269]), + array([ 0.45866084, -0.3927055 , 0.40507606])]} +---------------------- +{'AngularVelocity': array([-0.31331033, -0.14307204, -7.93507338]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.655553817749023, + 'FR_Wheel_Angle': 41.46318817138672, + 'Location': array([ -3.07470083, -20.16326523, 0.17113961]), + 'Rotation': array([ 0.03693083, 18.57933235, 0.48058301]), + 'Velocity': array([-0.66347253, -0.32381508, 0.00126258]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.608154296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.3550415 , -1784.58105469, 16.44677734]), + 'frame': 8995, + 'frame_number': 8995, + 'framesequence': 8993, + 'gaze_dir': array([ 0.98058069, -0.10716379, 0.16424824]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10716379, 0.16424824]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10716379, 0.16424824]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12495498359203339, + 'throttle_input': 0.0, + 'timestamp': 40.17138025909662, + 'timestamp_carla': 40171, + 'timestamp_device': 39848, + 'timestamp_stream': 40.17138025909662, + 'transform': [array([-0.20682631, -0.17721923, 0.02980009]), + array([ 0.45793682, -0.39880359, 0.40434757])]} +---------------------- +{'AngularVelocity': array([-0.23886374, -0.10427629, -7.97800207]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.649812698364258, + 'FR_Wheel_Angle': 41.454097747802734, + 'Location': array([ -3.10733962, -20.17541504, 0.17118898]), + 'Rotation': array([ 0.03657566, 18.19953728, 0.47584 ]), + 'Velocity': array([-0.68190134, -0.31082109, 0.00083028]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.6182861328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.52111816, -1785.85876465, 16.44702148]), + 'frame': 8996, + 'frame_number': 8996, + 'framesequence': 8994, + 'gaze_dir': array([ 0.98058069, -0.10781955, 0.16381851]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10781955, 0.16381851]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10781955, 0.16381851]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12557756900787354, + 'throttle_input': 0.0, + 'timestamp': 40.17585336044431, + 'timestamp_carla': 40175, + 'timestamp_device': 39852, + 'timestamp_stream': 40.17585336044431, + 'transform': [array([-0.20631035, -0.17889769, 0.0303676 ]), + array([ 0.45605853, -0.40513149, 0.40268421])]} +---------------------- +{'AngularVelocity': array([-0.23219851, -0.10439575, -8.10255432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.647449493408203, + 'FR_Wheel_Angle': 41.45037078857422, + 'Location': array([ -3.14059711, -20.18739319, 0.17121656]), + 'Rotation': array([ 0.03673276, 17.81705856, 0.47688127]), + 'Velocity': array([-0.65542823, -0.33668903, 0.00113579]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.6239013671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.63037109, -1786.92602539, 16.4473877 ]), + 'frame': 8997, + 'frame_number': 8997, + 'framesequence': 8995, + 'gaze_dir': array([ 0.98058069, -0.10863747, 0.16327724]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10863747, 0.16327724]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10863747, 0.16327724]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12618184089660645, + 'throttle_input': 0.0, + 'timestamp': 40.18043975904584, + 'timestamp_carla': 40180, + 'timestamp_device': 39857, + 'timestamp_stream': 40.18043975904584, + 'transform': [array([-0.20572829, -0.18062012, 0.03126053]), + array([ 0.45298496, -0.41161734, 0.40007025])]} +---------------------- +{'AngularVelocity': array([ 1.37419426, 0.15966162, -6.31024599]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.712661743164062, + 'FR_Wheel_Angle': 41.56889343261719, + 'Location': array([ -3.17195082, -20.19881439, 0.17111836]), + 'Rotation': array([ 0.03805098, 17.45921326, 0.46833265]), + 'Velocity': array([-0.51502651, -0.37801853, -0.02246565]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.6287841796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.80474854, -1788.22705078, 16.44750977]), + 'frame': 8998, + 'frame_number': 8998, + 'framesequence': 8996, + 'gaze_dir': array([ 0.98058057, -0.10945266, 0.1627319 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10945266, 0.1627319 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10945266, 0.1627319 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12711569666862488, + 'throttle_input': 0.0, + 'timestamp': 40.185134559869766, + 'timestamp_carla': 40185, + 'timestamp_device': 39862, + 'timestamp_stream': 40.185134559869766, + 'transform': [array([-0.20790474, -0.1808203 , 0.03160254]), + array([ 0.45192626, -0.41800463, 0.39905924])]} +---------------------- +{'AngularVelocity': array([ 2.44647408, -0.1200407 , -5.1937561 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.787004470825195, + 'FR_Wheel_Angle': 41.676856994628906, + 'Location': array([ -3.19382143, -20.21187401, 0.16884568]), + 'Rotation': array([ 0.07605416, 17.21469879, 0.3464891 ]), + 'Velocity': array([-0.36750495, -0.29658908, -0.04543327]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.6318359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.98852539, -1789.54846191, 16.44787598]), + 'frame': 8999, + 'frame_number': 8999, + 'framesequence': 8997, + 'gaze_dir': array([ 0.98058069, -0.11010236, 0.16229305]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11010236, 0.16229305]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11010236, 0.16229305]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1277199685573578, + 'throttle_input': 0.0, + 'timestamp': 40.18942905962467, + 'timestamp_carla': 40189, + 'timestamp_device': 39866, + 'timestamp_stream': 40.18942905962467, + 'transform': [array([-0.20949036, -0.18129273, 0.03155664]), + array([ 0.45221996, -0.42372686, 0.39918807])]} +---------------------- +{'AngularVelocity': array([ 2.03273535, -0.098126 , -5.17101526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.782854080200195, + 'FR_Wheel_Angle': 41.67160415649414, + 'Location': array([ -3.21381378, -20.22290421, 0.16654813]), + 'Rotation': array([ 0.11412562, 17.01006126, 0.22701587]), + 'Velocity': array([-0.37781459, -0.29663956, -0.03895039]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.6356201171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.81219482, -1790.47644043, 16.44836426]), + 'frame': 9000, + 'frame_number': 9000, + 'framesequence': 8998, + 'gaze_dir': array([ 0.98058057, -0.1107509 , 0.16185115]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1107509 , 0.16185115]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1107509 , 0.16185115]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12828761339187622, + 'throttle_input': 0.0, + 'timestamp': 40.19352265819907, + 'timestamp_carla': 40193, + 'timestamp_device': 39870, + 'timestamp_stream': 40.19352265819907, + 'transform': [array([-0.21062049, -0.18198608, 0.03127187]), + array([ 0.45339477, -0.42918038, 0.40001598])]} +---------------------- +{'AngularVelocity': array([ 1.9153111 , -0.10705432, -4.82604647]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77707290649414, + 'FR_Wheel_Angle': 41.659610748291016, + 'Location': array([ -3.23270965, -20.23342133, 0.16459982]), + 'Rotation': array([ 0.14353642, 16.81751442, 0.13058351]), + 'Velocity': array([-0.39388391, -0.29001734, -0.04028663]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.645263671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.72537231, -1791.44238281, 16.44885254]), + 'frame': 9001, + 'frame_number': 9001, + 'framesequence': 8999, + 'gaze_dir': array([ 0.98058069, -0.11139708, 0.1614071 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11139708, 0.1614071 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11139708, 0.1614071 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12880033254623413, + 'throttle_input': 0.0, + 'timestamp': 40.19745825976133, + 'timestamp_carla': 40197, + 'timestamp_device': 39874, + 'timestamp_stream': 40.19745825976133, + 'transform': [array([-0.21135277, -0.18285277, 0.03085819]), + array([ 0.45506817, -0.43451795, 0.40122077])]} +---------------------- +{'AngularVelocity': array([ 1.42606127, -0.0448219 , -5.17468023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.786956787109375, + 'FR_Wheel_Angle': 41.67799377441406, + 'Location': array([ -3.25281954, -20.24470329, 0.16260511]), + 'Rotation': array([ 0.17003755, 16.60940742, 0.03979452]), + 'Velocity': array([-0.37022999, -0.29424575, -0.0349292 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.654541015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.67102051, -1792.41308594, 16.44970703]), + 'frame': 9002, + 'frame_number': 9002, + 'framesequence': 9000, + 'gaze_dir': array([ 0.98058069, -0.11204206, 0.16096005]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11204206, 0.16096005]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11204206, 0.16096005]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1292947232723236, + 'throttle_input': 0.0, + 'timestamp': 40.20117945969105, + 'timestamp_carla': 40201, + 'timestamp_device': 39878, + 'timestamp_stream': 40.20117945969105, + 'transform': [array([-0.21175575, -0.183833 , 0.03040682]), + array([ 0.45683035, -0.43966007, 0.4025386 ])]} +---------------------- +{'AngularVelocity': array([ 1.28406715, -0.02679247, -5.02437162]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.781469345092773, + 'FR_Wheel_Angle': 41.67060852050781, + 'Location': array([ -3.27144551, -20.25521278, 0.16093382]), + 'Rotation': array([ 0.18774822, 16.41547585, -0.03128051]), + 'Velocity': array([-0.3846342 , -0.29074937, -0.03554289]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.669921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.67684937, -1793.41821289, 16.44934082]), + 'frame': 9003, + 'frame_number': 9003, + 'framesequence': 9001, + 'gaze_dir': array([ 0.98058069, -0.11268526, 0.16051041]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11268526, 0.16051041]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11268526, 0.16051041]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12986236810684204, + 'throttle_input': 0.0, + 'timestamp': 40.20611355826259, + 'timestamp_carla': 40206, + 'timestamp_device': 39882, + 'timestamp_stream': 40.20611355826259, + 'transform': [array([-0.21187423, -0.18534912, 0.02985521]), + array([ 0.459016 , -0.44663346, 0.40413842])]} +---------------------- +{'AngularVelocity': array([ 0.88165826, 0.02498775, -5.30919743]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78856086730957, + 'FR_Wheel_Angle': 41.68253707885742, + 'Location': array([ -3.29139543, -20.26661491, 0.15920877]), + 'Rotation': array([ 0.20302737, 16.20232201, -0.09808349]), + 'Velocity': array([-0.36797786, -0.29368109, -0.02966171]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.6834716796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.71075439, -1794.43078613, 16.45007324]), + 'frame': 9004, + 'frame_number': 9004, + 'framesequence': 9002, + 'gaze_dir': array([ 0.98058069, -0.11348597, 0.15994529]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11348597, 0.15994529]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11348597, 0.15994529]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13037507236003876, + 'throttle_input': 0.0, + 'timestamp': 40.21044605970383, + 'timestamp_carla': 40210, + 'timestamp_device': 39887, + 'timestamp_stream': 40.21044605970383, + 'transform': [array([-0.21171646, -0.18680054, 0.02952387]), + array([ 0.46039569, -0.45289156, 0.40510112])]} +---------------------- +{'AngularVelocity': array([ 1.20688558, -0.02469323, -4.43865824]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.765335083007812, + 'FR_Wheel_Angle': 41.64908981323242, + 'Location': array([ -3.30864644, -20.27663422, 0.15798311]), + 'Rotation': array([ 0.20976876, 16.01503563, -0.14266966]), + 'Velocity': array([-0.42647538, -0.27973744, -0.03893207]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.699951171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.76654053, -1795.7265625 , 16.45043945]), + 'frame': 9005, + 'frame_number': 9005, + 'framesequence': 9003, + 'gaze_dir': array([ 0.98058069, -0.11444367, 0.15926144]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11444367, 0.15926144]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11444367, 0.15926144]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1313638687133789, + 'throttle_input': 0.0, + 'timestamp': 40.2166610583663, + 'timestamp_carla': 40216, + 'timestamp_device': 39893, + 'timestamp_stream': 40.2166610583663, + 'transform': [array([-0.2111232 , -0.18903686, 0.02951217]), + array([ 0.46064842, -0.4620468 , 0.4051083 ])]} +---------------------- +{'AngularVelocity': array([ 0.65316099, 0.03824728, -5.34180164]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78107261657715, + 'FR_Wheel_Angle': 41.67047119140625, + 'Location': array([ -3.32963014, -20.28872299, 0.15630628]), + 'Rotation': array([ 0.22043751, 15.78404236, -0.19805904]), + 'Velocity': array([-0.37060139, -0.29100934, -0.02745027]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.7171630859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.92675781, -1797.23876953, 16.45080566]), + 'frame': 9006, + 'frame_number': 9006, + 'framesequence': 9004, + 'gaze_dir': array([ 0.98058057, -0.11508004, 0.1588022 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11508004, 0.1588022 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11508004, 0.1588022 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.132151260972023, + 'throttle_input': 0.0, + 'timestamp': 40.22059125825763, + 'timestamp_carla': 40220, + 'timestamp_device': 39897, + 'timestamp_stream': 40.22059125825763, + 'transform': [array([-0.21065216, -0.19048339, 0.02971897]), + array([ 0.46002689, -0.46787417, 0.40450722])]} +---------------------- +{'AngularVelocity': array([ 0.36336064, 0.06155776, -5.49408627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.786914825439453, + 'FR_Wheel_Angle': 41.678131103515625, + 'Location': array([ -3.34872818, -20.29961967, 0.15501791]), + 'Rotation': array([ 0.22565578, 15.57543659, -0.24023439]), + 'Velocity': array([-0.37346607, -0.29513785, -0.02175387]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.72509765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.91815186, -1798.40026855, 16.45117188]), + 'frame': 9007, + 'frame_number': 9007, + 'framesequence': 9005, + 'gaze_dir': array([ 0.98058069, -0.115714 , 0.15834087]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.115714 , 0.15834087]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.115714 , 0.15834087]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13249915838241577, + 'throttle_input': 0.0, + 'timestamp': 40.22464255988598, + 'timestamp_carla': 40224, + 'timestamp_device': 39901, + 'timestamp_stream': 40.22464255988598, + 'transform': [array([-0.21010253, -0.1919934 , 0.03018978]), + array([ 0.45849007, -0.47388902, 0.40313292])]} +---------------------- +{'AngularVelocity': array([ 0.18867129, 0.08429603, -5.5645752 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.788387298583984, + 'FR_Wheel_Angle': 41.679931640625, + 'Location': array([ -3.36910939, -20.31155968, 0.15383482]), + 'Rotation': array([ 0.22741796, 15.34178257, -0.27365109]), + 'Velocity': array([-0.37118429, -0.29394162, -0.01899971]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.73291015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 290.00778198, -1799.47277832, 16.45141602]), + 'frame': 9008, + 'frame_number': 9008, + 'framesequence': 9006, + 'gaze_dir': array([ 0.98058069, -0.11650442, 0.1577602 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11650442, 0.1577602 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11650442, 0.1577602 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13337810337543488, + 'throttle_input': 0.0, + 'timestamp': 40.22975815832615, + 'timestamp_carla': 40229, + 'timestamp_device': 39906, + 'timestamp_stream': 40.22975815832615, + 'transform': [array([-0.20932853, -0.19390625, 0.03117725]), + array([ 0.45508182, -0.48151109, 0.40024173])]} +---------------------- +{'AngularVelocity': array([ 0.31081197, 0.07600772, -5.47422171]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77861976623535, + 'FR_Wheel_Angle': 41.665287017822266, + 'Location': array([ -3.3881371 , -20.32258415, 0.15286085]), + 'Rotation': array([ 0.22668031, 15.12503815, -0.29962161]), + 'Velocity': array([-0.39491031, -0.29233539, -0.02310257]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.7388916015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 290.14144897, -1800.77246094, 16.45178223]), + 'frame': 9009, + 'frame_number': 9009, + 'framesequence': 9007, + 'gaze_dir': array([ 0.98058057, -0.11713478, 0.15729272]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11713478, 0.15729272]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11713478, 0.15729272]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1339823603630066, + 'throttle_input': 0.0, + 'timestamp': 40.23353345692158, + 'timestamp_carla': 40233, + 'timestamp_device': 39910, + 'timestamp_stream': 40.23353345692158, + 'transform': [array([-0.21106192, -0.19401123, 0.03150702]), + array([ 0.4540368 , -0.48694518, 0.39927846])]} +---------------------- +{'AngularVelocity': array([ 0.13210209, 0.0750975 , -5.72426414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77651596069336, + 'FR_Wheel_Angle': 41.66063690185547, + 'Location': array([ -3.40813446, -20.33415413, 0.15190962]), + 'Rotation': array([ 0.22465856, 14.89244938, -0.32519525]), + 'Velocity': array([-0.39878395, -0.29897353, -0.01742059]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.735107421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 290.18209839, -1801.89172363, 16.4519043 ]), + 'frame': 9010, + 'frame_number': 9010, + 'framesequence': 9008, + 'gaze_dir': array([ 0.98058069, -0.11776266, 0.15682319]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11776266, 0.15682319]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11776266, 0.15682319]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13465988636016846, + 'throttle_input': 0.0, + 'timestamp': 40.237375158816576, + 'timestamp_carla': 40237, + 'timestamp_device': 39914, + 'timestamp_stream': 40.237375158816576, + 'transform': [array([-0.21251114, -0.19435059, 0.03153976]), + array([ 0.4540163 , -0.49234846, 0.39918518])]} +---------------------- +{'AngularVelocity': array([-0.01864514, 0.06604049, -5.78806925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.779726028442383, + 'FR_Wheel_Angle': 41.66657638549805, + 'Location': array([ -3.42893577, -20.34623528, 0.15100035]), + 'Rotation': array([ 0.22311495, 14.64435005, -0.34805295]), + 'Velocity': array([-0.39408195, -0.29190937, -0.01520355]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.7391357421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 290.03973389, -1802.82287598, 16.45251465]), + 'frame': 9011, + 'frame_number': 9011, + 'framesequence': 9009, + 'gaze_dir': array([ 0.98058069, -0.11838928, 0.1563507 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11838928, 0.1563507 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11838928, 0.1563507 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1352824568748474, + 'throttle_input': 0.0, + 'timestamp': 40.24178725853562, + 'timestamp_carla': 40241, + 'timestamp_device': 39918, + 'timestamp_stream': 40.24178725853562, + 'transform': [array([-0.21373069, -0.19502684, 0.03127441]), + array([ 0.45512962, -0.49853325, 0.39995787])]} +---------------------- +{'AngularVelocity': array([ 0.20159774, 0.06466766, -5.6657176 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.775279998779297, + 'FR_Wheel_Angle': 41.654930114746094, + 'Location': array([ -3.44858289, -20.35754013, 0.15023969]), + 'Rotation': array([ 0.22017796, 14.40957928, -0.36630243]), + 'Velocity': array([-0.40495777, -0.29240307, -0.02015944]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.7471923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.92727661, -1803.77966309, 16.45288086]), + 'frame': 9012, + 'frame_number': 9012, + 'framesequence': 9010, + 'gaze_dir': array([ 0.98058069, -0.11901338, 0.15587616]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11901338, 0.15587616]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11901338, 0.15587616]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13588672876358032, + 'throttle_input': 0.0, + 'timestamp': 40.24596085771918, + 'timestamp_carla': 40245, + 'timestamp_device': 39922, + 'timestamp_stream': 40.24596085771918, + 'transform': [array([-0.21448547, -0.19589965, 0.03083887]), + array([ 0.45683718, -0.50445795, 0.40123054])]} +---------------------- +{'AngularVelocity': array([ 0.03636152, 0.07785939, -5.84654188]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77550506591797, + 'FR_Wheel_Angle': 41.65822982788086, + 'Location': array([ -3.46873307, -20.36896706, 0.1494296 ]), + 'Rotation': array([ 0.21743906, 14.16697598, -0.38589478]), + 'Velocity': array([-0.40466133, -0.29476747, -0.01543011]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.7587890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.80838013, -1804.77563477, 16.45324707]), + 'frame': 9013, + 'frame_number': 9013, + 'framesequence': 9011, + 'gaze_dir': array([ 0.98058069, -0.11963619, 0.15539867]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11963619, 0.15539867]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11963619, 0.15539867]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13639943301677704, + 'throttle_input': 0.0, + 'timestamp': 40.24959895759821, + 'timestamp_carla': 40249, + 'timestamp_device': 39926, + 'timestamp_stream': 40.24959895759821, + 'transform': [array([-0.21485519, -0.19681518, 0.03039742]), + array([ 0.45856521, -0.50972658, 0.40252241])]} +---------------------- +{'AngularVelocity': array([ 0.09387851, 0.07094153, -5.83668709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77170181274414, + 'FR_Wheel_Angle': 41.65185546875, + 'Location': array([ -3.48817801, -20.37987709, 0.14874452]), + 'Rotation': array([ 0.21414691, 13.93223763, -0.40200809]), + 'Velocity': array([-0.4147352 , -0.29257914, -0.01744451]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.769775390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.72747803, -1805.77697754, 16.45385742]), + 'frame': 9014, + 'frame_number': 9014, + 'framesequence': 9012, + 'gaze_dir': array([ 0.98058069, -0.12010159, 0.15503925]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12010159, 0.15503925]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12010159, 0.15503925]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1369853913784027, + 'throttle_input': 0.0, + 'timestamp': 40.253018356859684, + 'timestamp_carla': 40252, + 'timestamp_device': 39929, + 'timestamp_stream': 40.253018356859684, + 'transform': [array([-0.21498169, -0.1977893 , 0.0299856 ]), + array([ 0.4601908 , -0.51477742, 0.40372819])]} +---------------------- +{'AngularVelocity': array([-0.23071198, 0.09520584, -6.06658936]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77510643005371, + 'FR_Wheel_Angle': 41.655982971191406, + 'Location': array([ -3.50955009, -20.3918457 , 0.14805265]), + 'Rotation': array([ 0.20964581, 13.66891575, -0.41723633]), + 'Velocity': array([-0.40714526, -0.29540423, -0.00753837]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.7825927734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.6751709 , -1806.57519531, 16.45410156]), + 'frame': 9015, + 'frame_number': 9015, + 'framesequence': 9013, + 'gaze_dir': array([ 0.98058069, -0.12087544, 0.15443668]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12087544, 0.15443668]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12087544, 0.15443668]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13758966326713562, + 'throttle_input': 0.0, + 'timestamp': 40.25721575692296, + 'timestamp_carla': 40257, + 'timestamp_device': 39934, + 'timestamp_stream': 40.25721575692296, + 'transform': [array([-0.21486336, -0.19912353, 0.02956625]), + array([ 0.46188468, -0.52107096, 0.40495068])]} +---------------------- +{'AngularVelocity': array([-0.10591435, 0.09058418, -6.06794357]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76883888244629, + 'FR_Wheel_Angle': 41.6467399597168, + 'Location': array([ -3.52948236, -20.40289116, 0.14757116]), + 'Rotation': array([ 0.20399725, 13.42299843, -0.42721552]), + 'Velocity': array([-0.42263806, -0.29422703, -0.01232386]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.7958984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.72528076, -1807.80895996, 16.45458984]), + 'frame': 9016, + 'frame_number': 9016, + 'framesequence': 9014, + 'gaze_dir': array([ 0.98058069, -0.12149247, 0.15395175]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12149247, 0.15395175]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12149247, 0.15395175]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1382671594619751, + 'throttle_input': 0.0, + 'timestamp': 40.261329259723425, + 'timestamp_carla': 40261, + 'timestamp_device': 39938, + 'timestamp_stream': 40.261329259723425, + 'transform': [array([-0.21453674, -0.20052367, 0.02931628]), + array([ 0.46294338, -0.52735847, 0.40568131])]} +---------------------- +{'AngularVelocity': array([-0.29520577, 0.10087679, -6.20859194]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.770225524902344, + 'FR_Wheel_Angle': 41.648040771484375, + 'Location': array([ -3.55106401, -20.41480064, 0.14703314]), + 'Rotation': array([ 0.19833502, 13.15115452, -0.43707269]), + 'Velocity': array([-0.42049032, -0.29387829, -0.00588022]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.8131103515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.74414062, -1808.89208984, 16.4552002 ]), + 'frame': 9017, + 'frame_number': 9017, + 'framesequence': 9015, + 'gaze_dir': array([ 0.98058057, -0.12195352, 0.15358676]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12195352, 0.15358676]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12195352, 0.15358676]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.13888974487781525, + 'throttle_input': 0.0, + 'timestamp': 40.26482255756855, + 'timestamp_carla': 40264, + 'timestamp_device': 39941, + 'timestamp_stream': 40.26482255756855, + 'transform': [array([-0.21415024, -0.20176147, 0.02925985]), + array([ 0.46328488, -0.53273553, 0.40584844])]} +---------------------- +{'AngularVelocity': array([-0.21540548, 0.08693244, -6.24781799]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76651382446289, + 'FR_Wheel_Angle': 41.64187240600586, + 'Location': array([ -3.57167268, -20.42605209, 0.14660391]), + 'Rotation': array([ 0.19259766, 12.88971806, -0.44418326]), + 'Velocity': array([-0.43030021, -0.29202935, -0.00856325]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.8201904296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.69937134, -1809.72644043, 16.45544434]), + 'frame': 9018, + 'frame_number': 9018, + 'framesequence': 9016, + 'gaze_dir': array([ 0.98058057, -0.12256712, 0.15309754]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12256712, 0.15309754]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12256712, 0.15309754]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1396038681268692, + 'throttle_input': 0.0, + 'timestamp': 40.26846735924482, + 'timestamp_carla': 40268, + 'timestamp_device': 39945, + 'timestamp_stream': 40.26846735924482, + 'transform': [array([-0.2136557 , -0.20308715, 0.02938882]), + array([ 0.46294338, -0.53838348, 0.40547588])]} +---------------------- +{'AngularVelocity': array([-0.42288113, 0.1075162 , -6.42211199]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76384735107422, + 'FR_Wheel_Angle': 41.63637161254883, + 'Location': array([ -3.59357381, -20.43783188, 0.14622545]), + 'Rotation': array([ 0.18576747, 12.61139011, -0.45013431]), + 'Velocity': array([-0.43646875, -0.29605129, -0.00141527]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.831787109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.75918579, -1810.79162598, 16.45581055]), + 'frame': 9019, + 'frame_number': 9019, + 'framesequence': 9017, + 'gaze_dir': array([ 0.98058069, -0.12317821, 0.15260632]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12317821, 0.15260632]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12317821, 0.15260632]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1399700939655304, + 'throttle_input': 0.0, + 'timestamp': 40.27256875857711, + 'timestamp_carla': 40272, + 'timestamp_device': 39949, + 'timestamp_stream': 40.27256875857711, + 'transform': [array([-0.2130117 , -0.20459716, 0.02979301]), + array([ 0.46163198, -0.54478616, 0.40429589])]} +---------------------- +{'AngularVelocity': array([-0.32914582, 0.11820108, -6.50709867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.755722045898438, + 'FR_Wheel_Angle': 41.62058639526367, + 'Location': array([ -3.61478567, -20.44911766, 0.1460758 ]), + 'Rotation': array([ 0.17675163, 12.34122181, -0.45266724]), + 'Velocity': array([-0.45575348, -0.29696661, -0.00466694]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.8370361328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.79089355, -1811.84277344, 16.45568848]), + 'frame': 9020, + 'frame_number': 9020, + 'framesequence': 9018, + 'gaze_dir': array([ 0.98058069, -0.12393986, 0.1519884 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12393986, 0.1519884 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12393986, 0.1519884 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14105044305324554, + 'throttle_input': 0.0, + 'timestamp': 40.277945660054684, + 'timestamp_carla': 40277, + 'timestamp_device': 39954, + 'timestamp_stream': 40.277945660054684, + 'transform': [array([-0.21517783, -0.20488159, 0.02970489]), + array([ 0.4620896 , -0.55281258, 0.40453118])]} +---------------------- +{'AngularVelocity': array([-0.56180894, 0.10650824, -6.59236717]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75790023803711, + 'FR_Wheel_Angle': 41.62406921386719, + 'Location': array([ -3.63891292, -20.46196938, 0.14590456]), + 'Rotation': array([ 0.16747622, 12.02395439, -0.4520568 ]), + 'Velocity': array([-0.44593558, -0.29350749, 0.00299069]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.8428955078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.86599731, -1813.15539551, 16.45629883]), + 'frame': 9021, + 'frame_number': 9021, + 'framesequence': 9019, + 'gaze_dir': array([ 0.98058069, -0.12454648, 0.15149169]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12454648, 0.15149169]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12454648, 0.15149169]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14163640141487122, + 'throttle_input': 0.0, + 'timestamp': 40.28187955915928, + 'timestamp_carla': 40281, + 'timestamp_device': 39958, + 'timestamp_stream': 40.28187955915928, + 'transform': [array([-0.21641739, -0.20532471, 0.02940426]), + array([ 0.46332586, -0.55860376, 0.40540355])]} +---------------------- +{'AngularVelocity': array([-0.41063213, 0.1109873 , -6.61986256]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75849151611328, + 'FR_Wheel_Angle': 41.62525177001953, + 'Location': array([ -3.65990019, -20.47275925, 0.14563955]), + 'Rotation': array([ 0.16096023, 11.75259495, -0.45852652]), + 'Velocity': array([-4.52130765e-01, -2.93966472e-01, 3.14030651e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.853271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.57254028, -1814.13916016, 16.45690918]), + 'frame': 9022, + 'frame_number': 9022, + 'framesequence': 9020, + 'gaze_dir': array([ 0.98058069, -0.12515171, 0.1509921 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12515171, 0.1509921 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12515171, 0.1509921 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14224067330360413, + 'throttle_input': 0.0, + 'timestamp': 40.285378359258175, + 'timestamp_carla': 40285, + 'timestamp_device': 39962, + 'timestamp_stream': 40.285378359258175, + 'transform': [array([-0.21723892, -0.20589843, 0.02899168]), + array([ 0.46495146, -0.56374657, 0.40660641])]} +---------------------- +{'AngularVelocity': array([-0.55229026, 0.14200205, -6.77263165]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75494384765625, + 'FR_Wheel_Angle': 41.618587493896484, + 'Location': array([ -3.6835649 , -20.48484039, 0.14563593]), + 'Rotation': array([ 0.14940354, 11.44212627, -0.45800781]), + 'Velocity': array([-0.4606995 , -0.29699773, 0.00374675]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.86474609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.42376709, -1815.1151123 , 16.45739746]), + 'frame': 9023, + 'frame_number': 9023, + 'framesequence': 9021, + 'gaze_dir': array([ 0.98058069, -0.12575492, 0.15049008]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12575492, 0.15049008]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12575492, 0.15049008]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14286325871944427, + 'throttle_input': 0.0, + 'timestamp': 40.28976045921445, + 'timestamp_carla': 40289, + 'timestamp_device': 39966, + 'timestamp_stream': 40.28976045921445, + 'transform': [array([-0.21783863, -0.20686279, 0.02832436]), + array([ 0.46749911, -0.57028693, 0.40854833])]} +---------------------- +{'AngularVelocity': array([-0.25325906, 0.11517312, -6.77717161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74943733215332, + 'FR_Wheel_Angle': 41.610347747802734, + 'Location': array([ -3.70580339, -20.49598312, 0.14567728]), + 'Rotation': array([ 0.13892604, 11.14913273, -0.45547482]), + 'Velocity': array([-0.47437778, -0.29630718, -0.00591365]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.87841796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.33929443, -1816.10534668, 16.45776367]), + 'frame': 9024, + 'frame_number': 9024, + 'framesequence': 9022, + 'gaze_dir': array([ 0.98058057, -0.12635551, 0.14998613]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12635551, 0.14998613]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12635551, 0.14998613]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14354076981544495, + 'throttle_input': 0.0, + 'timestamp': 40.293879959732294, + 'timestamp_carla': 40293, + 'timestamp_device': 39970, + 'timestamp_stream': 40.293879959732294, + 'transform': [array([-0.21804759, -0.20795776, 0.02767355]), + array([ 0.46999896, -0.57656115, 0.41044435])]} +---------------------- +{'AngularVelocity': array([-0.58623016, 0.10978048, -6.98942995]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.745521545410156, + 'FR_Wheel_Angle': 41.60322189331055, + 'Location': array([ -3.73108554, -20.50850105, 0.14566614]), + 'Rotation': array([ 0.12912472, 10.81402683, -0.45297241]), + 'Velocity': array([-0.4771055 , -0.29979137, 0.00777699]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.892578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.21566772, -1817.12927246, 16.45849609]), + 'frame': 9025, + 'frame_number': 9025, + 'framesequence': 9023, + 'gaze_dir': array([ 0.98058069, -0.1269547 , 0.14947931]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1269547 , 0.14947931]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1269547 , 0.14947931]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1441633403301239, + 'throttle_input': 0.0, + 'timestamp': 40.297626458108425, + 'timestamp_carla': 40297, + 'timestamp_device': 39974, + 'timestamp_stream': 40.297626458108425, + 'transform': [array([-0.21798958, -0.20907837, 0.0271419 ]), + array([ 0.47208217, -0.58237362, 0.41199389])]} +---------------------- +{'AngularVelocity': array([-0.54065871, 0.1033353 , -7.12787724]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742952346801758, + 'FR_Wheel_Angle': 41.59840774536133, + 'Location': array([ -3.75442648, -20.51969719, 0.14574049]), + 'Rotation': array([ 0.12070309, 10.50715733, -0.45208743]), + 'Velocity': array([-0.49014339, -0.30319411, 0.00764352]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.9105224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.15661621, -1818.18566895, 16.45898438]), + 'frame': 9026, + 'frame_number': 9026, + 'framesequence': 9024, + 'gaze_dir': array([ 0.98058057, -0.12740232, 0.14909798]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12740232, 0.14909798]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12740232, 0.14909798]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14478591084480286, + 'throttle_input': 0.0, + 'timestamp': 40.30107446014881, + 'timestamp_carla': 40300, + 'timestamp_device': 39977, + 'timestamp_stream': 40.30107446014881, + 'transform': [array([-0.21775661, -0.21019043, 0.02674995]), + array([ 0.4736326 , -0.58782768, 0.41313791])]} +---------------------- +{'AngularVelocity': array([-0.48665828, 0.09575119, -7.1935668 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74102020263672, + 'FR_Wheel_Angle': 41.595001220703125, + 'Location': array([ -3.77947593, -20.53158569, 0.14595796]), + 'Rotation': array([ 0.11163261, 10.17417145, -0.4469299 ]), + 'Velocity': array([-0.4958187 , -0.30290577, 0.00656838]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.9232177734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.08740234, -1819.00256348, 16.45935059]), + 'frame': 9027, + 'frame_number': 9027, + 'framesequence': 9025, + 'gaze_dir': array([ 0.98058069, -0.12799793, 0.14858697]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12799793, 0.14858697]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12799793, 0.14858697]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.145500048995018, + 'throttle_input': 0.0, + 'timestamp': 40.30469225719571, + 'timestamp_carla': 40304, + 'timestamp_device': 39981, + 'timestamp_stream': 40.30469225719571, + 'transform': [array([-0.21736614, -0.21142334, 0.02649229]), + array([ 0.4747186 , -0.59360266, 0.41388848])]} +---------------------- +{'AngularVelocity': array([-0.11094696, 0.1089265 , -7.29903173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72925567626953, + 'FR_Wheel_Angle': 41.57841110229492, + 'Location': array([ -3.80327773, -20.54247284, 0.14633344]), + 'Rotation': array([ 0.10198155, 9.85986042, -0.43896481]), + 'Velocity': array([-0.52346069, -0.30382857, -0.00354063]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.93505859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.07086182, -1820.03845215, 16.45935059]), + 'frame': 9028, + 'frame_number': 9028, + 'framesequence': 9026, + 'gaze_dir': array([ 0.98058069, -0.12873887, 0.14794549]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12873887, 0.14794549]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12873887, 0.14794549]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14619587361812592, + 'throttle_input': 0.0, + 'timestamp': 40.308932058513165, + 'timestamp_carla': 40308, + 'timestamp_device': 39986, + 'timestamp_stream': 40.308932058513165, + 'transform': [array([-0.21675304, -0.21293335, 0.02644516]), + array([ 0.47506696, -0.600438 , 0.41402027])]} +---------------------- +{'AngularVelocity': array([-0.51714462, 0.04165338, -7.46238232]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73169708251953, + 'FR_Wheel_Angle': 41.580352783203125, + 'Location': array([ -3.83011103, -20.55465317, 0.14648332]), + 'Rotation': array([ 0.09519234, 9.50274086, -0.43515018]), + 'Velocity': array([-0.51886076, -0.30641222, 0.00833138]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.949951171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.10900879, -1821.33288574, 16.45996094]), + 'frame': 9029, + 'frame_number': 9029, + 'framesequence': 9027, + 'gaze_dir': array([ 0.98058069, -0.12932986, 0.14742914]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12932986, 0.14742914]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12932986, 0.14742914]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1469283252954483, + 'throttle_input': 0.0, + 'timestamp': 40.31343615800142, + 'timestamp_carla': 40313, + 'timestamp_device': 39990, + 'timestamp_stream': 40.31343615800142, + 'transform': [array([-0.2159743 , -0.21457519, 0.02670986]), + array([ 0.47428149, -0.60777307, 0.41324073])]} +---------------------- +{'AngularVelocity': array([-0.34233186, -0.03124886, -7.54518223]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.724336624145508, + 'FR_Wheel_Angle': 41.56804656982422, + 'Location': array([ -3.85484529, -20.56548119, 0.1468015 ]), + 'Rotation': array([ 0.08955061, 9.17553425, -0.42535394]), + 'Velocity': array([-0.5369159 , -0.3052977 , -0.00104086]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.96044921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.09744263, -1822.43383789, 16.46044922]), + 'frame': 9030, + 'frame_number': 9030, + 'framesequence': 9028, + 'gaze_dir': array([ 0.98058069, -0.12991877, 0.14691043]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12991877, 0.14691043]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12991877, 0.14691043]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14753258228302002, + 'throttle_input': 0.0, + 'timestamp': 40.31726025789976, + 'timestamp_carla': 40317, + 'timestamp_device': 39994, + 'timestamp_stream': 40.31726025789976, + 'transform': [array([-0.21525528, -0.21598755, 0.02715611]), + array([ 0.47277883, -0.6140132 , 0.4119387 ])]} +---------------------- +{'AngularVelocity': array([ 2.29180837e-03, 8.00971389e-02, -7.67648077e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.716482162475586, + 'FR_Wheel_Angle': 41.55548858642578, + 'Location': array([ -3.87936306, -20.57589149, 0.14706559]), + 'Rotation': array([ 0.08435966, 8.85225296, -0.41986081]), + 'Velocity': array([-0.55586827, -0.30544314, -0.00219565]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.963134765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.06207275, -1823.53540039, 16.46081543]), + 'frame': 9031, + 'frame_number': 9031, + 'framesequence': 9029, + 'gaze_dir': array([ 0.98058057, -0.13050504, 0.14638986]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13050504, 0.14638986]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13050504, 0.14638986]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1481185406446457, + 'throttle_input': 0.0, + 'timestamp': 40.321089658886194, + 'timestamp_carla': 40320, + 'timestamp_device': 39998, + 'timestamp_stream': 40.321089658886194, + 'transform': [array([-0.21449253, -0.21740478, 0.02783446]), + array([ 0.47045657, -0.62025881, 0.40995744])]} +---------------------- +{'AngularVelocity': array([-6.76778734e-01, -3.93342646e-03, -7.90978193e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.717056274414062, + 'FR_Wheel_Angle': 41.555328369140625, + 'Location': array([ -3.90939546, -20.58858681, 0.14750326]), + 'Rotation': array([ 0.07779585, 8.45331478, -0.40713498]), + 'Velocity': array([-0.55523682, -0.31150049, 0.01285255]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.9642333984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.05508423, -1824.60913086, 16.46105957]), + 'frame': 9032, + 'frame_number': 9032, + 'framesequence': 9030, + 'gaze_dir': array([ 0.98058057, -0.13108979, 0.14586645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13108979, 0.14586645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13108979, 0.14586645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1487228125333786, + 'throttle_input': 0.0, + 'timestamp': 40.32584885880351, + 'timestamp_carla': 40325, + 'timestamp_device': 40002, + 'timestamp_stream': 40.32584885880351, + 'transform': [array([-0.21638125, -0.2175952 , 0.0281304 ]), + array([ 0.46951401, -0.62771773, 0.40907866])]} +---------------------- +{'AngularVelocity': array([-0.53886116, 0.01673658, -8.08842468]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70769500732422, + 'FR_Wheel_Angle': 41.54095458984375, + 'Location': array([ -3.93714857, -20.59982681, 0.14814752]), + 'Rotation': array([ 0.07079491, 8.08697414, -0.38757324]), + 'Velocity': array([-0.57776815, -0.31164715, 0.00769662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.967041015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.07440186, -1825.71032715, 16.46154785]), + 'frame': 9033, + 'frame_number': 9033, + 'framesequence': 9031, + 'gaze_dir': array([ 0.98058057, -0.13167189, 0.14534123]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13167189, 0.14534123]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13167189, 0.14534123]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14930877089500427, + 'throttle_input': 0.0, + 'timestamp': 40.329554457217455, + 'timestamp_carla': 40329, + 'timestamp_device': 40006, + 'timestamp_stream': 40.329554457217455, + 'transform': [array([-0.21755072, -0.21795654, 0.02811151]), + array([ 0.46971208, -0.63341689, 0.40912706])]} +---------------------- +{'AngularVelocity': array([-0.29630908, -0.01957605, -8.14928246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70568084716797, + 'FR_Wheel_Angle': 41.53822708129883, + 'Location': array([ -3.96380949, -20.61031723, 0.14857049]), + 'Rotation': array([ 0.06597962, 7.73444796, -0.37533572]), + 'Velocity': array([-0.58404136, -0.30932367, 0.00246763]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.9678955078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.7539978 , -1826.66467285, 16.46191406]), + 'frame': 9034, + 'frame_number': 9034, + 'framesequence': 9032, + 'gaze_dir': array([ 0.98058069, -0.13225244, 0.14481318]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13225244, 0.14481318]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13225244, 0.14481318]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.149913027882576, + 'throttle_input': 0.0, + 'timestamp': 40.33344925940037, + 'timestamp_carla': 40333, + 'timestamp_device': 40010, + 'timestamp_stream': 40.33344925940037, + 'transform': [array([-0.21843189, -0.21855712, 0.0278644 ]), + array([ 0.47070929, -0.63939381, 0.40984473])]} +---------------------- +{'AngularVelocity': array([-5.70092320e-01, -7.13813584e-03, -8.31380177e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.702985763549805, + 'FR_Wheel_Angle': 41.53224182128906, + 'Location': array([ -3.99394703, -20.62190819, 0.14906427]), + 'Rotation': array([ 0.06161513, 7.3375411 , -0.36025998]), + 'Velocity': array([-0.59121323, -0.31318679, 0.01336558]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.97705078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.57901001, -1827.64697266, 16.46276855]), + 'frame': 9035, + 'frame_number': 9035, + 'framesequence': 9033, + 'gaze_dir': array([ 0.98058057, -0.13283086, 0.14428279]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13283086, 0.14428279]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13283086, 0.14428279]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15049898624420166, + 'throttle_input': 0.0, + 'timestamp': 40.337358359247446, + 'timestamp_carla': 40337, + 'timestamp_device': 40014, + 'timestamp_stream': 40.337358359247446, + 'transform': [array([-0.21896648, -0.21936157, 0.02746861]), + array([ 0.47227341, -0.64545566, 0.41099492])]} +---------------------- +{'AngularVelocity': array([-0.52177411, 0.04764853, -8.52495766]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.696184158325195, + 'FR_Wheel_Angle': 41.52064514160156, + 'Location': array([ -4.0254178 , -20.6335392 , 0.14991151]), + 'Rotation': array([ 0.05438196, 6.92627287, -0.33782959]), + 'Velocity': array([-0.607889 , -0.31589127, 0.01531121]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.98681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.40866089, -1828.64318848, 16.46337891]), + 'frame': 9036, + 'frame_number': 9036, + 'framesequence': 9034, + 'gaze_dir': array([ 0.98058057, -0.13326286, 0.14388385]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13326286, 0.14388385]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13326286, 0.14388385]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15112155675888062, + 'throttle_input': 0.0, + 'timestamp': 40.34111635759473, + 'timestamp_carla': 40341, + 'timestamp_device': 40017, + 'timestamp_stream': 40.34111635759473, + 'transform': [array([-0.21917041, -0.22030151, 0.02702355]), + array([ 0.47400826, -0.65140021, 0.41229177])]} +---------------------- +{'AngularVelocity': array([-0.42279431, 0.07614008, -8.82051945]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68285369873047, + 'FR_Wheel_Angle': 41.49887466430664, + 'Location': array([ -4.05688763, -20.64453316, 0.15092413]), + 'Rotation': array([ 0.04540709, 6.52025127, -0.31130978]), + 'Velocity': array([-0.63965124, -0.31482804, 0.01337801]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1166.9996337890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.25366211, -1829.44494629, 16.46362305]), + 'frame': 9037, + 'frame_number': 9037, + 'framesequence': 9035, + 'gaze_dir': array([ 0.98058069, -0.13383758, 0.14334945]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13383758, 0.14334945]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13383758, 0.14334945]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1517075151205063, + 'throttle_input': 0.0, + 'timestamp': 40.34458505734801, + 'timestamp_carla': 40344, + 'timestamp_device': 40021, + 'timestamp_stream': 40.34458505734801, + 'transform': [array([-0.21912497, -0.22128174, 0.0266228 ]), + array([ 0.47558606, -0.65699762, 0.41346002])]} +---------------------- +{'AngularVelocity': array([-0.22599229, 0.03990932, -8.91300964]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.679838180541992, + 'FR_Wheel_Angle': 41.494815826416016, + 'Location': array([ -4.08728981, -20.65482712, 0.15170133]), + 'Rotation': array([ 0.0393214 , 6.12584543, -0.28994748]), + 'Velocity': array([-0.64868963, -0.3092142 , 0.00782124]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0130615234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.15039062, -1830.48303223, 16.46447754]), + 'frame': 9038, + 'frame_number': 9038, + 'framesequence': 9036, + 'gaze_dir': array([ 0.98058057, -0.13440958, 0.14281325]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13440958, 0.14281325]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13440958, 0.14281325]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1523117870092392, + 'throttle_input': 0.0, + 'timestamp': 40.34827955812216, + 'timestamp_carla': 40348, + 'timestamp_device': 40025, + 'timestamp_stream': 40.34827955812216, + 'transform': [array([-0.21885647, -0.22243652, 0.02626644]), + array([ 0.47701356, -0.66307068, 0.41449764])]} +---------------------- +{'AngularVelocity': array([-0.44153318, 0.02833933, -9.00654697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.678268432617188, + 'FR_Wheel_Angle': 41.491943359375, + 'Location': array([ -4.11969328, -20.66550827, 0.1523937 ]), + 'Rotation': array([ 0.03475883, 5.70651531, -0.27139276]), + 'Velocity': array([-0.65363127, -0.31269541, 0.01571968]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0264892578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.07772827, -1831.51953125, 16.46435547]), + 'frame': 9039, + 'frame_number': 9039, + 'framesequence': 9037, + 'gaze_dir': array([ 0.98058069, -0.13483773, 0.14240909]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13483773, 0.14240909]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13483773, 0.14240909]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15256813168525696, + 'throttle_input': 0.0, + 'timestamp': 40.351845160126686, + 'timestamp_carla': 40351, + 'timestamp_device': 40028, + 'timestamp_stream': 40.351845160126686, + 'transform': [array([-0.21843265, -0.22362059, 0.02603886]), + array([ 0.47794929, -0.669007 , 0.41516167])]} +---------------------- +{'AngularVelocity': array([-0.67189187, 0.04192104, -9.3181181 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.665891647338867, + 'FR_Wheel_Angle': 41.471046447753906, + 'Location': array([ -4.15397739, -20.6761837 , 0.15340665]), + 'Rotation': array([ 0.02913759, 5.27084398, -0.23745722]), + 'Velocity': array([-0.68315929, -0.31370336, 0.02121809]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0352783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.9776001 , -1832.34143066, 16.46508789]), + 'frame': 9040, + 'frame_number': 9040, + 'framesequence': 9038, + 'gaze_dir': array([ 0.98058069, -0.13540597, 0.14186889]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13540597, 0.14186889]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13540597, 0.14186889]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15315409004688263, + 'throttle_input': 0.0, + 'timestamp': 40.35539745911956, + 'timestamp_carla': 40355, + 'timestamp_device': 40032, + 'timestamp_stream': 40.35539745911956, + 'transform': [array([-0.21788578, -0.22485352, 0.02597173]), + array([ 0.47832495, -0.67497802, 0.41535628])]} +---------------------- +{'AngularVelocity': array([-0.66422004, 0.0597492 , -9.46232224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.661813735961914, + 'FR_Wheel_Angle': 41.4642333984375, + 'Location': array([ -4.19015932, -20.68715096, 0.15455996]), + 'Rotation': array([ 0.02271721, 4.80989456, -0.19955446]), + 'Velocity': array([-0.69432747, -0.31360543, 0.02291056]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0467529296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.92822266, -1833.40539551, 16.46520996]), + 'frame': 9041, + 'frame_number': 9041, + 'framesequence': 9039, + 'gaze_dir': array([ 0.98058057, -0.13583127, 0.14146174]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13583127, 0.14146174]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13583127, 0.14146174]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15366679430007935, + 'throttle_input': 0.0, + 'timestamp': 40.35911485925317, + 'timestamp_carla': 40358, + 'timestamp_device': 40035, + 'timestamp_stream': 40.35911485925317, + 'transform': [array([-0.21720894, -0.22618651, 0.02609554]), + array([ 0.47798344, -0.68127501, 0.41499439])]} +---------------------- +{'AngularVelocity': array([-0.95879489, 0.15377811, -9.81509018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.627843856811523, + 'FR_Wheel_Angle': 41.41069030761719, + 'Location': array([ -4.22401667, -20.69626236, 0.15577574]), + 'Rotation': array([ 0.01600313, 4.39393282, -0.15481569]), + 'Velocity': array([-0.77444363, -0.28352585, 0.0290848 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.05322265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.86022949, -1834.24133301, 16.46569824]), + 'frame': 9042, + 'frame_number': 9042, + 'framesequence': 9040, + 'gaze_dir': array([ 0.98058069, -0.13639572, 0.1409176 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13639572, 0.1409176 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13639572, 0.1409176 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15425275266170502, + 'throttle_input': 0.0, + 'timestamp': 40.36257605999708, + 'timestamp_carla': 40362, + 'timestamp_device': 40039, + 'timestamp_stream': 40.36257605999708, + 'transform': [array([-0.21651156, -0.22744262, 0.02638985]), + array([ 0.47701356, -0.68716985, 0.4141368 ])]} +---------------------- +{'AngularVelocity': array([-0.69768173, 0.10844617, -9.7215004 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.632102966308594, + 'FR_Wheel_Angle': 41.41948318481445, + 'Location': array([ -4.26158953, -20.70655632, 0.15702139]), + 'Rotation': array([ 0.006878 , 3.93446326, -0.11602782]), + 'Velocity': array([-0.76545238, -0.30244744, 0.01967826]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0628662109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.83334351, -1835.33666992, 16.46606445]), + 'frame': 9043, + 'frame_number': 9043, + 'framesequence': 9041, + 'gaze_dir': array([ 0.98058057, -0.13695852, 0.14037065]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13695852, 0.14037065]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13695852, 0.14037065]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15458236634731293, + 'throttle_input': 0.0, + 'timestamp': 40.36653335765004, + 'timestamp_carla': 40366, + 'timestamp_device': 40043, + 'timestamp_stream': 40.36653335765004, + 'transform': [array([-0.21565682, -0.22889526, 0.02697334]), + array([ 0.47502598, -0.69390857, 0.41243109])]} +---------------------- +{'AngularVelocity': array([-1.72158074, -0.11495649, -9.98952579]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.610376358032227, + 'FR_Wheel_Angle': 41.3833122253418, + 'Location': array([ -4.30049419, -20.7170105 , 0.15829641]), + 'Rotation': array([ 2.57498119e-03, 3.45173955e+00, -6.28967211e-02]), + 'Velocity': array([-0.81877029, -0.25786379, 0.02280053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.063720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.78588867, -1836.39294434, 16.4666748 ]), + 'frame': 9044, + 'frame_number': 9044, + 'framesequence': 9042, + 'gaze_dir': array([ 0.98058069, -0.13751861, 0.13982201]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13751861, 0.13982201]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13751861, 0.13982201]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15509507060050964, + 'throttle_input': 0.0, + 'timestamp': 40.370594058185816, + 'timestamp_carla': 40370, + 'timestamp_device': 40047, + 'timestamp_stream': 40.370594058185816, + 'transform': [array([-0.2172332 , -0.22901367, 0.02718197]), + array([ 0.47439077, -0.70057648, 0.41181311])]} +---------------------- +{'AngularVelocity': array([ -1.61156654, -0.15201502, -10.15546799]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.61911392211914, + 'FR_Wheel_Angle': 41.39630126953125, + 'Location': array([ -4.33990049, -20.72651482, 0.15939088]), + 'Rotation': array([0.00430302, 2.97014356, 0.01362672]), + 'Velocity': array([-0.79988384, -0.28061536, 0.02519183]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.065185546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.74407959, -1837.49487305, 16.46691895]), + 'frame': 9045, + 'frame_number': 9045, + 'framesequence': 9043, + 'gaze_dir': array([ 0.98058069, -0.13807702, 0.1392706 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13807702, 0.1392706 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13807702, 0.1392706 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15593737363815308, + 'throttle_input': 0.0, + 'timestamp': 40.3746517598629, + 'timestamp_carla': 40374, + 'timestamp_device': 40051, + 'timestamp_stream': 40.3746517598629, + 'transform': [array([-0.21846023, -0.22938721, 0.02709738]), + array([ 0.47481424, -0.70708668, 0.41205376])]} +---------------------- +{'AngularVelocity': array([ -1.39099813, -0.13657792, -10.14580154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60898208618164, + 'FR_Wheel_Angle': 41.38198471069336, + 'Location': array([ -4.3761692 , -20.73499298, 0.16039808]), + 'Rotation': array([0.00637257, 2.52542734, 0.06853431]), + 'Velocity': array([-0.8254872 , -0.25491583, 0.02016762]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0693359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.45001221, -1838.45239258, 16.46765137]), + 'frame': 9046, + 'frame_number': 9046, + 'framesequence': 9044, + 'gaze_dir': array([ 0.98058069, -0.1386327 , 0.13871747]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1386327 , 0.13871747]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1386327 , 0.13871747]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15643177926540375, + 'throttle_input': 0.0, + 'timestamp': 40.378442358225584, + 'timestamp_carla': 40378, + 'timestamp_device': 40055, + 'timestamp_stream': 40.378442358225584, + 'transform': [array([-0.21927619, -0.22994629, 0.0268136 ]), + array([ 0.47593439, -0.71314132, 0.41287965])]} +---------------------- +{'AngularVelocity': array([ -0.94976807, -0.09131733, -10.23621273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.624919891357422, + 'FR_Wheel_Angle': 41.40385437011719, + 'Location': array([ -4.41689491, -20.74415398, 0.16133505]), + 'Rotation': array([0.00952811, 2.02846336, 0.12500034]), + 'Velocity': array([-0.79064447, -0.28976092, 0.02489349]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0755615234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.18109131, -1839.42724609, 16.46801758]), + 'frame': 9047, + 'frame_number': 9047, + 'framesequence': 9045, + 'gaze_dir': array([ 0.98058069, -0.13904852, 0.13830066]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13904852, 0.13830066]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13904852, 0.13830066]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15665151178836823, + 'throttle_input': 0.0, + 'timestamp': 40.38194505870342, + 'timestamp_carla': 40381, + 'timestamp_device': 40058, + 'timestamp_stream': 40.38194505870342, + 'transform': [array([-0.2197531 , -0.23062499, 0.02643689]), + array([ 0.47743702, -0.71875972, 0.41397589])]} +---------------------- +{'AngularVelocity': array([ -0.83626246, -0.06981175, -10.20238113]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.608606338500977, + 'FR_Wheel_Angle': 41.38053894042969, + 'Location': array([ -4.45385838, -20.75254059, 0.16228636]), + 'Rotation': array([0.01051166, 1.57354081, 0.15282337]), + 'Velocity': array([-0.83014816, -0.252011 , 0.01766923]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.0850830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.96179199, -1840.20300293, 16.46875 ]), + 'frame': 9048, + 'frame_number': 9048, + 'framesequence': 9046, + 'gaze_dir': array([ 0.98058057, -0.13960029, 0.13774365]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13960029, 0.13774365]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13960029, 0.13774365]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15712760388851166, + 'throttle_input': 0.0, + 'timestamp': 40.3853763602674, + 'timestamp_carla': 40385, + 'timestamp_device': 40062, + 'timestamp_stream': 40.3853763602674, + 'transform': [array([-0.21995716, -0.23143432, 0.02600485]), + array([ 0.47913092, -0.72435963, 0.41523623])]} +---------------------- +{'AngularVelocity': array([ -0.66600877, -0.05349408, -10.29757881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.61480140686035, + 'FR_Wheel_Angle': 41.388763427734375, + 'Location': array([ -4.49405718, -20.76110077, 0.16311686]), + 'Rotation': array([0.01187087, 1.08290184, 0.18194942]), + 'Velocity': array([-0.81807452, -0.26617315, 0.01851273]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.097900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.80187988, -1841.21289062, 16.46923828]), + 'frame': 9049, + 'frame_number': 9049, + 'framesequence': 9047, + 'gaze_dir': array([ 0.98058069, -0.14015038, 0.13718395]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14015038, 0.13718395]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14015038, 0.13718395]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1576036959886551, + 'throttle_input': 0.0, + 'timestamp': 40.38930245861411, + 'timestamp_carla': 40389, + 'timestamp_device': 40066, + 'timestamp_stream': 40.38930245861411, + 'transform': [array([-0.21987778, -0.23251586, 0.02550519]), + array([ 0.48109117, -0.73090702, 0.4166894 ])]} +---------------------- +{'AngularVelocity': array([ -0.49698448, -0.03315572, -10.32465363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.613401412963867, + 'FR_Wheel_Angle': 41.38612365722656, + 'Location': array([ -4.53489351, -20.76983261, 0.16396113]), + 'Rotation': array([0.01248559, 0.5812149 , 0.20039472]), + 'Velocity': array([-0.82347858, -0.26086882, 0.01690858]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.1116943359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.66717529, -1842.24035645, 16.46960449]), + 'frame': 9050, + 'frame_number': 9050, + 'framesequence': 9048, + 'gaze_dir': array([ 0.98058057, -0.14069821, 0.136622 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14069821, 0.136622 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14069821, 0.136622 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15809810161590576, + 'throttle_input': 0.0, + 'timestamp': 40.39327646046877, + 'timestamp_carla': 40393, + 'timestamp_device': 40070, + 'timestamp_stream': 40.39327646046877, + 'transform': [array([-0.21953571, -0.23373656, 0.0250729 ]), + array([ 0.48278508, -0.73765105, 0.41794869])]} +---------------------- +{'AngularVelocity': array([ -0.48996556, -0.02592298, -10.27522373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.592634201049805, + 'FR_Wheel_Angle': 41.35857391357422, + 'Location': array([ -4.57021332, -20.77735519, 0.16467634]), + 'Rotation': array([0.01219872, 0.14485732, 0.20733508]), + 'Velocity': array([-0.87182683, -0.20499887, 0.0105261 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.125244140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.52120972, -1843.2911377 , 16.47021484]), + 'frame': 9051, + 'frame_number': 9051, + 'framesequence': 9049, + 'gaze_dir': array([ 0.98058057, -0.14124326, 0.13605842]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14124326, 0.13605842]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14124326, 0.13605842]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15864743292331696, + 'throttle_input': 0.0, + 'timestamp': 40.39720156043768, + 'timestamp_carla': 40397, + 'timestamp_device': 40074, + 'timestamp_stream': 40.39720156043768, + 'transform': [array([-0.21899612, -0.23503783, 0.02479638]), + array([ 0.48393938, -0.74440563, 0.41875249])]} +---------------------- +{'AngularVelocity': array([ -0.40532947, -0.02637946, -10.43220711]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60905647277832, + 'FR_Wheel_Angle': 41.379676818847656, + 'Location': array([ -4.61239052, -20.78564835, 0.16532263]), + 'Rotation': array([ 0.01292955, -0.36984253, 0.22346911]), + 'Velocity': array([-0.83739376, -0.24891114, 0.01418284]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.1368408203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.38717651, -1844.35632324, 16.4708252 ]), + 'frame': 9052, + 'frame_number': 9052, + 'framesequence': 9050, + 'gaze_dir': array([ 0.98058069, -0.14165112, 0.1356338 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14165112, 0.1356338 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14165112, 0.1356338 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15916013717651367, + 'throttle_input': 0.0, + 'timestamp': 40.40065285935998, + 'timestamp_carla': 40400, + 'timestamp_device': 40077, + 'timestamp_stream': 40.40065285935998, + 'transform': [array([-0.21840248, -0.23622924, 0.02470501]), + array([ 0.48439699, -0.75039995, 0.41901892])]} +---------------------- +{'AngularVelocity': array([ -0.22314712, -0.01135002, -10.46940327]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.607715606689453, + 'FR_Wheel_Angle': 41.37690734863281, + 'Location': array([ -4.65391493, -20.7936821 , 0.1659691 ]), + 'Rotation': array([ 0.01330521, -0.87921131, 0.23241729]), + 'Velocity': array([-0.82828611, -0.25649825, 0.01444462]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.148681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.27676392, -1845.21936035, 16.47119141]), + 'frame': 9053, + 'frame_number': 9053, + 'framesequence': 9051, + 'gaze_dir': array([ 0.98058069, -0.14219221, 0.13506642]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14219221, 0.13506642]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14219221, 0.13506642]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15941649675369263, + 'throttle_input': 0.0, + 'timestamp': 40.40455165877938, + 'timestamp_carla': 40404, + 'timestamp_device': 40081, + 'timestamp_stream': 40.40455165877938, + 'transform': [array([-0.21761917, -0.23762085, 0.02482739]), + array([ 0.48410329, -0.75720906, 0.41865861])]} +---------------------- +{'AngularVelocity': array([-1.85767338e-01, -6.51050499e-03, -1.04994059e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.610498428344727, + 'FR_Wheel_Angle': 41.380897521972656, + 'Location': array([ -4.69319582, -20.80098343, 0.16654527]), + 'Rotation': array([ 0.01312079, -1.36071777, 0.23509571]), + 'Velocity': array([-0.83863151, -0.24586682, 0.01271491]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.15625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.18515015, -1846.27685547, 16.47143555]), + 'frame': 9054, + 'frame_number': 9054, + 'framesequence': 9052, + 'gaze_dir': array([ 0.98058057, -0.14259705, 0.13463891]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14259705, 0.13463891]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14259705, 0.13463891]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.15985596179962158, + 'throttle_input': 0.0, + 'timestamp': 40.408202059566975, + 'timestamp_carla': 40408, + 'timestamp_device': 40084, + 'timestamp_stream': 40.408202059566975, + 'transform': [array([-0.21681629, -0.23894653, 0.0251469 ]), + array([ 0.48309243, -0.76360655, 0.41772485])]} +---------------------- +{'AngularVelocity': array([-1.92295760e-01, -4.97801183e-03, -1.05268974e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60396957397461, + 'FR_Wheel_Angle': 41.37177658081055, + 'Location': array([ -4.73199368, -20.80803871, 0.16709004]), + 'Rotation': array([ 0.01265634, -1.83679235, 0.23465224]), + 'Velocity': array([-0.85488003, -0.22877429, 0.01096182]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.16259765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.09179688, -1847.14892578, 16.4720459 ]), + 'frame': 9055, + 'frame_number': 9055, + 'framesequence': 9053, + 'gaze_dir': array([ 0.98058057, -0.14313416, 0.13406776]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14313416, 0.13406776]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14313416, 0.13406776]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16033205389976501, + 'throttle_input': 0.0, + 'timestamp': 40.41198805719614, + 'timestamp_carla': 40411, + 'timestamp_device': 40088, + 'timestamp_stream': 40.41198805719614, + 'transform': [array([-0.21593373, -0.24033202, 0.02570022]), + array([ 0.48121414, -0.77023888, 0.41610864])]} +---------------------- +{'AngularVelocity': array([ 1.82503414, -0.72634995, -8.11916542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.638225555419922, + 'FR_Wheel_Angle': 41.431461334228516, + 'Location': array([ -4.77225828, -20.81615639, 0.16732542]), + 'Rotation': array([ 0.01969826, -2.3031311 , 0.20922251]), + 'Velocity': array([-0.78300452, -0.28899494, -0.00826897]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.1634521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.99713135, -1848.21899414, 16.47241211]), + 'frame': 9056, + 'frame_number': 9056, + 'framesequence': 9054, + 'gaze_dir': array([ 0.98058057, -0.14366952, 0.13349393]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14366952, 0.13349393]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14366952, 0.13349393]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16080813109874725, + 'throttle_input': 0.0, + 'timestamp': 40.41596815735102, + 'timestamp_carla': 40415, + 'timestamp_device': 40092, + 'timestamp_stream': 40.41596815735102, + 'transform': [array([-0.21742061, -0.24044311, 0.02591331]), + array([ 0.4805516 , -0.77697861, 0.41547784])]} +---------------------- +{'AngularVelocity': array([ 2.70074201, -1.15946758, -7.65052843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.646377563476562, + 'FR_Wheel_Angle': 41.4460563659668, + 'Location': array([ -4.80665445, -20.82481003, 0.16660036]), + 'Rotation': array([ 0.06199762, -2.63232517, 0.09115996]), + 'Velocity': array([-0.76556706, -0.26516312, -0.01125274]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.1651611328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.92086792, -1849.3190918 , 16.47290039]), + 'frame': 9057, + 'frame_number': 9057, + 'framesequence': 9055, + 'gaze_dir': array([ 0.98058069, -0.14420205, 0.13291851]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14420205, 0.13291851]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14420205, 0.13291851]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16121098399162292, + 'throttle_input': 0.0, + 'timestamp': 40.419763159006834, + 'timestamp_carla': 40419, + 'timestamp_device': 40096, + 'timestamp_stream': 40.419763159006834, + 'transform': [array([-0.21854129, -0.24077027, 0.02586191]), + array([ 0.48086578, -0.78324032, 0.41562173])]} +---------------------- +{'AngularVelocity': array([ 2.36478639, -1.01912057, -7.7935133 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.657329559326172, + 'FR_Wheel_Angle': 41.462257385253906, + 'Location': array([ -4.84369993, -20.83394432, 0.16578974]), + 'Rotation': array([ 0.11060125, -2.9851079 , -0.04315186]), + 'Velocity': array([-0.74332732, -0.27176756, -0.00979065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.169921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.59515381, -1850.28466797, 16.47363281]), + 'frame': 9058, + 'frame_number': 9058, + 'framesequence': 9056, + 'gaze_dir': array([ 0.98058057, -0.14473277, 0.13234039]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14473277, 0.13234039]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14473277, 0.13234039]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16168707609176636, + 'throttle_input': 0.0, + 'timestamp': 40.423480559140444, + 'timestamp_carla': 40423, + 'timestamp_device': 40100, + 'timestamp_stream': 40.423480559140444, + 'transform': [array([-0.21931949, -0.24129272, 0.02561012]), + array([ 0.48188347, -0.78936064, 0.41635314])]} +---------------------- +{'AngularVelocity': array([ 1.96266842, -0.8393445 , -7.76072168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.660242080688477, + 'FR_Wheel_Angle': 41.46769332885742, + 'Location': array([ -4.87848997, -20.8425045 , 0.16511385]), + 'Rotation': array([ 0.14888446, -3.30969357, -0.1529541 ]), + 'Velocity': array([-0.73862344, -0.27242616, -0.00908517]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.17626953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.30801392, -1851.26342773, 16.4744873 ]), + 'frame': 9059, + 'frame_number': 9059, + 'framesequence': 9057, + 'gaze_dir': array([ 0.98058057, -0.14526069, 0.13176073]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14526069, 0.13176073]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14526069, 0.13176073]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16214485466480255, + 'throttle_input': 0.0, + 'timestamp': 40.427141956985, + 'timestamp_carla': 40427, + 'timestamp_device': 40104, + 'timestamp_stream': 40.427141956985, + 'transform': [array([-0.21977329, -0.24198975, 0.02523058]), + array([ 0.48338613, -0.7954365 , 0.41745704])]} +---------------------- +{'AngularVelocity': array([ 1.76355171, -0.73137558, -7.60618019]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.661235809326172, + 'FR_Wheel_Angle': 41.4699592590332, + 'Location': array([ -4.91499281, -20.85172272, 0.16441423]), + 'Rotation': array([ 0.18302856, -3.65265012, -0.25381473]), + 'Velocity': array([-0.73794889, -0.26708308, -0.01059636]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.185302734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.0513916 , -1852.25219727, 16.47473145]), + 'frame': 9060, + 'frame_number': 9060, + 'framesequence': 9058, + 'gaze_dir': array([ 0.98058057, -0.1456556 , 0.13132404]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1456556 , 0.13132404]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1456556 , 0.13132404]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16254767775535583, + 'throttle_input': 0.0, + 'timestamp': 40.43069155886769, + 'timestamp_carla': 40430, + 'timestamp_device': 40107, + 'timestamp_stream': 40.43069155886769, + 'transform': [array([-0.21993476, -0.24281615, 0.02479271]), + array([ 0.48510051, -0.80141187, 0.41873273])]} +---------------------- +{'AngularVelocity': array([ 1.52095008, -0.62585199, -7.51847458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.652780532836914, + 'FR_Wheel_Angle': 41.45839309692383, + 'Location': array([ -4.95106363, -20.86080933, 0.16373773]), + 'Rotation': array([ 0.21150362, -3.98666477, -0.34185788]), + 'Velocity': array([-0.7366358 , -0.26485923, -0.01039723]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 284.83413696, -1853.04602051, 16.47509766]), + 'frame': 9061, + 'frame_number': 9061, + 'framesequence': 9059, + 'gaze_dir': array([ 0.98058057, -0.14617944, 0.13074069]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14617944, 0.13074069]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14617944, 0.13074069]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16274911165237427, + 'throttle_input': 0.0, + 'timestamp': 40.43459836021066, + 'timestamp_carla': 40434, + 'timestamp_device': 40111, + 'timestamp_stream': 40.43459836021066, + 'transform': [array([-0.21980071, -0.24388427, 0.02430635]), + array([ 0.48701978, -0.80811673, 0.42014623])]} +---------------------- +{'AngularVelocity': array([ 1.39639962, -0.57333404, -7.40301943]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.661865234375, + 'FR_Wheel_Angle': 41.4753532409668, + 'Location': array([ -4.98467922, -20.86912537, 0.16311339]), + 'Rotation': array([ 0.23483555, -4.29083395, -0.41690063]), + 'Velocity': array([-0.73961776, -0.26076266, -0.01081109]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.21044921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 284.64743042, -1854.07421875, 16.47595215]), + 'frame': 9062, + 'frame_number': 9062, + 'framesequence': 9060, + 'gaze_dir': array([ 0.98058057, -0.14670144, 0.13015468]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14670144, 0.13015468]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14670144, 0.13015468]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16315194964408875, + 'throttle_input': 0.0, + 'timestamp': 40.43852565810084, + 'timestamp_carla': 40438, + 'timestamp_device': 40115, + 'timestamp_stream': 40.43852565810084, + 'transform': [array([-0.21940769, -0.245083 , 0.02388713]), + array([ 0.48866585, -0.81497353, 0.42136782])]} +---------------------- +{'AngularVelocity': array([ 1.14207304, -0.45190248, -7.41954422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.665979385375977, + 'FR_Wheel_Angle': 41.47915267944336, + 'Location': array([ -5.01952362, -20.87781525, 0.16251837]), + 'Rotation': array([ 0.25453383, -4.6048913 , -0.48483267]), + 'Velocity': array([-0.7322827 , -0.26231235, -0.00967238]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 284.46347046, -1855.13464355, 16.47644043]), + 'frame': 9063, + 'frame_number': 9063, + 'framesequence': 9061, + 'gaze_dir': array([ 0.98058057, -0.1472211 , 0.12956661]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1472211 , 0.12956661]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1472211 , 0.12956661]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16362804174423218, + 'throttle_input': 0.0, + 'timestamp': 40.442383859306574, + 'timestamp_carla': 40442, + 'timestamp_device': 40119, + 'timestamp_stream': 40.442383859306574, + 'transform': [array([-0.21882045, -0.24634887, 0.02361826]), + array([ 0.489786 , -0.82181031, 0.42214891])]} +---------------------- +{'AngularVelocity': array([ 1.04737294, -0.40027168, -7.31959581]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.667715072631836, + 'FR_Wheel_Angle': 41.48151397705078, + 'Location': array([ -5.0558033 , -20.88704491, 0.16190538]), + 'Rotation': array([ 0.27173224, -4.93545771, -0.54751575]), + 'Velocity': array([-0.72992992, -0.25848529, -0.0105668 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.238525390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 284.29724121, -1856.20751953, 16.47680664]), + 'frame': 9064, + 'frame_number': 9064, + 'framesequence': 9062, + 'gaze_dir': array([ 0.98058057, -0.14773791, 0.128977 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14773791, 0.128977 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14773791, 0.128977 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1641041338443756, + 'throttle_input': 0.0, + 'timestamp': 40.446512158960104, + 'timestamp_carla': 40446, + 'timestamp_device': 40123, + 'timestamp_stream': 40.446512158960104, + 'transform': [array([-0.21802181, -0.24777831, 0.02354319]), + array([ 0.49018899, -0.82920188, 0.42236459])]} +---------------------- +{'AngularVelocity': array([ 1.00179803, -0.38111594, -7.09579372]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.659061431884766, + 'FR_Wheel_Angle': 41.469486236572266, + 'Location': array([ -5.08951378, -20.89552116, 0.16135664]), + 'Rotation': array([ 0.28495547, -5.2377038 , -0.59997541]), + 'Velocity': array([-0.75024438, -0.25014761, -0.01057903]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.2498779296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 284.14831543, -1857.28759766, 16.47753906]), + 'frame': 9065, + 'frame_number': 9065, + 'framesequence': 9063, + 'gaze_dir': array([ 0.98058069, -0.14825284, 0.1283848 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14825284, 0.1283848 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14825284, 0.1283848 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1646534651517868, + 'throttle_input': 0.0, + 'timestamp': 40.4509314596653, + 'timestamp_carla': 40450, + 'timestamp_device': 40127, + 'timestamp_stream': 40.4509314596653, + 'transform': [array([-0.21702784, -0.24936035, 0.02375145]), + array([ 0.48955378, -0.83716422, 0.42175224])]} +---------------------- +{'AngularVelocity': array([ 0.84946686, -0.30766031, -7.23119926]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66947364807129, + 'FR_Wheel_Angle': 41.48615264892578, + 'Location': array([ -5.12532568, -20.90446091, 0.1607842 ]), + 'Rotation': array([ 0.29768011, -5.55600262, -0.65237421]), + 'Velocity': array([-0.72918165, -0.25506106, -0.01003059]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.2586669921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 283.99835205, -1858.39001465, 16.47802734]), + 'frame': 9066, + 'frame_number': 9066, + 'framesequence': 9064, + 'gaze_dir': array([ 0.98058069, -0.14876491, 0.12779109]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14876491, 0.12779109]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14876491, 0.12779109]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.165294349193573, + 'throttle_input': 0.0, + 'timestamp': 40.4544772580266, + 'timestamp_carla': 40454, + 'timestamp_device': 40131, + 'timestamp_stream': 40.4544772580266, + 'transform': [array([-0.2161665 , -0.25064331, 0.02411163]), + array([ 0.48833799, -0.84358013, 0.42070246])]} +---------------------- +{'AngularVelocity': array([ 0.86892343, -0.30928066, -7.00265694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66135597229004, + 'FR_Wheel_Angle': 41.47316360473633, + 'Location': array([ -5.15863895, -20.91279221, 0.16026472]), + 'Rotation': array([ 0.30737898, -5.85165787, -0.69650263]), + 'Velocity': array([-0.74814957, -0.24617942, -0.01094222]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.2628173828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 283.8427124 , -1859.50610352, 16.47839355]), + 'frame': 9067, + 'frame_number': 9067, + 'framesequence': 9065, + 'gaze_dir': array([ 0.98058057, -0.14952904, 0.12689613]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14952904, 0.12689613]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14952904, 0.12689613]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16551408171653748, + 'throttle_input': 0.0, + 'timestamp': 40.460282158106565, + 'timestamp_carla': 40460, + 'timestamp_device': 40137, + 'timestamp_stream': 40.460282158106565, + 'transform': [array([-0.21803546, -0.25096679, 0.02404447]), + array([ 0.48872733, -0.8535642 , 0.42086616])]} +---------------------- +{'AngularVelocity': array([ 0.69609839, -0.22383708, -7.15938854]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.673137664794922, + 'FR_Wheel_Angle': 41.4937744140625, + 'Location': array([ -5.19457102, -20.92172813, 0.1597183 ]), + 'Rotation': array([ 0.31661341, -6.16858435, -0.74145514]), + 'Velocity': array([-0.72416031, -0.25197998, -0.00965025]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.2679443359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 283.71780396, -1861.04199219, 16.47937012]), + 'frame': 9068, + 'frame_number': 9068, + 'framesequence': 9066, + 'gaze_dir': array([ 0.98058057, -0.14990932, 0.12644663]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14990932, 0.12644663]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14990932, 0.12644663]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16622823476791382, + 'throttle_input': 0.0, + 'timestamp': 40.463957156986, + 'timestamp_carla': 40463, + 'timestamp_device': 40140, + 'timestamp_stream': 40.463957156986, + 'transform': [array([-0.21892032, -0.25137696, 0.02380565]), + array([ 0.48970404, -0.85977006, 0.42155969])]} +---------------------- +{'AngularVelocity': array([ 0.72521549, -0.24074294, -6.91893053]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.663105010986328, + 'FR_Wheel_Angle': 41.4769172668457, + 'Location': array([ -5.2273941 , -20.92988205, 0.15924947]), + 'Rotation': array([ 0.32300645, -6.45676088, -0.77789289]), + 'Velocity': array([-0.74730366, -0.2428686 , -0.01041356]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.275146484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 283.2124939 , -1861.82214355, 16.4798584 ]), + 'frame': 9069, + 'frame_number': 9069, + 'framesequence': 9067, + 'gaze_dir': array([ 0.98058069, -0.15041365, 0.12584633]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15041365, 0.12584633]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15041365, 0.12584633]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16670429706573486, + 'throttle_input': 0.0, + 'timestamp': 40.4675666578114, + 'timestamp_carla': 40467, + 'timestamp_device': 40144, + 'timestamp_stream': 40.4675666578114, + 'transform': [array([-0.21949042, -0.25196654, 0.02342806]), + array([ 0.49119985, -0.86587662, 0.42265785])]} +---------------------- +{'AngularVelocity': array([ 0.55365193, -0.15787661, -7.08291721]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.675201416015625, + 'FR_Wheel_Angle': 41.49558639526367, + 'Location': array([ -5.26346588, -20.93882942, 0.1587615 ]), + 'Rotation': array([ 0.32879847, -6.77280188, -0.81518543]), + 'Velocity': array([-0.72268975, -0.24891432, -0.00872032]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.28515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 282.91375732, -1862.8104248 , 16.48083496]), + 'frame': 9070, + 'frame_number': 9070, + 'framesequence': 9068, + 'gaze_dir': array([ 0.98058069, -0.15079078, 0.1253942 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15079078, 0.1253942 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15079078, 0.1253942 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1671803891658783, + 'throttle_input': 0.0, + 'timestamp': 40.471139058470726, + 'timestamp_carla': 40471, + 'timestamp_device': 40147, + 'timestamp_stream': 40.471139058470726, + 'transform': [array([-0.21976031, -0.2527124 , 0.02296127]), + array([ 0.49300987, -0.87198436, 0.42401806])]} +---------------------- +{'AngularVelocity': array([ 0.5865404 , -0.14394167, -6.96237755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67017364501953, + 'FR_Wheel_Angle': 41.489444732666016, + 'Location': array([ -5.29703426, -20.94713974, 0.15832636]), + 'Rotation': array([ 0.33275315, -7.06613874, -0.84692365]), + 'Velocity': array([-0.73503309, -0.24352759, -0.00965348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.2958984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 282.64932251, -1863.5904541 , 16.48120117]), + 'frame': 9071, + 'frame_number': 9071, + 'framesequence': 9069, + 'gaze_dir': array([ 0.98058069, -0.15129086, 0.12479036]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15129086, 0.12479036]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15129086, 0.12479036]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1676015555858612, + 'throttle_input': 0.0, + 'timestamp': 40.474840458482504, + 'timestamp_carla': 40474, + 'timestamp_device': 40151, + 'timestamp_stream': 40.474840458482504, + 'transform': [array([-0.21974082, -0.25363892, 0.0224488 ]), + array([ 0.4950316 , -0.87843913, 0.42550969])]} +---------------------- +{'AngularVelocity': array([ 0.60249287, -0.17270282, -6.87961721]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.668596267700195, + 'FR_Wheel_Angle': 41.48704147338867, + 'Location': array([ -5.33028746, -20.95530319, 0.15788969]), + 'Rotation': array([ 0.33640045, -7.35486507, -0.87802124]), + 'Velocity': array([-0.73982573, -0.2399853 , -0.00985339]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3082275390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 282.40130615, -1864.60449219, 16.48156738]), + 'frame': 9072, + 'frame_number': 9072, + 'framesequence': 9070, + 'gaze_dir': array([ 0.98058069, -0.15178902, 0.12418396]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15178902, 0.12418396]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15178902, 0.12418396]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1680593341588974, + 'throttle_input': 0.0, + 'timestamp': 40.478438660502434, + 'timestamp_carla': 40478, + 'timestamp_device': 40155, + 'timestamp_stream': 40.478438660502434, + 'transform': [array([-0.21947467, -0.25466186, 0.02197816]), + array([ 0.49685526, -0.88481969, 0.42688161])]} +---------------------- +{'AngularVelocity': array([ 0.44138867, -0.09600113, -6.9976449 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.680978775024414, + 'FR_Wheel_Angle': 41.50659942626953, + 'Location': array([ -5.36629391, -20.96417236, 0.1574413 ]), + 'Rotation': array([ 0.33950821, -7.66889095, -0.90982044]), + 'Velocity': array([-0.71442068, -0.24442214, -0.00804217]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.321533203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 282.16836548, -1865.64111328, 16.4822998 ]), + 'frame': 9073, + 'frame_number': 9073, + 'framesequence': 9071, + 'gaze_dir': array([ 0.98058069, -0.15216069, 0.12372828]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15216069, 0.12372828]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15216069, 0.12372828]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16826075315475464, + 'throttle_input': 0.0, + 'timestamp': 40.48200265690684, + 'timestamp_carla': 40481, + 'timestamp_device': 40158, + 'timestamp_stream': 40.48200265690684, + 'transform': [array([-0.21900654, -0.25577271, 0.02160427]), + array([ 0.49833742, -0.89124388, 0.42797184])]} +---------------------- +{'AngularVelocity': array([ 0.50705814, -0.12695104, -6.81061649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.670717239379883, + 'FR_Wheel_Angle': 41.48976135253906, + 'Location': array([ -5.3991456 , -20.97223854, 0.1570619 ]), + 'Rotation': array([ 0.34082642, -7.95411158, -0.93551636]), + 'Velocity': array([-0.73813152, -0.23665416, -0.00917786]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.336181640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.9826355 , -1866.47497559, 16.48278809]), + 'frame': 9074, + 'frame_number': 9074, + 'framesequence': 9072, + 'gaze_dir': array([ 0.98058069, -0.15265457, 0.12311841]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15265457, 0.12311841]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15265457, 0.12311841]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16864529252052307, + 'throttle_input': 0.0, + 'timestamp': 40.485534358769655, + 'timestamp_carla': 40485, + 'timestamp_device': 40162, + 'timestamp_stream': 40.485534358769655, + 'transform': [array([-0.21838455, -0.25694212, 0.02136496]), + array([ 0.4993073 , -0.89768523, 0.42867059])]} +---------------------- +{'AngularVelocity': array([ 0.40593198, -0.07973246, -6.87260342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67525863647461, + 'FR_Wheel_Angle': 41.49946212768555, + 'Location': array([ -5.43337917, -20.98057175, 0.15668623]), + 'Rotation': array([ 0.34151626, -8.2495203 , -0.96160871]), + 'Velocity': array([-0.73005009, -0.23925427, -0.00756793]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.348876953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.79370117, -1867.53503418, 16.4831543 ]), + 'frame': 9075, + 'frame_number': 9075, + 'framesequence': 9073, + 'gaze_dir': array([ 0.98058069, -0.1532684 , 0.12235343]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1532684 , 0.12235343]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1532684 , 0.12235343]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1691213846206665, + 'throttle_input': 0.0, + 'timestamp': 40.49078515917063, + 'timestamp_carla': 40490, + 'timestamp_device': 40167, + 'timestamp_stream': 40.49078515917063, + 'transform': [array([-0.21721019, -0.25878417, 0.02139511]), + array([ 0.49938244, -0.90736765, 0.42856678])]} +---------------------- +{'AngularVelocity': array([ 0.35116291, -0.04216844, -6.93701124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68760871887207, + 'FR_Wheel_Angle': 41.51654815673828, + 'Location': array([ -5.46796513, -20.98895645, 0.15631266]), + 'Rotation': array([ 0.34214464, -8.54789162, -0.98791498]), + 'Velocity': array([-0.70423645, -0.24071771, -0.00718743]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3607177734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.60760498, -1868.82995605, 16.48425293]), + 'frame': 9076, + 'frame_number': 9076, + 'framesequence': 9074, + 'gaze_dir': array([ 0.98058069, -0.15375631, 0.12173972]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15375631, 0.12173972]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15375631, 0.12173972]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1698538213968277, + 'throttle_input': 0.0, + 'timestamp': 40.4944630600512, + 'timestamp_carla': 40494, + 'timestamp_device': 40171, + 'timestamp_stream': 40.4944630600512, + 'transform': [array([-0.21630348, -0.26010254, 0.02162146]), + array([ 0.49868575, -0.91417634, 0.4279063 ])]} +---------------------- +{'AngularVelocity': array([ 0.3715232 , -0.05169594, -6.84712362]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.685705184936523, + 'FR_Wheel_Angle': 41.51512145996094, + 'Location': array([ -5.50286102, -20.997509 , 0.15595171]), + 'Rotation': array([ 0.34161872, -8.85160351, -1.01107776]), + 'Velocity': array([-0.70973217, -0.23659967, -0.00789736]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.38098145, -1869.98461914, 16.48449707]), + 'frame': 9077, + 'frame_number': 9077, + 'framesequence': 9075, + 'gaze_dir': array([ 0.98058069, -0.1541211 , 0.12127757]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1541211 , 0.12127757]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1541211 , 0.12127757]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17016510665416718, + 'throttle_input': 0.0, + 'timestamp': 40.497955460101366, + 'timestamp_carla': 40497, + 'timestamp_device': 40174, + 'timestamp_stream': 40.497955460101366, + 'transform': [array([-0.21538813, -0.26137084, 0.0220322 ]), + array([ 0.49730605, -0.92065173, 0.42670915])]} +---------------------- +{'AngularVelocity': array([ 0.31032246, -0.0195216 , -6.87425137]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.691545486450195, + 'FR_Wheel_Angle': 41.52383041381836, + 'Location': array([ -5.53725529, -21.00582504, 0.15559492]), + 'Rotation': array([ 0.34107915, -9.14872551, -1.03512573]), + 'Velocity': array([-0.69843227, -0.23705968, -0.00671804]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3662109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.20431519, -1870.8236084 , 16.48522949]), + 'frame': 9078, + 'frame_number': 9078, + 'framesequence': 9076, + 'gaze_dir': array([ 0.98058069, -0.1546047 , 0.12066046]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1546047 , 0.12066046]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1546047 , 0.12066046]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1706778109073639, + 'throttle_input': 0.0, + 'timestamp': 40.501387760043144, + 'timestamp_carla': 40501, + 'timestamp_device': 40178, + 'timestamp_stream': 40.501387760043144, + 'transform': [array([-0.21445163, -0.26262328, 0.02262091]), + array([ 0.49526381, -0.92702585, 0.42499393])]} +---------------------- +{'AngularVelocity': array([ 0.38970876, -0.0643302 , -6.71693087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67922019958496, + 'FR_Wheel_Angle': 41.506351470947266, + 'Location': array([ -5.57024097, -21.01382256, 0.15528791]), + 'Rotation': array([ 0.33931011, -9.43397236, -1.0547179 ]), + 'Velocity': array([-0.72697705, -0.23071775, -0.00811331]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.367919921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.04806519, -1871.90161133, 16.4855957 ]), + 'frame': 9079, + 'frame_number': 9079, + 'framesequence': 9077, + 'gaze_dir': array([ 0.98058069, -0.15508631, 0.12004083]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15508631, 0.12004083]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15508631, 0.12004083]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17113560438156128, + 'throttle_input': 0.0, + 'timestamp': 40.505431059747934, + 'timestamp_carla': 40505, + 'timestamp_device': 40182, + 'timestamp_stream': 40.505431059747934, + 'transform': [array([-0.21331611, -0.26409912, 0.02356605]), + array([ 0.49193069, -0.93451232, 0.4222365 ])]} +---------------------- +{'AngularVelocity': array([ 0.41152936, -0.05253376, -6.70444584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.675918579101562, + 'FR_Wheel_Angle': 41.502281188964844, + 'Location': array([ -5.6029563 , -21.02164841, 0.15497079]), + 'Rotation': array([ 0.33769137, -9.71531391, -1.07617176]), + 'Velocity': array([-0.73591775, -0.22917496, -0.00776108]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3656005859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 280.88751221, -1872.9753418 , 16.48620605]), + 'frame': 9080, + 'frame_number': 9080, + 'framesequence': 9078, + 'gaze_dir': array([ 0.98058069, -0.15556496, 0.11941987]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15556496, 0.11941987]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15556496, 0.11941987]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17162999510765076, + 'throttle_input': 0.0, + 'timestamp': 40.50960345938802, + 'timestamp_carla': 40509, + 'timestamp_device': 40186, + 'timestamp_stream': 40.50960345938802, + 'transform': [array([-0.21475516, -0.26421753, 0.0240876 ]), + array([ 0.49010703, -0.94193661, 0.42070782])]} +---------------------- +{'AngularVelocity': array([ 0.35946774, -0.05784791, -6.72269106]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.681747436523438, + 'FR_Wheel_Angle': 41.5107307434082, + 'Location': array([ -5.63670111, -21.02968407, 0.15466726]), + 'Rotation': array([ 0.33602479, -10.00452995, -1.09756446]), + 'Velocity': array([-0.72467017, -0.23001835, -0.00713577]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.357666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 280.70425415, -1874.07312012, 16.48632812]), + 'frame': 9081, + 'frame_number': 9081, + 'framesequence': 9079, + 'gaze_dir': array([ 0.98058057, -0.15604158, 0.11879639]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15604158, 0.11879639]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15604158, 0.11879639]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17214271426200867, + 'throttle_input': 0.0, + 'timestamp': 40.51319895684719, + 'timestamp_carla': 40513, + 'timestamp_device': 40190, + 'timestamp_stream': 40.51319895684719, + 'transform': [array([-0.21572556, -0.26452026, 0.02427754]), + array([ 0.48949915, -0.94817388, 0.42015198])]} +---------------------- +{'AngularVelocity': array([ 0.34056395, -0.03747445, -6.71410942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.673114776611328, + 'FR_Wheel_Angle': 41.49712371826172, + 'Location': array([ -5.67088079, -21.03784561, 0.15436861]), + 'Rotation': array([ 0.33375034, -10.29917812, -1.11828613]), + 'Velocity': array([-0.71770912, -0.2290348 , -0.00697843]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3521728515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 280.24969482, -1875.02685547, 16.48730469]), + 'frame': 9082, + 'frame_number': 9082, + 'framesequence': 9080, + 'gaze_dir': array([ 0.98058069, -0.15639707, 0.118328 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15639707, 0.118328 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15639707, 0.118328 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17263711988925934, + 'throttle_input': 0.0, + 'timestamp': 40.51683395728469, + 'timestamp_carla': 40516, + 'timestamp_device': 40193, + 'timestamp_stream': 40.51683395728469, + 'transform': [array([-0.21640861, -0.26501831, 0.02425447]), + array([ 0.48966989, -0.95444673, 0.42021808])]} +---------------------- +{'AngularVelocity': array([ 0.35706702, -0.03350098, -6.72443771]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.694517135620117, + 'FR_Wheel_Angle': 41.53055953979492, + 'Location': array([ -5.70523834, -21.04599571, 0.15404603]), + 'Rotation': array([ 0.33179691, -10.59498787, -1.14016724]), + 'Velocity': array([-0.69902515, -0.22788282, -0.0073496 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.357421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.92449951, -1875.79187012, 16.48828125]), + 'frame': 9083, + 'frame_number': 9083, + 'framesequence': 9081, + 'gaze_dir': array([ 0.98058057, -0.15686932, 0.1177012 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15686932, 0.1177012 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15686932, 0.1177012 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1731681376695633, + 'throttle_input': 0.0, + 'timestamp': 40.52031375840306, + 'timestamp_carla': 40520, + 'timestamp_device': 40197, + 'timestamp_stream': 40.52031375840306, + 'transform': [array([-0.21677807, -0.26565796, 0.02408115]), + array([ 0.49036658, -0.96049052, 0.42072558])]} +---------------------- +{'AngularVelocity': array([ 0.3983562 , -0.07375844, -6.62812471]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.685653686523438, + 'FR_Wheel_Angle': 41.517127990722656, + 'Location': array([ -5.73739004, -21.05356598, 0.1537372 ]), + 'Rotation': array([ 0.32998008, -10.87086582, -1.1605835 ]), + 'Velocity': array([-0.72006822, -0.22361846, -0.00813582]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.36474609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.59384155, -1876.78918457, 16.48876953]), + 'frame': 9084, + 'frame_number': 9084, + 'framesequence': 9082, + 'gaze_dir': array([ 0.98058069, -0.157456 , 0.11691523]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.157456 , 0.11691523]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.157456 , 0.11691523]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.173406183719635, + 'throttle_input': 0.0, + 'timestamp': 40.524450458586216, + 'timestamp_carla': 40524, + 'timestamp_device': 40202, + 'timestamp_stream': 40.524450458586216, + 'transform': [array([-0.21683018, -0.26662719, 0.02374947]), + array([ 0.49166432, -0.96780074, 0.42169181])]} +---------------------- +{'AngularVelocity': array([ 0.36170262, -0.05748626, -6.66627884]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.684906005859375, + 'FR_Wheel_Angle': 41.51529312133789, + 'Location': array([ -5.77206182, -21.06172562, 0.1533867 ]), + 'Rotation': array([ 0.32861406, -11.1699667 , -1.18408191]), + 'Velocity': array([-0.69781423, -0.22428806, -0.00736015]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3741455078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.27514648, -1878.0246582 , 16.48962402]), + 'frame': 9085, + 'frame_number': 9085, + 'framesequence': 9083, + 'gaze_dir': array([ 0.98058069, -0.15803827, 0.11612692]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15803827, 0.11612692]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15803827, 0.11612692]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1741386204957962, + 'throttle_input': 0.0, + 'timestamp': 40.531056959182024, + 'timestamp_carla': 40530, + 'timestamp_device': 40207, + 'timestamp_stream': 40.531056959182024, + 'transform': [array([-0.21605976, -0.26859254, 0.02321329]), + array([ 0.49376801, -0.97989368, 0.42321971])]} +---------------------- +{'AngularVelocity': array([ 0.31639108, -0.02819585, -6.65731716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70106315612793, + 'FR_Wheel_Angle': 41.54127883911133, + 'Location': array([ -5.80489492, -21.06934929, 0.15305535]), + 'Rotation': array([ 0.32716605, -11.45115948, -1.20709217]), + 'Velocity': array([-0.68874329, -0.22374694, -0.00666312]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.3853759765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.93908691, -1879.29504395, 16.49047852]), + 'frame': 9086, + 'frame_number': 9086, + 'framesequence': 9084, + 'gaze_dir': array([ 0.98058069, -0.15850171, 0.1154936 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15850171, 0.1154936 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15850171, 0.1154936 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1748710572719574, + 'throttle_input': 0.0, + 'timestamp': 40.534985058009624, + 'timestamp_carla': 40534, + 'timestamp_device': 40211, + 'timestamp_stream': 40.534985058009624, + 'transform': [array([-0.21536788, -0.26986206, 0.02301443]), + array([ 0.49460813, -0.98721385, 0.42380261])]} +---------------------- +{'AngularVelocity': array([ 0.37440318, -0.04496786, -6.5553751 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.687543869018555, + 'FR_Wheel_Angle': 41.53118133544922, + 'Location': array([ -5.83632803, -21.07666397, 0.15279306]), + 'Rotation': array([ 0.32407197, -11.71974468, -1.22436512]), + 'Velocity': array([-0.72021282, -0.21880907, -0.00784971]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4027099609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.5668335 , -1880.47949219, 16.49108887]), + 'frame': 9087, + 'frame_number': 9087, + 'framesequence': 9085, + 'gaze_dir': array([ 0.98058057, -0.15896215, 0.114859 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15896215, 0.114859 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15896215, 0.114859 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17536546289920807, + 'throttle_input': 0.0, + 'timestamp': 40.539045460522175, + 'timestamp_carla': 40538, + 'timestamp_device': 40215, + 'timestamp_stream': 40.539045460522175, + 'transform': [array([-0.2144706 , -0.2712512 , 0.02299169]), + array([ 0.4947857 , -0.9948802 , 0.42387134])]} +---------------------- +{'AngularVelocity': array([ 0.37460521, -0.04965905, -6.56721449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.691436767578125, + 'FR_Wheel_Angle': 41.52815246582031, + 'Location': array([ -5.86974525, -21.0844574 , 0.15250298]), + 'Rotation': array([ 0.32041782, -12.00712776, -1.2434386 ]), + 'Velocity': array([-0.71317792, -0.21876621, -0.0079223 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4119873046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.31848145, -1881.55773926, 16.49157715]), + 'frame': 9088, + 'frame_number': 9088, + 'framesequence': 9086, + 'gaze_dir': array([ 0.98058069, -0.15942051, 0.11422198]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15942051, 0.11422198]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15942051, 0.11422198]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1759331077337265, + 'throttle_input': 0.0, + 'timestamp': 40.54262726008892, + 'timestamp_carla': 40542, + 'timestamp_device': 40219, + 'timestamp_stream': 40.54262726008892, + 'transform': [array([-0.21357627, -0.27251342, 0.02315282]), + array([ 0.49432126, -1.00168025, 0.4234046 ])]} +---------------------- +{'AngularVelocity': array([ 0.30096743, -0.01259113, -6.58896112]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69236946105957, + 'FR_Wheel_Angle': 41.529293060302734, + 'Location': array([ -5.90431499, -21.09249496, 0.15218499]), + 'Rotation': array([ 0.31748083, -12.30549908, -1.26458752]), + 'Velocity': array([-0.68509567, -0.21927388, -0.00649703]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4169921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.07006836, -1882.64111328, 16.4921875 ]), + 'frame': 9089, + 'frame_number': 9089, + 'framesequence': 9087, + 'gaze_dir': array([ 0.98058057, -0.15987629, 0.11358312]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15987629, 0.11358312]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15987629, 0.11358312]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17618946731090546, + 'throttle_input': 0.0, + 'timestamp': 40.54625465720892, + 'timestamp_carla': 40546, + 'timestamp_device': 40223, + 'timestamp_stream': 40.54625465720892, + 'transform': [array([-0.21259139, -0.27381834, 0.0235097 ]), + array([ 0.4931328 , -1.00862205, 0.42236671])]} +---------------------- +{'AngularVelocity': array([ 0.26319346, 0.01048858, -6.58221769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71156883239746, + 'FR_Wheel_Angle': 41.560489654541016, + 'Location': array([ -5.93541813, -21.09955215, 0.15187879]), + 'Rotation': array([ 0.31539762, -12.57023907, -1.28677356]), + 'Velocity': array([-0.67083579, -0.21863514, -0.00565075]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4229736328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.86248779, -1883.72387695, 16.49304199]), + 'frame': 9090, + 'frame_number': 9090, + 'framesequence': 9088, + 'gaze_dir': array([ 0.98058057, -0.16021614, 0.11310325]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16021614, 0.11310325]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16021614, 0.11310325]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17670218646526337, + 'throttle_input': 0.0, + 'timestamp': 40.54976795986295, + 'timestamp_carla': 40549, + 'timestamp_device': 40226, + 'timestamp_stream': 40.54976795986295, + 'transform': [array([-0.21158656, -0.27509278, 0.02403952]), + array([ 0.49129549, -1.01534629, 0.42082611])]} +---------------------- +{'AngularVelocity': array([ 0.34173632, -0.02332344, -6.46814537]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.694137573242188, + 'FR_Wheel_Angle': 41.53267288208008, + 'Location': array([ -5.96675301, -21.10680771, 0.15165712]), + 'Rotation': array([ 0.31059602, -12.83940506, -1.30068946]), + 'Velocity': array([-0.71121049, -0.21326599, -0.00788578]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.419677734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.6555481 , -1884.56420898, 16.4934082 ]), + 'frame': 9091, + 'frame_number': 9091, + 'framesequence': 9089, + 'gaze_dir': array([ 0.98058057, -0.16066745, 0.11246122]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16066745, 0.11246122]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16066745, 0.11246122]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17728814482688904, + 'throttle_input': 0.0, + 'timestamp': 40.553770657628775, + 'timestamp_carla': 40553, + 'timestamp_device': 40230, + 'timestamp_stream': 40.553770657628775, + 'transform': [array([-0.2103997 , -0.27655151, 0.02488247]), + array([ 0.48832434, -1.02300072, 0.41837004])]} +---------------------- +{'AngularVelocity': array([ 2.88316399e-01, 7.75199733e-04, -6.52261448e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.710338592529297, + 'FR_Wheel_Angle': 41.55745315551758, + 'Location': array([ -6.0011344 , -21.11471558, 0.15133908]), + 'Rotation': array([ 0.30685988, -13.1360054 , -1.32086158]), + 'Velocity': array([-0.67649359, -0.21508415, -0.0064832 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4197998046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.45330811, -1885.64453125, 16.49377441]), + 'frame': 9092, + 'frame_number': 9092, + 'framesequence': 9090, + 'gaze_dir': array([ 0.98058069, -0.16122745, 0.11165693]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16122745, 0.11165693]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16122745, 0.11165693]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17785578966140747, + 'throttle_input': 0.0, + 'timestamp': 40.5590943582356, + 'timestamp_carla': 40558, + 'timestamp_device': 40235, + 'timestamp_stream': 40.5590943582356, + 'transform': [array([-0.21202014, -0.27679321, 0.0253224 ]), + array([ 0.48676705, -1.03268743, 0.41706976])]} +---------------------- +{'AngularVelocity': array([ 0.4418149 , -0.07056508, -6.49915552]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69841957092285, + 'FR_Wheel_Angle': 41.5399055480957, + 'Location': array([ -6.03293133, -21.12202263, 0.1511303 ]), + 'Rotation': array([ 0.30136159, -13.41002274, -1.33633411]), + 'Velocity': array([-0.70493412, -0.21224838, -0.00587958]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.41162109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.1902771 , -1886.95812988, 16.49450684]), + 'frame': 9093, + 'frame_number': 9093, + 'framesequence': 9091, + 'gaze_dir': array([ 0.98058069, -0.16167296, 0.11101087]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16167296, 0.11101087]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16167296, 0.11101087]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17871639132499695, + 'throttle_input': 0.0, + 'timestamp': 40.56269855797291, + 'timestamp_carla': 40562, + 'timestamp_device': 40239, + 'timestamp_stream': 40.56269855797291, + 'transform': [array([-0.21282905, -0.2771582 , 0.0253809 ]), + array([ 0.48660997, -1.03914011, 0.41689977])]} +---------------------- +{'AngularVelocity': array([ 0.38848487, -0.04944729, -6.46901178]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69241714477539, + 'FR_Wheel_Angle': 41.53343963623047, + 'Location': array([ -6.0633893 , -21.12891388, 0.15091303]), + 'Rotation': array([ 0.29774842, -13.67134476, -1.35531604]), + 'Velocity': array([-0.72013772, -0.21094915, -0.00741622]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.40673828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.60003662, -1887.93273926, 16.49560547]), + 'frame': 9094, + 'frame_number': 9094, + 'framesequence': 9092, + 'gaze_dir': array([ 0.98058069, -0.16211547, 0.11036365]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16211547, 0.11036365]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16211547, 0.11036365]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17921079695224762, + 'throttle_input': 0.0, + 'timestamp': 40.56623725965619, + 'timestamp_carla': 40566, + 'timestamp_device': 40243, + 'timestamp_stream': 40.56623725965619, + 'transform': [array([-0.21334003, -0.27769652, 0.02525579]), + array([ 0.48714957, -1.04544127, 0.4172655 ])]} +---------------------- +{'AngularVelocity': array([ 0.40877071, -0.04582486, -6.43116283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.693347930908203, + 'FR_Wheel_Angle': 41.5348014831543, + 'Location': array([ -6.09529829, -21.13619041, 0.15067586]), + 'Rotation': array([ 0.29268041, -13.94725609, -1.37286365]), + 'Velocity': array([-0.71930403, -0.20875183, -0.00828809]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4144287109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.21728516, -1888.92431641, 16.49645996]), + 'frame': 9095, + 'frame_number': 9095, + 'framesequence': 9093, + 'gaze_dir': array([ 0.98058057, -0.16244605, 0.10987645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16244605, 0.10987645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16244605, 0.10987645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17946714162826538, + 'throttle_input': 0.0, + 'timestamp': 40.56988576054573, + 'timestamp_carla': 40569, + 'timestamp_device': 40246, + 'timestamp_stream': 40.56988576054573, + 'transform': [array([-0.21355045, -0.27842283, 0.02499044]), + array([ 0.48821506, -1.05202222, 0.41804019])]} +---------------------- +{'AngularVelocity': array([ 0.28907335, 0.03843761, -6.47521687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.698467254638672, + 'FR_Wheel_Angle': 41.54296875, + 'Location': array([ -6.12842321, -21.14378166, 0.15047109]), + 'Rotation': array([ 0.28558385, -14.23494339, -1.38824451]), + 'Velocity': array([-0.70977336, -0.20985812, -0.00615542]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.42138671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.88427734, -1889.69665527, 16.49731445]), + 'frame': 9096, + 'frame_number': 9096, + 'framesequence': 9094, + 'gaze_dir': array([ 0.98058057, -0.16288444, 0.10922553]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16288444, 0.10922553]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16288444, 0.10922553]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18001648783683777, + 'throttle_input': 0.0, + 'timestamp': 40.574125457555056, + 'timestamp_carla': 40573, + 'timestamp_device': 40250, + 'timestamp_stream': 40.574125457555056, + 'transform': [array([-0.21339644, -0.27947631, 0.02458712]), + array([ 0.48979968, -1.05982935, 0.41921386])]} +---------------------- +{'AngularVelocity': array([ 0.30768332, 0.01253217, -6.45903635]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70090675354004, + 'FR_Wheel_Angle': 41.5460205078125, + 'Location': array([ -6.16038179, -21.15107536, 0.15028143]), + 'Rotation': array([ 0.2788288 , -14.51219463, -1.40298426]), + 'Velocity': array([-0.70582318, -0.20901595, -0.00673675]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.43017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.53106689, -1890.71020508, 16.4979248 ]), + 'frame': 9097, + 'frame_number': 9097, + 'framesequence': 9095, + 'gaze_dir': array([ 0.98058057, -0.1633198 , 0.10857347]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1633198 , 0.10857347]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1633198 , 0.10857347]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18041932582855225, + 'throttle_input': 0.0, + 'timestamp': 40.57777285948396, + 'timestamp_carla': 40577, + 'timestamp_device': 40254, + 'timestamp_stream': 40.57777285948396, + 'transform': [array([-0.21299389, -0.28050536, 0.02424633]), + array([ 0.49113154, -1.06668472, 0.42021057])]} +---------------------- +{'AngularVelocity': array([ 0.40478978, -0.02708098, -6.44231749]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.699308395385742, + 'FR_Wheel_Angle': 41.54759979248047, + 'Location': array([ -6.19116926, -21.1580162 , 0.15005563]), + 'Rotation': array([ 0.27323487, -14.77867413, -1.41928077]), + 'Velocity': array([-0.71053994, -0.20598562, -0.00821049]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4432373046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.18045044, -1891.76525879, 16.49841309]), + 'frame': 9098, + 'frame_number': 9098, + 'framesequence': 9096, + 'gaze_dir': array([ 0.98058069, -0.16364501, 0.10808268]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16364501, 0.10808268]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16364501, 0.10808268]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18091373145580292, + 'throttle_input': 0.0, + 'timestamp': 40.58111845701933, + 'timestamp_carla': 40580, + 'timestamp_device': 40257, + 'timestamp_stream': 40.58111845701933, + 'transform': [array([-0.21244343, -0.28153685, 0.02399605]), + array([ 0.49214241, -1.07307148, 0.42094308])]} +---------------------- +{'AngularVelocity': array([ 0.30855435, 0.03094593, -6.43919659]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.687429428100586, + 'FR_Wheel_Angle': 41.53044891357422, + 'Location': array([ -6.22439384, -21.16561508, 0.14985155]), + 'Rotation': array([ 0.2654348 , -15.07014942, -1.43441761]), + 'Velocity': array([-0.69871229, -0.20618984, -0.00685814]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.454833984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.91595459, -1892.59106445, 16.49890137]), + 'frame': 9099, + 'frame_number': 9099, + 'framesequence': 9097, + 'gaze_dir': array([ 0.98058057, -0.16407579, 0.10742758]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16407579, 0.10742758]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16407579, 0.10742758]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18157292902469635, + 'throttle_input': 0.0, + 'timestamp': 40.58487505838275, + 'timestamp_carla': 40584, + 'timestamp_device': 40261, + 'timestamp_stream': 40.58487505838275, + 'transform': [array([-0.21163402, -0.28277588, 0.02384373]), + array([ 0.49281862, -1.08034492, 0.42138857])]} +---------------------- +{'AngularVelocity': array([ 0.33791831, -0.03559916, -6.4306016 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.721174240112305, + 'FR_Wheel_Angle': 41.57759475708008, + 'Location': array([ -6.25548077, -21.17251015, 0.14955302]), + 'Rotation': array([ 0.26148012, -15.3383379 , -1.45501697]), + 'Velocity': array([-0.66374558, -0.20560084, -0.00725045]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4625244140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.63150024, -1893.62390137, 16.49951172]), + 'frame': 9100, + 'frame_number': 9100, + 'framesequence': 9098, + 'gaze_dir': array([ 0.98058069, -0.16450438, 0.10677017]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16450438, 0.10677017]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16450438, 0.10677017]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18217720091342926, + 'throttle_input': 0.0, + 'timestamp': 40.58871555700898, + 'timestamp_carla': 40588, + 'timestamp_device': 40265, + 'timestamp_stream': 40.58871555700898, + 'transform': [array([-0.21065548, -0.28410032, 0.02386576]), + array([ 0.4928391 , -1.08787942, 0.42132604])]} +---------------------- +{'AngularVelocity': array([ 0.29617092, 0.01048543, -6.41111565]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.71364402770996, + 'FR_Wheel_Angle': 41.566654205322266, + 'Location': array([ -6.28596973, -21.17933464, 0.14932966]), + 'Rotation': array([ 0.25568813, -15.60365295, -1.47085547]), + 'Velocity': array([-0.68268502, -0.20448495, -0.00659445]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4744873046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.36502075, -1894.70935059, 16.50024414]), + 'frame': 9101, + 'frame_number': 9101, + 'framesequence': 9099, + 'gaze_dir': array([ 0.98058069, -0.16482379, 0.10627645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16482379, 0.10627645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16482379, 0.10627645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18279977142810822, + 'throttle_input': 0.0, + 'timestamp': 40.59220276027918, + 'timestamp_carla': 40592, + 'timestamp_device': 40268, + 'timestamp_stream': 40.59220276027918, + 'transform': [array([-0.20968083, -0.28533447, 0.02405561]), + array([ 0.49223804, -1.09474528, 0.42077559])]} +---------------------- +{'AngularVelocity': array([ 0.17860922, 0.09000276, -6.42211723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70680809020996, + 'FR_Wheel_Angle': 41.55813980102539, + 'Location': array([ -6.31903315, -21.18687439, 0.1491594 ]), + 'Rotation': array([ 0.24708208, -15.89552402, -1.48376465]), + 'Velocity': array([-0.66589582, -0.20443434, -0.0046385 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4764404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.11181641, -1895.55078125, 16.50085449]), + 'frame': 9102, + 'frame_number': 9102, + 'framesequence': 9100, + 'gaze_dir': array([ 0.98058069, -0.16524774, 0.10561603]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16524774, 0.10561603]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16524774, 0.10561603]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18303781747817993, + 'throttle_input': 0.0, + 'timestamp': 40.595724157989025, + 'timestamp_carla': 40595, + 'timestamp_device': 40272, + 'timestamp_stream': 40.595724157989025, + 'transform': [array([-0.2086401 , -0.28660154, 0.02443239]), + array([ 0.49092665, -1.10167754, 0.41968182])]} +---------------------- +{'AngularVelocity': array([ 0.25563005, 0.01980232, -6.39242315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72307777404785, + 'FR_Wheel_Angle': 41.58240509033203, + 'Location': array([ -6.34886837, -21.19351196, 0.14893556]), + 'Rotation': array([ 0.24073683, -16.15547371, -1.49948096]), + 'Velocity': array([-0.66437513, -0.20363195, -0.00657879]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4798583984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 273.85586548, -1896.61914062, 16.50146484]), + 'frame': 9103, + 'frame_number': 9103, + 'framesequence': 9101, + 'gaze_dir': array([ 0.98058069, -0.16566865, 0.10495456]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16566865, 0.10495456]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16566865, 0.10495456]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1835322082042694, + 'throttle_input': 0.0, + 'timestamp': 40.59984305873513, + 'timestamp_carla': 40599, + 'timestamp_device': 40276, + 'timestamp_stream': 40.59984305873513, + 'transform': [array([-0.20735523, -0.28809568, 0.02513233]), + array([ 0.48845413, -1.10980654, 0.41764185])]} +---------------------- +{'AngularVelocity': array([ 0.27176616, 0.02973112, -6.33801031]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730955123901367, + 'FR_Wheel_Angle': 41.596805572509766, + 'Location': array([ -6.38129425, -21.20081711, 0.14867948]), + 'Rotation': array([ 0.23398861, -16.4420929 , -1.51507545]), + 'Velocity': array([-0.64686048, -0.19966274, -0.00689407]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4779052734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 273.59054565, -1897.68164062, 16.5020752 ]), + 'frame': 9104, + 'frame_number': 9104, + 'framesequence': 9102, + 'gaze_dir': array([ 0.98058069, -0.1660873 , 0.10429079]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1660873 , 0.10429079]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1660873 , 0.10429079]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18400830030441284, + 'throttle_input': 0.0, + 'timestamp': 40.60370345786214, + 'timestamp_carla': 40603, + 'timestamp_device': 40280, + 'timestamp_stream': 40.60370345786214, + 'transform': [array([-0.20855419, -0.28819457, 0.02543213]), + array([ 0.48745009, -1.11715329, 0.41676331])]} +---------------------- +{'AngularVelocity': array([ 3.06544423e-01, 2.02024169e-03, -6.34619856e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.721479415893555, + 'FR_Wheel_Angle': 41.580657958984375, + 'Location': array([ -6.41112185, -21.20746613, 0.14844705]), + 'Rotation': array([ 0.22721989, -16.70396233, -1.52893066]), + 'Velocity': array([-0.67067176, -0.19951114, -0.00783768]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4718017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 273.31033325, -1898.77636719, 16.50256348]), + 'frame': 9105, + 'frame_number': 9105, + 'framesequence': 9103, + 'gaze_dir': array([ 0.98058057, -0.16650289, 0.10362597]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16650289, 0.10362597]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16650289, 0.10362597]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1845942586660385, + 'throttle_input': 0.0, + 'timestamp': 40.607935059815645, + 'timestamp_carla': 40607, + 'timestamp_device': 40284, + 'timestamp_stream': 40.607935059815645, + 'transform': [array([-0.20950107, -0.28856933, 0.0254339 ]), + array([ 0.48753205, -1.12498784, 0.41675305])]} +---------------------- +{'AngularVelocity': array([ 0.3273263 , -0.00694806, -6.36380291]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.719942092895508, + 'FR_Wheel_Angle': 41.57791519165039, + 'Location': array([ -6.44116735, -21.21412277, 0.14820452]), + 'Rotation': array([ 0.22056729, -16.96775436, -1.54373169]), + 'Velocity': array([-0.67590493, -0.198833 , -0.00796793]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.474853515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.81774902, -1899.73754883, 16.50341797]), + 'frame': 9106, + 'frame_number': 9106, + 'framesequence': 9104, + 'gaze_dir': array([ 0.98058069, -0.16691625, 0.10295887]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16691625, 0.10295887]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16691625, 0.10295887]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18507035076618195, + 'throttle_input': 0.0, + 'timestamp': 40.61144295707345, + 'timestamp_carla': 40611, + 'timestamp_device': 40288, + 'timestamp_stream': 40.61144295707345, + 'transform': [array([-0.21001163, -0.28906128, 0.02525549]), + array([ 0.48824921, -1.1314311 , 0.41727525])]} +---------------------- +{'AngularVelocity': array([ 0.26212385, 0.03502604, -6.3159399 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73836326599121, + 'FR_Wheel_Angle': 41.60765838623047, + 'Location': array([ -6.47338009, -21.22130394, 0.14791086]), + 'Rotation': array([ 0.21411276, -17.25465393, -1.56170654]), + 'Velocity': array([-0.63437366, -0.19705684, -0.00658512]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.479736328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.31860352, -1900.71789551, 16.50427246]), + 'frame': 9107, + 'frame_number': 9107, + 'framesequence': 9105, + 'gaze_dir': array([ 0.98058069, -0.1672242 , 0.10245793]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1672242 , 0.10245793]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1672242 , 0.10245793]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18558306992053986, + 'throttle_input': 0.0, + 'timestamp': 40.614891059696674, + 'timestamp_carla': 40614, + 'timestamp_device': 40291, + 'timestamp_stream': 40.614891059696674, + 'transform': [array([-0.2102309 , -0.28970215, 0.02495732]), + array([ 0.48943084, -1.13781655, 0.41814622])]} +---------------------- +{'AngularVelocity': array([-1.33433652, 2.55198216, -6.63954782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.930391311645508, + 'FR_Wheel_Angle': 41.92237091064453, + 'Location': array([ -6.49171543, -21.23203087, 0.1463128 ]), + 'Rotation': array([ 0.14365937, -17.6503067 , -1.50177002]), + 'Velocity': array([-0.19325462, -0.21622886, -0.05750244]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.4842529296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.93499756, -1901.46960449, 16.50500488]), + 'frame': 9108, + 'frame_number': 9108, + 'framesequence': 9106, + 'gaze_dir': array([ 0.98058069, -0.16763286, 0.10178794]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16763286, 0.10178794]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16763286, 0.10178794]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1860591620206833, + 'throttle_input': 0.0, + 'timestamp': 40.61856605857611, + 'timestamp_carla': 40618, + 'timestamp_device': 40295, + 'timestamp_stream': 40.61856605857611, + 'transform': [array([-0.21015564, -0.29054809, 0.02455898]), + array([ 0.49100861, -1.14472544, 0.41930774])]} +---------------------- +{'AngularVelocity': array([-1.73698747, 2.75031686, -7.3429966 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.925838470458984, + 'FR_Wheel_Angle': 41.91478729248047, + 'Location': array([ -6.50404882, -21.24034309, 0.14478301]), + 'Rotation': array([ 0.05440928, -17.92542648, -1.38159192]), + 'Velocity': array([-0.2142527 , -0.24369562, -0.05356711]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.498291015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.56564331, -1902.48400879, 16.50561523]), + 'frame': 9109, + 'frame_number': 9109, + 'framesequence': 9107, + 'gaze_dir': array([ 0.98058069, -0.16803883, 0.10111633]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16803883, 0.10111633]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16803883, 0.10111633]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18637043237686157, + 'throttle_input': 0.0, + 'timestamp': 40.62231435999274, + 'timestamp_carla': 40622, + 'timestamp_device': 40299, + 'timestamp_stream': 40.62231435999274, + 'transform': [array([-0.20978305, -0.29155517, 0.0241369 ]), + array([ 0.49266151, -1.15192068, 0.42053947])]} +---------------------- +{'AngularVelocity': array([-1.5130862 , 2.60559607, -7.50754309]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.92483139038086, + 'FR_Wheel_Angle': 41.87986755371094, + 'Location': array([ -6.51598454, -21.24865723, 0.1433412 ]), + 'Rotation': array([ -0.02908977, -18.20670509, -1.27062988]), + 'Velocity': array([-0.21881588, -0.24541526, -0.05350641]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.507568359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.17831421, -1903.49597168, 16.50646973]), + 'frame': 9110, + 'frame_number': 9110, + 'framesequence': 9108, + 'gaze_dir': array([ 0.98058057, -0.16834125, 0.10061202]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16834125, 0.10061202]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16834125, 0.10061202]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18688315153121948, + 'throttle_input': 0.0, + 'timestamp': 40.625943560153246, + 'timestamp_carla': 40625, + 'timestamp_device': 40302, + 'timestamp_stream': 40.625943560153246, + 'transform': [array([-0.20919059, -0.29264039, 0.02378329]), + array([ 0.49408218, -1.15900123, 0.42157042])]} +---------------------- +{'AngularVelocity': array([-1.28853691, 2.24926162, -7.27130699]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.675785064697266, + 'FR_Wheel_Angle': 41.481544494628906, + 'Location': array([ -6.52867031, -21.25735283, 0.14192903]), + 'Rotation': array([ -0.10922155, -18.50869942, -1.16769385]), + 'Velocity': array([-0.21108688, -0.23545006, -0.04598549]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.51904296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 270.86135864, -1904.30786133, 16.50695801]), + 'frame': 9111, + 'frame_number': 9111, + 'framesequence': 9109, + 'gaze_dir': array([ 0.98058057, -0.16874251, 0.09993758]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16874251, 0.09993758]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16874251, 0.09993758]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18746910989284515, + 'throttle_input': 0.0, + 'timestamp': 40.62979405745864, + 'timestamp_carla': 40629, + 'timestamp_device': 40306, + 'timestamp_stream': 40.62979405745864, + 'transform': [array([-0.20834266, -0.2938855 , 0.02353407]), + array([ 0.49513406, -1.16663408, 0.42229682])]} +---------------------- +{'AngularVelocity': array([-1.14119411, 1.94544733, -6.12382984]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.537742614746094, + 'FR_Wheel_Angle': 41.25214767456055, + 'Location': array([ -6.54126215, -21.26616859, 0.14058176]), + 'Rotation': array([ -0.18524155, -18.82062531, -1.07131946]), + 'Velocity': array([-0.17949957, -0.19723396, -0.03847013]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.530517578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 270.5255127 , -1905.35656738, 16.50769043]), + 'frame': 9112, + 'frame_number': 9112, + 'framesequence': 9110, + 'gaze_dir': array([ 0.98058069, -0.1691407 , 0.09926219]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1691407 , 0.09926219]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1691407 , 0.09926219]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1880001276731491, + 'throttle_input': 0.0, + 'timestamp': 40.63336965814233, + 'timestamp_carla': 40633, + 'timestamp_device': 40310, + 'timestamp_stream': 40.63336965814233, + 'transform': [array([-0.20740879, -0.29509643, 0.02345322]), + array([ 0.49556434, -1.17382777, 0.42253354])]} +---------------------- +{'AngularVelocity': array([-0.70349622, 1.79463148, -6.69052029]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.469823837280273, + 'FR_Wheel_Angle': 41.13894271850586, + 'Location': array([ -6.55283928, -21.27378082, 0.13958223]), + 'Rotation': array([ -0.24462321, -19.09072876, -0.99389642]), + 'Velocity': array([-0.19571014, -0.23842283, -0.04406248]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.543212890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 270.20568848, -1906.43005371, 16.50842285]), + 'frame': 9113, + 'frame_number': 9113, + 'framesequence': 9111, + 'gaze_dir': array([ 0.98058069, -0.16943794, 0.09875396]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16943794, 0.09875396]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16943794, 0.09875396]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1885494738817215, + 'throttle_input': 0.0, + 'timestamp': 40.63697565719485, + 'timestamp_carla': 40636, + 'timestamp_device': 40313, + 'timestamp_stream': 40.63697565719485, + 'transform': [array([-0.20636036, -0.29635987, 0.02355234]), + array([ 0.49531847, -1.18111134, 0.4222461 ])]} +---------------------- +{'AngularVelocity': array([-1.06363761, 2.04265022, -6.11834669]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.295516967773438, + 'FR_Wheel_Angle': 40.81389236450195, + 'Location': array([ -6.56509686, -21.28116226, 0.138699 ]), + 'Rotation': array([ -0.29989311, -19.31412125, -0.9180603 ]), + 'Velocity': array([-0.18085209, -0.26532853, -0.04436107]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.5458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.92294312, -1907.25292969, 16.5090332 ]), + 'frame': 9114, + 'frame_number': 9114, + 'framesequence': 9112, + 'gaze_dir': array([ 0.98058069, -0.16983138, 0.0980758 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16983138, 0.0980758 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16983138, 0.0980758 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18904386460781097, + 'throttle_input': 0.0, + 'timestamp': 40.64066365733743, + 'timestamp_carla': 40640, + 'timestamp_device': 40317, + 'timestamp_stream': 40.64066365733743, + 'transform': [array([-0.20521446, -0.2976782 , 0.02385915]), + array([ 0.49430075, -1.18858838, 0.42135346])]} +---------------------- +{'AngularVelocity': array([-0.9439196 , 1.83750331, -5.72957659]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.075613021850586, + 'FR_Wheel_Angle': 40.45089340209961, + 'Location': array([ -6.57707262, -21.28892136, 0.13782792]), + 'Rotation': array([ -0.35527909, -19.53783989, -0.84155267]), + 'Velocity': array([-0.17032619, -0.22943644, -0.03943004]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.5523681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.62457275, -1908.32373047, 16.50964355]), + 'frame': 9115, + 'frame_number': 9115, + 'framesequence': 9113, + 'gaze_dir': array([ 0.98058069, -0.17022248, 0.09739541]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17022248, 0.09739541]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17022248, 0.09739541]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18953825533390045, + 'throttle_input': 0.0, + 'timestamp': 40.64431165903807, + 'timestamp_carla': 40644, + 'timestamp_device': 40321, + 'timestamp_stream': 40.64431165903807, + 'transform': [array([-0.20402347, -0.29899779, 0.02436692]), + array([ 0.49253857, -1.19599187, 0.41987556])]} +---------------------- +{'AngularVelocity': array([-0.86741787, 1.60340679, -5.25911856]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.861671447753906, + 'FR_Wheel_Angle': 40.098541259765625, + 'Location': array([ -6.58911896, -21.29653549, 0.13706049]), + 'Rotation': array([ -0.40698364, -19.76666069, -0.76904291]), + 'Velocity': array([-0.15692152, -0.19861005, -0.03238697]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.5498046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.30337524, -1909.38195801, 16.51025391]), + 'frame': 9116, + 'frame_number': 9116, + 'framesequence': 9114, + 'gaze_dir': array([ 0.98058057, -0.17061049, 0.09671412]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17061049, 0.09671412]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17061049, 0.09671412]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18986786901950836, + 'throttle_input': 0.0, + 'timestamp': 40.6487732604146, + 'timestamp_carla': 40648, + 'timestamp_device': 40325, + 'timestamp_stream': 40.6487732604146, + 'transform': [array([-0.20527461, -0.29914793, 0.02455085]), + array([ 0.49193069, -1.20469511, 0.41932899])]} +---------------------- +{'AngularVelocity': array([-0.73209238, 1.79025984, -6.88115835]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.663373947143555, + 'FR_Wheel_Angle': 39.75632095336914, + 'Location': array([ -6.60001087, -21.30273819, 0.13663073]), + 'Rotation': array([ -0.44329292, -19.95388222, -0.7121886 ]), + 'Velocity': array([-0.20306621, -0.27499852, -0.04313162]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.548583984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.00448608, -1910.45507812, 16.51098633]), + 'frame': 9117, + 'frame_number': 9117, + 'framesequence': 9115, + 'gaze_dir': array([ 0.98058069, -0.17099613, 0.09603063]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17099613, 0.09603063]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17099613, 0.09603063]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19060030579566956, + 'throttle_input': 0.0, + 'timestamp': 40.65241006016731, + 'timestamp_carla': 40652, + 'timestamp_device': 40329, + 'timestamp_stream': 40.65241006016731, + 'transform': [array([-0.2060228 , -0.29947022, 0.02447985]), + array([ 0.4922722 , -1.21162271, 0.41953304])]} +---------------------- +{'AngularVelocity': array([-0.59690368, 1.35059404, -5.42403793]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.423295974731445, + 'FR_Wheel_Angle': 39.357940673828125, + 'Location': array([ -6.61186886, -21.31089401, 0.13578367]), + 'Rotation': array([ -0.49141842, -20.20370102, -0.65728754]), + 'Velocity': array([-0.16121507, -0.19755793, -0.03037485]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.550537109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 268.41003418, -1911.41589355, 16.51196289]), + 'frame': 9118, + 'frame_number': 9118, + 'framesequence': 9116, + 'gaze_dir': array([ 0.98058057, -0.17137866, 0.09534625]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17137866, 0.09534625]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17137866, 0.09534625]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1908566653728485, + 'throttle_input': 0.0, + 'timestamp': 40.656350657343864, + 'timestamp_carla': 40656, + 'timestamp_device': 40333, + 'timestamp_stream': 40.656350657343864, + 'transform': [array([-0.20649059, -0.30004394, 0.02419413]), + array([ 0.49339917, -1.21907079, 0.42036289])]} +---------------------- +{'AngularVelocity': array([-0.57047135, 1.04001391, -4.43564081]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.162450790405273, + 'FR_Wheel_Angle': 38.914241790771484, + 'Location': array([ -6.62354469, -21.31835175, 0.13507952]), + 'Rotation': array([ -0.53277522, -20.43691635, -0.60888672]), + 'Velocity': array([-0.13200183, -0.16073036, -0.02004306]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.552734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.90304565, -1912.36413574, 16.51281738]), + 'frame': 9119, + 'frame_number': 9119, + 'framesequence': 9117, + 'gaze_dir': array([ 0.98058057, -0.17166415, 0.09483132]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17166415, 0.09483132]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17166415, 0.09483132]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19142431020736694, + 'throttle_input': 0.0, + 'timestamp': 40.65982275828719, + 'timestamp_carla': 40659, + 'timestamp_device': 40336, + 'timestamp_stream': 40.65982275828719, + 'transform': [array([-0.20661213, -0.30071044, 0.02383096]), + array([ 0.49481302, -1.22569025, 0.42142221])]} +---------------------- +{'AngularVelocity': array([-0.39163655, 1.04249978, -5.26279449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.86738395690918, + 'FR_Wheel_Angle': 38.422325134277344, + 'Location': array([ -6.63486719, -21.32485771, 0.13490476]), + 'Rotation': array([ -0.55862063, -20.6392765 , -0.56350708]), + 'Velocity': array([-0.15504533, -0.20409516, -0.02559665]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.5615234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.46923828, -1913.13232422, 16.51367188]), + 'frame': 9120, + 'frame_number': 9120, + 'framesequence': 9118, + 'gaze_dir': array([ 0.98058069, -0.17204189, 0.09414428]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17204189, 0.09414428]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17204189, 0.09414428]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19191871583461761, + 'throttle_input': 0.0, + 'timestamp': 40.663464058190584, + 'timestamp_carla': 40663, + 'timestamp_device': 40340, + 'timestamp_stream': 40.663464058190584, + 'transform': [array([-0.20644012, -0.30156615, 0.02338867]), + array([ 0.49653423, -1.23274171, 0.42271098])]} +---------------------- +{'AngularVelocity': array([-0.32100356, 1.16334331, -5.73073578]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.602876663208008, + 'FR_Wheel_Angle': 37.988258361816406, + 'Location': array([ -6.6457324 , -21.33132553, 0.13456152]), + 'Rotation': array([ -0.58566135, -20.84346771, -0.52581781]), + 'Velocity': array([-0.17007084, -0.21758734, -0.03154413]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.57373046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.04937744, -1914.13171387, 16.5144043 ]), + 'frame': 9121, + 'frame_number': 9121, + 'framesequence': 9119, + 'gaze_dir': array([ 0.98058057, -0.17232375, 0.09362736]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17232375, 0.09362736]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17232375, 0.09362736]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19239479303359985, + 'throttle_input': 0.0, + 'timestamp': 40.66716805845499, + 'timestamp_carla': 40667, + 'timestamp_device': 40343, + 'timestamp_stream': 40.66716805845499, + 'transform': [array([-0.20598465, -0.30257079, 0.02293932]), + array([ 0.49828276, -1.24004519, 0.42402029])]} +---------------------- +{'AngularVelocity': array([-0.29063424, 0.99394828, -5.2757678 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.358171463012695, + 'FR_Wheel_Angle': 37.58341598510742, + 'Location': array([ -6.65666914, -21.33834457, 0.13404931]), + 'Rotation': array([ -0.6169368 , -21.06920815, -0.49163815]), + 'Velocity': array([-0.15703192, -0.19119388, -0.02600241]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.5859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 266.6895752 , -1914.92724609, 16.51501465]), + 'frame': 9122, + 'frame_number': 9122, + 'framesequence': 9120, + 'gaze_dir': array([ 0.98058069, -0.17269668, 0.0929377 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17269668, 0.0929377 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17269668, 0.0929377 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19288919866085052, + 'throttle_input': 0.0, + 'timestamp': 40.670644856989384, + 'timestamp_carla': 40670, + 'timestamp_device': 40347, + 'timestamp_stream': 40.670644856989384, + 'transform': [array([-0.20534129, -0.30361328, 0.02258109]), + array([ 0.49971712, -1.24702334, 0.42506456])]} +---------------------- +{'AngularVelocity': array([ 2.12293482, -1.73803425, -4.17571878]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.96532440185547, + 'FR_Wheel_Angle': 36.94523239135742, + 'Location': array([ -6.67268896, -21.34285545, 0.13436353]), + 'Rotation': array([ -0.61269528, -21.22810745, -0.51174921]), + 'Velocity': array([-0.55062854, -0.13094337, 0.02461746]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.59814453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 266.29171753, -1915.95556641, 16.51574707]), + 'frame': 9123, + 'frame_number': 9123, + 'framesequence': 9121, + 'gaze_dir': array([ 0.98058069, -0.1730672 , 0.09224589]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1730672 , 0.09224589]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1730672 , 0.09224589]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19345684349536896, + 'throttle_input': 0.0, + 'timestamp': 40.6747094579041, + 'timestamp_carla': 40674, + 'timestamp_device': 40351, + 'timestamp_stream': 40.6747094579041, + 'transform': [array([-0.20435283, -0.30493164, 0.02231056]), + array([ 0.50084406, -1.25530839, 0.42585033])]} +---------------------- +{'AngularVelocity': array([ 4.09969854, -3.34464192, -4.61534595]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.676918029785156, + 'FR_Wheel_Angle': 36.48235321044922, + 'Location': array([ -6.69918633, -21.34569931, 0.13575649]), + 'Rotation': array([ -0.55221391, -21.39637947, -0.69750953]), + 'Velocity': array([-0.71512932, -0.1310865 , 0.03250562]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.6083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 265.91671753, -1916.98376465, 16.51635742]), + 'frame': 9124, + 'frame_number': 9124, + 'framesequence': 9122, + 'gaze_dir': array([ 0.98058069, -0.17343494, 0.09155261]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17343494, 0.09155261]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17343494, 0.09155261]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19396954774856567, + 'throttle_input': 0.0, + 'timestamp': 40.678962260484695, + 'timestamp_carla': 40678, + 'timestamp_device': 40355, + 'timestamp_stream': 40.678962260484695, + 'transform': [array([-0.20312549, -0.30639037, 0.0222549 ]), + array([ 0.50117874, -1.26408732, 0.42600918])]} +---------------------- +{'AngularVelocity': array([ 3.99563479, -3.3090651 , -4.55874538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.440628051757812, + 'FR_Wheel_Angle': 36.089073181152344, + 'Location': array([ -6.73114061, -21.34893036, 0.13709988]), + 'Rotation': array([ -0.47344136, -21.60310936, -0.94564849]), + 'Velocity': array([-0.67173034, -0.12985501, 0.03513515]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.617431640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 265.53070068, -1918.04528809, 16.51708984]), + 'frame': 9125, + 'frame_number': 9125, + 'framesequence': 9123, + 'gaze_dir': array([ 0.98058057, -0.17379956, 0.09085851]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17379956, 0.09085851]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17379956, 0.09085851]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19446395337581635, + 'throttle_input': 0.0, + 'timestamp': 40.68263455852866, + 'timestamp_carla': 40682, + 'timestamp_device': 40359, + 'timestamp_stream': 40.68263455852866, + 'transform': [array([-0.20196773, -0.30768433, 0.02240702]), + array([ 0.50074166, -1.27170038, 0.42556539])]} +---------------------- +{'AngularVelocity': array([ 3.42564416, -2.84363842, -4.35235786]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.197824478149414, + 'FR_Wheel_Angle': 35.69195556640625, + 'Location': array([ -6.76081514, -21.35198975, 0.13821232]), + 'Rotation': array([ -0.40875265, -21.78935432, -1.15444934]), + 'Velocity': array([-0.65526974, -0.12654835, 0.03327925]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1167.6217041015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 265.1451416 , -1919.1204834 , 16.51794434]), + 'frame': 9126, + 'frame_number': 9126, + 'framesequence': 9124, + 'gaze_dir': array([ 0.98058069, -0.17407157, 0.09033634]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17407157, 0.09033634]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17407157, 0.09033634]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19477523863315582, + 'throttle_input': 0.0, + 'timestamp': 40.68612515926361, + 'timestamp_carla': 40685, + 'timestamp_device': 40362, + 'timestamp_stream': 40.68612515926361, + 'transform': [array([-0.20080239, -0.30893677, 0.02274188]), + array([ 0.49962148, -1.27895248, 0.42459059])]} +---------------------- \ No newline at end of file diff --git a/PythonAPI/data/trials/trial_vxvy.txt b/PythonAPI/data/trials/trial_vxvy.txt new file mode 100644 index 0000000..0261a9c --- /dev/null +++ b/PythonAPI/data/trials/trial_vxvy.txt @@ -0,0 +1,25728 @@ +{'AngularVelocity': array([ 9.78889875e-05, 1.09064684e-04, -3.19293667e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607666, -18.32991219, 0.16131546]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.14342594e-06, -1.03433848e-07, -2.54609709e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7178955078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.24194336, -1695.39807129, 16.41784668]), + 'frame': 74364, + 'frame_number': 74364, + 'framesequence': 74362, + 'gaze_dir': array([ 0.98058057, -0.0451024 , 0.19085959]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0451024 , 0.19085959]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0451024 , 0.19085959]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.67125771194696, + 'timestamp_carla': 278670, + 'timestamp_device': 278263, + 'timestamp_stream': 278.67125771194696, + 'transform': [array([ 0.00865509, -0.00365967, 0.15906644]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.87442560e-05, -5.47307354e-05, -8.42986907e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607678, -18.32991219, 0.16133121]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.77920503e-06, 3.10066383e-07, 2.94175785e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7186279296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.92321777, -1696.30737305, 16.4173584 ]), + 'frame': 74365, + 'frame_number': 74365, + 'framesequence': 74363, + 'gaze_dir': array([ 0.98058057, -0.04586505, 0.19067775]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.04586505, 0.19067775]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.04586505, 0.19067775]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.67525901272893, + 'timestamp_carla': 278674, + 'timestamp_device': 278267, + 'timestamp_stream': 278.67525901272893, + 'transform': [array([ 0.00865494, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.81885257e-05, -5.32075792e-05, 4.64657646e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607726, -18.32991219, 0.16133152]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.79096980e-06, 3.28181784e-07, 3.05014837e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.71875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.46740723, -1697.04064941, 16.41711426]), + 'frame': 74366, + 'frame_number': 74366, + 'framesequence': 74364, + 'gaze_dir': array([ 0.98058057, -0.04644093, 0.19053832]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.04644093, 0.19053832]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.04644093, 0.19053832]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.67865931242704, + 'timestamp_carla': 278677, + 'timestamp_device': 278270, + 'timestamp_stream': 278.67865931242704, + 'transform': [array([ 0.00865509, -0.00365967, 0.1590701 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.42519998e-05, -4.78051479e-05, 1.83076409e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360775 , -18.32991219, 0.16132362]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.84193424e-06, 4.27975323e-07, 4.18642652e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.718994140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.87670898, -1697.59631348, 16.41699219]), + 'frame': 74367, + 'frame_number': 74367, + 'framesequence': 74365, + 'gaze_dir': array([ 0.98058057, -0.04720229, 0.19035114]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.04720229, 0.19035114]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.04720229, 0.19035114]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.68212101235986, + 'timestamp_carla': 278681, + 'timestamp_device': 278274, + 'timestamp_stream': 278.68212101235986, + 'transform': [array([ 0.00865494, -0.00365967, 0.15907185]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 5.68356554e-05, -3.88194962e-07, -5.74575688e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607786, -18.32991219, 0.16129443]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-4.22466542e-07, -1.62052447e-06, -4.00648918e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7193603515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.41577148, -1698.33337402, 16.41687012]), + 'frame': 74368, + 'frame_number': 74368, + 'framesequence': 74366, + 'gaze_dir': array([ 0.98058057, -0.04777136, 0.19020912]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.04777136, 0.19020912]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.04777136, 0.19020912]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.6855964139104, + 'timestamp_carla': 278684, + 'timestamp_device': 278277, + 'timestamp_stream': 278.6855964139104, + 'transform': [array([ 0.00865509, -0.00365967, 0.15907395]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.08587987e-05, -4.62901844e-05, -1.67224186e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607821, -18.32991219, 0.16131771]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.80570134e-06, 4.18445552e-07, 4.08523396e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7200927734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.81719971, -1698.88623047, 16.41625977]), + 'frame': 74369, + 'frame_number': 74369, + 'framesequence': 74367, + 'gaze_dir': array([ 0.98058057, -0.04853139, 0.19001663]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.04853139, 0.19001663]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.04853139, 0.19001663]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.68952161446214, + 'timestamp_carla': 278688, + 'timestamp_device': 278281, + 'timestamp_stream': 278.68952161446214, + 'transform': [array([ 0.00865509, -0.00365967, 0.15907395]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.75721890e-06, 4.85385390e-05, 2.41249012e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607845, -18.32991219, 0.16132458]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.82451151e-06, 3.90879563e-07, 3.37153033e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.720458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 290.35107422, -1699.6270752 , 16.4161377 ]), + 'frame': 74370, + 'frame_number': 74370, + 'framesequence': 74368, + 'gaze_dir': array([ 0.98058057, -0.04948179, 0.18977137]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.04948179, 0.18977137]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.04948179, 0.18977137]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.6940489113331, + 'timestamp_carla': 278693, + 'timestamp_device': 278286, + 'timestamp_stream': 278.6940489113331, + 'transform': [array([ 0.00865509, -0.00365967, 0.15907395]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.78833756e-05, -5.14919157e-05, 6.36057393e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607893, -18.32991219, 0.16132832]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.77911681e-06, 3.25192218e-07, 2.59324559e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 291.01525879, -1700.55749512, 16.41589355]), + 'frame': 74371, + 'frame_number': 74371, + 'framesequence': 74369, + 'gaze_dir': array([ 0.98058057, -0.05004913, 0.18962252]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05004913, 0.18962252]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05004913, 0.18962252]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.69753221422434, + 'timestamp_carla': 278696, + 'timestamp_device': 278289, + 'timestamp_stream': 278.69753221422434, + 'transform': [array([ 0.00865494, -0.00365967, 0.15907544]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([9.07730573e-05, 1.02846760e-04, 3.82801630e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607893, -18.32991219, 0.16132832]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.79660685e-06, 2.30423169e-07, 1.92058840e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.720703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 291.40985107, -1701.1151123 , 16.41589355]), + 'frame': 74372, + 'frame_number': 74372, + 'framesequence': 74370, + 'gaze_dir': array([ 0.98058057, -0.05080679, 0.18942092]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05080679, 0.18942092]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05080679, 0.18942092]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.70091911405325, + 'timestamp_carla': 278700, + 'timestamp_device': 278293, + 'timestamp_stream': 278.70091911405325, + 'transform': [array([ 0.00865509, -0.00365967, 0.15907738]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.71015145e-05, 4.08748019e-05, -3.20484119e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607881, -18.32991219, 0.16131949]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.71081557e-06, 2.54906467e-07, 1.54115420e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7213134765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 291.93487549, -1701.86230469, 16.41540527]), + 'frame': 74373, + 'frame_number': 74373, + 'framesequence': 74371, + 'gaze_dir': array([ 0.98058057, -0.05137885, 0.18926656]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05137885, 0.18926656]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05137885, 0.18926656]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.70464031398296, + 'timestamp_carla': 278703, + 'timestamp_device': 278296, + 'timestamp_stream': 278.70464031398296, + 'transform': [array([ 0.00865509, -0.00365967, 0.15907738]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([9.25805653e-05, 1.08688233e-04, 7.65796102e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607893, -18.32991219, 0.16131812]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.74546778e-06, 1.89529956e-07, 1.38602642e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.721923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 292.32965088, -1702.42834473, 16.41503906]), + 'frame': 74374, + 'frame_number': 74374, + 'framesequence': 74372, + 'gaze_dir': array([ 0.98058057, -0.05213508, 0.18905966]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05213508, 0.18905966]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05213508, 0.18905966]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7080831117928, + 'timestamp_carla': 278707, + 'timestamp_device': 278300, + 'timestamp_stream': 278.7080831117928, + 'transform': [array([ 0.00865524, -0.00365967, 0.15907913]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.89380366e-05, -4.96081448e-05, 3.43869175e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607893, -18.32991219, 0.16131812]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.57135729e-06, 2.94512120e-07, 1.01619022e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72216796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 292.84936523, -1703.17919922, 16.41479492]), + 'frame': 74375, + 'frame_number': 74375, + 'framesequence': 74373, + 'gaze_dir': array([ 0.98058057, -0.05270027, 0.18890288]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05270027, 0.18890288]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05270027, 0.18890288]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.71137911453843, + 'timestamp_carla': 278710, + 'timestamp_device': 278303, + 'timestamp_stream': 278.71137911453843, + 'transform': [array([ 0.00865509, -0.00365967, 0.15908048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([9.33866322e-05, 1.07595122e-04, 6.91019721e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607893, -18.32991219, 0.16131812]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.64563254e-06, 1.46785752e-07, 3.40254701e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7222900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 293.23614502, -1703.74230957, 16.41479492]), + 'frame': 74376, + 'frame_number': 74376, + 'framesequence': 74374, + 'gaze_dir': array([ 0.98058057, -0.05326499, 0.18874444]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05326499, 0.18874444]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05326499, 0.18874444]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7146678119898, + 'timestamp_carla': 278713, + 'timestamp_device': 278306, + 'timestamp_stream': 278.7146678119898, + 'transform': [array([ 0.00865524, -0.00365967, 0.15908219]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.92715992e-05, -5.06494907e-05, -1.07250992e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607881, -18.32991219, 0.16131672]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.18941954e-06, 8.89622598e-08, -2.45427451e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7227783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 293.62133789, -1704.30651855, 16.41442871]), + 'frame': 74377, + 'frame_number': 74377, + 'framesequence': 74375, + 'gaze_dir': array([ 0.98058057, -0.05402488, 0.18852833]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05402488, 0.18852833]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05402488, 0.18852833]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7182611115277, + 'timestamp_carla': 278717, + 'timestamp_device': 278310, + 'timestamp_stream': 278.7182611115277, + 'transform': [array([ 0.00865524, -0.00365967, 0.15908219]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.69240622e-05, -1.11297368e-05, -3.26386817e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607845, -18.32991219, 0.16129062]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.05642186e-06, -4.59724099e-08, -2.33646249e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7232666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 294.13745117, -1705.06835938, 16.41418457]), + 'frame': 74378, + 'frame_number': 74378, + 'framesequence': 74376, + 'gaze_dir': array([ 0.98058057, -0.05477814, 0.18831085]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05477814, 0.18831085]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05477814, 0.18831085]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7218443118036, + 'timestamp_carla': 278721, + 'timestamp_device': 278314, + 'timestamp_stream': 278.7218443118036, + 'transform': [array([ 0.0086554 , -0.00365967, 0.15908346]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.88598971e-06, 6.34592361e-05, -2.37740392e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607857, -18.32991219, 0.16129626]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.15816885e-06, 8.79960140e-08, -1.92034131e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7235107421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 294.64654541, -1705.82641602, 16.4140625 ]), + 'frame': 74379, + 'frame_number': 74379, + 'framesequence': 74377, + 'gaze_dir': array([ 0.98058057, -0.05534108, 0.18814619]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05534108, 0.18814619]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05534108, 0.18814619]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.725433614105, + 'timestamp_carla': 278724, + 'timestamp_device': 278317, + 'timestamp_stream': 278.725433614105, + 'transform': [array([ 0.0086554 , -0.00365967, 0.15908346]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.90624155e-05, -5.10572936e-05, 2.31636278e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607845, -18.32991219, 0.16130272]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.75635034e-06, 4.01117120e-07, 3.31316958e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 295.02545166, -1706.39489746, 16.41394043]), + 'frame': 74380, + 'frame_number': 74380, + 'framesequence': 74378, + 'gaze_dir': array([ 0.98058057, -0.05609281, 0.18792345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05609281, 0.18792345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05609281, 0.18792345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7289157137275, + 'timestamp_carla': 278728, + 'timestamp_device': 278321, + 'timestamp_stream': 278.7289157137275, + 'transform': [array([ 0.00865555, -0.00365967, 0.15908471]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.27056146e-05, 4.45275982e-05, 5.20072199e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607905, -18.32991219, 0.16130123]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.76056721e-06, 3.28329605e-07, 2.47766235e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.723876953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 295.52923584, -1707.15649414, 16.41381836]), + 'frame': 74381, + 'frame_number': 74381, + 'framesequence': 74379, + 'gaze_dir': array([ 0.98058057, -0.05665458, 0.18775485]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05665458, 0.18775485]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05665458, 0.18775485]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7322981134057, + 'timestamp_carla': 278731, + 'timestamp_device': 278324, + 'timestamp_stream': 278.7322981134057, + 'transform': [array([ 0.00865555, -0.00365967, 0.15908471]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.20230297e-05, 4.57538554e-05, 5.05405467e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607941, -18.32991219, 0.16130362]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.78063703e-06, 3.29922187e-07, 2.35046231e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72412109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 295.90420532, -1707.72753906, 16.41357422]), + 'frame': 74382, + 'frame_number': 74382, + 'framesequence': 74380, + 'gaze_dir': array([ 0.98058057, -0.05722158, 0.18758284]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05722158, 0.18758284]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05722158, 0.18758284]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7356640137732, + 'timestamp_carla': 278734, + 'timestamp_device': 278327, + 'timestamp_stream': 278.7356640137732, + 'transform': [array([ 0.0086557 , -0.00365967, 0.15908596]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.75804518e-05, -5.64944958e-06, -5.97764824e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03607965, -18.32991219, 0.16129509]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.59970215e-06, 1.84850066e-07, 1.11025969e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72412109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 296.28118896, -1708.30566406, 16.41357422]), + 'frame': 74383, + 'frame_number': 74383, + 'framesequence': 74381, + 'gaze_dir': array([ 0.98058057, -0.05815397, 0.18729588]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05815397, 0.18729588]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05815397, 0.18729588]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7399830110371, + 'timestamp_carla': 278739, + 'timestamp_device': 278332, + 'timestamp_stream': 278.7399830110371, + 'transform': [array([ 0.0086557 , -0.00365967, 0.15908596]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.68999026e-05, -4.32581546e-05, 8.98621124e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608 , -18.32991219, 0.1612936 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.74056696e-06, 3.10307371e-07, 2.46842857e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7247314453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 296.89813232, -1709.25976562, 16.41308594]), + 'frame': 74384, + 'frame_number': 74384, + 'framesequence': 74382, + 'gaze_dir': array([ 0.98058057, -0.05890227, 0.18706189]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05890227, 0.18706189]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05890227, 0.18706189]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.74443931132555, + 'timestamp_carla': 278743, + 'timestamp_device': 278336, + 'timestamp_stream': 278.74443931132555, + 'transform': [array([ 0.0086557 , -0.00365967, 0.15908596]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.47985224e-05, -4.15079012e-05, 5.47122276e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608 , -18.32991219, 0.1612936 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.49333584e-06, 3.05694982e-07, 7.39192401e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7249755859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 297.39044189, -1710.02893066, 16.41296387]), + 'frame': 74385, + 'frame_number': 74385, + 'framesequence': 74383, + 'gaze_dir': array([ 0.98058057, -0.05946716, 0.18688308]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05946716, 0.18688308]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05946716, 0.18688308]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.74784341454506, + 'timestamp_carla': 278747, + 'timestamp_device': 278339, + 'timestamp_stream': 278.74784341454506, + 'transform': [array([ 0.0086557 , -0.00365967, 0.15908596]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.42411222e-05, -4.24783902e-05, 6.96649067e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608012, -18.32991219, 0.16128264]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.64240293e-06, 3.57647650e-07, 2.21983748e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7252197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 297.76049805, -1710.61132812, 16.41259766]), + 'frame': 74386, + 'frame_number': 74386, + 'framesequence': 74384, + 'gaze_dir': array([ 0.98058057, -0.0602138 , 0.18664385]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0602138 , 0.18664385]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0602138 , 0.18664385]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7509948126972, + 'timestamp_carla': 278750, + 'timestamp_device': 278343, + 'timestamp_stream': 278.7509948126972, + 'transform': [array([ 0.00865585, -0.00365967, 0.15908742]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.44836481e-05, -4.60354313e-05, -4.37373274e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608048, -18.32991219, 0.16127667]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.60738556e-06, 3.11156043e-07, 1.90222723e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7254638671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 298.24743652, -1711.38391113, 16.41247559]), + 'frame': 74387, + 'frame_number': 74387, + 'framesequence': 74385, + 'gaze_dir': array([ 0.98058057, -0.06114718, 0.18634015]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06114718, 0.18634015]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06114718, 0.18634015]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.756408713758, + 'timestamp_carla': 278755, + 'timestamp_device': 278348, + 'timestamp_stream': 278.756408713758, + 'transform': [array([ 0.0086557 , -0.00365967, 0.1590825 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.81131465e-05, -1.00317620e-05, 3.85936715e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608072, -18.32991219, 0.1612775 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.83211352e-06, 2.74284957e-07, 2.91320583e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7257080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 298.85266113, -1712.35375977, 16.41235352]), + 'frame': 74388, + 'frame_number': 74388, + 'framesequence': 74386, + 'gaze_dir': array([ 0.98058057, -0.06189164, 0.18609422]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06189164, 0.18609422]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06189164, 0.18609422]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.76010201126337, + 'timestamp_carla': 278759, + 'timestamp_device': 278352, + 'timestamp_stream': 278.76010201126337, + 'transform': [array([ 0.0086557 , -0.00365967, 0.1590825 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.01357138e-05, -5.29893550e-05, -2.92750769e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608096, -18.32991219, 0.16127415]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.47335424e-06, 3.08785815e-07, 8.84120673e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7254638671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 299.33251953, -1713.1307373 , 16.41210938]), + 'frame': 74389, + 'frame_number': 74389, + 'framesequence': 74387, + 'gaze_dir': array([ 0.98058057, -0.06244791, 0.1859083 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06244791, 0.1859083 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06244791, 0.1859083 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7635355144739, + 'timestamp_carla': 278762, + 'timestamp_device': 278355, + 'timestamp_stream': 278.7635355144739, + 'transform': [array([ 0.0086557 , -0.00365967, 0.1590825 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.44336001e-05, -5.85936141e-05, -3.92454069e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608096, -18.32991219, 0.16127415]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.37229164e-06, 2.07911938e-07, -6.04938614e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7257080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 299.6895752 , -1713.71313477, 16.41186523]), + 'frame': 74390, + 'frame_number': 74390, + 'framesequence': 74388, + 'gaze_dir': array([ 0.98058057, -0.06319064, 0.18565716]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06319064, 0.18565716]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06319064, 0.18565716]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.76675871387124, + 'timestamp_carla': 278766, + 'timestamp_device': 278359, + 'timestamp_stream': 278.76675871387124, + 'transform': [array([ 0.00865585, -0.00365967, 0.15908395]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.51737033e-05, -5.90695090e-05, -8.46605417e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608096, -18.32991219, 0.16127415]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.22476796e-06, 1.00733011e-07, -2.23143114e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7259521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 300.1640625 , -1714.4934082 , 16.41149902]), + 'frame': 74391, + 'frame_number': 74391, + 'framesequence': 74389, + 'gaze_dir': array([ 0.98058057, -0.06411903, 0.18533859]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06411903, 0.18533859]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06411903, 0.18533859]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.77243151143193, + 'timestamp_carla': 278771, + 'timestamp_device': 278364, + 'timestamp_stream': 278.77243151143193, + 'transform': [array([ 0.0086557 , -0.00365967, 0.15907791]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.92428779e-05, 3.37443926e-05, -1.23861412e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608072, -18.32991219, 0.16126582]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.30787895e-06, 1.04376809e-07, -1.67892926e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7259521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 300.75369263, -1715.47277832, 16.41162109]), + 'frame': 74392, + 'frame_number': 74392, + 'framesequence': 74390, + 'gaze_dir': array([ 0.98058057, -0.06485946, 0.18508075]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06485946, 0.18508075]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06485946, 0.18508075]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.77595841139555, + 'timestamp_carla': 278775, + 'timestamp_device': 278368, + 'timestamp_stream': 278.77595841139555, + 'transform': [array([ 0.00865585, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.24755417e-05, -1.54919599e-05, 3.19615907e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608072, -18.32991219, 0.16126533]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.66124629e-06, 2.55065970e-07, 1.57940420e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7257080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 301.22103882, -1716.25732422, 16.41137695]), + 'frame': 74393, + 'frame_number': 74393, + 'framesequence': 74391, + 'gaze_dir': array([ 0.98058057, -0.0654127 , 0.18488596]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0654127 , 0.18488596]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0654127 , 0.18488596]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.77935311198235, + 'timestamp_carla': 278778, + 'timestamp_device': 278371, + 'timestamp_stream': 278.77935311198235, + 'transform': [array([ 0.00865585, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.29314714e-05, -5.37324340e-05, 4.65641421e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608096, -18.32991219, 0.16126002]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.72197553e-06, 3.27457656e-07, 2.27386161e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7259521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 301.56872559, -1716.84545898, 16.41113281]), + 'frame': 74394, + 'frame_number': 74394, + 'framesequence': 74392, + 'gaze_dir': array([ 0.98058057, -0.06597099, 0.1846875 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06597099, 0.1846875 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06597099, 0.1846875 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7829016111791, + 'timestamp_carla': 278782, + 'timestamp_device': 278374, + 'timestamp_stream': 278.7829016111791, + 'transform': [array([ 0.00865601, -0.00365967, 0.15908048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([9.21536630e-05, 1.07664542e-04, 8.23851138e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608096, -18.32991219, 0.16126002]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.68659891e-06, 1.61016359e-07, 7.49551182e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.726318359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 301.91821289, -1717.44055176, 16.4107666 ]), + 'frame': 74395, + 'frame_number': 74395, + 'framesequence': 74393, + 'gaze_dir': array([ 0.98058057, -0.06689449, 0.18435501]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06689449, 0.18435501]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06689449, 0.18435501]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7868938110769, + 'timestamp_carla': 278786, + 'timestamp_device': 278379, + 'timestamp_stream': 278.7868938110769, + 'transform': [array([ 0.00865601, -0.00365967, 0.15908048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.68997994e-05, 4.16854818e-05, 4.99720556e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608119, -18.32991219, 0.16124809]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.90791626e-06, 3.53248311e-07, 3.44718923e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 302.49304199, -1718.42871094, 16.4107666 ]), + 'frame': 74396, + 'frame_number': 74396, + 'framesequence': 74394, + 'gaze_dir': array([ 0.98058057, -0.06763097, 0.1840861 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06763097, 0.1840861 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06763097, 0.1840861 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.7909597121179, + 'timestamp_carla': 278790, + 'timestamp_device': 278383, + 'timestamp_stream': 278.7909597121179, + 'transform': [array([ 0.00865601, -0.00365967, 0.15908048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.10194976e-05, 3.94510462e-05, -5.21991842e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608167, -18.32991219, 0.16123542]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 1.88568606e-06, -8.63408161e-07, -2.15354026e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 302.94866943, -1719.22009277, 16.4107666 ]), + 'frame': 74397, + 'frame_number': 74397, + 'framesequence': 74395, + 'gaze_dir': array([ 0.98058057, -0.06873085, 0.1836783 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06873085, 0.1836783 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06873085, 0.1836783 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.79742131382227, + 'timestamp_carla': 278796, + 'timestamp_device': 278389, + 'timestamp_stream': 278.79742131382227, + 'transform': [array([ 0.00865585, -0.00365967, 0.15906994]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.68278377e-05, -5.58739048e-05, -3.24309298e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608203, -18.32991219, 0.16124351]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.54143856e-06, 2.64584088e-07, 1.00481258e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72705078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 303.62451172, -1720.4074707 , 16.41027832]), + 'frame': 74398, + 'frame_number': 74398, + 'framesequence': 74396, + 'gaze_dir': array([ 0.98058057, -0.06946461, 0.18340205]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06946461, 0.18340205]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06946461, 0.18340205]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.80074871331453, + 'timestamp_carla': 278800, + 'timestamp_device': 278393, + 'timestamp_stream': 278.80074871331453, + 'transform': [array([ 0.00865601, -0.00365967, 0.15907189]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.45126971e-05, -5.22522314e-05, 4.81394181e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16124557]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.66899246e-06, 3.25546125e-07, 1.87670943e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.725830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 304.07196045, -1721.20361328, 16.41052246]), + 'frame': 74399, + 'frame_number': 74399, + 'framesequence': 74397, + 'gaze_dir': array([ 0.98058057, -0.0700184 , 0.18319134]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0700184 , 0.18319134]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0700184 , 0.18319134]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.80474201217294, + 'timestamp_carla': 278804, + 'timestamp_device': 278396, + 'timestamp_stream': 278.80474201217294, + 'transform': [array([ 0.00865601, -0.00365967, 0.15907189]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([8.70961303e-05, 1.03915263e-04, 2.26674757e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.16124317]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.77420872e-06, 2.24765387e-07, 1.78999413e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7264404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 304.40826416, -1721.80615234, 16.41003418]), + 'frame': 74400, + 'frame_number': 74400, + 'framesequence': 74398, + 'gaze_dir': array([ 0.98058057, -0.07075019, 0.18290997]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07075019, 0.18290997]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07075019, 0.18290997]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8083433136344, + 'timestamp_carla': 278807, + 'timestamp_device': 278400, + 'timestamp_stream': 278.8083433136344, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907341]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.00080678e-05, -5.94316880e-05, 1.51895904e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16123791]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.59482862e-06, 2.62124217e-07, 1.02659993e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7266845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 304.85040283, -1722.60522461, 16.40966797]), + 'frame': 74401, + 'frame_number': 74401, + 'framesequence': 74399, + 'gaze_dir': array([ 0.98058057, -0.07129691, 0.18269756]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07129691, 0.18269756]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07129691, 0.18269756]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8117517121136, + 'timestamp_carla': 278811, + 'timestamp_device': 278403, + 'timestamp_stream': 278.8117517121136, + 'transform': [array([ 0.00865601, -0.00365967, 0.1590746 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.02670737e-05, -6.14158926e-05, 6.77285470e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16123725]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.65667790e-06, 3.76641964e-07, 2.12422747e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7269287109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 305.17907715, -1723.20410156, 16.40966797]), + 'frame': 74402, + 'frame_number': 74402, + 'framesequence': 74400, + 'gaze_dir': array([ 0.98058057, -0.07202671, 0.18241107]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07202671, 0.18241107]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07202671, 0.18241107]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8152250126004, + 'timestamp_carla': 278814, + 'timestamp_device': 278407, + 'timestamp_stream': 278.8152250126004, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907612]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.97695146e-05, -6.20098799e-05, 5.89786168e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16123725]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.58182285e-06, 3.39427487e-07, 1.33363443e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.726806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 305.61553955, -1724.00622559, 16.40991211]), + 'frame': 74403, + 'frame_number': 74403, + 'framesequence': 74401, + 'gaze_dir': array([ 0.98058057, -0.07275538, 0.18212168]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07275538, 0.18212168]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07275538, 0.18212168]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.81898591294885, + 'timestamp_carla': 278818, + 'timestamp_device': 278411, + 'timestamp_stream': 278.81898591294885, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907612]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.02994808e-05, -6.12170479e-05, -1.68917367e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608239, -18.32991219, 0.16123562]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.34108324e-06, 2.64412961e-07, -5.21861548e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 306.04891968, -1724.80993652, 16.40966797]), + 'frame': 74404, + 'frame_number': 74404, + 'framesequence': 74402, + 'gaze_dir': array([ 0.98058057, -0.07348289, 0.18182936]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07348289, 0.18182936]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07348289, 0.18182936]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8230713121593, + 'timestamp_carla': 278822, + 'timestamp_device': 278415, + 'timestamp_stream': 278.8230713121593, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907612]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.85661585e-05, -5.76565544e-05, -6.67541087e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608227, -18.32991219, 0.1612334 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.30192085e-06, 1.73568253e-07, -1.25524108e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7275390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 306.47903442, -1725.61560059, 16.40942383]), + 'frame': 74405, + 'frame_number': 74405, + 'framesequence': 74403, + 'gaze_dir': array([ 0.98058057, -0.07402636, 0.18160878]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07402636, 0.18160878]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07402636, 0.18160878]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8262454122305, + 'timestamp_carla': 278825, + 'timestamp_device': 278418, + 'timestamp_stream': 278.8262454122305, + 'transform': [array([ 0.00865601, -0.00365967, 0.15907735]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.53677484e-05, 1.01822530e-04, -2.88654547e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608215, -18.32991219, 0.16123149]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.57505439e-06, 1.55081509e-07, 1.45560789e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7275390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 306.79864502, -1726.21936035, 16.40942383]), + 'frame': 74406, + 'frame_number': 74406, + 'framesequence': 74404, + 'gaze_dir': array([ 0.98058057, -0.0745747 , 0.18138431]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0745747 , 0.18138431]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0745747 , 0.18138431]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8296444118023, + 'timestamp_carla': 278828, + 'timestamp_device': 278421, + 'timestamp_stream': 278.8296444118023, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907872]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.67170285e-05, -5.42754242e-05, 2.21821850e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608215, -18.32991219, 0.16122906]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.45419209e-06, 3.10976759e-07, 4.11767651e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 307.11968994, -1726.8302002 , 16.40930176]), + 'frame': 74407, + 'frame_number': 74407, + 'framesequence': 74405, + 'gaze_dir': array([ 0.98058057, -0.07529924, 0.18108472]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07529924, 0.18108472]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07529924, 0.18108472]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.83356261253357, + 'timestamp_carla': 278832, + 'timestamp_device': 278425, + 'timestamp_stream': 278.83356261253357, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907872]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.26591856e-05, 3.55363081e-05, 2.72848524e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608227, -18.32991219, 0.16122749]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.67322752e-06, 2.46238187e-07, 1.01402220e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5308837890625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 307.50741577, -1727.65783691, 16.60253906]), + 'frame': 74408, + 'frame_number': 74408, + 'framesequence': 74406, + 'gaze_dir': array([ 0.98058057, -0.07602257, 0.18078224]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07602257, 0.18078224]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07602257, 0.18078224]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.83728831261396, + 'timestamp_carla': 278836, + 'timestamp_device': 278429, + 'timestamp_stream': 278.83728831261396, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907872]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.64460463e-05, -5.28115161e-05, 1.44851356e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608215, -18.32991219, 0.16122513]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.53481425e-06, 2.78367651e-07, 7.10570821e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5308837890625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 307.92605591, -1728.46923828, 16.60253906]), + 'frame': 74409, + 'frame_number': 74409, + 'framesequence': 74407, + 'gaze_dir': array([ 0.98058057, -0.0765629 , 0.18055408]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0765629 , 0.18055408]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0765629 , 0.18055408]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8406407125294, + 'timestamp_carla': 278839, + 'timestamp_device': 278432, + 'timestamp_stream': 278.8406407125294, + 'transform': [array([ 0.00865616, -0.00365967, 0.15907872]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.33491296e-05, -9.98596988e-06, -1.49524897e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608215, -18.32991219, 0.16121456]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.41979137e-06, 1.09452522e-07, -1.56391579e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5308837890625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 308.23718262, -1729.07727051, 16.60253906]), + 'frame': 74410, + 'frame_number': 74410, + 'framesequence': 74408, + 'gaze_dir': array([ 0.98058057, -0.07710805, 0.18032195]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07710805, 0.18032195]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07710805, 0.18032195]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8439295142889, + 'timestamp_carla': 278843, + 'timestamp_device': 278435, + 'timestamp_stream': 278.8439295142889, + 'transform': [array([ 0.00865631, -0.00365967, 0.15908006]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.42718920e-05, -5.37794258e-05, -1.34651543e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608203, -18.32991219, 0.16120476]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([5.02866669e-06, 4.19369883e-07, 5.69297350e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5308837890625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 308.54956055, -1729.69250488, 16.60253906]), + 'frame': 74411, + 'frame_number': 74411, + 'framesequence': 74409, + 'gaze_dir': array([ 0.98058057, -0.07782833, 0.18001224]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07782833, 0.18001224]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07782833, 0.18001224]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8473909124732, + 'timestamp_carla': 278846, + 'timestamp_device': 278439, + 'timestamp_stream': 278.8473909124732, + 'transform': [array([ 0.00865631, -0.00365967, 0.15908006]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([9.08536094e-05, 1.06729764e-04, 4.89270235e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608215, -18.32991219, 0.16121204]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([5.02359126e-06, 3.47982848e-07, 4.45724319e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5308837890625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 308.96008301, -1730.50805664, 16.60266113]), + 'frame': 74412, + 'frame_number': 74412, + 'framesequence': 74410, + 'gaze_dir': array([ 0.98058057, -0.07854735, 0.17969967]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07854735, 0.17969967]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07854735, 0.17969967]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.85072061419487, + 'timestamp_carla': 278850, + 'timestamp_device': 278443, + 'timestamp_stream': 278.85072061419487, + 'transform': [array([ 0.00865646, -0.00365967, 0.15908124]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([9.11396273e-05, 1.04542894e-04, 2.85791685e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16121353]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.90382308e-06, 2.48049616e-07, 2.90164520e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.531005859375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 309.36737061, -1731.32519531, 16.60253906]), + 'frame': 74413, + 'frame_number': 74413, + 'framesequence': 74411, + 'gaze_dir': array([ 0.98058057, -0.07998163, 0.17906591]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07998163, 0.17906591]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07998163, 0.17906591]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.85960411280394, + 'timestamp_carla': 278858, + 'timestamp_device': 278451, + 'timestamp_stream': 278.85960411280394, + 'transform': [array([ 0.00865631, -0.00365967, 0.15904541]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.33915266e-05, -1.56234473e-05, 3.91052737e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.16121373]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.80357767e-06, 2.85066193e-07, 2.80556269e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.53125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 310.17211914, -1732.96435547, 16.60253906]), + 'frame': 74414, + 'frame_number': 74414, + 'framesequence': 74412, + 'gaze_dir': array([ 0.98058057, -0.08069686, 0.17874472]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08069686, 0.17874472]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08069686, 0.17874472]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.863075312227, + 'timestamp_carla': 278862, + 'timestamp_device': 278455, + 'timestamp_stream': 278.863075312227, + 'transform': [array([ 0.00865646, -0.00365967, 0.15904839]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.91714454e-05, -6.11595970e-05, 6.10384802e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360831 , -18.32991219, 0.16121329]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.71221028e-06, 3.22872069e-07, 2.09142047e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.527587890625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 310.56890869, -1733.78662109, 16.60241699]), + 'frame': 74415, + 'frame_number': 74415, + 'framesequence': 74413, + 'gaze_dir': array([ 0.98058057, -0.08123107, 0.17850259]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08123107, 0.17850259]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08123107, 0.17850259]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8666474111378, + 'timestamp_carla': 278865, + 'timestamp_device': 278458, + 'timestamp_stream': 278.8666474111378, + 'transform': [array([ 0.00865631, -0.00365967, 0.15905064]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.09580739e-05, 3.55639240e-05, -2.58096270e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16120765]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 3.71719239e-06, -5.26895718e-08, -5.99337160e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52783203125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 310.86410522, -1734.40258789, 16.60253906]), + 'frame': 74416, + 'frame_number': 74416, + 'framesequence': 74414, + 'gaze_dir': array([ 0.98058057, -0.08194404, 0.17817642]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08194404, 0.17817642]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08194404, 0.17817642]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.87017861381173, + 'timestamp_carla': 278869, + 'timestamp_device': 278462, + 'timestamp_stream': 278.87017861381173, + 'transform': [array([ 0.00865646, -0.00365967, 0.15905328]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.18167443e-05, 3.54768090e-05, -6.71481644e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16120765]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.43837371e-06, 1.88751144e-07, -5.12191145e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.528076171875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 311.25579834, -1735.22729492, 16.60253906]), + 'frame': 74417, + 'frame_number': 74417, + 'framesequence': 74415, + 'gaze_dir': array([ 0.98058057, -0.08265569, 0.17784742]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08265569, 0.17784742]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08265569, 0.17784742]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8741564117372, + 'timestamp_carla': 278873, + 'timestamp_device': 278466, + 'timestamp_stream': 278.8741564117372, + 'transform': [array([ 0.00865631, -0.00365967, 0.15905476]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.11973638e-05, 3.53513278e-05, 2.89598717e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360831 , -18.32991219, 0.16120598]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.59663079e-06, 3.14344646e-07, 1.06511900e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5284423828125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 311.64428711, -1736.05358887, 16.60241699]), + 'frame': 74418, + 'frame_number': 74418, + 'framesequence': 74416, + 'gaze_dir': array([ 0.98058057, -0.08336603, 0.17751555]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08336603, 0.17751555]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08336603, 0.17751555]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.87811091169715, + 'timestamp_carla': 278877, + 'timestamp_device': 278470, + 'timestamp_stream': 278.87811091169715, + 'transform': [array([ 0.00865646, -0.00365967, 0.15905666]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.84166958e-05, -5.80647866e-05, 2.63014613e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360831 , -18.32991219, 0.16120598]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.54717792e-06, 2.50603762e-07, 5.12728657e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5284423828125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 312.02929688, -1736.88146973, 16.60253906]), + 'frame': 74419, + 'frame_number': 74419, + 'framesequence': 74417, + 'gaze_dir': array([ 0.98058057, -0.08407503, 0.17718086]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08407503, 0.17718086]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08407503, 0.17718086]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8820672146976, + 'timestamp_carla': 278881, + 'timestamp_device': 278474, + 'timestamp_stream': 278.8820672146976, + 'transform': [array([ 0.00865631, -0.00365967, 0.15905796]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.86439520e-05, 1.03533064e-04, -3.45032760e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360831 , -18.32991219, 0.16120361]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.51629512e-06, 1.53683359e-07, -2.58035798e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52880859375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 312.41113281, -1737.71081543, 16.60241699]), + 'frame': 74420, + 'frame_number': 74420, + 'framesequence': 74418, + 'gaze_dir': array([ 0.98058057, -0.08478809, 0.17684074]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08478809, 0.17684074]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08478809, 0.17684074]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.88602451235056, + 'timestamp_carla': 278885, + 'timestamp_device': 278478, + 'timestamp_stream': 278.88602451235056, + 'transform': [array([ 0.00865646, -0.00365967, 0.15905969]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.97190548e-05, 1.04200684e-04, -1.16666195e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360831 , -18.32991219, 0.16120361]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.28766680e-06, 1.33283899e-08, -2.46154930e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52880859375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 312.79244995, -1738.5480957 , 16.60253906]), + 'frame': 74421, + 'frame_number': 74421, + 'framesequence': 74419, + 'gaze_dir': array([ 0.98058057, -0.08531658, 0.17658637]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08531658, 0.17658637]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08531658, 0.17658637]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8895138129592, + 'timestamp_carla': 278888, + 'timestamp_device': 278481, + 'timestamp_stream': 278.8895138129592, + 'transform': [array([ 0.00865631, -0.00365967, 0.15906143]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.42790915e-05, -5.69451186e-05, 3.46999265e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608334, -18.32991219, 0.16118652]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.75421302e-06, 3.31097965e-07, 2.82983499e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.529052734375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 313.07339478, -1739.1706543 , 16.60241699]), + 'frame': 74422, + 'frame_number': 74422, + 'framesequence': 74420, + 'gaze_dir': array([ 0.98058057, -0.08602186, 0.17624389]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08602186, 0.17624389]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08602186, 0.17624389]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.89301071316004, + 'timestamp_carla': 278892, + 'timestamp_device': 278485, + 'timestamp_stream': 278.89301071316004, + 'transform': [array([ 0.00865646, -0.00365967, 0.15906353]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.41966986e-05, -5.75754966e-05, -7.02245870e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608382, -18.32991219, 0.16118979]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.42096734e-06, 1.86208638e-07, -2.47847802e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.529296875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 313.44604492, -1740.00415039, 16.60241699]), + 'frame': 74423, + 'frame_number': 74423, + 'framesequence': 74421, + 'gaze_dir': array([ 0.98058057, -0.08654857, 0.17598583]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08654857, 0.17598583]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08654857, 0.17598583]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.89649971202016, + 'timestamp_carla': 278895, + 'timestamp_device': 278488, + 'timestamp_stream': 278.89649971202016, + 'transform': [array([ 0.00865631, -0.00365967, 0.1590651 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.60393530e-05, -5.91337994e-05, -2.28413171e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608394, -18.32991219, 0.16119084]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.38631287e-06, 2.59432710e-07, -1.75051864e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5294189453125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 313.72259521, -1740.62866211, 16.60253906]), + 'frame': 74424, + 'frame_number': 74424, + 'framesequence': 74422, + 'gaze_dir': array([ 0.98058057, -0.08725143, 0.17563844]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08725143, 0.17563844]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08725143, 0.17563844]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.8999933116138, + 'timestamp_carla': 278899, + 'timestamp_device': 278492, + 'timestamp_stream': 278.8999933116138, + 'transform': [array([ 0.00865646, -0.00365967, 0.159067 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.47748607e-05, -5.82483444e-05, 4.41653185e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608406, -18.32991219, 0.16119187]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.58298700e-06, 3.10614695e-07, 1.18463046e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5296630859375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 314.0894165 , -1741.46484375, 16.60241699]), + 'frame': 74425, + 'frame_number': 74425, + 'framesequence': 74423, + 'gaze_dir': array([ 0.98058057, -0.08778168, 0.17537402]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08778168, 0.17537402]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08778168, 0.17537402]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.903852712363, + 'timestamp_carla': 278903, + 'timestamp_device': 278495, + 'timestamp_stream': 278.903852712363, + 'transform': [array([ 0.00865646, -0.00365967, 0.159067 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.97856420e-05, -5.57777748e-05, 4.58273774e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608394, -18.32991219, 0.16119026]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.61628861e-06, 3.10031453e-07, 1.41276279e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52978515625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 314.36437988, -1742.09765625, 16.60253906]), + 'frame': 74426, + 'frame_number': 74426, + 'framesequence': 74424, + 'gaze_dir': array([ 0.98058057, -0.08848208, 0.17502169]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08848208, 0.17502169]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08848208, 0.17502169]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9074150137603, + 'timestamp_carla': 278906, + 'timestamp_device': 278499, + 'timestamp_stream': 278.9074150137603, + 'transform': [array([ 0.00865662, -0.00365967, 0.15906869]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.15316426e-05, -5.66339295e-05, -1.31646914e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360837 , -18.32991219, 0.16118534]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.51161532e-06, 2.20261271e-07, 2.86155046e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52978515625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 314.72528076, -1742.9362793 , 16.60253906]), + 'frame': 74427, + 'frame_number': 74427, + 'framesequence': 74425, + 'gaze_dir': array([ 0.98058057, -0.08918107, 0.17466655]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08918107, 0.17466655]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08918107, 0.17466655]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9107824116945, + 'timestamp_carla': 278910, + 'timestamp_device': 278503, + 'timestamp_stream': 278.9107824116945, + 'transform': [array([ 0.00865646, -0.00365967, 0.15907001]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([8.81673332e-05, 9.87441454e-05, 1.69811585e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360837 , -18.32991219, 0.16118534]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.71609383e-06, 1.97637121e-07, 1.21256999e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52978515625, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 315.08282471, -1743.77648926, 16.60266113]), + 'frame': 74428, + 'frame_number': 74428, + 'framesequence': 74426, + 'gaze_dir': array([ 0.98058057, -0.08970305, 0.17439906]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08970305, 0.17439906]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08970305, 0.17439906]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9144476130605, + 'timestamp_carla': 278913, + 'timestamp_device': 278506, + 'timestamp_stream': 278.9144476130605, + 'transform': [array([ 0.00865662, -0.00365967, 0.1590714 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.98245099e-05, -6.42271843e-05, 5.79918321e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360837 , -18.32991219, 0.16118534]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.66695292e-06, 2.84784477e-07, 1.47732542e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.530029296875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 315.34814453, -1744.40588379, 16.60253906]), + 'frame': 74429, + 'frame_number': 74429, + 'framesequence': 74427, + 'gaze_dir': array([ 0.98058057, -0.09022423, 0.17413002]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09022423, 0.17413002]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09022423, 0.17413002]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.91771171242, + 'timestamp_carla': 278917, + 'timestamp_device': 278509, + 'timestamp_stream': 278.91771171242, + 'transform': [array([ 0.00865646, -0.00365967, 0.1590727 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.49539439e-05, -5.88435323e-05, 4.78131255e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608346, -18.32991219, 0.16117969]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.66550227e-06, 2.86614522e-07, 1.55122107e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5301513671875, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 315.61154175, -1745.03601074, 16.60266113]), + 'frame': 74430, + 'frame_number': 74430, + 'framesequence': 74428, + 'gaze_dir': array([ 0.98058057, -0.09091964, 0.17376792]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09091964, 0.17376792]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09091964, 0.17376792]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9213642142713, + 'timestamp_carla': 278920, + 'timestamp_device': 278513, + 'timestamp_stream': 278.9213642142713, + 'transform': [array([ 0.00865662, -0.00365967, 0.15907392]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.61295193e-05, 9.75177609e-05, -4.46865045e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608322, -18.32991219, 0.16117634]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.67000518e-06, 1.50250273e-07, 8.65315742e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5303955078125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 315.96069336, -1745.87963867, 16.60241699]), + 'frame': 74431, + 'frame_number': 74431, + 'framesequence': 74429, + 'gaze_dir': array([ 0.98058057, -0.0916136 , 0.17340307]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.0916136 , 0.17340307]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.0916136 , 0.17340307]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.92527951300144, + 'timestamp_carla': 278924, + 'timestamp_device': 278517, + 'timestamp_stream': 278.92527951300144, + 'transform': [array([ 0.00865662, -0.00365967, 0.15907392]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.02825717e-05, -1.79887811e-05, -1.87043469e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608322, -18.32991219, 0.16117272]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.68176540e-06, 2.20162320e-07, 1.73876921e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.530517578125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 316.30648804, -1746.72460938, 16.60253906]), + 'frame': 74432, + 'frame_number': 74432, + 'framesequence': 74430, + 'gaze_dir': array([ 0.98058057, -0.09231137, 0.17303261]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09231137, 0.17303261]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09231137, 0.17303261]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9295627139509, + 'timestamp_carla': 278928, + 'timestamp_device': 278521, + 'timestamp_stream': 278.9295627139509, + 'transform': [array([ 0.00865662, -0.00365967, 0.15907392]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.48153878e-05, -5.56993473e-05, -1.24486451e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360831 , -18.32991219, 0.16117115]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.08217784e-06, 1.54168802e-07, -2.47223390e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.530517578125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 316.65142822, -1747.57751465, 16.60253906]), + 'frame': 74433, + 'frame_number': 74433, + 'framesequence': 74431, + 'gaze_dir': array([ 0.98058057, -0.09300239, 0.17266218]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09300239, 0.17266218]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09300239, 0.17266218]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9330752119422, + 'timestamp_carla': 278932, + 'timestamp_device': 278525, + 'timestamp_stream': 278.9330752119422, + 'transform': [array([ 0.00865662, -0.00365967, 0.15907392]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.59872499e-05, -5.43423848e-05, -4.60140143e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16117011]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.38612187e-06, 1.77940819e-07, -7.61054544e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.530517578125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 316.99038696, -1748.42529297, 16.60253906]), + 'frame': 74434, + 'frame_number': 74434, + 'framesequence': 74432, + 'gaze_dir': array([ 0.98058057, -0.09351835, 0.17238328]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09351835, 0.17238328]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09351835, 0.17238328]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9365420117974, + 'timestamp_carla': 278935, + 'timestamp_device': 278528, + 'timestamp_stream': 278.9365420117974, + 'transform': [array([ 0.00865677, -0.00365967, 0.15907525]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.54088004e-05, -5.44346185e-05, -2.89398855e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.16116881]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.45911428e-06, 1.95801249e-07, -2.07456196e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.530517578125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 317.24176025, -1749.0604248 , 16.60253906]), + 'frame': 74435, + 'frame_number': 74435, + 'framesequence': 74433, + 'gaze_dir': array([ 0.98058057, -0.09420676, 0.17200804]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09420676, 0.17200804]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09420676, 0.17200804]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.93991761282086, + 'timestamp_carla': 278939, + 'timestamp_device': 278532, + 'timestamp_stream': 278.93991761282086, + 'transform': [array([ 0.00865677, -0.00365967, 0.15907525]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([8.83212997e-05, 1.04880113e-04, 2.82585688e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.1611634 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.70734904e-06, 2.71185996e-07, 1.69331703e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.530517578125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 317.57476807, -1749.91052246, 16.60266113]), + 'frame': 74436, + 'frame_number': 74436, + 'framesequence': 74434, + 'gaze_dir': array([ 0.98058057, -0.09489366, 0.17163004]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09489366, 0.17163004]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09489366, 0.17163004]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.94481211155653, + 'timestamp_carla': 278944, + 'timestamp_device': 278536, + 'timestamp_stream': 278.94481211155653, + 'transform': [array([ 0.00865692, -0.00365967, 0.15907314]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([8.83023895e-05, 1.03653569e-04, 1.41186291e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16116077]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.70559553e-06, 2.60584045e-07, 1.67725244e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5306396484375, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 317.90447998, -1750.76196289, 16.60241699]), + 'frame': 74437, + 'frame_number': 74437, + 'framesequence': 74435, + 'gaze_dir': array([ 0.98058057, -0.09557904, 0.17124932]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09557904, 0.17124932]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09557904, 0.17124932]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.94810881465673, + 'timestamp_carla': 278947, + 'timestamp_device': 278540, + 'timestamp_stream': 278.94810881465673, + 'transform': [array([ 0.00865677, -0.00365967, 0.15907417]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([8.48212949e-05, 9.77669770e-05, 1.50801611e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16116077]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.71262956e-06, 1.82111975e-07, 1.06735526e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5303955078125, + 'focus_actor_name': 'Plane28', + 'focus_actor_pt': array([ 318.23065186, -1751.61474609, 16.60241699]), + 'frame': 74438, + 'frame_number': 74438, + 'framesequence': 74436, + 'gaze_dir': array([ 0.98058057, -0.09609077, 0.17096269]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09609077, 0.17096269]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09609077, 0.17096269]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9514734111726, + 'timestamp_carla': 278950, + 'timestamp_device': 278543, + 'timestamp_stream': 278.9514734111726, + 'transform': [array([ 0.00865692, -0.00365967, 0.15907556]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.84935808e-05, -6.11316427e-05, 3.43540137e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16116077]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.52569429e-06, 3.17738142e-07, 9.03539913e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7298583984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 318.5090332 , -1752.23974609, 16.40698242]), + 'frame': 74439, + 'frame_number': 74439, + 'framesequence': 74437, + 'gaze_dir': array([ 0.98058057, -0.09677868, 0.17057423]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09677868, 0.17057423]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09677868, 0.17057423]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9551179111004, + 'timestamp_carla': 278954, + 'timestamp_device': 278547, + 'timestamp_stream': 278.9551179111004, + 'transform': [array([ 0.00865692, -0.00365967, 0.15907556]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.95606291e-05, -6.21982326e-05, 1.82992210e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16115756]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.47213642e-06, 3.18953539e-07, 6.42865489e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72998046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 318.83178711, -1753.10144043, 16.40698242]), + 'frame': 74440, + 'frame_number': 74440, + 'framesequence': 74438, + 'gaze_dir': array([ 0.98058057, -0.09745982, 0.17018597]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09745982, 0.17018597]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09745982, 0.17018597]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9594170115888, + 'timestamp_carla': 278958, + 'timestamp_device': 278551, + 'timestamp_stream': 278.9594170115888, + 'transform': [array([ 0.00865692, -0.00365967, 0.15907556]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.16460605e-05, -6.54688774e-05, 4.44345034e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.16115627]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.62977914e-06, 2.90974270e-07, 1.34095812e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 319.14868164, -1753.95788574, 16.40673828]), + 'frame': 74441, + 'frame_number': 74441, + 'framesequence': 74439, + 'gaze_dir': array([ 0.98058057, -0.09813942, 0.16979498]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09813942, 0.16979498]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09813942, 0.16979498]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9632557146251, + 'timestamp_carla': 278962, + 'timestamp_device': 278555, + 'timestamp_stream': 278.9632557146251, + 'transform': [array([ 0.00865692, -0.00365967, 0.15907556]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.03695410e-05, -6.38142374e-05, -4.70514436e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.1611544 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.53250004e-06, 2.95408540e-07, 9.77002346e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 319.46209717, -1754.81567383, 16.40673828]), + 'frame': 74442, + 'frame_number': 74442, + 'framesequence': 74440, + 'gaze_dir': array([ 0.98058057, -0.09864679, 0.16950072]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09864679, 0.16950072]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09864679, 0.16950072]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9666154123843, + 'timestamp_carla': 278965, + 'timestamp_device': 278558, + 'timestamp_stream': 278.9666154123843, + 'transform': [array([ 0.00865707, -0.00365967, 0.15907681]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.97604378e-05, -6.32406955e-05, -6.85083933e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.1611544 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.21043478e-06, 2.01915384e-07, -1.58472612e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 319.69433594, -1755.45812988, 16.40673828]), + 'frame': 74443, + 'frame_number': 74443, + 'framesequence': 74441, + 'gaze_dir': array([ 0.98058057, -0.09932362, 0.16910499]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09932362, 0.16910499]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09932362, 0.16910499]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9700549133122, + 'timestamp_carla': 278969, + 'timestamp_device': 278562, + 'timestamp_stream': 278.9700549133122, + 'transform': [array([ 0.00865707, -0.00365967, 0.15907681]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.91333594e-05, -6.29309434e-05, 3.95640257e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.16114937]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.59856801e-06, 3.56165685e-07, 1.72000146e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7301025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.0017395 , -1756.31799316, 16.40698242]), + 'frame': 74444, + 'frame_number': 74444, + 'framesequence': 74442, + 'gaze_dir': array([ 0.98058057, -0.09999887, 0.16870658]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09999887, 0.16870658]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09999887, 0.16870658]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.97441041469574, + 'timestamp_carla': 278973, + 'timestamp_device': 278566, + 'timestamp_stream': 278.97441041469574, + 'transform': [array([ 0.00865707, -0.00365967, 0.15907681]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.66244663e-05, 1.00023048e-04, -1.83187822e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16114715]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.60013280e-06, 1.73724246e-07, 4.18687014e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.30578613, -1757.17907715, 16.40686035]), + 'frame': 74445, + 'frame_number': 74445, + 'framesequence': 74443, + 'gaze_dir': array([ 0.98058057, -0.10067252, 0.16830547]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10067252, 0.16830547]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10067252, 0.16830547]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.97815361246467, + 'timestamp_carla': 278977, + 'timestamp_device': 278570, + 'timestamp_stream': 278.97815361246467, + 'transform': [array([ 0.00865707, -0.00365967, 0.15907681]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.96289470e-05, -5.20823669e-05, 4.70127475e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608263, -18.32991219, 0.16114475]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.57269107e-06, 3.40680117e-07, 1.35722192e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7301025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.60629272, -1758.04138184, 16.40698242]), + 'frame': 74446, + 'frame_number': 74446, + 'framesequence': 74444, + 'gaze_dir': array([ 0.98058057, -0.10117542, 0.16800362]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10117542, 0.16800362]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10117542, 0.16800362]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.981443811208, + 'timestamp_carla': 278980, + 'timestamp_device': 278573, + 'timestamp_stream': 278.981443811208, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907808]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.01753350e-05, -5.30834805e-05, -3.66392896e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16113362]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.55548297e-06, 2.78382799e-07, 1.24749378e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.82888794, -1758.68725586, 16.40686035]), + 'frame': 74447, + 'frame_number': 74447, + 'framesequence': 74445, + 'gaze_dir': array([ 0.98058057, -0.10168254, 0.16769719]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10168254, 0.16769719]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10168254, 0.16769719]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.98471861332655, + 'timestamp_carla': 278984, + 'timestamp_device': 278576, + 'timestamp_stream': 278.98471861332655, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907808]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.63086971e-05, 9.87029125e-05, -1.66274765e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.16113228]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.26006955e-06, -2.45950638e-08, -2.56997999e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.73046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.05181885, -1759.34033203, 16.40673828]), + 'frame': 74448, + 'frame_number': 74448, + 'framesequence': 74446, + 'gaze_dir': array([ 0.98058057, -0.10235215, 0.16728933]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10235215, 0.16728933]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10235215, 0.16728933]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.98857981339097, + 'timestamp_carla': 278987, + 'timestamp_device': 278580, + 'timestamp_stream': 278.98857981339097, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907808]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.74152075e-05, -6.03068002e-05, 5.74047867e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16113056]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.52351060e-06, 3.15335342e-07, 1.04982522e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7303466796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.34368896, -1760.20568848, 16.40686035]), + 'frame': 74449, + 'frame_number': 74449, + 'framesequence': 74447, + 'gaze_dir': array([ 0.98058057, -0.102852 , 0.16698249]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.102852 , 0.16698249]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.102852 , 0.16698249]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9919172115624, + 'timestamp_carla': 278991, + 'timestamp_device': 278583, + 'timestamp_stream': 278.9919172115624, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907808]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.12499854e-05, 3.38671962e-05, 4.68939930e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608286, -18.32991219, 0.16112658]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.69762608e-06, 3.47192383e-07, 1.95095068e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.73046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.55981445, -1760.85375977, 16.40673828]), + 'frame': 74450, + 'frame_number': 74450, + 'framesequence': 74448, + 'gaze_dir': array([ 0.98058057, -0.10351874, 0.16656998]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10351874, 0.16656998]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10351874, 0.16656998]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.9950489141047, + 'timestamp_carla': 278994, + 'timestamp_device': 278587, + 'timestamp_stream': 278.9950489141047, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.88304140e-05, -5.93724144e-05, -2.98959526e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608274, -18.32991219, 0.16111839]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 3.57844851e-06, -1.49358527e-07, -7.04458507e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7303466796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.84567261, -1761.72106934, 16.40686035]), + 'frame': 74451, + 'frame_number': 74451, + 'framesequence': 74449, + 'gaze_dir': array([ 0.98058057, -0.10402152, 0.16625647]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10402152, 0.16625647]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10402152, 0.16625647]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 278.99827821180224, + 'timestamp_carla': 278997, + 'timestamp_device': 278590, + 'timestamp_stream': 278.99827821180224, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.28455174e-05, 3.33431453e-05, -5.45810337e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360831 , -18.32991219, 0.16111244]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.63511333e-06, 2.21539523e-07, 1.08124899e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7303466796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.05938721, -1762.37719727, 16.40698242]), + 'frame': 74452, + 'frame_number': 74452, + 'framesequence': 74450, + 'gaze_dir': array([ 0.98058057, -0.10468534, 0.16583928]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10468534, 0.16583928]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10468534, 0.16583928]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0018636137247, + 'timestamp_carla': 279001, + 'timestamp_device': 278594, + 'timestamp_stream': 279.0018636137247, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.34865797e-05, -5.36341795e-05, 2.12029704e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608346, -18.32991219, 0.16111244]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.66810752e-06, 3.66414895e-07, 2.39540110e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7305908203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.33917236, -1763.24645996, 16.40686035]), + 'frame': 74453, + 'frame_number': 74453, + 'framesequence': 74451, + 'gaze_dir': array([ 0.98058057, -0.10518085, 0.16552547]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10518085, 0.16552547]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10518085, 0.16552547]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.00547021254897, + 'timestamp_carla': 279004, + 'timestamp_device': 278597, + 'timestamp_stream': 279.00547021254897, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.54595647e-05, -1.11052714e-05, 2.27535040e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608406, -18.32991219, 0.1611068 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.75895331e-06, 3.56883959e-07, 3.20297026e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.73046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.54614258, -1763.89746094, 16.40686035]), + 'frame': 74454, + 'frame_number': 74454, + 'framesequence': 74452, + 'gaze_dir': array([ 0.98058057, -0.10567542, 0.16521016]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10567542, 0.16521016]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10567542, 0.16521016]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0086926110089, + 'timestamp_carla': 279008, + 'timestamp_device': 278600, + 'timestamp_stream': 279.0086926110089, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.57038841e-05, -5.85572270e-05, 5.68970790e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608441, -18.32991219, 0.16110954]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.77263939e-06, 3.58481174e-07, 2.85736285e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.75119019, -1764.54919434, 16.40710449]), + 'frame': 74455, + 'frame_number': 74455, + 'framesequence': 74453, + 'gaze_dir': array([ 0.98058057, -0.10633504, 0.16478637]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10633504, 0.16478637]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10633504, 0.16478637]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0120009146631, + 'timestamp_carla': 279011, + 'timestamp_device': 278604, + 'timestamp_stream': 279.0120009146631, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.72394885e-05, 9.80811237e-05, -1.75050701e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608441, -18.32991219, 0.16110665]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.77797585e-06, 2.01358915e-07, 1.88096252e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.73046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.02224731, -1765.42114258, 16.40686035]), + 'frame': 74456, + 'frame_number': 74456, + 'framesequence': 74454, + 'gaze_dir': array([ 0.98058057, -0.10683241, 0.16446435]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10683241, 0.16446435]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10683241, 0.16446435]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0153664126992, + 'timestamp_carla': 279014, + 'timestamp_device': 278607, + 'timestamp_stream': 279.0153664126992, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.75575252e-05, -6.09163071e-05, -3.22871483e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608429, -18.32991219, 0.1610944 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 3.81018504e-06, -7.39493373e-08, -4.62774246e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7303466796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.22479248, -1766.08093262, 16.40698242]), + 'frame': 74457, + 'frame_number': 74457, + 'framesequence': 74455, + 'gaze_dir': array([ 0.98058057, -0.10748906, 0.16403595]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10748906, 0.16403595]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10748906, 0.16403595]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.01933551207185, + 'timestamp_carla': 279018, + 'timestamp_device': 278611, + 'timestamp_stream': 279.01933551207185, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.48845531e-05, -5.92731958e-05, 4.34395361e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608441, -18.32991219, 0.16109851]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.81891902e-06, 4.22265146e-07, 3.82871687e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.48968506, -1766.95483398, 16.40710449]), + 'frame': 74458, + 'frame_number': 74458, + 'framesequence': 74456, + 'gaze_dir': array([ 0.98058057, -0.10814399, 0.16360493]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10814399, 0.16360493]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10814399, 0.16360493]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0233271121979, + 'timestamp_carla': 279022, + 'timestamp_device': 278615, + 'timestamp_stream': 279.0233271121979, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.92270883e-05, -6.27911286e-05, 3.34084433e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608489, -18.32991219, 0.16110188]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.69961651e-06, 3.02658862e-07, 2.01127928e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.75115967, -1767.82983398, 16.40710449]), + 'frame': 74459, + 'frame_number': 74459, + 'framesequence': 74457, + 'gaze_dir': array([ 0.98058057, -0.10863279, 0.16328077]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10863279, 0.16328077]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10863279, 0.16328077]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0265263132751, + 'timestamp_carla': 279025, + 'timestamp_device': 278618, + 'timestamp_stream': 279.0265263132751, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.73768778e-05, -6.03349654e-05, -5.55388965e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608501, -18.32991219, 0.16110007]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.37637800e-06, 2.50479189e-07, -9.96966355e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7301025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.94439697, -1768.48498535, 16.40722656]), + 'frame': 74460, + 'frame_number': 74460, + 'framesequence': 74458, + 'gaze_dir': array([ 0.98058057, -0.10912062, 0.16295514]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10912062, 0.16295514]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10912062, 0.16295514]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0297214128077, + 'timestamp_carla': 279029, + 'timestamp_device': 278621, + 'timestamp_stream': 279.0297214128077, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.87695296e-05, 3.57817844e-05, -3.81462968e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608537, -18.32991219, 0.16109408]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.7421081e-06, 3.5848467e-07, 2.6699563e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7301025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.13574219, -1769.14086914, 16.40722656]), + 'frame': 74461, + 'frame_number': 74461, + 'framesequence': 74459, + 'gaze_dir': array([ 0.98058057, -0.10977121, 0.16251761]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10977121, 0.16251761]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10977121, 0.16251761]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.03316071256995, + 'timestamp_carla': 279032, + 'timestamp_device': 278625, + 'timestamp_stream': 279.03316071256995, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.25636354e-05, -1.45496906e-05, 3.76322134e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608584, -18.32991219, 0.16109271]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.75206889e-06, 2.82539986e-07, 2.41579517e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7301025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.38842773, -1770.01831055, 16.40722656]), + 'frame': 74462, + 'frame_number': 74462, + 'framesequence': 74460, + 'gaze_dir': array([ 0.98058057, -0.11042499, 0.1620741 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11042499, 0.1620741 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11042499, 0.1620741 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.03691421449184, + 'timestamp_carla': 279036, + 'timestamp_device': 278629, + 'timestamp_stream': 279.03691421449184, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.76466293e-05, 1.00980775e-04, -1.03012361e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608584, -18.32991219, 0.16109271]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.60219781e-06, 1.75436725e-07, 4.09195927e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7301025390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.63949585, -1770.90356445, 16.40722656]), + 'frame': 74463, + 'frame_number': 74463, + 'framesequence': 74461, + 'gaze_dir': array([ 0.98058057, -0.11107204, 0.16163135]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11107204, 0.16163135]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11107204, 0.16163135]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0408303141594, + 'timestamp_carla': 279040, + 'timestamp_device': 278633, + 'timestamp_stream': 279.0408303141594, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([8.84744222e-05, 1.02413826e-04, 4.83341694e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608596, -18.32991219, 0.16108748]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.87185071e-06, 2.43739919e-07, 2.50697602e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72998046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.8850708 , -1771.78320312, 16.40734863]), + 'frame': 74464, + 'frame_number': 74464, + 'framesequence': 74462, + 'gaze_dir': array([ 0.98058057, -0.11155494, 0.16129844]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11155494, 0.16129844]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11155494, 0.16129844]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.04440431296825, + 'timestamp_carla': 279043, + 'timestamp_device': 278636, + 'timestamp_stream': 279.04440431296825, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.53927314e-05, -5.63749563e-05, -4.41277416e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608561, -18.32991219, 0.16107643]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 2.52998893e-06, -5.23952735e-07, -1.54727965e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7298583984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.06652832, -1772.44177246, 16.4074707 ]), + 'frame': 74465, + 'frame_number': 74465, + 'framesequence': 74463, + 'gaze_dir': array([ 0.98058057, -0.11203685, 0.16096409]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11203685, 0.16096409]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11203685, 0.16096409]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.04758471250534, + 'timestamp_carla': 279046, + 'timestamp_device': 278639, + 'timestamp_stream': 279.04758471250534, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.53482135e-05, -5.59693945e-05, 5.00322926e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360862 , -18.32991219, 0.16107738]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.72886495e-06, 3.47532335e-07, 2.48691824e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7296142578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.24597168, -1773.10095215, 16.40771484]), + 'frame': 74466, + 'frame_number': 74466, + 'framesequence': 74464, + 'gaze_dir': array([ 0.98058057, -0.11267944, 0.16051491]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11267944, 0.16051491]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11267944, 0.16051491]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0507228113711, + 'timestamp_carla': 279050, + 'timestamp_device': 278643, + 'timestamp_stream': 279.0507228113711, + 'transform': [array([ 0.00865738, -0.00365967, 0.15907928]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.71034063e-05, 1.01850033e-04, -1.02746037e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608656, -18.32991219, 0.16107719]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.41899510e-06, 8.50600159e-08, -1.02396363e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.729736328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.48284912, -1773.98291016, 16.40759277]), + 'frame': 74467, + 'frame_number': 74467, + 'framesequence': 74465, + 'gaze_dir': array([ 0.98058057, -0.11332025, 0.16006316]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11332025, 0.16006316]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11332025, 0.16006316]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0556799136102, + 'timestamp_carla': 279055, + 'timestamp_device': 278647, + 'timestamp_stream': 279.0556799136102, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907536]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.84194596e-05, 1.02957412e-04, -2.10403229e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360862 , -18.32991219, 0.16107425]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.56017915e-06, 2.21313670e-07, 5.58497777e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.71612549, -1774.86572266, 16.40783691]), + 'frame': 74468, + 'frame_number': 74468, + 'framesequence': 74466, + 'gaze_dir': array([ 0.98058057, -0.11395924, 0.15960886]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11395924, 0.15960886]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11395924, 0.15960886]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.05961741134524, + 'timestamp_carla': 279058, + 'timestamp_device': 278651, + 'timestamp_stream': 279.05961741134524, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907536]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.41421980e-05, -5.93517652e-05, 4.49326450e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608644, -18.32991219, 0.16107281]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.63617744e-06, 2.76126656e-07, 1.27589636e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.729248046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.94586182, -1775.74951172, 16.40771484]), + 'frame': 74469, + 'frame_number': 74469, + 'framesequence': 74467, + 'gaze_dir': array([ 0.98058057, -0.11459641, 0.159152 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11459641, 0.159152 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11459641, 0.159152 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0635110139847, + 'timestamp_carla': 279062, + 'timestamp_device': 278655, + 'timestamp_stream': 279.0635110139847, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907536]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.17874494e-05, 3.02223161e-05, 5.27508064e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360862 , -18.32991219, 0.16106972]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.69970291e-06, 3.16327203e-07, 1.67846025e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.17205811, -1776.63427734, 16.40795898]), + 'frame': 74470, + 'frame_number': 74470, + 'framesequence': 74468, + 'gaze_dir': array([ 0.98058057, -0.11523659, 0.15868907]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11523659, 0.15868907]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11523659, 0.15868907]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.06705571338534, + 'timestamp_carla': 279066, + 'timestamp_device': 278659, + 'timestamp_stream': 279.06705571338534, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907536]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.57801907e-05, -6.30287759e-05, 5.99975124e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608644, -18.32991219, 0.16106483]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.67045902e-06, 3.80140250e-07, 2.32128048e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.39645386, -1777.52661133, 16.40795898]), + 'frame': 74471, + 'frame_number': 74471, + 'framesequence': 74469, + 'gaze_dir': array([ 0.98058057, -0.11602454, 0.1581139 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11602454, 0.1581139 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11602454, 0.1581139 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0712642110884, + 'timestamp_carla': 279070, + 'timestamp_device': 278664, + 'timestamp_stream': 279.0712642110884, + 'transform': [array([ 0.00865707, -0.00365967, 0.15907407]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.70564191e-05, -6.46186454e-05, 6.86270141e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360862 , -18.32991219, 0.16106381]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.67956306e-06, 3.31642809e-07, 1.92068706e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7288818359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.6685791 , -1778.62988281, 16.40808105]), + 'frame': 74472, + 'frame_number': 74472, + 'framesequence': 74470, + 'gaze_dir': array([ 0.98058057, -0.11665571, 0.15764879]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11665571, 0.15764879]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11665571, 0.15764879]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0763458125293, + 'timestamp_carla': 279075, + 'timestamp_device': 278668, + 'timestamp_stream': 279.0763458125293, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.52114390e-05, 9.29106900e-05, -9.02575437e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360862 , -18.32991219, 0.16106381]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.41057364e-06, 8.69156764e-08, -1.14537652e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.728759765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.88327026, -1779.51745605, 16.40808105]), + 'frame': 74473, + 'frame_number': 74473, + 'framesequence': 74471, + 'gaze_dir': array([ 0.98058057, -0.11728982, 0.15717758]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11728982, 0.15717758]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11728982, 0.15717758]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.08015041425824, + 'timestamp_carla': 279079, + 'timestamp_device': 278672, + 'timestamp_stream': 279.08015041425824, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.28036074e-05, -1.92863899e-05, -8.90675949e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360862 , -18.32991219, 0.16106381]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.19823436e-06, 1.36768207e-07, -1.82280652e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.728271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.0960083 , -1780.41259766, 16.40820312]), + 'frame': 74474, + 'frame_number': 74474, + 'framesequence': 74472, + 'gaze_dir': array([ 0.98058057, -0.11775937, 0.15682611]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11775937, 0.15682611]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11775937, 0.15682611]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.08371391147375, + 'timestamp_carla': 279083, + 'timestamp_device': 278675, + 'timestamp_stream': 279.08371391147375, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.61710442e-05, -6.39435893e-05, 6.39420364e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.0360862 , -18.32991219, 0.16106381]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.62027720e-06, 3.57717511e-07, 1.75365014e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72802734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.25158691, -1781.07788086, 16.40844727]), + 'frame': 74475, + 'frame_number': 74475, + 'framesequence': 74473, + 'gaze_dir': array([ 0.98058057, -0.11838538, 0.15635407]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11838538, 0.15635407]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11838538, 0.15635407]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0873389132321, + 'timestamp_carla': 279086, + 'timestamp_device': 278679, + 'timestamp_stream': 279.0873389132321, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.04823329e-05, -6.55611875e-05, -1.20270738e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608656, -18.32991219, 0.16105576]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.30961381e-06, 1.50820696e-07, -1.00173733e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.45648193, -1781.96777344, 16.40869141]), + 'frame': 74476, + 'frame_number': 74476, + 'framesequence': 74474, + 'gaze_dir': array([ 0.98058057, -0.11900951, 0.15587956]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11900951, 0.15587956]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11900951, 0.15587956]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.0910278111696, + 'timestamp_carla': 279090, + 'timestamp_device': 278683, + 'timestamp_stream': 279.0910278111696, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.51721899e-05, -5.96040809e-05, -1.34536748e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608668, -18.32991219, 0.16104779]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.66257097e-06, 3.73990048e-07, 2.65281240e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.65786743, -1782.85839844, 16.40869141]), + 'frame': 74477, + 'frame_number': 74477, + 'framesequence': 74475, + 'gaze_dir': array([ 0.98058057, -0.11947517, 0.15552293]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11947517, 0.15552293]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11947517, 0.15552293]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.09450421109796, + 'timestamp_carla': 279093, + 'timestamp_device': 278686, + 'timestamp_stream': 279.09450421109796, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.64625035e-05, 9.82435595e-05, -1.85004993e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608704, -18.32991219, 0.16104622]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.87248417e-06, 2.44840038e-07, 2.95307225e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.80618286, -1783.52526855, 16.40869141]), + 'frame': 74478, + 'frame_number': 74478, + 'framesequence': 74476, + 'gaze_dir': array([ 0.98058057, -0.12009596, 0.15504405]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12009596, 0.15504405]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12009596, 0.15504405]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.09782641381025, + 'timestamp_carla': 279097, + 'timestamp_device': 278690, + 'timestamp_stream': 279.09782641381025, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.02218429e-05, -5.37601190e-05, 5.20580450e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608751, -18.32991219, 0.16105019]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.59068679e-06, 3.09688033e-07, 1.47997926e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7275390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.00128174, -1784.4173584 , 16.40881348]), + 'frame': 74479, + 'frame_number': 74479, + 'framesequence': 74477, + 'gaze_dir': array([ 0.98058057, -0.12056383, 0.15468051]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12056383, 0.15468051]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12056383, 0.15468051]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.101416811347, + 'timestamp_carla': 279100, + 'timestamp_device': 278693, + 'timestamp_stream': 279.101416811347, + 'transform': [array([ 0.00865723, -0.00365967, 0.15907048]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.43618264e-05, -1.60723503e-05, 3.73494487e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608751, -18.32991219, 0.16104987]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.69679935e-06, 2.30373118e-07, 1.61125601e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.1463623 , -1785.09204102, 16.40917969]), + 'frame': 74480, + 'frame_number': 74480, + 'framesequence': 74478, + 'gaze_dir': array([ 0.98058057, -0.12118125, 0.15419729]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12118125, 0.15419729]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12118125, 0.15419729]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.10587311163545, + 'timestamp_carla': 279105, + 'timestamp_device': 278697, + 'timestamp_stream': 279.10587311163545, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.39314354e-05, -5.81292734e-05, -1.24871769e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608716, -18.32991219, 0.16104718]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.30457749e-06, 1.36165184e-07, -1.11502668e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.33526611, -1785.98547363, 16.40917969]), + 'frame': 74481, + 'frame_number': 74481, + 'framesequence': 74479, + 'gaze_dir': array([ 0.98058057, -0.12179673, 0.1537116 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12179673, 0.1537116 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12179673, 0.1537116 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1090777143836, + 'timestamp_carla': 279108, + 'timestamp_device': 278701, + 'timestamp_stream': 279.1090777143836, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.28411622e-05, -5.58051979e-05, -1.14940451e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608704, -18.32991219, 0.16104576]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([ 4.34963022e-06, 1.45101211e-07, -7.84055519e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7271728515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.52056885, -1786.87976074, 16.40905762]), + 'frame': 74482, + 'frame_number': 74482, + 'framesequence': 74480, + 'gaze_dir': array([ 0.98058057, -0.12225588, 0.15334666]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12225588, 0.15334666]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12225588, 0.15334666]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.11243161186576, + 'timestamp_carla': 279111, + 'timestamp_device': 278704, + 'timestamp_stream': 279.11243161186576, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.61757845e-05, -6.00255626e-05, 5.21973007e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608763, -18.32991219, 0.16103996]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.70131636e-06, 2.96832297e-07, 2.16223911e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.727294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.65686035, -1787.54907227, 16.40905762]), + 'frame': 74483, + 'frame_number': 74483, + 'framesequence': 74481, + 'gaze_dir': array([ 0.98058057, -0.12286796, 0.15285668]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12286796, 0.15285668]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12286796, 0.15285668]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.11613911390305, + 'timestamp_carla': 279115, + 'timestamp_device': 278708, + 'timestamp_stream': 279.11613911390305, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.34722388e-05, -5.91448988e-05, 4.42127060e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03608787, -18.32991219, 0.16104232]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.60457750e-06, 3.52947978e-07, 1.72324348e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.726806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.83584595, -1788.44458008, 16.40942383]), + 'frame': 74484, + 'frame_number': 74484, + 'framesequence': 74482, + 'gaze_dir': array([ 0.98058057, -0.12332456, 0.15248853]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12332456, 0.15248853]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12332456, 0.15248853]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1198275126517, + 'timestamp_carla': 279119, + 'timestamp_device': 278711, + 'timestamp_stream': 279.1198275126517, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.45874102e-05, -5.81926106e-05, -1.32809632e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020504364743828773, + 'FR_Wheel_Angle': 0.020508261397480965, + 'Location': array([ 1.03608787, -18.32991219, 0.16103855]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([4.48720266e-06, 2.25921383e-07, 1.74341912e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.726806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.96746826, -1789.11499023, 16.40942383]), + 'frame': 74485, + 'frame_number': 74485, + 'framesequence': 74483, + 'gaze_dir': array([ 0.98058057, -0.12393783, 0.15199052]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12393783, 0.15199052]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12393783, 0.15199052]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1235282123089, + 'timestamp_carla': 279122, + 'timestamp_device': 278715, + 'timestamp_stream': 279.1235282123089, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00101902, -0.00120938, 0.00050048]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020503943786025047, + 'FR_Wheel_Angle': 0.02050658129155636, + 'Location': array([ 1.03602064, -18.32999802, 0.16103363]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-6.70856214e-04, -9.26465378e-04, -4.46987142e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7266845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.14154053, -1790.01843262, 16.4095459 ]), + 'frame': 74486, + 'frame_number': 74486, + 'framesequence': 74484, + 'gaze_dir': array([ 0.98058057, -0.12439182, 0.15161917]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12439182, 0.15161917]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12439182, 0.15161917]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1267143115401, + 'timestamp_carla': 279126, + 'timestamp_device': 278718, + 'timestamp_stream': 279.1267143115401, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.51536893e-04, -6.92840622e-05, 2.87311501e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050388976931572, + 'FR_Wheel_Angle': 0.020507564768195152, + 'Location': array([ 1.03597963, -18.33005142, 0.16103287]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.00075836, -0.00104364, 0.00022094]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.2684021 , -1790.68969727, 16.40979004]), + 'frame': 74487, + 'frame_number': 74487, + 'framesequence': 74485, + 'gaze_dir': array([ 0.98058057, -0.12484472, 0.15124647]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12484472, 0.15124647]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12484472, 0.15124647]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1298831142485, + 'timestamp_carla': 279129, + 'timestamp_device': 278721, + 'timestamp_stream': 279.1298831142485, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.002298 , 0.00189546, 0.00020458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020503666251897812, + 'FR_Wheel_Angle': 0.020507672801613808, + 'Location': array([ 1.03599596, -18.33003998, 0.16102801]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-1.14921015e-03, -1.50966772e-03, 9.69266839e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.726318359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.39324951, -1791.36132812, 16.40991211]), + 'frame': 74488, + 'frame_number': 74488, + 'framesequence': 74486, + 'gaze_dir': array([ 0.98058057, -0.12544838, 0.15074617]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12544838, 0.15074617]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12544838, 0.15074617]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1336757130921, + 'timestamp_carla': 279133, + 'timestamp_device': 278725, + 'timestamp_stream': 279.1336757130921, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.002056 , -0.0015163 , 0.00059273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020503785461187363, + 'FR_Wheel_Angle': 0.02050746977329254, + 'Location': array([ 1.0360105 , -18.33002853, 0.16102859]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([0.00107869, 0.00115539, 0.00021899]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7264404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.55712891, -1792.25976562, 16.40979004]), + 'frame': 74489, + 'frame_number': 74489, + 'framesequence': 74487, + 'gaze_dir': array([ 0.98058057, -0.12605001, 0.15024345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12605001, 0.15024345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12605001, 0.15024345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.13721211254597, + 'timestamp_carla': 279136, + 'timestamp_device': 278729, + 'timestamp_stream': 279.13721211254597, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00447356, 0.00391138, 0.00044008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050216868519783, + 'FR_Wheel_Angle': 0.020505091175436974, + 'Location': array([ 1.03593206, -18.33012581, 0.16103008]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.00376388, -0.00461543, 0.00035294]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7261962890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.71725464, -1793.15869141, 16.41015625]), + 'frame': 74490, + 'frame_number': 74490, + 'framesequence': 74488, + 'gaze_dir': array([ 0.98058057, -0.12650336, 0.14986193]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12650336, 0.14986193]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12650336, 0.14986193]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1405735127628, + 'timestamp_carla': 279139, + 'timestamp_device': 278732, + 'timestamp_stream': 279.1405735127628, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00208729, -0.00167121, 0.00027208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050270512700081, + 'FR_Wheel_Angle': 0.020505543798208237, + 'Location': array([ 1.03573382, -18.33036613, 0.16102996]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.00282781, -0.00350106, 0.00026491]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7259521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.8359375 , -1793.83862305, 16.41027832]), + 'frame': 74491, + 'frame_number': 74491, + 'framesequence': 74489, + 'gaze_dir': array([ 0.98058057, -0.12710147, 0.14935501]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12710147, 0.14935501]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12710147, 0.14935501]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.14403741434216, + 'timestamp_carla': 279143, + 'timestamp_device': 278736, + 'timestamp_stream': 279.14403741434216, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00151623, -0.00126145, 0.00056775]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050245925784111, + 'FR_Wheel_Angle': 0.020505186170339584, + 'Location': array([ 1.03557169, -18.33056641, 0.16103283]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.00325552, -0.00401197, 0.00025607]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7259521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.98983765, -1794.73876953, 16.41027832]), + 'frame': 74492, + 'frame_number': 74492, + 'framesequence': 74490, + 'gaze_dir': array([ 0.98058057, -0.12754758, 0.14897422]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12754758, 0.14897422]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12754758, 0.14897422]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.14754471182823, + 'timestamp_carla': 279146, + 'timestamp_device': 278739, + 'timestamp_stream': 279.14754471182823, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00219368, -0.00181059, 0.000516 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02050034888088703, + 'FR_Wheel_Angle': 0.02050582505762577, + 'Location': array([ 1.03529978, -18.33089447, 0.16103984]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-4.48490726e-03, -5.47617674e-03, 6.68382636e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.725830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.1026001 , -1795.41247559, 16.41052246]), + 'frame': 74493, + 'frame_number': 74493, + 'framesequence': 74491, + 'gaze_dir': array([ 0.98058057, -0.12799254, 0.1485921 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12799254, 0.1485921 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12799254, 0.1485921 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1507303118706, + 'timestamp_carla': 279150, + 'timestamp_device': 278742, + 'timestamp_stream': 279.1507303118706, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00297835, -0.0023636 , 0.00052998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020501671358942986, + 'FR_Wheel_Angle': 0.02050403505563736, + 'Location': array([ 1.0350616 , -18.33118439, 0.16103241]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-4.63054748e-03, -5.65451616e-03, 7.55453075e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7257080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.21331787, -1796.08654785, 16.41052246]), + 'frame': 74494, + 'frame_number': 74494, + 'framesequence': 74492, + 'gaze_dir': array([ 0.98058057, -0.12858556, 0.14807922]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12858556, 0.14807922]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12858556, 0.14807922]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1546355113387, + 'timestamp_carla': 279154, + 'timestamp_device': 278746, + 'timestamp_stream': 279.1546355113387, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00445909, -0.00381266, 0.00051275]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020502177998423576, + 'FR_Wheel_Angle': 0.0205045435577631, + 'Location': array([ 1.03480589, -18.33149529, 0.16101882]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.00374568, -0.00460046, -0.00022451]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7252197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.3581543 , -1796.98828125, 16.41101074]), + 'frame': 74495, + 'frame_number': 74495, + 'framesequence': 74493, + 'gaze_dir': array([ 0.98058057, -0.12917651, 0.14756398]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12917651, 0.14756398]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12917651, 0.14756398]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.15829161182046, + 'timestamp_carla': 279157, + 'timestamp_device': 278750, + 'timestamp_stream': 279.15829161182046, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00134404, 0.00126493, 0.00055808]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020500414073467255, + 'FR_Wheel_Angle': 0.020502926781773567, + 'Location': array([ 1.03452611, -18.3318367 , 0.16100825]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.00681563, -0.00825393, 0.00067633]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7252197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.49945068, -1797.89038086, 16.41101074]), + 'frame': 74496, + 'frame_number': 74496, + 'framesequence': 74494, + 'gaze_dir': array([ 0.98058057, -0.12976989, 0.14704242]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.12976989, 0.14704242]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.12976989, 0.14704242]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1620184145868, + 'timestamp_carla': 279161, + 'timestamp_device': 278754, + 'timestamp_stream': 279.1620184145868, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00547732, 0.00463613, 0.00018227]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020497092977166176, + 'FR_Wheel_Angle': 0.020502541214227676, + 'Location': array([ 1.03402936, -18.33243752, 0.16103332]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01260015, -0.01515309, 0.00043799]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72509765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.63818359, -1798.80004883, 16.41113281]), + 'frame': 74497, + 'frame_number': 74497, + 'framesequence': 74495, + 'gaze_dir': array([ 0.98058057, -0.13020909, 0.14665365]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13020909, 0.14665365]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13020909, 0.14665365]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.16565231233835, + 'timestamp_carla': 279165, + 'timestamp_device': 278757, + 'timestamp_stream': 279.16565231233835, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.37991957e-03, 2.91651627e-03, 8.66336559e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020496536046266556, + 'FR_Wheel_Angle': 0.020502077415585518, + 'Location': array([ 1.03350568, -18.33306694, 0.16104366]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-1.35723790e-02, -1.63115282e-02, 6.19482962e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.724853515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.73876953, -1799.47570801, 16.41137695]), + 'frame': 74498, + 'frame_number': 74498, + 'framesequence': 74496, + 'gaze_dir': array([ 0.98058057, -0.13079433, 0.14613195]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13079433, 0.14613195]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13079433, 0.14613195]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1692849136889, + 'timestamp_carla': 279168, + 'timestamp_device': 278761, + 'timestamp_stream': 279.1692849136889, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00382098, -0.00324686, 0.00035788]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049802616238594, + 'FR_Wheel_Angle': 0.020500747486948967, + 'Location': array([ 1.0329169 , -18.33377647, 0.16104721]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-1.09771015e-02, -1.32104838e-02, 1.64532667e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.724853515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.87014771, -1800.37939453, 16.41137695]), + 'frame': 74499, + 'frame_number': 74499, + 'framesequence': 74497, + 'gaze_dir': array([ 0.98058057, -0.13137749, 0.14560789]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13137749, 0.14560789]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13137749, 0.14560789]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.17301551252604, + 'timestamp_carla': 279172, + 'timestamp_device': 278765, + 'timestamp_stream': 279.17301551252604, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.09479220e-03, 1.55372161e-03, -4.57779279e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020495908334851265, + 'FR_Wheel_Angle': 0.0205015167593956, + 'Location': array([ 1.03230333, -18.33451462, 0.16105117]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01466903, -0.01761467, 0.00012859]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7244873046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.99780273, -1801.28356934, 16.41174316]), + 'frame': 74500, + 'frame_number': 74500, + 'framesequence': 74498, + 'gaze_dir': array([ 0.98058057, -0.13181236, 0.14521432]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13181236, 0.14521432]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13181236, 0.14521432]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.17638041451573, + 'timestamp_carla': 279175, + 'timestamp_device': 278768, + 'timestamp_stream': 279.17638041451573, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.26832235e-03, 1.05656404e-03, 8.54282989e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020495668053627014, + 'FR_Wheel_Angle': 0.020501229912042618, + 'Location': array([ 1.03168094, -18.3352623 , 0.16105041]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01508699, -0.01811363, 0.00011449]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7242431640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.09094238, -1801.96032715, 16.4119873 ]), + 'frame': 74501, + 'frame_number': 74501, + 'framesequence': 74499, + 'gaze_dir': array([ 0.98058057, -0.13225049, 0.14481543]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13225049, 0.14481543]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13225049, 0.14481543]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.179728012532, + 'timestamp_carla': 279179, + 'timestamp_device': 278771, + 'timestamp_stream': 279.179728012532, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.38732900e-03, 1.95549359e-03, 7.92536302e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049526572227478, + 'FR_Wheel_Angle': 0.02050038054585457, + 'Location': array([ 1.03104281, -18.33602715, 0.16104648]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01578357, -0.01894376, 0.00019488]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7242431640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.18304443, -1802.64428711, 16.4119873 ]), + 'frame': 74502, + 'frame_number': 74502, + 'framesequence': 74500, + 'gaze_dir': array([ 0.98058057, -0.13282838, 0.14428556]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13282838, 0.14428556]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13282838, 0.14428556]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1832553111017, + 'timestamp_carla': 279182, + 'timestamp_device': 278775, + 'timestamp_stream': 279.1832553111017, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00314234, 0.00263769, 0.00011879]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020494239404797554, + 'FR_Wheel_Angle': 0.020500071346759796, + 'Location': array([ 1.03030288, -18.33691788, 0.16104366]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01757186, -0.02107999, -0.0002731 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7242431640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.30175781, -1803.54980469, 16.4119873 ]), + 'frame': 74503, + 'frame_number': 74503, + 'framesequence': 74501, + 'gaze_dir': array([ 0.98058057, -0.1332593 , 0.14388767]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1332593 , 0.14388767]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1332593 , 0.14388767]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.18659641221166, + 'timestamp_carla': 279185, + 'timestamp_device': 278778, + 'timestamp_stream': 279.18659641221166, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00499878, -0.00432025, 0.00030417]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020496513694524765, + 'FR_Wheel_Angle': 0.020498795434832573, + 'Location': array([ 1.02962434, -18.33773232, 0.16104038]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01361222, -0.01635258, -0.00011372]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7239990234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.38818359, -1804.22741699, 16.41223145]), + 'frame': 74504, + 'frame_number': 74504, + 'framesequence': 74502, + 'gaze_dir': array([ 0.98058057, -0.13383345, 0.14335378]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13383345, 0.14335378]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13383345, 0.14335378]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.19002071395516, + 'timestamp_carla': 279189, + 'timestamp_device': 278782, + 'timestamp_stream': 279.19002071395516, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00381503, -0.00319097, 0.00042404]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049650065600872, + 'FR_Wheel_Angle': 0.02049875073134899, + 'Location': array([ 1.02896357, -18.33852577, 0.16103187]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01363425, -0.01638107, 0.00026718]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7235107421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.50036621, -1805.13366699, 16.41271973]), + 'frame': 74505, + 'frame_number': 74505, + 'framesequence': 74503, + 'gaze_dir': array([ 0.98058057, -0.13426159, 0.14295289]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13426159, 0.14295289]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13426159, 0.14295289]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.19348641112447, + 'timestamp_carla': 279192, + 'timestamp_device': 278785, + 'timestamp_stream': 279.19348641112447, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.09349287e-03, 3.28663574e-03, 1.61761272e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049397863447666, + 'FR_Wheel_Angle': 0.020499330013990402, + 'Location': array([ 1.02818727, -18.33945847, 0.16104266]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01803089, -0.02162196, 0.00030448]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7235107421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.58209229, -1805.81188965, 16.41271973]), + 'frame': 74506, + 'frame_number': 74506, + 'framesequence': 74504, + 'gaze_dir': array([ 0.98058057, -0.13469288, 0.14254659]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13469288, 0.14254659]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13469288, 0.14254659]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.19663401320577, + 'timestamp_carla': 279195, + 'timestamp_device': 278788, + 'timestamp_stream': 279.19663401320577, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00116884, -0.00118984, 0.00019486]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049473114311695, + 'FR_Wheel_Angle': 0.020497547462582588, + 'Location': array([ 1.02738583, -18.34041786, 0.16105144]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01672156, -0.02005365, 0.00027591]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7232666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.6625061 , -1806.49731445, 16.41296387]), + 'frame': 74507, + 'frame_number': 74507, + 'framesequence': 74505, + 'gaze_dir': array([ 0.98058057, -0.13511859, 0.14214315]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13511859, 0.14214315]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13511859, 0.14214315]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.1998037137091, + 'timestamp_carla': 279199, + 'timestamp_device': 278791, + 'timestamp_stream': 279.1998037137091, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00417769, 0.00363445, -0.00010146]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020492229610681534, + 'FR_Wheel_Angle': 0.02049773931503296, + 'Location': array([ 1.02647674, -18.34150505, 0.16105244]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02107936, -0.02525046, 0.00018251]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7230224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.74008179, -1807.17602539, 16.41320801]), + 'frame': 74508, + 'frame_number': 74508, + 'framesequence': 74506, + 'gaze_dir': array([ 0.98058057, -0.13568577, 0.14160183]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13568577, 0.14160183]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13568577, 0.14160183]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.20327591151, + 'timestamp_carla': 279202, + 'timestamp_device': 278795, + 'timestamp_stream': 279.20327591151, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00146626, 0.0012656 , -0.00012507]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020492427051067352, + 'FR_Wheel_Angle': 0.020497778430581093, + 'Location': array([ 1.02559853, -18.34255981, 0.16105491]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-2.07289699e-02, -2.48350184e-02, 7.32207263e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7230224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.84063721, -1808.08361816, 16.41320801]), + 'frame': 74509, + 'frame_number': 74509, + 'framesequence': 74507, + 'gaze_dir': array([ 0.98058057, -0.13625078, 0.14105825]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13625078, 0.14105825]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13625078, 0.14105825]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.20675671473145, + 'timestamp_carla': 279206, + 'timestamp_device': 278799, + 'timestamp_stream': 279.20675671473145, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00391505, -0.00331186, 0.00027982]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020493801683187485, + 'FR_Wheel_Angle': 0.02049657702445984, + 'Location': array([ 1.0246563 , -18.34368706, 0.16105621]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.01834118, -0.02198361, 0.00010803]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7230224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.93756104, -1808.99169922, 16.41320801]), + 'frame': 74510, + 'frame_number': 74510, + 'framesequence': 74508, + 'gaze_dir': array([ 0.98058057, -0.13667203, 0.14065014]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13667203, 0.14065014]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13667203, 0.14065014]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2104989141226, + 'timestamp_carla': 279209, + 'timestamp_device': 278802, + 'timestamp_stream': 279.2104989141226, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.84147630e-03, 1.50663115e-03, 1.26064488e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049209736287594, + 'FR_Wheel_Angle': 0.020497500896453857, + 'Location': array([ 1.02371991, -18.34481049, 0.16105796]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.0213029 , -0.02552004, 0.00012623]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7227783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.00769043, -1809.67126465, 16.41345215]), + 'frame': 74511, + 'frame_number': 74511, + 'framesequence': 74509, + 'gaze_dir': array([ 0.98058057, -0.13723323, 0.14010262]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13723323, 0.14010262]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13723323, 0.14010262]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.21403251215816, + 'timestamp_carla': 279213, + 'timestamp_device': 278806, + 'timestamp_stream': 279.21403251215816, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.24144727e-03, 2.60479236e-03, -3.08294398e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020491689443588257, + 'FR_Wheel_Angle': 0.020492807030677795, + 'Location': array([ 1.02282524, -18.34588242, 0.16105419]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02201428, -0.02637315, -0.00105222]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7222900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.09820557, -1810.57995605, 16.41394043]), + 'frame': 74512, + 'frame_number': 74512, + 'framesequence': 74510, + 'gaze_dir': array([ 0.98058057, -0.13765588, 0.13968737]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13765588, 0.13968737]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13765588, 0.13968737]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2174372114241, + 'timestamp_carla': 279216, + 'timestamp_device': 278809, + 'timestamp_stream': 279.2174372114241, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00624448, 0.00510321, -0.00025256]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020487971603870392, + 'FR_Wheel_Angle': 0.020491965115070343, + 'Location': array([ 1.02154517, -18.34741402, 0.16104613]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02849169, -0.03409518, -0.00192922]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7220458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.16418457, -1811.2668457 , 16.41418457]), + 'frame': 74513, + 'frame_number': 74513, + 'framesequence': 74511, + 'gaze_dir': array([ 0.98058057, -0.13821322, 0.13913594]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13821322, 0.13913594]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13821322, 0.13913594]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2210661135614, + 'timestamp_carla': 279220, + 'timestamp_device': 278813, + 'timestamp_stream': 279.2210661135614, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00398573, -0.00352397, 0.00038576]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489413291215897, + 'FR_Wheel_Angle': 0.020492084324359894, + 'Location': array([ 1.02032638, -18.34887123, 0.16105637]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02598378, -0.03108934, 0.00024053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.721923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.24838257, -1812.17614746, 16.41430664]), + 'frame': 74514, + 'frame_number': 74514, + 'framesequence': 74512, + 'gaze_dir': array([ 0.98058057, -0.13862871, 0.13872197]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13862871, 0.13872197]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13862871, 0.13872197]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.224741011858, + 'timestamp_carla': 279224, + 'timestamp_device': 278816, + 'timestamp_stream': 279.224741011858, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00726382, -0.00608829, 0.00018742]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02048938162624836, + 'FR_Wheel_Angle': 0.020494984462857246, + 'Location': array([ 1.01899779, -18.35046387, 0.16106148]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02336769, -0.02797131, 0.00010451]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7218017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.30899048, -1812.85656738, 16.41442871]), + 'frame': 74515, + 'frame_number': 74515, + 'framesequence': 74513, + 'gaze_dir': array([ 0.98058057, -0.13918218, 0.13816665]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13918218, 0.13816665]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13918218, 0.13816665]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2279937118292, + 'timestamp_carla': 279227, + 'timestamp_device': 278820, + 'timestamp_stream': 279.2279937118292, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00301379, -0.00232271, 0.00037297]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490380004048347, + 'FR_Wheel_Angle': 0.02049313113093376, + 'Location': array([ 1.01790047, -18.35177612, 0.16106273]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02430318, -0.02908526, 0.00023719]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7215576171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.38677979, -1813.76647949, 16.41467285]), + 'frame': 74516, + 'frame_number': 74516, + 'framesequence': 74514, + 'gaze_dir': array([ 0.98058057, -0.13959478, 0.13774978]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13959478, 0.13774978]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13959478, 0.13774978]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2314129136503, + 'timestamp_carla': 279230, + 'timestamp_device': 278823, + 'timestamp_stream': 279.2314129136503, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.12334489e-04, -3.41430241e-05, -3.87900536e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020491113886237144, + 'FR_Wheel_Angle': 0.020493946969509125, + 'Location': array([ 1.01670337, -18.35321045, 0.16106498]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02516701, -0.03012333, 0.00018404]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.72119140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.44262695, -1814.44726562, 16.41491699]), + 'frame': 74517, + 'frame_number': 74517, + 'framesequence': 74515, + 'gaze_dir': array([ 0.98058057, -0.14001031, 0.1373274 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14001031, 0.1373274 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14001031, 0.1373274 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2348056137562, + 'timestamp_carla': 279234, + 'timestamp_device': 278826, + 'timestamp_stream': 279.2348056137562, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.90190428e-03, 2.42785783e-03, -5.56729537e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020488779991865158, + 'FR_Wheel_Angle': 0.02049427479505539, + 'Location': array([ 1.01559758, -18.35453415, 0.16105606]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02708351, -0.0324058 , 0.00036449]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.720947265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.49688721, -1815.13525391, 16.4152832 ]), + 'frame': 74518, + 'frame_number': 74518, + 'framesequence': 74516, + 'gaze_dir': array([ 0.98058057, -0.1405582 , 0.13676657]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1405582 , 0.13676657]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1405582 , 0.13676657]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.23853931203485, + 'timestamp_carla': 279237, + 'timestamp_device': 278830, + 'timestamp_stream': 279.23853931203485, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-9.74796014e-04, 9.61064768e-04, 3.28166630e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490825176239014, + 'FR_Wheel_Angle': 0.020493552088737488, + 'Location': array([ 1.01433349, -18.35604477, 0.16106598]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02585126, -0.03093895, 0.00019428]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7208251953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.56561279, -1816.04589844, 16.4152832 ]), + 'frame': 74519, + 'frame_number': 74519, + 'framesequence': 74517, + 'gaze_dir': array([ 0.98058057, -0.14110383, 0.13620356]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14110383, 0.13620356]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14110383, 0.13620356]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.24214551225305, + 'timestamp_carla': 279241, + 'timestamp_device': 278834, + 'timestamp_stream': 279.24214551225305, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00299707, -0.00252337, 0.00019847]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490719005465508, + 'FR_Wheel_Angle': 0.02049349434673786, + 'Location': array([ 1.01317072, -18.35743713, 0.1610709 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02371345, -0.0283836 , 0.00021929]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7205810546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.63067627, -1816.95678711, 16.41564941]), + 'frame': 74520, + 'frame_number': 74520, + 'framesequence': 74518, + 'gaze_dir': array([ 0.98058057, -0.14151055, 0.13578096]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14151055, 0.13578096]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14151055, 0.13578096]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.24545411393046, + 'timestamp_carla': 279244, + 'timestamp_device': 278837, + 'timestamp_stream': 279.24545411393046, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00292514, -0.00247039, 0.00034429]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490871742367744, + 'FR_Wheel_Angle': 0.020493587478995323, + 'Location': array([ 1.01205373, -18.35877419, 0.16106963]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-2.34460942e-02, -2.80659534e-02, -8.01300994e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7203369140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.67697144, -1817.63830566, 16.41589355]), + 'frame': 74521, + 'frame_number': 74521, + 'framesequence': 74519, + 'gaze_dir': array([ 0.98058057, -0.14192013, 0.13535279]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14192013, 0.13535279]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14192013, 0.13535279]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2486144118011, + 'timestamp_carla': 279248, + 'timestamp_device': 278840, + 'timestamp_stream': 279.2486144118011, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00087738, -0.00069717, 0.00033153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489944145083427, + 'FR_Wheel_Angle': 0.020492669194936752, + 'Location': array([ 1.01087379, -18.36018562, 0.16106911]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02506148, -0.0299908 , 0.00011129]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7200927734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.72161865, -1818.32702637, 16.41601562]), + 'frame': 74522, + 'frame_number': 74522, + 'framesequence': 74520, + 'gaze_dir': array([ 0.98058057, -0.14246011, 0.13478436]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14246011, 0.13478436]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14246011, 0.13478436]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2519240118563, + 'timestamp_carla': 279251, + 'timestamp_device': 278844, + 'timestamp_stream': 279.2519240118563, + 'transform': [array([ 0.00865738, -0.00365967, 0.15906911]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00299947, -0.00257793, 0.00022181]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490432158112526, + 'FR_Wheel_Angle': 0.020493125542998314, + 'Location': array([ 1.00970232, -18.36158562, 0.16107132]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-2.42105760e-02, -2.89764162e-02, 4.41479679e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.719970703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.77758789, -1819.23840332, 16.41625977]), + 'frame': 74523, + 'frame_number': 74523, + 'framesequence': 74521, + 'gaze_dir': array([ 0.98058057, -0.1429978 , 0.13421375]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1429978 , 0.13421375]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1429978 , 0.13421375]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2559776119888, + 'timestamp_carla': 279255, + 'timestamp_device': 278848, + 'timestamp_stream': 279.2559776119888, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00141433, 0.00107281, -0.00012748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489249378442764, + 'FR_Wheel_Angle': 0.020494692027568817, + 'Location': array([ 1.00852382, -18.36299706, 0.16107711]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02627024, -0.03143751, 0.0002129 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.719482421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.82983398, -1820.15014648, 16.41674805]), + 'frame': 74524, + 'frame_number': 74524, + 'framesequence': 74522, + 'gaze_dir': array([ 0.98058057, -0.14339855, 0.13378549]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14339855, 0.13378549]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14339855, 0.13378549]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.25957191362977, + 'timestamp_carla': 279258, + 'timestamp_device': 278851, + 'timestamp_stream': 279.25957191362977, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00333286, -0.00285522, 0.00011849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049085684120655, + 'FR_Wheel_Angle': 0.020493678748607635, + 'Location': array([ 1.00735283, -18.36439896, 0.16107875]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02347321, -0.02809821, 0.00020121]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7193603515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.86657715, -1820.83227539, 16.41662598]), + 'frame': 74525, + 'frame_number': 74525, + 'framesequence': 74523, + 'gaze_dir': array([ 0.98058057, -0.14393225, 0.13321115]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14393225, 0.13321115]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14393225, 0.13321115]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.26297191157937, + 'timestamp_carla': 279262, + 'timestamp_device': 278855, + 'timestamp_stream': 279.26297191157937, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00200971, -0.00159462, 0.0002437 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049054391682148, + 'FR_Wheel_Angle': 0.02049318142235279, + 'Location': array([ 1.0062288 , -18.36574364, 0.16107692]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02401494, -0.02874433, 0.0001323 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.71923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.91253662, -1821.7442627 , 16.41674805]), + 'frame': 74526, + 'frame_number': 74526, + 'framesequence': 74524, + 'gaze_dir': array([ 0.98058057, -0.14433001, 0.13278009]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14433001, 0.13278009]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14433001, 0.13278009]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2663020119071, + 'timestamp_carla': 279265, + 'timestamp_device': 278858, + 'timestamp_stream': 279.2663020119071, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.92197738e-03, 1.49655272e-03, -3.78667937e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489726215600967, + 'FR_Wheel_Angle': 0.02049517072737217, + 'Location': array([ 1.0050534 , -18.36715126, 0.16107967]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-2.54370905e-02, -3.04456130e-02, 9.33027259e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.71923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.94454956, -1822.42663574, 16.41674805]), + 'frame': 74527, + 'frame_number': 74527, + 'framesequence': 74525, + 'gaze_dir': array([ 0.98058057, -0.14485969, 0.13220203]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14485969, 0.13220203]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14485969, 0.13220203]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2699742130935, + 'timestamp_carla': 279269, + 'timestamp_device': 278862, + 'timestamp_stream': 279.2699742130935, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00377653, -0.00309935, 0.00039766]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020491614937782288, + 'FR_Wheel_Angle': 0.02049429900944233, + 'Location': array([ 1.0039196 , -18.36850739, 0.16108139]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-2.21477002e-02, -2.65171453e-02, -8.31460929e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7186279296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.98400879, -1823.33898926, 16.4173584 ]), + 'frame': 74528, + 'frame_number': 74528, + 'framesequence': 74526, + 'gaze_dir': array([ 0.98058057, -0.14539105, 0.13161743]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14539105, 0.13161743]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14539105, 0.13161743]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.27398651465774, + 'timestamp_carla': 279273, + 'timestamp_device': 278866, + 'timestamp_stream': 279.27398651465774, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.61715397e-03, 3.17454245e-03, 6.47185007e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049078233540058, + 'FR_Wheel_Angle': 0.020493412390351295, + 'Location': array([ 1.0027467 , -18.3699131 , 0.16108276]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-2.60971878e-02, -3.12328134e-02, -7.72738422e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7186279296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.02020264, -1824.25842285, 16.4173584 ]), + 'frame': 74529, + 'frame_number': 74529, + 'framesequence': 74527, + 'gaze_dir': array([ 0.98058057, -0.14578404, 0.131182 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14578404, 0.131182 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14578404, 0.131182 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2775610126555, + 'timestamp_carla': 279276, + 'timestamp_device': 278869, + 'timestamp_stream': 279.2775610126555, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.50052032e-03, 1.95151928e-03, -2.40961235e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489508286118507, + 'FR_Wheel_Angle': 0.02049492858350277, + 'Location': array([ 1.00164056, -18.37123871, 0.16108342]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.025819 , -0.03090054, 0.00023536]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.71826171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.0446167 , -1824.94116211, 16.41772461]), + 'frame': 74530, + 'frame_number': 74530, + 'framesequence': 74528, + 'gaze_dir': array([ 0.98058057, -0.14643875, 0.13045074]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14643875, 0.13045074]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14643875, 0.13045074]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.28159281238914, + 'timestamp_carla': 279280, + 'timestamp_device': 278874, + 'timestamp_stream': 279.28159281238914, + 'transform': [array([ 0.00865723, -0.00365967, 0.15906769]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0021467 , -0.00179331, 0.00023315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020490523427724838, + 'FR_Wheel_Angle': 0.02049328200519085, + 'Location': array([ 1.0004667 , -18.37264252, 0.16108696]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02405217, -0.02878612, 0.00013353]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7178955078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.08093262, -1826.08374023, 16.41809082]), + 'frame': 74531, + 'frame_number': 74531, + 'framesequence': 74529, + 'gaze_dir': array([ 0.98058057, -0.1469591 , 0.12986426]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1469591 , 0.12986426]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1469591 , 0.12986426]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2861300110817, + 'timestamp_carla': 279285, + 'timestamp_device': 278878, + 'timestamp_stream': 279.2861300110817, + 'transform': [array([ 0.00865707, -0.00365967, 0.15906517]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.0023387 , 0.00195616, -0.00016344]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020489247515797615, + 'FR_Wheel_Angle': 0.020494423806667328, + 'Location': array([ 0.99926078, -18.37408638, 0.16108836]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02627181, -0.03143927, 0.00017445]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7174072265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.10583496, -1826.99658203, 16.4185791 ]), + 'frame': 74532, + 'frame_number': 74532, + 'framesequence': 74530, + 'gaze_dir': array([ 0.98058057, -0.14760719, 0.12912713]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14760719, 0.12912713]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14760719, 0.12912713]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2915403135121, + 'timestamp_carla': 279290, + 'timestamp_device': 278883, + 'timestamp_stream': 279.2915403135121, + 'transform': [array([ 0.00865723, -0.00365967, 0.15905991]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0030222 , -0.00255347, 0.00036131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02049066685140133, + 'FR_Wheel_Angle': 0.020493322983384132, + 'Location': array([ 0.9980821 , -18.37549782, 0.16109054]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-2.38044001e-02, -2.84900926e-02, -7.60912881e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.716796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.13180542, -1828.13952637, 16.41894531]), + 'frame': 74533, + 'frame_number': 74533, + 'framesequence': 74531, + 'gaze_dir': array([ 0.98058057, -0.14812224, 0.12853602]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14812224, 0.12853602]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14812224, 0.12853602]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.29533411189914, + 'timestamp_carla': 279294, + 'timestamp_device': 278887, + 'timestamp_stream': 279.29533411189914, + 'transform': [array([ 0.00865723, -0.00365967, 0.15905991]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.20908567e-03, 2.69778864e-03, 1.69124451e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020488345995545387, + 'FR_Wheel_Angle': 0.020493755117058754, + 'Location': array([ 0.99683195, -18.37699127, 0.1610923 ]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02783977, -0.03330724, 0.00018587]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7158203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.14840698, -1829.05249023, 16.41931152]), + 'frame': 74534, + 'frame_number': 74534, + 'framesequence': 74532, + 'gaze_dir': array([ 0.98058057, -0.14863491, 0.12794282]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14863491, 0.12794282]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14863491, 0.12794282]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.2991153113544, + 'timestamp_carla': 279298, + 'timestamp_device': 278891, + 'timestamp_stream': 279.2991153113544, + 'transform': [array([ 0.00865723, -0.00365967, 0.15905991]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00167465, -0.00147386, 0.00034031]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02048937790095806, + 'FR_Wheel_Angle': 0.020492073148489, + 'Location': array([ 0.99558383, -18.37848282, 0.16109486]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02604922, -0.03116518, 0.00011664]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7156982421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.16149902, -1829.96557617, 16.41943359]), + 'frame': 74535, + 'frame_number': 74535, + 'framesequence': 74533, + 'gaze_dir': array([ 0.98058057, -0.14914522, 0.12734757]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14914522, 0.12734757]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14914522, 0.12734757]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3032534122467, + 'timestamp_carla': 279302, + 'timestamp_device': 278895, + 'timestamp_stream': 279.3032534122467, + 'transform': [array([ 0.00865723, -0.00365967, 0.15905991]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00171965, -0.00132384, 0.00037107]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02048877254128456, + 'FR_Wheel_Angle': 0.020490607246756554, + 'Location': array([ 0.99432826, -18.37998199, 0.16109386]), + 'Rotation': array([-4.49836217e-02, 4.99759712e+01, -3.75976562e-02]), + 'Velocity': array([-0.02710138, -0.03241942, 0.00014207]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7152099609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.1708374 , -1830.87878418, 16.41992188]), + 'frame': 74536, + 'frame_number': 74536, + 'framesequence': 74534, + 'gaze_dir': array([ 0.98058057, -0.14965312, 0.12675032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14965312, 0.12675032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14965312, 0.12675032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3075032122433, + 'timestamp_carla': 279306, + 'timestamp_device': 278899, + 'timestamp_stream': 279.3075032122433, + 'transform': [array([ 0.00865723, -0.00365967, 0.15905991]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.03819806e-03, 1.72970525e-03, -8.21339927e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02048039622604847, + 'FR_Wheel_Angle': 0.020483369007706642, + 'Location': array([ 0.99223244, -18.38248444, 0.16109554]), + 'Rotation': array([-4.56871316e-02, 4.99760551e+01, -3.75976562e-02]), + 'Velocity': array([-0.04169395, -0.04980612, 0.00031862]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7149658203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.17657471, -1831.79187012, 16.42004395]), + 'frame': 74537, + 'frame_number': 74537, + 'framesequence': 74535, + 'gaze_dir': array([ 0.98058057, -0.15028562, 0.12599973]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15028562, 0.12599973]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15028562, 0.12599973]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3121554143727, + 'timestamp_carla': 279311, + 'timestamp_device': 278904, + 'timestamp_stream': 279.3121554143727, + 'transform': [array([ 0.00865707, -0.00365967, 0.15905771]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00800677, 0.00665053, 0.00185182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020477645099163055, + 'FR_Wheel_Angle': 0.020482942461967468, + 'Location': array([ 0.99033505, -18.38475037, 0.16108809]), + 'Rotation': array([-4.56871316e-02, 4.99760551e+01, -3.75976562e-02]), + 'Velocity': array([-0.04648899, -0.05552657, 0.00011295]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7144775390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.17858887, -1832.93505859, 16.4206543 ]), + 'frame': 74538, + 'frame_number': 74538, + 'framesequence': 74536, + 'gaze_dir': array([ 0.98058057, -0.15078813, 0.12539792]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15078813, 0.12539792]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15078813, 0.12539792]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.31592071428895, + 'timestamp_carla': 279315, + 'timestamp_device': 278908, + 'timestamp_stream': 279.31592071428895, + 'transform': [array([ 0.00865707, -0.00365967, 0.15905771]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00776297, -0.00647654, 0.00066558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020480865612626076, + 'FR_Wheel_Angle': 0.02048368565738201, + 'Location': array([ 0.98824996, -18.38724136, 0.16110283]), + 'Rotation': array([-4.56871316e-02, 4.99760551e+01, -3.75976562e-02]), + 'Velocity': array([-0.04087758, -0.04883483, 0.00028189]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7137451171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.17602539, -1833.8482666 , 16.42102051]), + 'frame': 74539, + 'frame_number': 74539, + 'framesequence': 74537, + 'gaze_dir': array([ 0.98058057, -0.15166079, 0.12434109]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15166079, 0.12434109]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15166079, 0.12434109]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3230460137129, + 'timestamp_carla': 279322, + 'timestamp_device': 278915, + 'timestamp_stream': 279.3230460137129, + 'transform': [array([ 0.00865692, -0.00365967, 0.1590416 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00745237, 0.00639581, 0.00062332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02047443389892578, + 'FR_Wheel_Angle': 0.0204775333404541, + 'Location': array([ 0.98608345, -18.38983154, 0.1611021 ]), + 'Rotation': array([-4.56871316e-02, 4.99760551e+01, -3.75976562e-02]), + 'Velocity': array([-0.05208837, -0.06218696, 0.00052317]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7132568359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.16293335, -1835.44445801, 16.42163086]), + 'frame': 74540, + 'frame_number': 74540, + 'framesequence': 74538, + 'gaze_dir': array([ 0.98058057, -0.15228119, 0.12358049]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15228119, 0.12358049]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15228119, 0.12358049]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3278719112277, + 'timestamp_carla': 279327, + 'timestamp_device': 278920, + 'timestamp_stream': 279.3278719112277, + 'transform': [array([ 0.00865692, -0.00365967, 0.1590416 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00372584, -0.00320655, -0.00056584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020475810393691063, + 'FR_Wheel_Angle': 0.02048148773610592, + 'Location': array([ 0.98370337, -18.39267349, 0.16111492]), + 'Rotation': array([-4.56871316e-02, 4.99760551e+01, -3.75976562e-02]), + 'Velocity': array([-0.04968425, -0.05933496, 0.0003383 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7113037109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.1463623 , -1836.58764648, 16.421875 ]), + 'frame': 74541, + 'frame_number': 74541, + 'framesequence': 74539, + 'gaze_dir': array([ 0.98058057, -0.15277402, 0.12297072]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15277402, 0.12297072]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15277402, 0.12297072]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.33189261332154, + 'timestamp_carla': 279331, + 'timestamp_device': 278924, + 'timestamp_stream': 279.33189261332154, + 'transform': [array([ 0.00865692, -0.00365967, 0.1590416 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00808371, 0.00683803, -0.00026519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02047041244804859, + 'FR_Wheel_Angle': 0.020473552867770195, + 'Location': array([ 0.9813078 , -18.39553452, 0.16111721]), + 'Rotation': array([-4.56871316e-02, 4.99761162e+01, -3.75976637e-02]), + 'Velocity': array([-0.05909217, -0.07053096, 0.00027057]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7110595703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.12927246, -1837.50061035, 16.42211914]), + 'frame': 74542, + 'frame_number': 74542, + 'framesequence': 74540, + 'gaze_dir': array([ 0.98058057, -0.15314111, 0.12251326]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15314111, 0.12251326]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15314111, 0.12251326]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.33556481450796, + 'timestamp_carla': 279334, + 'timestamp_device': 278927, + 'timestamp_stream': 279.33556481450796, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904331]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00219661, 0.00165234, 0.00951515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020469456911087036, + 'FR_Wheel_Angle': 0.020475441589951515, + 'Location': array([ 0.97851425, -18.39887238, 0.16112648]), + 'Rotation': array([-4.57144529e-02, 4.99763412e+01, -3.75976562e-02]), + 'Velocity': array([-0.06074722, -0.07252286, 0.00023343]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7105712890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.11407471, -1838.18359375, 16.42260742]), + 'frame': 74543, + 'frame_number': 74543, + 'framesequence': 74541, + 'gaze_dir': array([ 0.98058057, -0.15362966, 0.12190006]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15362966, 0.12190006]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15362966, 0.12190006]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3396924138069, + 'timestamp_carla': 279338, + 'timestamp_device': 278931, + 'timestamp_stream': 279.3396924138069, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904331]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00696689, -0.00581106, 0.01202713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02047264575958252, + 'FR_Wheel_Angle': 0.020475734025239944, + 'Location': array([ 0.97582531, -18.40208244, 0.16112922]), + 'Rotation': array([-4.56529818e-02, 4.99763184e+01, -3.75976562e-02]), + 'Velocity': array([-0.05519973, -0.06589957, 0.00015064]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7105712890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.09069824, -1839.09643555, 16.42285156]), + 'frame': 74544, + 'frame_number': 74544, + 'framesequence': 74542, + 'gaze_dir': array([ 0.98058057, -0.15411946, 0.1212802 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15411946, 0.1212802 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15411946, 0.1212802 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.34362971410155, + 'timestamp_carla': 279342, + 'timestamp_device': 278935, + 'timestamp_stream': 279.34362971410155, + 'transform': [array([ 0.00865723, -0.00365967, 0.15904453]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00474346, -0.00395843, -0.00109147]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020474838092923164, + 'FR_Wheel_Angle': 0.020477505400776863, + 'Location': array([ 0.97320479, -18.4052124 , 0.16112995]), + 'Rotation': array([-4.56256606e-02, 4.99764366e+01, -3.75976562e-02]), + 'Velocity': array([-0.05379692, -0.06423884, 0.00020907]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7100830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.06329346, -1840.01623535, 16.42333984]), + 'frame': 74545, + 'frame_number': 74545, + 'framesequence': 74543, + 'gaze_dir': array([ 0.98058057, -0.15460308, 0.12066311]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15460308, 0.12066311]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15460308, 0.12066311]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.34689701348543, + 'timestamp_carla': 279346, + 'timestamp_device': 278939, + 'timestamp_stream': 279.34689701348543, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904607]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.03259461, 0.02730413, 0.00577987]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02045883983373642, + 'FR_Wheel_Angle': 0.02046453393995762, + 'Location': array([ 0.97045243, -18.4085083 , 0.16113624]), + 'Rotation': array([-4.61993963e-02, 4.99770851e+01, -3.75976562e-02]), + 'Velocity': array([-0.0791754 , -0.0946171 , 0.00024821]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7100830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 333.03262329, -1840.92883301, 16.42346191]), + 'frame': 74546, + 'frame_number': 74546, + 'framesequence': 74544, + 'gaze_dir': array([ 0.98058057, -0.15508422, 0.12004407]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15508422, 0.12004407]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15508422, 0.12004407]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3510204143822, + 'timestamp_carla': 279350, + 'timestamp_device': 278943, + 'timestamp_stream': 279.3510204143822, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904607]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.0016704 , 0.00151726, -0.00856424]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020462263375520706, + 'FR_Wheel_Angle': 0.02046770602464676, + 'Location': array([ 0.96691865, -18.4127121 , 0.16113949]), + 'Rotation': array([-4.65409048e-02, 4.99761505e+01, -3.75976562e-02]), + 'Velocity': array([-0.07332275, -0.08741456, 0.00035298]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7098388671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.99816895, -1841.84130859, 16.42382812]), + 'frame': 74547, + 'frame_number': 74547, + 'framesequence': 74545, + 'gaze_dir': array([ 0.98058057, -0.15567945, 0.11927115]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15567945, 0.11927115]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15567945, 0.11927115]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3563220128417, + 'timestamp_carla': 279355, + 'timestamp_device': 278948, + 'timestamp_stream': 279.3563220128417, + 'transform': [array([ 0.00865692, -0.00365967, 0.15904267]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01382573, -0.01165387, 0.00691495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020467571914196014, + 'FR_Wheel_Angle': 0.020470427349209785, + 'Location': array([ 0.96365476, -18.41661644, 0.16114357]), + 'Rotation': array([-4.63291705e-02, 4.99770737e+01, -3.75976525e-02]), + 'Velocity': array([-0.06401543, -0.07644922, 0.00025738]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7093505859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.95022583, -1842.9765625 , 16.42431641]), + 'frame': 74548, + 'frame_number': 74548, + 'framesequence': 74546, + 'gaze_dir': array([ 0.98058057, -0.15615866, 0.11864305]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15615866, 0.11864305]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15615866, 0.11864305]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.36011991277337, + 'timestamp_carla': 279359, + 'timestamp_device': 278952, + 'timestamp_stream': 279.36011991277337, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904416]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00563284, -0.0044574 , 0.05836828]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020466601476073265, + 'FR_Wheel_Angle': 0.020469792187213898, + 'Location': array([ 0.96077937, -18.42004395, 0.161147 ]), + 'Rotation': array([-4.61993963e-02, 4.99769630e+01, -3.75976562e-02]), + 'Velocity': array([-0.06574268, -0.07843059, 0.00014597]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.70849609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.90713501, -1843.89575195, 16.42480469]), + 'frame': 74549, + 'frame_number': 74549, + 'framesequence': 74547, + 'gaze_dir': array([ 0.98058057, -0.15651277, 0.1181755 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15651277, 0.1181755 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15651277, 0.1181755 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3636840134859, + 'timestamp_carla': 279362, + 'timestamp_device': 278955, + 'timestamp_stream': 279.3636840134859, + 'transform': [array([ 0.00865692, -0.00365967, 0.15904541]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00142013, 0.00122835, -0.03303952]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020464779809117317, + 'FR_Wheel_Angle': 0.020469706505537033, + 'Location': array([ 0.95760036, -18.42383766, 0.16115052]), + 'Rotation': array([-4.61993963e-02, 4.99769516e+01, -3.75976562e-02]), + 'Velocity': array([-0.06891735, -0.08220273, 0.00011987]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7083740234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.87286377, -1844.57800293, 16.42504883]), + 'frame': 74550, + 'frame_number': 74550, + 'framesequence': 74548, + 'gaze_dir': array([ 0.98058057, -0.15698396, 0.11754885]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15698396, 0.11754885]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15698396, 0.11754885]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3670837134123, + 'timestamp_carla': 279366, + 'timestamp_device': 278959, + 'timestamp_stream': 279.3670837134123, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904725]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.03194084, 0.02686932, -0.02668992]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020450210198760033, + 'FR_Wheel_Angle': 0.020453283563256264, + 'Location': array([ 0.95396775, -18.42817307, 0.1611539 ]), + 'Rotation': array([-4.67458107e-02, 4.99778519e+01, -3.75976562e-02]), + 'Velocity': array([-0.09430294, -0.11245271, 0.00021288]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7081298828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.82385254, -1845.48986816, 16.42541504]), + 'frame': 74551, + 'frame_number': 74551, + 'framesequence': 74549, + 'gaze_dir': array([ 0.98058057, -0.15745263, 0.11692032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15745263, 0.11692032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15745263, 0.11692032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.37097631394863, + 'timestamp_carla': 279370, + 'timestamp_device': 278963, + 'timestamp_stream': 279.37097631394863, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904725]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00600179, 0.00555772, 0.14986135]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020445821806788445, + 'FR_Wheel_Angle': 0.020443854853510857, + 'Location': array([ 0.94917905, -18.4338932 , 0.16116177]), + 'Rotation': array([-4.80981879e-02, 4.99791718e+01, -3.75976600e-02]), + 'Velocity': array([-0.10194188, -0.12157419, -0.0002027 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.77120972, -1846.40148926, 16.42578125]), + 'frame': 74552, + 'frame_number': 74552, + 'framesequence': 74550, + 'gaze_dir': array([ 0.98058057, -0.1579188 , 0.11628993]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1579188 , 0.11628993]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1579188 , 0.11628993]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3756108134985, + 'timestamp_carla': 279374, + 'timestamp_device': 278967, + 'timestamp_stream': 279.3756108134985, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904725]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01045813, 0.009794 , -0.01512164]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020427443087100983, + 'FR_Wheel_Angle': 0.020430969074368477, + 'Location': array([ 0.94281822, -18.44146729, 0.16119038]), + 'Rotation': array([-4.98057380e-02, 4.99778404e+01, -3.75976525e-02]), + 'Velocity': array([-0.13489327, -0.16076051, 0.00046052]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.707763671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.71490479, -1847.31286621, 16.42602539]), + 'frame': 74553, + 'frame_number': 74553, + 'framesequence': 74551, + 'gaze_dir': array([ 0.98058057, -0.15838243, 0.11565768]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15838243, 0.11565768]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15838243, 0.11565768]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.37925071269274, + 'timestamp_carla': 279378, + 'timestamp_device': 278971, + 'timestamp_stream': 279.37925071269274, + 'transform': [array([ 0.00865692, -0.00365967, 0.15904827]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00729679, -0.00590615, -0.00183872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020427679643034935, + 'FR_Wheel_Angle': 0.020431412383913994, + 'Location': array([ 0.93714154, -18.44823074, 0.16119613]), + 'Rotation': array([-4.98057380e-02, 4.99778404e+01, -3.75976525e-02]), + 'Velocity': array([-0.13356137, -0.15921861, 0.00041853]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7073974609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.65496826, -1848.22412109, 16.4263916 ]), + 'frame': 74554, + 'frame_number': 74554, + 'framesequence': 74552, + 'gaze_dir': array([ 0.98058057, -0.15872763, 0.11518349]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15872763, 0.11518349]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15872763, 0.11518349]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3827623128891, + 'timestamp_carla': 279382, + 'timestamp_device': 278974, + 'timestamp_stream': 279.3827623128891, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904988]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01997356, -0.01656789, -0.00185463]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020431727170944214, + 'FR_Wheel_Angle': 0.02043651044368744, + 'Location': array([ 0.93090099, -18.45567322, 0.16120277]), + 'Rotation': array([-4.98057380e-02, 4.99778404e+01, -3.75976525e-02]), + 'Velocity': array([-0.12649347, -0.15082629, 0.00034807]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7069091796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.60766602, -1848.90563965, 16.42700195]), + 'frame': 74555, + 'frame_number': 74555, + 'framesequence': 74553, + 'gaze_dir': array([ 0.98058057, -0.15919033, 0.11454315]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15919033, 0.11454315]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15919033, 0.11454315]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3861818127334, + 'timestamp_carla': 279385, + 'timestamp_device': 278978, + 'timestamp_stream': 279.3861818127334, + 'transform': [array([ 0.00865692, -0.00365967, 0.15905103]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.02164371, -0.01830666, 0.01349288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020436318591237068, + 'FR_Wheel_Angle': 0.020440928637981415, + 'Location': array([ 0.92498457, -18.46273041, 0.16120373]), + 'Rotation': array([-4.93139625e-02, 4.99782066e+01, -3.75976562e-02]), + 'Velocity': array([-0.11748893, -0.14013879, 0.00036959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.70654296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.540802 , -1849.82324219, 16.42749023]), + 'frame': 74556, + 'frame_number': 74556, + 'framesequence': 74554, + 'gaze_dir': array([ 0.98058057, -0.15964697, 0.11390582]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.15964697, 0.11390582]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.15964697, 0.11390582]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.39002541452646, + 'timestamp_carla': 279389, + 'timestamp_device': 278982, + 'timestamp_stream': 279.39002541452646, + 'transform': [array([ 0.00865692, -0.00365967, 0.15905103]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.03063552, 0.02566713, 0.0038621 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02041819877922535, + 'FR_Wheel_Angle': 0.02042318694293499, + 'Location': array([ 0.91928744, -18.46954155, 0.16121528]), + 'Rotation': array([-4.99833226e-02, 4.99792862e+01, -3.75976562e-02]), + 'Velocity': array([-0.14993957, -0.17901117, 0.0003575 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7066650390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.47091675, -1850.73376465, 16.42736816]), + 'frame': 74557, + 'frame_number': 74557, + 'framesequence': 74555, + 'gaze_dir': array([ 0.98058057, -0.16010107, 0.11326668]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16010107, 0.11326668]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16010107, 0.11326668]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.39395751431584, + 'timestamp_carla': 279393, + 'timestamp_device': 278986, + 'timestamp_stream': 279.39395751431584, + 'transform': [array([ 0.00865692, -0.00365967, 0.15905103]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00481554, -0.00347189, 0.00066989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020421551540493965, + 'FR_Wheel_Angle': 0.020424170419573784, + 'Location': array([ 0.91204679, -18.47817993, 0.16122505]), + 'Rotation': array([-5.00789434e-02, 4.99793129e+01, -3.75976562e-02]), + 'Velocity': array([-1.44214392e-01, -1.71958119e-01, 5.38730601e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7059326171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.39715576, -1851.64404297, 16.42810059]), + 'frame': 74558, + 'frame_number': 74558, + 'framesequence': 74556, + 'gaze_dir': array([ 0.98058057, -0.1604391 , 0.11278735]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1604391 , 0.11278735]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1604391 , 0.11278735]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.3976422138512, + 'timestamp_carla': 279396, + 'timestamp_device': 278989, + 'timestamp_stream': 279.3976422138512, + 'transform': [array([ 0.00865707, -0.00365967, 0.15905216]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01050489, -0.00873065, -0.04353785]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02042226307094097, + 'FR_Wheel_Angle': 0.020424673333764076, + 'Location': array([ 0.90576088, -18.4856739 , 0.16123424]), + 'Rotation': array([-4.99218516e-02, 4.99789581e+01, -3.75976600e-02]), + 'Velocity': array([-0.14297213, -0.17047702, 0.00040064]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7056884765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.33972168, -1852.32470703, 16.42834473]), + 'frame': 74559, + 'frame_number': 74559, + 'framesequence': 74557, + 'gaze_dir': array([ 0.98058057, -0.16088872, 0.11214505]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16088872, 0.11214505]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16088872, 0.11214505]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.40087761357427, + 'timestamp_carla': 279400, + 'timestamp_device': 278993, + 'timestamp_stream': 279.40087761357427, + 'transform': [array([ 0.00865692, -0.00365967, 0.15905336]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00691968, -0.00580307, 0.00051333]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020420843735337257, + 'FR_Wheel_Angle': 0.020425844937562943, + 'Location': array([ 0.89860737, -18.49419975, 0.16124026]), + 'Rotation': array([-4.98672090e-02, 4.99790077e+01, -3.75976562e-02]), + 'Velocity': array([-0.14545596, -0.17341784, 0.00038718]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7056884765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.25982666, -1853.234375 , 16.4284668 ]), + 'frame': 74560, + 'frame_number': 74560, + 'framesequence': 74558, + 'gaze_dir': array([ 0.98058057, -0.16133575, 0.11150096]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16133575, 0.11150096]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16133575, 0.11150096]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.40496691316366, + 'timestamp_carla': 279404, + 'timestamp_device': 278997, + 'timestamp_stream': 279.40496691316366, + 'transform': [array([ 0.00865692, -0.00365967, 0.15905336]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00268398, -0.00255866, 0.02964264]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02041853405535221, + 'FR_Wheel_Angle': 0.020421097055077553, + 'Location': array([ 0.89165419, -18.50248909, 0.16125046]), + 'Rotation': array([-4.97715846e-02, 4.99793358e+01, -3.75976562e-02]), + 'Velocity': array([-0.14944218, -0.17824581, 0.0003591 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.705078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.17608643, -1854.14367676, 16.42919922]), + 'frame': 74561, + 'frame_number': 74561, + 'framesequence': 74559, + 'gaze_dir': array([ 0.98058057, -0.16178022, 0.11085509]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16178022, 0.11085509]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16178022, 0.11085509]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4094182141125, + 'timestamp_carla': 279408, + 'timestamp_device': 279001, + 'timestamp_stream': 279.4094182141125, + 'transform': [array([ 0.00865677, -0.00365967, 0.15905233]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00147933, -0.00101655, -0.00751668]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02041497826576233, + 'FR_Wheel_Angle': 0.0204196497797966, + 'Location': array([ 0.88424474, -18.51132202, 0.16126117]), + 'Rotation': array([-4.98672090e-02, 4.99797440e+01, -3.75976562e-02]), + 'Velocity': array([-0.15568048, -0.18559261, 0.00032488]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.704833984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 332.08886719, -1855.0526123 , 16.42944336]), + 'frame': 74562, + 'frame_number': 74562, + 'framesequence': 74560, + 'gaze_dir': array([ 0.98058057, -0.16222212, 0.11020744]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16222212, 0.11020744]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16222212, 0.11020744]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.41316041350365, + 'timestamp_carla': 279412, + 'timestamp_device': 279005, + 'timestamp_stream': 279.41316041350365, + 'transform': [array([ 0.00865677, -0.00365967, 0.15905233]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00156193, 0.0013273 , 0.00055751]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020410923287272453, + 'FR_Wheel_Angle': 0.020415395498275757, + 'Location': array([ 0.87721169, -18.51970673, 0.16127102]), + 'Rotation': array([-4.98672090e-02, 4.99797440e+01, -3.75976562e-02]), + 'Velocity': array([-0.16274509, -0.19400208, 0.00025813]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7044677734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.99795532, -1855.96130371, 16.4296875 ]), + 'frame': 74563, + 'frame_number': 74563, + 'framesequence': 74561, + 'gaze_dir': array([ 0.98058057, -0.16255432, 0.10971683]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16255432, 0.10971683]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16255432, 0.10971683]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4167036116123, + 'timestamp_carla': 279416, + 'timestamp_device': 279008, + 'timestamp_stream': 279.4167036116123, + 'transform': [array([ 0.00865677, -0.00365967, 0.15905233]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00353319, 0.00268629, -0.01299426]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020407332107424736, + 'FR_Wheel_Angle': 0.02041085623204708, + 'Location': array([ 0.86940551, -18.52901649, 0.16128239]), + 'Rotation': array([-4.98945303e-02, 4.99799767e+01, -3.75976562e-02]), + 'Velocity': array([-1.68950021e-01, -2.01505139e-01, -6.48498535e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7042236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.92681885, -1856.64770508, 16.42993164]), + 'frame': 74564, + 'frame_number': 74564, + 'framesequence': 74562, + 'gaze_dir': array([ 0.98058057, -0.16299164, 0.10906609]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16299164, 0.10906609]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16299164, 0.10906609]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.42010021209717, + 'timestamp_carla': 279419, + 'timestamp_device': 279012, + 'timestamp_stream': 279.42010021209717, + 'transform': [array([ 0.00865692, -0.00365967, 0.1590537 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00502204, 0.00453772, -0.02886526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020406536757946014, + 'FR_Wheel_Angle': 0.020408252254128456, + 'Location': array([ 0.86139691, -18.53856087, 0.16129489]), + 'Rotation': array([-4.98945303e-02, 4.99801178e+01, -3.75976562e-02]), + 'Velocity': array([-0.17445035, -0.20789811, 0.00042385]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7037353515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.82952881, -1857.55566406, 16.43041992]), + 'frame': 74565, + 'frame_number': 74565, + 'framesequence': 74563, + 'gaze_dir': array([ 0.98058057, -0.16342637, 0.10841362]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16342637, 0.10841362]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16342637, 0.10841362]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4241633117199, + 'timestamp_carla': 279423, + 'timestamp_device': 279016, + 'timestamp_stream': 279.4241633117199, + 'transform': [array([ 0.00865692, -0.00365967, 0.1590537 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01157504, 0.00965822, 0.00935179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02039477787911892, + 'FR_Wheel_Angle': 0.020399270579218864, + 'Location': array([ 0.85317081, -18.54837227, 0.16130893]), + 'Rotation': array([-5.02701886e-02, 4.99810371e+01, -3.75976562e-02]), + 'Velocity': array([-0.19086432, -0.22752278, 0.00040707]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.72860718, -1858.46325684, 16.43115234]), + 'frame': 74566, + 'frame_number': 74566, + 'framesequence': 74564, + 'gaze_dir': array([ 0.98058057, -0.16396691, 0.10759433]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16396691, 0.10759433]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16396691, 0.10759433]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4299074113369, + 'timestamp_carla': 279429, + 'timestamp_device': 279021, + 'timestamp_stream': 279.4299074113369, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904793]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01072814, 0.00915213, -0.02106916]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038661018013954, + 'FR_Wheel_Angle': 0.020390093326568604, + 'Location': array([ 0.84361035, -18.5597744 , 0.16131203]), + 'Rotation': array([-5.06595112e-02, 4.99816322e+01, -3.75976562e-02]), + 'Velocity': array([-0.20514122, -0.24444737, 0.00060133]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7030029296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.59719849, -1859.59887695, 16.43127441]), + 'frame': 74567, + 'frame_number': 74567, + 'framesequence': 74565, + 'gaze_dir': array([ 0.98058057, -0.16439573, 0.10693797]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16439573, 0.10693797]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16439573, 0.10693797]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4335243143141, + 'timestamp_carla': 279432, + 'timestamp_device': 279025, + 'timestamp_stream': 279.4335243143141, + 'transform': [array([ 0.00865707, -0.00365967, 0.15904793]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00733067, -0.00623088, -0.00283441]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038705162703991, + 'FR_Wheel_Angle': 0.020393524318933487, + 'Location': array([ 0.8338145 , -18.57144547, 0.1613335 ]), + 'Rotation': array([-5.06595112e-02, 4.99816322e+01, -3.75976562e-02]), + 'Velocity': array([-2.04346180e-01, -2.43554682e-01, -1.06534957e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.701904296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.48803711, -1860.50549316, 16.4317627 ]), + 'frame': 74568, + 'frame_number': 74568, + 'framesequence': 74566, + 'gaze_dir': array([ 0.98058057, -0.16482194, 0.1062799 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16482194, 0.1062799 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16482194, 0.1062799 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.43693021312356, + 'timestamp_carla': 279436, + 'timestamp_device': 279029, + 'timestamp_stream': 279.43693021312356, + 'transform': [array([ 0.00865723, -0.00365967, 0.1590495 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01080759, -0.00920147, -0.0019513 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02038843184709549, + 'FR_Wheel_Angle': 0.02039317972958088, + 'Location': array([ 0.82428539, -18.58280182, 0.16134186]), + 'Rotation': array([-5.06595112e-02, 4.99816322e+01, -3.75976562e-02]), + 'Velocity': array([-0.20193192, -0.2406866 , 0.00047688]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7015380859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.37533569, -1861.41162109, 16.43200684]), + 'frame': 74569, + 'frame_number': 74569, + 'framesequence': 74567, + 'gaze_dir': array([ 0.98058057, -0.16513905, 0.10578649]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16513905, 0.10578649]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16513905, 0.10578649]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4405312128365, + 'timestamp_carla': 279439, + 'timestamp_device': 279032, + 'timestamp_stream': 279.4405312128365, + 'transform': [array([ 0.00865723, -0.00365967, 0.1590495 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00668449, -0.00565497, -0.00164228]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020387711003422737, + 'FR_Wheel_Angle': 0.020391171798110008, + 'Location': array([ 0.81479836, -18.59411049, 0.16135857]), + 'Rotation': array([-5.06595112e-02, 4.99816322e+01, -3.75976562e-02]), + 'Velocity': array([-0.20319375, -0.24217586, 0.00039348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.701416015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.28869629, -1862.0892334 , 16.43249512]), + 'frame': 74570, + 'frame_number': 74570, + 'framesequence': 74568, + 'gaze_dir': array([ 0.98058057, -0.16556063, 0.10512546]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16556063, 0.10512546]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16556063, 0.10512546]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.44431611150503, + 'timestamp_carla': 279443, + 'timestamp_device': 279036, + 'timestamp_stream': 279.44431611150503, + 'transform': [array([ 0.00865723, -0.00365967, 0.1590495 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01374895, 0.01157672, -0.00185455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020378047600388527, + 'FR_Wheel_Angle': 0.020381273701786995, + 'Location': array([ 0.80499172, -18.60579872, 0.16136707]), + 'Rotation': array([-5.07824533e-02, 4.99816551e+01, -3.75976562e-02]), + 'Velocity': array([-0.22003685, -0.26223788, 0.00066551]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7010498046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.16967773, -1862.99462891, 16.43286133]), + 'frame': 74571, + 'frame_number': 74571, + 'framesequence': 74569, + 'gaze_dir': array([ 0.98058057, -0.1658743 , 0.10462984]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1658743 , 0.10462984]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1658743 , 0.10462984]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.44780431315303, + 'timestamp_carla': 279447, + 'timestamp_device': 279039, + 'timestamp_stream': 279.44780431315303, + 'transform': [array([ 0.00865723, -0.00365967, 0.1590495 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00685671, 0.005705 , -0.01414504]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02037804014980793, + 'FR_Wheel_Angle': 0.020378636196255684, + 'Location': array([ 0.79456669, -18.61822128, 0.16139011]), + 'Rotation': array([-5.07824533e-02, 4.99816551e+01, -3.75976562e-02]), + 'Velocity': array([-0.22601564, -0.26936281, 0.00062658]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7005615234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 331.07821655, -1863.67163086, 16.43322754]), + 'frame': 74572, + 'frame_number': 74572, + 'framesequence': 74570, + 'gaze_dir': array([ 0.98058057, -0.16629125, 0.10396588]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16629125, 0.10396588]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16629125, 0.10396588]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4511633142829, + 'timestamp_carla': 279450, + 'timestamp_device': 279043, + 'timestamp_stream': 279.4511633142829, + 'transform': [array([ 0.00865738, -0.00365967, 0.15905091]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00732979, -0.00628262, -0.00522711]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02037755586206913, + 'FR_Wheel_Angle': 0.020381763577461243, + 'Location': array([ 0.78447849, -18.63024712, 0.16140273]), + 'Rotation': array([-5.06868325e-02, 4.99818993e+01, -3.75976562e-02]), + 'Velocity': array([-0.22088768, -0.26326036, 0.0005321 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.7001953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.95285034, -1864.57617188, 16.43359375]), + 'frame': 74573, + 'frame_number': 74573, + 'framesequence': 74571, + 'gaze_dir': array([ 0.98058057, -0.16660459, 0.10346299]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16660459, 0.10346299]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16660459, 0.10346299]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4548306129873, + 'timestamp_carla': 279454, + 'timestamp_device': 279046, + 'timestamp_stream': 279.4548306129873, + 'transform': [array([ 0.00865738, -0.00365967, 0.15905091]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0044015 , -0.00354451, -0.00221304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020376626402139664, + 'FR_Wheel_Angle': 0.02038131095468998, + 'Location': array([ 0.77477467, -18.64180946, 0.16141555]), + 'Rotation': array([-5.06868325e-02, 4.99818993e+01, -3.75976562e-02]), + 'Velocity': array([-0.2225116 , -0.26519379, 0.00045578]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.699951171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.85574341, -1865.25939941, 16.43408203]), + 'frame': 74574, + 'frame_number': 74574, + 'framesequence': 74572, + 'gaze_dir': array([ 0.98058057, -0.16701688, 0.10279612]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16701688, 0.10279612]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16701688, 0.10279612]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.45859721302986, + 'timestamp_carla': 279457, + 'timestamp_device': 279050, + 'timestamp_stream': 279.45859721302986, + 'transform': [array([ 0.00865738, -0.00365967, 0.15905091]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00633151, -0.0051181 , -0.00151828]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020377052947878838, + 'FR_Wheel_Angle': 0.020380094647407532, + 'Location': array([ 0.76403183, -18.65461159, 0.16142811]), + 'Rotation': array([-5.06868325e-02, 4.99818993e+01, -3.75976562e-02]), + 'Velocity': array([-0.22176914, -0.26430231, 0.00045843]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.699462890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.72399902, -1866.16296387, 16.43444824]), + 'frame': 74575, + 'frame_number': 74575, + 'framesequence': 74573, + 'gaze_dir': array([ 0.98058057, -0.1674265 , 0.1021276 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1674265 , 0.1021276 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1674265 , 0.1021276 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4627624116838, + 'timestamp_carla': 279462, + 'timestamp_device': 279054, + 'timestamp_stream': 279.4627624116838, + 'transform': [array([ 0.00865738, -0.00365967, 0.15905091]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00107617, 0.00080858, -0.00138174]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020373031497001648, + 'FR_Wheel_Angle': 0.020376037806272507, + 'Location': array([ 0.75388432, -18.66670418, 0.16144153]), + 'Rotation': array([-5.06868325e-02, 4.99818993e+01, -3.75976562e-02]), + 'Velocity': array([-0.22877996, -0.27265021, 0.00043621]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.698974609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.58868408, -1867.06604004, 16.43493652]), + 'frame': 74576, + 'frame_number': 74576, + 'framesequence': 74574, + 'gaze_dir': array([ 0.98058057, -0.16783345, 0.10145745]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16783345, 0.10145745]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16783345, 0.10145745]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4661000110209, + 'timestamp_carla': 279465, + 'timestamp_device': 279058, + 'timestamp_stream': 279.4661000110209, + 'transform': [array([ 0.00865753, -0.00365967, 0.15905221]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00686253, 0.00555771, -0.00228621]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02036801539361477, + 'FR_Wheel_Angle': 0.020372513681650162, + 'Location': array([ 0.74300355, -18.67967224, 0.16146 ]), + 'Rotation': array([-5.06868325e-02, 4.99818993e+01, -3.75976562e-02]), + 'Velocity': array([-0.23751736, -0.28306115, 0.00044749]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6986083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.44976807, -1867.96862793, 16.43530273]), + 'frame': 74577, + 'frame_number': 74577, + 'framesequence': 74575, + 'gaze_dir': array([ 0.98058057, -0.16813613, 0.10095505]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16813613, 0.10095505]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16813613, 0.10095505]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4695687144995, + 'timestamp_carla': 279468, + 'timestamp_device': 279061, + 'timestamp_stream': 279.4695687144995, + 'transform': [array([ 0.00865753, -0.00365967, 0.15905221]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00267259, 0.00239934, -0.00228756]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02036478742957115, + 'FR_Wheel_Angle': 0.020367372781038284, + 'Location': array([ 0.73118895, -18.69375038, 0.16147423]), + 'Rotation': array([-5.06868325e-02, 4.99818993e+01, -3.75976562e-02]), + 'Velocity': array([-0.24314737, -0.28976229, 0.00048348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6983642578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.34350586, -1868.64343262, 16.43566895]), + 'frame': 74578, + 'frame_number': 74578, + 'framesequence': 74576, + 'gaze_dir': array([ 0.98058057, -0.16853838, 0.10028208]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16853838, 0.10028208]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16853838, 0.10028208]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.473414812237, + 'timestamp_carla': 279472, + 'timestamp_device': 279065, + 'timestamp_stream': 279.473414812237, + 'transform': [array([ 0.00865753, -0.00365967, 0.15905221]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00349474, 0.00262777, -0.001755 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02035626769065857, + 'FR_Wheel_Angle': 0.020362695679068565, + 'Location': array([ 0.71916127, -18.70808029, 0.16147983]), + 'Rotation': array([-5.06868325e-02, 4.99818993e+01, -3.75976562e-02]), + 'Velocity': array([-0.25378361, -0.3024323 , -0.00095979]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6978759765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.19827271, -1869.54492188, 16.43615723]), + 'frame': 74579, + 'frame_number': 74579, + 'framesequence': 74577, + 'gaze_dir': array([ 0.98058057, -0.16884059, 0.09977243]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16884059, 0.09977243]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16884059, 0.09977243]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4766679145396, + 'timestamp_carla': 279475, + 'timestamp_device': 279068, + 'timestamp_stream': 279.4766679145396, + 'transform': [array([ 0.00865753, -0.00365967, 0.15905221]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00466797, -0.00378311, -0.0024911 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020352927967905998, + 'FR_Wheel_Angle': 0.020356515422463417, + 'Location': array([ 0.70652419, -18.72313881, 0.16151223]), + 'Rotation': array([-5.10829836e-02, 4.99819298e+01, -3.75976562e-02]), + 'Velocity': array([-0.26380572, -0.31436661, 0.00056641]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.697509765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 330.08612061, -1870.22583008, 16.43652344]), + 'frame': 74580, + 'frame_number': 74580, + 'framesequence': 74578, + 'gaze_dir': array([ 0.98058057, -0.16913822, 0.09926703]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16913822, 0.09926703]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16913822, 0.09926703]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.479820612818, + 'timestamp_carla': 279479, + 'timestamp_device': 279071, + 'timestamp_stream': 279.479820612818, + 'transform': [array([ 0.00865768, -0.00365967, 0.15905353]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01343084, -0.01126774, -0.00241782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02035508304834366, + 'FR_Wheel_Angle': 0.020357994362711906, + 'Location': array([ 0.69481063, -18.73709679, 0.16152854]), + 'Rotation': array([-5.10829836e-02, 4.99819298e+01, -3.75976562e-02]), + 'Velocity': array([-0.26005021, -0.30989349, 0.00049948]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.697265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.9730835 , -1870.89953613, 16.43676758]), + 'frame': 74581, + 'frame_number': 74581, + 'framesequence': 74579, + 'gaze_dir': array([ 0.98058057, -0.16953371, 0.09859006]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16953371, 0.09859006]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16953371, 0.09859006]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.48311861231923, + 'timestamp_carla': 279482, + 'timestamp_device': 279075, + 'timestamp_stream': 279.48311861231923, + 'transform': [array([ 0.00865768, -0.00365967, 0.15905353]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0154381 , -0.01286931, -0.00256478]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02035703882575035, + 'FR_Wheel_Angle': 0.020360929891467094, + 'Location': array([ 0.68193352, -18.7524395 , 0.16154231]), + 'Rotation': array([-5.10829836e-02, 4.99819298e+01, -3.75976562e-02]), + 'Velocity': array([-0.25685489, -0.30610183, 0.00034617]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6968994140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.81890869, -1871.79956055, 16.43725586]), + 'frame': 74582, + 'frame_number': 74582, + 'framesequence': 74580, + 'gaze_dir': array([ 0.98058057, -0.16992649, 0.09791151]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16992649, 0.09791151]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16992649, 0.09791151]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4868953116238, + 'timestamp_carla': 279486, + 'timestamp_device': 279079, + 'timestamp_stream': 279.4868953116238, + 'transform': [array([ 0.00865768, -0.00365967, 0.15905353]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00568722, -0.0046787 , -0.00239523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020356714725494385, + 'FR_Wheel_Angle': 0.0203593447804451, + 'Location': array([ 0.66989714, -18.76678276, 0.16155869]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.25721556, -0.30651057, 0.00056675]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6962890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.66094971, -1872.69897461, 16.43786621]), + 'frame': 74583, + 'frame_number': 74583, + 'framesequence': 74581, + 'gaze_dir': array([ 0.98058057, -0.17021856, 0.09740287]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17021856, 0.09740287]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17021856, 0.09740287]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4904903136194, + 'timestamp_carla': 279489, + 'timestamp_device': 279082, + 'timestamp_stream': 279.4904903136194, + 'transform': [array([ 0.00865768, -0.00365967, 0.15905353]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00251518, -0.00212811, -0.00244537]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020352745428681374, + 'FR_Wheel_Angle': 0.020355135202407837, + 'Location': array([ 0.65794724, -18.7810173 , 0.16157517]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.2641286 , -0.31474659, 0.00042 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6959228515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.54052734, -1873.37145996, 16.43823242]), + 'frame': 74584, + 'frame_number': 74584, + 'framesequence': 74582, + 'gaze_dir': array([ 0.98058057, -0.17060658, 0.0967216 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17060658, 0.0967216 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17060658, 0.0967216 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.4941552132368, + 'timestamp_carla': 279493, + 'timestamp_device': 279086, + 'timestamp_stream': 279.4941552132368, + 'transform': [array([ 0.00865768, -0.00365967, 0.15905353]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00495871, -0.00414209, -0.00274055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020354198291897774, + 'FR_Wheel_Angle': 0.020357565954327583, + 'Location': array([ 0.64525145, -18.79614639, 0.16159202]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.26271716, -0.31307167, 0.00032673]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.695556640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.37640381, -1874.26977539, 16.43859863]), + 'frame': 74585, + 'frame_number': 74585, + 'framesequence': 74583, + 'gaze_dir': array([ 0.98058057, -0.17089804, 0.09620572]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17089804, 0.09620572]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17089804, 0.09620572]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.49742901325226, + 'timestamp_carla': 279496, + 'timestamp_device': 279089, + 'timestamp_stream': 279.49742901325226, + 'transform': [array([ 0.00865768, -0.00365967, 0.15905353]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00351066, -0.00310118, -0.00235804]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020351862534880638, + 'FR_Wheel_Angle': 0.02035588026046753, + 'Location': array([ 0.63285553, -18.8109169 , 0.1616111 ]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.26566797, -0.31657523, 0.00034327]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.25003052, -1874.94812012, 16.4387207 ]), + 'frame': 74586, + 'frame_number': 74586, + 'framesequence': 74584, + 'gaze_dir': array([ 0.98058057, -0.17118499, 0.09569418]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17118499, 0.09569418]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17118499, 0.09569418]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5006436146796, + 'timestamp_carla': 279499, + 'timestamp_device': 279092, + 'timestamp_stream': 279.5006436146796, + 'transform': [array([ 0.00865784, -0.00365967, 0.15905461]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00106814, 0.00082612, -0.00242003]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020349280908703804, + 'FR_Wheel_Angle': 0.020352210849523544, + 'Location': array([ 0.62080616, -18.82527351, 0.16162559]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.2701686, -0.3219353, 0.0005583]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6947021484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 329.12280273, -1875.61938477, 16.43945312]), + 'frame': 74587, + 'frame_number': 74587, + 'framesequence': 74585, + 'gaze_dir': array([ 0.98058057, -0.17156619, 0.09500905]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17156619, 0.09500905]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17156619, 0.09500905]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.50465931370854, + 'timestamp_carla': 279503, + 'timestamp_device': 279096, + 'timestamp_stream': 279.50465931370854, + 'transform': [array([ 0.00865784, -0.00365967, 0.15905461]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00084503, 0.00076296, -0.00270771]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034764178097248, + 'FR_Wheel_Angle': 0.02035173587501049, + 'Location': array([ 0.60793102, -18.84061623, 0.16164523]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.27302665, -0.32534224, 0.0004844 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6944580078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.94976807, -1876.51599121, 16.43969727]), + 'frame': 74588, + 'frame_number': 74588, + 'framesequence': 74586, + 'gaze_dir': array([ 0.98058057, -0.17194463, 0.09432241]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17194463, 0.09432241]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17194463, 0.09432241]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.50805881246924, + 'timestamp_carla': 279507, + 'timestamp_device': 279100, + 'timestamp_stream': 279.50805881246924, + 'transform': [array([ 0.00865784, -0.00365967, 0.15905461]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00626166, -0.00524667, -0.00288898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020349660888314247, + 'FR_Wheel_Angle': 0.02035435102880001, + 'Location': array([ 0.59563279, -18.85526848, 0.16165848]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.26950467, -0.32115492, 0.00032373]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6939697265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.77301025, -1877.41186523, 16.44030762]), + 'frame': 74589, + 'frame_number': 74589, + 'framesequence': 74587, + 'gaze_dir': array([ 0.98058057, -0.17232034, 0.09363426]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17232034, 0.09363426]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17232034, 0.09363426]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5112786144018, + 'timestamp_carla': 279510, + 'timestamp_device': 279104, + 'timestamp_stream': 279.5112786144018, + 'transform': [array([ 0.00865784, -0.00365967, 0.15905461]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01070313, -0.0091161 , -0.00217354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02035113051533699, + 'FR_Wheel_Angle': 0.020353995263576508, + 'Location': array([ 0.58253187, -18.87087822, 0.1616748 ]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-2.66943693e-01, -3.18094552e-01, 9.75131934e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.693359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.5927124 , -1878.30700684, 16.4407959 ]), + 'frame': 74590, + 'frame_number': 74590, + 'framesequence': 74588, + 'gaze_dir': array([ 0.98058057, -0.1727868 , 0.09277066]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1727868 , 0.09277066]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1727868 , 0.09277066]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5175321139395, + 'timestamp_carla': 279516, + 'timestamp_device': 279109, + 'timestamp_stream': 279.5175321139395, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0150651 , -0.01259398, -0.00316759]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020355181768536568, + 'FR_Wheel_Angle': 0.020358068868517876, + 'Location': array([ 0.57162434, -18.88387489, 0.16168132]), + 'Rotation': array([-5.10010198e-02, 4.99819374e+01, -3.75976562e-02]), + 'Velocity': array([-0.25988552, -0.30969307, 0.00051284]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.69287109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.36203003, -1879.42663574, 16.44140625]), + 'frame': 74591, + 'frame_number': 74591, + 'framesequence': 74589, + 'gaze_dir': array([ 0.98058057, -0.17315631, 0.09207915]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17315631, 0.09207915]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17315631, 0.09207915]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.52126801386476, + 'timestamp_carla': 279520, + 'timestamp_device': 279113, + 'timestamp_stream': 279.52126801386476, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00443833, -0.00373908, -0.00232194]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020350810140371323, + 'FR_Wheel_Angle': 0.020354250445961952, + 'Location': array([ 0.55749029, -18.90071487, 0.16169983]), + 'Rotation': array([-5.08439243e-02, 4.99819412e+01, -3.75976562e-02]), + 'Velocity': array([-0.2675021 , -0.31875846, 0.00065035]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6912841796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 328.17346191, -1880.32019043, 16.44189453]), + 'frame': 74592, + 'frame_number': 74592, + 'framesequence': 74590, + 'gaze_dir': array([ 0.98058057, -0.17352302, 0.09138617]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17352302, 0.09138617]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17352302, 0.09138617]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5249724127352, + 'timestamp_carla': 279524, + 'timestamp_device': 279117, + 'timestamp_stream': 279.5249724127352, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00459436, 0.00396082, -0.00274673]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020347952842712402, + 'FR_Wheel_Angle': 0.020353181287646294, + 'Location': array([ 0.54519117, -18.91537094, 0.16171023]), + 'Rotation': array([-5.08439243e-02, 4.99819412e+01, -3.75976562e-02]), + 'Velocity': array([-0.27247471, -0.32469416, 0.00053089]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.690673828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.98153687, -1881.21289062, 16.44250488]), + 'frame': 74593, + 'frame_number': 74593, + 'framesequence': 74591, + 'gaze_dir': array([ 0.98058057, -0.17379832, 0.0908615 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17379832, 0.0908615 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17379832, 0.0908615 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.52843161299825, + 'timestamp_carla': 279527, + 'timestamp_device': 279120, + 'timestamp_stream': 279.52843161299825, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00215486, 0.00179105, -0.00291079]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020347479730844498, + 'FR_Wheel_Angle': 0.020345458760857582, + 'Location': array([ 0.53243917, -18.93056679, 0.16172881]), + 'Rotation': array([-5.08439243e-02, 4.99819412e+01, -3.75976562e-02]), + 'Velocity': array([-0.27330285, -0.32567966, -0.00132444]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6904296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.83413696, -1881.88708496, 16.44274902]), + 'frame': 74594, + 'frame_number': 74594, + 'framesequence': 74592, + 'gaze_dir': array([ 0.98058057, -0.17416018, 0.09016597]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17416018, 0.09016597]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17416018, 0.09016597]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.53214141353965, + 'timestamp_carla': 279531, + 'timestamp_device': 279124, + 'timestamp_stream': 279.53214141353965, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01130619, 0.00952863, -0.00276975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020339634269475937, + 'FR_Wheel_Angle': 0.020345445722341537, + 'Location': array([ 0.51993215, -18.945467 , 0.161762 ]), + 'Rotation': array([-5.08439243e-02, 4.99819412e+01, -3.75976562e-02]), + 'Velocity': array([-0.28698179, -0.34195641, 0.00071165]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6898193359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.63598633, -1882.77844238, 16.4432373 ]), + 'frame': 74595, + 'frame_number': 74595, + 'framesequence': 74593, + 'gaze_dir': array([ 0.98058057, -0.17451926, 0.08946899]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17451926, 0.08946899]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17451926, 0.08946899]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.53645261377096, + 'timestamp_carla': 279535, + 'timestamp_device': 279128, + 'timestamp_stream': 279.53645261377096, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00653154, -0.00554083, -0.00260446]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034403383731842, + 'FR_Wheel_Angle': 0.020347395911812782, + 'Location': array([ 0.50598395, -18.96208382, 0.16178501]), + 'Rotation': array([-5.08439243e-02, 4.99819412e+01, -3.75976562e-02]), + 'Velocity': array([-0.27931514, -0.33281788, 0.00066609]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6893310546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.4342041 , -1883.66906738, 16.44384766]), + 'frame': 74596, + 'frame_number': 74596, + 'framesequence': 74594, + 'gaze_dir': array([ 0.98058057, -0.17487553, 0.08877058]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17487553, 0.08877058]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17487553, 0.08877058]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.54029151424766, + 'timestamp_carla': 279539, + 'timestamp_device': 279132, + 'timestamp_stream': 279.54029151424766, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00083335, 0.00074524, -0.00251569]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034052275121212, + 'FR_Wheel_Angle': 0.020343054085969925, + 'Location': array([ 0.49278831, -18.97780418, 0.16180283]), + 'Rotation': array([-5.08439243e-02, 4.99819412e+01, -3.75976562e-02]), + 'Velocity': array([-0.28543684, -0.34010878, 0.00053201]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6888427734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.22894287, -1884.55883789, 16.44433594]), + 'frame': 74597, + 'frame_number': 74597, + 'framesequence': 74595, + 'gaze_dir': array([ 0.98058057, -0.17522903, 0.08807076]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17522903, 0.08807076]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17522903, 0.08807076]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.54399291425943, + 'timestamp_carla': 279543, + 'timestamp_device': 279136, + 'timestamp_stream': 279.54399291425943, + 'transform': [array([ 0.00865799, -0.00365967, 0.15904492]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0002539 , -0.00034821, -0.00288413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020339293405413628, + 'FR_Wheel_Angle': 0.020344790071249008, + 'Location': array([ 0.48035559, -18.99262047, 0.16181751]), + 'Rotation': array([-5.08439243e-02, 4.99819412e+01, -3.75976562e-02]), + 'Velocity': array([-0.28757441, -0.34266403, 0.00048812]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.688232421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 327.02008057, -1885.44775391, 16.44482422]), + 'frame': 74598, + 'frame_number': 74598, + 'framesequence': 74596, + 'gaze_dir': array([ 0.98058057, -0.17549163, 0.08754631]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17549163, 0.08754631]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17549163, 0.08754631]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.54739471152425, + 'timestamp_carla': 279546, + 'timestamp_device': 279139, + 'timestamp_stream': 279.54739471152425, + 'transform': [array([ 0.00865814, -0.00365967, 0.15904607]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01018406, 0.00866637, -0.00274175]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034159190952778, + 'FR_Wheel_Angle': 0.02034871093928814, + 'Location': array([ 0.46781558, -19.00756264, 0.16181618]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.283566 , -0.33789682, 0.00061481]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6878662109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.86151123, -1886.11230469, 16.44519043]), + 'frame': 74599, + 'frame_number': 74599, + 'framesequence': 74597, + 'gaze_dir': array([ 0.98058057, -0.17584021, 0.08684403]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17584021, 0.08684403]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17584021, 0.08684403]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.55085131153464, + 'timestamp_carla': 279550, + 'timestamp_device': 279143, + 'timestamp_stream': 279.55085131153464, + 'transform': [array([ 0.00865814, -0.00365967, 0.15904607]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-8.76510312e-05, 1.70253319e-04, -2.27468647e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020344125106930733, + 'FR_Wheel_Angle': 0.020348386839032173, + 'Location': array([ 0.45391613, -19.02412224, 0.16184792]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.27872196, -0.33210307, 0.00069176]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.64651489, -1886.99975586, 16.44567871]), + 'frame': 74600, + 'frame_number': 74600, + 'framesequence': 74598, + 'gaze_dir': array([ 0.98058057, -0.176186 , 0.08614037]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.176186 , 0.08614037]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.176186 , 0.08614037]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.55490381270647, + 'timestamp_carla': 279554, + 'timestamp_device': 279147, + 'timestamp_stream': 279.55490381270647, + 'transform': [array([ 0.00865814, -0.00365967, 0.15904607]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00955591, 0.00799778, -0.00250415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034035511314869, + 'FR_Wheel_Angle': 0.020342810079455376, + 'Location': array([ 0.4412131 , -19.03925705, 0.1618713 ]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.28573331, -0.34045258, 0.00067188]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.686767578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.42785645, -1887.88635254, 16.44641113]), + 'frame': 74601, + 'frame_number': 74601, + 'framesequence': 74599, + 'gaze_dir': array([ 0.98058057, -0.17644544, 0.08560768]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17644544, 0.08560768]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17644544, 0.08560768]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5585949122906, + 'timestamp_carla': 279557, + 'timestamp_device': 279150, + 'timestamp_stream': 279.5585949122906, + 'transform': [array([ 0.00865814, -0.00365967, 0.15904607]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01383624, 0.01181284, -0.00293438]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033603936433792, + 'FR_Wheel_Angle': 0.020339392125606537, + 'Location': array([ 0.42734399, -19.05578041, 0.16188274]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29324999, -0.34940943, 0.00085522]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6864013671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.26028442, -1888.55578613, 16.44677734]), + 'frame': 74602, + 'frame_number': 74602, + 'framesequence': 74600, + 'gaze_dir': array([ 0.98058057, -0.17678626, 0.0849016 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17678626, 0.0849016 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17678626, 0.0849016 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5619142130017, + 'timestamp_carla': 279561, + 'timestamp_device': 279154, + 'timestamp_stream': 279.5619142130017, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904722]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00407435, 0.00362045, -0.00296193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020336022600531578, + 'FR_Wheel_Angle': 0.02033902145922184, + 'Location': array([ 0.41343063, -19.07235527, 0.16191585]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29503223, -0.35152873, 0.00062185]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.68603515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 326.03549194, -1889.4407959 , 16.44714355]), + 'frame': 74603, + 'frame_number': 74603, + 'framesequence': 74601, + 'gaze_dir': array([ 0.98058057, -0.17720896, 0.08401575]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17720896, 0.08401575]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17720896, 0.08401575]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5665078125894, + 'timestamp_carla': 279565, + 'timestamp_device': 279159, + 'timestamp_stream': 279.5665078125894, + 'transform': [array([ 0.00865814, -0.00365967, 0.15904522]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00244747, 0.00198177, -0.0027742 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033398672938347, + 'FR_Wheel_Angle': 0.020336944609880447, + 'Location': array([ 0.39972273, -19.0886879 , 0.16194141]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.2968359 , -0.35366216, 0.00050425]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.685302734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.74902344, -1890.54748535, 16.44799805]), + 'frame': 74604, + 'frame_number': 74604, + 'framesequence': 74602, + 'gaze_dir': array([ 0.98058057, -0.17754343, 0.08330663]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17754343, 0.08330663]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17754343, 0.08330663]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.57119961455464, + 'timestamp_carla': 279570, + 'timestamp_device': 279163, + 'timestamp_stream': 279.57119961455464, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00474023, 0.00392013, -0.00309273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020331086590886116, + 'FR_Wheel_Angle': 0.020336469635367393, + 'Location': array([ 0.38592106, -19.10512924, 0.16196422]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.30188805, -0.35968429, 0.00046809]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.51623535, -1891.43041992, 16.44848633]), + 'frame': 74605, + 'frame_number': 74605, + 'framesequence': 74603, + 'gaze_dir': array([ 0.98058057, -0.17787504, 0.08259618]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17787504, 0.08259618]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17787504, 0.08259618]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5755274146795, + 'timestamp_carla': 279574, + 'timestamp_device': 279167, + 'timestamp_stream': 279.5755274146795, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00663609, -0.00556799, -0.003026 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335016772150993, + 'FR_Wheel_Angle': 0.02033916860818863, + 'Location': array([ 0.37218395, -19.12149429, 0.16197574]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29503384, -0.35153079, 0.00059366]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.683837890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.27984619, -1892.3125 , 16.44909668]), + 'frame': 74606, + 'frame_number': 74606, + 'framesequence': 74604, + 'gaze_dir': array([ 0.98058057, -0.17820382, 0.08188442]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17820382, 0.08188442]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17820382, 0.08188442]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5792210139334, + 'timestamp_carla': 279578, + 'timestamp_device': 279171, + 'timestamp_stream': 279.5792210139334, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00305766, -0.0023092 , -0.00277767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033451572060585, + 'FR_Wheel_Angle': 0.020337238907814026, + 'Location': array([ 0.3583318 , -19.13799667, 0.16199577]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29591325, -0.35256106, 0.0005924 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.683349609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 325.04003906, -1893.19360352, 16.44958496]), + 'frame': 74607, + 'frame_number': 74607, + 'framesequence': 74605, + 'gaze_dir': array([ 0.98058057, -0.17852975, 0.08117135]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17852975, 0.08117135]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17852975, 0.08117135]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5833095125854, + 'timestamp_carla': 279582, + 'timestamp_device': 279175, + 'timestamp_stream': 279.5833095125854, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00134085, 0.00105098, -0.00307117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020332569256424904, + 'FR_Wheel_Angle': 0.020337292924523354, + 'Location': array([ 0.34423801, -19.15478897, 0.16201511]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29930395, -0.35660627, 0.00046739]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.682861328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.79672241, -1894.07373047, 16.45007324]), + 'frame': 74608, + 'frame_number': 74608, + 'framesequence': 74606, + 'gaze_dir': array([ 0.98058057, -0.17885283, 0.08045697]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17885283, 0.08045697]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17885283, 0.08045697]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.5874546132982, + 'timestamp_carla': 279586, + 'timestamp_device': 279179, + 'timestamp_stream': 279.5874546132982, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00638682, -0.0028066 , -0.00242768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020334018394351006, + 'FR_Wheel_Angle': 0.020337099209427834, + 'Location': array([ 0.33003443, -19.17171288, 0.16203293]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-2.96773702e-01, -3.53606701e-01, 5.21707516e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6822509765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.54980469, -1894.95288086, 16.45068359]), + 'frame': 74609, + 'frame_number': 74609, + 'framesequence': 74607, + 'gaze_dir': array([ 0.98058057, -0.17917305, 0.07974131]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17917305, 0.07974131]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17917305, 0.07974131]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.59086461365223, + 'timestamp_carla': 279590, + 'timestamp_device': 279183, + 'timestamp_stream': 279.59086461365223, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00564124, -0.00105882, -0.00243054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020334579050540924, + 'FR_Wheel_Angle': 0.020338313654065132, + 'Location': array([ 0.31692484, -19.18732834, 0.16204792]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29578227, -0.35244936, 0.00051651]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.29940796, -1895.83105469, 16.45117188]), + 'frame': 74610, + 'frame_number': 74610, + 'framesequence': 74608, + 'gaze_dir': array([ 0.98058057, -0.17941073, 0.0792051 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17941073, 0.0792051 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17941073, 0.0792051 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.59455881267786, + 'timestamp_carla': 279593, + 'timestamp_device': 279186, + 'timestamp_stream': 279.59455881267786, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00144733, 0.00228938, -0.00276102]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033463679254055, + 'FR_Wheel_Angle': 0.020338963717222214, + 'Location': array([ 0.30261871, -19.20437431, 0.16206294]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.295679 , -0.35233718, 0.00053956]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.681396484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 324.10983276, -1896.48730469, 16.45153809]), + 'frame': 74611, + 'frame_number': 74611, + 'framesequence': 74609, + 'gaze_dir': array([ 0.98058057, -0.17972593, 0.07848722]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17972593, 0.07848722]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17972593, 0.07848722]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.59810481220484, + 'timestamp_carla': 279597, + 'timestamp_device': 279190, + 'timestamp_stream': 279.59810481220484, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00918612, -0.00441751, -0.0026462 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020337842404842377, + 'FR_Wheel_Angle': 0.020342888310551643, + 'Location': array([ 0.28887737, -19.22074699, 0.16207351]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29008472, -0.34568802, 0.0004347 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6806640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.85327148, -1897.36364746, 16.45227051]), + 'frame': 74612, + 'frame_number': 74612, + 'framesequence': 74610, + 'gaze_dir': array([ 0.98058057, -0.18003826, 0.07776809]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18003826, 0.07776809]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18003826, 0.07776809]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6019504144788, + 'timestamp_carla': 279601, + 'timestamp_device': 279194, + 'timestamp_stream': 279.6019504144788, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00963813, -0.00417894, -0.00219756]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020339950919151306, + 'FR_Wheel_Angle': 0.020343217998743057, + 'Location': array([ 0.27479872, -19.23751831, 0.16209111]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.28642112, -0.34130889, 0.00045504]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6800537109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.59326172, -1898.23901367, 16.45263672]), + 'frame': 74613, + 'frame_number': 74613, + 'framesequence': 74611, + 'gaze_dir': array([ 0.98058057, -0.1802724 , 0.07722381]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1802724 , 0.07722381]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1802724 , 0.07722381]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.60580061376095, + 'timestamp_carla': 279605, + 'timestamp_device': 279197, + 'timestamp_stream': 279.60580061376095, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904351]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00771134, -0.00305129, -0.0025045 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020342307165265083, + 'FR_Wheel_Angle': 0.02034829929471016, + 'Location': array([ 0.26270258, -19.25193405, 0.16210327]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.28231069, -0.33641958, 0.00045957]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6795654296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.39440918, -1898.89978027, 16.45324707]), + 'frame': 74614, + 'frame_number': 74614, + 'framesequence': 74612, + 'gaze_dir': array([ 0.98058057, -0.18057968, 0.07650249]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18057968, 0.07650249]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18057968, 0.07650249]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6092124134302, + 'timestamp_carla': 279608, + 'timestamp_device': 279201, + 'timestamp_stream': 279.6092124134302, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00998963, 0.01179219, -0.00239321]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335162058472633, + 'FR_Wheel_Angle': 0.02033982053399086, + 'Location': array([ 0.24869174, -19.26862717, 0.16211818]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29476333, -0.35124877, 0.00065701]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.678955078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 323.12823486, -1899.77331543, 16.45373535]), + 'frame': 74615, + 'frame_number': 74615, + 'framesequence': 74613, + 'gaze_dir': array([ 0.98058057, -0.18088408, 0.07577997]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18088408, 0.07577997]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18088408, 0.07577997]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6128661110997, + 'timestamp_carla': 279612, + 'timestamp_device': 279205, + 'timestamp_stream': 279.6128661110997, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00117808, 0.00498968, -0.00229405]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033418044447899, + 'FR_Wheel_Angle': 0.020337585359811783, + 'Location': array([ 0.23465531, -19.2853508 , 0.1621453 ]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29647875, -0.35327712, 0.00060852]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.678466796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.85861206, -1900.64575195, 16.4543457 ]), + 'frame': 74616, + 'frame_number': 74616, + 'framesequence': 74614, + 'gaze_dir': array([ 0.98058057, -0.18110991, 0.07523865]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18110991, 0.07523865]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18110991, 0.07523865]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.61639881134033, + 'timestamp_carla': 279615, + 'timestamp_device': 279208, + 'timestamp_stream': 279.61639881134033, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 9.80459736e-05, 3.29438038e-03, -2.75384681e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020332997664809227, + 'FR_Wheel_Angle': 0.02033833973109722, + 'Location': array([ 0.22032285, -19.30242538, 0.16216655]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29853696, -0.35573435, 0.00053721]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.677978515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.65460205, -1901.29772949, 16.45483398]), + 'frame': 74617, + 'frame_number': 74617, + 'framesequence': 74615, + 'gaze_dir': array([ 0.98058057, -0.18140925, 0.07451402]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18140925, 0.07451402]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18140925, 0.07451402]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.61986481398344, + 'timestamp_carla': 279619, + 'timestamp_device': 279212, + 'timestamp_stream': 279.61986481398344, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00589296, -0.0010526 , -0.00239261]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020334307104349136, + 'FR_Wheel_Angle': 0.02033725567162037, + 'Location': array([ 0.20607294, -19.31940651, 0.16218491]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29625601, -0.35300678, 0.00047108]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.677490234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.37887573, -1902.16821289, 16.45532227]), + 'frame': 74618, + 'frame_number': 74618, + 'framesequence': 74616, + 'gaze_dir': array([ 0.98058057, -0.18163353, 0.07396559]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18163353, 0.07396559]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18163353, 0.07396559]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.62342531234026, + 'timestamp_carla': 279622, + 'timestamp_device': 279215, + 'timestamp_stream': 279.62342531234026, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00256062, 0.00179468, -0.00220356]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020333150401711464, + 'FR_Wheel_Angle': 0.02033594250679016, + 'Location': array([ 0.19230658, -19.33580589, 0.16219677]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29827482, -0.35541788, 0.00049674]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6771240234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 322.16818237, -1902.82531738, 16.45568848]), + 'frame': 74619, + 'frame_number': 74619, + 'framesequence': 74617, + 'gaze_dir': array([ 0.98058057, -0.18192779, 0.07323887]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18192779, 0.07323887]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18192779, 0.07323887]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6269098110497, + 'timestamp_carla': 279626, + 'timestamp_device': 279219, + 'timestamp_stream': 279.6269098110497, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0148351 , -0.00884523, -0.00224959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033732831478119, + 'FR_Wheel_Angle': 0.020340820774435997, + 'Location': array([ 0.17862946, -19.35210228, 0.16221203]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29098842, -0.34674236, 0.00045247]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.67626953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.8862915 , -1903.69384766, 16.45654297]), + 'frame': 74620, + 'frame_number': 74620, + 'framesequence': 74618, + 'gaze_dir': array([ 0.98058057, -0.18221912, 0.07251098]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18221912, 0.07251098]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18221912, 0.07251098]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6309369131923, + 'timestamp_carla': 279630, + 'timestamp_device': 279223, + 'timestamp_stream': 279.6309369131923, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00057977, 0.00283487, -0.00276977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033594809472561, + 'FR_Wheel_Angle': 0.020340343937277794, + 'Location': array([ 0.16463444, -19.36877441, 0.1622303 ]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.2933979 , -0.34960407, 0.00047356]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.67578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.60101318, -1904.5612793 , 16.45703125]), + 'frame': 74621, + 'frame_number': 74621, + 'framesequence': 74619, + 'gaze_dir': array([ 0.98058057, -0.18243515, 0.07196569]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18243515, 0.07196569]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18243515, 0.07196569]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.63419491425157, + 'timestamp_carla': 279633, + 'timestamp_device': 279226, + 'timestamp_stream': 279.63419491425157, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0030363 , 0.00064108, -0.00263501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020336277782917023, + 'FR_Wheel_Angle': 0.020341068506240845, + 'Location': array([ 0.15122038, -19.38475609, 0.16224563]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29282066, -0.34892416, 0.00045597]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6754150390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.38531494, -1905.20947266, 16.45739746]), + 'frame': 74622, + 'frame_number': 74622, + 'framesequence': 74620, + 'gaze_dir': array([ 0.98058057, -0.18264957, 0.07141975]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18264957, 0.07141975]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18264957, 0.07141975]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.63773971423507, + 'timestamp_carla': 279637, + 'timestamp_device': 279229, + 'timestamp_stream': 279.63773971423507, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.52122193e-05, 3.89463757e-03, -2.37262854e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335739478468895, + 'FR_Wheel_Angle': 0.02033878117799759, + 'Location': array([ 0.13714762, -19.40152168, 0.16226482]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29376474, -0.35003102, 0.00041697]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6748046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 321.16760254, -1905.85693359, 16.45800781]), + 'frame': 74623, + 'frame_number': 74623, + 'framesequence': 74621, + 'gaze_dir': array([ 0.98058057, -0.18293361, 0.07068899]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18293361, 0.07068899]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18293361, 0.07068899]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.64108681306243, + 'timestamp_carla': 279640, + 'timestamp_device': 279233, + 'timestamp_stream': 279.64108681306243, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00559347, -0.00101467, -0.0022884 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020337363705039024, + 'FR_Wheel_Angle': 0.02033996768295765, + 'Location': array([ 0.12378597, -19.4174366 , 0.16228069]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29093754, -0.34666887, 0.00054805]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.67431640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.87365723, -1906.72155762, 16.45849609]), + 'frame': 74624, + 'frame_number': 74624, + 'framesequence': 74622, + 'gaze_dir': array([ 0.98058057, -0.18314637, 0.07013598]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18314637, 0.07013598]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18314637, 0.07013598]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6444614119828, + 'timestamp_carla': 279643, + 'timestamp_device': 279236, + 'timestamp_stream': 279.6444614119828, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00025727, 0.00311268, -0.00272954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335139706730843, + 'FR_Wheel_Angle': 0.02033931575715542, + 'Location': array([ 0.10983949, -19.43405151, 0.16230072]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-2.94810295e-01, -3.51283967e-01, 3.16553109e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6739501953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.64923096, -1907.37414551, 16.4588623 ]), + 'frame': 74625, + 'frame_number': 74625, + 'framesequence': 74623, + 'gaze_dir': array([ 0.98058057, -0.1833553 , 0.06958793]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1833553 , 0.06958793]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1833553 , 0.06958793]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.64766781404614, + 'timestamp_carla': 279646, + 'timestamp_device': 279239, + 'timestamp_stream': 279.64766781404614, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 6.35023316e-05, 2.98023527e-03, -2.68108770e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335005596280098, + 'FR_Wheel_Angle': 0.020340770483016968, + 'Location': array([ 0.09680992, -19.44957352, 0.16231689]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29504472, -0.3515597 , 0.00046925]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.67333984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.42510986, -1908.01940918, 16.45935059]), + 'frame': 74626, + 'frame_number': 74626, + 'framesequence': 74624, + 'gaze_dir': array([ 0.98058057, -0.18363202, 0.06885436]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18363202, 0.06885436]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18363202, 0.06885436]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6510492116213, + 'timestamp_carla': 279650, + 'timestamp_device': 279243, + 'timestamp_stream': 279.6510492116213, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00766672, -0.0027897 , -0.00207911]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335737615823746, + 'FR_Wheel_Angle': 0.020340783521533012, + 'Location': array([ 0.08209121, -19.46710968, 0.16233227]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29195538, -0.34787661, 0.00039103]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6727294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 320.12249756, -1908.88085938, 16.45996094]), + 'frame': 74627, + 'frame_number': 74627, + 'framesequence': 74625, + 'gaze_dir': array([ 0.98058057, -0.18383712, 0.06830486]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18383712, 0.06830486]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18383712, 0.06830486]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.65456921234727, + 'timestamp_carla': 279653, + 'timestamp_device': 279246, + 'timestamp_stream': 279.65456921234727, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00265233, 0.00156794, -0.00223538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335521548986435, + 'FR_Wheel_Angle': 0.02033800072968006, + 'Location': array([ 0.06874389, -19.48301125, 0.16234802]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29414973, -0.35048571, 0.00047682]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.67236328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 319.89385986, -1909.5246582 , 16.46032715]), + 'frame': 74628, + 'frame_number': 74628, + 'framesequence': 74626, + 'gaze_dir': array([ 0.98058057, -0.18404265, 0.06774914]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18404265, 0.06774914]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18404265, 0.06774914]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6577821113169, + 'timestamp_carla': 279657, + 'timestamp_device': 279249, + 'timestamp_stream': 279.6577821113169, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00605546, -0.00128445, -0.00221526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020336704328656197, + 'FR_Wheel_Angle': 0.02033931016921997, + 'Location': array([ 0.0554922 , -19.49880028, 0.16236541]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29209012, -0.34803137, 0.00046053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 319.66094971, -1910.17419434, 16.46081543]), + 'frame': 74629, + 'frame_number': 74629, + 'framesequence': 74627, + 'gaze_dir': array([ 0.98058057, -0.18431202, 0.06701283]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18431202, 0.06701283]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18431202, 0.06701283]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.66108521446586, + 'timestamp_carla': 279660, + 'timestamp_device': 279253, + 'timestamp_stream': 279.66108521446586, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00068383, 0.00287607, -0.00281225]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033434435725212, + 'FR_Wheel_Angle': 0.02033839374780655, + 'Location': array([ 0.0415289 , -19.51543617, 0.16238602]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29620245, -0.35293177, 0.00042194]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6712646484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 319.34973145, -1911.03271484, 16.46142578]), + 'frame': 74630, + 'frame_number': 74630, + 'framesequence': 74628, + 'gaze_dir': array([ 0.98058057, -0.1845116 , 0.06646131]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1845116 , 0.06646131]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1845116 , 0.06646131]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6647176146507, + 'timestamp_carla': 279664, + 'timestamp_device': 279256, + 'timestamp_stream': 279.6647176146507, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00413138, 0.0005298 , -0.00225849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033403143286705, + 'FR_Wheel_Angle': 0.020338118076324463, + 'Location': array([ 0.02713889, -19.53257751, 0.1624034 ]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-2.96754211e-01, -3.53581905e-01, 1.62792203e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.670654296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 319.11468506, -1911.67407227, 16.46203613]), + 'frame': 74631, + 'frame_number': 74631, + 'framesequence': 74629, + 'gaze_dir': array([ 0.98058057, -0.18477583, 0.06572314]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18477583, 0.06572314]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18477583, 0.06572314]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6682207137346, + 'timestamp_carla': 279667, + 'timestamp_device': 279260, + 'timestamp_stream': 279.6682207137346, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00781753, -0.0028431 , -0.00223481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020336473360657692, + 'FR_Wheel_Angle': 0.020339999347925186, + 'Location': array([ 1.36614665e-02, -1.95486336e+01, 1.62417173e-01]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.2924993 , -0.34851456, 0.00055327]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6700439453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 318.79748535, -1912.53039551, 16.46264648]), + 'frame': 74632, + 'frame_number': 74632, + 'framesequence': 74630, + 'gaze_dir': array([ 0.98058057, -0.18503711, 0.06498392]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18503711, 0.06498392]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18503711, 0.06498392]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6722172126174, + 'timestamp_carla': 279671, + 'timestamp_device': 279264, + 'timestamp_stream': 279.6722172126174, + 'transform': [array([ 0.00865845, -0.00365967, 0.15904458]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00029819, 0.00305683, -0.00289584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020334169268608093, + 'FR_Wheel_Angle': 0.020338300615549088, + 'Location': array([-5.62596018e-04, -1.95655785e+01, 1.62435293e-01]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29650584, -0.35329223, 0.000531 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.669677734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 318.47689819, -1913.38537598, 16.4630127 ]), + 'frame': 74633, + 'frame_number': 74633, + 'framesequence': 74631, + 'gaze_dir': array([ 0.98058057, -0.18536001, 0.06405702]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18536001, 0.06405702]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18536001, 0.06405702]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6763439141214, + 'timestamp_carla': 279675, + 'timestamp_device': 279269, + 'timestamp_stream': 279.6763439141214, + 'transform': [array([ 0.00865829, -0.00365967, 0.15904336]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00587009, 0.00917428, -0.00217423]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033236064016819, + 'FR_Wheel_Angle': 0.020335223525762558, + 'Location': array([-1.45419594e-02, -1.95822315e+01, 1.62429348e-01]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29965791, -0.35705006, 0.00076326]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.668701171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 318.07064819, -1914.45397949, 16.46398926]), + 'frame': 74634, + 'frame_number': 74634, + 'framesequence': 74632, + 'gaze_dir': array([ 0.98058057, -0.18567829, 0.06312852]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18567829, 0.06312852]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18567829, 0.06312852]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6827437132597, + 'timestamp_carla': 279682, + 'timestamp_device': 279274, + 'timestamp_stream': 279.6827437132597, + 'transform': [array([ 0.00865845, -0.00365967, 0.15903252]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00328128, 0.00112551, -0.00219988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020332591608166695, + 'FR_Wheel_Angle': 0.020336534827947617, + 'Location': array([ -0.02791214, -19.5981617 , 0.16246189]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29925939, -0.35656223, 0.00064763]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6678466796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 317.65905762, -1915.52050781, 16.46459961]), + 'frame': 74635, + 'frame_number': 74635, + 'framesequence': 74633, + 'gaze_dir': array([ 0.98058057, -0.18592918, 0.06238571]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18592918, 0.06238571]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18592918, 0.06238571]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.68617191165686, + 'timestamp_carla': 279685, + 'timestamp_device': 279278, + 'timestamp_stream': 279.68617191165686, + 'transform': [array([ 0.00865845, -0.00365967, 0.15903252]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00023132, 0.00306954, -0.00395542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020332567393779755, + 'FR_Wheel_Angle': 0.020335061475634575, + 'Location': array([ -0.04240046, -19.6154213 , 0.1624874 ]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.30193168, -0.35974386, 0.00058841]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.666015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 317.32629395, -1916.37072754, 16.46533203]), + 'frame': 74636, + 'frame_number': 74636, + 'framesequence': 74634, + 'gaze_dir': array([ 0.98058057, -0.18611491, 0.06182937]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18611491, 0.06182937]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18611491, 0.06182937]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.68966011330485, + 'timestamp_carla': 279688, + 'timestamp_device': 279281, + 'timestamp_stream': 279.68966011330485, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01435823, -0.00840812, -0.00230682]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020336851477622986, + 'FR_Wheel_Angle': 0.0203399620950222, + 'Location': array([ -0.05506241, -19.63050652, 0.16250114]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29183477, -0.34771976, 0.00065152]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.66552734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 317.07528687, -1917.00610352, 16.46582031]), + 'frame': 74637, + 'frame_number': 74637, + 'framesequence': 74635, + 'gaze_dir': array([ 0.98058057, -0.18636061, 0.06108483]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18636061, 0.06108483]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18636061, 0.06108483]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.6934049129486, + 'timestamp_carla': 279692, + 'timestamp_device': 279285, + 'timestamp_stream': 279.6934049129486, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00209657, 0.00499375, -0.00292279]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020333394408226013, + 'FR_Wheel_Angle': 0.02033866196870804, + 'Location': array([ -0.06915216, -19.64729309, 0.16252105]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29785994, -0.35489464, 0.0005569 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6650390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 316.73681641, -1917.85412598, 16.46643066]), + 'frame': 74638, + 'frame_number': 74638, + 'framesequence': 74636, + 'gaze_dir': array([ 0.98058057, -0.18660331, 0.06033931]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18660331, 0.06033931]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18660331, 0.06033931]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.69703521206975, + 'timestamp_carla': 279696, + 'timestamp_device': 279289, + 'timestamp_stream': 279.69703521206975, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00109304, 0.00494418, -0.00229479]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020331615582108498, + 'FR_Wheel_Angle': 0.020334428176283836, + 'Location': array([ -0.08327816, -19.66412354, 0.16254279]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.30096638, -0.35858142, 0.00048218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.66455078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 316.39489746, -1918.70092773, 16.46691895]), + 'frame': 74639, + 'frame_number': 74639, + 'framesequence': 74637, + 'gaze_dir': array([ 0.98058057, -0.18678476, 0.05977526]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18678476, 0.05977526]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18678476, 0.05977526]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7005040124059, + 'timestamp_carla': 279699, + 'timestamp_device': 279292, + 'timestamp_stream': 279.7005040124059, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00127272, 0.00222729, -0.00298679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02033057063817978, + 'FR_Wheel_Angle': 0.020335763692855835, + 'Location': array([ -0.09765949, -19.68125534, 0.16256198]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-3.02781165e-01, -3.60752791e-01, 1.35159484e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6639404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 316.13430786, -1919.33984375, 16.4675293 ]), + 'frame': 74640, + 'frame_number': 74640, + 'framesequence': 74638, + 'gaze_dir': array([ 0.98058057, -0.18702224, 0.05902806]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18702224, 0.05902806]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18702224, 0.05902806]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7043316140771, + 'timestamp_carla': 279703, + 'timestamp_device': 279296, + 'timestamp_stream': 279.7043316140771, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01222348, -0.00716766, -0.00257579]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335497334599495, + 'FR_Wheel_Angle': 0.0203416645526886, + 'Location': array([ -0.11140886, -19.69763565, 0.16257331]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-2.94197738e-01, -3.50536913e-01, 1.88670150e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.663330078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 315.78649902, -1920.1842041 , 16.46813965]), + 'frame': 74641, + 'frame_number': 74641, + 'framesequence': 74639, + 'gaze_dir': array([ 0.98058057, -0.18725672, 0.05827992]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18725672, 0.05827992]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18725672, 0.05827992]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7079825140536, + 'timestamp_carla': 279707, + 'timestamp_device': 279300, + 'timestamp_stream': 279.7079825140536, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.001816 , 0.00233 , -0.00228296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020335961133241653, + 'FR_Wheel_Angle': 0.020339420065283775, + 'Location': array([ -0.12542301, -19.71433067, 0.16258903]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29339933, -0.34956449, 0.00052979]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.66259765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 315.4352417 , -1921.02709961, 16.46887207]), + 'frame': 74642, + 'frame_number': 74642, + 'framesequence': 74640, + 'gaze_dir': array([ 0.98058057, -0.18743017, 0.05771963]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18743017, 0.05771963]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18743017, 0.05771963]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7114942111075, + 'timestamp_carla': 279710, + 'timestamp_device': 279303, + 'timestamp_stream': 279.7114942111075, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00583466, 0.00816311, -0.00274924]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020334092900156975, + 'FR_Wheel_Angle': 0.020336667075753212, + 'Location': array([ -0.13950786, -19.73110962, 0.16260895]), + 'Rotation': array([-5.00789434e-02, 4.99819450e+01, -3.75976562e-02]), + 'Velocity': array([-0.29914293, -0.35641041, 0.0004978 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6622314453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 315.17034912, -1921.65673828, 16.46923828]), + 'frame': 74643, + 'frame_number': 74643, + 'framesequence': 74641, + 'gaze_dir': array([ 0.98058057, -0.18760195, 0.05715881]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18760195, 0.05715881]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18760195, 0.05715881]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.71472511440516, + 'timestamp_carla': 279714, + 'timestamp_device': 279306, + 'timestamp_stream': 279.71472511440516, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903363]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01377233, 0.01588581, -0.00246679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02032575011253357, + 'FR_Wheel_Angle': 0.020329708233475685, + 'Location': array([ -0.15294228, -19.74711418, 0.1626123 ]), + 'Rotation': array([-5.02975099e-02, 4.99819641e+01, -3.75976562e-02]), + 'Velocity': array([-0.31119525, -0.37075806, 0.00075925]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6617431640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 314.90350342, -1922.28552246, 16.46972656]), + 'frame': 74644, + 'frame_number': 74644, + 'framesequence': 74642, + 'gaze_dir': array([ 0.98058057, -0.18783069, 0.05640263]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18783069, 0.05640263]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18783069, 0.05640263]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.717913813889, + 'timestamp_carla': 279717, + 'timestamp_device': 279310, + 'timestamp_stream': 279.717913813889, + 'transform': [array([ 0.00865875, -0.00365967, 0.15903482]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0129346 , -0.00670105, -0.00199545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020330822095274925, + 'FR_Wheel_Angle': 0.020333299413323402, + 'Location': array([ -0.1671634 , -19.76405525, 0.16263759]), + 'Rotation': array([-5.02975099e-02, 4.99819641e+01, -3.75976562e-02]), + 'Velocity': array([-3.02347690e-01, -3.60229343e-01, 7.40957257e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.660888671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 314.5411377 , -1923.13122559, 16.47045898]), + 'frame': 74645, + 'frame_number': 74645, + 'framesequence': 74643, + 'gaze_dir': array([ 0.98058057, -0.18810894, 0.05546761]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18810894, 0.05546761]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18810894, 0.05546761]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7230054140091, + 'timestamp_carla': 279722, + 'timestamp_device': 279315, + 'timestamp_stream': 279.7230054140091, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903091]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.02641097, -0.01931345, -0.00240229]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020339880138635635, + 'FR_Wheel_Angle': 0.020344216376543045, + 'Location': array([ -0.1812961 , -19.78088951, 0.16264312]), + 'Rotation': array([-4.95325290e-02, 4.99819679e+01, -3.75976562e-02]), + 'Velocity': array([-2.85975486e-01, -3.40762585e-01, 1.61075586e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6602783203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 314.08905029, -1924.17358398, 16.47131348]), + 'frame': 74646, + 'frame_number': 74646, + 'framesequence': 74644, + 'gaze_dir': array([ 0.98058057, -0.18827565, 0.05489903]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18827565, 0.05489903]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18827565, 0.05489903]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.72654381394386, + 'timestamp_carla': 279725, + 'timestamp_device': 279318, + 'timestamp_stream': 279.72654381394386, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903091]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00580084, -0.00178543, -0.00260175]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02034357562661171, + 'FR_Wheel_Angle': 0.02034619450569153, + 'Location': array([ -0.19456866, -19.79670334, 0.16266128]), + 'Rotation': array([-4.88358513e-02, 4.99820023e+01, -3.75976562e-02]), + 'Velocity': array([-0.28254366, -0.33664396, 0.0006493 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6593017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 313.81176758, -1924.80554199, 16.47180176]), + 'frame': 74647, + 'frame_number': 74647, + 'framesequence': 74645, + 'gaze_dir': array([ 0.98058057, -0.18849361, 0.0541459 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18849361, 0.0541459 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18849361, 0.0541459 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.72989681363106, + 'timestamp_carla': 279729, + 'timestamp_device': 279322, + 'timestamp_stream': 279.72989681363106, + 'transform': [array([ 0.0086586 , -0.00365967, 0.15903091]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00705657, 0.00912462, -0.00277002]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.020339205861091614, + 'FR_Wheel_Angle': 0.02034323662519455, + 'Location': array([ -0.2072852 , -19.81185532, 0.16268454]), + 'Rotation': array([-4.88358513e-02, 4.99820023e+01, -3.75976562e-02]), + 'Velocity': array([-0.28774375, -0.34283087, 0.0006608 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.65869140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 313.44210815, -1925.64050293, 16.47241211]), + 'frame': 74648, + 'frame_number': 74648, + 'framesequence': 74646, + 'gaze_dir': array([ 0.98058057, -0.18870857, 0.05339192]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18870857, 0.05339192]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18870857, 0.05339192]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.73465371131897, + 'timestamp_carla': 279733, + 'timestamp_device': 279326, + 'timestamp_stream': 279.73465371131897, + 'transform': [array([ 0.00865875, -0.00365967, 0.1590289 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00255406, 0.00584232, -0.00207346]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.027962524443864822, + 'FR_Wheel_Angle': 0.03686715289950371, + 'Location': array([ -0.2212624 , -19.82850456, 0.16270801]), + 'Rotation': array([-4.88358513e-02, 4.99820023e+01, -3.75976562e-02]), + 'Velocity': array([-0.29005206, -0.34557471, 0.00054115]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6580810546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 313.06915283, -1926.47399902, 16.47302246]), + 'frame': 74649, + 'frame_number': 74649, + 'framesequence': 74647, + 'gaze_dir': array([ 0.98058057, -0.1889205 , 0.05263707]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1889205 , 0.05263707]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1889205 , 0.05263707]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7383363135159, + 'timestamp_carla': 279737, + 'timestamp_device': 279330, + 'timestamp_stream': 279.7383363135159, + 'transform': [array([ 0.00865875, -0.00365967, 0.1590289 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.004025 , -0.00185619, -0.01819659]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2030460387468338, + 'FR_Wheel_Angle': 0.22886502742767334, + 'Location': array([ -0.23452656, -19.84431458, 0.16272396]), + 'Rotation': array([-4.88358513e-02, 4.99820023e+01, -3.75976562e-02]), + 'Velocity': array([-2.85002142e-01, -3.40224266e-01, 2.60674948e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6572265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 312.69281006, -1927.3059082 , 16.47363281]), + 'frame': 74650, + 'frame_number': 74650, + 'framesequence': 74648, + 'gaze_dir': array([ 0.98058057, -0.18918158, 0.0516909 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18918158, 0.0516909 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18918158, 0.0516909 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7428953126073, + 'timestamp_carla': 279742, + 'timestamp_device': 279335, + 'timestamp_stream': 279.7428953126073, + 'transform': [array([ 0.0086589 , -0.00365967, 0.15902764]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00045948, -0.00141453, -0.05870035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5010737776756287, + 'FR_Wheel_Angle': 0.5187664031982422, + 'Location': array([ -0.24781087, -19.86020279, 0.1627396 ]), + 'Rotation': array([-4.88631688e-02, 4.99805183e+01, -3.75976562e-02]), + 'Velocity': array([-0.2849929 , -0.34199119, 0.00049109]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.65625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 312.21691895, -1928.34533691, 16.47460938]), + 'frame': 74651, + 'frame_number': 74651, + 'framesequence': 74649, + 'gaze_dir': array([ 0.98058057, -0.18933533, 0.05112487]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18933533, 0.05112487]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18933533, 0.05112487]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7464889138937, + 'timestamp_carla': 279745, + 'timestamp_device': 279338, + 'timestamp_stream': 279.7464889138937, + 'transform': [array([ 0.0086589 , -0.00365967, 0.15902764]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00302931, 0.00354283, -0.08969473]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5513813495635986, + 'FR_Wheel_Angle': 0.5607162117958069, + 'Location': array([ -0.26174042, -19.87692451, 0.16275905]), + 'Rotation': array([-4.88358513e-02, 4.99767723e+01, -3.75976562e-02]), + 'Velocity': array([-0.28667477, -0.34526995, 0.00047371]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6556396484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 311.93014526, -1928.96533203, 16.47497559]), + 'frame': 74652, + 'frame_number': 74652, + 'framesequence': 74650, + 'gaze_dir': array([ 0.98058057, -0.1895382 , 0.05036754]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1895382 , 0.05036754]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1895382 , 0.05036754]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7502172142267, + 'timestamp_carla': 279749, + 'timestamp_device': 279342, + 'timestamp_stream': 279.7502172142267, + 'transform': [array([ 0.0086589 , -0.00365967, 0.15902764]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01725314, 0.01604256, -0.10255358]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.6591805815696716, + 'FR_Wheel_Angle': 0.6850717663764954, + 'Location': array([ -0.2744109 , -19.89214516, 0.16277038]), + 'Rotation': array([-4.94710580e-02, 4.99731445e+01, -3.76281701e-02]), + 'Velocity': array([-0.30074185, -0.36258045, 0.00049052]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6549072265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 311.54385376, -1929.79272461, 16.47570801]), + 'frame': 74653, + 'frame_number': 74653, + 'framesequence': 74651, + 'gaze_dir': array([ 0.98058057, -0.18978791, 0.0494183 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18978791, 0.0494183 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18978791, 0.0494183 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7551314122975, + 'timestamp_carla': 279754, + 'timestamp_device': 279347, + 'timestamp_stream': 279.7551314122975, + 'transform': [array([ 0.00865875, -0.00365967, 0.15902475]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00220694, -0.00416051, -0.13961884]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.9109132289886475, + 'FR_Wheel_Angle': 0.9455409049987793, + 'Location': array([ -0.28884861, -19.90953064, 0.16278316]), + 'Rotation': array([-4.97715846e-02, 4.99676590e+01, -3.76281701e-02]), + 'Velocity': array([-0.29410633, -0.35635626, -0.00115826]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.654052734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 311.05563354, -1930.82641602, 16.4765625 ]), + 'frame': 74654, + 'frame_number': 74654, + 'framesequence': 74652, + 'gaze_dir': array([ 0.98058057, -0.18998393, 0.04865917]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18998393, 0.04865917]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18998393, 0.04865917]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7591957114637, + 'timestamp_carla': 279758, + 'timestamp_device': 279351, + 'timestamp_stream': 279.7591957114637, + 'transform': [array([ 0.00865875, -0.00365967, 0.15902475]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00815638, -0.00905768, -0.17979762]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2210687398910522, + 'FR_Wheel_Angle': 1.2611697912216187, + 'Location': array([ -0.30256692, -19.92611694, 0.16280495]), + 'Rotation': array([-4.94095869e-02, 4.99607735e+01, -3.76281738e-02]), + 'Velocity': array([-2.88954377e-01, -3.51987690e-01, 2.67095573e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.653076171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 310.6618042 , -1931.65026855, 16.47717285]), + 'frame': 74655, + 'frame_number': 74655, + 'framesequence': 74653, + 'gaze_dir': array([ 0.98058057, -0.19017695, 0.04789927]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19017695, 0.04789927]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19017695, 0.04789927]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7629766128957, + 'timestamp_carla': 279762, + 'timestamp_device': 279355, + 'timestamp_stream': 279.7629766128957, + 'transform': [array([ 0.00865875, -0.00365967, 0.15902475]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00618694, -0.00651699, -0.21736534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.4244493246078491, + 'FR_Wheel_Angle': 1.4508287906646729, + 'Location': array([ -0.31564102, -19.94200134, 0.16282238]), + 'Rotation': array([-4.87402268e-02, 4.99521065e+01, -3.76281738e-02]), + 'Velocity': array([-0.28316739, -0.34680256, 0.00042455]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6524658203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 310.26483154, -1932.47253418, 16.4777832 ]), + 'frame': 74656, + 'frame_number': 74656, + 'framesequence': 74654, + 'gaze_dir': array([ 0.98058057, -0.19031936, 0.04733029]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19031936, 0.04733029]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19031936, 0.04733029]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7660763114691, + 'timestamp_carla': 279765, + 'timestamp_device': 279358, + 'timestamp_stream': 279.7660763114691, + 'transform': [array([ 0.0086589 , -0.00365967, 0.15902627]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00573825, -0.00335222, -0.23589927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.5295627117156982, + 'FR_Wheel_Angle': 1.5640331506729126, + 'Location': array([ -0.32854924, -19.9577198 , 0.16283943]), + 'Rotation': array([-4.83987182e-02, 4.99422112e+01, -3.77197303e-02]), + 'Velocity': array([-2.80306399e-01, -3.44057679e-01, 3.02798755e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6519775390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 309.96569824, -1933.08666992, 16.47827148]), + 'frame': 74657, + 'frame_number': 74657, + 'framesequence': 74655, + 'gaze_dir': array([ 0.98058057, -0.19050704, 0.04656906]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19050704, 0.04656906]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19050704, 0.04656906]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7699876129627, + 'timestamp_carla': 279769, + 'timestamp_device': 279362, + 'timestamp_stream': 279.7699876129627, + 'transform': [array([ 0.0086589 , -0.00365967, 0.15902627]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00230663, 0.00386022, -0.24249488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.71554434299469, + 'FR_Wheel_Angle': 1.762171745300293, + 'Location': array([ -0.34214604, -19.97430611, 0.16285828]), + 'Rotation': array([-4.82416227e-02, 4.99308891e+01, -3.79333533e-02]), + 'Velocity': array([-0.28093272, -0.34517908, 0.00045878]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6513671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 309.56298828, -1933.90612793, 16.47912598]), + 'frame': 74658, + 'frame_number': 74658, + 'framesequence': 74656, + 'gaze_dir': array([ 0.98058057, -0.1906931 , 0.04580126]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1906931 , 0.04580126]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1906931 , 0.04580126]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.77443801239133, + 'timestamp_carla': 279773, + 'timestamp_device': 279366, + 'timestamp_stream': 279.77443801239133, + 'transform': [array([ 0.0086589 , -0.00365967, 0.15902627]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01215823, 0.01160653, -0.28028086]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.9961124658584595, + 'FR_Wheel_Angle': 2.062148332595825, + 'Location': array([ -0.35514626, -19.99021149, 0.16285564]), + 'Rotation': array([-4.80640382e-02, 4.99190369e+01, -3.80554236e-02]), + 'Velocity': array([-0.28455302, -0.35111767, 0.00085761]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6507568359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 309.15386963, -1934.73034668, 16.47973633]), + 'frame': 74659, + 'frame_number': 74659, + 'framesequence': 74657, + 'gaze_dir': array([ 0.98058057, -0.1908292 , 0.04523075]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1908292 , 0.04523075]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1908292 , 0.04523075]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.77783481404185, + 'timestamp_carla': 279777, + 'timestamp_device': 279369, + 'timestamp_stream': 279.77783481404185, + 'transform': [array([ 0.0086589 , -0.00365967, 0.15902627]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01533439, -0.00648529, -0.31718272]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.237166404724121, + 'FR_Wheel_Angle': 2.2966766357421875, + 'Location': array([ -0.36854723, -20.00667763, 0.16287933]), + 'Rotation': array([-4.80367169e-02, 4.99043274e+01, -3.81469764e-02]), + 'Velocity': array([-0.27184552, -0.33722073, 0.00060072]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6502685546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 308.84796143, -1935.34106445, 16.48022461]), + 'frame': 74660, + 'frame_number': 74660, + 'framesequence': 74658, + 'gaze_dir': array([ 0.98058057, -0.19100852, 0.04446749]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19100852, 0.04446749]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19100852, 0.04446749]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.78135311231017, + 'timestamp_carla': 279780, + 'timestamp_device': 279373, + 'timestamp_stream': 279.78135311231017, + 'transform': [array([ 0.00865906, -0.00365967, 0.15902729]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00947437, -0.00737366, -0.35635492]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.3881430625915527, + 'FR_Wheel_Angle': 2.4613664150238037, + 'Location': array([ -0.38096699, -20.02198601, 0.16289303]), + 'Rotation': array([-4.75381128e-02, 4.98892632e+01, -3.82995643e-02]), + 'Velocity': array([-0.26715243, -0.33342308, 0.00038827]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6495361328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 308.43624878, -1936.15612793, 16.48095703]), + 'frame': 74661, + 'frame_number': 74661, + 'framesequence': 74659, + 'gaze_dir': array([ 0.98058057, -0.19114064, 0.04389604]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19114064, 0.04389604]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19114064, 0.04389604]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.78478491306305, + 'timestamp_carla': 279784, + 'timestamp_device': 279376, + 'timestamp_stream': 279.78478491306305, + 'transform': [array([ 0.00865906, -0.00365967, 0.15902729]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00053269, -0.00201737, -0.38298199]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.672872304916382, + 'FR_Wheel_Angle': 2.7898125648498535, + 'Location': array([ -0.39332911, -20.03726387, 0.16291168]), + 'Rotation': array([-4.69985306e-02, 4.98730965e+01, -3.84826660e-02]), + 'Velocity': array([-0.26288062, -0.32941249, 0.00060741]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.64892578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 308.12609863, -1936.76477051, 16.48156738]), + 'frame': 74662, + 'frame_number': 74662, + 'framesequence': 74660, + 'gaze_dir': array([ 0.98058057, -0.19131459, 0.04313155]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19131459, 0.04313155]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19131459, 0.04313155]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.788275513798, + 'timestamp_carla': 279787, + 'timestamp_device': 279380, + 'timestamp_stream': 279.788275513798, + 'transform': [array([ 0.00865906, -0.00365967, 0.15902729]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.55186749e-03, -4.29350999e-04, -4.36404198e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.0373926162719727, + 'FR_Wheel_Angle': 3.145922899246216, + 'Location': array([ -0.40602568, -20.05303001, 0.1629279 ]), + 'Rotation': array([-4.69302274e-02, 4.98543625e+01, -3.85131761e-02]), + 'Velocity': array([-0.26096103, -0.32936737, 0.00047311]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6483154296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 307.7086792 , -1937.5769043 , 16.48217773]), + 'frame': 74663, + 'frame_number': 74663, + 'framesequence': 74661, + 'gaze_dir': array([ 0.98058057, -0.19144402, 0.04255334]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19144402, 0.04255334]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19144402, 0.04255334]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.791776612401, + 'timestamp_carla': 279791, + 'timestamp_device': 279383, + 'timestamp_stream': 279.791776612401, + 'transform': [array([ 0.00865906, -0.00365967, 0.15902729]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00536849, 0.00123592, -0.50815529]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.3445329666137695, + 'FR_Wheel_Angle': 3.471738338470459, + 'Location': array([ -0.41858119, -20.06869698, 0.16294429]), + 'Rotation': array([-4.70600016e-02, 4.98328285e+01, -3.85742150e-02]), + 'Velocity': array([-0.25937992, -0.32932076, 0.00055026]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6478271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 307.39105225, -1938.18945312, 16.48266602]), + 'frame': 74664, + 'frame_number': 74664, + 'framesequence': 74662, + 'gaze_dir': array([ 0.98058057, -0.19161262, 0.04178765]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19161262, 0.04178765]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19161262, 0.04178765]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7950311116874, + 'timestamp_carla': 279794, + 'timestamp_device': 279387, + 'timestamp_stream': 279.7950311116874, + 'transform': [array([ 0.00865921, -0.00365967, 0.15902849]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.35288453e-02, -3.55153985e-04, -4.62108433e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.645935535430908, + 'FR_Wheel_Angle': 3.8055315017700195, + 'Location': array([ -0.43036261, -20.08345985, 0.1629559 ]), + 'Rotation': array([-4.68687564e-02, 4.98108215e+01, -3.87267955e-02]), + 'Velocity': array([-2.50394523e-01, -3.18085253e-01, 1.10077854e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.64697265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 306.96792603, -1938.99865723, 16.48352051]), + 'frame': 74665, + 'frame_number': 74665, + 'framesequence': 74663, + 'gaze_dir': array([ 0.98058057, -0.19173673, 0.04121441]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19173673, 0.04121441]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19173673, 0.04121441]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.7984144128859, + 'timestamp_carla': 279797, + 'timestamp_device': 279390, + 'timestamp_stream': 279.7984144128859, + 'transform': [array([ 0.00865921, -0.00365967, 0.15902849]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.04738 , 0.02669702, -0.63147771]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9926705360412598, + 'FR_Wheel_Angle': 4.186078071594238, + 'Location': array([ -0.44177538, -20.09782219, 0.16296996]), + 'Rotation': array([-4.71487939e-02, 4.97878113e+01, -3.88183594e-02]), + 'Velocity': array([-0.27227184, -0.34921348, 0.00070852]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.646728515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 306.64932251, -1939.60290527, 16.48388672]), + 'frame': 74666, + 'frame_number': 74666, + 'framesequence': 74664, + 'gaze_dir': array([ 0.98058057, -0.19194059, 0.04025427]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19194059, 0.04025427]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19194059, 0.04025427]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8028137125075, + 'timestamp_carla': 279802, + 'timestamp_device': 279395, + 'timestamp_stream': 279.8028137125075, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902741]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.04789416, 0.02061513, -0.81922346]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.388992786407471, + 'FR_Wheel_Angle': 4.624660491943359, + 'Location': array([ -0.45561823, -20.115345 , 0.16299754]), + 'Rotation': array([-5.02360389e-02, 4.97555809e+01, -3.83605957e-02]), + 'Velocity': array([-0.30307755, -0.39327025, -0.00067688]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6458740234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 306.11206055, -1940.61193848, 16.48474121]), + 'frame': 74667, + 'frame_number': 74667, + 'framesequence': 74665, + 'gaze_dir': array([ 0.98058057, -0.19209999, 0.03948661]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19209999, 0.03948661]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19209999, 0.03948661]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.80767691135406, + 'timestamp_carla': 279806, + 'timestamp_device': 279399, + 'timestamp_stream': 279.80767691135406, + 'transform': [array([ 0.00865921, -0.00365967, 0.15902451]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00749512, -0.00834781, -0.79293823]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.817572116851807, + 'FR_Wheel_Angle': 5.098629951477051, + 'Location': array([ -0.46938032, -20.132864 , 0.16302676]), + 'Rotation': array([-5.06253578e-02, 4.97208481e+01, -3.83911058e-02]), + 'Velocity': array([-0.28991005, -0.37841448, 0.00078894]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6448974609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 305.67922974, -1941.41589355, 16.4855957 ]), + 'frame': 74668, + 'frame_number': 74668, + 'framesequence': 74666, + 'gaze_dir': array([ 0.98058057, -0.19225632, 0.03871832]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19225632, 0.03871832]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19225632, 0.03871832]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.81097411364317, + 'timestamp_carla': 279810, + 'timestamp_device': 279403, + 'timestamp_stream': 279.81097411364317, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902577]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.67809034e-04, -1.10202180e-02, -8.79638970e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.254549980163574, + 'FR_Wheel_Angle': 5.575193881988525, + 'Location': array([ -0.48325756, -20.15063095, 0.16302928]), + 'Rotation': array([-5.00174724e-02, 4.96827240e+01, -3.85742150e-02]), + 'Velocity': array([-0.28972057, -0.38170826, 0.00058037]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.643798828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 305.24316406, -1942.21826172, 16.48620605]), + 'frame': 74669, + 'frame_number': 74669, + 'framesequence': 74667, + 'gaze_dir': array([ 0.98058069, -0.19240957, 0.03794942]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19240957, 0.03794942]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19240957, 0.03794942]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8147841133177, + 'timestamp_carla': 279814, + 'timestamp_device': 279407, + 'timestamp_stream': 279.8147841133177, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902577]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01684844, -0.01815826, -0.92833334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.65797233581543, + 'FR_Wheel_Angle': 6.024302005767822, + 'Location': array([ -0.49671847, -20.16798401, 0.16305263]), + 'Rotation': array([-4.91295494e-02, 4.96418343e+01, -3.87573242e-02]), + 'Velocity': array([-0.27679744, -0.36775729, 0.00040583]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.643310546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 304.80395508, -1943.01879883, 16.48693848]), + 'frame': 74670, + 'frame_number': 74670, + 'framesequence': 74668, + 'gaze_dir': array([ 0.98058069, -0.1925222 , 0.0373738 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1925222 , 0.0373738 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1925222 , 0.0373738 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8185080140829, + 'timestamp_carla': 279817, + 'timestamp_device': 279410, + 'timestamp_stream': 279.8185080140829, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902577]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01315502, -0.01564266, -0.97085315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.021181106567383, + 'FR_Wheel_Angle': 6.426105976104736, + 'Location': array([ -0.50946289, -20.18449974, 0.16307041]), + 'Rotation': array([-4.81801517e-02, 4.96001511e+01, -3.89709510e-02]), + 'Velocity': array([-2.70879358e-01, -3.62428665e-01, 2.36201275e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6427001953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 304.4732666 , -1943.61645508, 16.48742676]), + 'frame': 74671, + 'frame_number': 74671, + 'framesequence': 74669, + 'gaze_dir': array([ 0.98058057, -0.19270682, 0.03640979]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19270682, 0.03640979]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19270682, 0.03640979]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8230903111398, + 'timestamp_carla': 279822, + 'timestamp_device': 279415, + 'timestamp_stream': 279.8230903111398, + 'transform': [array([ 0.00865921, -0.00365967, 0.15902387]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00279644, -0.00741555, -1.02115953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.355508804321289, + 'FR_Wheel_Angle': 6.808523654937744, + 'Location': array([ -0.5219624 , -20.20077705, 0.16308613]), + 'Rotation': array([-4.75107916e-02, 4.95568123e+01, -3.91540527e-02]), + 'Velocity': array([-0.26847038, -0.36110869, 0.00052967]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.641845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 303.91595459, -1944.61450195, 16.48828125]), + 'frame': 74672, + 'frame_number': 74672, + 'framesequence': 74670, + 'gaze_dir': array([ 0.98058057, -0.19281486, 0.03583329]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19281486, 0.03583329]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19281486, 0.03583329]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8263875134289, + 'timestamp_carla': 279825, + 'timestamp_device': 279418, + 'timestamp_stream': 279.8263875134289, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.37687617e-03, -5.96364203e-04, -1.06349146e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.704755783081055, + 'FR_Wheel_Angle': 7.185752868652344, + 'Location': array([ -0.53493667, -20.21776581, 0.16309574]), + 'Rotation': array([-4.72717360e-02, 4.95086250e+01, -3.91845703e-02]), + 'Velocity': array([-0.26966882, -0.36475414, 0.00058819]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.64111328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 303.58044434, -1945.20959473, 16.4888916 ]), + 'frame': 74673, + 'frame_number': 74673, + 'framesequence': 74671, + 'gaze_dir': array([ 0.98058057, -0.19292223, 0.03525059]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19292223, 0.03525059]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19292223, 0.03525059]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8297702111304, + 'timestamp_carla': 279829, + 'timestamp_device': 279421, + 'timestamp_stream': 279.8297702111304, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01917474, 0.00627823, -0.9912191 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.025372505187988, + 'FR_Wheel_Angle': 7.56805419921875, + 'Location': array([ -0.5472011 , -20.23387527, 0.1631068 ]), + 'Rotation': array([-4.70873229e-02, 4.94616547e+01, -3.93371545e-02]), + 'Velocity': array([-2.64999658e-01, -3.56946468e-01, -2.70733814e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6407470703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 303.23986816, -1945.80969238, 16.48937988]), + 'frame': 74674, + 'frame_number': 74674, + 'framesequence': 74672, + 'gaze_dir': array([ 0.98058057, -0.19306161, 0.03447905]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19306161, 0.03447905]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19306161, 0.03447905]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8333596140146, + 'timestamp_carla': 279832, + 'timestamp_device': 279425, + 'timestamp_stream': 279.8333596140146, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01199161, -0.00190765, -1.26770115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.405153274536133, + 'FR_Wheel_Angle': 8.013203620910645, + 'Location': array([ -0.5608232 , -20.25184441, 0.16313262]), + 'Rotation': array([-4.80367169e-02, 4.94056969e+01, -3.91845703e-02]), + 'Velocity': array([-0.27959958, -0.3832233 , 0.00041914]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.639892578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 302.7862854 , -1946.60229492, 16.49023438]), + 'frame': 74675, + 'frame_number': 74675, + 'framesequence': 74673, + 'gaze_dir': array([ 0.98058057, -0.19316386, 0.0339015 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19316386, 0.0339015 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19316386, 0.0339015 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8368053138256, + 'timestamp_carla': 279836, + 'timestamp_device': 279428, + 'timestamp_stream': 279.8368053138256, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01580439, 0.00358914, -1.20803034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.793259143829346, + 'FR_Wheel_Angle': 8.464919090270996, + 'Location': array([ -0.5744701 , -20.26992798, 0.16315627]), + 'Rotation': array([-4.77908328e-02, 4.93457680e+01, -3.93066406e-02]), + 'Velocity': array([-0.27453959, -0.37531301, 0.00041923]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.639404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 302.44488525, -1947.19396973, 16.49072266]), + 'frame': 74676, + 'frame_number': 74676, + 'framesequence': 74674, + 'gaze_dir': array([ 0.98058057, -0.19329785, 0.033129 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19329785, 0.033129 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19329785, 0.033129 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8404890112579, + 'timestamp_carla': 279839, + 'timestamp_device': 279432, + 'timestamp_stream': 279.8404890112579, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00592603, 0.00504981, -1.29488051]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.149539947509766, + 'FR_Wheel_Angle': 8.882625579833984, + 'Location': array([ -0.58707768, -20.28671455, 0.16317219]), + 'Rotation': array([-4.76337373e-02, 4.92877655e+01, -3.93981934e-02]), + 'Velocity': array([-0.2762562 , -0.38021335, 0.00051596]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.638671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 301.98583984, -1947.98327637, 16.49133301]), + 'frame': 74677, + 'frame_number': 74677, + 'framesequence': 74675, + 'gaze_dir': array([ 0.98058057, -0.19339705, 0.03254486]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19339705, 0.03254486]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19339705, 0.03254486]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.84372641146183, + 'timestamp_carla': 279843, + 'timestamp_device': 279435, + 'timestamp_stream': 279.84372641146183, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01560055, -0.01754307, -1.37460685]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.519699096679688, + 'FR_Wheel_Angle': 9.318614959716797, + 'Location': array([ -0.5999738 , -20.30399895, 0.16317295]), + 'Rotation': array([-4.66023795e-02, 4.92251091e+01, -3.97033691e-02]), + 'Velocity': array([-0.25690541, -0.35993728, 0.00060977]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6380615234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 301.6368103 , -1948.57849121, 16.49206543]), + 'frame': 74678, + 'frame_number': 74678, + 'framesequence': 74676, + 'gaze_dir': array([ 0.98058057, -0.1935256 , 0.03177143]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1935256 , 0.03177143]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1935256 , 0.03177143]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.84719921275973, + 'timestamp_carla': 279846, + 'timestamp_device': 279439, + 'timestamp_stream': 279.84719921275973, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01042498, -0.00715375, -1.45255554]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.959859848022461, + 'FR_Wheel_Angle': 9.860122680664062, + 'Location': array([ -0.61206728, -20.32026863, 0.16319187]), + 'Rotation': array([-4.62335497e-02, 4.91637955e+01, -3.97949181e-02]), + 'Velocity': array([-0.26078576, -0.36759368, 0.00049365]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.637451171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 301.17221069, -1949.36462402, 16.49267578]), + 'frame': 74679, + 'frame_number': 74679, + 'framesequence': 74677, + 'gaze_dir': array([ 0.98058057, -0.19361974, 0.03119251]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19361974, 0.03119251]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19361974, 0.03119251]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.85033751279116, + 'timestamp_carla': 279849, + 'timestamp_device': 279442, + 'timestamp_stream': 279.85033751279116, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00905167, 0.00892937, -1.46166539]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.539385795593262, + 'FR_Wheel_Angle': 10.589761734008789, + 'Location': array([ -0.62504804, -20.33781052, 0.16320121]), + 'Rotation': array([-4.64179628e-02, 4.90943680e+01, -3.97644080e-02]), + 'Velocity': array([-0.26540646, -0.37342429, 0.0006101 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.63671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 300.82254028, -1949.95141602, 16.49328613]), + 'frame': 74680, + 'frame_number': 74680, + 'framesequence': 74678, + 'gaze_dir': array([ 0.98058057, -0.19374292, 0.03041821]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19374292, 0.03041821]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19374292, 0.03041821]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.85401621460915, + 'timestamp_carla': 279853, + 'timestamp_device': 279446, + 'timestamp_stream': 279.85401621460915, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00184158, 0.01671175, -1.53240693]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.020062446594238, + 'FR_Wheel_Angle': 11.132659912109375, + 'Location': array([ -0.63691443, -20.35404587, 0.16320439]), + 'Rotation': array([-4.67458107e-02, 4.90245705e+01, -3.93676758e-02]), + 'Velocity': array([-0.26649725, -0.37804455, 0.00104554]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6361083984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 300.35247803, -1950.73425293, 16.49389648]), + 'frame': 74681, + 'frame_number': 74681, + 'framesequence': 74679, + 'gaze_dir': array([ 0.98058057, -0.19383301, 0.02983864]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19383301, 0.02983864]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19383301, 0.02983864]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.857241012156, + 'timestamp_carla': 279856, + 'timestamp_device': 279449, + 'timestamp_stream': 279.857241012156, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01234016, -0.00586872, -1.76484251]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.516090393066406, + 'FR_Wheel_Angle': 11.717400550842285, + 'Location': array([ -0.65015423, -20.3722229 , 0.16324127]), + 'Rotation': array([-4.69302274e-02, 4.89438019e+01, -3.94592248e-02]), + 'Velocity': array([-0.26396757, -0.38278475, 0.0007794 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6353759765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 299.99871826, -1951.31860352, 16.49462891]), + 'frame': 74682, + 'frame_number': 74682, + 'framesequence': 74680, + 'gaze_dir': array([ 0.98058069, -0.19395076, 0.0290635 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19395076, 0.0290635 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19395076, 0.0290635 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8607949130237, + 'timestamp_carla': 279860, + 'timestamp_device': 279453, + 'timestamp_stream': 279.8607949130237, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01797022, 0.0103201 , -1.65230811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.920894622802734, + 'FR_Wheel_Angle': 12.274637222290039, + 'Location': array([ -0.66142821, -20.38780594, 0.16326195]), + 'Rotation': array([-4.68687564e-02, 4.88715019e+01, -3.95202637e-02]), + 'Velocity': array([-2.61181206e-01, -3.76233697e-01, 1.65901176e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.634521484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 299.52313232, -1952.09814453, 16.4954834 ]), + 'frame': 74683, + 'frame_number': 74683, + 'framesequence': 74681, + 'gaze_dir': array([ 0.98058057, -0.19403768, 0.0284774 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19403768, 0.0284774 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19403768, 0.0284774 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8645972125232, + 'timestamp_carla': 279863, + 'timestamp_device': 279456, + 'timestamp_stream': 279.8645972125232, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.02267617, 0.01012086, -1.72035515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.448114395141602, + 'FR_Wheel_Angle': 12.896320343017578, + 'Location': array([ -0.67432964, -20.40576553, 0.1632698 ]), + 'Rotation': array([-4.61993963e-02, 4.87835388e+01, -3.97644043e-02]), + 'Velocity': array([-0.25377524, -0.36758929, -0.00058071]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6341552734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 299.16174316, -1952.68591309, 16.49584961]), + 'frame': 74684, + 'frame_number': 74684, + 'framesequence': 74682, + 'gaze_dir': array([ 0.98058069, -0.19414999, 0.02770145]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19414999, 0.02770145]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19414999, 0.02770145]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.86791141331196, + 'timestamp_carla': 279867, + 'timestamp_device': 279460, + 'timestamp_stream': 279.86791141331196, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.63810095e-04, 4.29252614e-05, -2.01711726e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.958698272705078, + 'FR_Wheel_Angle': 13.55435848236084, + 'Location': array([ -0.68815404, -20.42509079, 0.16329776]), + 'Rotation': array([-4.72444147e-02, 4.86827469e+01, -3.90625000e-02]), + 'Velocity': array([-2.65889138e-01, -3.92835140e-01, 1.26519197e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.63330078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 298.6807251 , -1953.46203613, 16.4967041 ]), + 'frame': 74685, + 'frame_number': 74685, + 'framesequence': 74683, + 'gaze_dir': array([ 0.98058069, -0.19423196, 0.02712068]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19423196, 0.02712068]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19423196, 0.02712068]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8713608123362, + 'timestamp_carla': 279870, + 'timestamp_device': 279463, + 'timestamp_stream': 279.8713608123362, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01144575, -0.01030651, -2.02794361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.465810775756836, + 'FR_Wheel_Angle': 14.226980209350586, + 'Location': array([ -0.7001881 , -20.44204712, 0.16330455]), + 'Rotation': array([-4.66911718e-02, 4.85925636e+01, -3.91845666e-02]), + 'Velocity': array([-0.25627762, -0.38364691, 0.00054428]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 298.31884766, -1954.04150391, 16.49719238]), + 'frame': 74686, + 'frame_number': 74686, + 'framesequence': 74684, + 'gaze_dir': array([ 0.98058069, -0.19431219, 0.02653966]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19431219, 0.02653966]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19431219, 0.02653966]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.87471341341734, + 'timestamp_carla': 279874, + 'timestamp_device': 279466, + 'timestamp_stream': 279.87471341341734, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00611471, 0.00577456, -2.15804315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.985074996948242, + 'FR_Wheel_Angle': 14.850194931030273, + 'Location': array([ -0.7133882 , -20.46073723, 0.16332377]), + 'Rotation': array([-4.69985306e-02, 4.84875259e+01, -3.88793908e-02]), + 'Velocity': array([-0.2669113 , -0.39948767, 0.00064704]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.632080078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 297.95523071, -1954.61975098, 16.4979248 ]), + 'frame': 74687, + 'frame_number': 74687, + 'framesequence': 74685, + 'gaze_dir': array([ 0.98058069, -0.19441673, 0.02576263]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19441673, 0.02576263]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19441673, 0.02576263]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.87827161327004, + 'timestamp_carla': 279877, + 'timestamp_device': 279470, + 'timestamp_stream': 279.87827161327004, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01114971, 0.00330333, -2.19761658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.477900505065918, + 'FR_Wheel_Angle': 15.510152816772461, + 'Location': array([ -0.7265622 , -20.47954369, 0.16333331]), + 'Rotation': array([-4.65409048e-02, 4.83788719e+01, -3.90014574e-02]), + 'Velocity': array([-0.26193306, -0.39584449, 0.00056205]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.63134765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 297.4664917 , -1955.39099121, 16.49865723]), + 'frame': 74688, + 'frame_number': 74688, + 'framesequence': 74686, + 'gaze_dir': array([ 0.98058069, -0.19449368, 0.02517514]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19449368, 0.02517514]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19449368, 0.02517514]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8816627115011, + 'timestamp_carla': 279881, + 'timestamp_device': 279473, + 'timestamp_stream': 279.8816627115011, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.57569419e-03, -1.71913989e-02, -2.44238114e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.081109046936035, + 'FR_Wheel_Angle': 16.30512046813965, + 'Location': array([ -0.73981899, -20.49863815, 0.1633506 ]), + 'Rotation': array([-4.60764542e-02, 4.82625084e+01, -3.89099084e-02]), + 'Velocity': array([-0.25316542, -0.39320704, 0.00048494]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6307373046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 297.09509277, -1955.97265625, 16.49926758]), + 'frame': 74689, + 'frame_number': 74689, + 'framesequence': 74687, + 'gaze_dir': array([ 0.98058057, -0.19459276, 0.02439739]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19459276, 0.02439739]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19459276, 0.02439739]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.88491671159863, + 'timestamp_carla': 279884, + 'timestamp_device': 279477, + 'timestamp_stream': 279.88491671159863, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00452239, -0.01660482, -2.5264504 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.604772567749023, + 'FR_Wheel_Angle': 16.99931526184082, + 'Location': array([ -0.75165218, -20.51579475, 0.1633639 ]), + 'Rotation': array([-4.54685651e-02, 4.81539879e+01, -3.90319824e-02]), + 'Velocity': array([-0.24860048, -0.38974488, 0.00049474]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.630126953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 296.60098267, -1956.74047852, 16.49975586]), + 'frame': 74690, + 'frame_number': 74690, + 'framesequence': 74688, + 'gaze_dir': array([ 0.98058069, -0.19466485, 0.02381531]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19466485, 0.02381531]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19466485, 0.02381531]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.88867151364684, + 'timestamp_carla': 279888, + 'timestamp_device': 279480, + 'timestamp_stream': 279.88867151364684, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.0051016 , -0.02093109, -2.60931587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.083189964294434, + 'FR_Wheel_Angle': 17.642770767211914, + 'Location': array([ -0.7634533 , -20.53302956, 0.16337509]), + 'Rotation': array([-4.50792462e-02, 4.80405273e+01, -3.90624925e-02]), + 'Velocity': array([-2.42504016e-01, -3.85523945e-01, -7.21883771e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.62939453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 296.22924805, -1957.31359863, 16.50048828]), + 'frame': 74691, + 'frame_number': 74691, + 'framesequence': 74689, + 'gaze_dir': array([ 0.98058069, -0.1947585 , 0.02303689]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1947585 , 0.02303689]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1947585 , 0.02303689]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.89217291399837, + 'timestamp_carla': 279891, + 'timestamp_device': 279484, + 'timestamp_stream': 279.89217291399837, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.04180071, 0.00853418, -2.30986214]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.599597930908203, + 'FR_Wheel_Angle': 18.34099578857422, + 'Location': array([ -0.77486897, -20.54977989, 0.16337761]), + 'Rotation': array([-4.42527942e-02, 4.79277534e+01, -3.94897461e-02]), + 'Velocity': array([-2.32588977e-01, -3.63594323e-01, 1.75528519e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.628662109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 295.72979736, -1958.07800293, 16.5012207 ]), + 'frame': 74692, + 'frame_number': 74692, + 'framesequence': 74690, + 'gaze_dir': array([ 0.98058057, -0.19482651, 0.02245432]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19482651, 0.02245432]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19482651, 0.02245432]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8957314118743, + 'timestamp_carla': 279895, + 'timestamp_device': 279487, + 'timestamp_stream': 279.8957314118743, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01306098, -0.03848722, -2.5299716 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.19270133972168, + 'FR_Wheel_Angle': 19.198963165283203, + 'Location': array([ -0.78558522, -20.56576538, 0.16334972]), + 'Rotation': array([-4.27296609e-02, 4.78139038e+01, -3.98864672e-02]), + 'Velocity': array([-0.20492788, -0.33907402, -0.00105368]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.628173828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 295.35418701, -1958.6484375 , 16.50170898]), + 'frame': 74693, + 'frame_number': 74693, + 'framesequence': 74691, + 'gaze_dir': array([ 0.98058069, -0.19489349, 0.0218656 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19489349, 0.0218656 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19489349, 0.0218656 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.8988618142903, + 'timestamp_carla': 279898, + 'timestamp_device': 279490, + 'timestamp_stream': 279.8988618142903, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01608556, -0.0192122 , -2.54550886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.793581008911133, + 'FR_Wheel_Angle': 20.00037956237793, + 'Location': array([ -0.79539949, -20.58045197, 0.16336311]), + 'Rotation': array([-4.15685289e-02, 4.77079887e+01, -4.05883789e-02]), + 'Velocity': array([-0.19973564, -0.32890525, 0.00096348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.62744140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 294.97290039, -1959.22363281, 16.50244141]), + 'frame': 74694, + 'frame_number': 74694, + 'framesequence': 74692, + 'gaze_dir': array([ 0.98058057, -0.19497932, 0.02108628]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19497932, 0.02108628]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19497932, 0.02108628]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9021588116884, + 'timestamp_carla': 279901, + 'timestamp_device': 279494, + 'timestamp_stream': 279.9021588116884, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.04228312, 0.01814645, -2.73685145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.42812728881836, + 'FR_Wheel_Angle': 20.884275436401367, + 'Location': array([ -0.80676961, -20.59747505, 0.16341339]), + 'Rotation': array([-4.39454354e-02, 4.75805893e+01, -3.89099121e-02]), + 'Velocity': array([-0.23386084, -0.37806204, 0.00068561]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6268310546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 294.46582031, -1959.98303223, 16.50305176]), + 'frame': 74695, + 'frame_number': 74695, + 'framesequence': 74693, + 'gaze_dir': array([ 0.98058069, -0.19504151, 0.02050306]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19504151, 0.02050306]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19504151, 0.02050306]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.90564131364226, + 'timestamp_carla': 279905, + 'timestamp_device': 279497, + 'timestamp_stream': 279.90564131364226, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00771374, 0.01552687, -2.83604336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.992328643798828, + 'FR_Wheel_Angle': 21.676511764526367, + 'Location': array([ -0.81800336, -20.61450577, 0.16344151]), + 'Rotation': array([-4.52500023e-02, 4.74469872e+01, -3.79638597e-02]), + 'Velocity': array([-0.23443174, -0.3841587 , 0.00045811]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6260986328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 294.08441162, -1960.54968262, 16.50378418]), + 'frame': 74696, + 'frame_number': 74696, + 'framesequence': 74694, + 'gaze_dir': array([ 0.98058057, -0.19512191, 0.01972316]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19512191, 0.01972316]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19512191, 0.01972316]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9091682136059, + 'timestamp_carla': 279908, + 'timestamp_device': 279501, + 'timestamp_stream': 279.9091682136059, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.35258322e-03, -2.56811026e-02, -3.08724213e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.599437713623047, + 'FR_Wheel_Angle': 22.595905303955078, + 'Location': array([ -0.82946229, -20.63207245, 0.16344462]), + 'Rotation': array([-4.50177751e-02, 4.73039818e+01, -3.79638672e-02]), + 'Velocity': array([-2.15884998e-01, -3.70118737e-01, 2.79669766e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.62548828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 293.57208252, -1961.30554199, 16.50439453]), + 'frame': 74697, + 'frame_number': 74697, + 'framesequence': 74695, + 'gaze_dir': array([ 0.98058069, -0.19519922, 0.01894295]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19519922, 0.01894295]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19519922, 0.01894295]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.91305711120367, + 'timestamp_carla': 279912, + 'timestamp_device': 279505, + 'timestamp_stream': 279.91305711120367, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.03832414, 0.01493373, -2.76472974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.228609085083008, + 'FR_Wheel_Angle': 23.465538024902344, + 'Location': array([ -0.84018904, -20.64863396, 0.16344959]), + 'Rotation': array([-4.40069064e-02, 4.71655235e+01, -3.87573205e-02]), + 'Velocity': array([-2.10917696e-01, -3.52116257e-01, 3.83901570e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6246337890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 293.05664062, -1962.0592041 , 16.50512695]), + 'frame': 74698, + 'frame_number': 74698, + 'framesequence': 74696, + 'gaze_dir': array([ 0.98058057, -0.19525553, 0.01835312]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19525553, 0.01835312]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19525553, 0.01835312]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.916576012969, + 'timestamp_carla': 279915, + 'timestamp_device': 279508, + 'timestamp_stream': 279.916576012969, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.09410128e-02, -2.06209929e-03, -3.26767826e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.777883529663086, + 'FR_Wheel_Angle': 24.265256881713867, + 'Location': array([ -0.85002959, -20.6639328 , 0.16346404]), + 'Rotation': array([-4.40683775e-02, 4.70335159e+01, -3.86047326e-02]), + 'Velocity': array([-0.22321269, -0.38051879, 0.00075792]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6241455078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 292.6651001 , -1962.62744141, 16.50561523]), + 'frame': 74699, + 'frame_number': 74699, + 'framesequence': 74697, + 'gaze_dir': array([ 0.98058069, -0.19532737, 0.01757238]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19532737, 0.01757238]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19532737, 0.01757238]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9199941121042, + 'timestamp_carla': 279919, + 'timestamp_device': 279512, + 'timestamp_stream': 279.9199941121042, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.07030822, -0.01085678, -3.27999544]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.395967483520508, + 'FR_Wheel_Angle': 25.138248443603516, + 'Location': array([ -0.86147606, -20.68185043, 0.16348431]), + 'Rotation': array([-4.52500023e-02, 4.68739128e+01, -3.73840332e-02]), + 'Velocity': array([-0.23407699, -0.40774435, 0.00056703]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.623046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 292.14437866, -1963.37756348, 16.50671387]), + 'frame': 74700, + 'frame_number': 74700, + 'framesequence': 74698, + 'gaze_dir': array([ 0.98058069, -0.19537903, 0.01698813]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19537903, 0.01698813]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19537903, 0.01698813]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.92353171110153, + 'timestamp_carla': 279922, + 'timestamp_device': 279515, + 'timestamp_stream': 279.92353171110153, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 7.36516714e-03, -2.60519842e-03, -2.91920853e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.966102600097656, + 'FR_Wheel_Angle': 26.021377563476562, + 'Location': array([ -0.87301129, -20.70012856, 0.16350624]), + 'Rotation': array([-4.59603406e-02, 4.67061920e+01, -3.65295410e-02]), + 'Velocity': array([-0.22598982, -0.39871088, -0.00040174]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.62255859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 291.75286865, -1963.93725586, 16.50732422]), + 'frame': 74701, + 'frame_number': 74701, + 'framesequence': 74699, + 'gaze_dir': array([ 0.98058069, -0.19542895, 0.01640373]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19542895, 0.01640373]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19542895, 0.01640373]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9267820119858, + 'timestamp_carla': 279926, + 'timestamp_device': 279518, + 'timestamp_stream': 279.9267820119858, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.93247807e-03, -1.18239247e-03, -4.16577482e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.53655433654785, + 'FR_Wheel_Angle': 26.880680084228516, + 'Location': array([ -0.88478047, -20.71884537, 0.16352688]), + 'Rotation': array([-4.58988696e-02, 4.65224457e+01, -3.65295410e-02]), + 'Velocity': array([-0.22769344, -0.40475872, 0.00050569]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6221923828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 291.35971069, -1964.49584961, 16.50756836]), + 'frame': 74702, + 'frame_number': 74702, + 'framesequence': 74700, + 'gaze_dir': array([ 0.98058057, -0.19547762, 0.01581322]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19547762, 0.01581322]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19547762, 0.01581322]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9298602119088, + 'timestamp_carla': 279929, + 'timestamp_device': 279521, + 'timestamp_stream': 279.9298602119088, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.67593099e-02, -2.99746403e-03, -4.27194452e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.16993522644043, + 'FR_Wheel_Angle': 27.848388671875, + 'Location': array([ -0.89583081, -20.73655319, 0.16353783]), + 'Rotation': array([-4.54070941e-02, 4.63444786e+01, -3.67736779e-02]), + 'Velocity': array([-2.21537471e-01, -3.98617417e-01, 3.78308294e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6214599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 290.96084595, -1965.05895996, 16.50830078]), + 'frame': 74703, + 'frame_number': 74703, + 'framesequence': 74701, + 'gaze_dir': array([ 0.98058069, -0.19553928, 0.01503162]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19553928, 0.01503162]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19553928, 0.01503162]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9332008138299, + 'timestamp_carla': 279932, + 'timestamp_device': 279525, + 'timestamp_stream': 279.9332008138299, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00508974, -0.00853264, -3.62842798]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.85647201538086, + 'FR_Wheel_Angle': 28.91102409362793, + 'Location': array([ -0.90736115, -20.7552166 , 0.16354972]), + 'Rotation': array([-4.48333584e-02, 4.61522903e+01, -3.68957557e-02]), + 'Velocity': array([-2.17699260e-01, -3.98756504e-01, 3.34677694e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6207275390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 290.43041992, -1965.80224609, 16.5090332 ]), + 'frame': 74704, + 'frame_number': 74704, + 'framesequence': 74702, + 'gaze_dir': array([ 0.98058069, -0.1955978 , 0.01424977]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1955978 , 0.01424977]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1955978 , 0.01424977]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9371704123914, + 'timestamp_carla': 279936, + 'timestamp_device': 279529, + 'timestamp_stream': 279.9371704123914, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.60184845e-03, 1.33030387e-02, -4.01355505e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.522197723388672, + 'FR_Wheel_Angle': 29.93036460876465, + 'Location': array([ -0.91856754, -20.77342796, 0.16354781]), + 'Rotation': array([-4.45533209e-02, 4.59523506e+01, -3.69567871e-02]), + 'Velocity': array([-0.22389382, -0.4057003 , 0.00069672]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.619873046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.89703369, -1966.54333496, 16.5098877 ]), + 'frame': 74705, + 'frame_number': 74705, + 'framesequence': 74703, + 'gaze_dir': array([ 0.98058069, -0.19565322, 0.0134677 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19565322, 0.0134677 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19565322, 0.0134677 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.94095561280847, + 'timestamp_carla': 279940, + 'timestamp_device': 279533, + 'timestamp_stream': 279.94095561280847, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.04136418, -0.02526344, -4.50108957]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.171262741088867, + 'FR_Wheel_Angle': 30.95463752746582, + 'Location': array([ -0.92964232, -20.79181671, 0.16354805]), + 'Rotation': array([-4.46147919e-02, 4.57535019e+01, -3.63159217e-02]), + 'Velocity': array([-0.21788563, -0.41663033, 0.00092111]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 289.36071777, -1967.28234863, 16.51062012]), + 'frame': 74706, + 'frame_number': 74706, + 'framesequence': 74704, + 'gaze_dir': array([ 0.98058069, -0.19569261, 0.0128825 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19569261, 0.0128825 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19569261, 0.0128825 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.94453831389546, + 'timestamp_carla': 279943, + 'timestamp_device': 279536, + 'timestamp_stream': 279.94453831389546, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.04048074, 0.01882459, -4.18539858]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.770423889160156, + 'FR_Wheel_Angle': 31.8980712890625, + 'Location': array([ -0.93991292, -20.80898666, 0.1635704 ]), + 'Rotation': array([-4.44986783e-02, 4.55629349e+01, -3.63159180e-02]), + 'Velocity': array([-0.21242094, -0.39875895, 0.00063088]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.618408203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.95751953, -1967.83374023, 16.51135254]), + 'frame': 74707, + 'frame_number': 74707, + 'framesequence': 74705, + 'gaze_dir': array([ 0.98058069, -0.19573027, 0.01229718]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19573027, 0.01229718]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19573027, 0.01229718]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.94780181348324, + 'timestamp_carla': 279947, + 'timestamp_device': 279539, + 'timestamp_stream': 279.94780181348324, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.03243208, 0.01478632, -4.24039316]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.420207977294922, + 'FR_Wheel_Angle': 32.98125457763672, + 'Location': array([ -0.95047325, -20.82688141, 0.16358615]), + 'Rotation': array([-4.36107554e-02, 4.53566475e+01, -3.68957482e-02]), + 'Velocity': array([-0.2040353 , -0.3896873 , 0.00061272]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.617919921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.55273438, -1968.3840332 , 16.51171875]), + 'frame': 74708, + 'frame_number': 74708, + 'framesequence': 74706, + 'gaze_dir': array([ 0.98058069, -0.19577786, 0.01151459]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19577786, 0.01151459]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19577786, 0.01151459]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.95095981284976, + 'timestamp_carla': 279950, + 'timestamp_device': 279543, + 'timestamp_stream': 279.95095981284976, + 'transform': [array([ 0.00865936, -0.00365967, 0.15902512]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0188066 , 0.01626603, -4.41194677]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.073543548583984, + 'FR_Wheel_Angle': 33.96874237060547, + 'Location': array([ -0.96074003, -20.84431648, 0.16359608]), + 'Rotation': array([-4.36722264e-02, 4.51531219e+01, -3.66516113e-02]), + 'Velocity': array([-0.20604695, -0.39674515, 0.00058743]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6170654296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 288.0090332 , -1969.11755371, 16.51257324]), + 'frame': 74709, + 'frame_number': 74709, + 'framesequence': 74707, + 'gaze_dir': array([ 0.98058069, -0.19583303, 0.0105346 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19583303, 0.0105346 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19583303, 0.0105346 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9557428136468, + 'timestamp_carla': 279955, + 'timestamp_device': 279548, + 'timestamp_stream': 279.9557428136468, + 'transform': [array([ 0.00865921, -0.00365967, 0.15902169]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01086748, -0.03140829, -4.79032373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.72216033935547, + 'FR_Wheel_Angle': 35.02981948852539, + 'Location': array([ -0.97051132, -20.8611927 , 0.16360985]), + 'Rotation': array([-4.33648676e-02, 4.49473419e+01, -3.64990234e-02]), + 'Velocity': array([-1.91011086e-01, -3.93087447e-01, 3.08699615e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.615966796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 287.32424927, -1970.03283691, 16.51367188]), + 'frame': 74710, + 'frame_number': 74710, + 'framesequence': 74708, + 'gaze_dir': array([ 0.98058057, -0.19586395, 0.0099429 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19586395, 0.0099429 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19586395, 0.0099429 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.95976231247187, + 'timestamp_carla': 279959, + 'timestamp_device': 279551, + 'timestamp_stream': 279.95976231247187, + 'transform': [array([ 0.00865921, -0.00365967, 0.15902169]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.35992793e-03, 2.14272365e-02, -4.51104736e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.378267288208008, + 'FR_Wheel_Angle': 36.13502883911133, + 'Location': array([ -0.98043948, -20.87841415, 0.1636031 ]), + 'Rotation': array([-4.30301912e-02, 4.47350540e+01, -3.69262695e-02]), + 'Velocity': array([-2.02024281e-01, -3.95106375e-01, 2.72359845e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.614990234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.90859985, -1970.58361816, 16.51428223]), + 'frame': 74711, + 'frame_number': 74711, + 'framesequence': 74709, + 'gaze_dir': array([ 0.98058069, -0.19591993, 0.00877118]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19591993, 0.00877118]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19591993, 0.00877118]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.96522841230035, + 'timestamp_carla': 279964, + 'timestamp_device': 279557, + 'timestamp_stream': 279.96522841230035, + 'transform': [array([ 0.00865906, -0.00365967, 0.1590157 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.02686006, -0.034172 , -5.03227043]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.06136703491211, + 'FR_Wheel_Angle': 37.21574783325195, + 'Location': array([ -0.99059993, -20.89630508, 0.16362347]), + 'Rotation': array([-4.30028699e-02, 4.45042610e+01, -3.63769531e-02]), + 'Velocity': array([-0.18394327, -0.39082322, 0.00069519]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.61376953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 286.0809021 , -1971.67053223, 16.51550293]), + 'frame': 74712, + 'frame_number': 74712, + 'framesequence': 74710, + 'gaze_dir': array([ 0.98058069, -0.19594553, 0.00817922]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19594553, 0.00817922]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19594553, 0.00817922]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.96846491470933, + 'timestamp_carla': 279967, + 'timestamp_device': 279560, + 'timestamp_stream': 279.96846491470933, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.04350445, -0.02650799, -5.18938828]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.783327102661133, + 'FR_Wheel_Angle': 38.41624450683594, + 'Location': array([ -1.00027716, -20.9136219 , 0.16364536]), + 'Rotation': array([-4.27569821e-02, 4.42733459e+01, -3.62854004e-02]), + 'Velocity': array([-0.1837189 , -0.39358869, 0.00069401]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6126708984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.66027832, -1972.21765137, 16.51599121]), + 'frame': 74713, + 'frame_number': 74713, + 'framesequence': 74711, + 'gaze_dir': array([ 0.98058057, -0.19597666, 0.0073958 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19597666, 0.0073958 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19597666, 0.0073958 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9721903130412, + 'timestamp_carla': 279971, + 'timestamp_device': 279564, + 'timestamp_stream': 279.9721903130412, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.02869409, -0.02322645, -5.28459597]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.506832122802734, + 'FR_Wheel_Angle': 39.62684631347656, + 'Location': array([ -1.00979972, -20.93088913, 0.16366397]), + 'Rotation': array([-4.29687165e-02, 4.40353737e+01, -3.55834961e-02]), + 'Velocity': array([-0.17845632, -0.39228228, 0.0006388 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6116943359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 285.10131836, -1972.9395752 , 16.51696777]), + 'frame': 74714, + 'frame_number': 74714, + 'framesequence': 74712, + 'gaze_dir': array([ 0.98058069, -0.19599789, 0.00680966]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19599789, 0.00680966]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19599789, 0.00680966]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.97588811442256, + 'timestamp_carla': 279975, + 'timestamp_device': 279567, + 'timestamp_stream': 279.97588811442256, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.42069592e-03, 1.66077409e-02, -5.23304749e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.256595611572266, + 'FR_Wheel_Angle': 40.87528610229492, + 'Location': array([ -1.01976168, -20.94916916, 0.16368282]), + 'Rotation': array([-4.33648676e-02, 4.37773666e+01, -3.50036621e-02]), + 'Velocity': array([-0.18504123, -0.39709854, 0.00043247]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6109619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 284.68121338, -1973.47827148, 16.5177002 ]), + 'frame': 74715, + 'frame_number': 74715, + 'framesequence': 74713, + 'gaze_dir': array([ 0.98058069, -0.19602355, 0.00602605]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19602355, 0.00602605]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19602355, 0.00602605]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.97925981134176, + 'timestamp_carla': 279978, + 'timestamp_device': 279571, + 'timestamp_stream': 279.97925981134176, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 5.32197766e-03, 2.21701600e-02, -5.49215746e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.796236038208008, + 'FR_Wheel_Angle': 41.682518005371094, + 'Location': array([ -1.02888072, -20.96613503, 0.1637006 ]), + 'Rotation': array([-4.40069064e-02, 4.35302238e+01, -3.38745117e-02]), + 'Velocity': array([-1.88212410e-01, -4.09268796e-01, 3.46446031e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6102294921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 284.1171875 , -1974.19628906, 16.51843262]), + 'frame': 74716, + 'frame_number': 74716, + 'framesequence': 74714, + 'gaze_dir': array([ 0.98058069, -0.19604607, 0.00524234]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19604607, 0.00524234]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19604607, 0.00524234]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.983372412622, + 'timestamp_carla': 279982, + 'timestamp_device': 279575, + 'timestamp_stream': 279.983372412622, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.0260049 , -0.01837769, -6.0470686 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.793840408325195, + 'FR_Wheel_Angle': 41.6781005859375, + 'Location': array([ -1.03897107, -20.98498154, 0.16371661]), + 'Rotation': array([-4.45806421e-02, 4.32521935e+01, -3.32641564e-02]), + 'Velocity': array([-1.84744865e-01, -4.21950400e-01, 2.67651078e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 283.55029297, -1974.91210938, 16.51928711]), + 'frame': 74717, + 'frame_number': 74717, + 'framesequence': 74715, + 'gaze_dir': array([ 0.98058057, -0.19606087, 0.00465599]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19606087, 0.00465599]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19606087, 0.00465599]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.98671541363, + 'timestamp_carla': 279986, + 'timestamp_device': 279578, + 'timestamp_stream': 279.98671541363, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.02606451, 0.03462061, -5.71143341]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.790142059326172, + 'FR_Wheel_Angle': 41.675289154052734, + 'Location': array([ -1.04908478, -21.0036869 , 0.1637315 ]), + 'Rotation': array([-4.48948294e-02, 4.29754601e+01, -3.37524377e-02]), + 'Velocity': array([-1.97015733e-01, -4.22168583e-01, 2.41100788e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6087646484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 283.12438965, -1975.44604492, 16.51989746]), + 'frame': 74718, + 'frame_number': 74718, + 'framesequence': 74716, + 'gaze_dir': array([ 0.98058069, -0.19607791, 0.00387215]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19607791, 0.00387215]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19607791, 0.00387215]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.990172713995, + 'timestamp_carla': 279989, + 'timestamp_device': 279582, + 'timestamp_stream': 279.990172713995, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.04827498, 0.03715359, -5.61574173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.615406036376953, + 'FR_Wheel_Angle': 41.37859344482422, + 'Location': array([ -1.05905688, -21.02194214, 0.1637394 ]), + 'Rotation': array([-4.47992086e-02, 4.27051010e+01, -3.44848633e-02]), + 'Velocity': array([-1.96458578e-01, -4.15581822e-01, 3.33285338e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.60791015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 282.55249023, -1976.15795898, 16.52075195]), + 'frame': 74719, + 'frame_number': 74719, + 'framesequence': 74717, + 'gaze_dir': array([ 0.98058069, -0.19608872, 0.00327973]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19608872, 0.00327973]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19608872, 0.00327973]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9933986142278, + 'timestamp_carla': 279992, + 'timestamp_device': 279585, + 'timestamp_stream': 279.9933986142278, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.05074105, 0.03502757, -5.58350515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.681228637695312, + 'FR_Wheel_Angle': 41.51264190673828, + 'Location': array([ -1.06940758, -21.04060173, 0.16374622]), + 'Rotation': array([-4.46762666e-02, 4.24296913e+01, -3.52172852e-02]), + 'Velocity': array([-1.97783560e-01, -4.12338287e-01, 3.62157822e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.607421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 282.1184082 , -1976.69433594, 16.52124023]), + 'frame': 74720, + 'frame_number': 74720, + 'framesequence': 74718, + 'gaze_dir': array([ 0.98058069, -0.19609764, 0.00269327]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19609764, 0.00269327]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19609764, 0.00269327]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.9965397119522, + 'timestamp_carla': 279995, + 'timestamp_device': 279588, + 'timestamp_stream': 279.9965397119522, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901783]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.05737225, 0.0341339 , -5.46083927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79652976989746, + 'FR_Wheel_Angle': 41.686405181884766, + 'Location': array([ -1.07956004, -21.05875778, 0.16375667]), + 'Rotation': array([-4.43757363e-02, 4.21603928e+01, -3.58886681e-02]), + 'Velocity': array([-1.96512163e-01, -4.05257910e-01, 2.42257112e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6068115234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.68713379, -1977.22412109, 16.52185059]), + 'frame': 74721, + 'frame_number': 74721, + 'framesequence': 74719, + 'gaze_dir': array([ 0.98058057, -0.19610481, 0.00210679]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19610481, 0.00210679]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19610481, 0.00210679]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 279.99973011389375, + 'timestamp_carla': 279999, + 'timestamp_device': 279591, + 'timestamp_stream': 279.99973011389375, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901783]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01973742, -0.02148317, -5.94126415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79644775390625, + 'FR_Wheel_Angle': 41.6812744140625, + 'Location': array([ -1.09003174, -21.07733917, 0.16377071]), + 'Rotation': array([-4.40069064e-02, 4.18824921e+01, -3.63159180e-02]), + 'Velocity': array([-0.19235402, -0.41139743, 0.00046846]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.606201171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 281.2543335 , -1977.75244141, 16.52258301]), + 'frame': 74722, + 'frame_number': 74722, + 'framesequence': 74720, + 'gaze_dir': array([ 0.98058069, -0.19611168, 0.00132278]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19611168, 0.00132278]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19611168, 0.00132278]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0036864131689, + 'timestamp_carla': 280003, + 'timestamp_device': 279595, + 'timestamp_stream': 280.0036864131689, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901783]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0079519 , 0.02207433, -5.68366814]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79125213623047, + 'FR_Wheel_Angle': 41.67374038696289, + 'Location': array([ -1.10047221, -21.09553909, 0.16378899]), + 'Rotation': array([-4.43142653e-02, 4.16109200e+01, -3.60717736e-02]), + 'Velocity': array([-2.07196608e-01, -4.16669071e-01, 2.82502180e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.60546875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 280.67327881, -1978.45678711, 16.52331543]), + 'frame': 74723, + 'frame_number': 74723, + 'framesequence': 74721, + 'gaze_dir': array([ 9.80580688e-01, -1.96115389e-01, 5.38758934e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, -1.96115389e-01, 5.38758934e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, -1.96115389e-01, 5.38758934e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0077734142542, + 'timestamp_carla': 280007, + 'timestamp_device': 279599, + 'timestamp_stream': 280.0077734142542, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.02742079, 0.02223166, -5.63338041]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.792879104614258, + 'FR_Wheel_Angle': 41.67930603027344, + 'Location': array([ -1.11101031, -21.11379814, 0.16379799]), + 'Rotation': array([-4.43757363e-02, 4.13367538e+01, -3.59191895e-02]), + 'Velocity': array([-0.20565231, -0.41094467, 0.00048024]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6046142578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 280.08935547, -1979.15881348, 16.52404785]), + 'frame': 74724, + 'frame_number': 74724, + 'framesequence': 74722, + 'gaze_dir': array([ 9.80580688e-01, -1.96115956e-01, -2.51258869e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, -1.96115956e-01, -2.51258869e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, -1.96115956e-01, -2.51258869e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0112020112574, + 'timestamp_carla': 280010, + 'timestamp_device': 279603, + 'timestamp_stream': 280.0112020112574, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.00736377, 0.01965311, -5.78905153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78660774230957, + 'FR_Wheel_Angle': 41.66813659667969, + 'Location': array([ -1.12129319, -21.13134003, 0.16381492]), + 'Rotation': array([-4.46421131e-02, 4.10738678e+01, -3.54003869e-02]), + 'Velocity': array([-2.14890987e-01, -4.22853261e-01, 3.54082586e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.603515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.49810791, -1979.86376953, 16.52502441]), + 'frame': 74725, + 'frame_number': 74725, + 'framesequence': 74723, + 'gaze_dir': array([ 9.80580688e-01, -1.96114331e-01, -8.37785366e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, -1.96114331e-01, -8.37785366e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, -1.96114331e-01, -8.37785366e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.01453741267323, + 'timestamp_carla': 280013, + 'timestamp_device': 279606, + 'timestamp_stream': 280.01453741267323, + 'transform': [array([ 0.00865921, -0.00365967, 0.1590168 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.02320786, -0.02217975, -6.17094278]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78847885131836, + 'FR_Wheel_Angle': 41.668792724609375, + 'Location': array([ -1.13273251, -21.15075111, 0.16382888]), + 'Rotation': array([-4.46762666e-02, 4.07801628e+01, -3.50646935e-02]), + 'Velocity': array([-0.2089339 , -0.42477146, 0.00045577]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.60302734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 279.05737305, -1980.38562012, 16.5255127 ]), + 'frame': 74726, + 'frame_number': 74726, + 'framesequence': 74724, + 'gaze_dir': array([ 0.98058069, -0.19611095, -0.0014243 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19611095, -0.0014243 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19611095, -0.0014243 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.01762031391263, + 'timestamp_carla': 280017, + 'timestamp_device': 279609, + 'timestamp_stream': 280.01762031391263, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901783]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01776974, -0.02783095, -6.20603371]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.790599822998047, + 'FR_Wheel_Angle': 41.67536544799805, + 'Location': array([ -1.14357746, -21.16890144, 0.16383937]), + 'Rotation': array([-4.46421131e-02, 4.05050926e+01, -3.50952148e-02]), + 'Velocity': array([-2.06816420e-01, -4.21347648e-01, -2.25415220e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6024169921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.6151123 , -1980.90612793, 16.52612305]), + 'frame': 74727, + 'frame_number': 74727, + 'framesequence': 74725, + 'gaze_dir': array([ 0.98058069, -0.19610368, -0.0022083 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19610368, -0.0022083 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19610368, -0.0022083 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0218839123845, + 'timestamp_carla': 280021, + 'timestamp_device': 279613, + 'timestamp_stream': 280.0218839123845, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.01377448, -0.02061892, -6.09931421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.792720794677734, + 'FR_Wheel_Angle': 41.677490234375, + 'Location': array([ -1.15407336, -21.186306 , 0.16384944]), + 'Rotation': array([-4.43142653e-02, 4.02400551e+01, -3.57666053e-02]), + 'Velocity': array([-2.07338572e-01, -4.14734900e-01, 1.42474179e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 278.02142334, -1981.59985352, 16.52709961]), + 'frame': 74728, + 'frame_number': 74728, + 'framesequence': 74726, + 'gaze_dir': array([ 0.98058069, -0.19609329, -0.00299227]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19609329, -0.00299227]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19609329, -0.00299227]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0251656137407, + 'timestamp_carla': 280024, + 'timestamp_device': 279617, + 'timestamp_stream': 280.0251656137407, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.0336948 , 0.03053257, -5.67562819]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.790590286254883, + 'FR_Wheel_Angle': 41.676666259765625, + 'Location': array([ -1.16563225, -21.2052269 , 0.16386074]), + 'Rotation': array([-4.43142653e-02, 3.99521561e+01, -3.61022986e-02]), + 'Velocity': array([-2.18584433e-01, -4.10142690e-01, 1.91020968e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.6004638671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 277.42492676, -1982.29125977, 16.52807617]), + 'frame': 74729, + 'frame_number': 74729, + 'framesequence': 74727, + 'gaze_dir': array([ 0.98058069, -0.19608335, -0.0035847 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19608335, -0.0035847 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19608335, -0.0035847 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0284803137183, + 'timestamp_carla': 280027, + 'timestamp_device': 279620, + 'timestamp_stream': 280.0284803137183, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.02595911, -0.0252041 , -6.03958035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.794767379760742, + 'FR_Wheel_Angle': 41.68001937866211, + 'Location': array([ -1.1763792 , -21.22262955, 0.16386108]), + 'Rotation': array([-4.40683775e-02, 3.96867180e+01, -3.67736816e-02]), + 'Velocity': array([-0.20933485, -0.40796751, 0.00043938]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5999755859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.97241211, -1982.81213379, 16.52856445]), + 'frame': 74730, + 'frame_number': 74730, + 'framesequence': 74728, + 'gaze_dir': array([ 0.98058069, -0.19607174, -0.00417111]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19607174, -0.00417111]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19607174, -0.00417111]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0317956134677, + 'timestamp_carla': 280031, + 'timestamp_device': 279623, + 'timestamp_stream': 280.0317956134677, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.03443888, -0.02010498, -6.03142595]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79362678527832, + 'FR_Wheel_Angle': 41.67731857299805, + 'Location': array([ -1.1874125 , -21.24036598, 0.16387267]), + 'Rotation': array([-4.41025272e-02, 3.94141693e+01, -3.67431603e-02]), + 'Velocity': array([-0.21293733, -0.40894312, 0.00048929]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.599365234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 276.52282715, -1983.32641602, 16.5291748 ]), + 'frame': 74731, + 'frame_number': 74731, + 'framesequence': 74729, + 'gaze_dir': array([ 0.98058069, -0.1960535 , -0.00495493]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1960535 , -0.00495493]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1960535 , -0.00495493]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.03541991114616, + 'timestamp_carla': 280034, + 'timestamp_device': 279627, + 'timestamp_stream': 280.03541991114616, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.04120328, -0.01297029, -6.2069931 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.788076400756836, + 'FR_Wheel_Angle': 41.668418884277344, + 'Location': array([ -1.19858325, -21.25816536, 0.16388187]), + 'Rotation': array([-4.45806421e-02, 3.91375656e+01, -3.59497033e-02]), + 'Velocity': array([-0.22159149, -0.41933292, 0.00043839]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5985107421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.91949463, -1984.01184082, 16.5300293 ]), + 'frame': 74732, + 'frame_number': 74732, + 'framesequence': 74730, + 'gaze_dir': array([ 0.98058069, -0.19603212, -0.00573867]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19603212, -0.00573867]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19603212, -0.00573867]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0393324121833, + 'timestamp_carla': 280038, + 'timestamp_device': 279631, + 'timestamp_stream': 280.0393324121833, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.01271279, 0.02459559, -5.89727354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.784727096557617, + 'FR_Wheel_Angle': 41.66611862182617, + 'Location': array([ -1.21033311, -21.27655411, 0.16390449]), + 'Rotation': array([-4.52295095e-02, 3.88539238e+01, -3.57971229e-02]), + 'Velocity': array([-0.23280494, -0.41878581, 0.00047332]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5975341796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 275.31341553, -1984.69470215, 16.53088379]), + 'frame': 74733, + 'frame_number': 74733, + 'framesequence': 74731, + 'gaze_dir': array([ 0.98058069, -0.19600761, -0.00652232]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19600761, -0.00652232]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19600761, -0.00652232]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0429646112025, + 'timestamp_carla': 280042, + 'timestamp_device': 279635, + 'timestamp_stream': 280.0429646112025, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.02023278, -0.02275672, -6.22904015]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.787311553955078, + 'FR_Wheel_Angle': 41.66898727416992, + 'Location': array([ -1.22294068, -21.29610634, 0.16391537]), + 'Rotation': array([-4.54070941e-02, 3.85517044e+01, -3.59497070e-02]), + 'Velocity': array([-2.25871444e-01, -4.19191569e-01, 2.73718819e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5968017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.7046814 , -1985.37524414, 16.53161621]), + 'frame': 74734, + 'frame_number': 74734, + 'framesequence': 74732, + 'gaze_dir': array([ 0.98058069, -0.19598724, -0.0071085 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19598724, -0.0071085 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19598724, -0.0071085 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.046467512846, + 'timestamp_carla': 280045, + 'timestamp_device': 279638, + 'timestamp_stream': 280.046467512846, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.02770175, -0.02006642, -6.25221586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78660774230957, + 'FR_Wheel_Angle': 41.66659164428711, + 'Location': array([ -1.23422372, -21.31341934, 0.16392711]), + 'Rotation': array([-4.52841520e-02, 3.82829170e+01, -3.62548791e-02]), + 'Velocity': array([-2.29387566e-01, -4.19283539e-01, 3.46441258e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.59619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 274.24749756, -1985.8828125 , 16.53222656]), + 'frame': 74735, + 'frame_number': 74735, + 'framesequence': 74733, + 'gaze_dir': array([ 0.98058069, -0.19595723, -0.00789196]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19595723, -0.00789196]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19595723, -0.00789196]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0500082112849, + 'timestamp_carla': 280049, + 'timestamp_device': 279642, + 'timestamp_stream': 280.0500082112849, + 'transform': [array([ 0.00865921, -0.00365967, 0.15901631]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.02505511, 0.01357443, -6.15525532]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77686882019043, + 'FR_Wheel_Angle': 41.65457534790039, + 'Location': array([ -1.24626839, -21.33158493, 0.1639342 ]), + 'Rotation': array([-4.56871316e-02, 3.80037346e+01, -3.61633301e-02]), + 'Velocity': array([-0.24904449, -0.43089402, 0.00051663]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5953369140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 273.63391113, -1986.55908203, 16.53308105]), + 'frame': 74736, + 'frame_number': 74736, + 'framesequence': 74734, + 'gaze_dir': array([ 0.98058069, -0.19591528, -0.0088726 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19591528, -0.0088726 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19591528, -0.0088726 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.055429212749, + 'timestamp_carla': 280054, + 'timestamp_device': 279647, + 'timestamp_stream': 280.055429212749, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.03035258, -0.01877235, -6.51400805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77880859375, + 'FR_Wheel_Angle': 41.651798248291016, + 'Location': array([ -1.25907755, -21.35081673, 0.16395374]), + 'Rotation': array([-4.60491329e-02, 3.77011337e+01, -3.54309082e-02]), + 'Velocity': array([-2.43013903e-01, -4.33241218e-01, 3.81081103e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.59423828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.86203003, -1987.40209961, 16.53417969]), + 'frame': 74737, + 'frame_number': 74737, + 'framesequence': 74735, + 'gaze_dir': array([ 0.98058069, -0.19587824, -0.00965576]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19587824, -0.00965576]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19587824, -0.00965576]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.05920511111617, + 'timestamp_carla': 280058, + 'timestamp_device': 279651, + 'timestamp_stream': 280.05920511111617, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.03202829, -0.0205855 , -6.57355118]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.776376724243164, + 'FR_Wheel_Angle': 41.649742126464844, + 'Location': array([ -1.27131093, -21.36896706, 0.16396587]), + 'Rotation': array([-4.63291705e-02, 3.74163971e+01, -3.53698768e-02]), + 'Velocity': array([-2.47873187e-01, -4.37414616e-01, 3.30851064e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5927734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 272.24237061, -1988.07275391, 16.53491211]), + 'frame': 74738, + 'frame_number': 74738, + 'framesequence': 74736, + 'gaze_dir': array([ 0.98058069, -0.19584818, -0.01024751]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19584818, -0.01024751]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19584818, -0.01024751]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0626050122082, + 'timestamp_carla': 280062, + 'timestamp_device': 279654, + 'timestamp_stream': 280.0626050122082, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.02270817, 0.02473253, -6.24292803]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77288246154785, + 'FR_Wheel_Angle': 41.647579193115234, + 'Location': array([ -1.28463221, -21.38851547, 0.16398083]), + 'Rotation': array([-4.64794338e-02, 3.71095734e+01, -3.54309082e-02]), + 'Velocity': array([-2.60158390e-01, -4.35865521e-01, 2.75869359e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5921630859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.77236938, -1988.57788086, 16.53564453]), + 'frame': 74739, + 'frame_number': 74739, + 'framesequence': 74737, + 'gaze_dir': array([ 0.98058069, -0.19580562, -0.01103039]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19580562, -0.01103039]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19580562, -0.01103039]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0660964138806, + 'timestamp_carla': 280065, + 'timestamp_device': 279658, + 'timestamp_stream': 280.0660964138806, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.06212245, 0.03161701, -6.0197835 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.777612686157227, + 'FR_Wheel_Angle': 41.65454864501953, + 'Location': array([ -1.29779351, -21.40764046, 0.16398735]), + 'Rotation': array([-4.62950207e-02, 3.68074722e+01, -3.60107459e-02]), + 'Velocity': array([-2.56926090e-01, -4.24237728e-01, 6.70146910e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.59130859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 271.14807129, -1989.2442627 , 16.53637695]), + 'frame': 74740, + 'frame_number': 74740, + 'framesequence': 74738, + 'gaze_dir': array([ 0.98058069, -0.19577177, -0.01161594]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19577177, -0.01161594]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19577177, -0.01161594]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0696147121489, + 'timestamp_carla': 280069, + 'timestamp_device': 279661, + 'timestamp_stream': 280.0696147121489, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.05047414, 0.02115439, -5.93027973]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.782934188842773, + 'FR_Wheel_Angle': 41.66477584838867, + 'Location': array([ -1.30948925, -21.42443466, 0.16398743]), + 'Rotation': array([-0.04559834, 36.54302216, -0.03723145]), + 'Velocity': array([-0.25165385, -0.41286081, 0.00048038]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.590576171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 270.67932129, -1989.74108887, 16.53710938]), + 'frame': 74741, + 'frame_number': 74741, + 'framesequence': 74739, + 'gaze_dir': array([ 0.98058069, -0.19572376, -0.0123985 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19572376, -0.0123985 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19572376, -0.0123985 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.07322511449456, + 'timestamp_carla': 280072, + 'timestamp_device': 279665, + 'timestamp_stream': 280.07322511449456, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.07395935, -0.02483721, -6.6444912 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.775054931640625, + 'FR_Wheel_Angle': 41.64413070678711, + 'Location': array([ -1.3233844 , -21.44421387, 0.16400306]), + 'Rotation': array([-0.04556419, 36.22918701, -0.03729248]), + 'Velocity': array([-0.25918117, -0.43404299, 0.00055665]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5897216796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 270.05041504, -1990.40307617, 16.53796387]), + 'frame': 74742, + 'frame_number': 74742, + 'framesequence': 74740, + 'gaze_dir': array([ 0.98058069, -0.19568582, -0.0129838 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19568582, -0.0129838 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19568582, -0.0129838 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0764771141112, + 'timestamp_carla': 280075, + 'timestamp_device': 279668, + 'timestamp_stream': 280.0764771141112, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.06415455, -0.01739407, -6.88070297]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.765625, + 'FR_Wheel_Angle': 41.630409240722656, + 'Location': array([ -1.33628738, -21.46228981, 0.16402812]), + 'Rotation': array([-4.68072854e-02, 3.59404678e+01, -3.57055701e-02]), + 'Velocity': array([-0.27333063, -0.45206437, 0.00046771]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.589111328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 269.57818604, -1990.89660645, 16.53857422]), + 'frame': 74743, + 'frame_number': 74743, + 'framesequence': 74741, + 'gaze_dir': array([ 0.98058069, -0.19563191, -0.01377198]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19563191, -0.01377198]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19563191, -0.01377198]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0798526145518, + 'timestamp_carla': 280079, + 'timestamp_device': 279672, + 'timestamp_stream': 280.0798526145518, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.00776747, 0.02236608, -6.72513771]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.756391525268555, + 'FR_Wheel_Angle': 41.6151237487793, + 'Location': array([ -1.35155046, -21.48340607, 0.16404773]), + 'Rotation': array([-4.79479246e-02, 3.56043549e+01, -3.46679725e-02]), + 'Velocity': array([-2.93964297e-01, -4.63984132e-01, 3.65459913e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5882568359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 268.93981934, -1991.55908203, 16.53942871]), + 'frame': 74744, + 'frame_number': 74744, + 'framesequence': 74742, + 'gaze_dir': array([ 0.98058069, -0.19558984, -0.014357 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19558984, -0.014357 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19558984, -0.014357 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.08361541107297, + 'timestamp_carla': 280083, + 'timestamp_device': 279675, + 'timestamp_stream': 280.08361541107297, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.38398992e-05, 2.19989400e-02, -6.96751070e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.749298095703125, + 'FR_Wheel_Angle': 41.60524368286133, + 'Location': array([ -1.36589062, -21.5030899 , 0.16406578]), + 'Rotation': array([-4.85558137e-02, 3.52875557e+01, -3.41186486e-02]), + 'Velocity': array([-0.30410692, -0.47574633, 0.00054463]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.587646484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 268.46417236, -1992.04931641, 16.53991699]), + 'frame': 74745, + 'frame_number': 74745, + 'framesequence': 74743, + 'gaze_dir': array([ 0.98058069, -0.19553088, -0.01513881]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19553088, -0.01513881]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19553088, -0.01513881]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.08696691319346, + 'timestamp_carla': 280086, + 'timestamp_device': 279679, + 'timestamp_stream': 280.08696691319346, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.03459573, -0.0098239 , -7.55952311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742679595947266, + 'FR_Wheel_Angle': 41.591007232666016, + 'Location': array([ -1.3819102 , -21.52479935, 0.16408542]), + 'Rotation': array([-4.91910204e-02, 3.49363937e+01, -3.36303636e-02]), + 'Velocity': array([-3.11410546e-01, -4.93370891e-01, 4.53667628e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.586669921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.82598877, -1992.70239258, 16.54101562]), + 'frame': 74746, + 'frame_number': 74746, + 'framesequence': 74744, + 'gaze_dir': array([ 0.98058069, -0.19548473, -0.01572352]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19548473, -0.01572352]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19548473, -0.01572352]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0901111140847, + 'timestamp_carla': 280089, + 'timestamp_device': 279682, + 'timestamp_stream': 280.0901111140847, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-0.05505073, -0.01833468, -7.90267038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731857299804688, + 'FR_Wheel_Angle': 41.572078704833984, + 'Location': array([ -1.39790952, -21.54610062, 0.1641005 ]), + 'Rotation': array([-4.99560013e-02, 3.45932770e+01, -3.32641527e-02]), + 'Velocity': array([-3.28433990e-01, -5.13616562e-01, 4.19564225e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5860595703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 267.34692383, -1993.18933105, 16.54150391]), + 'frame': 74747, + 'frame_number': 74747, + 'framesequence': 74745, + 'gaze_dir': array([ 0.98058069, -0.1954203 , -0.0165049 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1954203 , -0.0165049 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1954203 , -0.0165049 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.0940679125488, + 'timestamp_carla': 280093, + 'timestamp_device': 279686, + 'timestamp_stream': 280.0940679125488, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-9.69661102e-02, 4.67667822e-04, -8.27866554e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.711410522460938, + 'FR_Wheel_Angle': 41.54957580566406, + 'Location': array([ -1.41410792, -21.56731224, 0.16410831]), + 'Rotation': array([-5.06253578e-02, 3.42538414e+01, -3.30810510e-02]), + 'Velocity': array([-0.36362052, -0.54548085, 0.00065259]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5850830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 266.70422363, -1993.83789062, 16.54248047]), + 'frame': 74748, + 'frame_number': 74748, + 'framesequence': 74746, + 'gaze_dir': array([ 0.98058069, -0.19535275, -0.01728602]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19535275, -0.01728602]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19535275, -0.01728602]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.09811951220036, + 'timestamp_carla': 280097, + 'timestamp_device': 279690, + 'timestamp_stream': 280.09811951220036, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.12658159e-02, -2.38549127e-03, -8.31542587e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.705110549926758, + 'FR_Wheel_Angle': 41.530208587646484, + 'Location': array([ -1.43333328, -21.59194946, 0.16414413]), + 'Rotation': array([-5.20596988e-02, 3.38567963e+01, -3.17077562e-02]), + 'Velocity': array([-0.37441635, -0.55769598, 0.00063944]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5843505859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 266.05895996, -1994.48388672, 16.54321289]), + 'frame': 74749, + 'frame_number': 74749, + 'framesequence': 74747, + 'gaze_dir': array([ 0.98058069, -0.19529964, -0.01787614]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19529964, -0.01787614]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19529964, -0.01787614]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.10132771357894, + 'timestamp_carla': 280100, + 'timestamp_device': 279693, + 'timestamp_stream': 280.10132771357894, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.22382799e-02, 6.80282805e-03, -9.09389305e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69864845275879, + 'FR_Wheel_Angle': 41.516357421875, + 'Location': array([ -1.45270395, -21.61655045, 0.16416866]), + 'Rotation': array([-5.22782654e-02, 3.34449806e+01, -3.16772498e-02]), + 'Velocity': array([-3.87409419e-01, -5.67524433e-01, 4.60789190e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5836181640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 265.56958008, -1994.97033691, 16.54394531]), + 'frame': 74750, + 'frame_number': 74750, + 'framesequence': 74748, + 'gaze_dir': array([ 0.98058069, -0.19522661, -0.01865677]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19522661, -0.01865677]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19522661, -0.01865677]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.10489071160555, + 'timestamp_carla': 280104, + 'timestamp_device': 279697, + 'timestamp_stream': 280.10489071160555, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.29968440e-02, 1.73826306e-03, -8.58500957e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.693580627441406, + 'FR_Wheel_Angle': 41.509395599365234, + 'Location': array([ -1.47368467, -21.64286995, 0.1641843 ]), + 'Rotation': array([-5.20323776e-02, 3.30057373e+01, -3.24096680e-02]), + 'Velocity': array([-3.97959560e-01, -5.75737000e-01, 3.38616373e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.582763671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 264.91983032, -1995.61181641, 16.5447998 ]), + 'frame': 74751, + 'frame_number': 74751, + 'framesequence': 74749, + 'gaze_dir': array([ 0.98058069, -0.19516994, -0.01924055]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19516994, -0.01924055]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19516994, -0.01924055]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1081092134118, + 'timestamp_carla': 280107, + 'timestamp_device': 279700, + 'timestamp_stream': 280.1081092134118, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.87609284e-03, 2.51443079e-03, -8.89710045e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.684961318969727, + 'FR_Wheel_Angle': 41.49475860595703, + 'Location': array([ -1.49316597, -21.6669445 , 0.16420288]), + 'Rotation': array([-0.0520597 , 32.60310364, -0.03289795]), + 'Velocity': array([-4.14207727e-01, -5.89497745e-01, 5.65576542e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.58203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 264.43203735, -1996.09008789, 16.54553223]), + 'frame': 74752, + 'frame_number': 74752, + 'framesequence': 74750, + 'gaze_dir': array([ 0.98058069, -0.19511153, -0.01982417]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19511153, -0.01982417]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19511153, -0.01982417]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.11139491200447, + 'timestamp_carla': 280110, + 'timestamp_device': 279703, + 'timestamp_stream': 280.11139491200447, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.29552912e-02, 8.77309591e-03, -9.79222012e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.676799774169922, + 'FR_Wheel_Angle': 41.47886276245117, + 'Location': array([ -1.51509488, -21.69355583, 0.16422595]), + 'Rotation': array([-0.05240121, 32.15060425, -0.03302002]), + 'Velocity': array([-4.30890292e-01, -6.01264000e-01, 2.66554358e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5814208984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 263.94287109, -1996.56677246, 16.54614258]), + 'frame': 74753, + 'frame_number': 74753, + 'framesequence': 74751, + 'gaze_dir': array([ 0.98058069, -0.19505073, -0.02041356]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19505073, -0.02041356]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19505073, -0.02041356]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1146305128932, + 'timestamp_carla': 280114, + 'timestamp_device': 279706, + 'timestamp_stream': 280.1146305128932, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 7.13638775e-03, 8.17743223e-03, -9.96588802e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.668376922607422, + 'FR_Wheel_Angle': 41.46585464477539, + 'Location': array([ -1.5359962 , -21.71855927, 0.16424701]), + 'Rotation': array([-0.05252415, 31.72432899, -0.03317261]), + 'Velocity': array([-4.47234899e-01, -6.14542425e-01, 5.14519226e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5806884765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 263.44720459, -1997.046875 , 16.546875 ]), + 'frame': 74754, + 'frame_number': 74754, + 'framesequence': 74752, + 'gaze_dir': array([ 0.98058069, -0.1949888 , -0.02099681]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1949888 , -0.02099681]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1949888 , -0.02099681]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.11779391393065, + 'timestamp_carla': 280117, + 'timestamp_device': 279709, + 'timestamp_stream': 280.11779391393065, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 7.24086724e-03, 2.10308284e-02, -9.40223503e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.652849197387695, + 'FR_Wheel_Angle': 41.43329620361328, + 'Location': array([ -1.56062043, -21.74746704, 0.16427048]), + 'Rotation': array([-0.05319351, 31.24383163, -0.03329467]), + 'Velocity': array([-4.77913707e-01, -6.35424972e-01, 4.73697175e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.580078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 262.95513916, -1997.52050781, 16.54748535]), + 'frame': 74755, + 'frame_number': 74755, + 'framesequence': 74753, + 'gaze_dir': array([ 0.98058069, -0.19490331, -0.02177616]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19490331, -0.02177616]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19490331, -0.02177616]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.12121491134167, + 'timestamp_carla': 280120, + 'timestamp_device': 279713, + 'timestamp_stream': 280.12121491134167, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-8.36697314e-03, 1.49460603e-02, -9.89450455e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.637128829956055, + 'FR_Wheel_Angle': 41.41204071044922, + 'Location': array([ -1.58465159, -21.77508926, 0.16429916]), + 'Rotation': array([-0.05410875, 30.79051781, -0.03283691]), + 'Velocity': array([-0.50619227, -0.66104412, 0.00073086]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5791015625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 262.29516602, -1998.15161133, 16.54833984]), + 'frame': 74756, + 'frame_number': 74756, + 'framesequence': 74754, + 'gaze_dir': array([ 0.98058069, -0.19483729, -0.02235897]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19483729, -0.02235897]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19483729, -0.02235897]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1246395111084, + 'timestamp_carla': 280124, + 'timestamp_device': 279716, + 'timestamp_stream': 280.1246395111084, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 3.98411462e-03, 4.02937597e-03, -1.03448153e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63212013244629, + 'FR_Wheel_Angle': 41.40254211425781, + 'Location': array([ -1.61180115, -21.80583382, 0.16432506]), + 'Rotation': array([-0.05440928, 30.28160095, -0.03292846]), + 'Velocity': array([-5.22060037e-01, -6.73353553e-01, 6.26783352e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.57861328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 261.79983521, -1998.62182617, 16.54882812]), + 'frame': 74757, + 'frame_number': 74757, + 'framesequence': 74755, + 'gaze_dir': array([ 0.98058069, -0.19474636, -0.02313771]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19474636, -0.02313771]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19474636, -0.02313771]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.12859401106834, + 'timestamp_carla': 280128, + 'timestamp_device': 279720, + 'timestamp_stream': 280.12859401106834, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.02138671e-03, -5.92891313e-03, -1.06785374e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.624698638916016, + 'FR_Wheel_Angle': 41.39641571044922, + 'Location': array([ -1.63692987, -21.83382988, 0.16434966]), + 'Rotation': array([-0.05417023, 29.8147068 , -0.03356933]), + 'Velocity': array([-5.33444405e-01, -6.80023253e-01, 6.53717492e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4267578125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 261.11523438, -1999.22668457, 16.69775391]), + 'frame': 74758, + 'frame_number': 74758, + 'framesequence': 74756, + 'gaze_dir': array([ 0.98058069, -0.1946523 , -0.02391608]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1946523 , -0.02391608]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1946523 , -0.02391608]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.13218841329217, + 'timestamp_carla': 280131, + 'timestamp_device': 279724, + 'timestamp_stream': 280.13218841329217, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 3.69735546e-02, 6.42179325e-03, -1.04294786e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.62125015258789, + 'FR_Wheel_Angle': 41.384483337402344, + 'Location': array([ -1.66390312, -21.86341476, 0.1643758 ]), + 'Rotation': array([-0.0538014 , 29.31608963, -0.03439331]), + 'Velocity': array([-5.45692801e-01, -6.79745078e-01, 5.43844712e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4268798828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 260.4486084 , -1999.85046387, 16.69763184]), + 'frame': 74759, + 'frame_number': 74759, + 'framesequence': 74757, + 'gaze_dir': array([ 0.98058069, -0.19457915, -0.02450406]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19457915, -0.02450406]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19457915, -0.02450406]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.13571921363473, + 'timestamp_carla': 280135, + 'timestamp_device': 279727, + 'timestamp_stream': 280.13571921363473, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.67667919e-02, -1.85526418e-03, -1.14668436e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.616884231567383, + 'FR_Wheel_Angle': 41.38492965698242, + 'Location': array([ -1.69261932, -21.89434433, 0.16439751]), + 'Rotation': array([-0.05330962, 28.7778492 , -0.03518677]), + 'Velocity': array([-5.53545117e-01, -6.82349384e-01, 1.47647850e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4267578125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 259.94314575, -2000.32006836, 16.69775391]), + 'frame': 74760, + 'frame_number': 74760, + 'framesequence': 74758, + 'gaze_dir': array([ 0.98058069, -0.19447963, -0.02528175]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19447963, -0.02528175]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19447963, -0.02528175]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1392258144915, + 'timestamp_carla': 280138, + 'timestamp_device': 279731, + 'timestamp_stream': 280.1392258144915, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.12853106e-03, 1.13441003e-03, -1.11564665e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.610795974731445, + 'FR_Wheel_Angle': 41.371768951416016, + 'Location': array([ -1.7203294 , -21.92374992, 0.16442554]), + 'Rotation': array([-0.05303642, 28.2530632 , -0.03543091]), + 'Velocity': array([-5.71517766e-01, -6.93945587e-01, 6.69243338e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4268798828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 259.27209473, -2000.93908691, 16.69763184]), + 'frame': 74761, + 'frame_number': 74761, + 'framesequence': 74759, + 'gaze_dir': array([ 0.98058069, -0.19437701, -0.02605904]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19437701, -0.02605904]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19437701, -0.02605904]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1429586112499, + 'timestamp_carla': 280142, + 'timestamp_device': 279735, + 'timestamp_stream': 280.1429586112499, + 'transform': [array([ 0.00865936, -0.00365967, 0.15901101]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 6.73744082e-03, 2.35083769e-03, -1.12481384e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.606904983520508, + 'FR_Wheel_Angle': 41.364131927490234, + 'Location': array([ -1.74801528, -21.9526329 , 0.16444805]), + 'Rotation': array([-0.05294762, 27.73484993, -0.03588867]), + 'Velocity': array([-0.58346653, -0.69655585, 0.00077369]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4268798828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 258.59866333, -2001.55541992, 16.69763184]), + 'frame': 74762, + 'frame_number': 74762, + 'framesequence': 74760, + 'gaze_dir': array([ 0.98058069, -0.19421682, -0.02722715]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19421682, -0.02722715]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19421682, -0.02722715]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.14966571331024, + 'timestamp_carla': 280149, + 'timestamp_device': 279741, + 'timestamp_stream': 280.14966571331024, + 'transform': [array([ 0.00865952, -0.00365967, 0.1589977 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.34538043e-03, 2.74864980e-03, -1.13551121e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60327911376953, + 'FR_Wheel_Angle': 41.357521057128906, + 'Location': array([ -1.776407 , -21.98171997, 0.16447303]), + 'Rotation': array([-0.052852 , 27.20811653, -0.03656006]), + 'Velocity': array([-5.95534027e-01, -6.97768629e-01, 6.39581645e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4268798828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 257.58123779, -2002.47729492, 16.69763184]), + 'frame': 74763, + 'frame_number': 74763, + 'framesequence': 74761, + 'gaze_dir': array([ 0.98058069, -0.19407897, -0.02819292]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19407897, -0.02819292]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19407897, -0.02819292]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.15405701473355, + 'timestamp_carla': 280153, + 'timestamp_device': 279746, + 'timestamp_stream': 280.15405701473355, + 'transform': [array([ 0.00865936, -0.00365967, 0.15899667]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.60888936e-02, 6.71612611e-03, -1.21085997e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.597640991210938, + 'FR_Wheel_Angle': 41.347389221191406, + 'Location': array([ -1.8069303 , -22.01237106, 0.16450503]), + 'Rotation': array([-0.05294762, 26.64572334, -0.03686523]), + 'Velocity': array([-6.11730576e-01, -7.01210022e-01, 5.35047031e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425537109375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 256.7350769 , -2003.23510742, 16.69763184]), + 'frame': 74764, + 'frame_number': 74764, + 'framesequence': 74762, + 'gaze_dir': array([ 0.98058069, -0.1939929 , -0.02877915]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1939929 , -0.02877915]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1939929 , -0.02877915]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.157604213804, + 'timestamp_carla': 280157, + 'timestamp_device': 279749, + 'timestamp_stream': 280.157604213804, + 'transform': [array([ 0.00865952, -0.00365967, 0.1589978 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.70949192e-02, 4.69767163e-03, -1.21489944e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.597122192382812, + 'FR_Wheel_Angle': 41.34584426879883, + 'Location': array([ -1.83737576, -22.04236221, 0.16453063]), + 'Rotation': array([-0.05270174, 26.08712769, -0.03771972]), + 'Velocity': array([-6.19261801e-01, -6.96361244e-01, 4.50735068e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.42529296875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 256.21936035, -2003.69348145, 16.69775391]), + 'frame': 74765, + 'frame_number': 74765, + 'framesequence': 74763, + 'gaze_dir': array([ 0.98058069, -0.1938763 , -0.02955446]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1938763 , -0.02955446]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1938763 , -0.02955446]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.16098611429334, + 'timestamp_carla': 280160, + 'timestamp_device': 279753, + 'timestamp_stream': 280.16098611429334, + 'transform': [array([ 0.00865952, -0.00365967, 0.1589978 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-9.43218637e-03, 5.00969402e-03, -1.17724037e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.590503692626953, + 'FR_Wheel_Angle': 41.334678649902344, + 'Location': array([ -1.86936295, -22.07327652, 0.16456389]), + 'Rotation': array([-0.05267442, 25.50948334, -0.03814697]), + 'Velocity': array([-6.39079332e-01, -7.04404056e-01, 6.94243878e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425537109375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 255.53495789, -2004.29760742, 16.69763184]), + 'frame': 74766, + 'frame_number': 74766, + 'framesequence': 74764, + 'gaze_dir': array([ 0.98058069, -0.19378705, -0.03013416]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19378705, -0.03013416]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19378705, -0.03013416]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1643521115184, + 'timestamp_carla': 280163, + 'timestamp_device': 279756, + 'timestamp_stream': 280.1643521115184, + 'transform': [array([ 0.00865967, -0.00365967, 0.15899907]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-8.83144233e-03, 4.89520561e-03, -1.19514742e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.583057403564453, + 'FR_Wheel_Angle': 41.3239860534668, + 'Location': array([ -1.89960349, -22.10191154, 0.16459568]), + 'Rotation': array([-0.05303642, 24.96984291, -0.03799438]), + 'Velocity': array([-6.55580819e-01, -7.09287226e-01, 6.12072938e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4254150390625, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 255.02133179, -2004.74780273, 16.69775391]), + 'frame': 74767, + 'frame_number': 74767, + 'framesequence': 74765, + 'gaze_dir': array([ 0.98058069, -0.19369605, -0.03071358]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19369605, -0.03071358]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19369605, -0.03071358]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1675894111395, + 'timestamp_carla': 280167, + 'timestamp_device': 279759, + 'timestamp_stream': 280.1675894111395, + 'transform': [array([ 0.00865967, -0.00365967, 0.15899907]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.95489538e-03, 2.69422564e-03, -1.21257029e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.579370498657227, + 'FR_Wheel_Angle': 41.31903839111328, + 'Location': array([ -1.93087327, -22.13096619, 0.16462708]), + 'Rotation': array([-0.05322766, 24.41619682, -0.03805542]), + 'Velocity': array([-0.6683383 , -0.70971543, 0.00077606]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425537109375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 254.50639343, -2005.1965332 , 16.69775391]), + 'frame': 74768, + 'frame_number': 74768, + 'framesequence': 74766, + 'gaze_dir': array([ 0.98058069, -0.19357172, -0.0314877 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19357172, -0.0314877 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19357172, -0.0314877 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.17150181159377, + 'timestamp_carla': 280170, + 'timestamp_device': 279763, + 'timestamp_stream': 280.17150181159377, + 'transform': [array([ 0.00865967, -0.00365967, 0.15899907]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.08220723, -0.02587469, -10.84412384]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.601844787597656, + 'FR_Wheel_Angle': 41.36049270629883, + 'Location': array([ -1.96067572, -22.15830231, 0.16460793]), + 'Rotation': array([-0.051766 , 23.89677238, -0.04016113]), + 'Velocity': array([-6.34892046e-01, -6.69951975e-01, -1.88779828e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4256591796875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 253.81596375, -2005.79370117, 16.69763184]), + 'frame': 74769, + 'frame_number': 74769, + 'framesequence': 74767, + 'gaze_dir': array([ 0.98058069, -0.19344428, -0.0322613 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19344428, -0.0322613 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19344428, -0.0322613 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.174983214587, + 'timestamp_carla': 280174, + 'timestamp_device': 279767, + 'timestamp_stream': 280.174983214587, + 'transform': [array([ 0.00865967, -0.00365967, 0.15899907]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.04682993, -0.01252316, -10.90725613]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.61301612854004, + 'FR_Wheel_Angle': 41.36499786376953, + 'Location': array([ -1.99409544, -22.18846893, 0.16461971]), + 'Rotation': array([-0.04950521, 23.31594658, -0.04330444]), + 'Velocity': array([-0.62415779, -0.64116627, 0.00156172]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4254150390625, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 253.12310791, -2006.38818359, 16.69787598]), + 'frame': 74770, + 'frame_number': 74770, + 'framesequence': 74768, + 'gaze_dir': array([ 0.98058069, -0.19334592, -0.0328456 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19334592, -0.0328456 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19334592, -0.0328456 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.17838441208005, + 'timestamp_carla': 280177, + 'timestamp_device': 279770, + 'timestamp_stream': 280.17838441208005, + 'transform': [array([ 0.00865982, -0.00365967, 0.15900013]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.03821457, 0.01613123, -11.61060905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.591005325317383, + 'FR_Wheel_Angle': 41.333412170410156, + 'Location': array([ -2.02536798, -22.21593475, 0.16468097]), + 'Rotation': array([-0.05053657, 22.78718948, -0.04199218]), + 'Velocity': array([-0.66971666, -0.66757995, 0.00153585]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425537109375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 252.59793091, -2006.83569336, 16.69775391]), + 'frame': 74771, + 'frame_number': 74771, + 'framesequence': 74769, + 'gaze_dir': array([ 0.98058069, -0.19324683, -0.03342369]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19324683, -0.03342369]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19324683, -0.03342369]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1817520111799, + 'timestamp_carla': 280181, + 'timestamp_device': 279773, + 'timestamp_stream': 280.1817520111799, + 'transform': [array([ 0.00865982, -0.00365967, 0.15900013]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.55768423e-02, 9.23169404e-03, -1.21987867e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.57932472229004, + 'FR_Wheel_Angle': 41.31632995605469, + 'Location': array([ -2.06025386, -22.24592781, 0.16474254]), + 'Rotation': array([-0.05227827, 22.20187759, -0.03961181]), + 'Velocity': array([-0.6957022 , -0.68252212, 0.00109636]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4256591796875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 252.07676697, -2007.27709961, 16.69775391]), + 'frame': 74772, + 'frame_number': 74772, + 'framesequence': 74770, + 'gaze_dir': array([ 0.98058069, -0.19311164, -0.03419599]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19311164, -0.03419599]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19311164, -0.03419599]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.18510691449046, + 'timestamp_carla': 280184, + 'timestamp_device': 279777, + 'timestamp_stream': 280.18510691449046, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-7.27882329e-03, 6.54167868e-03, -1.21090479e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.578706741333008, + 'FR_Wheel_Angle': 41.31718444824219, + 'Location': array([ -2.09322667, -22.27376175, 0.16477318]), + 'Rotation': array([-0.0530091 , 21.65044022, -0.03863525]), + 'Velocity': array([-7.03450978e-01, -6.76463246e-01, 6.95056922e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4256591796875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 251.37800598, -2007.86462402, 16.69775391]), + 'frame': 74773, + 'frame_number': 74773, + 'framesequence': 74771, + 'gaze_dir': array([ 0.98058069, -0.19297341, -0.03496774]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19297341, -0.03496774]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19297341, -0.03496774]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.18903121352196, + 'timestamp_carla': 280188, + 'timestamp_device': 279781, + 'timestamp_stream': 280.18903121352196, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.01552303e-02, 4.16024402e-03, -1.24550648e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.57184600830078, + 'FR_Wheel_Angle': 41.30316162109375, + 'Location': array([ -2.12963438, -22.30388641, 0.16481471]), + 'Rotation': array([-0.05358966, 21.04504204, -0.03787231]), + 'Velocity': array([-0.72210181, -0.68157399, 0.00080203]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.42578125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 250.67697144, -2008.44946289, 16.69775391]), + 'frame': 74774, + 'frame_number': 74774, + 'framesequence': 74772, + 'gaze_dir': array([ 0.98058069, -0.19286688, -0.03555059]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19286688, -0.03555059]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19286688, -0.03555059]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.19289761409163, + 'timestamp_carla': 280192, + 'timestamp_device': 279784, + 'timestamp_stream': 280.19289761409163, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.20954325e-02, 1.74966932e-03, -1.25660753e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.568042755126953, + 'FR_Wheel_Angle': 41.297645568847656, + 'Location': array([ -2.16483521, -22.33239746, 0.1648441 ]), + 'Rotation': array([-0.05410875, 20.46585274, -0.03726196]), + 'Velocity': array([-0.73557389, -0.68072104, 0.00084876]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4259033203125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 250.14556885, -2008.8894043 , 16.69763184]), + 'frame': 74775, + 'frame_number': 74775, + 'framesequence': 74773, + 'gaze_dir': array([ 0.98058069, -0.1927232 , -0.03632136]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1927232 , -0.03632136]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1927232 , -0.03632136]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.19605481252074, + 'timestamp_carla': 280195, + 'timestamp_device': 279788, + 'timestamp_stream': 280.19605481252074, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.59640552e-02, 3.91497882e-03, -1.27307673e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.562393188476562, + 'FR_Wheel_Angle': 41.2894287109375, + 'Location': array([ -2.19892907, -22.35944939, 0.16487914]), + 'Rotation': array([-0.05447076, 19.90897369, -0.03668213]), + 'Velocity': array([-0.75239235, -0.68223077, 0.00075703]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4259033203125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 249.44036865, -2009.46923828, 16.69763184]), + 'frame': 74776, + 'frame_number': 74776, + 'framesequence': 74774, + 'gaze_dir': array([ 0.98058069, -0.19261372, -0.03689757]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19261372, -0.03689757]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19261372, -0.03689757]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.1994294114411, + 'timestamp_carla': 280198, + 'timestamp_device': 279791, + 'timestamp_stream': 280.1994294114411, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.69256721e-02, 1.09596318e-02, -1.26027603e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.560108184814453, + 'FR_Wheel_Angle': 41.286773681640625, + 'Location': array([ -2.23721218, -22.38917923, 0.16489704]), + 'Rotation': array([-0.05474396, 19.2900753 , -0.03634643]), + 'Velocity': array([-7.65079319e-01, -6.74150705e-01, 6.19506813e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.426025390625, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 248.91133118, -2009.90124512, 16.69750977]), + 'frame': 74777, + 'frame_number': 74777, + 'framesequence': 74775, + 'gaze_dir': array([ 0.98058069, -0.19246466, -0.03766731]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19246466, -0.03766731]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19246466, -0.03766731]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.20344491302967, + 'timestamp_carla': 280202, + 'timestamp_device': 279795, + 'timestamp_stream': 280.20344491302967, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 7.16542825e-04, 7.52344029e-03, -1.28208027e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.556232452392578, + 'FR_Wheel_Angle': 41.279544830322266, + 'Location': array([ -2.27400589, -22.41717529, 0.16493411]), + 'Rotation': array([-0.05496253, 18.69563675, -0.03582764]), + 'Velocity': array([-0.77840829, -0.6742807 , 0.00091039]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.42578125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 248.2020874 , -2010.47607422, 16.69775391]), + 'frame': 74778, + 'frame_number': 74778, + 'framesequence': 74776, + 'gaze_dir': array([ 0.98058069, -0.19231254, -0.03843644]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19231254, -0.03843644]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19231254, -0.03843644]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2069211117923, + 'timestamp_carla': 280206, + 'timestamp_device': 279799, + 'timestamp_stream': 280.2069211117923, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.87436491e-02, 1.12594301e-02, -1.28722267e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.55306053161621, + 'FR_Wheel_Angle': 41.273681640625, + 'Location': array([ -2.31058645, -22.44445038, 0.16497043]), + 'Rotation': array([-0.05526306, 18.10778046, -0.0352478 ]), + 'Velocity': array([-7.91295588e-01, -6.70637786e-01, 6.42614323e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4259033203125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 247.49058533, -2011.0480957 , 16.69763184]), + 'frame': 74779, + 'frame_number': 74779, + 'framesequence': 74777, + 'gaze_dir': array([ 0.98058069, -0.19215733, -0.03920496]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19215733, -0.03920496]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19215733, -0.03920496]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.21050211414695, + 'timestamp_carla': 280209, + 'timestamp_device': 279803, + 'timestamp_stream': 280.21050211414695, + 'transform': [array([ 0.00865997, -0.00365967, 0.1590012 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.00563499e-02, -6.35820022e-03, -1.32735481e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.55067253112793, + 'FR_Wheel_Angle': 41.26832580566406, + 'Location': array([ -2.35068774, -22.47371483, 0.16500735]), + 'Rotation': array([-0.0554543 , 17.46752739, -0.03482056]), + 'Velocity': array([-8.01046252e-01, -6.72139287e-01, 6.74533832e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4259033203125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 246.77677917, -2011.61730957, 16.69763184]), + 'frame': 74780, + 'frame_number': 74780, + 'framesequence': 74778, + 'gaze_dir': array([ 0.98058069, -0.19191815, -0.04035949]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19191815, -0.04035949]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19191815, -0.04035949]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2174736112356, + 'timestamp_carla': 280216, + 'timestamp_device': 279809, + 'timestamp_stream': 280.2174736112356, + 'transform': [array([ 0.00866013, -0.00365967, 0.1589864 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.71978397e-02, -9.15145036e-03, -1.33355827e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.54920768737793, + 'FR_Wheel_Angle': 41.265846252441406, + 'Location': array([ -2.38901567, -22.50101662, 0.1650373 ]), + 'Rotation': array([-0.05560457, 16.86270142, -0.03479004]), + 'Velocity': array([-0.81094211, -0.66553658, 0.00081115]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4259033203125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 245.69909668, -2012.46789551, 16.69763184]), + 'frame': 74781, + 'frame_number': 74781, + 'framesequence': 74779, + 'gaze_dir': array([ 0.98058069, -0.19175528, -0.04112642]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19175528, -0.04112642]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19175528, -0.04112642]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2208897136152, + 'timestamp_carla': 280220, + 'timestamp_device': 279813, + 'timestamp_stream': 280.2208897136152, + 'transform': [array([ 0.00865997, -0.00365967, 0.15898758]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.02983206e-02, -6.11311384e-03, -1.33874550e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.546369552612305, + 'FR_Wheel_Angle': 41.26091003417969, + 'Location': array([ -2.4267633 , -22.52734375, 0.16507225]), + 'Rotation': array([-0.05569336, 16.26996994, -0.03439331]), + 'Velocity': array([-8.23132396e-01, -6.61318183e-01, 7.42571312e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4244384765625, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 244.97947693, -2013.02966309, 16.69763184]), + 'frame': 74782, + 'frame_number': 74782, + 'framesequence': 74780, + 'gaze_dir': array([ 0.98058069, -0.19163141, -0.04169972]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19163141, -0.04169972]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19163141, -0.04169972]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2245027124882, + 'timestamp_carla': 280223, + 'timestamp_device': 279816, + 'timestamp_stream': 280.2245027124882, + 'transform': [array([ 0.00866013, -0.00365967, 0.15898895]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.11662257e-02, -9.63997189e-03, -1.34847746e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.545482635498047, + 'FR_Wheel_Angle': 41.259952545166016, + 'Location': array([ -2.46588635, -22.55400848, 0.16510487]), + 'Rotation': array([-0.05584363, 15.66021252, -0.03408813]), + 'Velocity': array([-8.31530571e-01, -6.54836178e-01, 7.65311706e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4244384765625, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 244.43977356, -2013.44824219, 16.69775391]), + 'frame': 74783, + 'frame_number': 74783, + 'framesequence': 74781, + 'gaze_dir': array([ 0.98058069, -0.19150585, -0.04227265]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19150585, -0.04227265]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19150585, -0.04227265]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2278606146574, + 'timestamp_carla': 280227, + 'timestamp_device': 279819, + 'timestamp_stream': 280.2278606146574, + 'transform': [array([ 0.00865997, -0.00365967, 0.1589901 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.03164800e-02, 7.00882357e-03, -1.32199383e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.543094635009766, + 'FR_Wheel_Angle': 41.2575569152832, + 'Location': array([ -2.50880742, -22.58257675, 0.16514164]), + 'Rotation': array([-0.05584363, 14.99590111, -0.03390503]), + 'Velocity': array([-8.45321774e-01, -6.42380834e-01, 8.28671444e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.424560546875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 243.89888 , -2013.8651123 , 16.69763184]), + 'frame': 74784, + 'frame_number': 74784, + 'framesequence': 74782, + 'gaze_dir': array([ 0.98058069, -0.19133531, -0.04303791]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19133531, -0.04303791]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19133531, -0.04303791]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2312561124563, + 'timestamp_carla': 280230, + 'timestamp_device': 279823, + 'timestamp_stream': 280.2312561124563, + 'transform': [array([ 0.00866013, -0.00365967, 0.15899159]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 6.81179948e-03, 1.10853063e-02, -1.32576866e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.540420532226562, + 'FR_Wheel_Angle': 41.25274658203125, + 'Location': array([ -2.54852653, -22.60838318, 0.16517715]), + 'Rotation': array([-0.0559734 , 14.38535595, -0.0335083 ]), + 'Velocity': array([-8.57504785e-01, -6.36292398e-01, 8.47971416e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4248046875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 243.17385864, -2014.42004395, 16.69763184]), + 'frame': 74785, + 'frame_number': 74785, + 'framesequence': 74783, + 'gaze_dir': array([ 0.98058069, -0.19120441, -0.04361578]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19120441, -0.04361578]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19120441, -0.04361578]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2346940115094, + 'timestamp_carla': 280234, + 'timestamp_device': 279826, + 'timestamp_stream': 280.2346940115094, + 'transform': [array([ 0.00866013, -0.00365967, 0.15899159]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.98213547e-03, 7.35336775e-03, -1.33661156e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.538410186767578, + 'FR_Wheel_Angle': 41.25056457519531, + 'Location': array([ -2.58785415, -22.6333313 , 0.16521491]), + 'Rotation': array([-0.05630808, 13.78652382, -0.03295898]), + 'Velocity': array([-0.86778194, -0.63115674, 0.00096096]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4248046875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 242.6244812 , -2014.83740234, 16.69775391]), + 'frame': 74786, + 'frame_number': 74786, + 'framesequence': 74784, + 'gaze_dir': array([ 0.98058069, -0.19102852, -0.04437983]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19102852, -0.04437983]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19102852, -0.04437983]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2386354133487, + 'timestamp_carla': 280238, + 'timestamp_device': 279830, + 'timestamp_stream': 280.2386354133487, + 'transform': [array([ 0.00866013, -0.00365967, 0.15899159]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.99140662e-02, 1.18020864e-03, -1.32515182e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.542312622070312, + 'FR_Wheel_Angle': 41.257835388183594, + 'Location': array([ -2.6308682 , -22.66002083, 0.16524342]), + 'Rotation': array([-0.05623978, 13.13345146, -0.03280639]), + 'Velocity': array([-0.86718625, -0.61612117, 0.00092388]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4246826171875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 241.89556885, -2015.38708496, 16.69775391]), + 'frame': 74787, + 'frame_number': 74787, + 'framesequence': 74785, + 'gaze_dir': array([ 0.98058069, -0.19084957, -0.04514317]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19084957, -0.04514317]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19084957, -0.04514317]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2425054125488, + 'timestamp_carla': 280241, + 'timestamp_device': 279834, + 'timestamp_stream': 280.2425054125488, + 'transform': [array([ 0.00866013, -0.00365967, 0.15899159]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.40821014e-02, -1.91335334e-03, -1.31415586e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.54789924621582, + 'FR_Wheel_Angle': 41.26642608642578, + 'Location': array([ -2.66921663, -22.68328476, 0.1652687 ]), + 'Rotation': array([-0.05575483, 12.55172729, -0.03305053]), + 'Velocity': array([-8.62237811e-01, -6.00161672e-01, 7.16524082e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4248046875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 241.16448975, -2015.93383789, 16.69775391]), + 'frame': 74788, + 'frame_number': 74788, + 'framesequence': 74786, + 'gaze_dir': array([ 0.98058069, -0.1907137 , -0.04571375]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1907137 , -0.04571375]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1907137 , -0.04571375]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2456900142133, + 'timestamp_carla': 280245, + 'timestamp_device': 279837, + 'timestamp_stream': 280.2456900142133, + 'transform': [array([ 0.00866028, -0.00365967, 0.15899315]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.04055570e-03, 1.41143184e-02, -1.31387196e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.54397964477539, + 'FR_Wheel_Angle': 41.25822448730469, + 'Location': array([ -2.71172142, -22.70843506, 0.1653102 ]), + 'Rotation': array([-0.05560457, 11.91362476, -0.03295898]), + 'Velocity': array([-0.87710315, -0.59382737, 0.00101204]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.424560546875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 240.61610413, -2016.34094238, 16.69787598]), + 'frame': 74789, + 'frame_number': 74789, + 'framesequence': 74787, + 'gaze_dir': array([ 0.98058069, -0.19052941, -0.04647582]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19052941, -0.04647582]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19052941, -0.04647582]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.24899511411786, + 'timestamp_carla': 280248, + 'timestamp_device': 279841, + 'timestamp_stream': 280.24899511411786, + 'transform': [array([ 0.00866028, -0.00365967, 0.15899315]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-6.72685867e-03, 1.51581587e-02, -1.32938948e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.53929328918457, + 'FR_Wheel_Angle': 41.253353118896484, + 'Location': array([ -2.7528038 , -22.73206711, 0.16535717]), + 'Rotation': array([-0.05630808, 11.30460358, -0.03179932]), + 'Velocity': array([-0.89276832, -0.59067947, 0.00094271]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425048828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 239.88127136, -2016.88269043, 16.69763184]), + 'frame': 74790, + 'frame_number': 74790, + 'framesequence': 74788, + 'gaze_dir': array([ 0.98058069, -0.1903421 , -0.04723714]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1903421 , -0.04723714]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1903421 , -0.04723714]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.25287591293454, + 'timestamp_carla': 280252, + 'timestamp_device': 279845, + 'timestamp_stream': 280.25287591293454, + 'transform': [array([ 0.00866028, -0.00365967, 0.15899315]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 7.79552665e-03, 8.55132006e-03, -1.33511953e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.539228439331055, + 'FR_Wheel_Angle': 41.251487731933594, + 'Location': array([ -2.79655337, -22.75662041, 0.16539745]), + 'Rotation': array([-0.05679302, 10.6578331 , -0.03094482]), + 'Velocity': array([-8.99372160e-01, -5.81413984e-01, 8.25226307e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4251708984375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 239.14424133, -2017.42138672, 16.69763184]), + 'frame': 74791, + 'frame_number': 74791, + 'framesequence': 74789, + 'gaze_dir': array([ 0.98058075, -0.19019851, -0.047812 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.19019851, -0.047812 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.19019851, -0.047812 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.25628551468253, + 'timestamp_carla': 280255, + 'timestamp_device': 279848, + 'timestamp_stream': 280.25628551468253, + 'transform': [array([ 0.00866028, -0.00365967, 0.15899315]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.27043454e-03, 1.29671888e-02, -1.34390631e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.534908294677734, + 'FR_Wheel_Angle': 41.2441291809082, + 'Location': array([ -2.83851075, -22.77956581, 0.16544101]), + 'Rotation': array([-0.05722332, 10.04164028, -0.0302124 ]), + 'Velocity': array([-0.91441524, -0.57695544, 0.00104127]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4249267578125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 238.58575439, -2017.82653809, 16.69775391]), + 'frame': 74792, + 'frame_number': 74792, + 'framesequence': 74790, + 'gaze_dir': array([ 0.98058069, -0.19005466, -0.04838061]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19005466, -0.04838061]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19005466, -0.04838061]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.25950311124325, + 'timestamp_carla': 280258, + 'timestamp_device': 279851, + 'timestamp_stream': 280.25950311124325, + 'transform': [array([ 0.00866043, -0.00365967, 0.1589945 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.33687589e-02, 2.93587055e-03, -1.37542982e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.532562255859375, + 'FR_Wheel_Angle': 41.23749542236328, + 'Location': array([ -2.88396335, -22.80374908, 0.16548714]), + 'Rotation': array([-0.05773558, 9.37922668, -0.02920532]), + 'Velocity': array([-0.92508292, -0.57387388, 0.00104135]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425048828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 238.03178406, -2018.22595215, 16.69763184]), + 'frame': 74793, + 'frame_number': 74793, + 'framesequence': 74791, + 'gaze_dir': array([ 0.98058069, -0.18985972, -0.04914002]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18985972, -0.04914002]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18985972, -0.04914002]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2632305137813, + 'timestamp_carla': 280262, + 'timestamp_device': 279855, + 'timestamp_stream': 280.2632305137813, + 'transform': [array([ 0.00866043, -0.00365967, 0.1589945 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.46122496e-02, -7.59161892e-04, -1.37210789e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.53255271911621, + 'FR_Wheel_Angle': 41.23756408691406, + 'Location': array([ -2.9291327 , -22.82707405, 0.16552013]), + 'Rotation': array([-0.05789268, 8.7276783 , -0.02908325]), + 'Velocity': array([-0.93168426, -0.56256539, 0.00117278]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4249267578125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 237.28933716, -2018.75720215, 16.69787598]), + 'frame': 74794, + 'frame_number': 74794, + 'framesequence': 74792, + 'gaze_dir': array([ 0.98058069, -0.1897119 , -0.04970762]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1897119 , -0.04970762]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1897119 , -0.04970762]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.26665261387825, + 'timestamp_carla': 280266, + 'timestamp_device': 279858, + 'timestamp_stream': 280.26665261387825, + 'transform': [array([ 0.00866058, -0.00365967, 0.15899552]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.98130417e-02, -3.21755884e-03, -1.37786760e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.532747268676758, + 'FR_Wheel_Angle': 41.23774337768555, + 'Location': array([ -2.97401333, -22.84962845, 0.16556187]), + 'Rotation': array([-0.05795415, 8.08260632, -0.02850341]), + 'Velocity': array([-0.93737477, -0.55316073, 0.0010776 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425048828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 236.73260498, -2019.15283203, 16.69775391]), + 'frame': 74795, + 'frame_number': 74795, + 'framesequence': 74793, + 'gaze_dir': array([ 0.98058075, -0.18951167, -0.05046566]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18951167, -0.05046566]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18951167, -0.05046566]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.27018421143293, + 'timestamp_carla': 280269, + 'timestamp_device': 279862, + 'timestamp_stream': 280.27018421143293, + 'transform': [array([ 0.00866058, -0.00365967, 0.15899552]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.37367877e-02, 5.50633958e-05, -1.37951021e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.532129287719727, + 'FR_Wheel_Angle': 41.23701858520508, + 'Location': array([ -3.01840425, -22.87138176, 0.1656052 ]), + 'Rotation': array([-0.0579883 , 7.44463921, -0.02780151]), + 'Velocity': array([-0.94473827, -0.54367518, 0.0009703 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.42529296875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 235.98651123, -2019.67895508, 16.69763184]), + 'frame': 74796, + 'frame_number': 74796, + 'framesequence': 74794, + 'gaze_dir': array([ 0.98058075, -0.18935834, -0.05103799]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18935834, -0.05103799]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18935834, -0.05103799]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.27372681349516, + 'timestamp_carla': 280273, + 'timestamp_device': 279865, + 'timestamp_stream': 280.27372681349516, + 'transform': [array([ 0.00866058, -0.00365967, 0.15899552]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.96750160e-02, 3.34072928e-03, -1.38828011e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.5284366607666, + 'FR_Wheel_Angle': 41.23037338256836, + 'Location': array([ -3.06101227, -22.89163589, 0.16565128]), + 'Rotation': array([-0.05837762, 6.83880758, -0.02703858]), + 'Velocity': array([-0.95828199, -0.53725278, 0.00100385]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.42529296875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 235.42126465, -2020.07458496, 16.69763184]), + 'frame': 74797, + 'frame_number': 74797, + 'framesequence': 74795, + 'gaze_dir': array([ 0.98058069, -0.18915276, -0.0517946 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18915276, -0.0517946 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18915276, -0.0517946 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.27694591134787, + 'timestamp_carla': 280276, + 'timestamp_device': 279869, + 'timestamp_stream': 280.27694591134787, + 'transform': [array([ 0.00866058, -0.00365967, 0.15899552]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.71755569e-03, 8.33522808e-03, -1.37245102e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.5252742767334, + 'FR_Wheel_Angle': 41.227333068847656, + 'Location': array([ -3.10767245, -22.91318321, 0.16569805]), + 'Rotation': array([-0.05880792, 6.17850256, -0.02624512]), + 'Velocity': array([-0.97163349, -0.52482563, 0.00101308]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.42529296875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 234.67147827, -2020.59545898, 16.69763184]), + 'frame': 74798, + 'frame_number': 74798, + 'framesequence': 74796, + 'gaze_dir': array([ 0.98058069, -0.18899702, -0.05236007]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18899702, -0.05236007]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18899702, -0.05236007]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.28020461276174, + 'timestamp_carla': 280279, + 'timestamp_device': 279872, + 'timestamp_stream': 280.28020461276174, + 'transform': [array([ 0.00866074, -0.00365967, 0.15899658]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.89249197e-02, -4.53662639e-03, -1.39364424e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.528379440307617, + 'FR_Wheel_Angle': 41.23433303833008, + 'Location': array([ -3.15032077, -22.93235779, 0.1657328 ]), + 'Rotation': array([-0.05874645, 5.57494879, -0.02584839]), + 'Velocity': array([-0.9698956 , -0.51733208, 0.00104679]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4251708984375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 234.10919189, -2020.9831543 , 16.69775391]), + 'frame': 74799, + 'frame_number': 74799, + 'framesequence': 74797, + 'gaze_dir': array([ 0.98058069, -0.18878618, -0.05311522]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18878618, -0.05311522]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18878618, -0.05311522]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2837711125612, + 'timestamp_carla': 280283, + 'timestamp_device': 279876, + 'timestamp_stream': 280.2837711125612, + 'transform': [array([ 0.00866074, -0.00365967, 0.15899658]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.58200707e-02, -3.31343105e-03, -1.38617191e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.531551361083984, + 'FR_Wheel_Angle': 41.235408782958984, + 'Location': array([ -3.19909286, -22.95361328, 0.16576836]), + 'Rotation': array([-0.0583503 , 4.88901091, -0.02609253]), + 'Velocity': array([-0.96923262, -0.50204808, 0.00119267]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4251708984375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 233.3558197 , -2021.49865723, 16.69775391]), + 'frame': 74800, + 'frame_number': 74800, + 'framesequence': 74798, + 'gaze_dir': array([ 0.98058069, -0.18857232, -0.05386952]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18857232, -0.05386952]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18857232, -0.05386952]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2881729118526, + 'timestamp_carla': 280287, + 'timestamp_device': 279880, + 'timestamp_stream': 280.2881729118526, + 'transform': [array([ 0.00866089, -0.00365967, 0.15899545]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-6.96028932e-04, 1.19788153e-02, -1.36494017e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.526268005371094, + 'FR_Wheel_Angle': 41.229270935058594, + 'Location': array([ -3.24694395, -22.97377205, 0.1658213 ]), + 'Rotation': array([-0.05874645, 4.22163057, -0.02514648]), + 'Velocity': array([-9.86922145e-01, -4.89228547e-01, 9.31937655e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4251708984375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 232.6003418 , -2022.01123047, 16.69775391]), + 'frame': 74801, + 'frame_number': 74801, + 'framesequence': 74799, + 'gaze_dir': array([ 0.98058069, -0.18835545, -0.05462296]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18835545, -0.05462296]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18835545, -0.05462296]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2919361144304, + 'timestamp_carla': 280291, + 'timestamp_device': 279884, + 'timestamp_stream': 280.2919361144304, + 'transform': [array([ 0.00866089, -0.00365967, 0.15899545]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.85787793e-03, 4.91396524e-03, -1.37040453e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525714874267578, + 'FR_Wheel_Angle': 41.229305267333984, + 'Location': array([ -3.29257321, -22.99237823, 0.1658667 ]), + 'Rotation': array([-0.05905381, 3.58826017, -0.02423096]), + 'Velocity': array([-9.93430793e-01, -4.79626060e-01, 8.20939546e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4249267578125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 231.84281921, -2022.52075195, 16.69787598]), + 'frame': 74802, + 'frame_number': 74802, + 'framesequence': 74800, + 'gaze_dir': array([ 0.98058075, -0.1881896 , -0.05519179]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.1881896 , -0.05519179]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.1881896 , -0.05519179]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.2951460145414, + 'timestamp_carla': 280294, + 'timestamp_device': 279887, + 'timestamp_stream': 280.2951460145414, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 7.99583644e-03, 3.28377075e-03, -1.37604017e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524457931518555, + 'FR_Wheel_Angle': 41.22675323486328, + 'Location': array([ -3.33772111, -23.0102272 , 0.16591129]), + 'Rotation': array([-0.05929287, 2.96354437, -0.02346802]), + 'Velocity': array([-1.00131464e+00, -4.70610470e-01, 9.54811578e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.425048828125, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 231.26904297, -2022.90393066, 16.69775391]), + 'frame': 74803, + 'frame_number': 74803, + 'framesequence': 74801, + 'gaze_dir': array([ 0.98058069, -0.18802366, -0.05575436]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18802366, -0.05575436]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18802366, -0.05575436]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.29847141355276, + 'timestamp_carla': 280297, + 'timestamp_device': 279890, + 'timestamp_stream': 280.29847141355276, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 8.22387449e-03, 1.37274002e-03, -1.37370100e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52562713623047, + 'FR_Wheel_Angle': 41.22751998901367, + 'Location': array([ -3.38484216, -23.02829552, 0.1659531 ]), + 'Rotation': array([-0.0592314 , 2.31240106, -0.02297973]), + 'Velocity': array([-1.00401819, -0.45863479, 0.00108994]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4251708984375, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 230.69989014, -2023.28149414, 16.69775391]), + 'frame': 74804, + 'frame_number': 74804, + 'framesequence': 74802, + 'gaze_dir': array([ 0.98058069, -0.18779926, -0.05650559]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18779926, -0.05650559]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18779926, -0.05650559]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3019137121737, + 'timestamp_carla': 280301, + 'timestamp_device': 279894, + 'timestamp_stream': 280.3019137121737, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.73659357e-02, 8.10668455e-04, -1.40269184e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524581909179688, + 'FR_Wheel_Angle': 41.22404861450195, + 'Location': array([ -3.43472934, -23.04673767, 0.16600139]), + 'Rotation': array([-0.05929287, 1.62693286, -0.02224731]), + 'Velocity': array([-1.01158631e+00, -4.52559829e-01, 9.49220615e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.42529296875, + 'focus_actor_name': 'Plane27', + 'focus_actor_pt': array([ 229.93734741, -2023.78344727, 16.69763184]), + 'frame': 74805, + 'frame_number': 74805, + 'framesequence': 74803, + 'gaze_dir': array([ 0.98058069, -0.18762942, -0.057067 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18762942, -0.057067 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18762942, -0.057067 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3054648116231, + 'timestamp_carla': 280304, + 'timestamp_device': 279897, + 'timestamp_stream': 280.3054648116231, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 5.24737202e-02, -4.61348891e-03, -1.34819565e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525489807128906, + 'FR_Wheel_Angle': 41.2288703918457, + 'Location': array([ -3.47900009, -23.06249428, 0.16603878]), + 'Rotation': array([-0.05942264, 1.0241909 , -0.02194214]), + 'Velocity': array([-1.01444554e+00, -4.31233883e-01, -2.00042719e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5350341796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 229.37730408, -2024.17504883, 16.58996582]), + 'frame': 74806, + 'frame_number': 74806, + 'framesequence': 74804, + 'gaze_dir': array([ 0.98058069, -0.18745615, -0.05763361]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18745615, -0.05763361]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18745615, -0.05763361]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.30880051106215, + 'timestamp_carla': 280308, + 'timestamp_device': 279900, + 'timestamp_stream': 280.30880051106215, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.94199267e-02, 2.00659037e-03, -1.40455256e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52385139465332, + 'FR_Wheel_Angle': 41.225013732910156, + 'Location': array([ -3.52957201, -23.07990265, 0.1660907 ]), + 'Rotation': array([-0.05938849, 0.33409441, -0.02102661]), + 'Velocity': array([-1.02274966, -0.42981559, 0.00112058]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5343017578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 228.7984314 , -2024.55053711, 16.59069824]), + 'frame': 74807, + 'frame_number': 74807, + 'framesequence': 74805, + 'gaze_dir': array([ 0.98058075, -0.18722425, -0.05838257]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18722425, -0.05838257]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18722425, -0.05838257]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.31209361180663, + 'timestamp_carla': 280311, + 'timestamp_device': 279904, + 'timestamp_stream': 280.31209361180663, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.17021147e-02, -2.22352496e-03, -1.37614975e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524978637695312, + 'FR_Wheel_Angle': 41.228309631347656, + 'Location': array([ -3.5741744 , -23.09467697, 0.16613296]), + 'Rotation': array([-0.05944996, -0.27062988, -0.02041626]), + 'Velocity': array([-1.02510750e+00, -4.13165271e-01, 9.57796525e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5333251953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 228.03070068, -2025.04467773, 16.59179688]), + 'frame': 74808, + 'frame_number': 74808, + 'framesequence': 74806, + 'gaze_dir': array([ 0.98058075, -0.18704881, -0.05894224]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18704881, -0.05894224]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18704881, -0.05894224]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3152591139078, + 'timestamp_carla': 280314, + 'timestamp_device': 279907, + 'timestamp_stream': 280.3152591139078, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.10270656e-02, 4.84722294e-03, -1.40324278e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.522716522216797, + 'FR_Wheel_Angle': 41.2210807800293, + 'Location': array([ -3.62417555, -23.11066055, 0.16618583]), + 'Rotation': array([-0.05947728, -0.94741839, -0.01950073]), + 'Velocity': array([-1.03505206, -0.4070906 , 0.00125126]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.53271484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 227.45507812, -2025.41235352, 16.59228516]), + 'frame': 74809, + 'frame_number': 74809, + 'framesequence': 74807, + 'gaze_dir': array([ 0.98058069, -0.18681166, -0.05968955]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18681166, -0.05968955]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18681166, -0.05968955]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3192089125514, + 'timestamp_carla': 280318, + 'timestamp_device': 279911, + 'timestamp_stream': 280.3192089125514, + 'transform': [array([ 0.00866104, -0.00365967, 0.15899655]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.74491699e-02, -3.47494311e-03, -1.41249552e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.5236759185791, + 'FR_Wheel_Angle': 41.22262954711914, + 'Location': array([ -3.67254543, -23.12547874, 0.16623187]), + 'Rotation': array([-0.05957291, -1.5987854 , -0.0185852 ]), + 'Velocity': array([-1.03752887e+00, -3.97213817e-01, 8.24437127e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.53173828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 226.68392944, -2025.90112305, 16.59326172]), + 'frame': 74810, + 'frame_number': 74810, + 'framesequence': 74808, + 'gaze_dir': array([ 0.98058069, -0.18651058, -0.06062377]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18651058, -0.06062377]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18651058, -0.06062377]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3239436112344, + 'timestamp_carla': 280323, + 'timestamp_device': 279916, + 'timestamp_stream': 280.3239436112344, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 1.22223124e-02, 4.43660375e-03, -1.38136415e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52059555053711, + 'FR_Wheel_Angle': 41.218505859375, + 'Location': array([ -3.72296739, -23.14027214, 0.1662849 ]), + 'Rotation': array([-0.05957291, -2.27420115, -0.01800537]), + 'Velocity': array([-1.04971385e+00, -3.79041970e-01, 8.22315225e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.530517578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 225.71575928, -2026.50878906, 16.59448242]), + 'frame': 74811, + 'frame_number': 74811, + 'framesequence': 74809, + 'gaze_dir': array([ 0.98058069, -0.18632843, -0.0611813 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18632843, -0.0611813 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18632843, -0.0611813 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3276543132961, + 'timestamp_carla': 280327, + 'timestamp_device': 279919, + 'timestamp_stream': 280.3276543132961, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.16566080e-02, -4.96959360e-03, -1.41066828e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.523847579956055, + 'FR_Wheel_Angle': 41.223114013671875, + 'Location': array([ -3.76846027, -23.15310669, 0.16632587]), + 'Rotation': array([-0.05942264, -2.88439989, -0.01733398]), + 'Velocity': array([-1.04577458, -0.37337202, 0.00114787]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5296630859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 225.13577271, -2026.86950684, 16.59509277]), + 'frame': 74812, + 'frame_number': 74812, + 'framesequence': 74810, + 'gaze_dir': array([ 0.98058069, -0.18608235, -0.06192572]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18608235, -0.06192572]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18608235, -0.06192572]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.33123391121626, + 'timestamp_carla': 280330, + 'timestamp_device': 279923, + 'timestamp_stream': 280.33123391121626, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.02429225e-03, 5.43301227e-03, -1.38732548e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52066421508789, + 'FR_Wheel_Angle': 41.2192497253418, + 'Location': array([ -3.81978679, -23.16694832, 0.16637883]), + 'Rotation': array([-0.05942264, -3.56890988, -0.01672363]), + 'Velocity': array([-1.05700946, -0.3568359 , 0.00126997]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.528564453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 224.35879517, -2027.34899902, 16.59619141]), + 'frame': 74813, + 'frame_number': 74813, + 'framesequence': 74811, + 'gaze_dir': array([ 0.98058069, -0.18583329, -0.06266914]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18583329, -0.06266914]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18583329, -0.06266914]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.33507781103253, + 'timestamp_carla': 280334, + 'timestamp_device': 279927, + 'timestamp_stream': 280.33507781103253, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.27425946e-03, 2.61847046e-03, -1.38935299e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.51988983154297, + 'FR_Wheel_Angle': 41.218955993652344, + 'Location': array([ -3.86765766, -23.17923927, 0.16642696]), + 'Rotation': array([-0.05957291, -4.20446873, -0.01589966]), + 'Velocity': array([-1.06265342, -0.34539351, 0.00118648]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.527587890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 223.57991028, -2027.82543945, 16.5970459 ]), + 'frame': 74814, + 'frame_number': 74814, + 'framesequence': 74812, + 'gaze_dir': array([ 0.98058069, -0.18558127, -0.06341156]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18558127, -0.06341156]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18558127, -0.06341156]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.33896181359887, + 'timestamp_carla': 280338, + 'timestamp_device': 279931, + 'timestamp_stream': 280.33896181359887, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.61998789e-02, 3.89220216e-03, -1.41609507e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.518905639648438, + 'FR_Wheel_Angle': 41.21711730957031, + 'Location': array([ -3.91948652, -23.19191933, 0.16647965]), + 'Rotation': array([-0.05957291, -4.89114618, -0.0151062 ]), + 'Velocity': array([-1.0683893 , -0.33795932, 0.00112967]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5267333984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 222.7991333 , -2028.29882812, 16.59790039]), + 'frame': 74815, + 'frame_number': 74815, + 'framesequence': 74813, + 'gaze_dir': array([ 0.98058069, -0.18538883, -0.06397196]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18538883, -0.06397196]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18538883, -0.06397196]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.34236301109195, + 'timestamp_carla': 280341, + 'timestamp_device': 279934, + 'timestamp_stream': 280.34236301109195, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.56780142e-02, -2.70830380e-04, -1.41658974e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52056121826172, + 'FR_Wheel_Angle': 41.21724319458008, + 'Location': array([ -3.96895051, -23.20341492, 0.16652656]), + 'Rotation': array([-0.05951143, -5.54483414, -0.01449585]), + 'Velocity': array([-1.06946313, -0.32584986, 0.00115285]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52587890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 222.20782471, -2028.65429688, 16.59875488]), + 'frame': 74816, + 'frame_number': 74816, + 'framesequence': 74814, + 'gaze_dir': array([ 0.98058069, -0.18513159, -0.06471259]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18513159, -0.06471259]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18513159, -0.06471259]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3459741137922, + 'timestamp_carla': 280345, + 'timestamp_device': 279938, + 'timestamp_stream': 280.3459741137922, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.02055526, -0.01460628, -13.91993332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.523683547973633, + 'FR_Wheel_Angle': 41.223873138427734, + 'Location': array([ -4.01575661, -23.21377945, 0.16656409]), + 'Rotation': array([-0.05936117, -6.16373158, -0.01382446]), + 'Velocity': array([-1.06530082, -0.30849451, 0.00138892]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5250244140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 221.42375183, -2029.12219238, 16.59960938]), + 'frame': 74817, + 'frame_number': 74817, + 'framesequence': 74815, + 'gaze_dir': array([ 0.98058075, -0.18493725, -0.06526599]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18493725, -0.06526599]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18493725, -0.06526599]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3491452112794, + 'timestamp_carla': 280348, + 'timestamp_device': 279941, + 'timestamp_stream': 280.3491452112794, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.08268084e-02, 2.23173224e-03, -1.36728983e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524431228637695, + 'FR_Wheel_Angle': 41.22555923461914, + 'Location': array([ -4.06667519, -23.22434807, 0.16661163]), + 'Rotation': array([-0.05880792, -6.82645321, -0.01443482]), + 'Velocity': array([-1.06669784, -0.29267561, 0.00138874]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5242919921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 220.83596802, -2029.47009277, 16.6003418 ]), + 'frame': 74818, + 'frame_number': 74818, + 'framesequence': 74816, + 'gaze_dir': array([ 0.98058075, -0.18474123, -0.06581879]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18474123, -0.06581879]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18474123, -0.06581879]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3524758145213, + 'timestamp_carla': 280351, + 'timestamp_device': 279944, + 'timestamp_stream': 280.3524758145213, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.72022972e-02, 5.82287367e-03, -1.37295618e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.523731231689453, + 'FR_Wheel_Angle': 41.22373580932617, + 'Location': array([ -4.11593294, -23.23400116, 0.16666569]), + 'Rotation': array([-0.0587806 , -7.46805477, -0.01339722]), + 'Velocity': array([-1.07163179, -0.28184685, 0.0013476 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.523681640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 220.24716187, -2029.81628418, 16.60095215]), + 'frame': 74819, + 'frame_number': 74819, + 'framesequence': 74817, + 'gaze_dir': array([ 0.98058069, -0.1844766 , -0.06655682]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1844766 , -0.06655682]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1844766 , -0.06655682]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.35604271292686, + 'timestamp_carla': 280355, + 'timestamp_device': 279948, + 'timestamp_stream': 280.35604271292686, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.34124516e-03, -2.66397316e-02, -1.35905333e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.535261154174805, + 'FR_Wheel_Angle': 41.24177932739258, + 'Location': array([ -4.16782141, -23.24359894, 0.16669689]), + 'Rotation': array([-0.05837762, -8.14237499, -0.01303101]), + 'Velocity': array([-1.04872417, -0.26774547, 0.00123792]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5225830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 219.45846558, -2030.27612305, 16.60205078]), + 'frame': 74820, + 'frame_number': 74820, + 'framesequence': 74818, + 'gaze_dir': array([ 0.98058069, -0.18427467, -0.06711387]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18427467, -0.06711387]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18427467, -0.06711387]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.35932771116495, + 'timestamp_carla': 280358, + 'timestamp_device': 279951, + 'timestamp_stream': 280.35932771116495, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.03692355, 0.01567699, -13.78530979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.527000427246094, + 'FR_Wheel_Angle': 41.22896194458008, + 'Location': array([ -4.21439886, -23.25166893, 0.16675957]), + 'Rotation': array([-0.05832298, -8.74659252, -0.01223755]), + 'Velocity': array([-1.07025027, -0.25762302, 0.00131883]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.52197265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 218.86120605, -2030.6217041 , 16.60266113]), + 'frame': 74821, + 'frame_number': 74821, + 'framesequence': 74819, + 'gaze_dir': array([ 0.98058069, -0.18407314, -0.06766468]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18407314, -0.06766468]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18407314, -0.06766468]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3626829124987, + 'timestamp_carla': 280362, + 'timestamp_device': 279954, + 'timestamp_stream': 280.3626829124987, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.87788662e-02, 1.29510015e-02, -1.36742315e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525066375732422, + 'FR_Wheel_Angle': 41.22670364379883, + 'Location': array([ -4.2676754 , -23.26025581, 0.16682063]), + 'Rotation': array([-0.05868498, -9.43647575, -0.01092529]), + 'Velocity': array([-1.07748163, -0.24379632, 0.00125252]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5211181640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 218.26895142, -2030.96191406, 16.60351562]), + 'frame': 74822, + 'frame_number': 74822, + 'framesequence': 74820, + 'gaze_dir': array([ 0.98058075, -0.18386994, -0.06821489]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18386994, -0.06821489]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18386994, -0.06821489]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3658067137003, + 'timestamp_carla': 280365, + 'timestamp_device': 279957, + 'timestamp_stream': 280.3658067137003, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.11087647e-03, -2.96601281e-03, -1.36709871e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.526721954345703, + 'FR_Wheel_Angle': 41.229156494140625, + 'Location': array([ -4.31777954, -23.26772881, 0.16687237]), + 'Rotation': array([-5.88420779e-02, -1.00845480e+01, -9.82665922e-03]), + 'Velocity': array([-1.07699955, -0.23195328, 0.00113629]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5203857421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 217.67567444, -2031.30041504, 16.60424805]), + 'frame': 74823, + 'frame_number': 74823, + 'framesequence': 74821, + 'gaze_dir': array([ 0.98058075, -0.18359576, -0.06894942]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18359576, -0.06894942]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18359576, -0.06894942]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3693253137171, + 'timestamp_carla': 280368, + 'timestamp_device': 279961, + 'timestamp_stream': 280.3693253137171, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.22014692e-02, 3.76031152e-03, -1.38044872e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.526819229125977, + 'FR_Wheel_Angle': 41.22832107543945, + 'Location': array([ -4.36371708, -23.27409554, 0.16691825]), + 'Rotation': array([-5.86849824e-02, -1.06788807e+01, -9.27734375e-03]), + 'Velocity': array([-1.07886279, -0.22210836, 0.00128324]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.51953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 216.88105774, -2031.75 , 16.60498047]), + 'frame': 74824, + 'frame_number': 74824, + 'framesequence': 74822, + 'gaze_dir': array([ 0.98058069, -0.18338659, -0.06950378]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18338659, -0.06950378]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18338659, -0.06950378]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.37285471335053, + 'timestamp_carla': 280372, + 'timestamp_device': 279964, + 'timestamp_stream': 280.37285471335053, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.56071549e-02, 9.09073278e-03, -1.37425089e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.523160934448242, + 'FR_Wheel_Angle': 41.223079681396484, + 'Location': array([ -4.41570187, -23.28068352, 0.16697578]), + 'Rotation': array([-5.88420779e-02, -1.13486500e+01, -8.27026367e-03]), + 'Velocity': array([-1.08956718, -0.20882423, 0.00128428]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.518798828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 216.27935791, -2032.08776855, 16.60571289]), + 'frame': 74825, + 'frame_number': 74825, + 'framesequence': 74823, + 'gaze_dir': array([ 0.98058075, -0.18310729, -0.07023638]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18310729, -0.07023638]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18310729, -0.07023638]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.37618021294475, + 'timestamp_carla': 280375, + 'timestamp_device': 279968, + 'timestamp_stream': 280.37618021294475, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.82523425e-03, -1.87381008e-03, -1.37354288e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52364158630371, + 'FR_Wheel_Angle': 41.22401809692383, + 'Location': array([ -4.46546602, -23.28641701, 0.16702542]), + 'Rotation': array([-5.88420779e-02, -1.19894295e+01, -7.38525437e-03]), + 'Velocity': array([-1.09075189e+00, -1.96687907e-01, 8.58058920e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.517822265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 215.48162842, -2032.53186035, 16.60668945]), + 'frame': 74826, + 'frame_number': 74826, + 'framesequence': 74824, + 'gaze_dir': array([ 0.98058075, -0.18282503, -0.07096785]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18282503, -0.07096785]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18282503, -0.07096785]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.37988091260195, + 'timestamp_carla': 280379, + 'timestamp_device': 279972, + 'timestamp_stream': 280.37988091260195, + 'transform': [array([ 0.00866119, -0.00365967, 0.15899415]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-7.97718018e-03, 7.97391811e-04, -1.37563858e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.522939682006836, + 'FR_Wheel_Angle': 41.226444244384766, + 'Location': array([ -4.51445961, -23.29152298, 0.16707511]), + 'Rotation': array([-5.87464534e-02, -1.26198626e+01, -6.80541992e-03]), + 'Velocity': array([-1.09452116, -0.18501127, 0.00121448]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.516845703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 214.68206787, -2032.97277832, 16.60766602]), + 'frame': 74827, + 'frame_number': 74827, + 'framesequence': 74825, + 'gaze_dir': array([ 0.98058075, -0.18246755, -0.07188197]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18246755, -0.07188197]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18246755, -0.07188197]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3851686120033, + 'timestamp_carla': 280384, + 'timestamp_device': 279977, + 'timestamp_stream': 280.3851686120033, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898888]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.05356444e-03, -1.02033652e-03, -1.37094069e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524215698242188, + 'FR_Wheel_Angle': 41.22547149658203, + 'Location': array([ -4.56519651, -23.29624367, 0.16712306]), + 'Rotation': array([-5.85278869e-02, -1.32723284e+01, -6.37817383e-03]), + 'Velocity': array([-1.09348178e+00, -1.71927080e-01, 1.05796335e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 213.67869568, -2033.5201416 , 16.60888672]), + 'frame': 74828, + 'frame_number': 74828, + 'framesequence': 74826, + 'gaze_dir': array([ 0.98058075, -0.18225175, -0.07242736]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18225175, -0.07242736]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18225175, -0.07242736]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3887002132833, + 'timestamp_carla': 280388, + 'timestamp_device': 279980, + 'timestamp_stream': 280.3887002132833, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898888]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.97617696e-03, -2.21990398e-03, -1.36626396e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525667190551758, + 'FR_Wheel_Angle': 41.22738265991211, + 'Location': array([ -4.6168704 , -23.30045891, 0.16716976]), + 'Rotation': array([-5.83229810e-02, -1.39359636e+01, -5.88989304e-03]), + 'Velocity': array([-1.09198773e+00, -1.58883154e-01, 1.08064653e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.514404296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 213.07772827, -2033.84472656, 16.60949707]), + 'frame': 74829, + 'frame_number': 74829, + 'framesequence': 74827, + 'gaze_dir': array([ 0.98058069, -0.18196073, -0.07315539]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18196073, -0.07315539]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18196073, -0.07315539]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.39196361228824, + 'timestamp_carla': 280391, + 'timestamp_device': 279984, + 'timestamp_stream': 280.39196361228824, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898888]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-8.47552437e-03, 1.43826124e-03, -1.36928749e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525028228759766, + 'FR_Wheel_Angle': 41.22625732421875, + 'Location': array([ -4.66654539, -23.30393791, 0.16722278]), + 'Rotation': array([-5.82888313e-02, -1.45732002e+01, -5.15747070e-03]), + 'Velocity': array([-1.09521627, -0.14699265, 0.00125841]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5133056640625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 212.27296448, -2034.27600098, 16.6105957 ]), + 'frame': 74830, + 'frame_number': 74830, + 'framesequence': 74828, + 'gaze_dir': array([ 0.98058069, -0.18174112, -0.07369925]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18174112, -0.07369925]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18174112, -0.07369925]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3956306129694, + 'timestamp_carla': 280394, + 'timestamp_device': 279987, + 'timestamp_stream': 280.3956306129694, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898888]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.17827396e-03, -4.15927498e-03, -1.36690607e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.5258731842041, + 'FR_Wheel_Angle': 41.22773742675781, + 'Location': array([ -4.71704435, -23.30690575, 0.16727252]), + 'Rotation': array([-5.82273602e-02, -1.52205667e+01, -4.45556594e-03]), + 'Velocity': array([-1.0948987 , -0.13476272, 0.00129315]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5126953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 211.66983032, -2034.59655762, 16.61120605]), + 'frame': 74831, + 'frame_number': 74831, + 'framesequence': 74829, + 'gaze_dir': array([ 0.98058075, -0.18151765, -0.074248 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18151765, -0.074248 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18151765, -0.074248 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.3988800123334, + 'timestamp_carla': 280398, + 'timestamp_device': 279990, + 'timestamp_stream': 280.3988800123334, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898888]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.46653333e-02, 7.60124577e-03, -1.38792200e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524089813232422, + 'FR_Wheel_Angle': 41.2240104675293, + 'Location': array([ -4.77028751, -23.30941391, 0.16732959]), + 'Rotation': array([-5.81658892e-02, -1.59027882e+01, -3.69262719e-03]), + 'Velocity': array([-1.1010505 , -0.12346262, 0.00135758]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5118408203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 211.05957031, -2034.91845703, 16.61206055]), + 'frame': 74832, + 'frame_number': 74832, + 'framesequence': 74830, + 'gaze_dir': array([ 0.98058075, -0.18114376, -0.07515555]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18114376, -0.07515555]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18114376, -0.07515555]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.40235621109605, + 'timestamp_carla': 280401, + 'timestamp_device': 279995, + 'timestamp_stream': 280.40235621109605, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898888]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.56653316e-02, 8.27423949e-03, -1.39543362e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52230453491211, + 'FR_Wheel_Angle': 41.222042083740234, + 'Location': array([ -4.81908607, -23.31114197, 0.16738251]), + 'Rotation': array([-5.81658892e-02, -1.65275726e+01, -2.80761765e-03]), + 'Velocity': array([-1.10665202e+00, -1.12051062e-01, 1.05499022e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5106201171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 210.04647827, -2035.44775391, 16.61315918]), + 'frame': 74833, + 'frame_number': 74833, + 'framesequence': 74831, + 'gaze_dir': array([ 0.98058075, -0.18091817, -0.07569696]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18091817, -0.07569696]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18091817, -0.07569696]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.40669241175056, + 'timestamp_carla': 280406, + 'timestamp_device': 279998, + 'timestamp_stream': 280.40669241175056, + 'transform': [array([ 0.00866089, -0.00365967, 0.15898721]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.02239603e-02, -3.22835433e-04, -1.39391804e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.5231990814209, + 'FR_Wheel_Angle': 41.2239875793457, + 'Location': array([ -4.86909819, -23.31236267, 0.16743244]), + 'Rotation': array([-5.81385680e-02, -1.71676140e+01, -2.10571196e-03]), + 'Velocity': array([-1.10584533e+00, -1.00014061e-01, 1.03043078e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.510009765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 209.43981934, -2035.76159668, 16.6138916 ]), + 'frame': 74834, + 'frame_number': 74834, + 'framesequence': 74832, + 'gaze_dir': array([ 0.98058075, -0.18061413, -0.07641963]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18061413, -0.07641963]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18061413, -0.07641963]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.41022131219506, + 'timestamp_carla': 280409, + 'timestamp_device': 280002, + 'timestamp_stream': 280.41022131219506, + 'transform': [array([ 0.00866089, -0.00365967, 0.15898721]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 6.97651599e-03, -2.11069174e-02, -1.35633526e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.530742645263672, + 'FR_Wheel_Angle': 41.23793029785156, + 'Location': array([ -4.91931772, -23.31306839, 0.16747265]), + 'Rotation': array([-5.74350581e-02, -1.78116550e+01, -2.19726493e-03]), + 'Velocity': array([-1.08847475, -0.08514731, 0.0011816 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.509033203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 208.62747192, -2036.17834473, 16.61462402]), + 'frame': 74835, + 'frame_number': 74835, + 'framesequence': 74833, + 'gaze_dir': array([ 0.98058075, -0.18038477, -0.07695945]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.18038477, -0.07695945]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.18038477, -0.07695945]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.41371331363916, + 'timestamp_carla': 280413, + 'timestamp_device': 280005, + 'timestamp_stream': 280.41371331363916, + 'transform': [array([ 0.00866089, -0.00365967, 0.15898721]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.48233862e-02, 5.68892108e-03, -1.36723318e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.53141212463379, + 'FR_Wheel_Angle': 41.23551559448242, + 'Location': array([ -4.96926737, -23.3132019 , 0.16751483]), + 'Rotation': array([-5.68544902e-02, -1.84508762e+01, -2.13623024e-03]), + 'Velocity': array([-1.08801532, -0.07368647, 0.00145924]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.50830078125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 208.01863098, -2036.48803711, 16.61535645]), + 'frame': 74836, + 'frame_number': 74836, + 'framesequence': 74834, + 'gaze_dir': array([ 0.98058069, -0.1801514 , -0.07750409]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1801514 , -0.07750409]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1801514 , -0.07750409]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.41685331240296, + 'timestamp_carla': 280416, + 'timestamp_device': 280008, + 'timestamp_stream': 280.41685331240296, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.28731167e-02, 3.84740275e-03, -1.37087326e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.53046989440918, + 'FR_Wheel_Angle': 41.23455047607422, + 'Location': array([ -5.02006197, -23.31274414, 0.16757271]), + 'Rotation': array([-5.69706038e-02, -1.91004658e+01, -9.76562325e-04]), + 'Velocity': array([-1.09115708e+00, -6.18003644e-02, 9.21964645e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5074462890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 207.40261841, -2036.79882812, 16.61633301]), + 'frame': 74837, + 'frame_number': 74837, + 'framesequence': 74835, + 'gaze_dir': array([ 0.98058075, -0.17984013, -0.07822368]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17984013, -0.07822368]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17984013, -0.07822368]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4204694144428, + 'timestamp_carla': 280419, + 'timestamp_device': 280012, + 'timestamp_stream': 280.4204694144428, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.38150377e-02, 7.99173117e-03, -1.37228909e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52973175048828, + 'FR_Wheel_Angle': 41.23339080810547, + 'Location': array([ -5.07063913, -23.31172562, 0.16762935]), + 'Rotation': array([-5.69091327e-02, -1.97478046e+01, -1.83104508e-04]), + 'Velocity': array([-1.09341288, -0.04915002, 0.00129163]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5067138671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 206.58618164, -2037.20739746, 16.61706543]), + 'frame': 74838, + 'frame_number': 74838, + 'framesequence': 74836, + 'gaze_dir': array([ 0.98058075, -0.17952597, -0.07894202]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17952597, -0.07894202]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17952597, -0.07894202]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.42452931404114, + 'timestamp_carla': 280423, + 'timestamp_device': 280016, + 'timestamp_stream': 280.42452931404114, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.59220582e-02, 1.05240894e-02, -1.37437010e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.529666900634766, + 'FR_Wheel_Angle': 41.23371887207031, + 'Location': array([ -5.12151241, -23.31011581, 0.16768436]), + 'Rotation': array([-5.69091327e-02, -2.03989506e+01, 6.26776018e-04]), + 'Velocity': array([-1.09513748, -0.03668841, 0.00132024]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.505615234375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 205.76802063, -2037.6126709 , 16.61816406]), + 'frame': 74839, + 'frame_number': 74839, + 'framesequence': 74837, + 'gaze_dir': array([ 0.98058069, -0.17920892, -0.0796591 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17920892, -0.0796591 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17920892, -0.0796591 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.42847991362214, + 'timestamp_carla': 280427, + 'timestamp_device': 280020, + 'timestamp_stream': 280.42847991362214, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.42919151e-02, 9.71500948e-03, -1.36094656e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52769660949707, + 'FR_Wheel_Angle': 41.23048782348633, + 'Location': array([ -5.16750288, -23.30815887, 0.16773425]), + 'Rotation': array([-5.69091327e-02, -2.09871445e+01, 1.39489747e-03]), + 'Velocity': array([-1.09830093, -0.02348005, 0.00144238]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.504638671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 204.94827271, -2038.01464844, 16.61914062]), + 'frame': 74840, + 'frame_number': 74840, + 'framesequence': 74838, + 'gaze_dir': array([ 0.98058075, -0.17888905, -0.0803749 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17888905, -0.0803749 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17888905, -0.0803749 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4323715120554, + 'timestamp_carla': 280431, + 'timestamp_device': 280024, + 'timestamp_stream': 280.4323715120554, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.73141684e-03, -5.92385232e-03, -1.36088600e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52814292907715, + 'FR_Wheel_Angle': 41.23201370239258, + 'Location': array([ -5.21838236, -23.30543709, 0.16778697]), + 'Rotation': array([-5.71003780e-02, -2.16381416e+01, 2.44573248e-03]), + 'Velocity': array([-1.09760118e+00, -1.14023425e-02, 9.25979577e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5037841796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 204.12693787, -2038.41345215, 16.61999512]), + 'frame': 74841, + 'frame_number': 74841, + 'framesequence': 74839, + 'gaze_dir': array([ 0.98058075, -0.17856629, -0.08108942]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17856629, -0.08108942]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17856629, -0.08108942]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.43553491309285, + 'timestamp_carla': 280434, + 'timestamp_device': 280028, + 'timestamp_stream': 280.43553491309285, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.41295360e-02, 9.49160755e-03, -1.38572702e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525257110595703, + 'FR_Wheel_Angle': 41.22575378417969, + 'Location': array([ -5.27106857, -23.3020153 , 0.16784663]), + 'Rotation': array([-5.70047572e-02, -2.23132153e+01, 3.31483944e-03]), + 'Velocity': array([-1.10518718e+00, 8.78570427e-05, 1.15835422e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5028076171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 203.30401611, -2038.80883789, 16.62084961]), + 'frame': 74842, + 'frame_number': 74842, + 'framesequence': 74840, + 'gaze_dir': array([ 0.98058075, -0.17832297, -0.08162311]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17832297, -0.08162311]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17832297, -0.08162311]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4396433122456, + 'timestamp_carla': 280438, + 'timestamp_device': 280031, + 'timestamp_stream': 280.4396433122456, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.68856606e-02, -3.00219934e-03, -1.38082476e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.526626586914062, + 'FR_Wheel_Angle': 41.23027801513672, + 'Location': array([ -5.32220507, -23.29810333, 0.16789371]), + 'Rotation': array([-5.68271726e-02, -2.29686394e+01, 3.95846600e-03]), + 'Velocity': array([-1.10080254e+00, 1.20483190e-02, 1.06204033e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.501953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 202.68734741, -2039.10253906, 16.6217041 ]), + 'frame': 74843, + 'frame_number': 74843, + 'framesequence': 74841, + 'gaze_dir': array([ 0.98058075, -0.17799523, -0.08233535]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17799523, -0.08233535]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17799523, -0.08233535]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4433030113578, + 'timestamp_carla': 280442, + 'timestamp_device': 280035, + 'timestamp_stream': 280.4433030113578, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.34751198e-02, 9.50164162e-03, -1.38770905e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524341583251953, + 'FR_Wheel_Angle': 41.225093841552734, + 'Location': array([ -5.37054205, -23.29384995, 0.16794921]), + 'Rotation': array([-5.67315482e-02, -2.35884800e+01, 4.58718417e-03]), + 'Velocity': array([-1.10704958, 0.02491973, 0.00126792]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.5010986328125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 201.86166382, -2039.4921875 , 16.62255859]), + 'frame': 74844, + 'frame_number': 74844, + 'framesequence': 74842, + 'gaze_dir': array([ 0.98058069, -0.17774566, -0.08287273]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17774566, -0.08287273]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17774566, -0.08287273]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.44650611281395, + 'timestamp_carla': 280445, + 'timestamp_device': 280038, + 'timestamp_stream': 280.44650611281395, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.18489394e-02, 6.66626683e-03, -1.39099360e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.523529052734375, + 'FR_Wheel_Angle': 41.22273635864258, + 'Location': array([ -5.41956711, -23.28899765, 0.16800198]), + 'Rotation': array([-5.67315482e-02, -2.42179623e+01, 5.35580562e-03]), + 'Velocity': array([-1.10873914, 0.03698045, 0.00123557]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.500244140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 201.23666382, -2039.7845459 , 16.62341309]), + 'frame': 74845, + 'frame_number': 74845, + 'framesequence': 74843, + 'gaze_dir': array([ 0.98058069, -0.17749701, -0.08340395]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17749701, -0.08340395]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17749701, -0.08340395]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4497157111764, + 'timestamp_carla': 280449, + 'timestamp_device': 280041, + 'timestamp_stream': 280.4497157111764, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-8.19423515e-03, 2.46497616e-03, -1.37769680e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.521831512451172, + 'FR_Wheel_Angle': 41.22087097167969, + 'Location': array([ -5.47232389, -23.28316307, 0.16805798]), + 'Rotation': array([-5.66700771e-02, -2.48957901e+01, 6.05828175e-03]), + 'Velocity': array([-1.11133969, 0.05235795, 0.00121557]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4996337890625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 200.61711121, -2040.07202148, 16.62402344]), + 'frame': 74846, + 'frame_number': 74846, + 'framesequence': 74844, + 'gaze_dir': array([ 0.98058075, -0.17716217, -0.08411289]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17716217, -0.08411289]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17716217, -0.08411289]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4531384110451, + 'timestamp_carla': 280452, + 'timestamp_device': 280045, + 'timestamp_stream': 280.4531384110451, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-6.96939975e-03, -2.14544794e-04, -1.37940283e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.521480560302734, + 'FR_Wheel_Angle': 41.22083282470703, + 'Location': array([ -5.52230644, -23.27705574, 0.16810802]), + 'Rotation': array([-5.66086061e-02, -2.55389786e+01, 6.71142107e-03]), + 'Velocity': array([-1.11159945, 0.06473487, 0.00127438]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4986572265625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 199.78756714, -2040.45336914, 16.625 ]), + 'frame': 74847, + 'frame_number': 74847, + 'framesequence': 74845, + 'gaze_dir': array([ 0.98058075, -0.17690982, -0.08464236]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17690982, -0.08464236]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17690982, -0.08464236]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.45677791163325, + 'timestamp_carla': 280456, + 'timestamp_device': 280048, + 'timestamp_stream': 280.45677791163325, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.27531674e-03, -1.21706724e-02, -1.37137890e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524803161621094, + 'FR_Wheel_Angle': 41.22670364379883, + 'Location': array([ -5.57412529, -23.27012634, 0.16815555]), + 'Rotation': array([-5.62124550e-02, -2.62072220e+01, 7.03365309e-03]), + 'Velocity': array([-1.10311747, 0.0764894 , 0.00116906]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4979248046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 199.16598511, -2040.7364502 , 16.62573242]), + 'frame': 74848, + 'frame_number': 74848, + 'framesequence': 74846, + 'gaze_dir': array([ 0.98058075, -0.17657001, -0.08534893]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17657001, -0.08534893]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17657001, -0.08534893]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4599739126861, + 'timestamp_carla': 280459, + 'timestamp_device': 280052, + 'timestamp_stream': 280.4599739126861, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-6.22218708e-03, -9.85492719e-04, -1.37185898e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.523752212524414, + 'FR_Wheel_Angle': 41.22477722167969, + 'Location': array([ -5.62325716, -23.26299286, 0.16820957]), + 'Rotation': array([-5.58436252e-02, -2.68419323e+01, 7.45998509e-03]), + 'Velocity': array([-1.10434198, 0.08966604, 0.00115747]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.496826171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 198.33380127, -2041.11206055, 16.62683105]), + 'frame': 74849, + 'frame_number': 74849, + 'framesequence': 74847, + 'gaze_dir': array([ 0.98058075, -0.17631134, -0.085882 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17631134, -0.085882 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17631134, -0.085882 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4633946120739, + 'timestamp_carla': 280462, + 'timestamp_device': 280055, + 'timestamp_stream': 280.4633946120739, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-9.19189025e-03, 3.17450147e-03, -1.37668133e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52238655090332, + 'FR_Wheel_Angle': 41.22474670410156, + 'Location': array([ -5.67151117, -23.25542831, 0.16826385]), + 'Rotation': array([-5.58163039e-02, -2.74660816e+01, 8.19329266e-03]), + 'Velocity': array([-1.10659182, 0.10196906, 0.00127662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4962158203125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 197.70393372, -2041.39367676, 16.62731934]), + 'frame': 74850, + 'frame_number': 74850, + 'framesequence': 74848, + 'gaze_dir': array([ 0.98058075, -0.1760537 , -0.08640892]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.1760537 , -0.08640892]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.1760537 , -0.08640892]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4665094129741, + 'timestamp_carla': 280465, + 'timestamp_device': 280058, + 'timestamp_stream': 280.4665094129741, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.18194726e-03, -6.73872652e-03, -1.37039585e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52507972717285, + 'FR_Wheel_Angle': 41.22657775878906, + 'Location': array([ -5.72264338, -23.24683952, 0.16831295]), + 'Rotation': array([-5.54543026e-02, -2.81291752e+01, 8.67525395e-03]), + 'Velocity': array([-1.0991925 , 0.11353763, 0.00125744]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4954833984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 197.07955933, -2041.6706543 , 16.62805176]), + 'frame': 74851, + 'frame_number': 74851, + 'framesequence': 74849, + 'gaze_dir': array([ 0.98058075, -0.17570685, -0.08711205]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17570685, -0.08711205]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17570685, -0.08711205]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4702335111797, + 'timestamp_carla': 280469, + 'timestamp_device': 280062, + 'timestamp_stream': 280.4702335111797, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.52828563e-02, -8.97872262e-03, -1.37068272e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.530786514282227, + 'FR_Wheel_Angle': 41.234527587890625, + 'Location': array([ -5.77216244, -23.23796082, 0.16835365]), + 'Rotation': array([-5.47234714e-02, -2.87734928e+01, 8.75381008e-03]), + 'Velocity': array([-1.08548379, 0.12201323, 0.00139855]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.494384765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 196.24365234, -2042.0378418 , 16.62915039]), + 'frame': 74852, + 'frame_number': 74852, + 'framesequence': 74850, + 'gaze_dir': array([ 0.98058075, -0.17535719, -0.0878138 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17535719, -0.0878138 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17535719, -0.0878138 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4741035141051, + 'timestamp_carla': 280473, + 'timestamp_device': 280066, + 'timestamp_stream': 280.4741035141051, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.49886885e-02, 1.36567624e-02, -1.37771225e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.527761459350586, + 'FR_Wheel_Angle': 41.229793548583984, + 'Location': array([ -5.82100248, -23.22862053, 0.16841148]), + 'Rotation': array([-5.45049049e-02, -2.94094582e+01, 9.38462559e-03]), + 'Velocity': array([-1.09070909, 0.13598347, 0.00128546]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4935302734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 195.40634155, -2042.4017334 , 16.63000488]), + 'frame': 74853, + 'frame_number': 74853, + 'framesequence': 74851, + 'gaze_dir': array([ 0.98058075, -0.17509378, -0.08833785]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17509378, -0.08833785]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17509378, -0.08833785]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.47751451283693, + 'timestamp_carla': 280476, + 'timestamp_device': 280069, + 'timestamp_stream': 280.47751451283693, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.54606735e-02, 1.28266327e-02, -1.38171263e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.526901245117188, + 'FR_Wheel_Angle': 41.228126525878906, + 'Location': array([ -5.87082815, -23.21849632, 0.16846561]), + 'Rotation': array([-5.44434339e-02, -3.00595455e+01, 1.03285862e-02]), + 'Velocity': array([-1.09130359, 0.14835353, 0.00130459]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.49267578125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 194.77896118, -2042.67175293, 16.63085938]), + 'frame': 74854, + 'frame_number': 74854, + 'framesequence': 74852, + 'gaze_dir': array([ 0.98058075, -0.17482609, -0.08886645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17482609, -0.08886645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17482609, -0.08886645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4807168133557, + 'timestamp_carla': 280480, + 'timestamp_device': 280072, + 'timestamp_stream': 280.4807168133557, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.15354506e-02, 5.22185257e-03, -1.38508358e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.526098251342773, + 'FR_Wheel_Angle': 41.228458404541016, + 'Location': array([ -5.91961145, -23.20800972, 0.16852123]), + 'Rotation': array([-5.44092841e-02, -3.06977329e+01, 1.13241626e-02]), + 'Velocity': array([-1.09165978e+00, 1.60505533e-01, 7.79075606e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4920654296875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 194.14437866, -2042.94262695, 16.63146973]), + 'frame': 74855, + 'frame_number': 74855, + 'framesequence': 74853, + 'gaze_dir': array([ 0.98058075, -0.17446941, -0.08956466]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17446941, -0.08956466]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17446941, -0.08956466]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4839910119772, + 'timestamp_carla': 280483, + 'timestamp_device': 280076, + 'timestamp_stream': 280.4839910119772, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.88487191e-02, 2.10994598e-03, -1.38222370e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52667808532715, + 'FR_Wheel_Angle': 41.22867965698242, + 'Location': array([ -5.96888781, -23.19685555, 0.16857341]), + 'Rotation': array([-5.41975498e-02, -3.13444939e+01, 1.19003011e-02]), + 'Velocity': array([-1.0883348 , 0.17269781, 0.00124488]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.490966796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 193.30340576, -2043.2980957 , 16.63244629]), + 'frame': 74856, + 'frame_number': 74856, + 'framesequence': 74854, + 'gaze_dir': array([ 0.98058075, -0.17420076, -0.09008605]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17420076, -0.09008605]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17420076, -0.09008605]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.48773941397667, + 'timestamp_carla': 280487, + 'timestamp_device': 280079, + 'timestamp_stream': 280.48773941397667, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-3.70936864e-03, -1.20901549e-02, -1.35825100e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.529359817504883, + 'FR_Wheel_Angle': 41.232784271240234, + 'Location': array([ -6.01541901, -23.18578529, 0.16861904]), + 'Rotation': array([-5.37399240e-02, -3.19567738e+01, 1.22065237e-02]), + 'Velocity': array([-1.07925701, 0.18454391, 0.00141826]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4903564453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 192.67337036, -2043.56188965, 16.63305664]), + 'frame': 74857, + 'frame_number': 74857, + 'framesequence': 74855, + 'gaze_dir': array([ 0.98058069, -0.17383921, -0.09078174]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17383921, -0.09078174]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17383921, -0.09078174]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4911046139896, + 'timestamp_carla': 280490, + 'timestamp_device': 280083, + 'timestamp_stream': 280.4911046139896, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-4.47087223e-04, -2.01823432e-02, -1.34347401e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.53145980834961, + 'FR_Wheel_Angle': 41.235816955566406, + 'Location': array([ -6.06607151, -23.17313385, 0.16866447]), + 'Rotation': array([-5.34325652e-02, -3.26239204e+01, 1.27147753e-02]), + 'Velocity': array([-1.07213449, 0.1960433 , 0.00122973]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4893798828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 191.82995605, -2043.91149902, 16.6340332 ]), + 'frame': 74858, + 'frame_number': 74858, + 'framesequence': 74856, + 'gaze_dir': array([ 0.98058075, -0.17356694, -0.09130125]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17356694, -0.09130125]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17356694, -0.09130125]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4945258125663, + 'timestamp_carla': 280493, + 'timestamp_device': 280086, + 'timestamp_stream': 280.4945258125663, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.17810416, 0.41019347, -13.60080051]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.529020309448242, + 'FR_Wheel_Angle': 41.233394622802734, + 'Location': array([ -6.11481476, -23.16040802, 0.16905044]), + 'Rotation': array([ -0.06695634, -33.26719666, 0.03842858]), + 'Velocity': array([-1.07339823, 0.21257178, 0.00615919]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.48876953125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 191.19812012, -2044.17077637, 16.63464355]), + 'frame': 74859, + 'frame_number': 74859, + 'framesequence': 74857, + 'gaze_dir': array([ 0.98058075, -0.17329031, -0.09182522]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17329031, -0.09182522]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17329031, -0.09182522]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.4977622143924, + 'timestamp_carla': 280497, + 'timestamp_device': 280089, + 'timestamp_stream': 280.4977622143924, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.01371424, 0.08530699, -13.56673908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.529359817504883, + 'FR_Wheel_Angle': 41.23590850830078, + 'Location': array([ -6.16405869, -23.14687157, 0.16931057]), + 'Rotation': array([ -0.07311717, -33.92124557, 0.04668535]), + 'Velocity': array([-1.07136035, 0.22277385, 0.00337773]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4879150390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 190.559021 , -2044.4309082 , 16.63549805]), + 'frame': 74860, + 'frame_number': 74860, + 'framesequence': 74858, + 'gaze_dir': array([ 0.98058075, -0.17292182, -0.09251726]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17292182, -0.09251726]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17292182, -0.09251726]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.50123961269855, + 'timestamp_carla': 280500, + 'timestamp_device': 280093, + 'timestamp_stream': 280.50123961269855, + 'transform': [array([ 0.00866104, -0.00365967, 0.15898824]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 2.22733105e-03, 1.31183248e-02, -1.36532021e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525657653808594, + 'FR_Wheel_Angle': 41.22683334350586, + 'Location': array([ -6.21084356, -23.13345909, 0.16943812]), + 'Rotation': array([ -0.07440124, -34.54367828, 0.04801318]), + 'Velocity': array([-1.07769132, 0.23615275, 0.00211584]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4869384765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 189.71212769, -2044.77197266, 16.63647461]), + 'frame': 74861, + 'frame_number': 74861, + 'framesequence': 74859, + 'gaze_dir': array([ 0.98058075, -0.17255057, -0.09320784]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17255057, -0.09320784]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17255057, -0.09320784]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5054548121989, + 'timestamp_carla': 280504, + 'timestamp_device': 280097, + 'timestamp_stream': 280.5054548121989, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.84897476e-03, -1.98422745e-02, -1.37235451e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.523874282836914, + 'FR_Wheel_Angle': 41.224586486816406, + 'Location': array([ -6.25821543, -23.11930847, 0.1695061 ]), + 'Rotation': array([ -0.07440124, -35.17542267, 0.04805462]), + 'Velocity': array([-1.07951915, 0.24852215, 0.00124854]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4859619140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 188.86392212, -2045.10974121, 16.63745117]), + 'frame': 74862, + 'frame_number': 74862, + 'framesequence': 74860, + 'gaze_dir': array([ 0.98058075, -0.17227104, -0.09372347]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17227104, -0.09372347]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17227104, -0.09372347]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5087636113167, + 'timestamp_carla': 280508, + 'timestamp_device': 280100, + 'timestamp_stream': 280.5087636113167, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.60034795e-03, -3.12172677e-02, -1.37010994e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.524520874023438, + 'FR_Wheel_Angle': 41.2259407043457, + 'Location': array([ -6.30645227, -23.10433769, 0.16954383]), + 'Rotation': array([ -0.07324012, -35.82150269, 0.04728217]), + 'Velocity': array([-1.07523203e+00, 2.60186672e-01, 9.29212547e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4849853515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 188.22846985, -2045.36010742, 16.63818359]), + 'frame': 74863, + 'frame_number': 74863, + 'framesequence': 74861, + 'gaze_dir': array([ 0.98058069, -0.17189495, -0.09441143]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17189495, -0.09441143]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17189495, -0.09441143]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.51205901429057, + 'timestamp_carla': 280511, + 'timestamp_device': 280104, + 'timestamp_stream': 280.51205901429057, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 4.54808353e-03, -3.41249146e-02, -1.37140846e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52410316467285, + 'FR_Wheel_Angle': 41.22504425048828, + 'Location': array([ -6.35399389, -23.08898926, 0.1695713 ]), + 'Rotation': array([ -0.07214729, -36.46025467, 0.04660949]), + 'Velocity': array([-1.07311904e+00, 2.72543490e-01, 4.58512310e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.484130859375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 187.37788391, -2045.6920166 , 16.63903809]), + 'frame': 74864, + 'frame_number': 74864, + 'framesequence': 74862, + 'gaze_dir': array([ 0.98058075, -0.17160895, -0.09493034]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17160895, -0.09493034]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17160895, -0.09493034]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5153936110437, + 'timestamp_carla': 280514, + 'timestamp_device': 280107, + 'timestamp_stream': 280.5153936110437, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.23175429e-02, -1.90377142e-02, -1.39377060e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52249526977539, + 'FR_Wheel_Angle': 41.22285079956055, + 'Location': array([ -6.40438843, -23.0720768 , 0.16959816]), + 'Rotation': array([ -0.07098615, -37.14006042, 0.04608352]), + 'Velocity': array([-1.07430553e+00, 2.84330517e-01, 5.91063465e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4832763671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 186.73423767, -2045.94042969, 16.63977051]), + 'frame': 74865, + 'frame_number': 74865, + 'framesequence': 74863, + 'gaze_dir': array([ 0.98058075, -0.17122807, -0.09561564]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17122807, -0.09561564]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17122807, -0.09561564]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.51899971440434, + 'timestamp_carla': 280518, + 'timestamp_device': 280111, + 'timestamp_stream': 280.51899971440434, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.48214564, -0.96792859, -13.62685013]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.525882720947266, + 'FR_Wheel_Angle': 41.22731018066406, + 'Location': array([ -6.44988585, -23.05624008, 0.16957699]), + 'Rotation': array([ -0.06811064, -37.75583649, 0.04188915]), + 'Velocity': array([-1.0632205 , 0.29476935, -0.00605958]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.482177734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 185.88134766, -2046.26635742, 16.64086914]), + 'frame': 74866, + 'frame_number': 74866, + 'framesequence': 74864, + 'gaze_dir': array([ 0.98058075, -0.17084444, -0.0962994 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17084444, -0.0962994 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17084444, -0.0962994 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5229035131633, + 'timestamp_carla': 280522, + 'timestamp_device': 280115, + 'timestamp_stream': 280.5229035131633, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ 0.03612322, -0.21845923, -13.69505596]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.52126121520996, + 'FR_Wheel_Angle': 41.22206497192383, + 'Location': array([ -6.49856806, -23.03866577, 0.16929932]), + 'Rotation': array([-5.50854728e-02, -3.84166946e+01, 2.12047826e-02]), + 'Velocity': array([-1.07143605, 0.30884025, -0.0025282 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4813232421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 185.02719116, -2046.58874512, 16.64172363]), + 'frame': 74867, + 'frame_number': 74867, + 'framesequence': 74865, + 'gaze_dir': array([ 0.98058075, -0.17055567, -0.09680992]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17055567, -0.09680992]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17055567, -0.09680992]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.52617801353335, + 'timestamp_carla': 280525, + 'timestamp_device': 280118, + 'timestamp_stream': 280.52617801353335, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.0178718 , -0.04815022, -13.82590675]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.521087646484375, + 'FR_Wheel_Angle': 41.22092819213867, + 'Location': array([ -6.54632998, -23.02080345, 0.16921349]), + 'Rotation': array([-5.09395488e-02, -3.90738297e+01, 1.78459678e-02]), + 'Velocity': array([-1.06764293e+00, 3.21951628e-01, -3.99434561e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.48046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 184.38734436, -2046.82763672, 16.64257812]), + 'frame': 74868, + 'frame_number': 74868, + 'framesequence': 74866, + 'gaze_dir': array([ 0.98058075, -0.17026536, -0.09731958]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.17026536, -0.09731958]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.17026536, -0.09731958]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.529479611665, + 'timestamp_carla': 280528, + 'timestamp_device': 280121, + 'timestamp_stream': 280.529479611665, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.19562724e-02, -2.34820254e-04, -1.38165245e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.520381927490234, + 'FR_Wheel_Angle': 41.21970748901367, + 'Location': array([ -6.59339762, -23.00255775, 0.16920978]), + 'Rotation': array([-4.95666787e-02, -3.97259674e+01, 1.78759620e-02]), + 'Velocity': array([-1.06532574e+00, 3.34841788e-01, 4.83031268e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4798583984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 183.74679565, -2047.06469727, 16.64318848]), + 'frame': 74869, + 'frame_number': 74869, + 'framesequence': 74867, + 'gaze_dir': array([ 0.98058075, -0.16987494, -0.09799949]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16987494, -0.09799949]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16987494, -0.09799949]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5332477129996, + 'timestamp_carla': 280532, + 'timestamp_device': 280125, + 'timestamp_stream': 280.5332477129996, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.59387365e-02, 1.22725405e-02, -1.42753401e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.51810646057129, + 'FR_Wheel_Angle': 41.213165283203125, + 'Location': array([ -6.64254856, -22.98283577, 0.16924903]), + 'Rotation': array([-4.92524914e-02, -4.04094124e+01, 1.87939107e-02]), + 'Velocity': array([-1.06581581e+00, 3.49984199e-01, 1.04173901e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4788818359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 182.88946533, -2047.37866211, 16.64404297]), + 'frame': 74870, + 'frame_number': 74870, + 'framesequence': 74868, + 'gaze_dir': array([ 0.98058075, -0.16957809, -0.09851228]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16957809, -0.09851228]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16957809, -0.09851228]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.53682121261954, + 'timestamp_carla': 280536, + 'timestamp_device': 280128, + 'timestamp_stream': 280.53682121261954, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-5.69375046e-03, -5.96039044e-03, -1.44379263e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.519725799560547, + 'FR_Wheel_Angle': 41.21672821044922, + 'Location': array([ -6.69030952, -22.96300316, 0.169296 ]), + 'Rotation': array([-4.91636992e-02, -4.10788307e+01, 1.95677802e-02]), + 'Velocity': array([-1.05781257e+00, 3.61337960e-01, 3.93848401e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4781494140625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 182.24072266, -2047.61352539, 16.64477539]), + 'frame': 74871, + 'frame_number': 74871, + 'framesequence': 74869, + 'gaze_dir': array([ 0.98058075, -0.1691829 , -0.09918942]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.1691829 , -0.09918942]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.1691829 , -0.09918942]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.54012881219387, + 'timestamp_carla': 280539, + 'timestamp_device': 280132, + 'timestamp_stream': 280.54012881219387, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.27041060e-02, 8.69173836e-03, -1.42950468e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.517562866210938, + 'FR_Wheel_Angle': 41.2133903503418, + 'Location': array([ -6.73517561, -22.94378662, 0.16935524]), + 'Rotation': array([-4.91295494e-02, -4.17091484e+01, 2.03330591e-02]), + 'Velocity': array([-1.0589751 , 0.37434363, 0.00138208]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4771728515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 181.38119507, -2047.92138672, 16.64587402]), + 'frame': 74872, + 'frame_number': 74872, + 'framesequence': 74870, + 'gaze_dir': array([ 0.98058075, -0.1688855 , -0.09969496]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.1688855 , -0.09969496]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.1688855 , -0.09969496]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5437735132873, + 'timestamp_carla': 280543, + 'timestamp_device': 280135, + 'timestamp_stream': 280.5437735132873, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.17126871e-02, 2.20753672e-03, -1.42449837e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.519420623779297, + 'FR_Wheel_Angle': 41.215389251708984, + 'Location': array([ -6.78269291, -22.92280388, 0.16941276]), + 'Rotation': array([-4.88358513e-02, -4.23807564e+01, 2.08325330e-02]), + 'Velocity': array([-1.05059159, 0.38487938, 0.0015123 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.476318359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 180.73739624, -2048.14941406, 16.64660645]), + 'frame': 74873, + 'frame_number': 74873, + 'framesequence': 74871, + 'gaze_dir': array([ 0.98058075, -0.16848558, -0.10036933]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16848558, -0.10036933]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16848558, -0.10036933]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5470209121704, + 'timestamp_carla': 280546, + 'timestamp_device': 280139, + 'timestamp_stream': 280.5470209121704, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.01624146, 0.01607235, -13.96074486]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.515851974487305, + 'FR_Wheel_Angle': 41.21200180053711, + 'Location': array([ -6.83100748, -22.90077782, 0.16947773]), + 'Rotation': array([-4.87743765e-02, -4.30645790e+01, 2.17137318e-02]), + 'Velocity': array([-1.05387187, 0.4005231 , 0.00137223]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4754638671875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 179.87576294, -2048.45141602, 16.64746094]), + 'frame': 74874, + 'frame_number': 74874, + 'framesequence': 74872, + 'gaze_dir': array([ 0.98058075, -0.16818465, -0.10087278]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16818465, -0.10087278]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16818465, -0.10087278]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.55046301335096, + 'timestamp_carla': 280549, + 'timestamp_device': 280142, + 'timestamp_stream': 280.55046301335096, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.16754845e-02, 5.59144048e-03, -1.43635025e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.514347076416016, + 'FR_Wheel_Angle': 41.20956802368164, + 'Location': array([ -6.87890911, -22.87823868, 0.16954009]), + 'Rotation': array([-4.86514345e-02, -4.37468185e+01, 2.25423332e-02]), + 'Velocity': array([-1.05102181, 0.41415542, 0.00132747]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.474609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 179.23034668, -2048.67480469, 16.64831543]), + 'frame': 74875, + 'frame_number': 74875, + 'framesequence': 74873, + 'gaze_dir': array([ 0.98058075, -0.16777693, -0.10154946]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16777693, -0.10154946]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16777693, -0.10154946]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.55404361337423, + 'timestamp_carla': 280553, + 'timestamp_device': 280146, + 'timestamp_stream': 280.55404361337423, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.14645055e-02, 3.05544143e-03, -1.43792038e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.514070510864258, + 'FR_Wheel_Angle': 41.20777130126953, + 'Location': array([ -6.92311001, -22.85681915, 0.16959469]), + 'Rotation': array([-4.84260395e-02, -4.43796158e+01, 2.31203400e-02]), + 'Velocity': array([-1.04814053, 0.42646125, 0.00128793]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4737548828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 178.36003113, -2048.97290039, 16.64916992]), + 'frame': 74876, + 'frame_number': 74876, + 'framesequence': 74874, + 'gaze_dir': array([ 0.98058075, -0.16747248, -0.10205079]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16747248, -0.10205079]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16747248, -0.10205079]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.55726651102304, + 'timestamp_carla': 280556, + 'timestamp_device': 280149, + 'timestamp_stream': 280.55726651102304, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.36377672e-02, 5.00714360e-03, -1.40994492e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.51284408569336, + 'FR_Wheel_Angle': 41.20680236816406, + 'Location': array([ -6.97097111, -22.83295441, 0.16965084]), + 'Rotation': array([-4.80981879e-02, -4.50663834e+01, 2.37475913e-02]), + 'Velocity': array([-1.04598892, 0.43983433, 0.0013362 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4730224609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 177.71310425, -2049.19189453, 16.64990234]), + 'frame': 74877, + 'frame_number': 74877, + 'framesequence': 74875, + 'gaze_dir': array([ 0.98058075, -0.16716652, -0.10255119]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16716652, -0.10255119]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16716652, -0.10255119]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.56040911376476, + 'timestamp_carla': 280559, + 'timestamp_device': 280152, + 'timestamp_stream': 280.56040911376476, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.10913329e-02, -4.48582461e-03, -1.43707685e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.51415252685547, + 'FR_Wheel_Angle': 41.20892333984375, + 'Location': array([ -7.01967144, -22.80793381, 0.16970539]), + 'Rotation': array([-4.75995839e-02, -4.57728767e+01, 2.40800828e-02]), + 'Velocity': array([-1.03684163, 0.45116055, 0.0013682 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4722900390625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 177.06552124, -2049.40893555, 16.65063477]), + 'frame': 74878, + 'frame_number': 74878, + 'framesequence': 74876, + 'gaze_dir': array([ 0.98058075, -0.16675518, -0.10321868]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16675518, -0.10321868]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16675518, -0.10321868]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5641498118639, + 'timestamp_carla': 280563, + 'timestamp_device': 280156, + 'timestamp_stream': 280.5641498118639, + 'transform': [array([ 0.00866089, -0.00365967, 0.1589866 ]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.15013132e-02, -3.20205069e-03, -1.43709373e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.51506996154785, + 'FR_Wheel_Angle': 41.20814895629883, + 'Location': array([ -7.06390476, -22.78452492, 0.16975513]), + 'Rotation': array([-4.70258482e-02, -4.64198074e+01, 2.43576989e-02]), + 'Velocity': array([-1.0302788 , 0.4623518 , 0.00123347]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4713134765625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 176.19885254, -2049.69628906, 16.65148926]), + 'frame': 74879, + 'frame_number': 74879, + 'framesequence': 74877, + 'gaze_dir': array([ 0.98058075, -0.16634122, -0.1038845 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16634122, -0.1038845 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16634122, -0.1038845 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.56853991374373, + 'timestamp_carla': 280567, + 'timestamp_device': 280160, + 'timestamp_stream': 280.56853991374373, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.25788748e-02, -2.46665021e-03, -1.39823046e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.516733169555664, + 'FR_Wheel_Angle': 41.21338653564453, + 'Location': array([ -7.11162472, -22.75857162, 0.169808 ]), + 'Rotation': array([-4.64179628e-02, -4.71197701e+01, 2.46718731e-02]), + 'Velocity': array([-1.02138543, 0.47278813, 0.0013013 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.47021484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 175.33106995, -2049.97973633, 16.65258789]), + 'frame': 74880, + 'frame_number': 74880, + 'framesequence': 74878, + 'gaze_dir': array([ 0.98058075, -0.16592458, -0.10454867]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16592458, -0.10454867]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16592458, -0.10454867]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.57217551395297, + 'timestamp_carla': 280571, + 'timestamp_device': 280164, + 'timestamp_stream': 280.57217551395297, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.92825161e-02, -1.56616850e-03, -1.38649693e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.518997192382812, + 'FR_Wheel_Angle': 41.218467712402344, + 'Location': array([ -7.15458059, -22.73455048, 0.16985554]), + 'Rotation': array([-4.58373986e-02, -4.77545853e+01, 2.49822736e-02]), + 'Velocity': array([-1.0112704 , 0.48163298, 0.00106733]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4691162109375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 174.46212769, -2050.26000977, 16.65344238]), + 'frame': 74881, + 'frame_number': 74881, + 'framesequence': 74879, + 'gaze_dir': array([ 0.98058075, -0.16560796, -0.10504949]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16560796, -0.10504949]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16560796, -0.10504949]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.57568181306124, + 'timestamp_carla': 280574, + 'timestamp_device': 280167, + 'timestamp_stream': 280.57568181306124, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.18832141e-02, -5.19383848e-02, -1.42394333e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.5301513671875, + 'FR_Wheel_Angle': 41.24101257324219, + 'Location': array([ -7.1999402 , -22.70850945, 0.16988434]), + 'Rotation': array([-4.44030575e-02, -4.84346771e+01, 2.46560033e-02]), + 'Velocity': array([-9.74930644e-01, 4.77420807e-01, 4.97231493e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.46826171875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 173.80473328, -2050.46948242, 16.65429688]), + 'frame': 74882, + 'frame_number': 74882, + 'framesequence': 74880, + 'gaze_dir': array([ 0.98058075, -0.16518666, -0.10571072]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16518666, -0.10571072]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16518666, -0.10571072]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5789544135332, + 'timestamp_carla': 280578, + 'timestamp_device': 280171, + 'timestamp_stream': 280.5789544135332, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.85574666e-02, -7.19506107e-03, -1.38276033e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.536062240600586, + 'FR_Wheel_Angle': 41.24600601196289, + 'Location': array([ -7.24384689, -22.68263817, 0.16992977]), + 'Rotation': array([-4.30028699e-02, -4.90987244e+01, 2.44332869e-02]), + 'Velocity': array([-0.96205413, 0.48624954, 0.00122448]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.46728515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 172.93386841, -2050.74365234, 16.65527344]), + 'frame': 74883, + 'frame_number': 74883, + 'framesequence': 74881, + 'gaze_dir': array([ 0.98058075, -0.16486977, -0.10620428]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16486977, -0.10620428]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16486977, -0.10620428]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5827053114772, + 'timestamp_carla': 280581, + 'timestamp_device': 280174, + 'timestamp_stream': 280.5827053114772, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02331322, 0.01739403, -13.43932152]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.535980224609375, + 'FR_Wheel_Angle': 41.245540618896484, + 'Location': array([ -7.2819376 , -22.65961647, 0.16997382]), + 'Rotation': array([-4.25110944e-02, -4.96737442e+01, 2.52996124e-02]), + 'Velocity': array([-0.9581545 , 0.49654543, 0.00128048]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4666748046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 172.28166199, -2050.94628906, 16.65588379]), + 'frame': 74884, + 'frame_number': 74884, + 'framesequence': 74882, + 'gaze_dir': array([ 0.98058075, -0.16444387, -0.10686255]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16444387, -0.10686255]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16444387, -0.10686255]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.5864248126745, + 'timestamp_carla': 280585, + 'timestamp_device': 280178, + 'timestamp_stream': 280.5864248126745, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02293921, 0.02405378, -13.40880489]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.535167694091797, + 'FR_Wheel_Angle': 41.2517204284668, + 'Location': array([ -7.32161808, -22.63505745, 0.1700214 ]), + 'Rotation': array([-4.22993600e-02, -5.02766571e+01, 2.65426077e-02]), + 'Velocity': array([-0.95434415, 0.50773126, 0.00114389]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4656982421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 171.40890503, -2051.21435547, 16.65686035]), + 'frame': 74885, + 'frame_number': 74885, + 'framesequence': 74883, + 'gaze_dir': array([ 0.98058075, -0.16401532, -0.10751911]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16401532, -0.10751911]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16401532, -0.10751911]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.59025601297617, + 'timestamp_carla': 280589, + 'timestamp_device': 280182, + 'timestamp_stream': 280.59025601297617, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02726881, 0.01469329, -13.2648859 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.543886184692383, + 'FR_Wheel_Angle': 41.257225036621094, + 'Location': array([ -7.36752987, -22.60591698, 0.17006104]), + 'Rotation': array([-4.13499624e-02, -5.09729462e+01, 2.68658418e-02]), + 'Velocity': array([-0.93122756, 0.51001996, 0.0012025 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4647216796875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 170.5350647 , -2051.47900391, 16.65771484]), + 'frame': 74886, + 'frame_number': 74886, + 'framesequence': 74884, + 'gaze_dir': array([ 0.98058075, -0.16358417, -0.10817394]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16358417, -0.10817394]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16358417, -0.10817394]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.59413331374526, + 'timestamp_carla': 280593, + 'timestamp_device': 280186, + 'timestamp_stream': 280.59413331374526, + 'transform': [array([ 0.00866074, -0.00365967, 0.15898438]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02865075, 0.01746199, -13.2486372 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.545833587646484, + 'FR_Wheel_Angle': 41.26169204711914, + 'Location': array([ -7.405725 , -22.58108521, 0.17010535]), + 'Rotation': array([-4.08650190e-02, -5.15541916e+01, 2.78337747e-02]), + 'Velocity': array([-0.92104101, 0.51580656, 0.00106717]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.463623046875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 169.66020203, -2051.73999023, 16.65881348]), + 'frame': 74887, + 'frame_number': 74887, + 'framesequence': 74885, + 'gaze_dir': array([ 0.98058075, -0.16315041, -0.10882706]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16315041, -0.10882706]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16315041, -0.10882706]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.59849351271987, + 'timestamp_carla': 280597, + 'timestamp_device': 280190, + 'timestamp_stream': 280.59849351271987, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.66959669e-02, 5.40702743e-03, -1.30253057e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.548080444335938, + 'FR_Wheel_Angle': 41.267337799072266, + 'Location': array([ -7.44625187, -22.55414963, 0.17014953]), + 'Rotation': array([-4.04073969e-02, -5.21776237e+01, 2.88678054e-02]), + 'Velocity': array([-0.90925747, 0.52419442, 0.00099271]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.462646484375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 168.7842865 , -2051.99755859, 16.65979004]), + 'frame': 74888, + 'frame_number': 74888, + 'framesequence': 74886, + 'gaze_dir': array([ 0.98058075, -0.16271403, -0.10947844]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16271403, -0.10947844]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16271403, -0.10947844]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6026216112077, + 'timestamp_carla': 280601, + 'timestamp_device': 280194, + 'timestamp_stream': 280.6026216112077, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02526977, 0.01534436, -13.11382866]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.55113410949707, + 'FR_Wheel_Angle': 41.27028274536133, + 'Location': array([ -7.48615837, -22.52700424, 0.17019096]), + 'Rotation': array([-3.98883037e-02, -5.27967300e+01, 2.98057366e-02]), + 'Velocity': array([-0.89898825, 0.5289064 , 0.00096012]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.461669921875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 167.90733337, -2052.25146484, 16.66064453]), + 'frame': 74889, + 'frame_number': 74889, + 'framesequence': 74887, + 'gaze_dir': array([ 0.98058075, -0.16227169, -0.11013301]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16227169, -0.11013301]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16227169, -0.11013301]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.60647851228714, + 'timestamp_carla': 280605, + 'timestamp_device': 280198, + 'timestamp_stream': 280.60647851228714, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.55323239e-02, 1.30680308e-03, -1.29050560e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.557950973510742, + 'FR_Wheel_Angle': 41.281742095947266, + 'Location': array([ -7.52533674, -22.49974632, 0.17021839]), + 'Rotation': array([-3.91233228e-02, -5.34079018e+01, 3.03606130e-02]), + 'Velocity': array([-0.87986982, 0.52952462, 0.00112884]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.460693359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 167.02268982, -2052.50390625, 16.66149902]), + 'frame': 74890, + 'frame_number': 74890, + 'framesequence': 74888, + 'gaze_dir': array([ 0.98058075, -0.1619416 , -0.11061783]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.1619416 , -0.11061783]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.1619416 , -0.11061783]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6098445132375, + 'timestamp_carla': 280609, + 'timestamp_device': 280201, + 'timestamp_stream': 280.6098445132375, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-2.52122376e-02, -4.65097930e-03, -1.27539339e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.563528060913086, + 'FR_Wheel_Angle': 41.290409088134766, + 'Location': array([ -7.56237841, -22.47340965, 0.17025711]), + 'Rotation': array([-3.83583419e-02, -5.39910240e+01, 3.09148282e-02]), + 'Velocity': array([-8.63297105e-01, 5.31178713e-01, 4.58860392e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4599609375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 166.36528015, -2052.68896484, 16.66223145]), + 'frame': 74891, + 'frame_number': 74891, + 'framesequence': 74889, + 'gaze_dir': array([ 0.98058075, -0.16149808, -0.11126436]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16149808, -0.11126436]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16149808, -0.11126436]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6136812120676, + 'timestamp_carla': 280612, + 'timestamp_device': 280205, + 'timestamp_stream': 280.6136812120676, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.51792290e-02, -1.41959626e-03, -1.25502586e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.564760208129883, + 'FR_Wheel_Angle': 41.293888092041016, + 'Location': array([ -7.59985352, -22.44616699, 0.17030002]), + 'Rotation': array([-3.78119238e-02, -5.45845528e+01, 3.16293314e-02]), + 'Velocity': array([-8.52905095e-01, 5.40161610e-01, 8.49018106e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.458984375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 165.48562622, -2052.93334961, 16.66333008]), + 'frame': 74892, + 'frame_number': 74892, + 'framesequence': 74890, + 'gaze_dir': array([ 0.98058075, -0.16105196, -0.11190911]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16105196, -0.11190911]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16105196, -0.11190911]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6174569129944, + 'timestamp_carla': 280616, + 'timestamp_device': 280209, + 'timestamp_stream': 280.6174569129944, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.34022990e-02, -5.50966430e-03, -1.22943163e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.57062339782715, + 'FR_Wheel_Angle': 41.30390548706055, + 'Location': array([ -7.63594627, -22.41938972, 0.17033039]), + 'Rotation': array([-3.69581506e-02, -5.51598701e+01, 3.20750363e-02]), + 'Velocity': array([-0.8353371 , 0.54121673, 0.00115608]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4578857421875, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 164.60494995, -2053.17407227, 16.66442871]), + 'frame': 74893, + 'frame_number': 74893, + 'framesequence': 74891, + 'gaze_dir': array([ 0.98058075, -0.16060328, -0.11255206]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16060328, -0.11255206]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16060328, -0.11255206]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6210455112159, + 'timestamp_carla': 280620, + 'timestamp_device': 280213, + 'timestamp_stream': 280.6210455112159, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02400454, 0.01587348, -12.42007637]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.574325561523438, + 'FR_Wheel_Angle': 41.31000518798828, + 'Location': array([ -7.67257166, -22.39161873, 0.17037208]), + 'Rotation': array([-3.63502651e-02, -5.57486687e+01, 3.28102410e-02]), + 'Velocity': array([-0.82410842, 0.54362988, 0.00102509]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.45703125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 163.72337341, -2053.41137695, 16.66516113]), + 'frame': 74894, + 'frame_number': 74894, + 'framesequence': 74892, + 'gaze_dir': array([ 0.98058075, -0.16026595, -0.11303188]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.16026595, -0.11303188]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.16026595, -0.11303188]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6244013123214, + 'timestamp_carla': 280623, + 'timestamp_device': 280216, + 'timestamp_stream': 280.6244013123214, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.01754947, -0.02948354, -11.87696457]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.588560104370117, + 'FR_Wheel_Angle': 41.33383560180664, + 'Location': array([ -7.70712757, -22.36490631, 0.17039585]), + 'Rotation': array([-3.52437757e-02, -5.63092690e+01, 3.28397453e-02]), + 'Velocity': array([-0.79032719, 0.53249711, 0.00099184]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.456298828125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 163.06323242, -2053.58666992, 16.66589355]), + 'frame': 74895, + 'frame_number': 74895, + 'framesequence': 74893, + 'gaze_dir': array([ 0.98058075, -0.15992372, -0.11351557]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.15992372, -0.11351557]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.15992372, -0.11351557]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6277787126601, + 'timestamp_carla': 280627, + 'timestamp_device': 280219, + 'timestamp_stream': 280.6277787126601, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02304363, 0.01417398, -11.92578793]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.590909957885742, + 'FR_Wheel_Angle': 41.3369026184082, + 'Location': array([ -7.74205732, -22.33733749, 0.17043625]), + 'Rotation': array([-3.43899988e-02, -5.68804703e+01, 3.33315693e-02]), + 'Velocity': array([-0.7806018 , 0.53696293, 0.00104432]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4554443359375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 162.39582825, -2053.76171875, 16.66674805]), + 'frame': 74896, + 'frame_number': 74896, + 'framesequence': 74894, + 'gaze_dir': array([ 0.98058075, -0.15946864, -0.114154 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.15946864, -0.114154 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.15946864, -0.114154 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.63096741214395, + 'timestamp_carla': 280630, + 'timestamp_device': 280223, + 'timestamp_stream': 280.63096741214395, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02268572, 0.02005389, -11.76419258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.596189498901367, + 'FR_Wheel_Angle': 41.34641647338867, + 'Location': array([ -7.77496338, -22.31083679, 0.17046887]), + 'Rotation': array([-3.37479636e-02, -5.74219437e+01, 3.40107530e-02]), + 'Velocity': array([-0.76501966, 0.5370487 , 0.00088009]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4544677734375, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 161.51191711, -2053.99023438, 16.66772461]), + 'frame': 74897, + 'frame_number': 74897, + 'framesequence': 74895, + 'gaze_dir': array([ 0.98058075, -0.15912652, -0.11463042]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.15912652, -0.11463042]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.15912652, -0.11463042]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6343337111175, + 'timestamp_carla': 280633, + 'timestamp_device': 280226, + 'timestamp_stream': 280.6343337111175, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([ -0.02249819, 0.01690778, -11.59315872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60194969177246, + 'FR_Wheel_Angle': 41.35614776611328, + 'Location': array([ -7.8068552 , -22.2846508 , 0.17050201]), + 'Rotation': array([-3.32015492e-02, -5.79509544e+01, 3.48008834e-02]), + 'Velocity': array([-0.74890751, 0.53590876, 0.00101774]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.4537353515625, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 160.85006714, -2054.15869141, 16.66833496]), + 'frame': 74898, + 'frame_number': 74898, + 'framesequence': 74896, + 'gaze_dir': array([ 0.98058075, -0.15878297, -0.11510582]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.15878297, -0.11510582]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.15878297, -0.11510582]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6379305124283, + 'timestamp_carla': 280637, + 'timestamp_device': 280229, + 'timestamp_stream': 280.6379305124283, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- +{'AngularVelocity': array([-1.01085231e-02, 5.77900652e-03, -1.13516874e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60550308227539, + 'FR_Wheel_Angle': 41.36273193359375, + 'Location': array([ -7.83843613, -22.25820732, 0.17052913]), + 'Rotation': array([-3.27780768e-02, -5.84787369e+01, 3.56231183e-02]), + 'Velocity': array([-0.7344479 , 0.53932482, 0.00111411]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.453125, + 'focus_actor_name': 'Road_Grass_Town05_125', + 'focus_actor_pt': array([ 160.18771362, -2054.32543945, 16.66906738]), + 'frame': 74899, + 'frame_number': 74899, + 'framesequence': 74897, + 'gaze_dir': array([ 0.98058075, -0.15832153, -0.11573967]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058075, -0.15832153, -0.11573967]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058075, -0.15832153, -0.11573967]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 280.6412376128137, + 'timestamp_carla': 280640, + 'timestamp_device': 280233, + 'timestamp_stream': 280.6412376128137, + 'transform': [array([ 0.00866058, -0.00365967, 0.15898247]), + array([-0.0577151 , -0.02408502, 0.01029164])]} +---------------------- \ No newline at end of file diff --git a/PythonAPI/data/vehicle_logs/backward_0.txt b/PythonAPI/data/vehicle_logs/backward_0.txt new file mode 100644 index 0000000..33a4efe --- /dev/null +++ b/PythonAPI/data/vehicle_logs/backward_0.txt @@ -0,0 +1,32712 @@ +{'AngularVelocity': array([-3.25185692e-06, -1.47676781e-06, 1.45206347e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72255514e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-5.19121357e-10, 3.37193895e-09, -1.50938024e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63578033]), + 'frame': 21506, + 'frame_number': 21506, + 'framesequence': 86713, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.4035000503063, + 'timestamp_carla': 734402, + 'timestamp_device': 1605002, + 'timestamp_stream': 734.4035000503063, + 'transform': [array([-55.32588196, 81.88571167, -0.15709276]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.61870586e-05, -6.06113281e-06, -3.50142071e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71923637e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 5.22841193e-09, -1.76567667e-08, -1.39236442e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63669586]), + 'frame': 21507, + 'frame_number': 21507, + 'framesequence': 86718, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.4385433495045, + 'timestamp_carla': 734437, + 'timestamp_device': 1605044, + 'timestamp_stream': 734.4385433495045, + 'transform': [array([-55.32588196, 81.88571167, -0.15710978]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.42959099e-05, -4.83418262e-06, -2.87580537e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71771040e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 6.00546368e-09, -1.64434617e-08, 2.22415925e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63608551]), + 'frame': 21508, + 'frame_number': 21508, + 'framesequence': 86721, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.47049145028, + 'timestamp_carla': 734469, + 'timestamp_device': 1605069, + 'timestamp_stream': 734.47049145028, + 'transform': [array([-55.32588196, 81.88571167, -0.15709609]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.85705703e-05, 4.22580524e-06, 2.65274580e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.69432641e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 2.33956132e-10, 7.87173793e-09, -6.13145821e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96533203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63438416]), + 'frame': 21509, + 'frame_number': 21509, + 'framesequence': 86725, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.5035890489817, + 'timestamp_carla': 734502, + 'timestamp_device': 1605102, + 'timestamp_stream': 734.5035890489817, + 'transform': [array([-55.32588196, 81.88571167, -0.15709609]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.93969661e-05, 3.01147247e-06, 2.72414380e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.73335068e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 3.60581964e-09, -1.94355732e-08, 2.78615946e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63574982]), + 'frame': 21510, + 'frame_number': 21510, + 'framesequence': 86729, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.5362092517316, + 'timestamp_carla': 734535, + 'timestamp_device': 1605135, + 'timestamp_stream': 734.5362092517316, + 'transform': [array([-55.32588196, 81.88571167, -0.15709284]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-2.17836623e-05, 5.31353771e-06, -5.67127278e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70042983e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([1.26107125e-08, 3.41446800e-08, 8.71138531e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63574982]), + 'frame': 21511, + 'frame_number': 21511, + 'framesequence': 86733, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.5682775489986, + 'timestamp_carla': 734567, + 'timestamp_device': 1605168, + 'timestamp_stream': 734.5682775489986, + 'transform': [array([-55.32588196, 81.88571167, -0.15708746]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-8.49454136e-06, -1.55280668e-06, 1.94642369e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72179216e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-7.17686977e-09, -5.78994097e-09, 2.32429506e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63607788]), + 'frame': 21512, + 'frame_number': 21512, + 'framesequence': 86737, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.6031882502139, + 'timestamp_carla': 734602, + 'timestamp_device': 1605202, + 'timestamp_stream': 734.6031882502139, + 'transform': [array([-55.32588196, 81.88571167, -0.15710635]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-3.49852530e-06, -3.38572204e-06, -2.01313921e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72404281e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 3.94640720e-09, 1.64957097e-08, -1.15137096e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63661194]), + 'frame': 21513, + 'frame_number': 21513, + 'framesequence': 86741, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.6355625502765, + 'timestamp_carla': 734634, + 'timestamp_device': 1605235, + 'timestamp_stream': 734.6355625502765, + 'transform': [array([-55.32588196, 81.88571167, -0.15709761]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-5.53846166e-06, -2.71528825e-06, 1.73377934e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.68208114e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-1.65396719e-09, 4.47278792e-09, -5.51261881e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63472748]), + 'frame': 21514, + 'frame_number': 21514, + 'framesequence': 86745, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.6684734523296, + 'timestamp_carla': 734667, + 'timestamp_device': 1605268, + 'timestamp_stream': 734.6684734523296, + 'transform': [array([-55.32588196, 81.88571167, -0.15709631]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.85643039e-05, 4.86351246e-06, -6.78055967e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.64492603e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 1.12049241e-08, 2.59810164e-08, -1.04408260e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63559723]), + 'frame': 21515, + 'frame_number': 21515, + 'framesequence': 86749, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.7035731524229, + 'timestamp_carla': 734702, + 'timestamp_device': 1605302, + 'timestamp_stream': 734.7035731524229, + 'transform': [array([-55.32588196, 81.88571167, -0.15711272]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.60954642e-05, 5.85044017e-06, -5.53653479e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72514911e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([1.41292098e-08, 3.24290390e-08, 3.26909998e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63572693]), + 'frame': 21516, + 'frame_number': 21516, + 'framesequence': 86753, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.7345766499639, + 'timestamp_carla': 734733, + 'timestamp_device': 1605335, + 'timestamp_stream': 734.7345766499639, + 'transform': [array([-55.32588196, 81.88571167, -0.15709223]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-3.93421578e-06, -2.26446105e-06, -2.42673615e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.75074569e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-5.26787636e-09, -4.27399538e-09, -1.97687143e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965087890625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63408661]), + 'frame': 21517, + 'frame_number': 21517, + 'framesequence': 86757, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.7709037512541, + 'timestamp_carla': 734769, + 'timestamp_device': 1605368, + 'timestamp_stream': 734.7709037512541, + 'transform': [array([-55.32588196, 81.88571167, -0.157121 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.67759008e-05, 4.65978792e-06, -2.33413067e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.73510553e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([1.10889387e-08, 2.85065358e-08, 1.72567365e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63613892]), + 'frame': 21518, + 'frame_number': 21518, + 'framesequence': 86761, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.801975350827, + 'timestamp_carla': 734800, + 'timestamp_device': 1605402, + 'timestamp_stream': 734.801975350827, + 'transform': [array([-55.32588196, 81.88571167, -0.15709704]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 2.49413552e-05, -4.00996323e-05, 8.98996255e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72465318e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.35279005e-08, -2.59870081e-08, 2.47731194e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.964111328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63326263]), + 'frame': 21519, + 'frame_number': 21519, + 'framesequence': 86765, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.8348070494831, + 'timestamp_carla': 734833, + 'timestamp_device': 1605435, + 'timestamp_stream': 734.8348070494831, + 'transform': [array([-55.32588196, 81.88571167, -0.15709448]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.84587277e-05, 1.38019573e-06, 5.91859783e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71332352e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 3.37778944e-10, -2.30675319e-08, -2.07710254e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63565826]), + 'frame': 21520, + 'frame_number': 21520, + 'framesequence': 86769, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.8675932511687, + 'timestamp_carla': 734866, + 'timestamp_device': 1605468, + 'timestamp_stream': 734.8675932511687, + 'transform': [array([-55.32588196, 81.88571167, -0.15709288]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.42131350e-05, -5.61709749e-06, 3.86801952e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71736709e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 3.49651819e-09, -1.67659824e-08, -2.06480021e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63591003]), + 'frame': 21521, + 'frame_number': 21521, + 'framesequence': 86772, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.8988477513194, + 'timestamp_carla': 734897, + 'timestamp_device': 1605493, + 'timestamp_stream': 734.8988477513194, + 'transform': [array([-55.32588196, 81.88571167, -0.15708198]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 1.10166666e-05, -3.19067331e-05, 8.26393121e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71851157e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-1.36544411e-08, 1.29071713e-08, -1.63249962e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63607025]), + 'frame': 21522, + 'frame_number': 21522, + 'framesequence': 86777, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.9371328502893, + 'timestamp_carla': 734936, + 'timestamp_device': 1605535, + 'timestamp_stream': 734.9371328502893, + 'transform': [array([-55.32588196, 81.88571167, -0.15713519]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 1.13825026e-05, -3.31199735e-05, 6.20200913e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72705646e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.00060066e-08, -1.92614618e-08, 4.60410112e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968505859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63716125]), + 'frame': 21523, + 'frame_number': 21523, + 'framesequence': 86781, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 734.9656599499285, + 'timestamp_carla': 734964, + 'timestamp_device': 1605568, + 'timestamp_stream': 734.9656599499285, + 'transform': [array([-55.32588196, 81.88571167, -0.15715507]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.54422923e-06, -3.27845100e-06, -3.34187855e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72015186e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([1.09800631e-08, 2.48946730e-08, 1.06496809e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.963134765625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51367188, 117.63184357]), + 'frame': 21524, + 'frame_number': 21524, + 'framesequence': 86785, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.0015856511891, + 'timestamp_carla': 735000, + 'timestamp_device': 1605602, + 'timestamp_stream': 735.0015856511891, + 'transform': [array([-55.32588196, 81.88571167, -0.15714881]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-6.97008488e-07, -3.25185192e-06, -4.37652270e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.65831565e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 8.36140135e-09, 2.30815562e-08, -5.86776703e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51269531, 117.62985229]), + 'frame': 21525, + 'frame_number': 21525, + 'framesequence': 86789, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.0335419513285, + 'timestamp_carla': 735032, + 'timestamp_device': 1605635, + 'timestamp_stream': 735.0335419513285, + 'transform': [array([-55.32588196, 81.88571167, -0.15711489]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.52321354e-05, 4.46093600e-06, -8.16842505e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.74376485e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([1.07640448e-08, 2.37472815e-08, 8.20813177e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.961669921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63047791]), + 'frame': 21526, + 'frame_number': 21526, + 'framesequence': 86793, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.068460650742, + 'timestamp_carla': 735067, + 'timestamp_device': 1605668, + 'timestamp_stream': 735.068460650742, + 'transform': [array([-55.32588196, 81.88571167, -0.15711489]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.06387446e-05, 1.94009112e-06, -3.76952747e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71977037e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 5.05706921e-10, -2.50902463e-08, -3.96099087e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51464844, 117.63387299]), + 'frame': 21527, + 'frame_number': 21527, + 'framesequence': 86797, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.1004739515483, + 'timestamp_carla': 735099, + 'timestamp_device': 1605702, + 'timestamp_stream': 735.1004739515483, + 'transform': [array([-55.32588196, 81.88571167, -0.15709421]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-2.35306720e-06, -4.14948818e-06, 1.00799769e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.73834793e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-2.02063877e-09, 3.45136630e-09, 3.27420217e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51464844, 117.63387299]), + 'frame': 21528, + 'frame_number': 21528, + 'framesequence': 86801, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.13530664891, + 'timestamp_carla': 735134, + 'timestamp_device': 1605735, + 'timestamp_stream': 735.13530664891, + 'transform': [array([-55.32588196, 81.88571167, -0.15710337]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.50409251e-05, 2.01205353e-06, 1.92122429e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71614648e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-1.28372390e-09, 5.40274847e-09, -4.61120595e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63594055]), + 'frame': 21529, + 'frame_number': 21529, + 'framesequence': 86805, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.1681229509413, + 'timestamp_carla': 735167, + 'timestamp_device': 1605768, + 'timestamp_stream': 735.1681229509413, + 'transform': [array([-55.32588196, 81.88571167, -0.15709352]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.35892460e-05, 3.96388096e-08, -1.30352049e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70809741e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 2.06920459e-09, 1.35717340e-08, -9.71221889e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63502502]), + 'frame': 21530, + 'frame_number': 21530, + 'framesequence': 86809, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.2012277506292, + 'timestamp_carla': 735200, + 'timestamp_device': 1605802, + 'timestamp_stream': 735.2012277506292, + 'transform': [array([-55.32588196, 81.88571167, -0.1570904 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-8.59517854e-07, -6.97996893e-06, 1.18817522e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70931814e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-2.85907764e-09, 4.62459626e-09, -1.03902814e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63600922]), + 'frame': 21531, + 'frame_number': 21531, + 'framesequence': 86813, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.2368515506387, + 'timestamp_carla': 735235, + 'timestamp_device': 1605835, + 'timestamp_stream': 735.2368515506387, + 'transform': [array([-55.32588196, 81.88571167, -0.15710932]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.44278921e-05, -6.83235157e-06, 8.13280332e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71648979e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-5.44405721e-09, -3.42431896e-08, 2.50425335e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63632202]), + 'frame': 21532, + 'frame_number': 21532, + 'framesequence': 86817, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.2679512500763, + 'timestamp_carla': 735267, + 'timestamp_device': 1605868, + 'timestamp_stream': 735.2679512500763, + 'transform': [array([-55.32588196, 81.88571167, -0.15708697]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.77929230e-05, 1.70492899e-06, 2.30354025e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70935632e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.81524767e-09, -3.10111936e-08, 3.82270809e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965576171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63442993]), + 'frame': 21533, + 'frame_number': 21533, + 'framesequence': 86821, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.3015243522823, + 'timestamp_carla': 735300, + 'timestamp_device': 1605902, + 'timestamp_stream': 735.3015243522823, + 'transform': [array([-55.32588196, 81.88571167, -0.15709127]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-7.06281844e-06, 8.67226149e-08, -8.32929892e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72564504e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-2.37795561e-09, 2.34794573e-10, 4.29525360e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63666534]), + 'frame': 21534, + 'frame_number': 21534, + 'framesequence': 86825, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.3344281502068, + 'timestamp_carla': 735333, + 'timestamp_device': 1605935, + 'timestamp_stream': 735.3344281502068, + 'transform': [array([-55.32588196, 81.88571167, -0.15708941]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 8.54228620e-06, -3.12798438e-05, 1.40541019e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71820633e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-4.32544880e-08, -4.69957229e-08, 2.37846361e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': True, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63623047]), + 'frame': 21535, + 'frame_number': 21535, + 'framesequence': 86829, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.3679747506976, + 'timestamp_carla': 735367, + 'timestamp_device': 1605968, + 'timestamp_stream': 735.3679747506976, + 'transform': [array([-55.32588196, 81.88571167, -0.15709357]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.38791675e-05, 3.16248361e-06, -6.06886896e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.73018454e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([1.28619781e-08, 3.20058149e-08, 2.39815708e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967529296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6364212 ]), + 'frame': 21536, + 'frame_number': 21536, + 'framesequence': 86833, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.4015753492713, + 'timestamp_carla': 735400, + 'timestamp_device': 1606002, + 'timestamp_stream': 735.4015753492713, + 'transform': [array([-55.32588196, 81.88571167, -0.15709673]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-9.35896651e-07, -5.15671536e-06, -8.33804303e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72404281e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.91997013e-09, 7.20234497e-11, 4.27055347e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63600159]), + 'frame': 21537, + 'frame_number': 21537, + 'framesequence': 86838, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.4479145519435, + 'timestamp_carla': 735447, + 'timestamp_device': 1606043, + 'timestamp_stream': 735.4479145519435, + 'transform': [array([-55.32588196, 81.88571167, -0.15713324]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.41204976e-06, -5.38297036e-06, -5.98855687e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70428271e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.93355615e-09, 6.73763878e-10, -4.53186018e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63568878]), + 'frame': 21538, + 'frame_number': 21538, + 'framesequence': 86842, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.4771940521896, + 'timestamp_carla': 735476, + 'timestamp_device': 1606077, + 'timestamp_stream': 735.4771940521896, + 'transform': [array([-55.32588196, 81.88571167, -0.15715979]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.50128490e-05, 1.36865049e-06, 9.40739486e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71473494e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-2.39920683e-09, 4.05346601e-09, -5.57899466e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96337890625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51367188, 117.6320343 ]), + 'frame': 21539, + 'frame_number': 21539, + 'framesequence': 86846, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.512804351747, + 'timestamp_carla': 735511, + 'timestamp_device': 1606110, + 'timestamp_stream': 735.512804351747, + 'transform': [array([-55.32588196, 81.88571167, -0.1571461 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-7.13754559e-07, -4.50996822e-06, 6.01808603e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72953599e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.01014058e-09, 8.12074463e-10, 1.69939987e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96044921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62937927]), + 'frame': 21540, + 'frame_number': 21540, + 'framesequence': 86850, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.5420286506414, + 'timestamp_carla': 735541, + 'timestamp_device': 1606143, + 'timestamp_stream': 735.5420286506414, + 'transform': [array([-55.32588196, 81.88571167, -0.15716323]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.57695486e-05, 3.24155008e-06, 1.16315304e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.65499689e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-1.70031846e-08, -2.40703866e-08, -9.11617244e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9619140625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63075256]), + 'frame': 21541, + 'frame_number': 21541, + 'framesequence': 86854, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.5806469507515, + 'timestamp_carla': 735579, + 'timestamp_device': 1606177, + 'timestamp_stream': 735.5806469507515, + 'transform': [array([-55.32588196, 81.88571167, -0.1571704 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.62044809e-05, -5.50645791e-06, 1.39100775e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71389570e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.63901043e-09, -3.38996848e-08, 1.87263489e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.960205078125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62903595]), + 'frame': 21542, + 'frame_number': 21542, + 'framesequence': 86858, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.6099220514297, + 'timestamp_carla': 735609, + 'timestamp_device': 1606210, + 'timestamp_stream': 735.6099220514297, + 'transform': [array([-55.32588196, 81.88571167, -0.1571749 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([3.33046773e-05, 1.60446041e-06, 1.22815280e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72350882e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 2.57455834e-09, -2.23571490e-08, -2.06871031e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.959228515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14550781, 10474.51171875, 117.62831879]), + 'frame': 21543, + 'frame_number': 21543, + 'framesequence': 86862, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.6470915488899, + 'timestamp_carla': 735646, + 'timestamp_device': 1606243, + 'timestamp_stream': 735.6470915488899, + 'transform': [array([-55.32588196, 81.88571167, -0.15715811]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.81208009e-06, -5.28094279e-06, -4.85968876e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71675673e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-3.90718169e-09, 8.80890527e-10, 8.76998893e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.958740234375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14550781, 10474.51171875, 117.62786865]), + 'frame': 21544, + 'frame_number': 21544, + 'framesequence': 86866, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.6781323514879, + 'timestamp_carla': 735677, + 'timestamp_device': 1606277, + 'timestamp_stream': 735.6781323514879, + 'transform': [array([-55.32588196, 81.88571167, -0.15710467]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-6.21887693e-06, -3.72670661e-06, 2.34753594e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.68936723e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-7.68669128e-09, -5.44192291e-09, -4.22554003e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96044921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62954712]), + 'frame': 21545, + 'frame_number': 21545, + 'framesequence': 86870, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.7117671519518, + 'timestamp_carla': 735710, + 'timestamp_device': 1606310, + 'timestamp_stream': 735.7117671519518, + 'transform': [array([-55.32588196, 81.88571167, -0.15709017]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.76993963e-05, 6.06157573e-06, 6.65182576e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.67075149e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-4.32516745e-10, 3.38091288e-09, -7.74011598e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63489532]), + 'frame': 21546, + 'frame_number': 21546, + 'framesequence': 86874, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.743030551821, + 'timestamp_carla': 735742, + 'timestamp_device': 1606343, + 'timestamp_stream': 735.743030551821, + 'transform': [array([-55.32588196, 81.88571167, -0.15706736]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.37505623e-05, -2.87313969e-06, 1.51671795e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72587391e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-2.19820322e-08, -6.91606843e-08, -2.92301174e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63634491]), + 'frame': 21547, + 'frame_number': 21547, + 'framesequence': 86878, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.7754978500307, + 'timestamp_carla': 735774, + 'timestamp_device': 1606377, + 'timestamp_stream': 735.7754978500307, + 'transform': [array([-55.32588196, 81.88571167, -0.15706378]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-2.18123041e-05, 6.48094010e-06, -9.00263919e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.73117639e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 2.98474467e-09, 1.22304282e-08, -1.36156086e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.97021484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.6386261 ]), + 'frame': 21548, + 'frame_number': 21548, + 'framesequence': 86882, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.8070840500295, + 'timestamp_carla': 735806, + 'timestamp_device': 1606410, + 'timestamp_stream': 735.8070840500295, + 'transform': [array([-55.32588196, 81.88571167, -0.15705782]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.97134250e-05, 5.96423570e-06, 2.44391374e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71648979e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-5.66262415e-09, -5.22408383e-09, -1.25131599e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.97021484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63898468]), + 'frame': 21549, + 'frame_number': 21549, + 'framesequence': 86885, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.8398286513984, + 'timestamp_carla': 735839, + 'timestamp_device': 1606435, + 'timestamp_stream': 735.8398286513984, + 'transform': [array([-55.32588196, 81.88571167, -0.15706457]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([3.44157306e-05, 2.72807233e-06, 1.63039915e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70966145e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([-2.39199127e-09, -3.44190703e-08, -2.30569829e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.970947265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15625 , 10474.51757812, 117.63957977]), + 'frame': 21550, + 'frame_number': 21550, + 'framesequence': 86889, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.872520249337, + 'timestamp_carla': 735871, + 'timestamp_device': 1606468, + 'timestamp_stream': 735.872520249337, + 'transform': [array([-55.32588196, 81.88571167, -0.15707 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 5.16214895e-05, -5.39378061e-06, -3.40511508e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038430397398769855, + 'FR_Wheel_Angle': 0.003843336831778288, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72862050e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 1.86929583e-09, -2.54494257e-08, 3.01299093e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.97021484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63890076]), + 'frame': 21551, + 'frame_number': 21551, + 'framesequence': 86893, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.903654050082, + 'timestamp_carla': 735902, + 'timestamp_device': 1606502, + 'timestamp_stream': 735.903654050082, + 'transform': [array([-55.32588196, 81.88571167, -0.15706405]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-5.84513065e-04, -1.17938814e-03, -9.96048548e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003843572922050953, + 'FR_Wheel_Angle': 0.003843809710815549, + 'Location': array([-6.63888092e+01, 8.92711105e+01, 1.73098559e-03]), + 'Rotation': array([6.75505679e-03, 1.52621414e+02, 4.74066846e-03]), + 'Velocity': array([ 3.01616956e-02, -1.55881345e-02, -1.96456913e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9697265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63835907]), + 'frame': 21552, + 'frame_number': 21552, + 'framesequence': 86897, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.9382076524198, + 'timestamp_carla': 735937, + 'timestamp_device': 1606535, + 'timestamp_stream': 735.9382076524198, + 'transform': [array([-55.32588196, 81.88571167, -0.15708739]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00126507, -0.00242813, -0.0001301 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038439473137259483, + 'FR_Wheel_Angle': 0.0038441363722085953, + 'Location': array([-6.63856888e+01, 8.92695007e+01, 1.72640802e-03]), + 'Rotation': array([7.67713226e-03, 1.52621414e+02, 4.73995088e-03]), + 'Velocity': array([ 0.02486334, -0.01284948, 0.00012214]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.97021484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63895416]), + 'frame': 21553, + 'frame_number': 21553, + 'framesequence': 86901, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 735.9699046500027, + 'timestamp_carla': 735969, + 'timestamp_device': 1606568, + 'timestamp_stream': 735.9699046500027, + 'transform': [array([-55.32588196, 81.88571167, -0.15708022]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-2.98046018e-03, -5.90703450e-03, -7.85557859e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038441880606114864, + 'FR_Wheel_Angle': 0.0038443657103925943, + 'Location': array([-6.63831711e+01, 8.92681885e+01, 1.71256065e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.02129441, -0.01100471, -0.00020757]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63661957]), + 'frame': 21554, + 'frame_number': 21554, + 'framesequence': 86905, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.0045290514827, + 'timestamp_carla': 736003, + 'timestamp_device': 1606602, + 'timestamp_stream': 736.0045290514827, + 'transform': [array([-55.32588196, 81.88571167, -0.15709856]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-3.40112601e-03, -6.59716269e-03, -8.40261491e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003844387363642454, + 'FR_Wheel_Angle': 0.003844568273052573, + 'Location': array([-6.63810806e+01, 8.92671051e+01, 1.72820082e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.01883195, -0.00973219, 0.00031162]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63733673]), + 'frame': 21555, + 'frame_number': 21555, + 'framesequence': 86909, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.0370692498982, + 'timestamp_carla': 736036, + 'timestamp_device': 1606635, + 'timestamp_stream': 736.0370692498982, + 'transform': [array([-55.32588196, 81.88571167, -0.1570933 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-3.72639205e-03, -7.22963223e-03, -4.72707943e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038444483652710915, + 'FR_Wheel_Angle': 0.0038446204271167517, + 'Location': array([-6.63791809e+01, 8.92661209e+01, 1.72198296e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.01737717, -0.0089802 , 0.00020096]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63550568]), + 'frame': 21556, + 'frame_number': 21556, + 'framesequence': 86913, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.0709928497672, + 'timestamp_carla': 736070, + 'timestamp_device': 1606668, + 'timestamp_stream': 736.0709928497672, + 'transform': [array([-55.32588196, 81.88571167, -0.15710066]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-4.28485172e-03, -8.32144544e-03, -5.85203088e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003844523336738348, + 'FR_Wheel_Angle': 0.003844756865873933, + 'Location': array([-6.63774719e+01, 8.92652435e+01, 1.69829361e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.0166315 , -0.00859456, -0.00078596]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6360321 ]), + 'frame': 21557, + 'frame_number': 21557, + 'framesequence': 86917, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.1029391512275, + 'timestamp_carla': 736102, + 'timestamp_device': 1606701, + 'timestamp_stream': 736.1029391512275, + 'transform': [array([-55.32588196, 81.88571167, -0.15709066]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-3.85405705e-03, -7.51781510e-03, -6.65275584e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003844552207738161, + 'FR_Wheel_Angle': 0.003844665130600333, + 'Location': array([-6.63757782e+01, 8.92643661e+01, 1.71492575e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.01631194, -0.00842965, 0.00030523]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63529205]), + 'frame': 21558, + 'frame_number': 21558, + 'framesequence': 86921, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.1388205513358, + 'timestamp_carla': 736137, + 'timestamp_device': 1606735, + 'timestamp_stream': 736.1388205513358, + 'transform': [array([-55.32588196, 81.88571167, -0.1571158 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00378146, -0.00746362, -0.00015948]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003844501683488488, + 'FR_Wheel_Angle': 0.003844665130600333, + 'Location': array([-6.63741608e+01, 8.92635040e+01, 1.73563953e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.01648438, -0.00851869, -0.00014315]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6362915 ]), + 'frame': 21559, + 'frame_number': 21559, + 'framesequence': 86925, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.1705018505454, + 'timestamp_carla': 736169, + 'timestamp_device': 1606768, + 'timestamp_stream': 736.1705018505454, + 'transform': [array([-55.32588196, 81.88571167, -0.15709758]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-3.71247600e-03, -7.41382968e-03, -4.80506314e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00384445465169847, + 'FR_Wheel_Angle': 0.003844549646601081, + 'Location': array([-6.63724289e+01, 8.92626038e+01, 1.72438612e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.01724828, -0.00891329, 0.00053813]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51464844, 117.63378143]), + 'frame': 21560, + 'frame_number': 21560, + 'framesequence': 86929, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.203137151897, + 'timestamp_carla': 736202, + 'timestamp_device': 1606801, + 'timestamp_stream': 736.203137151897, + 'transform': [array([-55.32588196, 81.88571167, -0.15709326]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00395698, -0.0077934 , -0.0001708 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00384435523301363, + 'FR_Wheel_Angle': 0.0038444912061095238, + 'Location': array([-6.63705826e+01, 8.92616653e+01, 1.71183585e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.01835411, -0.00948487, -0.00020331]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63560486]), + 'frame': 21561, + 'frame_number': 21561, + 'framesequence': 86933, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.2372517511249, + 'timestamp_carla': 736236, + 'timestamp_device': 1606835, + 'timestamp_stream': 736.2372517511249, + 'transform': [array([-55.32588196, 81.88571167, -0.157102 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.0037698 , -0.00733494, -0.00019678]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003844263730570674, + 'FR_Wheel_Angle': 0.003844352439045906, + 'Location': array([-6.63685837e+01, 8.92606430e+01, 1.72953599e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.01977473, -0.01021945, 0.00030904]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6360321 ]), + 'frame': 21562, + 'frame_number': 21562, + 'framesequence': 86937, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.2711746506393, + 'timestamp_carla': 736270, + 'timestamp_device': 1606868, + 'timestamp_stream': 736.2711746506393, + 'transform': [array([-55.32588196, 81.88571167, -0.15710536]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00367671, -0.00734982, -0.0001034 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003844137769192457, + 'FR_Wheel_Angle': 0.0038435840979218483, + 'Location': array([-6.63663788e+01, 8.92594986e+01, 1.73708913e-03]), + 'Rotation': array([7.95716979e-03, 1.52621414e+02, 4.73848265e-03]), + 'Velocity': array([ 0.02170724, -0.01121829, 0.00060511]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63516235]), + 'frame': 21563, + 'frame_number': 21563, + 'framesequence': 86941, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.3040204495192, + 'timestamp_carla': 736303, + 'timestamp_device': 1606901, + 'timestamp_stream': 736.3040204495192, + 'transform': [array([-55.32588196, 81.88571167, -0.1570991 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.04501161e-03, 3.90433008e-03, 3.00026913e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003843182697892189, + 'FR_Wheel_Angle': 0.003843329381197691, + 'Location': array([-6.63640060e+01, 8.92582703e+01, 1.70901290e-03]), + 'Rotation': array([8.06645304e-03, 1.52621414e+02, 4.73873178e-03]), + 'Velocity': array([ 0.01693074, -0.00875238, 0.00123194]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63482666]), + 'frame': 21564, + 'frame_number': 21564, + 'framesequence': 86945, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.3359735496342, + 'timestamp_carla': 736335, + 'timestamp_device': 1606935, + 'timestamp_stream': 736.3359735496342, + 'transform': [array([-55.32588196, 81.88571167, -0.15708941]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.52038909e-03, 6.98875543e-03, -3.71329515e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038429962005466223, + 'FR_Wheel_Angle': 0.003843123558908701, + 'Location': array([-6.63610077e+01, 8.92567291e+01, 1.72949792e-03]), + 'Rotation': array([8.06645304e-03, 1.52621414e+02, 4.73873178e-03]), + 'Velocity': array([ 0.01961571, -0.01014021, 0.00028029]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63545227]), + 'frame': 21565, + 'frame_number': 21565, + 'framesequence': 86949, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.3698445521295, + 'timestamp_carla': 736369, + 'timestamp_device': 1606968, + 'timestamp_stream': 736.3698445521295, + 'transform': [array([-55.32588196, 81.88571167, -0.15709795]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([3.84007278e-03, 7.49036903e-03, 3.60419581e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038428199477493763, + 'FR_Wheel_Angle': 0.0038429307751357555, + 'Location': array([-6.63576813e+01, 8.92550201e+01, 1.72545435e-03]), + 'Rotation': array([8.06645304e-03, 1.52621414e+02, 4.73873178e-03]), + 'Velocity': array([ 0.02187731, -0.01130937, -0.00010577]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967529296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6364212 ]), + 'frame': 21566, + 'frame_number': 21566, + 'framesequence': 86953, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.4048684500158, + 'timestamp_carla': 736404, + 'timestamp_device': 1607001, + 'timestamp_stream': 736.4048684500158, + 'transform': [array([-55.32588196, 81.88571167, -0.15711215]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.79213924e-03, 7.29100080e-03, -1.43059447e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038426078390330076, + 'FR_Wheel_Angle': 0.0038426779210567474, + 'Location': array([-6.63540344e+01, 8.92531357e+01, 1.72156328e-03]), + 'Rotation': array([8.06645304e-03, 1.52621414e+02, 4.73873178e-03]), + 'Velocity': array([ 2.45608967e-02, -1.26963221e-02, -3.99589517e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63556671]), + 'frame': 21567, + 'frame_number': 21567, + 'framesequence': 86957, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.4397527500987, + 'timestamp_carla': 736438, + 'timestamp_device': 1607035, + 'timestamp_stream': 736.4397527500987, + 'transform': [array([-55.32588196, 81.88571167, -0.15711832]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.37082450e-03, 6.57716021e-03, -2.17161196e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003842315636575222, + 'FR_Wheel_Angle': 0.003842391073703766, + 'Location': array([-6.63500214e+01, 8.92510605e+01, 1.72934530e-03]), + 'Rotation': array([8.06645304e-03, 1.52621414e+02, 4.73873178e-03]), + 'Velocity': array([ 2.82091834e-02, -1.45821869e-02, 8.99600927e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965087890625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63414764]), + 'frame': 21568, + 'frame_number': 21568, + 'framesequence': 86961, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.4700823500752, + 'timestamp_carla': 736469, + 'timestamp_device': 1607068, + 'timestamp_stream': 736.4700823500752, + 'transform': [array([-55.32588196, 81.88571167, -0.15709022]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.58455721e-03, 6.84809964e-03, -1.97967511e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038420374039560556, + 'FR_Wheel_Angle': -0.04736435413360596, + 'Location': array([-6.63454742e+01, 8.92487183e+01, 1.72301289e-03]), + 'Rotation': array([8.06645304e-03, 1.52621414e+02, 4.73873178e-03]), + 'Velocity': array([ 0.03171257, -0.01639279, 0.00014698]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96435546875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51464844, 117.63352966]), + 'frame': 21569, + 'frame_number': 21569, + 'framesequence': 86965, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.5038602501154, + 'timestamp_carla': 736503, + 'timestamp_device': 1607101, + 'timestamp_stream': 736.5038602501154, + 'transform': [array([-55.32588196, 81.88571167, -0.15709682]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.00856849, 0.00334291, -0.00646321]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.943065881729126, + 'FR_Wheel_Angle': -5.390079498291016, + 'Location': array([-6.63404846e+01, 8.92461014e+01, 1.72720908e-03]), + 'Rotation': array([8.07328336e-03, 1.52622864e+02, 4.63989656e-03]), + 'Velocity': array([ 0.03546832, -0.01841559, 0.00043956]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63633728]), + 'frame': 21570, + 'frame_number': 21570, + 'framesequence': 86969, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.5366247519851, + 'timestamp_carla': 736535, + 'timestamp_device': 1607135, + 'timestamp_stream': 736.5366247519851, + 'transform': [array([-55.32588196, 81.88571167, -0.15709335]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.03178873, -0.00697347, -0.02998605]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.778613090515137, + 'FR_Wheel_Angle': -12.11865520477295, + 'Location': array([-6.63350296e+01, 8.92429276e+01, 1.70683861e-03]), + 'Rotation': array([8.05962272e-03, 1.52636276e+02, 4.34200792e-03]), + 'Velocity': array([ 3.85914519e-02, -2.03877538e-02, 3.69548798e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63568115]), + 'frame': 21571, + 'frame_number': 21571, + 'framesequence': 86974, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.5738337524235, + 'timestamp_carla': 736573, + 'timestamp_device': 1607176, + 'timestamp_stream': 736.5738337524235, + 'transform': [array([-55.32588196, 81.88571167, -0.15712878]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.04554749, -0.01875867, 0.02217421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.31205940246582, + 'FR_Wheel_Angle': -17.857946395874023, + 'Location': array([-6.63295364e+01, 8.92392960e+01, 1.74628256e-03]), + 'Rotation': array([7.95716979e-03, 1.52665771e+02, 4.00897255e-03]), + 'Velocity': array([ 0.04453965, -0.02599513, 0.00018036]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63602448]), + 'frame': 21572, + 'frame_number': 21572, + 'framesequence': 86977, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.6058689504862, + 'timestamp_carla': 736605, + 'timestamp_device': 1607201, + 'timestamp_stream': 736.6058689504862, + 'transform': [array([-55.32588196, 81.88571167, -0.15710619]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.06039131, -0.03154688, 0.11926054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.380319595336914, + 'FR_Wheel_Angle': -23.252866744995117, + 'Location': array([-6.63231506e+01, 8.92345963e+01, 1.71893113e-03]), + 'Rotation': array([7.90252816e-03, 1.52720764e+02, 3.81436059e-03]), + 'Velocity': array([ 0.0508491 , -0.03254673, 0.0003469 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9638671875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63248444]), + 'frame': 21573, + 'frame_number': 21573, + 'framesequence': 86981, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.6372060514987, + 'timestamp_carla': 736636, + 'timestamp_device': 1607235, + 'timestamp_stream': 736.6372060514987, + 'transform': [array([-55.32588196, 81.88571167, -0.15708826]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.28135937, -0.09059112, 3.86405516]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.1192741394043, + 'FR_Wheel_Angle': -27.989330291748047, + 'Location': array([-6.63089752e+01, 8.92229385e+01, 1.78095815e-03]), + 'Rotation': array([-1.31139625e-03, 1.52889603e+02, -5.64575195e-03]), + 'Velocity': array([ 2.71279305e-01, -2.48501226e-01, -1.30558010e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63474274]), + 'frame': 21574, + 'frame_number': 21574, + 'framesequence': 86985, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.6701768524945, + 'timestamp_carla': 736669, + 'timestamp_device': 1607268, + 'timestamp_stream': 736.6701768524945, + 'transform': [array([-55.32588196, 81.88571167, -0.15708826]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-4.78215143e-02, 1.02849875e-03, 6.56469440e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.58163833618164, + 'FR_Wheel_Angle': -30.73867416381836, + 'Location': array([-6.62634811e+01, 8.91813354e+01, 1.80361746e-03]), + 'Rotation': array([-8.05962272e-03, 1.53627838e+02, -1.67541504e-02]), + 'Velocity': array([ 3.74031693e-01, -4.06466782e-01, -1.59778589e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967529296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63653564]), + 'frame': 21575, + 'frame_number': 21575, + 'framesequence': 86989, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.7040835507214, + 'timestamp_carla': 736703, + 'timestamp_device': 1607301, + 'timestamp_stream': 736.7040835507214, + 'transform': [array([-55.32588196, 81.88571167, -0.15709636]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.09372915, 0.00673344, 6.67773533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.64601135253906, + 'FR_Wheel_Angle': -30.547897338867188, + 'Location': array([-6.62077789e+01, 8.91280365e+01, 1.79686537e-03]), + 'Rotation': array([-4.30301903e-03, 1.54605621e+02, -1.07727051e-02]), + 'Velocity': array([ 0.42113665, -0.45336378, 0.00057812]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967529296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63653564]), + 'frame': 21576, + 'frame_number': 21576, + 'framesequence': 86993, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.7378085516393, + 'timestamp_carla': 736737, + 'timestamp_device': 1607335, + 'timestamp_stream': 736.7378085516393, + 'transform': [array([-55.32588196, 81.88571167, -0.15709971]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.03791378, 0.01469146, 7.28036165]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.54844284057617, + 'FR_Wheel_Angle': -30.712602615356445, + 'Location': array([-6.61479416e+01, 8.90723724e+01, 1.76295277e-03]), + 'Rotation': array([ 9.15245269e-04, 1.55660736e+02, -3.81469680e-03]), + 'Velocity': array([ 4.41273034e-01, -4.71147895e-01, -6.08444207e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63572693]), + 'frame': 21577, + 'frame_number': 21577, + 'framesequence': 86997, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.7706597521901, + 'timestamp_carla': 736769, + 'timestamp_device': 1607368, + 'timestamp_stream': 736.7706597521901, + 'transform': [array([-55.32588196, 81.88571167, -0.15709516]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-6.30925351e-04, -6.81756588e-04, 7.85052061e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.42164993286133, + 'FR_Wheel_Angle': -30.67694854736328, + 'Location': array([-6.60840759e+01, 8.90147247e+01, 1.74906722e-03]), + 'Rotation': array([3.04626417e-03, 1.56777908e+02, 1.74065644e-04]), + 'Velocity': array([ 4.81625587e-01, -4.91349369e-01, 9.83619684e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63539124]), + 'frame': 21578, + 'frame_number': 21578, + 'framesequence': 87003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.8186647519469, + 'timestamp_carla': 736817, + 'timestamp_device': 1607418, + 'timestamp_stream': 736.8186647519469, + 'transform': [array([-55.32588196, 81.88571167, -0.1571482 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.23235548e-03, 2.36809207e-03, 8.60249615e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.46390914916992, + 'FR_Wheel_Angle': -30.659563064575195, + 'Location': array([-6.60132523e+01, 8.89537277e+01, 1.74826616e-03]), + 'Rotation': array([2.39056605e-03, 1.57987152e+02, 7.66285753e-04]), + 'Velocity': array([ 5.41244090e-01, -5.28107345e-01, -4.18415060e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63584137]), + 'frame': 21579, + 'frame_number': 21579, + 'framesequence': 87005, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.8720403499901, + 'timestamp_carla': 736871, + 'timestamp_device': 1607435, + 'timestamp_stream': 736.8720403499901, + 'transform': [array([-55.32588196, 81.88571167, -0.15713783]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([1.30460737e-02, 7.12104281e-03, 9.22034168e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.42408752441406, + 'FR_Wheel_Angle': -30.638805389404297, + 'Location': array([-6.59336090e+01, 8.88882294e+01, 1.74300186e-03]), + 'Rotation': array([2.47252826e-03, 1.59317459e+02, 1.93058699e-03]), + 'Velocity': array([ 5.93263209e-01, -5.52629769e-01, -2.12678904e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.961669921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63053894]), + 'frame': 21580, + 'frame_number': 21580, + 'framesequence': 87014, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.9157784506679, + 'timestamp_carla': 736915, + 'timestamp_device': 1607510, + 'timestamp_stream': 736.9157784506679, + 'transform': [array([-55.32588196, 81.88571167, -0.15712622]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([3.94330435e-02, 3.64195928e-03, 1.13297844e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.38227081298828, + 'FR_Wheel_Angle': -29.29983901977539, + 'Location': array([-6.58521881e+01, 8.88242722e+01, 1.72751420e-03]), + 'Rotation': array([3.76343401e-03, 1.60662048e+02, 4.29436285e-03]), + 'Velocity': array([ 6.24953032e-01, -5.53689659e-01, -5.10311111e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.963134765625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51367188, 117.63157654]), + 'frame': 21581, + 'frame_number': 21581, + 'framesequence': 87019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.9547887519002, + 'timestamp_carla': 736954, + 'timestamp_device': 1607551, + 'timestamp_stream': 736.9547887519002, + 'transform': [array([-55.32588196, 81.88571167, -0.157157 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.07284882, -0.01225704, 10.76770687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.391544342041016, + 'FR_Wheel_Angle': -27.334972381591797, + 'Location': array([-6.57610779e+01, 8.87589035e+01, 1.75642967e-03]), + 'Rotation': array([2.47252826e-03, 1.62009888e+02, 9.08100978e-03]), + 'Velocity': array([ 7.12354243e-01, -5.48660696e-01, -2.67372117e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.964111328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63273621]), + 'frame': 21582, + 'frame_number': 21582, + 'framesequence': 87024, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 736.9905032515526, + 'timestamp_carla': 736989, + 'timestamp_device': 1607593, + 'timestamp_stream': 736.9905032515526, + 'transform': [array([-55.32588196, 81.88571167, -0.15714091]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.01223682, 0.02348473, 11.15058041]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.132816314697266, + 'FR_Wheel_Angle': -28.590858459472656, + 'Location': array([-6.56625824e+01, 8.86943741e+01, 1.74181932e-03]), + 'Rotation': array([4.62403800e-03, 1.63329742e+02, 9.73535236e-03]), + 'Velocity': array([ 7.26373494e-01, -5.40253401e-01, -1.44147867e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.960693359375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51269531, 117.62966156]), + 'frame': 21583, + 'frame_number': 21583, + 'framesequence': 87027, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.0215247496963, + 'timestamp_carla': 737020, + 'timestamp_device': 1607618, + 'timestamp_stream': 737.0215247496963, + 'transform': [array([-55.32588196, 81.88571167, -0.15709883]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.01751676, -0.01411763, 11.18802834]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.763885498046875, + 'FR_Wheel_Angle': -27.872615814208984, + 'Location': array([-6.55625992e+01, 8.86307373e+01, 1.74292561e-03]), + 'Rotation': array([5.78517001e-03, 1.64713516e+02, 9.37113538e-03]), + 'Velocity': array([ 7.57748067e-01, -5.32513261e-01, 4.23598278e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.962646484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63127136]), + 'frame': 21584, + 'frame_number': 21584, + 'framesequence': 87030, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.047889649868, + 'timestamp_carla': 737047, + 'timestamp_device': 1607643, + 'timestamp_stream': 737.047889649868, + 'transform': [array([-55.32588196, 81.88571167, -0.15710215]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([1.02321794e-02, 4.20503505e-03, 1.15350971e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.37334442138672, + 'FR_Wheel_Angle': -28.17255401611328, + 'Location': array([-6.54566956e+01, 8.85677261e+01, 1.73457141e-03]), + 'Rotation': array([5.66905690e-03, 1.66126724e+02, 9.38230101e-03]), + 'Velocity': array([ 7.85183549e-01, -5.25063694e-01, 3.44085674e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63547516]), + 'frame': 21585, + 'frame_number': 21585, + 'framesequence': 87034, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.0780253522098, + 'timestamp_carla': 737077, + 'timestamp_device': 1607676, + 'timestamp_stream': 737.0780253522098, + 'transform': [array([-55.32588196, 81.88571167, -0.15707156]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.94020977e-02, 8.35552718e-03, 1.16303225e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.11872100830078, + 'FR_Wheel_Angle': -28.091676712036133, + 'Location': array([-6.53474274e+01, 8.85059433e+01, 1.71820633e-03]), + 'Rotation': array([6.21547177e-03, 1.67576706e+02, 9.69625637e-03]), + 'Velocity': array([ 8.03701282e-01, -5.10133982e-01, -3.90787114e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63514709]), + 'frame': 21586, + 'frame_number': 21586, + 'framesequence': 87038, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.1102883517742, + 'timestamp_carla': 737109, + 'timestamp_device': 1607710, + 'timestamp_stream': 737.1102883517742, + 'transform': [array([-55.32588196, 81.88571167, -0.15706782]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.45101359e-02, 5.12033794e-03, 1.15333385e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.20600891113281, + 'FR_Wheel_Angle': -28.114086151123047, + 'Location': array([-6.52396927e+01, 8.84485626e+01, 1.73186301e-03]), + 'Rotation': array([7.21950969e-03, 1.68980804e+02, 1.09657543e-02]), + 'Velocity': array([ 8.12966585e-01, -4.87986624e-01, 1.79615017e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9697265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63820648]), + 'frame': 21587, + 'frame_number': 21587, + 'framesequence': 87042, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.145606752485, + 'timestamp_carla': 737144, + 'timestamp_device': 1607743, + 'timestamp_stream': 737.145606752485, + 'transform': [array([-55.32588196, 81.88571167, -0.1570912 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.08446402e-02, 7.55956909e-03, 1.12650013e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.223182678222656, + 'FR_Wheel_Angle': -28.123498916625977, + 'Location': array([-6.51297760e+01, 8.83932877e+01, 1.71339989e-03]), + 'Rotation': array([8.55822675e-03, 1.70395615e+02, 1.23275379e-02]), + 'Velocity': array([ 8.01272273e-01, -4.55431074e-01, -1.33171081e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.969970703125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63858032]), + 'frame': 21588, + 'frame_number': 21588, + 'framesequence': 87046, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.1773604489863, + 'timestamp_carla': 737176, + 'timestamp_device': 1607776, + 'timestamp_stream': 737.1773604489863, + 'transform': [array([-55.32588196, 81.88571167, -0.15707843]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([1.76217388e-02, 4.86837048e-03, 1.09284964e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.239585876464844, + 'FR_Wheel_Angle': -28.13463020324707, + 'Location': array([-6.50225983e+01, 8.83426132e+01, 1.71092025e-03]), + 'Rotation': array([9.37101897e-03, 1.71756729e+02, 1.30316522e-02]), + 'Velocity': array([ 7.88827777e-01, -4.23424840e-01, 7.91454295e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6362381 ]), + 'frame': 21589, + 'frame_number': 21589, + 'framesequence': 87050, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.2122623510659, + 'timestamp_carla': 737211, + 'timestamp_device': 1607810, + 'timestamp_stream': 737.2122623510659, + 'transform': [array([-55.32588196, 81.88571167, -0.15709555]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([8.23355187e-03, 1.66323769e-03, 1.06642189e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.2575569152832, + 'FR_Wheel_Angle': -28.145557403564453, + 'Location': array([-6.49179001e+01, 8.82960815e+01, 1.71126367e-03]), + 'Rotation': array([9.80815105e-03, 1.73070663e+02, 1.32175926e-02]), + 'Velocity': array([ 7.75690436e-01, -3.93593818e-01, -1.09729765e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63751984]), + 'frame': 21590, + 'frame_number': 21590, + 'framesequence': 87054, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.2437675520778, + 'timestamp_carla': 737243, + 'timestamp_device': 1607843, + 'timestamp_stream': 737.2437675520778, + 'transform': [array([-55.32588196, 81.88571167, -0.15708086]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([9.80781112e-03, 1.61394814e-03, 1.02650671e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.27497863769531, + 'FR_Wheel_Angle': -28.153858184814453, + 'Location': array([-6.48140564e+01, 8.82527161e+01, 1.70359609e-03]), + 'Rotation': array([1.02247922e-02, 1.74359909e+02, 1.33258775e-02]), + 'Velocity': array([ 7.55396843e-01, -3.61983746e-01, 3.44419474e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63580322]), + 'frame': 21591, + 'frame_number': 21591, + 'framesequence': 87058, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.276260651648, + 'timestamp_carla': 737275, + 'timestamp_device': 1607876, + 'timestamp_stream': 737.276260651648, + 'transform': [array([-55.32588196, 81.88571167, -0.15707968]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([7.55914953e-03, 8.36809864e-04, 1.00931473e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.28854751586914, + 'FR_Wheel_Angle': -28.11144256591797, + 'Location': array([-6.47143326e+01, 8.82136765e+01, 1.71248429e-03]), + 'Rotation': array([9.87645332e-03, 1.75588547e+02, 1.25862975e-02]), + 'Velocity': array([ 7.47599006e-01, -3.38555783e-01, 7.44056670e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968505859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.6372757 ]), + 'frame': 21592, + 'frame_number': 21592, + 'framesequence': 87062, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.3100843504071, + 'timestamp_carla': 737309, + 'timestamp_device': 1607910, + 'timestamp_stream': 737.3100843504071, + 'transform': [array([-55.32588196, 81.88571167, -0.1570898 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.25104930e-02, -5.12208045e-03, 9.36468887e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.178993225097656, + 'FR_Wheel_Angle': -24.785049438476562, + 'Location': array([-6.46145248e+01, 8.81774673e+01, 1.70622824e-03]), + 'Rotation': array([9.90377367e-03, 1.76784775e+02, 1.40548581e-02]), + 'Velocity': array([ 7.35779583e-01, -2.99513996e-01, -1.68981554e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63739014]), + 'frame': 21593, + 'frame_number': 21593, + 'framesequence': 87066, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.341161750257, + 'timestamp_carla': 737340, + 'timestamp_device': 1607943, + 'timestamp_stream': 737.341161750257, + 'transform': [array([-55.32588196, 81.88571167, -0.15707697]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.97750833e-02, 2.28873850e-03, 8.48594761e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.77208709716797, + 'FR_Wheel_Angle': -25.966753005981445, + 'Location': array([-6.45159149e+01, 8.81474228e+01, 1.70882221e-03]), + 'Rotation': array([9.15928278e-03, 1.77809128e+02, 1.63795277e-02]), + 'Velocity': array([ 7.36945927e-01, -2.56101012e-01, -3.73687741e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63638306]), + 'frame': 21594, + 'frame_number': 21594, + 'framesequence': 87069, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.3722094520926, + 'timestamp_carla': 737371, + 'timestamp_device': 1607968, + 'timestamp_stream': 737.3722094520926, + 'transform': [array([-55.32588196, 81.88571167, -0.15707 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-6.68603927e-03, 3.25733796e-03, 8.73264694e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.43299865722656, + 'FR_Wheel_Angle': -25.512210845947266, + 'Location': array([-6.44197235e+01, 8.81194992e+01, 1.71080581e-03]), + 'Rotation': array([9.71935876e-03, 1.78837753e+02, 1.14550442e-02]), + 'Velocity': array([ 7.17063487e-01, -2.50676632e-01, -9.98401592e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63766479]), + 'frame': 21595, + 'frame_number': 21595, + 'framesequence': 87073, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.4048484489322, + 'timestamp_carla': 737404, + 'timestamp_device': 1608001, + 'timestamp_stream': 737.4048484489322, + 'transform': [array([-55.32588196, 81.88571167, -0.15707777]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 2.19336106e-03, -2.27089110e-03, 8.32770443e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.02354431152344, + 'FR_Wheel_Angle': -25.693925857543945, + 'Location': array([-6.43247223e+01, 8.80937805e+01, 1.71698572e-03]), + 'Rotation': array([9.48030222e-03, 1.79841736e+02, 1.15472274e-02]), + 'Velocity': array([ 7.11897492e-01, -2.26618171e-01, 3.99684905e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9697265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63835907]), + 'frame': 21596, + 'frame_number': 21596, + 'framesequence': 87077, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.4369336515665, + 'timestamp_carla': 737436, + 'timestamp_device': 1608035, + 'timestamp_stream': 737.4369336515665, + 'transform': [array([-55.32588196, 81.88571167, -0.15707919]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-9.75366309e-03, -2.36815959e-03, 8.39767742e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.16155242919922, + 'FR_Wheel_Angle': -25.56650733947754, + 'Location': array([-6.42299118e+01, 8.80699081e+01, 1.70996657e-03]), + 'Rotation': array([ 9.29588731e-03, -1.79158035e+02, 1.00284163e-02]), + 'Velocity': array([ 7.04574585e-01, -2.15465754e-01, -3.24401859e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63758087]), + 'frame': 21597, + 'frame_number': 21597, + 'framesequence': 87081, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.4714649505913, + 'timestamp_carla': 737470, + 'timestamp_device': 1608068, + 'timestamp_stream': 737.4714649505913, + 'transform': [array([-55.32588196, 81.88571167, -0.15709917]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-4.17779945e-03, 4.48011851e-04, 8.29492950e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.20599365234375, + 'FR_Wheel_Angle': -25.628726959228516, + 'Location': array([-6.41362915e+01, 8.80480728e+01, 1.70802115e-03]), + 'Rotation': array([ 9.06366017e-03, -1.78174606e+02, 9.59087536e-03]), + 'Velocity': array([ 6.99397862e-01, -2.00164422e-01, -3.38344573e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63744354]), + 'frame': 21598, + 'frame_number': 21598, + 'framesequence': 87085, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.5035342499614, + 'timestamp_carla': 737502, + 'timestamp_device': 1608101, + 'timestamp_stream': 737.5035342499614, + 'transform': [array([-55.32588196, 81.88571167, -0.15709208]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-1.54995930e-03, 2.87036016e-03, 8.23171997e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.167884826660156, + 'FR_Wheel_Angle': -25.62615394592285, + 'Location': array([-6.40428391e+01, 8.80279083e+01, 1.70626631e-03]), + 'Rotation': array([ 8.86558462e-03, -1.77193710e+02, 9.14809387e-03]), + 'Velocity': array([ 6.97215796e-01, -1.87181979e-01, -2.93016434e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63544464]), + 'frame': 21599, + 'frame_number': 21599, + 'framesequence': 87089, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.5364162512124, + 'timestamp_carla': 737535, + 'timestamp_device': 1608135, + 'timestamp_stream': 737.5364162512124, + 'transform': [array([-55.32588196, 81.88571167, -0.15709369]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([1.93256990e-03, 3.59205226e-03, 8.19255447e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.17425537109375, + 'FR_Wheel_Angle': -25.630863189697266, + 'Location': array([-6.39505157e+01, 8.80096207e+01, 1.71404833e-03]), + 'Rotation': array([ 8.67433939e-03, -1.76227875e+02, 8.90297629e-03]), + 'Velocity': array([ 6.97709084e-01, -1.74369469e-01, -2.17485416e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63615417]), + 'frame': 21600, + 'frame_number': 21600, + 'framesequence': 87093, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.5703768506646, + 'timestamp_carla': 737569, + 'timestamp_device': 1608168, + 'timestamp_stream': 737.5703768506646, + 'transform': [array([-55.32588196, 81.88571167, -0.15710272]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.04792945e-03, 7.74096698e-04, 8.14645863e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.17710494995117, + 'FR_Wheel_Angle': -25.632047653198242, + 'Location': array([-6.38584023e+01, 8.79930038e+01, 1.71801564e-03]), + 'Rotation': array([ 8.60603806e-03, -1.75266846e+02, 8.72518867e-03]), + 'Velocity': array([ 6.97151840e-01, -1.61570475e-01, -1.27239226e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63599396]), + 'frame': 21601, + 'frame_number': 21601, + 'framesequence': 87097, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.604297850281, + 'timestamp_carla': 737603, + 'timestamp_device': 1608201, + 'timestamp_stream': 737.604297850281, + 'transform': [array([-55.32588196, 81.88571167, -0.15710722]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.18743351e-03, -7.60105811e-03, 8.09429741e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.17647171020508, + 'FR_Wheel_Angle': -25.62947654724121, + 'Location': array([-6.37664909e+01, 8.79779968e+01, 1.72400475e-03]), + 'Rotation': array([ 8.46943446e-03, -1.74310089e+02, 8.47170316e-03]), + 'Velocity': array([ 7.01505661e-01, -1.49037942e-01, 3.66940483e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63508606]), + 'frame': 21602, + 'frame_number': 21602, + 'framesequence': 87101, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.635021649301, + 'timestamp_carla': 737634, + 'timestamp_device': 1608234, + 'timestamp_stream': 737.635021649301, + 'transform': [array([-55.32588196, 81.88571167, -0.1570877 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([7.50548439e-03, 4.40791575e-03, 8.05859947e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.18083953857422, + 'FR_Wheel_Angle': -25.631309509277344, + 'Location': array([-6.36737251e+01, 8.79644394e+01, 1.72480580e-03]), + 'Rotation': array([ 8.35332088e-03, -1.73347321e+02, 8.43571872e-03]), + 'Velocity': array([ 6.97498322e-01, -1.36900827e-01, 1.05218882e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965576171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63463593]), + 'frame': 21603, + 'frame_number': 21603, + 'framesequence': 87105, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.6690532490611, + 'timestamp_carla': 737668, + 'timestamp_device': 1608268, + 'timestamp_stream': 737.6690532490611, + 'transform': [array([-55.32588196, 81.88571167, -0.15709929]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 2.17464962e-03, -3.80039302e-04, 8.06604099e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.170623779296875, + 'FR_Wheel_Angle': -24.02899742126465, + 'Location': array([-6.35800629e+01, 8.79523392e+01, 1.71523087e-03]), + 'Rotation': array([ 8.33282992e-03, -1.72375702e+02, 8.32748041e-03]), + 'Velocity': array([ 6.99553907e-01, -1.25190631e-01, 9.64641586e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967529296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63658905]), + 'frame': 21604, + 'frame_number': 21604, + 'framesequence': 87109, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.7024969495833, + 'timestamp_carla': 737701, + 'timestamp_device': 1608301, + 'timestamp_stream': 737.7024969495833, + 'transform': [array([-55.32588196, 81.88571167, -0.15710124]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 3.48599404e-02, -8.10825615e-04, 6.94021893e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.23287010192871, + 'FR_Wheel_Angle': -22.263607025146484, + 'Location': array([-6.34883881e+01, 8.79438171e+01, 1.73575396e-03]), + 'Rotation': array([ 7.77958520e-03, -1.71509216e+02, 1.23362346e-02]), + 'Velocity': array([ 7.09140062e-01, -8.12681094e-02, 3.01074964e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63542938]), + 'frame': 21605, + 'frame_number': 21605, + 'framesequence': 87113, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.7364481501281, + 'timestamp_carla': 737735, + 'timestamp_device': 1608334, + 'timestamp_stream': 737.7364481501281, + 'transform': [array([-55.32588196, 81.88571167, -0.15710601]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-3.28699201e-02, 4.91158431e-03, 7.31761169e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.947105407714844, + 'FR_Wheel_Angle': -23.41057014465332, + 'Location': array([-6.33937492e+01, 8.79382019e+01, 1.72244071e-03]), + 'Rotation': array([ 7.99132045e-03, -1.70680237e+02, 9.82237048e-03]), + 'Velocity': array([ 7.04689801e-01, -7.92937279e-02, 2.56538397e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63523865]), + 'frame': 21606, + 'frame_number': 21606, + 'framesequence': 87117, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.7700708508492, + 'timestamp_carla': 737769, + 'timestamp_device': 1608368, + 'timestamp_stream': 737.7700708508492, + 'transform': [array([-55.32588196, 81.88571167, -0.15710601]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 1.46794866e-03, -2.71774898e-03, 7.19170570e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.5946102142334, + 'FR_Wheel_Angle': -22.80349349975586, + 'Location': array([-6.33003960e+01, 8.79331589e+01, 1.71862601e-03]), + 'Rotation': array([ 8.31917021e-03, -1.69825363e+02, 8.76021013e-03]), + 'Velocity': array([ 7.06263840e-01, -6.65287822e-02, 1.29289620e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.634758 ]), + 'frame': 21607, + 'frame_number': 21607, + 'framesequence': 87121, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.8017364516854, + 'timestamp_carla': 737801, + 'timestamp_device': 1608401, + 'timestamp_stream': 737.8017364516854, + 'transform': [array([-55.32588196, 81.88571167, -0.15709196]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-4.73508192e-03, 1.76058454e-03, 7.22019768e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.198286056518555, + 'FR_Wheel_Angle': -23.04096221923828, + 'Location': array([-6.32067070e+01, 8.79299469e+01, 1.72942155e-03]), + 'Rotation': array([ 8.13475531e-03, -1.68986862e+02, 8.29443242e-03]), + 'Velocity': array([ 7.07782507e-01, -5.60852699e-02, 1.43980971e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.634758 ]), + 'frame': 21608, + 'frame_number': 21608, + 'framesequence': 87125, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.8367409519851, + 'timestamp_carla': 737836, + 'timestamp_device': 1608434, + 'timestamp_stream': 737.8367409519851, + 'transform': [array([-55.32588196, 81.88571167, -0.15710871]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.05427272, -0.05055585, 7.1162591 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.005014419555664, + 'FR_Wheel_Angle': -23.01283836364746, + 'Location': array([-6.31147575e+01, 8.79279404e+01, 1.77653308e-03]), + 'Rotation': array([ 6.28377357e-03, -1.68160645e+02, 4.04442614e-03]), + 'Velocity': array([ 6.97186887e-01, -4.53348495e-02, 6.78415294e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6361618 ]), + 'frame': 21609, + 'frame_number': 21609, + 'framesequence': 87129, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.8692515492439, + 'timestamp_carla': 737868, + 'timestamp_device': 1608468, + 'timestamp_stream': 737.8692515492439, + 'transform': [array([-55.32588196, 81.88571167, -0.15709883]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.19763586, -0.17818335, 7.17700529]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.011213302612305, + 'FR_Wheel_Angle': -22.983951568603516, + 'Location': array([-6.30218735e+01, 8.79273148e+01, 1.88567152e-03]), + 'Rotation': array([ 1.94660376e-03, -1.67321320e+02, -2.71606469e-03]), + 'Velocity': array([ 0.70893872, -0.03400151, 0.0025843 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965576171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63449097]), + 'frame': 21610, + 'frame_number': 21610, + 'framesequence': 87133, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.9045559503138, + 'timestamp_carla': 737903, + 'timestamp_device': 1608501, + 'timestamp_stream': 737.9045559503138, + 'transform': [array([-55.32588196, 81.88571167, -0.15711448]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.29278558, -0.30018187, 7.11182261]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.027116775512695, + 'FR_Wheel_Angle': -22.990436553955078, + 'Location': array([-6.29296913e+01, 8.79280090e+01, 2.56190286e-03]), + 'Rotation': array([-2.30450574e-02, -1.66494949e+02, -4.29382399e-02]), + 'Velocity': array([ 0.69436806, -0.02352441, 0.00492175]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63547516]), + 'frame': 21611, + 'frame_number': 21611, + 'framesequence': 87137, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.938200250268, + 'timestamp_carla': 737937, + 'timestamp_device': 1608534, + 'timestamp_stream': 737.938200250268, + 'transform': [array([-55.32588196, 81.88571167, -0.15710944]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.28328264, -0.30782551, 7.07042646]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.026277542114258, + 'FR_Wheel_Angle': -22.992828369140625, + 'Location': array([-6.28381004e+01, 8.79300461e+01, 3.38889123e-03]), + 'Rotation': array([-5.14791347e-02, -1.65671265e+02, -8.59679878e-02]), + 'Velocity': array([ 0.69418812, -0.01286476, 0.0052413 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51464844, 117.63391113]), + 'frame': 21612, + 'frame_number': 21612, + 'framesequence': 87142, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 737.9737309515476, + 'timestamp_carla': 737973, + 'timestamp_device': 1608576, + 'timestamp_stream': 737.9737309515476, + 'transform': [array([-55.32588196, 81.88571167, -0.15712115]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.20452982, -0.30883133, 7.0188098 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.025392532348633, + 'FR_Wheel_Angle': -22.99203872680664, + 'Location': array([-6.27470055e+01, 8.79334259e+01, 4.18906193e-03]), + 'Rotation': array([-7.93463066e-02, -1.64853638e+02, -1.25946030e-01]), + 'Velocity': array([ 0.68677115, -0.00390166, 0.00544097]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965576171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63441467]), + 'frame': 21613, + 'frame_number': 21613, + 'framesequence': 87146, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.0065319500864, + 'timestamp_carla': 738005, + 'timestamp_device': 1608609, + 'timestamp_stream': 738.0065319500864, + 'transform': [array([-55.32588196, 81.88571167, -0.15710597]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([2.58531086e-02, 6.61646016e-03, 7.11606646e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.01923942565918, + 'FR_Wheel_Angle': -22.98541831970215, + 'Location': array([-6.26561165e+01, 8.79381714e+01, 4.47367644e-03]), + 'Rotation': array([-8.74947160e-02, -1.64031799e+02, -1.27716050e-01]), + 'Velocity': array([7.09620118e-01, 6.72875904e-03, 5.98907471e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.964111328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63324738]), + 'frame': 21614, + 'frame_number': 21614, + 'framesequence': 87149, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.03392605111, + 'timestamp_carla': 738033, + 'timestamp_device': 1608634, + 'timestamp_stream': 738.03392605111, + 'transform': [array([-55.32588196, 81.88571167, -0.15712306]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.02603398, -0.15361623, 7.17228985]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.017940521240234, + 'FR_Wheel_Angle': -22.63551139831543, + 'Location': array([-6.25624466e+01, 8.79443512e+01, 4.47482103e-03]), + 'Rotation': array([-8.91134739e-02, -1.63188843e+02, -1.22009248e-01]), + 'Velocity': array([0.69781333, 0.01338279, 0.00239891]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63476562]), + 'frame': 21615, + 'frame_number': 21615, + 'framesequence': 87153, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.0690884515643, + 'timestamp_carla': 738068, + 'timestamp_device': 1608668, + 'timestamp_stream': 738.0690884515643, + 'transform': [array([-55.32588196, 81.88571167, -0.15712306]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.01129655, -0.37599188, 6.52827072]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.011396408081055, + 'FR_Wheel_Angle': -19.051748275756836, + 'Location': array([-6.24707146e+01, 8.79524765e+01, 5.60130086e-03]), + 'Rotation': array([-1.32020712e-01, -1.62381500e+02, -1.26892105e-01]), + 'Velocity': array([0.69073164, 0.04224384, 0.00791325]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.964111328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63305664]), + 'frame': 21616, + 'frame_number': 21616, + 'framesequence': 87157, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.1021602489054, + 'timestamp_carla': 738101, + 'timestamp_device': 1608701, + 'timestamp_stream': 738.1021602489054, + 'transform': [array([-55.32588196, 81.88571167, -0.15710685]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.03830357, -0.38820595, 6.10857916]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.056949615478516, + 'FR_Wheel_Angle': -20.803003311157227, + 'Location': array([-6.23799515e+01, 8.79645233e+01, 7.00560538e-03]), + 'Rotation': array([-1.80911213e-01, -1.61692719e+02, -1.34063706e-01]), + 'Velocity': array([0.6837315 , 0.06390592, 0.00833231]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.964111328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63305664]), + 'frame': 21617, + 'frame_number': 21617, + 'framesequence': 87161, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.1340914517641, + 'timestamp_carla': 738133, + 'timestamp_device': 1608734, + 'timestamp_stream': 738.1340914517641, + 'transform': [array([-55.32588196, 81.88571167, -0.15708968]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.44175705e-04, -3.70716661e-01, 6.32302427e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.903888702392578, + 'FR_Wheel_Angle': -20.014610290527344, + 'Location': array([-6.22907410e+01, 8.79767151e+01, 8.36195890e-03]), + 'Rotation': array([-2.27568224e-01, -1.60974197e+02, -1.45843491e-01]), + 'Velocity': array([0.68240112, 0.06500084, 0.00801375]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63467407]), + 'frame': 21618, + 'frame_number': 21618, + 'framesequence': 87165, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.1675451509655, + 'timestamp_carla': 738166, + 'timestamp_device': 1608768, + 'timestamp_stream': 738.1675451509655, + 'transform': [array([-55.32588196, 81.88571167, -0.15709083]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.00960835, 0.0344347 , 6.33742905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.932811737060547, + 'FR_Wheel_Angle': -20.35183334350586, + 'Location': array([-6.21977882e+01, 8.79908066e+01, 8.82727560e-03]), + 'Rotation': array([-2.41877481e-01, -1.60251938e+02, -1.41296417e-01]), + 'Velocity': array([ 7.04588294e-01, 7.86463991e-02, -4.22515848e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63639069]), + 'frame': 21619, + 'frame_number': 21619, + 'framesequence': 87169, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.1986161507666, + 'timestamp_carla': 738197, + 'timestamp_device': 1608801, + 'timestamp_stream': 738.1986161507666, + 'transform': [array([-55.32588196, 81.88571167, -0.15707584]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.23730469, -0.28910416, 6.20365572]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.81833839416504, + 'FR_Wheel_Angle': -20.236753463745117, + 'Location': array([-6.21078682e+01, 8.80054398e+01, 9.27187875e-03]), + 'Rotation': array([ -0.25848165, -159.54769897, -0.17593379]), + 'Velocity': array([0.6870144 , 0.08747704, 0.0040433 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63627625]), + 'frame': 21620, + 'frame_number': 21620, + 'framesequence': 87173, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.2337740510702, + 'timestamp_carla': 738233, + 'timestamp_device': 1608834, + 'timestamp_stream': 738.2337740510702, + 'transform': [array([-55.32588196, 81.88571167, -0.15709826]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.23257548, -0.30301797, 6.17954254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.894533157348633, + 'FR_Wheel_Angle': -20.255008697509766, + 'Location': array([-6.20165939e+01, 8.80215530e+01, 9.95478593e-03]), + 'Rotation': array([ -0.28393778, -158.83300781, -0.21817017]), + 'Velocity': array([0.68041486, 0.09386043, 0.00430023]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968994140625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63777924]), + 'frame': 21621, + 'frame_number': 21621, + 'framesequence': 87177, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.2671758495271, + 'timestamp_carla': 738266, + 'timestamp_device': 1608868, + 'timestamp_stream': 738.2671758495271, + 'transform': [array([-55.32588196, 81.88571167, -0.15709712]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.08582797, -0.26123369, 6.2106719 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.885517120361328, + 'FR_Wheel_Angle': -20.25282859802246, + 'Location': array([-6.19271088e+01, 8.80386124e+01, 1.08843511e-02]), + 'Rotation': array([ -0.31759694, -158.12301636, -0.24258418]), + 'Velocity': array([0.67539281, 0.10042147, 0.00625899]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63553619]), + 'frame': 21622, + 'frame_number': 21622, + 'framesequence': 87181, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.3015196509659, + 'timestamp_carla': 738300, + 'timestamp_device': 1608901, + 'timestamp_stream': 738.3015196509659, + 'transform': [array([-55.32588196, 81.88571167, -0.15710379]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.26344329, -0.0230535 , 6.24282503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.89522361755371, + 'FR_Wheel_Angle': -20.255983352661133, + 'Location': array([-6.18378372e+01, 8.80567856e+01, 1.16277980e-02]), + 'Rotation': array([ -0.34241101, -157.41018677, -0.21520992]), + 'Velocity': array([0.67824751, 0.1076715 , 0.00323061]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63565063]), + 'frame': 21623, + 'frame_number': 21623, + 'framesequence': 87185, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.3341655507684, + 'timestamp_carla': 738333, + 'timestamp_device': 1608934, + 'timestamp_stream': 738.3341655507684, + 'transform': [array([-55.32588196, 81.88571167, -0.15709494]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.2343013 , -0.03085084, 6.23303032]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.894332885742188, + 'FR_Wheel_Angle': -20.25661277770996, + 'Location': array([-6.17480545e+01, 8.80761490e+01, 1.21482750e-02]), + 'Rotation': array([ -0.36133066, -156.69230652, -0.18252565]), + 'Velocity': array([0.67311054, 0.11426663, 0.00236845]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63497925]), + 'frame': 21624, + 'frame_number': 21624, + 'framesequence': 87189, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.3674148507416, + 'timestamp_carla': 738366, + 'timestamp_device': 1608968, + 'timestamp_stream': 738.3674148507416, + 'transform': [array([-55.32588196, 81.88571167, -0.15709494]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.11906195, -0.3431811 , 6.12970352]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.89796257019043, + 'FR_Wheel_Angle': -20.261863708496094, + 'Location': array([-6.16605644e+01, 8.80961685e+01, 1.31395627e-02]), + 'Rotation': array([ -0.39767408, -155.98770142, -0.18844604]), + 'Velocity': array([0.66710061, 0.1255573 , 0.00603677]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63586426]), + 'frame': 21625, + 'frame_number': 21625, + 'framesequence': 87193, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.3992770500481, + 'timestamp_carla': 738398, + 'timestamp_device': 1609001, + 'timestamp_stream': 738.3992770500481, + 'transform': [array([-55.32588196, 81.88571167, -0.15708514]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.20177764, -0.3005302 , 6.01313543]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.90319061279297, + 'FR_Wheel_Angle': -20.262414932250977, + 'Location': array([-6.15747070e+01, 8.81168365e+01, 1.39157390e-02]), + 'Rotation': array([ -0.42355368, -155.30525208, -0.2266845 ]), + 'Velocity': array([0.65330207, 0.13171606, 0.00419348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63586426]), + 'frame': 21626, + 'frame_number': 21626, + 'framesequence': 87197, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.4347222521901, + 'timestamp_carla': 738434, + 'timestamp_device': 1609034, + 'timestamp_stream': 738.4347222521901, + 'transform': [array([-55.32588196, 81.88571167, -0.15710746]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.03619619, -0.3094441 , 5.89620018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.217756271362305, + 'FR_Wheel_Angle': -17.33627700805664, + 'Location': array([-6.14885292e+01, 8.81389542e+01, 1.47372717e-02]), + 'Rotation': array([ -0.45360649, -154.6124115 , -0.25482175]), + 'Velocity': array([0.64524603, 0.1427754 , 0.00646874]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96826171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63684845]), + 'frame': 21627, + 'frame_number': 21627, + 'framesequence': 87201, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.466646451503, + 'timestamp_carla': 738466, + 'timestamp_device': 1609068, + 'timestamp_stream': 738.466646451503, + 'transform': [array([-55.32588196, 81.88571167, -0.15709323]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.27075756, -0.00523271, 4.94824266]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.647293090820312, + 'FR_Wheel_Angle': -17.209461212158203, + 'Location': array([-6.14050331e+01, 8.81638947e+01, 1.54553503e-02]), + 'Rotation': array([ -0.47784683, -154.03465271, -0.22671504]), + 'Velocity': array([0.636971 , 0.17505075, 0.00332669]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965576171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63461304]), + 'frame': 21628, + 'frame_number': 21628, + 'framesequence': 87205, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.4998022504151, + 'timestamp_carla': 738499, + 'timestamp_device': 1609101, + 'timestamp_stream': 738.4998022504151, + 'transform': [array([-55.32588196, 81.88571167, -0.15709323]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.19432297, -0.10292432, 5.31861019]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.318885803222656, + 'FR_Wheel_Angle': -17.49161720275879, + 'Location': array([-6.13171806e+01, 8.81915054e+01, 1.60063077e-02]), + 'Rotation': array([ -0.50000399, -153.43254089, -0.1984863 ]), + 'Velocity': array([0.71240598, 0.18236108, 0.00312382]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63603973]), + 'frame': 21629, + 'frame_number': 21629, + 'framesequence': 87209, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.5326173491776, + 'timestamp_carla': 738532, + 'timestamp_device': 1609134, + 'timestamp_stream': 738.5326173491776, + 'transform': [array([-55.32588196, 81.88571167, -0.15709127]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.05880797, -0.02072421, 4.87658644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.47260093688965, + 'FR_Wheel_Angle': -17.334335327148438, + 'Location': array([-6.12262840e+01, 8.82205276e+01, 1.65436845e-02]), + 'Rotation': array([ -0.51830888, -152.79553223, -0.17291258]), + 'Velocity': array([0.692644 , 0.19061044, 0.00127173]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63603973]), + 'frame': 21630, + 'frame_number': 21630, + 'framesequence': 87213, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.5670740492642, + 'timestamp_carla': 738566, + 'timestamp_device': 1609168, + 'timestamp_stream': 738.5670740492642, + 'transform': [array([-55.32588196, 81.88571167, -0.15710291]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.03875026, 0.01034235, 4.91964626]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.7592830657959, + 'FR_Wheel_Angle': -17.32159423828125, + 'Location': array([-6.11361351e+01, 8.82503815e+01, 1.64585020e-02]), + 'Rotation': array([ -0.51366436, -152.17602539, -0.16806024]), + 'Velocity': array([ 0.68000299, 0.1931435 , -0.00085572]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63623047]), + 'frame': 21631, + 'frame_number': 21631, + 'framesequence': 87217, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.6000707522035, + 'timestamp_carla': 738599, + 'timestamp_device': 1609201, + 'timestamp_stream': 738.6000707522035, + 'transform': [array([-55.32588196, 81.88571167, -0.15709826]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.05132236, -0.03633843, 4.82204723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.77342987060547, + 'FR_Wheel_Angle': -17.381454467773438, + 'Location': array([-6.10495148e+01, 8.82801056e+01, 1.63153745e-02]), + 'Rotation': array([ -0.50912225, -151.57450867, -0.16607662]), + 'Velocity': array([ 6.68587387e-01, 1.98218212e-01, -2.77752872e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.6350708 ]), + 'frame': 21632, + 'frame_number': 21632, + 'framesequence': 87221, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.6323675513268, + 'timestamp_carla': 738631, + 'timestamp_device': 1609234, + 'timestamp_stream': 738.6323675513268, + 'transform': [array([-55.32588196, 81.88571167, -0.15709071]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.20781183, -0.33304164, 4.75595713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.737850189208984, + 'FR_Wheel_Angle': -17.375396728515625, + 'Location': array([-6.09641991e+01, 8.83103409e+01, 1.64551064e-02]), + 'Rotation': array([ -0.51577491, -150.97952271, -0.18078607]), + 'Velocity': array([0.6539945 , 0.20347127, 0.00337656]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63553619]), + 'frame': 21633, + 'frame_number': 21633, + 'framesequence': 87225, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.6678213514388, + 'timestamp_carla': 738667, + 'timestamp_device': 1609268, + 'timestamp_stream': 738.6678213514388, + 'transform': [array([-55.32588196, 81.88571167, -0.15711103]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.10422015, -0.32903659, 4.82328415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.73605728149414, + 'FR_Wheel_Angle': -17.374027252197266, + 'Location': array([-6.08791008e+01, 8.83418045e+01, 1.76511277e-02]), + 'Rotation': array([ -0.56021208, -150.37051392, -0.20684819]), + 'Velocity': array([0.64750564, 0.2095906 , 0.00801753]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6362915 ]), + 'frame': 21634, + 'frame_number': 21634, + 'framesequence': 87229, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.7034521512687, + 'timestamp_carla': 738702, + 'timestamp_device': 1609301, + 'timestamp_stream': 738.7034521512687, + 'transform': [array([-55.32588196, 81.88571167, -0.15712328]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.20909028, -0.03215432, 4.75612545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.740522384643555, + 'FR_Wheel_Angle': -17.376279830932617, + 'Location': array([-6.07967033e+01, 8.83732147e+01, 1.83949564e-02]), + 'Rotation': array([ -0.58373523, -149.78190613, -0.18002316]), + 'Velocity': array([0.63995457, 0.21022409, 0.00293886]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96533203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63425446]), + 'frame': 21635, + 'frame_number': 21635, + 'framesequence': 87233, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.7338158525527, + 'timestamp_carla': 738733, + 'timestamp_device': 1609334, + 'timestamp_stream': 738.7338158525527, + 'transform': [array([-55.32588196, 81.88571167, -0.15709257]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.1966517 , -0.02169047, 4.70499372]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.74363136291504, + 'FR_Wheel_Angle': -17.3818416595459, + 'Location': array([-6.07140427e+01, 8.84056549e+01, 1.88381094e-02]), + 'Rotation': array([-5.99151015e-01, -1.49188736e+02, -1.46301210e-01]), + 'Velocity': array([0.6281727 , 0.21351564, 0.00226656]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9638671875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63303375]), + 'frame': 21636, + 'frame_number': 21636, + 'framesequence': 87237, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.768040150404, + 'timestamp_carla': 738767, + 'timestamp_device': 1609368, + 'timestamp_stream': 738.768040150404, + 'transform': [array([-55.32588196, 81.88571167, -0.15710059]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.4524411 , -0.71218914, 4.5610714 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.74947166442871, + 'FR_Wheel_Angle': -17.381786346435547, + 'Location': array([-6.06321716e+01, 8.84386902e+01, 2.02232264e-02]), + 'Rotation': array([ -0.6465115 , -148.59967041, -0.21563722]), + 'Velocity': array([0.60047722, 0.21876232, 0.01030731]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63610077]), + 'frame': 21637, + 'frame_number': 21637, + 'framesequence': 87241, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.8016982488334, + 'timestamp_carla': 738801, + 'timestamp_device': 1609401, + 'timestamp_stream': 738.8016982488334, + 'transform': [array([-55.32588196, 81.88571167, -0.15710059]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.6590693 , -0.74228019, 4.53414679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.53043556213379, + 'FR_Wheel_Angle': -16.445554733276367, + 'Location': array([-6.05538216e+01, 8.84714127e+01, 2.20849887e-02]), + 'Rotation': array([ -0.70398074, -148.03347778, -0.32006827]), + 'Velocity': array([0.607584 , 0.22810487, 0.01243234]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63529968]), + 'frame': 21638, + 'frame_number': 21638, + 'framesequence': 87245, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.8337876498699, + 'timestamp_carla': 738833, + 'timestamp_device': 1609434, + 'timestamp_stream': 738.8337876498699, + 'transform': [array([-55.32588196, 81.88571167, -0.15708961]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.47073251, -0.05922708, 3.55122495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.0638427734375, + 'FR_Wheel_Angle': -13.09276294708252, + 'Location': array([-6.04756317e+01, 8.85058746e+01, 2.31044665e-02]), + 'Rotation': array([ -0.69092143, -147.52365112, -0.38198847]), + 'Velocity': array([0.59957284, 0.2551429 , 0.00642268]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63529968]), + 'frame': 21639, + 'frame_number': 21639, + 'framesequence': 87249, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.8662233501673, + 'timestamp_carla': 738865, + 'timestamp_device': 1609468, + 'timestamp_stream': 738.8662233501673, + 'transform': [array([-55.32588196, 81.88571167, -0.1570859 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.49623951, -0.07982087, 3.56905842]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.223480224609375, + 'FR_Wheel_Angle': -14.962918281555176, + 'Location': array([-6.03974266e+01, 8.85435257e+01, 2.36424915e-02]), + 'Rotation': array([ -0.66155159, -147.09909058, -0.43218988]), + 'Velocity': array([0.59458673, 0.26187649, 0.0055051 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63639832]), + 'frame': 21640, + 'frame_number': 21640, + 'framesequence': 87253, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.899825450033, + 'timestamp_carla': 738899, + 'timestamp_device': 1609501, + 'timestamp_stream': 738.899825450033, + 'transform': [array([-55.32588196, 81.88571167, -0.15709281]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.51305223, -0.16741657, 3.58047414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.39789581298828, + 'FR_Wheel_Angle': -14.071442604064941, + 'Location': array([-6.03201485e+01, 8.85805283e+01, 2.47396752e-02]), + 'Rotation': array([ -0.65505606, -146.63529968, -0.51556396]), + 'Velocity': array([0.59049559, 0.26203376, 0.00727424]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63677216]), + 'frame': 21641, + 'frame_number': 21641, + 'framesequence': 87257, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.9318556524813, + 'timestamp_carla': 738931, + 'timestamp_device': 1609534, + 'timestamp_stream': 738.9318556524813, + 'transform': [array([-55.32588196, 81.88571167, -0.15708579]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.04479072, -0.0226077 , 3.60940385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.71708869934082, + 'FR_Wheel_Angle': -14.450433731079102, + 'Location': array([-6.02436104e+01, 8.86183014e+01, 2.50886045e-02]), + 'Rotation': array([ -0.6392169 , -146.19148254, -0.54492182]), + 'Velocity': array([5.92326760e-01, 2.66741216e-01, 2.21056936e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63607788]), + 'frame': 21642, + 'frame_number': 21642, + 'framesequence': 87261, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 738.9683473519981, + 'timestamp_carla': 738967, + 'timestamp_device': 1609568, + 'timestamp_stream': 738.9683473519981, + 'transform': [array([-55.32588196, 81.88571167, -0.15711795]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.01632102, -0.00816778, 3.64754462]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.55145835876465, + 'FR_Wheel_Angle': -14.357056617736816, + 'Location': array([-6.01659889e+01, 8.86571655e+01, 2.49235425e-02]), + 'Rotation': array([ -0.63784403, -145.73046875, -0.54193103]), + 'Velocity': array([ 0.59431541, 0.2721628 , -0.00115566]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63677979]), + 'frame': 21643, + 'frame_number': 21643, + 'framesequence': 87265, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.0015761516988, + 'timestamp_carla': 739001, + 'timestamp_device': 1609601, + 'timestamp_stream': 739.0015761516988, + 'transform': [array([-55.32588196, 81.88571167, -0.15710834]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.46829829, -0.09119764, 3.55954313]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.59602165222168, + 'FR_Wheel_Angle': -14.345558166503906, + 'Location': array([-6.00898247e+01, 8.86959915e+01, 2.50401590e-02]), + 'Rotation': array([ -0.6230225 , -145.28414917, -0.56686407]), + 'Velocity': array([0.58409292, 0.27655485, 0.00458205]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96435546875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51464844, 117.63356781]), + 'frame': 21644, + 'frame_number': 21644, + 'framesequence': 87269, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.0379278510809, + 'timestamp_carla': 739037, + 'timestamp_device': 1609634, + 'timestamp_stream': 739.0379278510809, + 'transform': [array([-55.32588196, 81.88571167, -0.15712763]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.21437685, -0.08368005, 3.66528988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.597455978393555, + 'FR_Wheel_Angle': -14.347275733947754, + 'Location': array([-6.00146408e+01, 8.87353973e+01, 2.58014575e-02]), + 'Rotation': array([ -0.60482007, -144.83378601, -0.59826654]), + 'Velocity': array([0.57278955, 0.2761254 , 0.00865789]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965576171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63452911]), + 'frame': 21645, + 'frame_number': 21645, + 'framesequence': 87273, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.067590650171, + 'timestamp_carla': 739067, + 'timestamp_device': 1609668, + 'timestamp_stream': 739.067590650171, + 'transform': [array([-55.32588196, 81.88571167, -0.15716033]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.17943822, -0.08984244, 3.65256929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.599702835083008, + 'FR_Wheel_Angle': -14.349067687988281, + 'Location': array([-5.99399223e+01, 8.87754059e+01, 2.70287227e-02]), + 'Rotation': array([ -0.6017738 , -144.37585449, -0.60955811]), + 'Velocity': array([0.56468862, 0.2774592 , 0.00933061]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9638671875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63259888]), + 'frame': 21646, + 'frame_number': 21646, + 'framesequence': 87277, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.0981065519154, + 'timestamp_carla': 739097, + 'timestamp_device': 1609701, + 'timestamp_stream': 739.0981065519154, + 'transform': [array([-55.32588196, 81.88571167, -0.15711294]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.06388393, -0.03724798, 3.50786805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.599456787109375, + 'FR_Wheel_Angle': -14.347925186157227, + 'Location': array([-5.98655510e+01, 8.88159256e+01, 2.81610768e-02]), + 'Rotation': array([ -0.59911686, -143.92373657, -0.61978149]), + 'Velocity': array([0.5609681, 0.2796073, 0.0050174]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96044921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62932587]), + 'frame': 21647, + 'frame_number': 21647, + 'framesequence': 87281, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.1321357488632, + 'timestamp_carla': 739131, + 'timestamp_device': 1609734, + 'timestamp_stream': 739.1321357488632, + 'transform': [array([-55.32588196, 81.88571167, -0.157107 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.2923809 , -0.06582961, 3.45328069]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.599571228027344, + 'FR_Wheel_Angle': -14.348329544067383, + 'Location': array([-5.97929420e+01, 8.88558884e+01, 2.83003524e-02]), + 'Rotation': array([ -0.59155583, -143.4879303 , -0.61767572]), + 'Velocity': array([0.56535864, 0.28574967, 0.00162324]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965087890625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63406372]), + 'frame': 21648, + 'frame_number': 21648, + 'framesequence': 87285, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.1668955497444, + 'timestamp_carla': 739166, + 'timestamp_device': 1609767, + 'timestamp_stream': 739.1668955497444, + 'transform': [array([-55.32588196, 81.88571167, -0.15710925]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.49521047, -0.11964332, 3.49897218]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.5864200592041, + 'FR_Wheel_Angle': -14.323925971984863, + 'Location': array([-5.97198944e+01, 8.88968048e+01, 2.85889711e-02]), + 'Rotation': array([ -0.56469953, -143.05081177, -0.66430658]), + 'Velocity': array([0.55929589, 0.29173672, 0.00422602]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63465881]), + 'frame': 21649, + 'frame_number': 21649, + 'framesequence': 87289, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.2004962489009, + 'timestamp_carla': 739200, + 'timestamp_device': 1609801, + 'timestamp_stream': 739.2004962489009, + 'transform': [array([-55.32588196, 81.88571167, -0.15710142]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.29364514, 0.31379217, 3.44809651]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.924969673156738, + 'FR_Wheel_Angle': -10.197184562683105, + 'Location': array([-5.96459770e+01, 8.89403610e+01, 3.02670561e-02]), + 'Rotation': array([ -0.55868214, -142.59864807, -0.62240595]), + 'Velocity': array([0.55794412, 0.30726922, 0.01707801]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965576171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.63443756]), + 'frame': 21650, + 'frame_number': 21650, + 'framesequence': 87293, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.2341513521969, + 'timestamp_carla': 739233, + 'timestamp_device': 1609834, + 'timestamp_stream': 739.2341513521969, + 'transform': [array([-55.32588196, 81.88571167, -0.15709753]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.29585609, 0.26511231, 2.57566833]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.845691680908203, + 'FR_Wheel_Angle': -11.355127334594727, + 'Location': array([-5.95756569e+01, 8.89855270e+01, 3.26327048e-02]), + 'Rotation': array([ -0.55853188, -142.25396729, -0.54730231]), + 'Velocity': array([0.52351946, 0.31917188, 0.01734817]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63521576]), + 'frame': 21651, + 'frame_number': 21651, + 'framesequence': 87297, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.2684659510851, + 'timestamp_carla': 739267, + 'timestamp_device': 1609867, + 'timestamp_stream': 739.2684659510851, + 'transform': [array([-55.32588196, 81.88571167, -0.15710071]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.65683621, 0.33740747, 2.90510821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.877120971679688, + 'FR_Wheel_Angle': -11.09151840209961, + 'Location': array([-5.95085373e+01, 8.90289307e+01, 3.47008407e-02]), + 'Rotation': array([ -0.57071006, -141.90365601, -0.45907584]), + 'Velocity': array([0.51311857, 0.29816771, 0.01177931]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966552734375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63560486]), + 'frame': 21652, + 'frame_number': 21652, + 'framesequence': 87301, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.3000275492668, + 'timestamp_carla': 739299, + 'timestamp_device': 1609901, + 'timestamp_stream': 739.3000275492668, + 'transform': [array([-55.32588196, 81.88571167, -0.1570833 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.19400214, 0.29237002, 2.52992058]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.279043197631836, + 'FR_Wheel_Angle': -11.18260669708252, + 'Location': array([-5.94420547e+01, 8.90718155e+01, 3.57662477e-02]), + 'Rotation': array([ -0.57415932, -141.57221985, -0.38693234]), + 'Velocity': array([0.52538055, 0.31880185, 0.00464674]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63529205]), + 'frame': 21653, + 'frame_number': 21653, + 'framesequence': 87305, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.3341101519763, + 'timestamp_carla': 739333, + 'timestamp_device': 1609934, + 'timestamp_stream': 739.3341101519763, + 'transform': [array([-55.32588196, 81.88571167, -0.15709181]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.36831963, -0.12239671, 2.53710175]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.445233345031738, + 'FR_Wheel_Angle': -11.06939697265625, + 'Location': array([-5.93740425e+01, 8.91158371e+01, 3.57907005e-02]), + 'Rotation': array([ -0.56426924, -141.25505066, -0.39236441]), + 'Velocity': array([0.50983024, 0.31291088, 0.00158454]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968505859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63703156]), + 'frame': 21654, + 'frame_number': 21654, + 'framesequence': 87309, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.3685485497117, + 'timestamp_carla': 739368, + 'timestamp_device': 1609967, + 'timestamp_stream': 739.3685485497117, + 'transform': [array([-55.32588196, 81.88571167, -0.15709998]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00348804, -0.08935349, 2.76900434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.49839973449707, + 'FR_Wheel_Angle': -11.135651588439941, + 'Location': array([-5.93077736e+01, 8.91596985e+01, 3.63656878e-02]), + 'Rotation': array([ -0.55443376, -140.93243408, -0.41513056]), + 'Velocity': array([0.50651687, 0.31624648, 0.00869349]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63617706]), + 'frame': 21655, + 'frame_number': 21655, + 'framesequence': 87313, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.3997119516134, + 'timestamp_carla': 739399, + 'timestamp_device': 1610001, + 'timestamp_stream': 739.3997119516134, + 'transform': [array([-55.32588196, 81.88571167, -0.15708178]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.39089999, -0.132137 , 2.46317959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.453836441040039, + 'FR_Wheel_Angle': -11.1311616897583, + 'Location': array([-5.92419968e+01, 8.92035751e+01, 3.72082815e-02]), + 'Rotation': array([ -0.54476905, -140.61875916, -0.44244376]), + 'Velocity': array([0.5048157 , 0.31883693, 0.00522261]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63536072]), + 'frame': 21656, + 'frame_number': 21656, + 'framesequence': 87317, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.4349764510989, + 'timestamp_carla': 739434, + 'timestamp_device': 1610034, + 'timestamp_stream': 739.4349764510989, + 'transform': [array([-55.32588196, 81.88571167, -0.15710215]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.22636686, 0.20842206, 2.4182179 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.45573616027832, + 'FR_Wheel_Angle': -11.132513999938965, + 'Location': array([-5.91767769e+01, 8.92475967e+01, 3.78378555e-02]), + 'Rotation': array([ -0.51190215, -140.31536865, -0.46087649]), + 'Velocity': array([0.49704757, 0.31647721, 0.00844588]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968505859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63718414]), + 'frame': 21657, + 'frame_number': 21657, + 'framesequence': 87321, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.4683375507593, + 'timestamp_carla': 739467, + 'timestamp_device': 1610067, + 'timestamp_stream': 739.4683375507593, + 'transform': [array([-55.32588196, 81.88571167, -0.15709856]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.13175106, 0.31268683, 2.46950078]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.454940795898438, + 'FR_Wheel_Angle': -11.131226539611816, + 'Location': array([-5.91140251e+01, 8.92905731e+01, 3.84791084e-02]), + 'Rotation': array([ -0.48044232, -140.01622009, -0.43988034]), + 'Velocity': array([0.49498507, 0.31575862, 0.00444207]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63514709]), + 'frame': 21658, + 'frame_number': 21658, + 'framesequence': 87325, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.5023089498281, + 'timestamp_carla': 739501, + 'timestamp_device': 1610101, + 'timestamp_stream': 739.5023089498281, + 'transform': [array([-55.32588196, 81.88571167, -0.15710112]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.14714734, 0.3264012 , 2.71085572]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.44245719909668, + 'FR_Wheel_Angle': -11.12122631072998, + 'Location': array([-5.90461121e+01, 8.93375397e+01, 3.88374999e-02]), + 'Rotation': array([ -0.46126997, -139.69358826, -0.39779654]), + 'Velocity': array([0.54945326, 0.35576826, 0.00379558]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63550568]), + 'frame': 21659, + 'frame_number': 21659, + 'framesequence': 87329, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.5360900498927, + 'timestamp_carla': 739535, + 'timestamp_device': 1610134, + 'timestamp_stream': 739.5360900498927, + 'transform': [array([-55.32588196, 81.88571167, -0.15710112]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.01728805, 0.28443828, 2.67524338]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.446211814880371, + 'FR_Wheel_Angle': -11.123950958251953, + 'Location': array([-5.89764633e+01, 8.93862000e+01, 3.91879156e-02]), + 'Rotation': array([ -0.43573189, -139.35774231, -0.35946646]), + 'Velocity': array([0.52689523, 0.34565634, 0.00521197]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63524628]), + 'frame': 21660, + 'frame_number': 21660, + 'framesequence': 87333, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.5712380521, + 'timestamp_carla': 739570, + 'timestamp_device': 1610167, + 'timestamp_stream': 739.5712380521, + 'transform': [array([-55.32588196, 81.88571167, -0.15711196]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.02456326, -0.02346697, 2.64829254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.466322898864746, + 'FR_Wheel_Angle': -9.073193550109863, + 'Location': array([-5.89087448e+01, 8.94338837e+01, 3.92501354e-02]), + 'Rotation': array([ -0.42782253, -139.0302887 , -0.34674063]), + 'Velocity': array([ 0.52054715, 0.34626922, -0.00134567]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.966064453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63524628]), + 'frame': 21661, + 'frame_number': 21661, + 'framesequence': 87337, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.5985920503736, + 'timestamp_carla': 739598, + 'timestamp_device': 1610201, + 'timestamp_stream': 739.5985920503736, + 'transform': [array([-55.32588196, 81.88571167, -0.15712595]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.18336868, 0.23457275, 1.54635346]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.509711265563965, + 'FR_Wheel_Angle': -6.614040851593018, + 'Location': array([-5.88424416e+01, 8.94831009e+01, 3.90405916e-02]), + 'Rotation': array([ -0.42899048, -138.77206421, -0.33392325]), + 'Velocity': array([5.04507601e-01, 3.77610266e-01, 3.63206869e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.965087890625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51464844, 117.6341629 ]), + 'frame': 21662, + 'frame_number': 21662, + 'framesequence': 87341, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.6352950520813, + 'timestamp_carla': 739634, + 'timestamp_device': 1610234, + 'timestamp_stream': 739.6352950520813, + 'transform': [array([-55.32588196, 81.88571167, -0.15713783]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.1022746 , 0.3117829 , 1.92843103]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.238518714904785, + 'FR_Wheel_Angle': -8.283499717712402, + 'Location': array([-5.87758713e+01, 8.95351639e+01, 3.92169468e-02]), + 'Rotation': array([ -0.41058314, -138.56646729, -0.29376218]), + 'Velocity': array([0.50989765, 0.37309924, 0.00362792]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.964111328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63276672]), + 'frame': 21663, + 'frame_number': 21663, + 'framesequence': 87345, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.6711576506495, + 'timestamp_carla': 739670, + 'timestamp_device': 1610267, + 'timestamp_stream': 739.6711576506495, + 'transform': [array([-55.32588196, 81.88571167, -0.15713534]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.25034338, 0.20477767, 1.64034283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.85666561126709, + 'FR_Wheel_Angle': -7.418310642242432, + 'Location': array([-5.87100906e+01, 8.95858765e+01, 3.96648310e-02]), + 'Rotation': array([ -0.38326922, -138.33459473, -0.26467893]), + 'Velocity': array([0.49118355, 0.36949268, 0.00784231]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.963134765625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51367188, 117.63157654]), + 'frame': 21664, + 'frame_number': 21664, + 'framesequence': 87349, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.7051002494991, + 'timestamp_carla': 739704, + 'timestamp_device': 1610301, + 'timestamp_stream': 739.7051002494991, + 'transform': [array([-55.32588196, 81.88571167, -0.15711761]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.39408541, 0.1562544 , 1.71898735]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.483776092529297, + 'FR_Wheel_Angle': -7.757381916046143, + 'Location': array([-5.86459770e+01, 8.96363907e+01, 4.06093858e-02]), + 'Rotation': array([ -0.33474073, -138.13270569, -0.28228751]), + 'Velocity': array([0.48174953, 0.36640093, 0.01025311]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.963134765625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51367188, 117.63182831]), + 'frame': 21665, + 'frame_number': 21665, + 'framesequence': 87353, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.7342871502042, + 'timestamp_carla': 739733, + 'timestamp_device': 1610334, + 'timestamp_stream': 739.7342871502042, + 'transform': [array([-55.32588196, 81.88571167, -0.15714458]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.01796756, -0.00931583, 1.76510751]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.280426979064941, + 'FR_Wheel_Angle': -7.7172160148620605, + 'Location': array([-5.85842400e+01, 8.96851273e+01, 4.12059687e-02]), + 'Rotation': array([ -0.30935973, -137.92741394, -0.28915402]), + 'Velocity': array([4.84705985e-01, 3.67430836e-01, 7.83061987e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96435546875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51464844, 117.63359833]), + 'frame': 21666, + 'frame_number': 21666, + 'framesequence': 87357, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.7683286517859, + 'timestamp_carla': 739767, + 'timestamp_device': 1610367, + 'timestamp_stream': 739.7683286517859, + 'transform': [array([-55.32588196, 81.88571167, -0.15712169]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.04213744, -0.01849217, 1.78573573]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.288185119628906, + 'FR_Wheel_Angle': -7.676723957061768, + 'Location': array([-5.85204315e+01, 8.97356491e+01, 4.10177112e-02]), + 'Rotation': array([ -0.31234452, -137.71107483, -0.2846069 ]), + 'Velocity': array([ 0.49045202, 0.37343681, -0.00201476]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96240234375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63090515]), + 'frame': 21667, + 'frame_number': 21667, + 'framesequence': 87361, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.8019742518663, + 'timestamp_carla': 739801, + 'timestamp_device': 1610401, + 'timestamp_stream': 739.8019742518663, + 'transform': [array([-55.32588196, 81.88571167, -0.15710524]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.45889893, -0.20465244, 1.69595361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.288975715637207, + 'FR_Wheel_Angle': -7.677391529083252, + 'Location': array([-5.84559250e+01, 8.97870941e+01, 4.07774635e-02]), + 'Rotation': array([ -0.31323245, -137.48770142, -0.28347772]), + 'Velocity': array([0.48982257, 0.37810379, 0.00210559]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.964111328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51367188, 117.63319397]), + 'frame': 21668, + 'frame_number': 21668, + 'framesequence': 87365, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.8346804492176, + 'timestamp_carla': 739834, + 'timestamp_device': 1610434, + 'timestamp_stream': 739.8346804492176, + 'transform': [array([-55.32588196, 81.88571167, -0.15708944]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.92081636, -0.15944137, 1.52933967]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.291836738586426, + 'FR_Wheel_Angle': -7.681528091430664, + 'Location': array([-5.83929253e+01, 8.98379211e+01, 4.16008271e-02]), + 'Rotation': array([ -0.26364529, -137.29820251, -0.38211051]), + 'Velocity': array([0.46499136, 0.37264225, 0.01289352]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63483429]), + 'frame': 21669, + 'frame_number': 21669, + 'framesequence': 87369, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.8686364516616, + 'timestamp_carla': 739868, + 'timestamp_device': 1610467, + 'timestamp_stream': 739.8686364516616, + 'transform': [array([-55.32588196, 81.88571167, -0.15708944]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.76586384, 0.10610351, 1.62868845]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.282157897949219, + 'FR_Wheel_Angle': -7.672144412994385, + 'Location': array([-5.83276634e+01, 8.98917770e+01, 4.32392396e-02]), + 'Rotation': array([ -0.18981777, -137.08068848, -0.46228018]), + 'Velocity': array([0.52072877, 0.42364904, 0.01705933]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63641357]), + 'frame': 21670, + 'frame_number': 21670, + 'framesequence': 87373, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.8987884521484, + 'timestamp_carla': 739898, + 'timestamp_device': 1610501, + 'timestamp_stream': 739.8987884521484, + 'transform': [array([-55.32588196, 81.88571167, -0.15706569]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.14984977, 0.36716071, 1.77303958]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.278761863708496, + 'FR_Wheel_Angle': -7.666131496429443, + 'Location': array([-5.82613564e+01, 8.99466019e+01, 4.40478399e-02]), + 'Rotation': array([ -0.15520921, -136.85739136, -0.43569946]), + 'Velocity': array([0.49923149, 0.39561993, 0.004131 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63641357]), + 'frame': 21671, + 'frame_number': 21671, + 'framesequence': 87377, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.9329589493573, + 'timestamp_carla': 739932, + 'timestamp_device': 1610534, + 'timestamp_stream': 739.9329589493573, + 'transform': [array([-55.32588196, 81.88571167, -0.15708061]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.14968044, 0.36807618, 1.98234749]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.283894538879395, + 'FR_Wheel_Angle': -7.331226825714111, + 'Location': array([-5.81909943e+01, 9.00049286e+01, 4.43517976e-02]), + 'Rotation': array([ -0.13711604, -136.60688782, -0.38861081]), + 'Velocity': array([0.53860325, 0.42629799, 0.00304352]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.97021484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15527344, 10474.51660156, 117.63879395]), + 'frame': 21672, + 'frame_number': 21672, + 'framesequence': 87381, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.965615849942, + 'timestamp_carla': 739965, + 'timestamp_device': 1610567, + 'timestamp_stream': 739.965615849942, + 'transform': [array([-55.32588196, 81.88571167, -0.1570788 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.13726656, -0.01547288, 1.26148033]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.4102554321289062, + 'FR_Wheel_Angle': -2.3488454818725586, + 'Location': array([-5.81221733e+01, 9.00628815e+01, 4.47238050e-02]), + 'Rotation': array([-1.10505626e-01, -1.36403702e+02, -4.08203125e-01]), + 'Velocity': array([0.50976682, 0.43390289, 0.00177921]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63729858]), + 'frame': 21673, + 'frame_number': 21673, + 'framesequence': 87385, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 739.9990098513663, + 'timestamp_carla': 739998, + 'timestamp_device': 1610601, + 'timestamp_stream': 739.9990098513663, + 'transform': [array([-55.32588196, 81.88571167, -0.15708415]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.03747934, -0.03194067, 0.76922959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.298065185546875, + 'FR_Wheel_Angle': -4.755426406860352, + 'Location': array([-5.80553322e+01, 9.01233597e+01, 4.46560942e-02]), + 'Rotation': array([-1.07268117e-01, -1.36313080e+02, -4.11895752e-01]), + 'Velocity': array([ 0.49702224, 0.44471851, -0.00107988]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.51660156, 117.63748169]), + 'frame': 21674, + 'frame_number': 21674, + 'framesequence': 87389, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.0319806523621, + 'timestamp_carla': 740031, + 'timestamp_device': 1610634, + 'timestamp_stream': 740.0319806523621, + 'transform': [array([-55.32588196, 81.88571167, -0.15708415]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 4.42452170e-03, -8.73293669e-04, 1.13585877e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.15219259262085, + 'FR_Wheel_Angle': -3.6173205375671387, + 'Location': array([-5.79897308e+01, 9.01817398e+01, 4.44792435e-02]), + 'Rotation': array([-1.06414340e-01, -1.36178528e+02, -4.16107267e-01]), + 'Velocity': array([ 0.50644326, 0.4399403 , -0.0015433 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96826171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63694763]), + 'frame': 21675, + 'frame_number': 21675, + 'framesequence': 87393, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.0647180490196, + 'timestamp_carla': 740064, + 'timestamp_device': 1610667, + 'timestamp_stream': 740.0647180490196, + 'transform': [array([-55.32588196, 81.88571167, -0.15708415]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.02060786, 0.04608671, 0.92076182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.188944339752197, + 'FR_Wheel_Angle': -4.15701961517334, + 'Location': array([-5.79220428e+01, 9.02427292e+01, 4.42856885e-02]), + 'Rotation': array([-1.04583852e-01, -1.36059952e+02, -4.09301788e-01]), + 'Velocity': array([ 0.50383711, 0.44577062, -0.00121922]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96826171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63694763]), + 'frame': 21676, + 'frame_number': 21676, + 'framesequence': 87397, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.0986669510603, + 'timestamp_carla': 740098, + 'timestamp_device': 1610701, + 'timestamp_stream': 740.0986669510603, + 'transform': [array([-55.32588196, 81.88571167, -0.15709345]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00954206, -0.04074118, 1.03310645]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.072804927825928, + 'FR_Wheel_Angle': -3.949998140335083, + 'Location': array([-5.78566208e+01, 9.03016968e+01, 4.41088378e-02]), + 'Rotation': array([-1.04802415e-01, -1.35939133e+02, -4.10827637e-01]), + 'Velocity': array([ 0.49882796, 0.44184223, -0.00181032]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96826171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63694763]), + 'frame': 21677, + 'frame_number': 21677, + 'framesequence': 87401, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.1325986497104, + 'timestamp_carla': 740132, + 'timestamp_device': 1610734, + 'timestamp_stream': 740.1325986497104, + 'transform': [array([-55.32588196, 81.88571167, -0.15709883]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00838271, -0.04094112, 1.00779533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.139565944671631, + 'FR_Wheel_Angle': -3.97912335395813, + 'Location': array([-5.77911797e+01, 9.03609924e+01, 4.38818261e-02]), + 'Rotation': array([-1.07029058e-01, -1.35818817e+02, -4.13970917e-01]), + 'Velocity': array([ 0.49964949, 0.44457346, -0.00162004]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63601685]), + 'frame': 21678, + 'frame_number': 21678, + 'framesequence': 87405, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.1656717509031, + 'timestamp_carla': 740165, + 'timestamp_device': 1610767, + 'timestamp_stream': 740.1656717509031, + 'transform': [array([-55.32588196, 81.88571167, -0.15709548]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.0106001 , 0.01390526, 1.00699854]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.1381144523620605, + 'FR_Wheel_Angle': -3.978891372680664, + 'Location': array([-5.77246628e+01, 9.04215393e+01, 4.36801799e-02]), + 'Rotation': array([-1.07268117e-01, -1.35694672e+02, -4.12750334e-01]), + 'Velocity': array([ 0.50171739, 0.44838625, -0.00101491]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63547516]), + 'frame': 21679, + 'frame_number': 21679, + 'framesequence': 87409, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.1983609497547, + 'timestamp_carla': 740197, + 'timestamp_device': 1610801, + 'timestamp_stream': 740.1983609497547, + 'transform': [array([-55.32588196, 81.88571167, -0.1570909 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.11184094, 0.22255716, 0.99065584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.138134002685547, + 'FR_Wheel_Angle': -3.979290723800659, + 'Location': array([-5.76583443e+01, 9.04821930e+01, 4.35375497e-02]), + 'Rotation': array([-1.05342001e-01, -1.35571243e+02, -4.07562286e-01]), + 'Velocity': array([0.50239533, 0.451437 , 0.00069053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63581085]), + 'frame': 21680, + 'frame_number': 21680, + 'framesequence': 87413, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.2319998517632, + 'timestamp_carla': 740231, + 'timestamp_device': 1610834, + 'timestamp_stream': 740.2319998517632, + 'transform': [array([-55.32588196, 81.88571167, -0.15709543]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.16644368, 0.47225896, 0.93490493]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.138991355895996, + 'FR_Wheel_Angle': -3.9797704219818115, + 'Location': array([-5.75930634e+01, 9.05425568e+01, 4.38604616e-02]), + 'Rotation': array([-8.12382624e-02, -1.35450043e+02, -3.55957001e-01]), + 'Velocity': array([0.49162641, 0.44217178, 0.00527567]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63626862]), + 'frame': 21681, + 'frame_number': 21681, + 'framesequence': 87417, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.2666006498039, + 'timestamp_carla': 740266, + 'timestamp_device': 1610867, + 'timestamp_stream': 740.2666006498039, + 'transform': [array([-55.32588196, 81.88571167, -0.15710565]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.16633545, 0.45703781, 0.941984 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.139060020446777, + 'FR_Wheel_Angle': -3.980178117752075, + 'Location': array([-5.75289536e+01, 9.06019974e+01, 4.43553068e-02]), + 'Rotation': array([-5.40746041e-02, -1.35333115e+02, -3.00842196e-01]), + 'Velocity': array([0.49003631, 0.44248807, 0.00509169]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.967041015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63581848]), + 'frame': 21682, + 'frame_number': 21682, + 'framesequence': 87421, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.2987526506186, + 'timestamp_carla': 740298, + 'timestamp_device': 1610901, + 'timestamp_stream': 740.2987526506186, + 'transform': [array([-55.32588196, 81.88571167, -0.15709318]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.01596412, -0.04617845, 0.99963111]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.138950824737549, + 'FR_Wheel_Angle': -3.97969651222229, + 'Location': array([-5.74643936e+01, 9.06617584e+01, 4.44801971e-02]), + 'Rotation': array([-4.55983393e-02, -1.35214569e+02, -2.86956757e-01]), + 'Velocity': array([ 0.48801315, 0.4436425 , -0.00127844]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63479614]), + 'frame': 21683, + 'frame_number': 21683, + 'framesequence': 87425, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.3334304504097, + 'timestamp_carla': 740332, + 'timestamp_device': 1610934, + 'timestamp_stream': 740.3334304504097, + 'transform': [array([-55.32588196, 81.88571167, -0.15710486]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([-0.00111736, -0.03811583, 0.86338323]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.146665334701538, + 'FR_Wheel_Angle': -0.45013168454170227, + 'Location': array([-5.73994904e+01, 9.07221680e+01, 4.42281626e-02]), + 'Rotation': array([-4.87129055e-02, -1.35096359e+02, -2.91168213e-01]), + 'Velocity': array([ 0.48635039, 0.44894212, -0.00199648]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.63603973]), + 'frame': 21684, + 'frame_number': 21684, + 'framesequence': 87429, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.3664531521499, + 'timestamp_carla': 740365, + 'timestamp_device': 1610967, + 'timestamp_stream': 740.3664531521499, + 'transform': [array([-55.32588196, 81.88571167, -0.15709856]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([ 0.32198936, 0.82863802, -0.46625245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.4059524536132812, + 'FR_Wheel_Angle': 0.5764979720115662, + 'Location': array([-5.73372269e+01, 9.07840958e+01, 4.43420298e-02]), + 'Rotation': array([-3.01484540e-02, -1.35090057e+02, -2.42126465e-01]), + 'Velocity': array([0.45193449, 0.46566355, 0.00761326]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.9658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51464844, 117.63487244]), + 'frame': 21685, + 'frame_number': 21685, + 'framesequence': 87433, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 740.398275051266, + 'timestamp_carla': 740397, + 'timestamp_device': 1611001, + 'timestamp_stream': 740.398275051266, + 'transform': [array([-55.32588196, 81.88571167, -0.1570867 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.05962272e-03])]} +{'AngularVelocity': array([0.27932188, 0.83887446, 0.13126898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7312617897987366, + 'FR_Wheel_Angle': -0.35365089774131775, + 'Location': array([-5.72782364e+01, 9.08442001e+01, 4.53188233e-02]), + 'Rotation': array([ 1.96436234e-02, -1.35107712e+02, -1.46453843e-01]), + 'Velocity': array([0.44751197, 0.4387778 , 0.01102553]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.96630859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.515625 , 117.63550568]), + 'frame': 21686, + 'frame_number': 21686, + 'framesequence': 87437, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0317387655377388, + 'timestamp': 740.4325373508036, + 'timestamp_carla': 740431, + 'timestamp_device': 1611034, + 'timestamp_stream': 740.4325373508036, + 'transform': [array([-55.32508087, 81.88529968, -0.15685722]), + array([-4.74015111e-03, -1.17378571e+02, 7.04192463e-03])]} +{'AngularVelocity': array([ 0.2900804 , 0.80748928, -0.12704046]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3184894323348999, + 'FR_Wheel_Angle': 0.1204560324549675, + 'Location': array([-5.72203598e+01, 9.09023819e+01, 4.63554673e-02]), + 'Rotation': array([ 6.76735118e-02, -1.35106155e+02, -5.07507175e-02]), + 'Velocity': array([0.42933482, 0.42979798, 0.01020699]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.968017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15429688, 10474.515625 , 117.63668823]), + 'frame': 21687, + 'frame_number': 21687, + 'framesequence': 87441, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.035706110298633575, + 'timestamp': 740.4666615501046, + 'timestamp_carla': 740466, + 'timestamp_device': 1611067, + 'timestamp_stream': 740.4666615501046, + 'transform': [array([-55.3240509 , 81.88476562, -0.15674771]), + array([-4.74015111e-03, -1.17378571e+02, 6.55698124e-03])]} +{'AngularVelocity': array([0.0084786 , 0.08778722, 0.0325017 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0811435654759407, + 'FR_Wheel_Angle': 0.027893604710698128, + 'Location': array([-5.71638107e+01, 9.09593277e+01, 4.71362583e-02]), + 'Rotation': array([ 1.02678224e-01, -1.35111404e+02, 1.61464158e-02]), + 'Velocity': array([0.42997989, 0.42537227, 0.00224495]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.995849609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.10058594, 10474.48828125, 117.57810974]), + 'frame': 21688, + 'frame_number': 21688, + 'framesequence': 87445, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.035706110298633575, + 'timestamp': 740.4987301491201, + 'timestamp_carla': 740498, + 'timestamp_device': 1611101, + 'timestamp_stream': 740.4987301491201, + 'transform': [array([-55.32313919, 81.8842926 , -0.15673561]), + array([-4.74015111e-03, -1.17378571e+02, 6.55698124e-03])]} +{'AngularVelocity': array([ 0.00434572, -0.02956142, 0.01802328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.039300061762332916, + 'FR_Wheel_Angle': -0.007606961764395237, + 'Location': array([-5.71073341e+01, 9.10155334e+01, 4.70373034e-02]), + 'Rotation': array([ 1.01926908e-01, -1.35112610e+02, 1.53353447e-02]), + 'Velocity': array([ 0.42740539, 0.42646921, -0.00192675]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.08251953125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.07519531, 10474.47558594, 117.55021667]), + 'frame': 21689, + 'frame_number': 21689, + 'framesequence': 87449, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.035706110298633575, + 'timestamp': 740.5318815521896, + 'timestamp_carla': 740531, + 'timestamp_device': 1611134, + 'timestamp_stream': 740.5318815521896, + 'transform': [array([-55.32225418, 81.88383484, -0.1567833 ]), + array([-4.74015111e-03, -1.17378571e+02, 6.75505726e-03])]} +{'AngularVelocity': array([ 0.00711634, -0.01180019, 0.00165007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015211997553706169, + 'FR_Wheel_Angle': 0.015212537720799446, + 'Location': array([-5.70502815e+01, 9.10723801e+01, 4.67796996e-02]), + 'Rotation': array([ 9.97480750e-02, -1.35113968e+02, 1.37953721e-02]), + 'Velocity': array([ 0.42855048, 0.42742771, -0.00197788]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.18603515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.07617188, 10474.4765625 , 117.55144501]), + 'frame': 21690, + 'frame_number': 21690, + 'framesequence': 87453, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.043656062334775925, + 'timestamp': 740.5665363520384, + 'timestamp_carla': 740565, + 'timestamp_device': 1611167, + 'timestamp_stream': 740.5665363520384, + 'transform': [array([-55.32138443, 81.8833847 , -0.15685864]), + array([-4.74015111e-03, -1.17378571e+02, 7.02143554e-03])]} +{'AngularVelocity': array([ 0.0197658 , 0.12731634, -0.00564542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015209468081593513, + 'FR_Wheel_Angle': 0.015210752375423908, + 'Location': array([-5.69929886e+01, 9.11299973e+01, 4.71043661e-02]), + 'Rotation': array([ 1.23278074e-01, -1.35114868e+02, 6.51819780e-02]), + 'Velocity': array([0.43224379, 0.42914709, 0.00202893]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.297119140625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.0859375 , 10474.48144531, 117.56256104]), + 'frame': 21691, + 'frame_number': 21691, + 'framesequence': 87457, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.05555810034275055, + 'timestamp': 740.6005468517542, + 'timestamp_carla': 740599, + 'timestamp_device': 1611201, + 'timestamp_stream': 740.6005468517542, + 'transform': [array([-55.32057571, 81.88296509, -0.15691991]), + array([-4.74015111e-03, -1.17378571e+02, 7.27415178e-03])]} +{'AngularVelocity': array([0.00480297, 0.02333079, 0.04347682]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015209371224045753, + 'FR_Wheel_Angle': 0.015212353318929672, + 'Location': array([-5.69355888e+01, 9.11871872e+01, 4.70725149e-02]), + 'Rotation': array([ 1.26413137e-01, -1.35115967e+02, 6.99096471e-02]), + 'Velocity': array([ 0.43147147, 0.43005547, -0.00094513]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.4091796875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.09765625, 10474.48730469, 117.57637024]), + 'frame': 21692, + 'frame_number': 21692, + 'framesequence': 87461, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.07142747938632965, + 'timestamp': 740.6331486515701, + 'timestamp_carla': 740632, + 'timestamp_device': 1611234, + 'timestamp_stream': 740.6331486515701, + 'transform': [array([-55.31984329, 81.88258362, -0.15696195]), + array([-4.74015111e-03, -1.17378571e+02, 7.49271689e-03])]} +{'AngularVelocity': array([ 0.00211939, -0.00086812, -0.0043531 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.015210255049169064, + 'FR_Wheel_Angle': 0.01521136611700058, + 'Location': array([-5.68775826e+01, 9.12449951e+01, 4.69068028e-02]), + 'Rotation': array([ 1.27048343e-01, -1.35116455e+02, 7.17439130e-02]), + 'Velocity': array([ 0.43435118, 0.43274778, -0.0013584 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.515380859375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.11132812, 10474.49414062, 117.59051514]), + 'frame': 21693, + 'frame_number': 21693, + 'framesequence': 87465, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.08729686588048935, + 'timestamp': 740.6658427491784, + 'timestamp_carla': 740665, + 'timestamp_device': 1611267, + 'timestamp_stream': 740.6658427491784, + 'transform': [array([-55.31913757, 81.88222504, -0.15700066]), + array([-4.74015111e-03, -1.17378571e+02, 7.67713226e-03])]} +{'AngularVelocity': array([-0.00392147, 0.0030582 , 0.04441121]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.01521041989326477, + 'FR_Wheel_Angle': 0.01521284319460392, + 'Location': array([-5.68200073e+01, 9.13023682e+01, 4.67196926e-02]), + 'Rotation': array([ 1.26966372e-01, -1.35117661e+02, 7.16041699e-02]), + 'Velocity': array([ 0.42855075, 0.42721802, -0.00133875]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.613037109375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.12402344, 10474.50097656, 117.60383606]), + 'frame': 21694, + 'frame_number': 21694, + 'framesequence': 87469, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.09126421064138412, + 'timestamp': 740.6998859494925, + 'timestamp_carla': 740699, + 'timestamp_device': 1611300, + 'timestamp_stream': 740.6998859494925, + 'transform': [array([-55.31845474, 81.88187408, -0.15704688]), + array([-4.74015111e-03, -1.17378571e+02, 7.84105714e-03])]} +{'AngularVelocity': array([ 0.00158906, -0.00055203, 0.14659016]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.11272680014371872, + 'FR_Wheel_Angle': 0.986609697341919, + 'Location': array([-5.67620773e+01, 9.13601456e+01, 4.65339944e-02]), + 'Rotation': array([ 1.26761481e-01, -1.35114868e+02, 7.14713261e-02]), + 'Velocity': array([ 0.43013927, 0.42886928, -0.00135238]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.703857421875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.13378906, 10474.50683594, 117.61475372]), + 'frame': 21695, + 'frame_number': 21695, + 'framesequence': 87473, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0952315554022789, + 'timestamp': 740.7322485521436, + 'timestamp_carla': 740731, + 'timestamp_device': 1611334, + 'timestamp_stream': 740.7322485521436, + 'transform': [array([-55.31782913, 81.88153839, -0.1570664 ]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02404161, 0.03340928, -0.90550107]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.203016757965088, + 'FR_Wheel_Angle': 5.92720890045166, + 'Location': array([-5.67057953e+01, 9.14174271e+01, 4.63794991e-02]), + 'Rotation': array([ 1.26338005e-01, -1.35156479e+02, 7.41180927e-02]), + 'Velocity': array([ 0.41584697, 0.44596347, -0.00115257]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.789794921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14160156, 10474.50976562, 117.62327576]), + 'frame': 21696, + 'frame_number': 21696, + 'framesequence': 87477, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0952315554022789, + 'timestamp': 740.7656168490648, + 'timestamp_carla': 740765, + 'timestamp_device': 1611367, + 'timestamp_stream': 740.7656168490648, + 'transform': [array([-55.31721497, 81.88122559, -0.15706977]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([-0.02264501, -0.01123292, -0.88434231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.5555148124694824, + 'FR_Wheel_Angle': 3.2958037853240967, + 'Location': array([-5.66499100e+01, 9.14776917e+01, 4.62042131e-02]), + 'Rotation': array([ 1.26536071e-01, -1.35296692e+02, 7.40109608e-02]), + 'Velocity': array([ 0.41144744, 0.4503158 , -0.00124418]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.8681640625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51269531, 117.63063049]), + 'frame': 21697, + 'frame_number': 21697, + 'framesequence': 87481, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0952315554022789, + 'timestamp': 740.7999254502356, + 'timestamp_carla': 740799, + 'timestamp_device': 1611400, + 'timestamp_stream': 740.7999254502356, + 'transform': [array([-55.31661987, 81.88091278, -0.15707912]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01105081, 0.00591079, -0.84696811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.126313209533691, + 'FR_Wheel_Angle': 4.539848804473877, + 'Location': array([-5.65944290e+01, 9.15359344e+01, 4.60412502e-02]), + 'Rotation': array([ 1.26822948e-01, -1.35397110e+02, 7.10605606e-02]), + 'Velocity': array([ 0.41710067, 0.44640011, -0.00132926]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3256.936279296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.63030243]), + 'frame': 21698, + 'frame_number': 21698, + 'framesequence': 87485, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0952315554022789, + 'timestamp': 740.833089351654, + 'timestamp_carla': 740832, + 'timestamp_device': 1611434, + 'timestamp_stream': 740.833089351654, + 'transform': [array([-55.31606293, 81.88062286, -0.15707564]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([-0.00570195, 0.00545216, -0.98661983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.90523099899292, + 'FR_Wheel_Angle': 3.990565061569214, + 'Location': array([-5.65384407e+01, 9.15951538e+01, 4.58768755e-02]), + 'Rotation': array([ 1.26911744e-01, -1.35512878e+02, 7.10231960e-02]), + 'Velocity': array([ 0.41145265, 0.44293594, -0.00103101]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.0029296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.6293869 ]), + 'frame': 21699, + 'frame_number': 21699, + 'framesequence': 87489, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0952315554022789, + 'timestamp': 740.8652507513762, + 'timestamp_carla': 740864, + 'timestamp_device': 1611467, + 'timestamp_stream': 740.8652507513762, + 'transform': [array([-55.31554413, 81.88035583, -0.15706655]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 4.70956205e-04, 1.23412795e-02, -9.55988765e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.064099311828613, + 'FR_Wheel_Angle': 4.1650896072387695, + 'Location': array([-5.64838676e+01, 9.16523438e+01, 4.57185246e-02]), + 'Rotation': array([ 1.27997741e-01, -1.35621643e+02, 7.00368136e-02]), + 'Velocity': array([ 0.39843047, 0.42574221, -0.00105232]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.06640625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62973785]), + 'frame': 21700, + 'frame_number': 21700, + 'framesequence': 87493, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0952315554022789, + 'timestamp': 740.8993338495493, + 'timestamp_carla': 740898, + 'timestamp_device': 1611500, + 'timestamp_stream': 740.8993338495493, + 'transform': [array([-55.3150177 , 81.88008881, -0.15707567]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00708489, 0.00908825, -0.81032574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.014184474945068, + 'FR_Wheel_Angle': 4.173249244689941, + 'Location': array([-5.64285278e+01, 9.17102203e+01, 4.55575846e-02]), + 'Rotation': array([ 1.27273738e-01, -1.35729172e+02, 6.98941126e-02]), + 'Velocity': array([ 0.40940434, 0.43651313, -0.0014056 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.125732421875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63065338]), + 'frame': 21701, + 'frame_number': 21701, + 'framesequence': 87497, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0952315554022789, + 'timestamp': 740.9309732504189, + 'timestamp_carla': 740930, + 'timestamp_device': 1611534, + 'timestamp_stream': 740.9309732504189, + 'transform': [array([-55.31452942, 81.87982941, -0.15706347]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.0060419 , 0.00753596, -0.80956173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.990530490875244, + 'FR_Wheel_Angle': 4.150449752807617, + 'Location': array([-5.63737602e+01, 9.17673111e+01, 4.53958400e-02]), + 'Rotation': array([ 1.27587929e-01, -1.35838257e+02, 6.96326047e-02]), + 'Velocity': array([ 0.40518734, 0.43066919, -0.00110309]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.183349609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62975311]), + 'frame': 21702, + 'frame_number': 21702, + 'framesequence': 87501, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.09919890016317368, + 'timestamp': 740.9656481519341, + 'timestamp_carla': 740964, + 'timestamp_device': 1611567, + 'timestamp_stream': 740.9656481519341, + 'transform': [array([-55.31402206, 81.87957001, -0.15707907]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01023935, 0.00396232, -0.94565642]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9903268814086914, + 'FR_Wheel_Angle': 4.15065336227417, + 'Location': array([-5.63189163e+01, 9.18242188e+01, 4.52422984e-02]), + 'Rotation': array([ 1.27164453e-01, -1.35948166e+02, 6.93725348e-02]), + 'Velocity': array([ 0.41294396, 0.43657592, -0.00125567]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.23974609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51269531, 117.63098145]), + 'frame': 21703, + 'frame_number': 21703, + 'framesequence': 87505, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.09919890016317368, + 'timestamp': 741.0010098516941, + 'timestamp_carla': 741000, + 'timestamp_device': 1611600, + 'timestamp_stream': 741.0010098516941, + 'transform': [array([-55.31352234, 81.87930298, -0.15709335]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00215952, 0.00990353, -0.91528577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9903883934020996, + 'FR_Wheel_Angle': 4.149198532104492, + 'Location': array([-5.62637863e+01, 9.18812180e+01, 4.50760536e-02]), + 'Rotation': array([ 1.27540112e-01, -1.36057846e+02, 6.91219568e-02]), + 'Velocity': array([ 0.40713504, 0.42904636, -0.00117038]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.295166015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51171875, 117.62942505]), + 'frame': 21704, + 'frame_number': 21704, + 'framesequence': 87509, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.09919890016317368, + 'timestamp': 741.0333539508283, + 'timestamp_carla': 741032, + 'timestamp_device': 1611634, + 'timestamp_stream': 741.0333539508283, + 'transform': [array([-55.31307602, 81.8790741 , -0.15707777]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00555715, 0.00916972, -0.84591454]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.989896535873413, + 'FR_Wheel_Angle': 4.150025844573975, + 'Location': array([-5.62072296e+01, 9.19394913e+01, 4.49110307e-02]), + 'Rotation': array([ 1.26986876e-01, -1.36167953e+02, 6.89969361e-02]), + 'Velocity': array([ 0.41873866, 0.43998608, -0.00132949]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.349609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14550781, 10474.51074219, 117.62800598]), + 'frame': 21705, + 'frame_number': 21705, + 'framesequence': 87513, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.10316624492406845, + 'timestamp': 741.0658565498888, + 'timestamp_carla': 741065, + 'timestamp_device': 1611667, + 'timestamp_stream': 741.0658565498888, + 'transform': [array([-55.31263733, 81.87884521, -0.15706968]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.0008989 , 0.00984932, -0.78709131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.990769147872925, + 'FR_Wheel_Angle': 4.149824619293213, + 'Location': array([-5.61513557e+01, 9.19968643e+01, 4.47505452e-02]), + 'Rotation': array([ 1.27649397e-01, -1.36278137e+02, 6.86324462e-02]), + 'Velocity': array([ 0.41343257, 0.43206549, -0.00110086]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.403076171875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51171875, 117.62957001]), + 'frame': 21706, + 'frame_number': 21706, + 'framesequence': 87517, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.10316624492406845, + 'timestamp': 741.0978531502187, + 'timestamp_carla': 741097, + 'timestamp_device': 1611700, + 'timestamp_stream': 741.0978531502187, + 'transform': [array([-55.31220627, 81.87863159, -0.15706168]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.0146687 , 0.02284209, -1.13986266]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.400055408477783, + 'FR_Wheel_Angle': 8.646528244018555, + 'Location': array([-5.60954933e+01, 9.20540771e+01, 4.45830822e-02]), + 'Rotation': array([ 1.28120676e-01, -1.36398605e+02, 6.89980090e-02]), + 'Velocity': array([ 0.40550125, 0.43073621, -0.00106628]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.45263671875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51171875, 117.63038635]), + 'frame': 21707, + 'frame_number': 21707, + 'framesequence': 87520, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.10713358968496323, + 'timestamp': 741.130352050066, + 'timestamp_carla': 741129, + 'timestamp_device': 1611725, + 'timestamp_stream': 741.130352050066, + 'transform': [array([-55.31178665, 81.87841797, -0.15706088]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01377491, 0.01303735, -2.12432766]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.607743263244629, + 'FR_Wheel_Angle': 8.514724731445312, + 'Location': array([-5.60422363e+01, 9.21117325e+01, 4.44296934e-02]), + 'Rotation': array([ 1.28202647e-01, -1.36617416e+02, 7.23587126e-02]), + 'Velocity': array([ 0.3887361 , 0.45203936, -0.00111835]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.501953125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63119507]), + 'frame': 21708, + 'frame_number': 21708, + 'framesequence': 87524, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1111009418964386, + 'timestamp': 741.1622036509216, + 'timestamp_carla': 741161, + 'timestamp_device': 1611759, + 'timestamp_stream': 741.1622036509216, + 'transform': [array([-55.31137466, 81.87820435, -0.15705653]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00219103, -0.00311976, -1.50885355]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.125890254974365, + 'FR_Wheel_Angle': 8.20491886138916, + 'Location': array([-5.59885178e+01, 9.21698914e+01, 4.42687869e-02]), + 'Rotation': array([ 1.28352910e-01, -1.36832397e+02, 6.80131689e-02]), + 'Velocity': array([ 0.40125445, 0.44238478, -0.0014395 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.550048828125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63128662]), + 'frame': 21709, + 'frame_number': 21709, + 'framesequence': 87529, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1111009418964386, + 'timestamp': 741.1988497488201, + 'timestamp_carla': 741198, + 'timestamp_device': 1611800, + 'timestamp_stream': 741.1988497488201, + 'transform': [array([-55.31092834, 81.87796783, -0.15709338]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00390153, 0.02300601, -1.99358225]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.934525489807129, + 'FR_Wheel_Angle': 8.35660457611084, + 'Location': array([-5.59296799e+01, 9.22325363e+01, 4.41108607e-02]), + 'Rotation': array([ 1.26727328e-01, -1.37059860e+02, 6.82767108e-02]), + 'Velocity': array([ 0.42476332, 0.47484207, -0.00134899]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.5966796875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51367188, 117.6317215 ]), + 'frame': 21710, + 'frame_number': 21710, + 'framesequence': 87533, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.11506828665733337, + 'timestamp': 741.2323856502771, + 'timestamp_carla': 741231, + 'timestamp_device': 1611834, + 'timestamp_stream': 741.2323856502771, + 'transform': [array([-55.31050491, 81.87775421, -0.15708694]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00269406, 0.01393698, -1.81828296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.616494655609131, + 'FR_Wheel_Angle': 8.358997344970703, + 'Location': array([-5.58733330e+01, 9.22923889e+01, 4.39417548e-02]), + 'Rotation': array([ 1.28509998e-01, -1.37283249e+02, 6.65004626e-02]), + 'Velocity': array([ 0.41994557, 0.46073219, -0.00138255]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.642822265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14453125, 10474.51171875, 117.62804413]), + 'frame': 21711, + 'frame_number': 21711, + 'framesequence': 87537, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.11903563141822815, + 'timestamp': 741.2709092497826, + 'timestamp_carla': 741270, + 'timestamp_device': 1611867, + 'timestamp_stream': 741.2709092497826, + 'transform': [array([-55.31003952, 81.8775177 , -0.15712649]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.0029022 , 0.014789 , -1.82027435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.645665645599365, + 'FR_Wheel_Angle': 8.270476341247559, + 'Location': array([-5.58166313e+01, 9.23520966e+01, 4.37711999e-02]), + 'Rotation': array([ 1.29397929e-01, -1.37505585e+02, 6.58674911e-02]), + 'Velocity': array([ 0.41253299, 0.45043528, -0.00092809]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.6904296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14550781, 10474.51171875, 117.62869263]), + 'frame': 21712, + 'frame_number': 21712, + 'framesequence': 87541, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.11903563141822815, + 'timestamp': 741.3023011498153, + 'timestamp_carla': 741301, + 'timestamp_device': 1611900, + 'timestamp_stream': 741.3023011498153, + 'transform': [array([-55.30963898, 81.87730408, -0.15708926]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01031975, 0.01241686, -1.81656837]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.695549011230469, + 'FR_Wheel_Angle': 8.310546875, + 'Location': array([-5.57605171e+01, 9.24106979e+01, 4.36041914e-02]), + 'Rotation': array([ 1.29746273e-01, -1.37726379e+02, 6.52735010e-02]), + 'Velocity': array([ 0.41230842, 0.44676325, -0.001226 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.739501953125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14257812, 10474.51171875, 117.62474823]), + 'frame': 21713, + 'frame_number': 21713, + 'framesequence': 87545, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.12300297617912292, + 'timestamp': 741.3352381512523, + 'timestamp_carla': 741334, + 'timestamp_device': 1611934, + 'timestamp_stream': 741.3352381512523, + 'transform': [array([-55.30922699, 81.87709045, -0.15707675]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01839278, 0.00830962, -1.78303826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.695924758911133, + 'FR_Wheel_Angle': 8.31218433380127, + 'Location': array([-5.57042694e+01, 9.24690323e+01, 4.34328355e-02]), + 'Rotation': array([ 1.29650638e-01, -1.37946884e+02, 6.48702607e-02]), + 'Velocity': array([ 0.41738677, 0.448856 , -0.00163504]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.78759765625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14550781, 10474.51171875, 117.628479 ]), + 'frame': 21714, + 'frame_number': 21714, + 'framesequence': 87549, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1269855797290802, + 'timestamp': 741.3693800494075, + 'timestamp_carla': 741368, + 'timestamp_device': 1611967, + 'timestamp_stream': 741.3693800494075, + 'transform': [array([-55.30880737, 81.87687683, -0.15707843]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00691429, 0.01854839, -1.76024234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.697756767272949, + 'FR_Wheel_Angle': 8.312825202941895, + 'Location': array([-5.56483727e+01, 9.25265198e+01, 4.32664007e-02]), + 'Rotation': array([ 1.30374640e-01, -1.38160233e+02, 6.41963109e-02]), + 'Velocity': array([ 0.40461192, 0.43191072, -0.00129171]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.83544921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62973785]), + 'frame': 21715, + 'frame_number': 21715, + 'framesequence': 87553, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1269855797290802, + 'timestamp': 741.4018738493323, + 'timestamp_carla': 741401, + 'timestamp_device': 1612000, + 'timestamp_stream': 741.4018738493323, + 'transform': [array([-55.30840683, 81.87665558, -0.1570674 ]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01034214, 0.01357099, -1.86607718]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.699014186859131, + 'FR_Wheel_Angle': 8.314934730529785, + 'Location': array([-5.55936432e+01, 9.25823593e+01, 4.31178175e-02]), + 'Rotation': array([ 1.30620524e-01, -1.38372284e+02, 6.37355149e-02]), + 'Velocity': array([ 0.40338123, 0.42683491, -0.00136628]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.88232421875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51269531, 117.62957764]), + 'frame': 21716, + 'frame_number': 21716, + 'framesequence': 87557, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1269855797290802, + 'timestamp': 741.4327280521393, + 'timestamp_carla': 741431, + 'timestamp_device': 1612034, + 'timestamp_stream': 741.4327280521393, + 'transform': [array([-55.30801773, 81.87644196, -0.15705077]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.11561267, -0.06290626, -1.83347428]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.685214042663574, + 'FR_Wheel_Angle': 8.300355911254883, + 'Location': array([-5.55378456e+01, 9.26387482e+01, 4.29742709e-02]), + 'Rotation': array([ 1.28188983e-01, -1.38587219e+02, 6.39717728e-02]), + 'Velocity': array([ 0.48261446, 0.50241423, -0.0012891 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.92919921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51269531, 117.63067627]), + 'frame': 21717, + 'frame_number': 21717, + 'framesequence': 87561, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.13492026925086975, + 'timestamp': 741.4656826518476, + 'timestamp_carla': 741464, + 'timestamp_device': 1612067, + 'timestamp_stream': 741.4656826518476, + 'transform': [array([-55.30760574, 81.87622833, -0.15705603]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([-0.00566554, 0.02516391, -1.92040741]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.007914543151855, + 'FR_Wheel_Angle': 9.77535629272461, + 'Location': array([-5.54738808e+01, 9.27028961e+01, 4.27910499e-02]), + 'Rotation': array([ 1.27526462e-01, -1.38836258e+02, 6.36951551e-02]), + 'Velocity': array([ 0.46106046, 0.48060939, -0.00136743]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3257.974853515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51171875, 117.63234711]), + 'frame': 21718, + 'frame_number': 21718, + 'framesequence': 87565, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.13492026925086975, + 'timestamp': 741.4982310496271, + 'timestamp_carla': 741497, + 'timestamp_device': 1612100, + 'timestamp_stream': 741.4982310496271, + 'transform': [array([-55.30718613, 81.87601471, -0.15705691]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.03187404, 0.04976025, -2.84861422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.485278129577637, + 'FR_Wheel_Angle': 14.053756713867188, + 'Location': array([-5.54135971e+01, 9.27646332e+01, 4.26130965e-02]), + 'Rotation': array([ 1.30244866e-01, -1.39124802e+02, 6.58387467e-02]), + 'Velocity': array([ 0.43100384, 0.48444986, -0.0010454 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.02099609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14941406, 10474.51171875, 117.63182831]), + 'frame': 21719, + 'frame_number': 21719, + 'framesequence': 87569, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.13492026925086975, + 'timestamp': 741.5327716507018, + 'timestamp_carla': 741532, + 'timestamp_device': 1612134, + 'timestamp_stream': 741.5327716507018, + 'transform': [array([-55.30674744, 81.8757782 , -0.15707339]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([-0.01272379, -0.0030954 , -2.78741455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.46450424194336, + 'FR_Wheel_Angle': 11.59630012512207, + 'Location': array([-5.53547058e+01, 9.28274231e+01, 4.24223617e-02]), + 'Rotation': array([ 1.31406009e-01, -1.39501877e+02, 6.37658164e-02]), + 'Velocity': array([ 0.42800951, 0.47571903, -0.00151185]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.067626953125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51171875, 117.63175201]), + 'frame': 21720, + 'frame_number': 21720, + 'framesequence': 87573, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.13888761401176453, + 'timestamp': 741.5679485499859, + 'timestamp_carla': 741567, + 'timestamp_device': 1612167, + 'timestamp_stream': 741.5679485499859, + 'transform': [array([-55.3062973 , 81.87554169, -0.157088 ]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02460317, 0.02272605, -2.64949942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.43627643585205, + 'FR_Wheel_Angle': 12.857975959777832, + 'Location': array([-5.52952957e+01, 9.28886719e+01, 4.22394834e-02]), + 'Rotation': array([ 1.31754339e-01, -1.39828369e+02, 6.11176752e-02]), + 'Velocity': array([ 0.42924488, 0.46957323, -0.00137526]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.115478515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51074219, 117.63011169]), + 'frame': 21721, + 'frame_number': 21721, + 'framesequence': 87577, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1428549587726593, + 'timestamp': 741.5992031507194, + 'timestamp_carla': 741598, + 'timestamp_device': 1612200, + 'timestamp_stream': 741.5992031507194, + 'transform': [array([-55.30587769, 81.87532806, -0.15706728]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.00973132, 0.01441962, -2.6383884 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.9845552444458, + 'FR_Wheel_Angle': 12.338114738464355, + 'Location': array([-5.52382126e+01, 9.29473801e+01, 4.20892984e-02]), + 'Rotation': array([ 1.32464677e-01, -1.40163284e+02, 6.00690283e-02]), + 'Velocity': array([ 0.42137462, 0.45631212, -0.00099562]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.1650390625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.50976562, 117.62865448]), + 'frame': 21722, + 'frame_number': 21722, + 'framesequence': 87581, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1428549587726593, + 'timestamp': 741.6326347514987, + 'timestamp_carla': 741631, + 'timestamp_device': 1612234, + 'timestamp_stream': 741.6326347514987, + 'transform': [array([-55.30542755, 81.87509918, -0.15707012]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02055368, 0.01752695, -2.69347262]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.176758766174316, + 'FR_Wheel_Angle': 12.429981231689453, + 'Location': array([-5.51793633e+01, 9.30070190e+01, 4.19174843e-02]), + 'Rotation': array([ 1.32505655e-01, -1.40499634e+02, 5.91560304e-02]), + 'Velocity': array([ 0.42416966, 0.45456132, -0.00097477]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.21484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51074219, 117.6307373 ]), + 'frame': 21723, + 'frame_number': 21723, + 'framesequence': 87585, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.15078964829444885, + 'timestamp': 741.6644790507853, + 'timestamp_carla': 741663, + 'timestamp_device': 1612267, + 'timestamp_stream': 741.6644790507853, + 'transform': [array([-55.30498886, 81.87487793, -0.15706076]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01545706, 0.01837146, -2.67553425]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.146163940429688, + 'FR_Wheel_Angle': 12.470769882202148, + 'Location': array([-5.51218643e+01, 9.30646439e+01, 4.17628773e-02]), + 'Rotation': array([ 1.32662758e-01, -1.40828217e+02, 5.82678877e-02]), + 'Velocity': array([ 0.42499396, 0.44916815, -0.00109158]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51074219, 117.63046265]), + 'frame': 21724, + 'frame_number': 21724, + 'framesequence': 87589, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.15475699305534363, + 'timestamp': 741.6984360516071, + 'timestamp_carla': 741697, + 'timestamp_device': 1612300, + 'timestamp_stream': 741.6984360516071, + 'transform': [array([-55.30451965, 81.87464905, -0.15707107]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01906233, 0.01685915, -2.69923401]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.14321231842041, + 'FR_Wheel_Angle': 12.469325065612793, + 'Location': array([-5.50633774e+01, 9.31226349e+01, 4.15843092e-02]), + 'Rotation': array([ 1.32758379e-01, -1.41160736e+02, 5.76924048e-02]), + 'Velocity': array([ 0.4288514 , 0.44882002, -0.00121703]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.314697265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51171875, 117.63140106]), + 'frame': 21725, + 'frame_number': 21725, + 'framesequence': 87593, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.15475699305534363, + 'timestamp': 741.732767149806, + 'timestamp_carla': 741731, + 'timestamp_device': 1612334, + 'timestamp_stream': 741.732767149806, + 'transform': [array([-55.30403137, 81.87438965, -0.15707983]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01453329, 0.02042605, -2.62925816]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.14341926574707, + 'FR_Wheel_Angle': 12.471256256103516, + 'Location': array([-5.50045700e+01, 9.31801910e+01, 4.14256565e-02]), + 'Rotation': array([ 1.32963285e-01, -1.41487381e+02, 5.68770617e-02]), + 'Velocity': array([ 0.43131614, 0.44565704, -0.00095829]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.3671875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51269531, 117.63037109]), + 'frame': 21726, + 'frame_number': 21726, + 'framesequence': 87597, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 741.7657305523753, + 'timestamp_carla': 741764, + 'timestamp_device': 1612367, + 'timestamp_stream': 741.7657305523753, + 'transform': [array([-55.30355453, 81.87413788, -0.15707423]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02185749, 0.01931303, -2.66682863]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.143850326538086, + 'FR_Wheel_Angle': 12.47178840637207, + 'Location': array([-5.49450760e+01, 9.32378082e+01, 4.12409119e-02]), + 'Rotation': array([ 1.33427739e-01, -1.41821625e+02, 5.61681837e-02]), + 'Velocity': array([ 0.43284556, 0.44295123, -0.00137788]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.4208984375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51171875, 117.62950134]), + 'frame': 21727, + 'frame_number': 21727, + 'framesequence': 87601, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 741.7997734509408, + 'timestamp_carla': 741798, + 'timestamp_device': 1612400, + 'timestamp_stream': 741.7997734509408, + 'transform': [array([-55.30304718, 81.87387848, -0.15707895]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01142561, 0.01628757, -2.70981216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.14455795288086, + 'FR_Wheel_Angle': 12.47260570526123, + 'Location': array([-5.48859444e+01, 9.32943954e+01, 4.10757326e-02]), + 'Rotation': array([ 1.33666798e-01, -1.42153305e+02, 5.53870760e-02]), + 'Velocity': array([ 0.43373233, 0.43716422, -0.00098063]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.475341796875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51171875, 117.63007355]), + 'frame': 21728, + 'frame_number': 21728, + 'framesequence': 87605, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.16269169747829437, + 'timestamp': 741.8328938521445, + 'timestamp_carla': 741832, + 'timestamp_device': 1612434, + 'timestamp_stream': 741.8328938521445, + 'transform': [array([-55.30253601, 81.87361908, -0.15707442]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01805766, 0.02235996, -2.50626421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.146581649780273, + 'FR_Wheel_Angle': 12.480860710144043, + 'Location': array([-5.48271141e+01, 9.33500443e+01, 4.09067795e-02]), + 'Rotation': array([ 1.34568378e-01, -1.42476501e+02, 5.44427931e-02]), + 'Velocity': array([ 0.4247919 , 0.42463169, -0.0011573 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.5322265625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51171875, 117.62960815]), + 'frame': 21729, + 'frame_number': 21729, + 'framesequence': 87609, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.16269169747829437, + 'timestamp': 741.8646059520543, + 'timestamp_carla': 741863, + 'timestamp_device': 1612467, + 'timestamp_stream': 741.8646059520543, + 'transform': [array([-55.30202866, 81.87336731, -0.15706214]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.03600299, 0.03284626, -2.99286675]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.813461303710938, + 'FR_Wheel_Angle': 17.459426879882812, + 'Location': array([-5.47681351e+01, 9.34055634e+01, 4.07395847e-02]), + 'Rotation': array([ 1.34602532e-01, -1.42815231e+02, 5.49427308e-02]), + 'Velocity': array([ 0.42210597, 0.42967853, -0.00100963]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.58984375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14746094, 10474.51269531, 117.63007355]), + 'frame': 21730, + 'frame_number': 21730, + 'framesequence': 87613, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.16665904223918915, + 'timestamp': 741.8989703506231, + 'timestamp_carla': 741898, + 'timestamp_device': 1612500, + 'timestamp_stream': 741.8989703506231, + 'transform': [array([-55.30148315, 81.87309265, -0.15707462]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02635848, 0.01955184, -3.71652389]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.884224891662598, + 'FR_Wheel_Angle': 16.33994483947754, + 'Location': array([-5.47114105e+01, 9.34615707e+01, 4.05729935e-02]), + 'Rotation': array([ 1.34937212e-01, -1.43249481e+02, 5.70583828e-02]), + 'Velocity': array([ 0.40908298, 0.44519842, -0.00125258]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.647705078125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63130951]), + 'frame': 21731, + 'frame_number': 21731, + 'framesequence': 87617, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1745937317609787, + 'timestamp': 741.9320833496749, + 'timestamp_carla': 741931, + 'timestamp_device': 1612534, + 'timestamp_stream': 741.9320833496749, + 'transform': [array([-55.30093765, 81.87281036, -0.1570721 ]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.01121214, 0.01515399, -3.13700795]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.063913345336914, + 'FR_Wheel_Angle': 16.64841651916504, + 'Location': array([-5.46540413e+01, 9.35171738e+01, 4.04105261e-02]), + 'Rotation': array([ 1.34950876e-01, -1.43669434e+02, 5.24409674e-02]), + 'Velocity': array([ 0.41978195, 0.43040472, -0.00120179]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.70751953125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51367188, 117.63007355]), + 'frame': 21732, + 'frame_number': 21732, + 'framesequence': 87621, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 741.9660620503128, + 'timestamp_carla': 741965, + 'timestamp_device': 1612567, + 'timestamp_stream': 741.9660620503128, + 'transform': [array([-55.30036163, 81.87252045, -0.15707716]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02021404, 0.024453 , -3.42590666]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.48063850402832, + 'FR_Wheel_Angle': 16.53829574584961, + 'Location': array([-5.45970001e+01, 9.35715714e+01, 4.02521417e-02]), + 'Rotation': array([ 1.35408491e-01, -1.44086884e+02, 5.18404841e-02]), + 'Velocity': array([ 0.41605574, 0.42905715, -0.00101015]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.769287109375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51367188, 117.63033295]), + 'frame': 21733, + 'frame_number': 21733, + 'framesequence': 87624, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18252842128276825, + 'timestamp': 741.996250551194, + 'timestamp_carla': 741995, + 'timestamp_device': 1612592, + 'timestamp_stream': 741.996250551194, + 'transform': [array([-55.29982376, 81.8722229 , -0.15705459]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02375082, 0.02318238, -3.340832 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.366144180297852, + 'FR_Wheel_Angle': 16.69896125793457, + 'Location': array([-5.45379295e+01, 9.36271667e+01, 4.00768928e-02]), + 'Rotation': array([ 1.35435820e-01, -1.44510818e+02, 5.03421351e-02]), + 'Velocity': array([ 0.42613083, 0.43004954, -0.00116932]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.83349609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14648438, 10474.51464844, 117.62982941]), + 'frame': 21734, + 'frame_number': 21734, + 'framesequence': 87629, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18252842128276825, + 'timestamp': 742.0323035493493, + 'timestamp_carla': 742031, + 'timestamp_device': 1612634, + 'timestamp_stream': 742.0323035493493, + 'transform': [array([-55.29918671, 81.87190247, -0.15708528]), + array([-4.74015111e-03, -1.17378571e+02, 7.95716979e-03])]} +{'AngularVelocity': array([ 0.02258837, 0.01988592, -3.44057488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.322409629821777, + 'FR_Wheel_Angle': 16.602283477783203, + 'Location': array([-5.44796753e+01, 9.36811829e+01, 3.99185456e-02]), + 'Rotation': array([ 1.35975406e-01, -1.44932816e+02, 4.92659211e-02]), + 'Velocity': array([ 0.42706811, 0.42476523, -0.00124905]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.896728515625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63209534]), + 'frame': 21735, + 'frame_number': 21735, + 'framesequence': 87632, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 742.062180750072, + 'timestamp_carla': 742061, + 'timestamp_device': 1612659, + 'timestamp_stream': 742.062180750072, + 'transform': [array([-55.29870605, 81.8716507 , -0.15715504]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.0219622 , 0.02353687, -3.49132705]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.36953353881836, + 'FR_Wheel_Angle': 16.626480102539062, + 'Location': array([-5.44196510e+01, 9.37359543e+01, 3.97523791e-02]), + 'Rotation': array([ 1.35722682e-01, -1.45358566e+02, 4.84924465e-02]), + 'Velocity': array([ 0.43770874, 0.42906004, -0.00126955]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.96484375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.14550781, 10474.51367188, 117.62903595]), + 'frame': 21736, + 'frame_number': 21736, + 'framesequence': 87637, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 742.0987310521305, + 'timestamp_carla': 742098, + 'timestamp_device': 1612700, + 'timestamp_stream': 742.0987310521305, + 'transform': [array([-55.29804611, 81.87129974, -0.15715352]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.02066604, 0.02549477, -3.39691639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.369889259338379, + 'FR_Wheel_Angle': 16.627674102783203, + 'Location': array([-5.43594131e+01, 9.37902222e+01, 3.95735428e-02]), + 'Rotation': array([ 1.36446685e-01, -1.45786438e+02, 4.72857617e-02]), + 'Velocity': array([ 0.43733999, 0.4228346 , -0.00125046]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.0224609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51464844, 117.63083649]), + 'frame': 21737, + 'frame_number': 21737, + 'framesequence': 87640, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 742.1291407495737, + 'timestamp_carla': 742128, + 'timestamp_device': 1612725, + 'timestamp_stream': 742.1291407495737, + 'transform': [array([-55.29745483, 81.87099457, -0.15710789]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.03712435, 0.01687051, -3.47984982]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.371278762817383, + 'FR_Wheel_Angle': 16.629802703857422, + 'Location': array([-5.42979660e+01, 9.38446960e+01, 3.93884182e-02]), + 'Rotation': array([ 1.36808679e-01, -1.46222595e+02, 4.62713093e-02]), + 'Velocity': array([ 0.44719973, 0.42520499, -0.00147053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.097412109375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.1484375 , 10474.51367188, 117.63100433]), + 'frame': 21738, + 'frame_number': 21738, + 'framesequence': 87645, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 742.1650150492787, + 'timestamp_carla': 742164, + 'timestamp_device': 1612767, + 'timestamp_stream': 742.1650150492787, + 'transform': [array([-55.29668808, 81.87060547, -0.15711857]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.02606423, 0.02084228, -3.3903904 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.371012687683105, + 'FR_Wheel_Angle': 16.630834579467773, + 'Location': array([-5.42385406e+01, 9.38965836e+01, 3.92353348e-02]), + 'Rotation': array([ 1.37478039e-01, -1.46636581e+02, 4.51753102e-02]), + 'Velocity': array([ 0.44076529, 0.41344085, -0.00105867]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.167236328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.515625 , 117.63557434]), + 'frame': 21739, + 'frame_number': 21739, + 'framesequence': 87649, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 742.1972961500287, + 'timestamp_carla': 742196, + 'timestamp_device': 1612800, + 'timestamp_stream': 742.1972961500287, + 'transform': [array([-55.29598999, 81.87023163, -0.15709706]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.0333413 , 0.01953928, -3.46376729]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.368502616882324, + 'FR_Wheel_Angle': 16.604114532470703, + 'Location': array([-5.41773491e+01, 9.39492645e+01, 3.90556604e-02]), + 'Rotation': array([ 1.37532681e-01, -1.47066071e+02, 4.44674119e-02]), + 'Velocity': array([ 0.44649756, 0.41366604, -0.00146351]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.252685546875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.515625 , 117.63451385]), + 'frame': 21740, + 'frame_number': 21740, + 'framesequence': 87653, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 742.231538452208, + 'timestamp_carla': 742230, + 'timestamp_device': 1612833, + 'timestamp_stream': 742.231538452208, + 'transform': [array([-55.29520798, 81.8698349 , -0.15709901]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-0.01958852, 0.01327537, -3.24748182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.080498695373535, + 'FR_Wheel_Angle': 19.0111083984375, + 'Location': array([-5.41119537e+01, 9.40042267e+01, 3.88860963e-02]), + 'Rotation': array([ 1.36166647e-01, -1.47510635e+02, 4.34993282e-02]), + 'Velocity': array([ 0.47571999, 0.4233669 , -0.00144254]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.333740234375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.515625 , 117.6366806 ]), + 'frame': 21741, + 'frame_number': 21741, + 'framesequence': 87656, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.20236514508724213, + 'timestamp': 742.2639967501163, + 'timestamp_carla': 742263, + 'timestamp_device': 1612858, + 'timestamp_stream': 742.2639967501163, + 'transform': [array([-55.29445648, 81.86945343, -0.15708742]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.01514165, 0.02075879, -4.27136755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.674213409423828, + 'FR_Wheel_Angle': 22.0515079498291, + 'Location': array([-5.40502052e+01, 9.40572052e+01, 3.87018844e-02]), + 'Rotation': array([ 1.38782606e-01, -1.48007767e+02, 4.52478081e-02]), + 'Velocity': array([ 0.44246089, 0.42478514, -0.00139556]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.422119140625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.51660156, 117.63650513]), + 'frame': 21742, + 'frame_number': 21742, + 'framesequence': 87661, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21031509339809418, + 'timestamp': 742.2986084520817, + 'timestamp_carla': 742298, + 'timestamp_device': 1612900, + 'timestamp_stream': 742.2986084520817, + 'transform': [array([-55.29362488, 81.86901855, -0.15709752]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-0.02726888, -0.01792389, -3.70240283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.740840911865234, + 'FR_Wheel_Angle': 20.0594425201416, + 'Location': array([-5.39906158e+01, 9.41094513e+01, 3.85293476e-02]), + 'Rotation': array([ 1.39813960e-01, -1.48541885e+02, 4.16472182e-02]), + 'Velocity': array([ 0.43630728, 0.4032703 , -0.00133329]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.506591796875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.51757812, 117.63767242]), + 'frame': 21743, + 'frame_number': 21743, + 'framesequence': 87665, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21428243815898895, + 'timestamp': 742.3318079523742, + 'timestamp_carla': 742331, + 'timestamp_device': 1612933, + 'timestamp_stream': 742.3318079523742, + 'transform': [array([-55.29281998, 81.8686142 , -0.15709278]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 7.63289351e-03, 1.61283067e-03, -3.64820910e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.716678619384766, + 'FR_Wheel_Angle': 21.09812355041504, + 'Location': array([-5.39308968e+01, 9.41598740e+01, 3.83553579e-02]), + 'Rotation': array([ 1.40053019e-01, -1.49034470e+02, 3.94570641e-02]), + 'Velocity': array([ 0.43017486, 0.39225286, -0.00140655]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.599365234375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51660156, 117.63667297]), + 'frame': 21744, + 'frame_number': 21744, + 'framesequence': 87669, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21428243815898895, + 'timestamp': 742.3645635508001, + 'timestamp_carla': 742363, + 'timestamp_device': 1612967, + 'timestamp_stream': 742.3645635508001, + 'transform': [array([-55.29199982, 81.86819458, -0.1570873 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.01643161, -0.01028778, -3.88010359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.278810501098633, + 'FR_Wheel_Angle': 20.709218978881836, + 'Location': array([-5.38726997e+01, 9.42085342e+01, 3.81988809e-02]), + 'Rotation': array([ 1.40087172e-01, -1.49535492e+02, 3.83977145e-02]), + 'Velocity': array([ 0.43263832, 0.38774413, -0.00135256]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.6904296875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.51757812, 117.63715363]), + 'frame': 21745, + 'frame_number': 21745, + 'framesequence': 87673, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21824978291988373, + 'timestamp': 742.3982407487929, + 'timestamp_carla': 742397, + 'timestamp_device': 1613000, + 'timestamp_stream': 742.3982407487929, + 'transform': [array([-55.2911377 , 81.86774445, -0.15709145]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-1.37763703e-03, -1.65957666e-03, -3.76019859e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.4399471282959, + 'FR_Wheel_Angle': 20.749053955078125, + 'Location': array([-5.38135338e+01, 9.42569733e+01, 3.80368307e-02]), + 'Rotation': array([ 1.39725178e-01, -1.50027222e+02, 3.74002568e-02]), + 'Velocity': array([ 0.43387911, 0.38223162, -0.00156078]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.783203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.51855469, 117.6377182 ]), + 'frame': 21746, + 'frame_number': 21746, + 'framesequence': 87677, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 742.4322178512812, + 'timestamp_carla': 742431, + 'timestamp_device': 1613033, + 'timestamp_stream': 742.4322178512812, + 'transform': [array([-55.29024887, 81.86727142, -0.15709659]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 2.05434859e-03, -7.69181084e-03, -3.45156121e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.420351028442383, + 'FR_Wheel_Angle': 20.79704475402832, + 'Location': array([-5.37551079e+01, 9.43039932e+01, 3.78828309e-02]), + 'Rotation': array([ 1.39943734e-01, -1.50515869e+02, 3.60941403e-02]), + 'Velocity': array([ 0.43795207, 0.377406 , -0.00118472]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.88037109375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.51855469, 117.63732147]), + 'frame': 21747, + 'frame_number': 21747, + 'framesequence': 87681, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 742.4648561514914, + 'timestamp_carla': 742464, + 'timestamp_device': 1613067, + 'timestamp_stream': 742.4648561514914, + 'transform': [array([-55.28936768, 81.86682129, -0.15709001]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.00747494, -0.00559837, -3.74139524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.413616180419922, + 'FR_Wheel_Angle': 20.794204711914062, + 'Location': array([-5.36956482e+01, 9.43510513e+01, 3.77188399e-02]), + 'Rotation': array([ 1.40210122e-01, -1.51005127e+02, 3.49695310e-02]), + 'Velocity': array([ 0.44020042, 0.37355193, -0.00120252]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3259.979736328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51660156, 117.63681793]), + 'frame': 21748, + 'frame_number': 21748, + 'framesequence': 87685, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 742.4984949491918, + 'timestamp_carla': 742497, + 'timestamp_device': 1613100, + 'timestamp_stream': 742.4984949491918, + 'transform': [array([-55.28843689, 81.86634827, -0.15709373]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 0.01233862, -0.00514221, -3.88806438]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.414512634277344, + 'FR_Wheel_Angle': 20.79166603088379, + 'Location': array([-5.36351128e+01, 9.43981018e+01, 3.75620946e-02]), + 'Rotation': array([ 1.39629543e-01, -1.51504959e+02, 3.44153754e-02]), + 'Velocity': array([ 0.45553222, 0.38067049, -0.00093719]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.079833984375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15332031, 10474.51855469, 117.63749695]), + 'frame': 21749, + 'frame_number': 21749, + 'framesequence': 87689, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.23411917686462402, + 'timestamp': 742.5320170521736, + 'timestamp_carla': 742531, + 'timestamp_device': 1613133, + 'timestamp_stream': 742.5320170521736, + 'transform': [array([-55.28748322, 81.86585999, -0.15709534]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-0.01825285, 0.00548031, -3.56817889]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.41647720336914, + 'FR_Wheel_Angle': 20.798921585083008, + 'Location': array([-5.35739403e+01, 9.44448242e+01, 3.73853184e-02]), + 'Rotation': array([ 1.40688226e-01, -1.52003250e+02, 3.26070487e-02]), + 'Velocity': array([ 0.44084543, 0.36129832, -0.00121778]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.18359375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51757812, 117.63713837]), + 'frame': 21750, + 'frame_number': 21750, + 'framesequence': 87693, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2380865216255188, + 'timestamp': 742.5652359500527, + 'timestamp_carla': 742564, + 'timestamp_device': 1613167, + 'timestamp_stream': 742.5652359500527, + 'transform': [array([-55.28652191, 81.86535645, -0.15709417]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-0.01499318, -0.00490323, -3.4393084 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.399032592773438, + 'FR_Wheel_Angle': 20.766942977905273, + 'Location': array([-5.35139732e+01, 9.44897842e+01, 3.72169763e-02]), + 'Rotation': array([ 1.41398564e-01, -1.52493179e+02, 3.12161874e-02]), + 'Velocity': array([ 0.43830344, 0.3510907 , -0.00127409]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.29150390625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51855469, 117.63699341]), + 'frame': 21751, + 'frame_number': 21751, + 'framesequence': 87697, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.5994429513812, + 'timestamp_carla': 742598, + 'timestamp_device': 1613200, + 'timestamp_stream': 742.5994429513812, + 'transform': [array([-55.28549576, 81.86483002, -0.15710111]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-0.02620896, 0.014643 , -4.94275236]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.4040470123291, + 'FR_Wheel_Angle': 20.912975311279297, + 'Location': array([-5.34457664e+01, 9.45398331e+01, 3.70517634e-02]), + 'Rotation': array([ 1.38304487e-01, -1.53040527e+02, 3.19107138e-02]), + 'Velocity': array([ 0.49386325, 0.39087418, -0.00134853]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.399658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51855469, 117.63712311]), + 'frame': 21752, + 'frame_number': 21752, + 'framesequence': 87701, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.6318111494184, + 'timestamp_carla': 742631, + 'timestamp_device': 1613233, + 'timestamp_stream': 742.6318111494184, + 'transform': [array([-55.28451157, 81.86431122, -0.15709157]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 2.38437951e-03, 2.29597297e-02, -5.20430946e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.336503982543945, + 'FR_Wheel_Angle': 26.476408004760742, + 'Location': array([-5.33795929e+01, 9.45881729e+01, 3.68612930e-02]), + 'Rotation': array([ 1.41132191e-01, -1.53590698e+02, 3.04634161e-02]), + 'Velocity': array([ 0.47181129, 0.38124305, -0.00126454]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.513916015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15136719, 10474.51855469, 117.63644409]), + 'frame': 21753, + 'frame_number': 21753, + 'framesequence': 87704, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.6643830500543, + 'timestamp_carla': 742663, + 'timestamp_device': 1613258, + 'timestamp_stream': 742.6643830500543, + 'transform': [array([-55.28347397, 81.86378479, -0.15708756]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-0.02153567, -0.00852627, -5.66153622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.43743324279785, + 'FR_Wheel_Angle': 24.273557662963867, + 'Location': array([-5.33165665e+01, 9.46361694e+01, 3.66815850e-02]), + 'Rotation': array([ 1.42477736e-01, -1.54229141e+02, 3.04943714e-02]), + 'Velocity': array([ 0.45654815, 0.38279507, -0.00093863]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.626220703125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51855469, 117.63741302]), + 'frame': 21754, + 'frame_number': 21754, + 'framesequence': 87709, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.6978688500822, + 'timestamp_carla': 742697, + 'timestamp_device': 1613300, + 'timestamp_stream': 742.6978688500822, + 'transform': [array([-55.28237534, 81.86322021, -0.15709233]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([ 7.90490955e-03, 2.02006637e-03, -5.24388170e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.126977920532227, + 'FR_Wheel_Angle': 25.207176208496094, + 'Location': array([-5.32535286e+01, 9.46825180e+01, 3.65040861e-02]), + 'Rotation': array([ 1.42757773e-01, -1.54825150e+02, 2.55714636e-02]), + 'Velocity': array([ 0.45746112, 0.3640216 , -0.00148708]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.742919921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51953125, 117.63783264]), + 'frame': 21755, + 'frame_number': 21755, + 'framesequence': 87713, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.7317979522049, + 'timestamp_carla': 742731, + 'timestamp_device': 1613333, + 'timestamp_stream': 742.7317979522049, + 'transform': [array([-55.28123474, 81.86263275, -0.15709859]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-3.86271183e-03, -1.05943298e-03, -5.44752073e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.356828689575195, + 'FR_Wheel_Angle': 24.795473098754883, + 'Location': array([-5.31898537e+01, 9.47284317e+01, 3.63324247e-02]), + 'Rotation': array([ 1.42361626e-01, -1.55436447e+02, 2.51098573e-02]), + 'Velocity': array([ 0.4619877 , 0.3646735 , -0.00124882]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.865966796875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51953125, 117.63736725]), + 'frame': 21756, + 'frame_number': 21756, + 'framesequence': 87717, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.7654334492981, + 'timestamp_carla': 742764, + 'timestamp_device': 1613367, + 'timestamp_stream': 742.7654334492981, + 'transform': [array([-55.28007507, 81.86203766, -0.15709992]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-1.05111822e-02, -2.86013284e-03, -5.40186453e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.295522689819336, + 'FR_Wheel_Angle': 25.027252197265625, + 'Location': array([-5.31275139e+01, 9.47723160e+01, 3.61759849e-02]), + 'Rotation': array([ 1.42819241e-01, -1.56027863e+02, 2.26673689e-02]), + 'Velocity': array([ 0.45928186, 0.35080281, -0.00098124]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3260.994140625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51953125, 117.63676453]), + 'frame': 21757, + 'frame_number': 21757, + 'framesequence': 87721, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.7981548495591, + 'timestamp_carla': 742797, + 'timestamp_device': 1613400, + 'timestamp_stream': 742.7981548495591, + 'transform': [array([-55.27892303, 81.86144257, -0.1570939 ]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-2.71086022e-02, -4.50965762e-03, -5.78043127e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.249624252319336, + 'FR_Wheel_Angle': 24.938703536987305, + 'Location': array([-5.30604668e+01, 9.48183212e+01, 3.60092446e-02]), + 'Rotation': array([ 1.39848113e-01, -1.56656113e+02, 2.32899114e-02]), + 'Velocity': array([ 0.51195329, 0.38026416, -0.00098975]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3261.124267578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.51953125, 117.63665009]), + 'frame': 21758, + 'frame_number': 21758, + 'framesequence': 87725, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.8320154510438, + 'timestamp_carla': 742831, + 'timestamp_device': 1613433, + 'timestamp_stream': 742.8320154510438, + 'transform': [array([-55.27769852, 81.86080933, -0.15709886]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-0.01168932, 0.00672609, -5.54249668]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.2882022857666, + 'FR_Wheel_Angle': 24.943714141845703, + 'Location': array([-5.29924355e+01, 9.48642044e+01, 3.58064547e-02]), + 'Rotation': array([ 1.42334297e-01, -1.57287521e+02, 2.04308629e-02]), + 'Velocity': array([ 0.49094898, 0.36152762, -0.00147732]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3261.2548828125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.52050781, 117.63726807]), + 'frame': 21759, + 'frame_number': 21759, + 'framesequence': 87729, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0006775109213776886, + 'throttle_input': 0.24205386638641357, + 'timestamp': 742.8666968494654, + 'timestamp_carla': 742866, + 'timestamp_device': 1613467, + 'timestamp_stream': 742.8666968494654, + 'transform': [array([-55.27641296, 81.86014557, -0.15710796]), + array([-4.74015111e-03, -1.17378571e+02, 8.06645304e-03])]} +{'AngularVelocity': array([-2.34325510e-03, 2.18448904e-03, -5.45642662e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.291515350341797, + 'FR_Wheel_Angle': 24.947772979736328, + 'Location': array([-5.29257851e+01, 9.49081039e+01, 3.56251411e-02]), + 'Rotation': array([ 1.43297359e-01, -1.57908096e+02, 1.83501858e-02]), + 'Velocity': array([ 0.48569709, 0.34957495, -0.00145402]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3261.392578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15234375, 10474.52050781, 117.63679504]), + 'frame': 21760, + 'frame_number': 21760, + 'framesequence': 87733, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.01148106437176466, + 'throttle_input': 0.24602121114730835, + 'timestamp': 742.900606751442, + 'timestamp_carla': 742900, + 'timestamp_device': 1613500, + 'timestamp_stream': 742.900606751442, + 'transform': [array([-55.27509689, 81.85956573, -0.15710929]), + array([-4.70599998e-03, -1.17378159e+02, 8.08011368e-03])]} +{'AngularVelocity': array([ 5.21933148e-03, 2.83318525e-03, -5.41204739e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.29682731628418, + 'FR_Wheel_Angle': 24.95347023010254, + 'Location': array([-5.28601074e+01, 9.49502716e+01, 3.54484059e-02]), + 'Rotation': array([ 1.43857434e-01, -1.58514374e+02, 1.64930709e-02]), + 'Velocity': array([ 0.4788757 , 0.33682251, -0.00142109]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3261.53564453125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.15039062, 10474.51953125, 117.6359024 ]), + 'frame': 21761, + 'frame_number': 21761, + 'framesequence': 87737, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03257545828819275, + 'throttle_input': 0.24602121114730835, + 'timestamp': 742.9321963489056, + 'timestamp_carla': 742931, + 'timestamp_device': 1613533, + 'timestamp_stream': 742.9321963489056, + 'transform': [array([-55.27375793, 81.85910797, -0.15708873]), + array([-4.64452850e-03, -1.17377136e+02, 8.07328429e-03])]} +{'AngularVelocity': array([ 0.01342098, -0.00682527, -5.31649685]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.294231414794922, + 'FR_Wheel_Angle': 24.951030731201172, + 'Location': array([-5.27954254e+01, 9.49908981e+01, 3.52775082e-02]), + 'Rotation': array([ 1.43891588e-01, -1.59105637e+02, 1.52797978e-02]), + 'Velocity': array([ 0.480602 , 0.32976645, -0.0010864 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3261.676513671875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.16015625, 10474.49609375, 117.63676453]), + 'frame': 21762, + 'frame_number': 21762, + 'framesequence': 87741, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05637989565730095, + 'throttle_input': 0.2539559006690979, + 'timestamp': 742.9648926518857, + 'timestamp_carla': 742964, + 'timestamp_device': 1613567, + 'timestamp_stream': 742.9648926518857, + 'transform': [array([-55.27222443, 81.85874939, -0.15707788]), + array([-4.56256606e-03, -1.17375290e+02, 8.04596115e-03])]} +{'AngularVelocity': array([ 7.35955173e-03, 1.59930601e-03, -5.42371035e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.2979679107666, + 'FR_Wheel_Angle': 24.955907821655273, + 'Location': array([-5.27290726e+01, 9.50314636e+01, 3.50986384e-02]), + 'Rotation': array([ 1.43474951e-01, -1.59713562e+02, 1.41712725e-02]), + 'Velocity': array([ 0.48379821, 0.32492206, -0.00146358]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3261.80419921875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.18066406, 10474.43945312, 117.63806152]), + 'frame': 21763, + 'frame_number': 21763, + 'framesequence': 87745, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.08130131661891937, + 'throttle_input': 0.2658579349517822, + 'timestamp': 742.9978384524584, + 'timestamp_carla': 742997, + 'timestamp_device': 1613600, + 'timestamp_stream': 742.9978384524584, + 'transform': [array([-55.27056122, 81.85850525, -0.15707353]), + array([-4.48060408e-03, -1.17372589e+02, 8.03230237e-03])]} +{'AngularVelocity': array([ 3.29206767e-03, -2.60154065e-03, -5.47115278e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.582406997680664, + 'FR_Wheel_Angle': 28.42831039428711, + 'Location': array([-5.26634331e+01, 9.50708542e+01, 3.49325091e-02]), + 'Rotation': array([ 1.43509090e-01, -1.60311600e+02, 1.31361829e-02]), + 'Velocity': array([ 0.48606178, 0.32061961, -0.0007181 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3261.930908203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.21386719, 10474.33398438, 117.63671112]), + 'frame': 21764, + 'frame_number': 21764, + 'framesequence': 87749, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1096285954117775, + 'throttle_input': 0.269825279712677, + 'timestamp': 743.0335640497506, + 'timestamp_carla': 743033, + 'timestamp_device': 1613633, + 'timestamp_stream': 743.0335640497506, + 'transform': [array([-55.26857376, 81.85843658, -0.15709482]), + array([-4.41230182e-03, -1.17368515e+02, 8.03230237e-03])]} +{'AngularVelocity': array([-3.39702331e-03, 5.57116186e-03, -6.24554682e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.994789123535156, + 'FR_Wheel_Angle': 29.736360549926758, + 'Location': array([-5.25987587e+01, 9.51108475e+01, 3.47529128e-02]), + 'Rotation': array([ 1.44123808e-01, -1.60989166e+02, 1.48160532e-02]), + 'Velocity': array([ 0.46421149, 0.33049968, -0.00135703]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.0556640625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.265625 , 10474.17871094, 117.63578796]), + 'frame': 21765, + 'frame_number': 21765, + 'framesequence': 87753, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13760796189308167, + 'throttle_input': 0.269825279712677, + 'timestamp': 743.0676429495215, + 'timestamp_carla': 743067, + 'timestamp_device': 1613667, + 'timestamp_stream': 743.0676429495215, + 'transform': [array([-55.26656723, 81.85852051, -0.15709829]), + array([-4.34400002e-03, -1.17363724e+02, 8.05962179e-03])]} +{'AngularVelocity': array([-1.55926740e-03, -1.09945266e-02, -5.95336580e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.516767501831055, + 'FR_Wheel_Angle': 28.63958740234375, + 'Location': array([-5.25346603e+01, 9.51502686e+01, 3.45814042e-02]), + 'Rotation': array([ 1.43700346e-01, -1.61681763e+02, 1.06127104e-02]), + 'Velocity': array([ 0.47916943, 0.32193932, -0.00177885]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.18017578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.34082031, 10473.94433594, 117.63343811]), + 'frame': 21766, + 'frame_number': 21766, + 'framesequence': 87757, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1684255450963974, + 'throttle_input': 0.2737926244735718, + 'timestamp': 743.1005402505398, + 'timestamp_carla': 743100, + 'timestamp_device': 1613700, + 'timestamp_stream': 743.1005402505398, + 'transform': [array([-55.26447296, 81.85876465, -0.157088 ]), + array([-4.26886790e-03, -1.17358025e+02, 8.06645397e-03])]} +{'AngularVelocity': array([-0.02617627, 0.01352334, -4.25630283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.26081657409668, + 'FR_Wheel_Angle': 29.262372970581055, + 'Location': array([-5.24653473e+01, 9.51911240e+01, 3.44074145e-02]), + 'Rotation': array([ 1.42552868e-01, -1.62392212e+02, 9.46327206e-03]), + 'Velocity': array([ 0.49633658, 0.32808357, -0.00154662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.2958984375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.43359375, 10473.671875 , 117.63506317]), + 'frame': 21767, + 'frame_number': 21767, + 'framesequence': 87761, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19589221477508545, + 'throttle_input': 0.2737926244735718, + 'timestamp': 743.1328136511147, + 'timestamp_carla': 743132, + 'timestamp_device': 1613733, + 'timestamp_stream': 743.1328136511147, + 'transform': [array([-55.2622261 , 81.85919189, -0.15707254]), + array([-4.18007560e-03, -1.17351196e+02, 8.05279240e-03])]} +{'AngularVelocity': array([-1.74390003e-02, -6.36856304e-04, -4.39884377e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.95269012451172, + 'FR_Wheel_Angle': 29.065711975097656, + 'Location': array([-5.23972092e+01, 9.52305908e+01, 3.42263319e-02]), + 'Rotation': array([ 1.43372491e-01, -1.63107880e+02, 6.48068218e-03]), + 'Velocity': array([ 0.5020712 , 0.32001543, -0.00143701]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.39892578125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.54394531, 10473.34765625, 117.63639069]), + 'frame': 21768, + 'frame_number': 21768, + 'framesequence': 87764, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2226630598306656, + 'throttle_input': 0.2737926244735718, + 'timestamp': 743.1642077490687, + 'timestamp_carla': 743163, + 'timestamp_device': 1613758, + 'timestamp_stream': 743.1642077490687, + 'transform': [array([-55.25984573, 81.85979462, -0.15704927]), + array([-4.09811316e-03, -1.17343338e+02, 8.01181048e-03])]} +{'AngularVelocity': array([-8.87877215e-03, 2.07046513e-03, -4.34681082e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.02817153930664, + 'FR_Wheel_Angle': 29.06659507751465, + 'Location': array([-5.23299713e+01, 9.52682571e+01, 3.40592489e-02]), + 'Rotation': array([ 1.43980384e-01, -1.63802399e+02, 4.12906567e-03]), + 'Velocity': array([ 0.49643722, 0.30864322, -0.00106411]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.492431640625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.67480469, 10472.95703125, 117.63655853]), + 'frame': 21769, + 'frame_number': 21769, + 'framesequence': 87768, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25027620792388916, + 'throttle_input': 0.2737926244735718, + 'timestamp': 743.1953835524619, + 'timestamp_carla': 743194, + 'timestamp_device': 1613792, + 'timestamp_stream': 743.1953835524619, + 'transform': [array([-55.25727844, 81.86058807, -0.15702666]), + array([-4.00932087e-03, -1.17334213e+02, 7.95716792e-03])]} +{'AngularVelocity': array([ 0.04385187, -0.04015797, -5.28030014]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.014423370361328, + 'FR_Wheel_Angle': 29.06751823425293, + 'Location': array([-5.22575912e+01, 9.53075562e+01, 3.38824354e-02]), + 'Rotation': array([ 1.39766157e-01, -1.64539169e+02, 6.14401093e-03]), + 'Velocity': array([ 0.59520948, 0.3568151 , -0.00179323]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.5751953125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.82421875, 10472.50878906, 117.63531494]), + 'frame': 21770, + 'frame_number': 21770, + 'framesequence': 87773, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.27618640661239624, + 'throttle_input': 0.2737926244735718, + 'timestamp': 743.2316403500736, + 'timestamp_carla': 743231, + 'timestamp_device': 1613833, + 'timestamp_stream': 743.2316403500736, + 'transform': [array([-55.25391006, 81.86188507, -0.15704603]), + array([-3.97516973e-03, -1.17321304e+02, 7.88886845e-03])]} +{'AngularVelocity': array([-0.03957228, 0.0181203 , -4.8088131 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.024688720703125, + 'FR_Wheel_Angle': 29.082046508789062, + 'Location': array([-5.21794624e+01, 9.53488388e+01, 3.36700715e-02]), + 'Rotation': array([ 1.41562492e-01, -1.65332642e+02, 2.26396765e-03]), + 'Velocity': array([ 0.56405109, 0.33188727, -0.00151789]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.649658203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9518.99609375, 10471.98730469, 117.63290405]), + 'frame': 21771, + 'frame_number': 21771, + 'framesequence': 87776, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3063264787197113, + 'throttle_input': 0.2737926244735718, + 'timestamp': 743.2637898512185, + 'timestamp_carla': 743263, + 'timestamp_device': 1613858, + 'timestamp_stream': 743.2637898512185, + 'transform': [array([-55.25093079, 81.86303711, -0.15703526]), + array([-3.91369825e-03, -1.17309738e+02, 7.90252816e-03])]} +{'AngularVelocity': array([-0.02108114, 0.00843832, -4.65146637]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.031837463378906, + 'FR_Wheel_Angle': 29.092864990234375, + 'Location': array([-5.21036835e+01, 9.53876419e+01, 3.34576331e-02]), + 'Rotation': array([ 1.43727660e-01, -1.66098389e+02, -1.58691336e-03]), + 'Velocity': array([ 0.54919416, 0.31296101, -0.00162309]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3262.716796875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9519.234375 , 10471.24707031, 117.62536621]), + 'frame': 21772, + 'frame_number': 21772, + 'framesequence': 87781, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33388471603393555, + 'throttle_input': 0.2737926244735718, + 'timestamp': 743.2991929501295, + 'timestamp_carla': 743298, + 'timestamp_device': 1613900, + 'timestamp_stream': 743.2991929501295, + 'transform': [array([-55.24739075, 81.86465454, -0.15706265]), + array([-3.91369825e-03, -1.17294998e+02, 7.94350822e-03])]} +{'AngularVelocity': array([-1.16006890e-02, 2.31021841e-04, -4.56302595e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.037851333618164, + 'FR_Wheel_Angle': 29.100027084350586, + 'Location': array([-5.20299149e+01, 9.54241714e+01, 3.32619771e-02]), + 'Rotation': array([ 1.44451663e-01, -1.66839554e+02, -4.08935500e-03]), + 'Velocity': array([ 0.53988498, 0.29734257, -0.00151227]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3292.1943359375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9545.59082031, 10484.08007812, 117.63140869]), + 'frame': 21773, + 'frame_number': 21773, + 'framesequence': 87785, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36404311656951904, + 'throttle_input': 0.27775996923446655, + 'timestamp': 743.3315657489002, + 'timestamp_carla': 743331, + 'timestamp_device': 1613933, + 'timestamp_stream': 743.3315657489002, + 'transform': [array([-55.24381638, 81.86652374, -0.15703641]), + array([-3.81807564e-03, -1.17279236e+02, 7.90252816e-03])]} +{'AngularVelocity': array([-2.02651210e-02, 3.83667927e-03, -4.16898251e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.04294776916504, + 'FR_Wheel_Angle': 29.080846786499023, + 'Location': array([-5.19582977e+01, 9.54584045e+01, 3.30885202e-02]), + 'Rotation': array([ 1.44588262e-01, -1.67556259e+02, -5.85937547e-03]), + 'Velocity': array([ 0.52667463, 0.28186607, -0.00157491]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3293.43408203125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9546.92871094, 10483.77636719, 117.63214111]), + 'frame': 21774, + 'frame_number': 21774, + 'framesequence': 87789, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3916013240814209, + 'throttle_input': 0.2856946587562561, + 'timestamp': 743.3656880520284, + 'timestamp_carla': 743365, + 'timestamp_device': 1613967, + 'timestamp_stream': 743.3656880520284, + 'transform': [array([-55.23983765, 81.86860657, -0.15702914]), + array([-3.72245279e-03, -1.17261475e+02, 7.86154624e-03])]} +{'AngularVelocity': array([-1.30903432e-02, -2.31937529e-03, -6.09352589e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.19463348388672, + 'FR_Wheel_Angle': 30.351139068603516, + 'Location': array([-5.18797417e+01, 9.54946823e+01, 3.29044238e-02]), + 'Rotation': array([ 1.40435517e-01, -1.68333435e+02, -3.99780180e-03]), + 'Velocity': array([ 0.6006701 , 0.31234577, -0.00155744]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3294.73291015625, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9548.35742188, 10483.45117188, 117.63130188]), + 'frame': 21775, + 'frame_number': 21775, + 'framesequence': 87793, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4209173917770386, + 'throttle_input': 0.3015792965888977, + 'timestamp': 743.3998428508639, + 'timestamp_carla': 743399, + 'timestamp_device': 1614000, + 'timestamp_stream': 743.3998428508639, + 'transform': [array([-55.23574066, 81.87091827, -0.15704635]), + array([-3.72928311e-03, -1.17242485e+02, 7.92302005e-03])]} +{'AngularVelocity': array([ 6.06380356e-03, 2.25642193e-02, -6.65286779e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.681734085083008, + 'FR_Wheel_Angle': 34.89678955078125, + 'Location': array([-5.18014679e+01, 9.55306931e+01, 3.26957591e-02]), + 'Rotation': array([ 1.42901212e-01, -1.69160736e+02, -5.40161133e-03]), + 'Velocity': array([ 0.56378084, 0.31011915, -0.00147372]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3296.198486328125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9549.97363281, 10483.08496094, 117.62860107]), + 'frame': 21776, + 'frame_number': 21776, + 'framesequence': 87797, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.451149046421051, + 'throttle_input': 0.3174487054347992, + 'timestamp': 743.4316120520234, + 'timestamp_carla': 743431, + 'timestamp_device': 1614033, + 'timestamp_stream': 743.4316120520234, + 'transform': [array([-55.22961426, 81.87291718, -0.15633568]), + array([-5.19094348e-04, -1.17218277e+02, 5.33437682e-03])]} +{'AngularVelocity': array([-4.03718725e-02, -6.08633040e-03, -6.47235250e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.213359832763672, + 'FR_Wheel_Angle': 32.37458419799805, + 'Location': array([-5.17270050e+01, 9.55660782e+01, 3.24978903e-02]), + 'Rotation': array([ 1.43953055e-01, -1.70041550e+02, -8.85009766e-03]), + 'Velocity': array([ 0.55101192, 0.29635364, -0.00152987]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3297.753662109375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9551.70800781, 10482.69238281, 117.63209534]), + 'frame': 21777, + 'frame_number': 21777, + 'framesequence': 87801, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47874388098716736, + 'throttle_input': 0.3333180844783783, + 'timestamp': 743.4647320508957, + 'timestamp_carla': 743464, + 'timestamp_device': 1614067, + 'timestamp_stream': 743.4647320508957, + 'transform': [array([-55.20796585, 81.88750458, -0.15460473]), + array([ 5.64856594e-03, -1.17110390e+02, -1.31225691e-03])]} +{'AngularVelocity': array([ 2.63851718e-03, -1.09274709e-03, -6.33885527e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.876949310302734, + 'FR_Wheel_Angle': 33.63344955444336, + 'Location': array([-5.16524887e+01, 9.55991745e+01, 3.23062800e-02]), + 'Rotation': array([ 1.43679857e-01, -1.70872604e+02, -1.30920401e-02]), + 'Velocity': array([ 0.54676569, 0.28008386, -0.0014885 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3334.083251953125, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9584.37304688, 10497.81835938, 117.48622131]), + 'frame': 21778, + 'frame_number': 21778, + 'framesequence': 87805, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5052583813667297, + 'throttle_input': 0.33728542923927307, + 'timestamp': 743.4981127493083, + 'timestamp_carla': 743497, + 'timestamp_device': 1614100, + 'timestamp_stream': 743.4981127493083, + 'transform': [array([-55.17824936, 81.90849304, -0.15334843]), + array([ 1.16249816e-02, -1.16956886e+02, -5.98144624e-03])]} +{'AngularVelocity': array([ 2.93130823e-03, -8.96019954e-03, -6.33460522e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.56612777709961, + 'FR_Wheel_Angle': 33.1076774597168, + 'Location': array([-5.15787163e+01, 9.56310425e+01, 3.21126841e-02]), + 'Rotation': array([ 1.43317848e-01, -1.71710999e+02, -1.47705069e-02]), + 'Velocity': array([ 0.5450477 , 0.27132687, -0.00158169]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3336.011474609375, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9588.27539062, 10492.52246094, 117.09653473]), + 'frame': 21779, + 'frame_number': 21779, + 'framesequence': 87808, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5329447388648987, + 'throttle_input': 0.3452201187610626, + 'timestamp': 743.529985152185, + 'timestamp_carla': 743529, + 'timestamp_device': 1614125, + 'timestamp_stream': 743.529985152185, + 'transform': [array([-55.1473999 , 81.92990112, -0.15272988]), + array([ 1.45551320e-02, -1.16797623e+02, -8.23974796e-03])]} +{'AngularVelocity': array([ 2.71477667e-03, -5.86541323e-03, -5.99573994e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.719905853271484, + 'FR_Wheel_Angle': 33.247066497802734, + 'Location': array([-5.15077286e+01, 9.56604004e+01, 3.19462083e-02]), + 'Rotation': array([ 1.43283695e-01, -1.72497421e+02, -1.73645020e-02]), + 'Velocity': array([ 0.53323042, 0.25454679, -0.00118554]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3344.748046875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9599.25195312, 10487.69335938, 116.8199234 ]), + 'frame': 21780, + 'frame_number': 21780, + 'framesequence': 87813, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5605396032333374, + 'throttle_input': 0.3491874635219574, + 'timestamp': 743.5646864511073, + 'timestamp_carla': 743564, + 'timestamp_device': 1614167, + 'timestamp_stream': 743.5646864511073, + 'transform': [array([-55.10946655, 81.9581604 , -0.15262923]), + array([ 1.62968300e-02, -1.16594162e+02, -8.54492374e-03])]} +{'AngularVelocity': array([ 0.01322113, -0.01159207, -6.19685888]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.694442749023438, + 'FR_Wheel_Angle': 33.27760696411133, + 'Location': array([-5.14366837e+01, 9.56886673e+01, 3.17632183e-02]), + 'Rotation': array([ 1.42860234e-01, -1.73287521e+02, -1.88293438e-02]), + 'Velocity': array([ 0.53137791, 0.24588987, -0.00142139]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3354.955810546875, + 'focus_actor_name': 'BP_RepSpline113', + 'focus_actor_pt': array([-9611.6484375 , 10483.09082031, 116.68565369]), + 'frame': 21781, + 'frame_number': 21781, + 'framesequence': 87817, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.590459942817688, + 'throttle_input': 0.35712215304374695, + 'timestamp': 743.5991566516459, + 'timestamp_carla': 743598, + 'timestamp_device': 1614200, + 'timestamp_stream': 743.5991566516459, + 'transform': [array([-55.06887436, 81.98950958, -0.15274031]), + array([ 1.67544540e-02, -1.16372154e+02, -8.05664342e-03])]} +{'AngularVelocity': array([-8.99067800e-03, 2.27198657e-03, -5.78361177e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.698020935058594, + 'FR_Wheel_Angle': 33.28519058227539, + 'Location': array([-5.13664284e+01, 9.57154770e+01, 3.15885432e-02]), + 'Rotation': array([ 1.42587021e-01, -1.74063782e+02, -2.08435059e-02]), + 'Velocity': array([ 0.51754892, 0.23033844, -0.00116861]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3396.82763671875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9653.40234375, 10490.1015625 , 116.65879059]), + 'frame': 21782, + 'frame_number': 21782, + 'framesequence': 87820, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3610894978046417, + 'timestamp': 743.6294392496347, + 'timestamp_carla': 743628, + 'timestamp_device': 1614225, + 'timestamp_stream': 743.6294392496347, + 'transform': [array([-55.02959442, 82.01943207, -0.15260634]), + array([ 1.76423769e-02, -1.16157959e+02, -8.42285436e-03])]} +{'AngularVelocity': array([ 4.70019039e-03, -5.54360636e-03, -5.79166985e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.700443267822266, + 'FR_Wheel_Angle': 33.28878402709961, + 'Location': array([-5.12958832e+01, 9.57413559e+01, 3.14014703e-02]), + 'Rotation': array([ 1.41869858e-01, -1.74840805e+02, -2.21252386e-02]), + 'Velocity': array([ 0.5221467 , 0.22461139, -0.00181222]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3400.840576171875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9661.79589844, 10478.95214844, 116.68565369]), + 'frame': 21783, + 'frame_number': 21783, + 'framesequence': 87825, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.6645353510976, + 'timestamp_carla': 743664, + 'timestamp_device': 1614267, + 'timestamp_stream': 743.6645353510976, + 'transform': [array([-54.98223495, 82.05706787, -0.1529379 ]), + array([ 1.67544540e-02, -1.15894028e+02, -7.20215309e-03])]} +{'AngularVelocity': array([ 6.96092262e-04, -5.17062494e-04, -5.90641832e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.704280853271484, + 'FR_Wheel_Angle': 33.290283203125, + 'Location': array([-5.12272606e+01, 9.57654572e+01, 3.12470142e-02]), + 'Rotation': array([ 1.41610309e-01, -1.75593323e+02, -2.40478516e-02]), + 'Velocity': array([ 0.51466811, 0.21283309, -0.00120408]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3404.813232421875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9669.92773438, 10468.15039062, 116.6654129 ]), + 'frame': 21784, + 'frame_number': 21784, + 'framesequence': 87829, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5851680040359497, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.6997146494687, + 'timestamp_carla': 743699, + 'timestamp_device': 1614300, + 'timestamp_stream': 743.6997146494687, + 'transform': [array([-54.93501663, 82.09440613, -0.1534465 ]), + array([ 1.34281516e-02, -1.15631897e+02, -5.46264835e-03])]} +{'AngularVelocity': array([-0.03264299, 0.00933992, -5.42141438]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.705894470214844, + 'FR_Wheel_Angle': 33.2996711730957, + 'Location': array([-5.11560097e+01, 9.57894440e+01, 3.10381223e-02]), + 'Rotation': array([ 1.40927285e-01, -1.76369476e+02, -2.55432054e-02]), + 'Velocity': array([ 0.51258224, 0.20216548, -0.00196966]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3406.255615234375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9676.8828125 , 10453.32128906, 116.73579407]), + 'frame': 21785, + 'frame_number': 21785, + 'framesequence': 87833, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5813043713569641, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.7310072518885, + 'timestamp_carla': 743730, + 'timestamp_device': 1614333, + 'timestamp_stream': 743.7310072518885, + 'transform': [array([-54.8920784 , 82.1282959 , -0.15376696]), + array([ 1.07712075e-02, -1.15394371e+02, -4.30298038e-03])]} +{'AngularVelocity': array([ 0.08409881, -0.07944374, -6.16761827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.671730041503906, + 'FR_Wheel_Angle': 33.27467346191406, + 'Location': array([-5.10881233e+01, 9.58113556e+01, 3.09217349e-02]), + 'Rotation': array([ 1.39438301e-01, -1.77101151e+02, -2.53601056e-02]), + 'Velocity': array([ 0.57791013, 0.21771614, -0.00122218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2801.680419921875, + 'focus_actor_name': 'BP_Lamppost_tall33', + 'focus_actor_pt': array([-9137.3203125 , 10176.37207031, 116.89809418]), + 'frame': 21786, + 'frame_number': 21786, + 'framesequence': 87837, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5867244601249695, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.763794451952, + 'timestamp_carla': 743763, + 'timestamp_device': 1614366, + 'timestamp_stream': 743.763794451952, + 'transform': [array([-54.84703064, 82.1644516 , -0.15421185]), + array([ 8.24403763e-03, -1.15143211e+02, -2.68554827e-03])]} +{'AngularVelocity': array([-0.0177657 , 0.02984108, -6.6547718 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.00041961669922, + 'FR_Wheel_Angle': 38.531158447265625, + 'Location': array([-5.10088387e+01, 9.58358078e+01, 3.07273772e-02]), + 'Rotation': array([ 1.37689769e-01, -1.77975433e+02, -2.59704590e-02]), + 'Velocity': array([ 0.56925035, 0.21847142, -0.00123169]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3445.976806640625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9723.19140625, 10440.93847656, 116.9105835 ]), + 'frame': 21787, + 'frame_number': 21787, + 'framesequence': 87841, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5957335233688354, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.797166749835, + 'timestamp_carla': 743796, + 'timestamp_device': 1614400, + 'timestamp_stream': 743.797166749835, + 'transform': [array([-54.80048752, 82.20251465, -0.15461566]), + array([ 6.40671700e-03, -1.14881180e+02, -1.19018648e-03])]} +{'AngularVelocity': array([-0.03091999, 0.00918703, -7.12158108]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.57427215576172, + 'FR_Wheel_Angle': 37.00712585449219, + 'Location': array([-5.09350815e+01, 9.58600845e+01, 3.05315685e-02]), + 'Rotation': array([ 1.39807135e-01, -1.78895599e+02, -2.77099609e-02]), + 'Velocity': array([ 0.54420412, 0.22231452, -0.00095046]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3450.6748046875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9732.66503906, 10427.95996094, 117.00962067]), + 'frame': 21788, + 'frame_number': 21788, + 'framesequence': 87845, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.830399248749, + 'timestamp_carla': 743829, + 'timestamp_device': 1614433, + 'timestamp_stream': 743.830399248749, + 'transform': [array([-54.75333786, 82.24173737, -0.15492205]), + array([ 4.91090585e-03, -1.14613754e+02, -6.10362695e-05])]} +{'AngularVelocity': array([-1.95874367e-02, 3.43405409e-03, -6.54602671e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.051725387573242, + 'FR_Wheel_Angle': 37.5975341796875, + 'Location': array([-5.08622208e+01, 9.58826065e+01, 3.03437319e-02]), + 'Rotation': array([ 1.39704674e-01, -1.79778183e+02, -3.40881273e-02]), + 'Velocity': array([ 0.53476715, 0.196466 , -0.00109111]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3455.622314453125, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9742.56835938, 10414.39355469, 117.1003418 ]), + 'frame': 21789, + 'frame_number': 21789, + 'framesequence': 87848, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.8638954497874, + 'timestamp_carla': 743863, + 'timestamp_device': 1614458, + 'timestamp_stream': 743.8638954497874, + 'transform': [array([-54.70527649, 82.2822113 , -0.15518387]), + array([ 3.81807564e-03, -1.14339249e+02, 9.15244571e-04])]} +{'AngularVelocity': array([-0.05301387, -0.0070135 , -6.41669464]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.371187210083008, + 'FR_Wheel_Angle': 37.41825866699219, + 'Location': array([-5.07946510e+01, 9.59023819e+01, 3.01465504e-02]), + 'Rotation': array([ 1.39356345e-01, 1.79398941e+02, -3.55224572e-02]), + 'Velocity': array([ 0.52861553, 0.18592453, -0.002035 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3460.735107421875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9752.69433594, 10400.52050781, 117.16911316]), + 'frame': 21790, + 'frame_number': 21790, + 'framesequence': 87853, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.897051949054, + 'timestamp_carla': 743896, + 'timestamp_device': 1614500, + 'timestamp_stream': 743.897051949054, + 'transform': [array([-54.65791321, 82.32227325, -0.155441 ]), + array([ 2.32226425e-03, -1.14068443e+02, 1.84415013e-03])]} +{'AngularVelocity': array([-1.28103523e-02, 1.23456423e-03, -6.21395636e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.20732307434082, + 'FR_Wheel_Angle': 37.49718475341797, + 'Location': array([-5.07275581e+01, 9.59210205e+01, 3.00075430e-02]), + 'Rotation': array([ 1.38646007e-01, 1.78587082e+02, -3.78723145e-02]), + 'Velocity': array([ 0.51815021, 0.17739958, -0.00113225]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3466.059326171875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9763.11523438, 10386.24316406, 117.22852325]), + 'frame': 21791, + 'frame_number': 21791, + 'framesequence': 87857, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.9302960522473, + 'timestamp_carla': 743929, + 'timestamp_device': 1614533, + 'timestamp_stream': 743.9302960522473, + 'transform': [array([-54.61000443, 82.36322021, -0.15563165]), + array([ 1.12698111e-03, -1.13793190e+02, 2.52033886e-03])]} +{'AngularVelocity': array([ 0.01562146, -0.01065804, -6.56226587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.23175811767578, + 'FR_Wheel_Angle': 37.430118560791016, + 'Location': array([-5.06580811e+01, 9.59391708e+01, 2.98341643e-02]), + 'Rotation': array([ 1.38065442e-01, 1.77746750e+02, -3.96728404e-02]), + 'Velocity': array([ 0.51263243, 0.16815962, -0.00144769]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3471.4208984375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9773.42773438, 10372.1171875 , 117.28595734]), + 'frame': 21792, + 'frame_number': 21792, + 'framesequence': 87861, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3690241873264313, + 'timestamp': 743.9643584489822, + 'timestamp_carla': 743963, + 'timestamp_device': 1614566, + 'timestamp_stream': 743.9643584489822, + 'transform': [array([-54.5604248 , 82.40603638, -0.15577947]), + array([ 1.57094342e-04, -1.13507217e+02, 3.01211281e-03])]} +{'AngularVelocity': array([ 0.01799903, -0.00994227, -6.44720268]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.266292572021484, + 'FR_Wheel_Angle': 37.450828552246094, + 'Location': array([-5.05912895e+01, 9.59555817e+01, 2.96785627e-02]), + 'Rotation': array([ 1.37361929e-01, 1.76942581e+02, -4.13513146e-02]), + 'Velocity': array([ 0.50545019, 0.15819344, -0.00155637]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3476.959228515625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9783.93261719, 10357.72558594, 117.32794189]), + 'frame': 21793, + 'frame_number': 21793, + 'framesequence': 87865, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5983337163925171, + 'throttle_input': 0.3491874635219574, + 'timestamp': 743.9974328503013, + 'timestamp_carla': 743996, + 'timestamp_device': 1614600, + 'timestamp_stream': 743.9974328503013, + 'transform': [array([-54.51119614, 82.44897461, -0.155792 ]), + array([-1.70754720e-04, -1.13222076e+02, 3.04626371e-03])]} +{'AngularVelocity': array([-0.02647546, 0.00660884, -5.90611935]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.26802635192871, + 'FR_Wheel_Angle': 37.46486282348633, + 'Location': array([-5.05243454e+01, 9.59710693e+01, 2.95161717e-02]), + 'Rotation': array([ 1.36419356e-01, 1.76142487e+02, -4.27246019e-02]), + 'Velocity': array([ 0.49972257, 0.14697929, -0.00154985]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3482.81005859375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9794.875 , 10342.734375 , 117.35812378]), + 'frame': 21794, + 'frame_number': 21794, + 'framesequence': 87868, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.598736584186554, + 'throttle_input': 0.34125277400016785, + 'timestamp': 744.0294294506311, + 'timestamp_carla': 744028, + 'timestamp_device': 1614625, + 'timestamp_stream': 744.0294294506311, + 'transform': [array([-54.46257019, 82.49166107, -0.15573883]), + array([-2.59547174e-04, -1.12939827e+02, 2.85501871e-03])]} +{'AngularVelocity': array([ 3.55096790e-03, -4.17174306e-03, -6.12492180e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.27109718322754, + 'FR_Wheel_Angle': 37.468833923339844, + 'Location': array([-5.04590530e+01, 9.59852448e+01, 2.93733496e-02]), + 'Rotation': array([ 1.36002719e-01, 1.75363266e+02, -4.47082520e-02]), + 'Velocity': array([ 0.49350893, 0.13892592, -0.00095765]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3488.744873046875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9805.81347656, 10327.75 , 117.36117554]), + 'frame': 21795, + 'frame_number': 21795, + 'framesequence': 87872, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.599761962890625, + 'throttle_input': 0.33728542923927307, + 'timestamp': 744.0632561519742, + 'timestamp_carla': 744062, + 'timestamp_device': 1614658, + 'timestamp_stream': 744.0632561519742, + 'transform': [array([-54.41022491, 82.53813934, -0.1557361 ]), + array([-5.39584900e-04, -1.12634468e+02, 2.77988683e-03])]} +{'AngularVelocity': array([ 4.91997041e-03, -6.92981668e-03, -6.12655783e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.27203369140625, + 'FR_Wheel_Angle': 37.46781921386719, + 'Location': array([-5.03936958e+01, 9.59984741e+01, 2.92175580e-02]), + 'Rotation': array([ 1.35087475e-01, 1.74582779e+02, -4.60815355e-02]), + 'Velocity': array([ 0.49374089, 0.13160542, -0.00099857]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3494.730224609375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9816.671875 , 10312.87402344, 117.35098267]), + 'frame': 21796, + 'frame_number': 21796, + 'framesequence': 87876, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.0947692506015, + 'timestamp_carla': 744094, + 'timestamp_device': 1614691, + 'timestamp_stream': 744.0947692506015, + 'transform': [array([-54.36070251, 82.58257294, -0.15570743]), + array([-7.58150942e-04, -1.12344284e+02, 2.68426398e-03])]} +{'AngularVelocity': array([ 0.04593437, -0.03551433, -6.88633537]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.279489517211914, + 'FR_Wheel_Angle': 37.49274444580078, + 'Location': array([-5.03268776e+01, 9.60108948e+01, 2.90592853e-02]), + 'Rotation': array([ 1.33168191e-01, 1.73778259e+02, -4.65698242e-02]), + 'Velocity': array([ 0.52582955, 0.13181154, -0.00119796]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3467.22705078125, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9796.98925781, 10283.61523438, 117.34455109]), + 'frame': 21797, + 'frame_number': 21797, + 'framesequence': 87881, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.1296161524951, + 'timestamp_carla': 744129, + 'timestamp_device': 1614733, + 'timestamp_stream': 744.1296161524951, + 'transform': [array([-54.30437851, 82.63366699, -0.15565665]), + array([-7.64981145e-04, -1.12012856e+02, 2.39056605e-03])]} +{'AngularVelocity': array([ 0.11674512, -0.03078594, -6.28468657]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.568317413330078, + 'FR_Wheel_Angle': 39.105018615722656, + 'Location': array([-5.02621765e+01, 9.60216064e+01, 2.88962461e-02]), + 'Rotation': array([ 1.33741930e-01, 1.73051773e+02, -4.88891490e-02]), + 'Velocity': array([ 0.49642429, 0.12680031, -0.0011912 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3475.426513671875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9809.84570312, 10269.08886719, 117.34054565]), + 'frame': 21798, + 'frame_number': 21798, + 'framesequence': 87884, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.1611451506615, + 'timestamp_carla': 744160, + 'timestamp_device': 1614758, + 'timestamp_stream': 744.1611451506615, + 'transform': [array([-54.25306702, 82.68069458, -0.15564868]), + array([-1.07916980e-03, -1.11709419e+02, 2.38373596e-03])]} +{'AngularVelocity': array([-0.07000108, -0.01501129, -7.14491367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.739967346191406, + 'FR_Wheel_Angle': 41.02280044555664, + 'Location': array([-5.01908302e+01, 9.60342178e+01, 2.87621208e-02]), + 'Rotation': array([ 1.29145205e-01, 1.72161636e+02, -4.35791016e-02]), + 'Velocity': array([ 5.79848647e-01, 1.39670745e-01, -5.63693058e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3484.93701171875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9824.58984375, 10252.42773438, 117.32139587]), + 'frame': 21799, + 'frame_number': 21799, + 'framesequence': 87889, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.1976616494358, + 'timestamp_carla': 744197, + 'timestamp_device': 1614800, + 'timestamp_stream': 744.1976616494358, + 'transform': [array([-54.19263077, 82.73668671, -0.15569609]), + array([-1.37969817e-03, -1.11350266e+02, 2.41788663e-03])]} +{'AngularVelocity': array([-0.15264787, 0.0244166 , -6.95633173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.56643295288086, + 'FR_Wheel_Angle': 41.58925247192383, + 'Location': array([-5.01153831e+01, 9.60479355e+01, 2.85683721e-02]), + 'Rotation': array([ 1.29227176e-01, 1.71169128e+02, -4.86450121e-02]), + 'Velocity': array([ 0.57779354, 0.1288826 , -0.00149765]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3493.78564453125, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9838.15234375, 10237.10351562, 117.32306671]), + 'frame': 21800, + 'frame_number': 21800, + 'framesequence': 87892, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.229210048914, + 'timestamp_carla': 744228, + 'timestamp_device': 1614825, + 'timestamp_stream': 744.229210048914, + 'transform': [array([-54.13985062, 82.78618622, -0.15568119]), + array([-1.58460380e-03, -1.11034683e+02, 2.42471672e-03])]} +{'AngularVelocity': array([-9.54106525e-02, 2.43091607e-03, -7.08841753e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.741392135620117, + 'FR_Wheel_Angle': 41.5899658203125, + 'Location': array([-5.00392952e+01, 9.60607071e+01, 2.83780955e-02]), + 'Rotation': array([ 1.29411593e-01, 1.70160614e+02, -5.29174730e-02]), + 'Velocity': array([ 0.58256662, 0.12661158, -0.00133814]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3542.7705078125, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9889.98730469, 10232.83691406, 117.3243103 ]), + 'frame': 21801, + 'frame_number': 21801, + 'framesequence': 87896, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.263839751482, + 'timestamp_carla': 744263, + 'timestamp_device': 1614858, + 'timestamp_stream': 744.263839751482, + 'transform': [array([-54.0811615 , 82.84172058, -0.15571073]), + array([-1.93294347e-03, -1.10682541e+02, 2.47252826e-03])]} +{'AngularVelocity': array([-9.58223641e-02, 1.71762530e-03, -7.09618902e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.740671157836914, + 'FR_Wheel_Angle': 41.59089660644531, + 'Location': array([-4.99627228e+01, 9.60723343e+01, 2.81951427e-02]), + 'Rotation': array([ 1.28810525e-01, 1.69143906e+02, -5.67016527e-02]), + 'Velocity': array([ 0.58492589, 0.11586078, -0.00120737]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3597.666015625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9946.66992188, 10232.83691406, 117.32939148]), + 'frame': 21802, + 'frame_number': 21802, + 'framesequence': 87900, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.294893451035, + 'timestamp_carla': 744294, + 'timestamp_device': 1614891, + 'timestamp_stream': 744.294893451035, + 'transform': [array([-54.0282402 , 82.89241791, -0.15572722]), + array([-2.28811335e-03, -1.10362999e+02, 2.58864183e-03])]} +{'AngularVelocity': array([-0.11897566, 0.01342407, -7.06995583]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74032974243164, + 'FR_Wheel_Angle': 41.58998107910156, + 'Location': array([-4.98870239e+01, 9.60824509e+01, 2.80243196e-02]), + 'Rotation': array([ 1.27956763e-01, 1.68141388e+02, -5.97534142e-02]), + 'Velocity': array([ 0.58420503, 0.10347013, -0.00116503]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3660.927734375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-10011.91210938, 10232.83691406, 117.33448792]), + 'frame': 21803, + 'frame_number': 21803, + 'framesequence': 87904, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.3247311525047, + 'timestamp_carla': 744324, + 'timestamp_device': 1614925, + 'timestamp_stream': 744.3247311525047, + 'transform': [array([-53.97567749, 82.94464874, -0.15582739]), + array([-2.58181128e-03, -1.10039543e+02, 2.75939633e-03])]} +{'AngularVelocity': array([-0.12527804, 0.01790225, -7.05641413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74030303955078, + 'FR_Wheel_Angle': 41.58595275878906, + 'Location': array([-4.98099709e+01, 9.60913467e+01, 2.78357603e-02]), + 'Rotation': array([ 1.26952723e-01, 1.67123169e+02, -6.24084361e-02]), + 'Velocity': array([ 0.58463299, 0.09203272, -0.0011328 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3720.23876953125, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-10073.02050781, 10232.83691406, 117.34687042]), + 'frame': 21804, + 'frame_number': 21804, + 'framesequence': 87908, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.3570164516568, + 'timestamp_carla': 744356, + 'timestamp_device': 1614958, + 'timestamp_stream': 744.3570164516568, + 'transform': [array([-53.92055893, 82.99867249, -0.1559457 ]), + array([-3.57901887e-03, -1.09702965e+02, 3.26483115e-03])]} +{'AngularVelocity': array([-0.13022013, 0.02220347, -7.062747 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73917579650879, + 'FR_Wheel_Angle': 41.589752197265625, + 'Location': array([-4.97328606e+01, 9.60988770e+01, 2.76518147e-02]), + 'Rotation': array([ 1.25839397e-01, 1.66104279e+02, -6.46362156e-02]), + 'Velocity': array([ 0.58544308, 0.081489 , -0.00144487]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3782.02392578125, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-10136.70605469, 10232.83691406, 117.35590363]), + 'frame': 21805, + 'frame_number': 21805, + 'framesequence': 87912, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.599285900592804, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.391870751977, + 'timestamp_carla': 744391, + 'timestamp_device': 1614991, + 'timestamp_stream': 744.391870751977, + 'transform': [array([-53.86112595, 83.05755615, -0.15608482]), + array([-4.29618871e-03, -1.09337959e+02, 3.76343494e-03])]} +{'AngularVelocity': array([-0.11998656, 0.02222583, -6.77130985]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.735275268554688, + 'FR_Wheel_Angle': 41.5804328918457, + 'Location': array([-4.96556129e+01, 9.61050262e+01, 2.74669547e-02]), + 'Rotation': array([ 1.24780722e-01, 1.65088852e+02, -6.70471042e-02]), + 'Velocity': array([ 0.5839693 , 0.07095189, -0.00171252]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3848.678955078125, + 'focus_actor_name': 'BP_Block05_33', + 'focus_actor_pt': array([-10205.25195312, 10232.83398438, 117.39641571]), + 'frame': 21806, + 'frame_number': 21806, + 'framesequence': 87916, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5852962136268616, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.4221310503781, + 'timestamp_carla': 744421, + 'timestamp_device': 1615025, + 'timestamp_stream': 744.4221310503781, + 'transform': [array([-53.80917358, 83.10895538, -0.15601535]), + array([-5.08849043e-03, -1.09020279e+02, 3.51071777e-03])]} +{'AngularVelocity': array([-0.08901373, 0.00913938, -7.04418898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74104118347168, + 'FR_Wheel_Angle': 41.591163635253906, + 'Location': array([-4.95783386e+01, 9.61097336e+01, 2.72994507e-02]), + 'Rotation': array([ 1.23435169e-01, 1.64072128e+02, -6.88781589e-02]), + 'Velocity': array([ 0.59187043, 0.06325679, -0.00136842]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3923.61767578125, + 'focus_actor_name': 'BP_Block05_33', + 'focus_actor_pt': array([-10282.23535156, 10232.83496094, 117.43500519]), + 'frame': 21807, + 'frame_number': 21807, + 'framesequence': 87919, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5681204199790955, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.4542057514191, + 'timestamp_carla': 744453, + 'timestamp_device': 1615050, + 'timestamp_stream': 744.4542057514191, + 'transform': [array([-53.75272369, 83.16482544, -0.15582445]), + array([-5.38901892e-03, -1.08676315e+02, 2.69792508e-03])]} +{'AngularVelocity': array([-0.09165337, 0.00932266, -7.06309843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.741910934448242, + 'FR_Wheel_Angle': 41.59172439575195, + 'Location': array([-4.95018730e+01, 9.61131363e+01, 2.71313377e-02]), + 'Rotation': array([ 1.22356005e-01, 1.63069000e+02, -7.09838718e-02]), + 'Velocity': array([ 0.59124726, 0.05265948, -0.00127868]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3991.237060546875, + 'focus_actor_name': 'BP_Block05_33', + 'focus_actor_pt': array([-10351.578125 , 10232.83496094, 117.42562103]), + 'frame': 21808, + 'frame_number': 21808, + 'framesequence': 87923, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5445906519889832, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.4872095510364, + 'timestamp_carla': 744486, + 'timestamp_device': 1615083, + 'timestamp_stream': 744.4872095510364, + 'transform': [array([-53.69540787, 83.22074127, -0.15578109]), + array([-6.83701877e-03, -1.08331375e+02, 2.34275521e-03])]} +{'AngularVelocity': array([-7.92945027e-02, 2.24708952e-03, -7.02044249e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74214744567871, + 'FR_Wheel_Angle': 41.59213638305664, + 'Location': array([-4.94247704e+01, 9.61151962e+01, 2.69429293e-02]), + 'Rotation': array([ 1.21078759e-01, 1.62056656e+02, -7.29064718e-02]), + 'Velocity': array([ 0.59252721, 0.04333588, -0.00148226]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4067.0888671875, + 'focus_actor_name': 'BP_Block05_33', + 'focus_actor_pt': array([-10429.24121094, 10232.83496094, 117.37379456]), + 'frame': 21809, + 'frame_number': 21809, + 'framesequence': 87927, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5217017531394958, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.5213205516338, + 'timestamp_carla': 744520, + 'timestamp_device': 1615116, + 'timestamp_stream': 744.5213205516338, + 'transform': [array([-53.63768387, 83.27584839, -0.15588082]), + array([-9.08415113e-03, -1.07990105e+02, 2.47252942e-03])]} +{'AngularVelocity': array([-0.11863659, 0.024869 , -7.10082197]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74047088623047, + 'FR_Wheel_Angle': 41.591678619384766, + 'Location': array([-4.93480034e+01, 9.61158752e+01, 2.67721079e-02]), + 'Rotation': array([ 1.19753703e-01, 1.61050995e+02, -7.51953050e-02]), + 'Velocity': array([ 0.58850837, 0.02864203, -0.00112363]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4146.166015625, + 'focus_actor_name': 'BP_Block05_33', + 'focus_actor_pt': array([-10510.01953125, 10232.83496094, 117.35283661]), + 'frame': 21810, + 'frame_number': 21810, + 'framesequence': 87932, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5134068131446838, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.5562037490308, + 'timestamp_carla': 744555, + 'timestamp_device': 1615158, + 'timestamp_stream': 744.5562037490308, + 'transform': [array([-53.58018494, 83.33011627, -0.15609394]), + array([-1.10853966e-02, -1.07653847e+02, 3.10090743e-03])]} +{'AngularVelocity': array([-7.74057880e-02, 3.05445748e-03, -7.04913235e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74261474609375, + 'FR_Wheel_Angle': 41.58932113647461, + 'Location': array([-4.92715111e+01, 9.61152191e+01, 2.66003311e-02]), + 'Rotation': array([ 1.18374005e-01, 1.60047699e+02, -7.66906664e-02]), + 'Velocity': array([ 0.59292954, 0.02258604, -0.00139532]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8085.986328125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14262.74023438, 11424.51367188, 117.53302002]), + 'frame': 21811, + 'frame_number': 21811, + 'framesequence': 87936, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5212805867195129, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.5878418497741, + 'timestamp_carla': 744587, + 'timestamp_device': 1615191, + 'timestamp_stream': 744.5878418497741, + 'transform': [array([-53.52806473, 83.38007355, -0.15622416]), + array([-1.17069436e-02, -1.07346970e+02, 3.65415262e-03])]} +{'AngularVelocity': array([-0.12776895, 0.03762877, -6.97660494]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74203109741211, + 'FR_Wheel_Angle': 41.591426849365234, + 'Location': array([-4.91947708e+01, 9.61132278e+01, 2.64262296e-02]), + 'Rotation': array([ 1.17028452e-01, 1.59041473e+02, -7.89489597e-02]), + 'Velocity': array([ 0.58435076, 0.00837724, -0.00142236]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8073.10693359375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14262.74023438, 11373.74609375, 117.62123871]), + 'frame': 21812, + 'frame_number': 21812, + 'framesequence': 87939, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5336955189704895, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.6208232492208, + 'timestamp_carla': 744620, + 'timestamp_device': 1615216, + 'timestamp_stream': 744.6208232492208, + 'transform': [array([-53.47288895, 83.43450928, -0.15630084]), + array([-1.09283021e-02, -1.07016411e+02, 4.06396296e-03])]} +{'AngularVelocity': array([-0.10099073, 0.02369148, -6.91017818]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74195671081543, + 'FR_Wheel_Angle': 41.59053421020508, + 'Location': array([-4.91184654e+01, 9.61099319e+01, 2.62555592e-02]), + 'Rotation': array([ 1.15607776e-01, 1.58038834e+02, -8.08105394e-02]), + 'Velocity': array([ 5.86163759e-01, -8.88850554e-05, -1.22647756e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8070.7431640625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14271.43066406, 11330.29785156, 117.70101929]), + 'frame': 21813, + 'frame_number': 21813, + 'framesequence': 87943, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5464217066764832, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.6545892506838, + 'timestamp_carla': 744654, + 'timestamp_device': 1615250, + 'timestamp_stream': 744.6545892506838, + 'transform': [array([-53.41611099, 83.49202728, -0.1564088 ]), + array([-9.73984879e-03, -1.06670258e+02, 4.62403940e-03])]} +{'AngularVelocity': array([-0.12883058, 0.04434542, -6.88915396]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.743257522583008, + 'FR_Wheel_Angle': 41.595760345458984, + 'Location': array([-4.90418625e+01, 9.61053009e+01, 2.60797404e-02]), + 'Rotation': array([ 1.14166602e-01, 1.57033539e+02, -8.27941820e-02]), + 'Velocity': array([ 0.58123839, -0.01227301, -0.00164747]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8058.6171875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14271.4296875 , 11280.69140625, 117.7571106 ]), + 'frame': 21814, + 'frame_number': 21814, + 'framesequence': 87947, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5532517433166504, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.6871602497995, + 'timestamp_carla': 744686, + 'timestamp_device': 1615283, + 'timestamp_stream': 744.6871602497995, + 'transform': [array([-53.36112976, 83.54914093, -0.15649937]), + array([-8.86558462e-03, -1.06329788e+02, 5.12264250e-03])]} +{'AngularVelocity': array([-0.10563142, 0.02913003, -6.99829149]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.741897583007812, + 'FR_Wheel_Angle': 41.59403610229492, + 'Location': array([-4.89662895e+01, 9.60993423e+01, 2.59196367e-02]), + 'Rotation': array([ 1.12698115e-01, 1.56040009e+02, -8.45031515e-02]), + 'Velocity': array([ 0.58336437, -0.02093367, -0.00136898]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8037.1201171875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14262.74023438, 11226.3125 , 117.83228302]), + 'frame': 21815, + 'frame_number': 21815, + 'framesequence': 87952, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5513107776641846, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.722051050514, + 'timestamp_carla': 744721, + 'timestamp_device': 1615325, + 'timestamp_stream': 744.722051050514, + 'transform': [array([-53.30225372, 83.61112213, -0.1565816 ]), + array([-8.33282992e-03, -1.05962189e+02, 5.46415104e-03])]} +{'AngularVelocity': array([-0.10757329, 0.03518798, -6.69006586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.744070053100586, + 'FR_Wheel_Angle': 41.59618377685547, + 'Location': array([-4.88902779e+01, 9.60920715e+01, 2.57437024e-02]), + 'Rotation': array([ 1.11072533e-01, 1.55038818e+02, -8.62731785e-02]), + 'Velocity': array([ 0.5831067 , -0.03123839, -0.00165383]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7920.99658203125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14162.74023438, 11146.31445312, 117.89139557]), + 'frame': 21816, + 'frame_number': 21816, + 'framesequence': 87956, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5443708896636963, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.7557607516646, + 'timestamp_carla': 744755, + 'timestamp_device': 1615358, + 'timestamp_stream': 744.7557607516646, + 'transform': [array([-53.2462883 , 83.67020416, -0.15668403]), + array([-8.85192491e-03, -1.05612762e+02, 5.84664429e-03])]} +{'AngularVelocity': array([-0.09309314, 0.02299576, -7.04259253]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742122650146484, + 'FR_Wheel_Angle': 41.593265533447266, + 'Location': array([-4.88144760e+01, 9.60834122e+01, 2.55886745e-02]), + 'Rotation': array([ 1.09385476e-01, 1.54038727e+02, -8.78295526e-02]), + 'Velocity': array([ 0.58890933, -0.04115053, -0.00084546]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7917.7216796875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14171.4296875 , 11094.92480469, 117.93621063]), + 'frame': 21817, + 'frame_number': 21817, + 'framesequence': 87959, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538090169429779, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.7872103489935, + 'timestamp_carla': 744786, + 'timestamp_device': 1615383, + 'timestamp_stream': 744.7872103489935, + 'transform': [array([-53.19406128, 83.7256546 , -0.15666634]), + array([-9.37101897e-03, -1.05286491e+02, 5.78517094e-03])]} +{'AngularVelocity': array([-0.12154108, 0.04898006, -6.97100782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74222183227539, + 'FR_Wheel_Angle': 41.59386444091797, + 'Location': array([-4.87384377e+01, 9.60734482e+01, 2.54191104e-02]), + 'Rotation': array([ 1.07903324e-01, 1.53033081e+02, -8.98132250e-02]), + 'Velocity': array([ 0.58214402, -0.05262945, -0.00130173]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7906.39111328125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14171.4296875 , 11043.80761719, 117.98835754]), + 'frame': 21818, + 'frame_number': 21818, + 'framesequence': 87963, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5336588621139526, + 'throttle_input': 0.3293507397174835, + 'timestamp': 744.8206808492541, + 'timestamp_carla': 744820, + 'timestamp_device': 1615416, + 'timestamp_stream': 744.8206808492541, + 'transform': [array([-53.13803482, 83.78565979, -0.15659791]), + array([-9.48713254e-03, -1.04935272e+02, 5.46415104e-03])]} +{'AngularVelocity': array([-0.11916353, 0.04762372, -7.00873041]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742252349853516, + 'FR_Wheel_Angle': 41.596073150634766, + 'Location': array([-4.86624222e+01, 9.60621338e+01, 2.52455045e-02]), + 'Rotation': array([ 1.06359698e-01, 1.52024139e+02, -9.16137695e-02]), + 'Velocity': array([ 0.5809412 , -0.06269718, -0.00132299]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7896.15283203125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14171.4296875 , 10996.234375 , 117.98095703]), + 'frame': 21819, + 'frame_number': 21819, + 'framesequence': 87967, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5344096422195435, + 'throttle_input': 0.32538339495658875, + 'timestamp': 744.8541298508644, + 'timestamp_carla': 744853, + 'timestamp_device': 1615450, + 'timestamp_stream': 744.8541298508644, + 'transform': [array([-53.08221054, 83.84606171, -0.15658474]), + array([-9.56226420e-03, -1.04583595e+02, 5.38902078e-03])]} +{'AngularVelocity': array([-0.0854314 , 0.02301137, -6.95562315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742870330810547, + 'FR_Wheel_Angle': 41.59389877319336, + 'Location': array([-4.85874100e+01, 9.60496063e+01, 2.50913519e-02]), + 'Rotation': array([ 1.04577020e-01, 1.51026901e+02, -9.29870605e-02]), + 'Velocity': array([ 0.5871976 , -0.070878 , -0.00138743]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7885.47802734375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14171.4296875 , 10945.171875 , 117.93545532]), + 'frame': 21820, + 'frame_number': 21820, + 'framesequence': 87971, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5373943448066711, + 'throttle_input': 0.3174487054347992, + 'timestamp': 744.8877882510424, + 'timestamp_carla': 744887, + 'timestamp_device': 1615483, + 'timestamp_stream': 744.8877882510424, + 'transform': [array([-53.02616882, 83.90757751, -0.15660925]), + array([-9.50762257e-03, -1.04227592e+02, 5.48464339e-03])]} +{'AngularVelocity': array([-0.07896434, 0.0184677 , -7.03926516]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74275779724121, + 'FR_Wheel_Angle': 41.5940055847168, + 'Location': array([-4.85121956e+01, 9.60357208e+01, 2.49342248e-02]), + 'Rotation': array([ 1.02951437e-01, 1.50023544e+02, -9.47570726e-02]), + 'Velocity': array([ 0.58659512, -0.08110789, -0.00117493]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7855.63671875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14152.5546875 , 10889.28125 , 117.92211914]), + 'frame': 21821, + 'frame_number': 21821, + 'framesequence': 87975, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5409833192825317, + 'throttle_input': 0.31348133087158203, + 'timestamp': 744.9210279509425, + 'timestamp_carla': 744920, + 'timestamp_device': 1615516, + 'timestamp_stream': 744.9210279509425, + 'transform': [array([-52.9709549 , 83.96916962, -0.15664819]), + array([-9.38467961e-03, -1.03873276e+02, 5.66905737e-03])]} +{'AngularVelocity': array([-0.07766002, 0.01891146, -7.03579998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742631912231445, + 'FR_Wheel_Angle': 41.591529846191406, + 'Location': array([-4.84373436e+01, 9.60204849e+01, 2.47770213e-02]), + 'Rotation': array([ 1.01257548e-01, 1.49022034e+02, -9.64965671e-02]), + 'Velocity': array([ 0.58566242, -0.09173628, -0.00072141]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4824.28564453125, + 'focus_actor_name': 'AmericanLights_Town04_34_TrafficLight', + 'focus_actor_pt': array([-11223.97167969, 10095.40429688, 117.64465332]), + 'frame': 21822, + 'frame_number': 21822, + 'framesequence': 87979, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5426679253578186, + 'throttle_input': 0.3055466413497925, + 'timestamp': 744.9530291520059, + 'timestamp_carla': 744952, + 'timestamp_device': 1615550, + 'timestamp_stream': 744.9530291520059, + 'transform': [array([-52.91759109, 84.02964783, -0.15663022]), + array([-9.11147147e-03, -1.03527695e+02, 5.66222798e-03])]} +{'AngularVelocity': array([-0.07968028, 0.02379015, -6.83896542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742700576782227, + 'FR_Wheel_Angle': 41.59674072265625, + 'Location': array([-4.83614388e+01, 9.60036697e+01, 2.45947167e-02]), + 'Rotation': array([ 9.98437032e-02, 1.48005508e+02, -9.85412672e-02]), + 'Velocity': array([ 0.57547182, -0.10072555, -0.00122639]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7743.30029296875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14062.74023438, 10764.82226562, 117.94897461]), + 'frame': 21823, + 'frame_number': 21823, + 'framesequence': 87983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5417340993881226, + 'throttle_input': 0.3015792965888977, + 'timestamp': 744.9872716516256, + 'timestamp_carla': 744986, + 'timestamp_device': 1615583, + 'timestamp_stream': 744.9872716516256, + 'transform': [array([-52.86050034, 84.09524536, -0.15664315]), + array([-8.92022625e-03, -1.03154869e+02, 5.68954740e-03])]} +{'AngularVelocity': array([-0.07991865, 0.02287068, -6.99537754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74408721923828, + 'FR_Wheel_Angle': 41.576969146728516, + 'Location': array([-4.82889900e+01, 9.59862595e+01, 2.44620405e-02]), + 'Rotation': array([ 9.79312435e-02, 1.47027435e+02, -9.97009352e-02]), + 'Velocity': array([ 0.57670647, -0.11096255, -0.0011853 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7734.263671875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14062.74121094, 10715.84179688, 117.94786072]), + 'frame': 21824, + 'frame_number': 21824, + 'framesequence': 87987, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399395823478699, + 'throttle_input': 0.3015792965888977, + 'timestamp': 745.0197980515659, + 'timestamp_carla': 745019, + 'timestamp_device': 1615616, + 'timestamp_stream': 745.0197980515659, + 'transform': [array([-52.80687332, 84.1574173 , -0.15669629]), + array([-9.28905699e-03, -1.02802979e+02, 5.90128498e-03])]} +{'AngularVelocity': array([-0.08439944, 0.03395453, -7.02348042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74065399169922, + 'FR_Wheel_Angle': 41.589603424072266, + 'Location': array([-4.82143631e+01, 9.59668732e+01, 2.43035033e-02]), + 'Rotation': array([ 9.55543444e-02, 1.46015121e+02, -1.00646958e-01]), + 'Velocity': array([ 0.58435863, -0.12326017, -0.00136467]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7724.861328125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14062.74023438, 10663.14160156, 117.94930267]), + 'frame': 21825, + 'frame_number': 21825, + 'framesequence': 87991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538694441318512, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.0550607517362, + 'timestamp_carla': 745054, + 'timestamp_device': 1615650, + 'timestamp_stream': 745.0550607517362, + 'transform': [array([-52.7493248 , 84.22480011, -0.15679872]), + array([-9.69886780e-03, -1.02423302e+02, 6.21547317e-03])]} +{'AngularVelocity': array([-0.1013304 , 0.05102835, -7.06680012]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.739049911499023, + 'FR_Wheel_Angle': 41.588443756103516, + 'Location': array([-4.81395760e+01, 9.59461594e+01, 2.41392795e-02]), + 'Rotation': array([ 9.41541493e-02, 1.44998383e+02, -1.02813713e-01]), + 'Velocity': array([ 0.57524055, -0.13358025, -0.00119728]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7716.33740234375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14062.74023438, 10613.52441406, 117.9778595 ]), + 'frame': 21826, + 'frame_number': 21826, + 'framesequence': 87995, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538987398147583, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.0862905494869, + 'timestamp_carla': 745085, + 'timestamp_device': 1615683, + 'timestamp_stream': 745.0862905494869, + 'transform': [array([-52.6988945 , 84.28450775, -0.15685013]), + array([-1.01974718e-02, -1.02088684e+02, 6.46135909e-03])]} +{'AngularVelocity': array([-0.0935735 , 0.04408487, -7.061584 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.740570068359375, + 'FR_Wheel_Angle': 41.59067153930664, + 'Location': array([-4.80659523e+01, 9.59243317e+01, 2.39889417e-02]), + 'Rotation': array([ 9.24261138e-02, 1.43990433e+02, -1.04461662e-01]), + 'Velocity': array([ 0.57225221, -0.14296517, -0.00134447]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7716.412109375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14071.4296875 , 10562.03320312, 118.0186615 ]), + 'frame': 21827, + 'frame_number': 21827, + 'framesequence': 87999, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5398114323616028, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.1195256523788, + 'timestamp_carla': 745119, + 'timestamp_device': 1615716, + 'timestamp_stream': 745.1195256523788, + 'transform': [array([-52.64520264, 84.34906769, -0.15687694]), + array([-1.02862641e-02, -1.01729004e+02, 6.55698264e-03])]} +{'AngularVelocity': array([-0.07557822, 0.02417643, -7.04648733]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742399215698242, + 'FR_Wheel_Angle': 41.59229278564453, + 'Location': array([-4.79929237e+01, 9.59013443e+01, 2.38386057e-02]), + 'Rotation': array([ 9.05204937e-02, 1.42986267e+02, -1.05773926e-01]), + 'Velocity': array([ 0.57337826, -0.1521527 , -0.00136742]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7708.94580078125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14071.4296875 , 10515.02832031, 118.05325317]), + 'frame': 21828, + 'frame_number': 21828, + 'framesequence': 88003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5402508974075317, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.1532844491303, + 'timestamp_carla': 745152, + 'timestamp_device': 1615750, + 'timestamp_stream': 745.1532844491303, + 'transform': [array([-52.59137726, 84.41464996, -0.15696526]), + array([-1.05458116e-02, -1.01365456e+02, 6.87800115e-03])]} +{'AngularVelocity': array([-0.08915526, 0.04456824, -7.06867361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.739572525024414, + 'FR_Wheel_Angle': 41.589508056640625, + 'Location': array([-4.79200516e+01, 9.58768616e+01, 2.36961637e-02]), + 'Rotation': array([ 8.83075073e-02, 1.41977325e+02, -1.07086167e-01]), + 'Velocity': array([ 0.57253104, -0.16488953, -0.00108521]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7701.22802734375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14071.4296875 , 10464.625 , 118.06507111]), + 'frame': 21829, + 'frame_number': 21829, + 'framesequence': 88007, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401776432991028, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.1856256499887, + 'timestamp_carla': 745185, + 'timestamp_device': 1615783, + 'timestamp_stream': 745.1856256499887, + 'transform': [array([-52.54047394, 84.47740936, -0.15704939]), + array([-1.09692831e-02, -1.01019211e+02, 7.21951108e-03])]} +{'AngularVelocity': array([-0.08394405, 0.04529453, -6.80986977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.733551025390625, + 'FR_Wheel_Angle': 41.5826416015625, + 'Location': array([-4.78464203e+01, 9.58507919e+01, 2.35298052e-02]), + 'Rotation': array([ 8.64701867e-02, 1.40952469e+02, -1.08612046e-01]), + 'Velocity': array([ 0.56849349, -0.17382602, -0.00158672]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7684.90087890625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14062.73828125, 10412.04492188, 118.10582733]), + 'frame': 21830, + 'frame_number': 21830, + 'framesequence': 88011, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.219674050808, + 'timestamp_carla': 745219, + 'timestamp_device': 1615816, + 'timestamp_stream': 745.219674050808, + 'transform': [array([-52.4874649 , 84.54364014, -0.15713602]), + array([-1.12356609e-02, -1.00655624e+02, 7.52003724e-03])]} +{'AngularVelocity': array([-0.06781861, 0.03040834, -7.06957483]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.738237380981445, + 'FR_Wheel_Angle': 41.59087371826172, + 'Location': array([-4.77735176e+01, 9.58229141e+01, 2.33912170e-02]), + 'Rotation': array([ 8.46465304e-02, 1.39951477e+02, -1.10076867e-01]), + 'Velocity': array([ 0.56750751, -0.18469712, -0.00116466]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7865.9775390625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14247.13574219, 10399.68945312, 118.17540741]), + 'frame': 21831, + 'frame_number': 21831, + 'framesequence': 88015, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.252772051841, + 'timestamp_carla': 745252, + 'timestamp_device': 1615850, + 'timestamp_stream': 745.252772051841, + 'transform': [array([-52.43683624, 84.60756683, -0.15724105]), + array([-1.17001133e-02, -1.00306175e+02, 7.92302191e-03])]} +{'AngularVelocity': array([-0.1076511 , 0.07485121, -6.99494314]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74118995666504, + 'FR_Wheel_Angle': 41.59225082397461, + 'Location': array([-4.77015877e+01, 9.57944336e+01, 2.32323743e-02]), + 'Rotation': array([ 8.31234008e-02, 1.38938904e+02, -1.11755356e-01]), + 'Velocity': array([ 0.55131513, -0.19292845, -0.00130223]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7965.2861328125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14351.63476562, 10367.57226562, 118.22896576]), + 'frame': 21832, + 'frame_number': 21832, + 'framesequence': 88019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.2858846522868, + 'timestamp_carla': 745285, + 'timestamp_device': 1615883, + 'timestamp_stream': 745.2858846522868, + 'transform': [array([-52.38684464, 84.67153931, -0.15732475]), + array([-1.20552834e-02, -9.99582443e+01, 8.24403856e-03])]} +{'AngularVelocity': array([-0.01232312, -0.01808739, -7.62399435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731000900268555, + 'FR_Wheel_Angle': 41.58184051513672, + 'Location': array([-4.76302757e+01, 9.57644806e+01, 2.31063366e-02]), + 'Rotation': array([ 7.97492862e-02, 1.37931015e+02, -1.11450195e-01]), + 'Velocity': array([ 0.58276159, -0.20478754, -0.00157702]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7958.744140625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14351.63476562, 10317.23535156, 118.28456116]), + 'frame': 21833, + 'frame_number': 21833, + 'framesequence': 88023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29761195182800293, + 'timestamp': 745.3198419511318, + 'timestamp_carla': 745319, + 'timestamp_device': 1615916, + 'timestamp_stream': 745.3198419511318, + 'transform': [array([-52.33638 , 84.73690033, -0.15741178]), + array([-1.23284906e-02, -9.96043854e+01, 8.55822675e-03])]} +{'AngularVelocity': array([-0.04794234, 0.04815443, -7.25567961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.742782592773438, + 'FR_Wheel_Angle': 41.599449157714844, + 'Location': array([-4.75583496e+01, 9.57323685e+01, 2.29508486e-02]), + 'Rotation': array([ 7.89911300e-02, 1.36903900e+02, -1.14807136e-01]), + 'Velocity': array([ 0.54693103, -0.20834345, -0.001427 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7952.5439453125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14351.6328125 , 10267.21875 , 118.32859802]), + 'frame': 21834, + 'frame_number': 21834, + 'framesequence': 88027, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.352783549577, + 'timestamp_carla': 745352, + 'timestamp_device': 1615949, + 'timestamp_stream': 745.352783549577, + 'transform': [array([-52.28826523, 84.79992676, -0.15749049]), + array([-1.26768304e-02, -9.92646179e+01, 8.87241680e-03])]} +{'AngularVelocity': array([-0.04532488, 0.03543619, -7.1429677 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74979591369629, + 'FR_Wheel_Angle': 41.605472564697266, + 'Location': array([-4.74900818e+01, 9.57004547e+01, 2.28177160e-02]), + 'Rotation': array([ 7.75362998e-02, 1.35918182e+02, -1.16210915e-01]), + 'Velocity': array([ 0.53230202, -0.21292707, -0.00129284]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8160.673828125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14562.74121094, 10252.16503906, 118.40283966]), + 'frame': 21835, + 'frame_number': 21835, + 'framesequence': 88031, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.3852390497923, + 'timestamp_carla': 745384, + 'timestamp_device': 1615983, + 'timestamp_stream': 745.3852390497923, + 'transform': [array([-52.24139404, 84.86220551, -0.15752237]), + array([-1.28339250e-02, -9.89306564e+01, 9.01585165e-03])]} +{'AngularVelocity': array([-0.04499416, 0.02667233, -6.90784359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.759315490722656, + 'FR_Wheel_Angle': 41.612178802490234, + 'Location': array([-4.74244614e+01, 9.56684875e+01, 2.26790514e-02]), + 'Rotation': array([ 7.62727186e-02, 1.34969177e+02, -1.17797822e-01]), + 'Velocity': array([ 0.50772661, -0.2131625 , -0.0014403 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8760.55078125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-15160.36523438, 10299.68945312, 118.54112244]), + 'frame': 21836, + 'frame_number': 21836, + 'framesequence': 88035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.4196706488729, + 'timestamp_carla': 745419, + 'timestamp_device': 1616016, + 'timestamp_stream': 745.4196706488729, + 'transform': [array([-52.19232941, 84.92816925, -0.15756041]), + array([-1.27997734e-02, -9.85783844e+01, 9.13196523e-03])]} +{'AngularVelocity': array([-0.04318751, 0.02567847, -6.73166084]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.763935089111328, + 'FR_Wheel_Angle': 41.63764953613281, + 'Location': array([-4.73611908e+01, 9.56363449e+01, 2.25591566e-02]), + 'Rotation': array([ 7.41143823e-02, 1.34049454e+02, -1.18255593e-01]), + 'Velocity': array([ 0.49429119, -0.21677047, -0.00123187]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8858.361328125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-15262.73925781, 10263.18066406, 118.57915497]), + 'frame': 21837, + 'frame_number': 21837, + 'framesequence': 88039, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.4528702497482, + 'timestamp_carla': 745452, + 'timestamp_device': 1616049, + 'timestamp_stream': 745.4528702497482, + 'transform': [array([-52.14596558, 84.9911499 , -0.15761994]), + array([-1.30251702e-02, -9.82432709e+01, 9.37101990e-03])]} +{'AngularVelocity': array([-0.04022909, 0.02797718, -6.44748116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.762348175048828, + 'FR_Wheel_Angle': 41.633079528808594, + 'Location': array([-4.73011208e+01, 9.56046143e+01, 2.24592481e-02]), + 'Rotation': array([ 7.23453611e-02, 1.33164917e+02, -1.19354226e-01]), + 'Velocity': array([ 4.74254668e-01, -2.17508256e-01, -4.09626955e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7440.29833984375, + 'focus_actor_name': 'AmericanLights_Town04_37_TrafficLight', + 'focus_actor_pt': array([-13866.36914062, 9996.50585938, 118.36985779]), + 'frame': 21838, + 'frame_number': 21838, + 'framesequence': 88043, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.4857601523399, + 'timestamp_carla': 745485, + 'timestamp_device': 1616083, + 'timestamp_stream': 745.4857601523399, + 'transform': [array([-52.10074615, 85.05337524, -0.1576606 ]), + array([-1.31959245e-02, -9.79137115e+01, 9.54177603e-03])]} +{'AngularVelocity': array([-0.04258061, 0.02325334, -6.46789789]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7733097076416, + 'FR_Wheel_Angle': 41.64333724975586, + 'Location': array([-4.72413559e+01, 9.55718765e+01, 2.23344322e-02]), + 'Rotation': array([ 7.02553242e-02, 1.32277069e+02, -1.19750954e-01]), + 'Velocity': array([ 0.46680996, -0.22283851, -0.00103769]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 9166.4521484375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-15578.69824219, 10199.68945312, 118.68363953]), + 'frame': 21839, + 'frame_number': 21839, + 'framesequence': 88047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.5191154517233, + 'timestamp_carla': 745518, + 'timestamp_device': 1616116, + 'timestamp_stream': 745.5191154517233, + 'transform': [array([-52.05554199, 85.11632538, -0.15769005]), + array([-1.32369054e-02, -9.75816727e+01, 9.65788867e-03])]} +{'AngularVelocity': array([ 0.01103502, -0.05494386, -6.32249022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.774600982666016, + 'FR_Wheel_Angle': 41.65120315551758, + 'Location': array([-4.71833229e+01, 9.55389404e+01, 2.22266279e-02]), + 'Rotation': array([ 6.82950541e-02, 1.31411133e+02, -1.20178215e-01]), + 'Velocity': array([ 0.46605662, -0.22404292, -0.00117441]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13613.5283203125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-19988.50976562, 10758.55566406, 119.452034 ]), + 'frame': 21840, + 'frame_number': 21840, + 'framesequence': 88051, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.5517771504819, + 'timestamp_carla': 745551, + 'timestamp_device': 1616149, + 'timestamp_stream': 745.5517771504819, + 'transform': [array([-52.01198196, 85.17771912, -0.15770951]), + array([-1.32847168e-02, -9.72591629e+01, 9.75351036e-03])]} +{'AngularVelocity': array([-0.03969091, 0.03718859, -5.99065161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77735710144043, + 'FR_Wheel_Angle': 41.60944366455078, + 'Location': array([-4.71272583e+01, 9.55059814e+01, 2.21184064e-02]), + 'Rotation': array([ 6.68060780e-02, 1.30567017e+02, -1.21826142e-01]), + 'Velocity': array([ 0.43360022, -0.22389705, -0.00076494]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13605.1640625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-19988.50976562, 10678.0625 , 119.47809601]), + 'frame': 21841, + 'frame_number': 21841, + 'framesequence': 88055, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.29364460706710815, + 'timestamp': 745.5853823497891, + 'timestamp_carla': 745584, + 'timestamp_device': 1616183, + 'timestamp_stream': 745.5853823497891, + 'transform': [array([-51.96780014, 85.24076843, -0.15772526]), + array([-1.32164154e-02, -9.69293365e+01, 9.80815385e-03])]} +{'AngularVelocity': array([-0.02266458, -0.00875687, -8.64530373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731019973754883, + 'FR_Wheel_Angle': 41.57794952392578, + 'Location': array([-4.70641594e+01, 9.54669418e+01, 2.20340248e-02]), + 'Rotation': array([ 5.87806031e-02, 1.29600296e+02, -1.15020730e-01]), + 'Velocity': array([ 0.54709411, -0.29044697, -0.00113644]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10239.4404296875, + 'focus_actor_name': 'SM_BusStop6_468', + 'focus_actor_pt': array([-16657.3671875 , 10175.67382812, 118.92831421]), + 'frame': 21842, + 'frame_number': 21842, + 'framesequence': 88059, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.6192260496318, + 'timestamp_carla': 745618, + 'timestamp_device': 1616216, + 'timestamp_stream': 745.6192260496318, + 'transform': [array([-51.92416 , 85.30371094, -0.15776165]), + array([-1.32642267e-02, -9.66011658e+01, 9.93792620e-03])]} +{'AngularVelocity': array([-0.02115925, 0.03611601, -8.25529194]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74165916442871, + 'FR_Wheel_Angle': 41.594974517822266, + 'Location': array([-4.69977493e+01, 9.54249496e+01, 2.18936056e-02]), + 'Rotation': array([ 5.94158135e-02, 1.28583954e+02, -1.19995102e-01]), + 'Velocity': array([ 0.518287 , -0.28475019, -0.00087382]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10237.01953125, + 'focus_actor_name': 'SM_BusStop6_468', + 'focus_actor_pt': array([-16659.8984375 , 10115.70898438, 118.93713379]), + 'frame': 21843, + 'frame_number': 21843, + 'framesequence': 88063, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.651738550514, + 'timestamp_carla': 745651, + 'timestamp_device': 1616249, + 'timestamp_stream': 745.651738550514, + 'transform': [array([-51.88290787, 85.36397552, -0.15777683]), + array([-1.33120380e-02, -9.62883377e+01, 1.00267213e-02])]} +{'AngularVelocity': array([-0.01423073, 0.00879955, -8.04628277]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.749267578125, + 'FR_Wheel_Angle': 41.60637664794922, + 'Location': array([-4.69339981e+01, 9.53830338e+01, 2.17625704e-02]), + 'Rotation': array([ 5.92450574e-02, 1.27597176e+02, -1.23504624e-01]), + 'Velocity': array([ 0.49749953, -0.28428337, -0.0008565 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10226.1884765625, + 'focus_actor_name': 'SM_BusStop6_468', + 'focus_actor_pt': array([-16653.703125 , 10055.07617188, 118.95796967]), + 'frame': 21844, + 'frame_number': 21844, + 'framesequence': 88067, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.6874907501042, + 'timestamp_carla': 745687, + 'timestamp_device': 1616283, + 'timestamp_stream': 745.6874907501042, + 'transform': [array([-51.83831024, 85.42987823, -0.1578141 ]), + array([-1.32505661e-02, -9.59474030e+01, 1.01018492e-02])]} +{'AngularVelocity': array([-0.00846049, -0.0127177 , -7.89207745]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75318145751953, + 'FR_Wheel_Angle': 41.614200592041016, + 'Location': array([-4.68737602e+01, 9.53419418e+01, 2.16479395e-02]), + 'Rotation': array([ 5.80224544e-02, 1.26652138e+02, -1.25274628e-01]), + 'Velocity': array([ 0.48007438, -0.28414413, -0.00125758]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13602.1171875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20013.34765625, 10368.2734375 , 119.56536102]), + 'frame': 21845, + 'frame_number': 21845, + 'framesequence': 88071, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.7200389504433, + 'timestamp_carla': 745719, + 'timestamp_device': 1616316, + 'timestamp_stream': 745.7200389504433, + 'transform': [array([-51.79849625, 85.48954773, -0.15783186]), + array([-1.33256987e-02, -9.56400681e+01, 1.02247922e-02])]} +{'AngularVelocity': array([-0.01427761, -0.00985505, -7.70914602]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.759428024291992, + 'FR_Wheel_Angle': 41.62103271484375, + 'Location': array([-4.68149414e+01, 9.53003769e+01, 2.15445608e-02]), + 'Rotation': array([ 5.62397763e-02, 1.25717110e+02, -1.26403794e-01]), + 'Velocity': array([ 0.46363196, -0.28581834, -0.00073224]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13606.654296875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20024.0390625 , 10287.08984375, 119.58176422]), + 'frame': 21846, + 'frame_number': 21846, + 'framesequence': 88075, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.7523361518979, + 'timestamp_carla': 745751, + 'timestamp_device': 1616349, + 'timestamp_stream': 745.7523361518979, + 'transform': [array([-51.75947952, 85.5486908 , -0.15781122]), + array([-1.32232457e-02, -9.53365479e+01, 1.01906434e-02])]} +{'AngularVelocity': array([-0.02671029, 0.01574356, -7.62470722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76076316833496, + 'FR_Wheel_Angle': 41.62623977661133, + 'Location': array([-4.67573433e+01, 9.52582092e+01, 2.14339737e-02]), + 'Rotation': array([ 5.37877381e-02, 1.24788475e+02, -1.26739472e-01]), + 'Velocity': array([ 0.45245579, -0.29213199, -0.00053617]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13611.158203125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20033.6796875 , 10213.87597656, 119.61312103]), + 'frame': 21847, + 'frame_number': 21847, + 'framesequence': 88079, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.7840565517545, + 'timestamp_carla': 745783, + 'timestamp_device': 1616383, + 'timestamp_stream': 745.7840565517545, + 'transform': [array([-51.72151184, 85.60693359, -0.15775514]), + array([-1.29773589e-02, -9.50387268e+01, 1.00198882e-02])]} +{'AngularVelocity': array([-2.28734277e-02, -5.46473311e-03, -7.72395658e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76304054260254, + 'FR_Wheel_Angle': 41.62315368652344, + 'Location': array([-4.67027779e+01, 9.52169113e+01, 2.13458147e-02]), + 'Rotation': array([ 5.13903387e-02, 1.23896507e+02, -1.26647934e-01]), + 'Velocity': array([ 0.45290229, -0.30127296, -0.00104203]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13615.9931640625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20043.20703125, 10141.52148438, 119.60679626]), + 'frame': 21848, + 'frame_number': 21848, + 'framesequence': 88083, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.818545050919, + 'timestamp_carla': 745818, + 'timestamp_device': 1616416, + 'timestamp_stream': 745.818545050919, + 'transform': [array([-51.68070602, 85.67027283, -0.15772173]), + array([-1.26426797e-02, -9.47160034e+01, 9.84913018e-03])]} +{'AngularVelocity': array([-0.02479131, 0.01883579, -7.56259871]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.762617111206055, + 'FR_Wheel_Angle': 41.62815856933594, + 'Location': array([-4.66472511e+01, 9.51735306e+01, 2.12395750e-02]), + 'Rotation': array([ 4.95735109e-02, 1.22981400e+02, -1.27685517e-01]), + 'Velocity': array([ 0.43616492, -0.30071723, -0.00073445]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13621.115234375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20052.55859375, 10070.50097656, 119.56788635]), + 'frame': 21849, + 'frame_number': 21849, + 'framesequence': 88087, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.8514632508159, + 'timestamp_carla': 745851, + 'timestamp_device': 1616449, + 'timestamp_stream': 745.8514632508159, + 'transform': [array([-51.64251328, 85.73022461, -0.15772361]), + array([-1.25812078e-02, -9.44114456e+01, 9.87645425e-03])]} +{'AngularVelocity': array([-0.03095286, -0.01957456, -7.77120113]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.761127471923828, + 'FR_Wheel_Angle': 41.62507247924805, + 'Location': array([-4.65939255e+01, 9.51305542e+01, 2.11540889e-02]), + 'Rotation': array([ 4.71829437e-02, 1.22086731e+02, -1.27349839e-01]), + 'Velocity': array([ 0.44459242, -0.31726748, -0.00074124]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13617.7802734375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20053.41992188, 9992.72460938, 119.52492523]), + 'frame': 21850, + 'frame_number': 21850, + 'framesequence': 88091, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.8854786492884, + 'timestamp_carla': 745885, + 'timestamp_device': 1616483, + 'timestamp_stream': 745.8854786492884, + 'transform': [array([-51.60374832, 85.79175568, -0.1577493 ]), + array([-1.25812078e-02, -9.40999069e+01, 9.95841622e-03])]} +{'AngularVelocity': array([-0.0203394 , 0.00886955, -7.58139515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.765451431274414, + 'FR_Wheel_Angle': 41.62446212768555, + 'Location': array([-4.6539341e+01, 9.5085083e+01, 2.1045560e-02]), + 'Rotation': array([ 4.50246036e-02, 1.21167221e+02, -1.28173813e-01]), + 'Velocity': array([ 0.42984366, -0.31599376, -0.00103661]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 14151.056640625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20588.66601562, 9960.59277344, 119.62361145]), + 'frame': 21851, + 'frame_number': 21851, + 'framesequence': 88095, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5388592481613159, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.9196446500719, + 'timestamp_carla': 745919, + 'timestamp_device': 1616516, + 'timestamp_stream': 745.9196446500719, + 'transform': [array([-51.56557465, 85.85306549, -0.15778647]), + array([-1.26563394e-02, -9.37905197e+01, 1.00881914e-02])]} +{'AngularVelocity': array([-1.36871752e-03, -3.05332113e-02, -6.17405367e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.761104583740234, + 'FR_Wheel_Angle': 41.62678909301758, + 'Location': array([-4.64859962e+01, 9.50390244e+01, 2.09520236e-02]), + 'Rotation': array([ 4.23813201e-02, 1.20262032e+02, -1.27838105e-01]), + 'Velocity': array([ 4.41897988e-01, -3.31490457e-01, -1.95760716e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 15252.177734375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-21690.40820312, 9961.58300781, 119.83454895]), + 'frame': 21852, + 'frame_number': 21852, + 'framesequence': 88099, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5253822803497314, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.9517932496965, + 'timestamp_carla': 745951, + 'timestamp_device': 1616549, + 'timestamp_stream': 745.9517932496965, + 'transform': [array([-51.5303421 , 85.90960693, -0.15778205]), + array([-1.31481132e-02, -9.35060043e+01, 1.00676995e-02])]} +{'AngularVelocity': array([-0.00644085, 0.0775962 , -6.18893719]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.760543823242188, + 'FR_Wheel_Angle': 41.62620162963867, + 'Location': array([-4.64332962e+01, 9.49920578e+01, 2.08634082e-02]), + 'Rotation': array([ 4.14182656e-02, 1.19343399e+02, -1.30096406e-01]), + 'Velocity': array([ 0.42698109, -0.33123112, -0.00178439]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16378.25, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-22817.42578125, 9952.87988281, 120.06691742]), + 'frame': 21853, + 'frame_number': 21853, + 'framesequence': 88103, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5068880915641785, + 'throttle_input': 0.2896620035171509, + 'timestamp': 745.9859039522707, + 'timestamp_carla': 745985, + 'timestamp_device': 1616583, + 'timestamp_stream': 745.9859039522707, + 'transform': [array([-51.49370575, 85.96746063, -0.15777387]), + array([-1.40565289e-02, -9.32152328e+01, 9.90377646e-03])]} +{'AngularVelocity': array([ 3.65244341e-03, 1.52175114e-01, -5.52189922e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.759902954101562, + 'FR_Wheel_Angle': 41.62345504760742, + 'Location': array([-4.63829536e+01, 9.49458160e+01, 2.04963963e-02]), + 'Rotation': array([ 5.03999628e-02, 1.18457481e+02, -1.48254380e-01]), + 'Velocity': array([ 0.41027945, -0.33032897, -0.00295753]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 17538.9609375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-23979.01171875, 9941.796875 , 120.26667023]), + 'frame': 21854, + 'frame_number': 21854, + 'framesequence': 88107, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4805017411708832, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.0181587524712, + 'timestamp_carla': 746017, + 'timestamp_device': 1616616, + 'timestamp_stream': 746.0181587524712, + 'transform': [array([-51.45984268, 86.0195694 , -0.15774423]), + array([-1.53542645e-02, -9.29536591e+01, 9.67837963e-03])]} +{'AngularVelocity': array([ 0.01087513, 0.1272008 , -5.57709742]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.767805099487305, + 'FR_Wheel_Angle': 41.63656234741211, + 'Location': array([-4.63328438e+01, 9.48982925e+01, 2.00845618e-02]), + 'Rotation': array([ 5.95387556e-02, 1.17566429e+02, -1.65496796e-01]), + 'Velocity': array([ 0.40045375, -0.331633 , -0.00252984]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 18414.943359375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-24856.56640625, 9901.1484375 , 120.36804962]), + 'frame': 21855, + 'frame_number': 21855, + 'framesequence': 88111, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46096378564834595, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.0526137501001, + 'timestamp_carla': 746052, + 'timestamp_device': 1616649, + 'timestamp_stream': 746.0526137501001, + 'transform': [array([-51.42442322, 86.07262421, -0.15773185]), + array([-1.65836979e-02, -9.26878815e+01, 9.44615528e-03])]} +{'AngularVelocity': array([-2.55261455e-03, 1.91340840e-03, -5.53830528e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.769620895385742, + 'FR_Wheel_Angle': 41.641902923583984, + 'Location': array([-4.62843513e+01, 9.48509140e+01, 1.97667219e-02]), + 'Rotation': array([ 6.52078092e-02, 1.16685387e+02, -1.76849321e-01]), + 'Velocity': array([ 0.39127573, -0.33583263, -0.00054966]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 18720.427734375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-25164.00976562, 9832.11621094, 120.34937286]), + 'frame': 21856, + 'frame_number': 21856, + 'framesequence': 88115, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4530717134475708, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.0839462503791, + 'timestamp_carla': 746083, + 'timestamp_device': 1616683, + 'timestamp_stream': 746.0839462503791, + 'transform': [array([-51.39265442, 86.11980438, -0.15767868]), + array([-1.70208309e-02, -9.24522400e+01, 9.24124941e-03])]} +{'AngularVelocity': array([-0.01531676, -0.03199191, -5.3502779 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.773651123046875, + 'FR_Wheel_Angle': 41.644901275634766, + 'Location': array([-4.62376518e+01, 9.48039246e+01, 1.97648145e-02]), + 'Rotation': array([ 6.05632849e-02, 1.15824265e+02, -1.72729477e-01]), + 'Velocity': array([ 3.77488077e-01, -3.33807886e-01, 7.86781311e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19044.87890625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-25490.0546875 , 9759.76464844, 120.32704163]), + 'frame': 21857, + 'frame_number': 21857, + 'framesequence': 88119, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4605792462825775, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.1187610514462, + 'timestamp_carla': 746118, + 'timestamp_device': 1616716, + 'timestamp_stream': 746.1187610514462, + 'transform': [array([-51.35768127, 86.17233276, -0.1576591 ]), + array([-1.63787920e-02, -9.21908722e+01, 9.15928464e-03])]} +{'AngularVelocity': array([-0.01605198, -0.02607504, -5.22152758]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.772808074951172, + 'FR_Wheel_Angle': 41.64421844482422, + 'Location': array([-4.61918144e+01, 9.47563248e+01, 1.97862517e-02]), + 'Rotation': array([ 5.53108677e-02, 1.14962486e+02, -1.68456987e-01]), + 'Velocity': array([ 3.65521550e-01, -3.33945841e-01, -7.73429856e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19282.4296875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-25728.77734375, 9690.95117188, 120.29930115]), + 'frame': 21858, + 'frame_number': 21858, + 'framesequence': 88123, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4745140075683594, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.1512708514929, + 'timestamp_carla': 746150, + 'timestamp_device': 1616749, + 'timestamp_stream': 746.1512708514929, + 'transform': [array([-51.32534027, 86.22244263, -0.15764286]), + array([-1.50605664e-02, -9.19426193e+01, 9.26856697e-03])]} +{'AngularVelocity': array([-0.0269057 , -0.02670199, -5.25441408]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.17350959777832, + 'FR_Wheel_Angle': 35.90283966064453, + 'Location': array([-4.61468430e+01, 9.47076035e+01, 1.98137574e-02]), + 'Rotation': array([ 4.95188683e-02, 1.14116447e+02, -1.64764404e-01]), + 'Velocity': array([ 3.64406109e-01, -3.58728528e-01, -1.71089167e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19511.7890625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-25959.1796875 , 9611.04101562, 120.30623627]), + 'frame': 21859, + 'frame_number': 21859, + 'framesequence': 88127, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4881008267402649, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.1844915524125, + 'timestamp_carla': 746184, + 'timestamp_device': 1616783, + 'timestamp_stream': 746.1844915524125, + 'transform': [array([-51.29262543, 86.27462769, -0.15764932]), + array([-1.34759629e-02, -9.16849136e+01, 9.46664438e-03])]} +{'AngularVelocity': array([ 0.02537787, -0.12052139, -6.66241693]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.120119094848633, + 'FR_Wheel_Angle': 38.13555145263672, + 'Location': array([-4.61021881e+01, 9.46545258e+01, 1.98311899e-02]), + 'Rotation': array([ 4.30438481e-02, 1.13319824e+02, -1.59942597e-01]), + 'Velocity': array([ 0.38468805, -0.39348647, -0.00046043]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19713.763671875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-26161.91601562, 9532.66992188, 120.37575531]), + 'frame': 21860, + 'frame_number': 21860, + 'framesequence': 88131, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49370405077934265, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.2174551524222, + 'timestamp_carla': 746217, + 'timestamp_device': 1616816, + 'timestamp_stream': 746.2174551524222, + 'transform': [array([-51.26050568, 86.32728577, -0.15765302]), + array([-1.21645667e-02, -9.14257355e+01, 9.63056833e-03])]} +{'AngularVelocity': array([ 0.0233058 , -0.12278329, -7.02754784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.35550308227539, + 'FR_Wheel_Angle': 37.150943756103516, + 'Location': array([-4.60550461e+01, 9.45981903e+01, 1.98132601e-02]), + 'Rotation': array([ 3.93896997e-02, 1.12446663e+02, -1.54113799e-01]), + 'Velocity': array([ 3.92289013e-01, -3.95408392e-01, -2.97479623e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19895.599609375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-26344.28125 , 9448.63867188, 120.47245026]), + 'frame': 21861, + 'frame_number': 21861, + 'framesequence': 88135, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.491103857755661, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.2510871514678, + 'timestamp_carla': 746250, + 'timestamp_device': 1616849, + 'timestamp_stream': 746.2510871514678, + 'transform': [array([-51.22815323, 86.38093567, -0.15765998]), + array([-1.14542264e-02, -9.11622467e+01, 9.71935969e-03])]} +{'AngularVelocity': array([ 0.01415269, -0.10995438, -6.63449764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.216930389404297, + 'FR_Wheel_Angle': 37.584842681884766, + 'Location': array([-4.60108795e+01, 9.45436859e+01, 1.98434349e-02]), + 'Rotation': array([ 3.61590199e-02, 1.11624352e+02, -1.52648926e-01]), + 'Velocity': array([ 3.71317714e-01, -3.93835783e-01, 4.14562201e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20062.583984375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-26511.5 , 9362.09277344, 120.55640411]), + 'frame': 21862, + 'frame_number': 21862, + 'framesequence': 88139, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48388931155204773, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.2849430516362, + 'timestamp_carla': 746284, + 'timestamp_device': 1616883, + 'timestamp_stream': 746.2849430516362, + 'transform': [array([-51.19609451, 86.43426514, -0.1576675 ]), + array([-1.13449432e-02, -9.09009476e+01, 9.74668097e-03])]} +{'AngularVelocity': array([ 0.0866246 , -0.16379581, -6.72063875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.22762680053711, + 'FR_Wheel_Angle': 37.35204315185547, + 'Location': array([-4.59676743e+01, 9.44888687e+01, 1.96967591e-02]), + 'Rotation': array([ 3.72313596e-02, 1.10804398e+02, -1.39434814e-01]), + 'Velocity': array([ 0.36860859, -0.40002218, -0.00178371]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20235.619140625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-26684.39257812, 9272.61328125, 120.61576843]), + 'frame': 21863, + 'frame_number': 21863, + 'framesequence': 88143, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47740715742111206, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.3182599507272, + 'timestamp_carla': 746317, + 'timestamp_device': 1616916, + 'timestamp_stream': 746.3182599507272, + 'transform': [array([-51.1649971 , 86.48593903, -0.15766034]), + array([-1.15156984e-02, -9.06483612e+01, 9.70569812e-03])]} +{'AngularVelocity': array([ 0.05861213, -0.09256824, -6.22015667]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.28388023376465, + 'FR_Wheel_Angle': 37.446075439453125, + 'Location': array([-4.59247894e+01, 9.44321976e+01, 1.94723792e-02]), + 'Rotation': array([ 4.09538113e-02, 1.09989220e+02, -1.25366196e-01]), + 'Velocity': array([ 0.34737158, -0.4048045 , -0.00131475]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20376.107421875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-26824.32617188, 9181.81933594, 120.64880371]), + 'frame': 21864, + 'frame_number': 21864, + 'framesequence': 88147, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4731956124305725, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.3510553501546, + 'timestamp_carla': 746350, + 'timestamp_device': 1616949, + 'timestamp_stream': 746.3510553501546, + 'transform': [array([-51.13476562, 86.53623199, -0.15763184]), + array([-1.16659626e-02, -9.04032059e+01, 9.58958734e-03])]} +{'AngularVelocity': array([ 0.04761676, -0.10226347, -5.95231009]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.288578033447266, + 'FR_Wheel_Angle': 37.48813247680664, + 'Location': array([-4.58856430e+01, 9.43788910e+01, 1.92817207e-02]), + 'Rotation': array([ 4.49904539e-02, 1.09223801e+02, -1.13067612e-01]), + 'Velocity': array([ 0.32066184, -0.38512388, -0.00107691]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20498.30859375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-26945.57421875, 9092.67578125, 120.65531921]), + 'frame': 21865, + 'frame_number': 21865, + 'framesequence': 88151, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4744224548339844, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.3839804492891, + 'timestamp_carla': 746383, + 'timestamp_device': 1616983, + 'timestamp_stream': 746.3839804492891, + 'transform': [array([-51.10472107, 86.58661652, -0.15760098]), + array([-1.15498491e-02, -9.01582565e+01, 9.48030315e-03])]} +{'AngularVelocity': array([ 0.04155224, -0.09749286, -5.79853725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.28921890258789, + 'FR_Wheel_Angle': 37.508033752441406, + 'Location': array([-4.58481178e+01, 9.43262863e+01, 1.91075411e-02]), + 'Rotation': array([ 4.73058894e-02, 1.08477547e+02, -9.93347168e-02]), + 'Velocity': array([ 0.30639026, -0.37873381, -0.00093343]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20618.68359375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27064.62109375, 9005.14941406, 120.63456726]), + 'frame': 21866, + 'frame_number': 21866, + 'framesequence': 88155, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47786495089530945, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.4186413511634, + 'timestamp_carla': 746418, + 'timestamp_device': 1617016, + 'timestamp_stream': 746.4186413511634, + 'transform': [array([-51.07347107, 86.63986206, -0.1575999 ]), + array([-1.11468676e-02, -8.99001541e+01, 9.46664158e-03])]} +{'AngularVelocity': array([-0.05713784, -0.09518159, -6.15342188]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.28443717956543, + 'FR_Wheel_Angle': 37.49398422241211, + 'Location': array([-4.58119659e+01, 9.42739029e+01, 1.91233344e-02]), + 'Rotation': array([ 4.16231714e-02, 1.07736076e+02, -9.63134691e-02]), + 'Velocity': array([ 3.13452512e-01, -4.02146250e-01, 9.53102062e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20736.1171875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27180.35546875, 8916.66699219, 120.61481476]), + 'frame': 21867, + 'frame_number': 21867, + 'framesequence': 88159, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4814905524253845, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.4524648524821, + 'timestamp_carla': 746451, + 'timestamp_device': 1617049, + 'timestamp_stream': 746.4524648524821, + 'transform': [array([-51.04339218, 86.69199371, -0.15760428]), + array([-1.07438872e-02, -8.96482239e+01, 9.52811446e-03])]} +{'AngularVelocity': array([-0.034121 , -0.03753881, -5.93098211]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.270645141601562, + 'FR_Wheel_Angle': 37.4702262878418, + 'Location': array([-4.57760582e+01, 9.42204437e+01, 1.92203037e-02]), + 'Rotation': array([ 3.51208299e-02, 1.06982101e+02, -9.54894722e-02]), + 'Velocity': array([ 0.29982996, -0.39148033, 0.00064814]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20828.322265625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27270.37109375, 8822.39550781, 120.62349701]), + 'frame': 21868, + 'frame_number': 21868, + 'framesequence': 88163, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48282724618911743, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.4836258515716, + 'timestamp_carla': 746483, + 'timestamp_device': 1617083, + 'timestamp_stream': 746.4836258515716, + 'transform': [array([-51.01587677, 86.74024963, -0.15754974]), + array([-1.03477361e-02, -8.94154510e+01, 9.41883121e-03])]} +{'AngularVelocity': array([-0.06964425, 0.08711622, -5.91963768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.259462356567383, + 'FR_Wheel_Angle': 37.45527267456055, + 'Location': array([-4.57375145e+01, 9.41612091e+01, 1.93273071e-02]), + 'Rotation': array([ 2.57156603e-02, 1.06158875e+02, -9.18274075e-02]), + 'Velocity': array([ 0.32266432, -0.45074806, 0.00048099]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20908.546875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27348.06835938, 8729.66113281, 120.65880585]), + 'frame': 21869, + 'frame_number': 21869, + 'framesequence': 88167, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.481618732213974, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.5181984491646, + 'timestamp_carla': 746517, + 'timestamp_device': 1617116, + 'timestamp_stream': 746.5181984491646, + 'transform': [array([-50.98561478, 86.79374695, -0.15752646]), + array([-1.00267176e-02, -8.91580505e+01, 9.29588825e-03])]} +{'AngularVelocity': array([-0.06200572, -0.03939534, -6.39500523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.14497184753418, + 'FR_Wheel_Angle': 34.10204315185547, + 'Location': array([-4.56975098e+01, 9.40987320e+01, 1.93727389e-02]), + 'Rotation': array([ 2.04700753e-02, 1.05287857e+02, -9.23767015e-02]), + 'Velocity': array([ 3.35355639e-01, -4.70922470e-01, 2.15120308e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20983.541015625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27420.37109375, 8643.36621094, 120.63278961]), + 'frame': 21870, + 'frame_number': 21870, + 'framesequence': 88171, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47978758811950684, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.5508947521448, + 'timestamp_carla': 746550, + 'timestamp_device': 1617149, + 'timestamp_stream': 746.5508947521448, + 'transform': [array([-50.95733261, 86.84427643, -0.15750165]), + array([-9.93792433e-03, -8.89155807e+01, 9.22758412e-03])]} +{'AngularVelocity': array([-0.03483846, 0.01068261, -5.08820724]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.785598754882812, + 'FR_Wheel_Angle': 32.58412170410156, + 'Location': array([-4.56612587e+01, 9.40361404e+01, 1.94544122e-02]), + 'Rotation': array([ 1.55933211e-02, 1.04522156e+02, -9.68017578e-02]), + 'Velocity': array([ 2.89026439e-01, -4.63192403e-01, 3.86905653e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21067.50390625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27500.9375 , 8547.20996094, 120.59976959]), + 'frame': 21871, + 'frame_number': 21871, + 'framesequence': 88175, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4784875214099884, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.5849416516721, + 'timestamp_carla': 746584, + 'timestamp_device': 1617183, + 'timestamp_stream': 746.5849416516721, + 'transform': [array([-50.92822647, 86.89667511, -0.15749657]), + array([-9.86279268e-03, -8.86647339e+01, 9.18660499e-03])]} +{'AngularVelocity': array([-0.027875 , -0.04600943, -5.13099575]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.216272354125977, + 'FR_Wheel_Angle': 33.705352783203125, + 'Location': array([-4.56285820e+01, 9.39763641e+01, 1.95164774e-02]), + 'Rotation': array([ 1.23284906e-02, 1.03829781e+02, -9.50622410e-02]), + 'Velocity': array([ 0.27211949, -0.43096355, 0.00048169]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21137.982421875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27567.81445312, 8456.13085938, 120.58657837]), + 'frame': 21872, + 'frame_number': 21872, + 'framesequence': 88179, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47898194193840027, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.616869751364, + 'timestamp_carla': 746616, + 'timestamp_device': 1617216, + 'timestamp_stream': 746.616869751364, + 'transform': [array([-50.90118027, 86.94581604, -0.15746376]), + array([-9.80132073e-03, -8.84299774e+01, 9.10464488e-03])]} +{'AngularVelocity': array([-6.22568168e-02, 4.60670888e-03, -5.19262266e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.49276351928711, + 'FR_Wheel_Angle': 33.146366119384766, + 'Location': array([-4.55967026e+01, 9.39169922e+01, 1.95854474e-02]), + 'Rotation': array([ 6.29060389e-03, 1.03121101e+02, -9.30480734e-02]), + 'Velocity': array([ 0.25891045, -0.44030654, 0.0005613 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21192.953125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27618.64257812, 8361.703125 , 120.57957458]), + 'frame': 21873, + 'frame_number': 21873, + 'framesequence': 88183, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4799157977104187, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.6516499519348, + 'timestamp_carla': 746651, + 'timestamp_device': 1617249, + 'timestamp_stream': 746.6516499519348, + 'transform': [array([-50.87203598, 86.99941254, -0.15746358]), + array([-9.58958548e-03, -8.81746063e+01, 9.06366110e-03])]} +{'AngularVelocity': array([-0.03935707, 0.02191323, -4.94805765]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.790393829345703, + 'FR_Wheel_Angle': 33.31207275390625, + 'Location': array([-4.55672798e+01, 9.38602905e+01, 1.96690653e-02]), + 'Rotation': array([ 1.26358494e-03, 1.02465965e+02, -9.15832371e-02]), + 'Velocity': array([ 2.44592845e-01, -4.20694113e-01, 3.61151673e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21245.021484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27666.45703125, 8272.89453125, 120.55867767]), + 'frame': 21874, + 'frame_number': 21874, + 'framesequence': 88187, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4804101884365082, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.6834034509957, + 'timestamp_carla': 746682, + 'timestamp_device': 1617283, + 'timestamp_stream': 746.6834034509957, + 'transform': [array([-50.84549332, 87.04914856, -0.15739332]), + array([-9.28905699e-03, -8.79383163e+01, 8.85875616e-03])]} +{'AngularVelocity': array([-0.03822185, -0.04086305, -4.51608133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.74744415283203, + 'FR_Wheel_Angle': 33.368675231933594, + 'Location': array([-4.55381813e+01, 9.38029099e+01, 1.97082032e-02]), + 'Rotation': array([-3.08724539e-03, 1.01801697e+02, -9.09118652e-02]), + 'Velocity': array([ 0.2319321 , -0.40145123, 0.00049926]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21302.32421875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27718.71289062, 8175.82128906, 120.55089569]), + 'frame': 21875, + 'frame_number': 21875, + 'framesequence': 88191, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4799157977104187, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.7172437496483, + 'timestamp_carla': 746716, + 'timestamp_device': 1617316, + 'timestamp_stream': 746.7172437496483, + 'transform': [array([-50.81748962, 87.10174561, -0.15737221]), + array([-9.14562307e-03, -8.76888580e+01, 8.75630323e-03])]} +{'AngularVelocity': array([-0.1199414 , -0.21178479, -5.53247023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.658184051513672, + 'FR_Wheel_Angle': 33.239627838134766, + 'Location': array([-4.55113602e+01, 9.37479858e+01, 1.98239796e-02]), + 'Rotation': array([-1.19323395e-02, 1.01173706e+02, -8.52966085e-02]), + 'Velocity': array([ 2.84318835e-01, -5.05098760e-01, -3.07559967e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21355.97265625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27767.31640625, 8085.53515625, 120.48422241]), + 'frame': 21876, + 'frame_number': 21876, + 'framesequence': 88195, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4795861840248108, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.7501717507839, + 'timestamp_carla': 746749, + 'timestamp_device': 1617349, + 'timestamp_stream': 746.7501717507839, + 'transform': [array([-50.79061508, 87.15274048, -0.15737478]), + array([-9.16611310e-03, -8.74475250e+01, 8.77679139e-03])]} +{'AngularVelocity': array([-6.20686740e-04, -6.80933222e-02, -6.33571243e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.679296493530273, + 'FR_Wheel_Angle': 33.25794982910156, + 'Location': array([-4.54782295e+01, 9.36783829e+01, 1.99122895e-02]), + 'Rotation': array([-1.97392460e-02, 1.00370171e+02, -8.25805590e-02]), + 'Velocity': array([ 2.88304389e-01, -5.03704190e-01, 6.57367709e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21402.5234375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27808.1171875 , 7990.16796875, 120.45239258]), + 'frame': 21877, + 'frame_number': 21877, + 'framesequence': 88199, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47978758811950684, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.7849919497967, + 'timestamp_carla': 746784, + 'timestamp_device': 1617383, + 'timestamp_stream': 746.7849919497967, + 'transform': [array([-50.76257324, 87.2064743 , -0.15740827]), + array([-9.14562307e-03, -8.71937256e+01, 8.86558648e-03])]} +{'AngularVelocity': array([-0.00994647, -0.06595454, -6.04138851]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.68887710571289, + 'FR_Wheel_Angle': 33.271636962890625, + 'Location': array([-4.54470406e+01, 9.36115112e+01, 1.99716855e-02]), + 'Rotation': array([-2.24644914e-02, 9.95984650e+01, -8.46862718e-02]), + 'Velocity': array([ 2.68964350e-01, -4.86598015e-01, 3.86943808e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21439.0, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27838.63671875, 7897.92333984, 120.46591949]), + 'frame': 21878, + 'frame_number': 21878, + 'framesequence': 88203, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.8164759501815, + 'timestamp_carla': 746815, + 'timestamp_device': 1617416, + 'timestamp_stream': 746.8164759501815, + 'transform': [array([-50.73725891, 87.2559433 , -0.15734093]), + array([-8.94754753e-03, -8.69608536e+01, 8.67434032e-03])]} +{'AngularVelocity': array([-0.01305177, -0.08476403, -5.99488831]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.691913604736328, + 'FR_Wheel_Angle': 33.274845123291016, + 'Location': array([-4.54178162e+01, 9.35461960e+01, 2.00454611e-02]), + 'Rotation': array([-2.69450955e-02, 9.88485107e+01, -8.48388523e-02]), + 'Velocity': array([ 2.56535560e-01, -4.77839410e-01, 3.18431848e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21474.83203125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-27867.77929688, 7800.72949219, 120.50333405]), + 'frame': 21879, + 'frame_number': 21879, + 'framesequence': 88207, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.8502027504146, + 'timestamp_carla': 746849, + 'timestamp_device': 1617449, + 'timestamp_stream': 746.8502027504146, + 'transform': [array([-50.71039963, 87.30853271, -0.15732037]), + array([-8.85875523e-03, -8.67135544e+01, 8.57188739e-03])]} +{'AngularVelocity': array([-0.04305253, -0.04098478, -5.88013601]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.68769073486328, + 'FR_Wheel_Angle': 33.273006439208984, + 'Location': array([-4.53894997e+01, 9.34807281e+01, 2.01431550e-02]), + 'Rotation': array([-3.32015492e-02, 9.81122513e+01, -8.33740234e-02]), + 'Velocity': array([ 0.24897835, -0.50093281, 0.0006211 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 18388.373046875, + 'focus_actor_name': 'BP_RepSpline18', + 'focus_actor_pt': array([-24779.20117188, 7876.68798828, 119.96595764]), + 'frame': 21880, + 'frame_number': 21880, + 'framesequence': 88211, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.8827401511371, + 'timestamp_carla': 746882, + 'timestamp_device': 1617482, + 'timestamp_stream': 746.8827401511371, + 'transform': [array([-50.68481445, 87.35913086, -0.15732107]), + array([-8.89290590e-03, -8.64761734e+01, 8.59237742e-03])]} +{'AngularVelocity': array([-0.02326167, -0.03037381, -5.46982956]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.694908142089844, + 'FR_Wheel_Angle': 32.634456634521484, + 'Location': array([-4.53627319e+01, 9.34159317e+01, 2.02117059e-02]), + 'Rotation': array([-3.68966796e-02, 9.73868866e+01, -8.43200535e-02]), + 'Velocity': array([ 0.22214392, -0.46293223, 0.00046946]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16979.923828125, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-23366.53515625, 7877.65283203, 119.72172546]), + 'frame': 21881, + 'frame_number': 21881, + 'framesequence': 88215, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.9169169515371, + 'timestamp_carla': 746916, + 'timestamp_device': 1617516, + 'timestamp_stream': 746.9169169515371, + 'transform': [array([-50.65829086, 87.41215515, -0.15735003]), + array([-8.90656654e-03, -8.62278748e+01, 8.67434032e-03])]} +{'AngularVelocity': array([-0.02465534, 0.01558148, -4.45476341]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.446727752685547, + 'FR_Wheel_Angle': 27.391969680786133, + 'Location': array([-4.53385277e+01, 9.33537292e+01, 2.03028005e-02]), + 'Rotation': array([-4.16846424e-02, 9.67180939e+01, -8.51135030e-02]), + 'Velocity': array([ 0.19283773, -0.45033538, 0.00106034]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 15312.8837890625, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-21696.39453125, 7909.37939453, 119.47834778]), + 'frame': 21882, + 'frame_number': 21882, + 'framesequence': 88219, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.9495543502271, + 'timestamp_carla': 746949, + 'timestamp_device': 1617549, + 'timestamp_stream': 746.9495543502271, + 'transform': [array([-50.63328171, 87.46269226, -0.15736525]), + array([-8.98169819e-03, -8.59917831e+01, 8.75630416e-03])]} +{'AngularVelocity': array([-0.02201982, -0.04700652, -4.28240538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.306713104248047, + 'FR_Wheel_Angle': 30.045480728149414, + 'Location': array([-4.53178635e+01, 9.32936478e+01, 2.03775298e-02]), + 'Rotation': array([-4.57486063e-02, 9.61687622e+01, -8.50830004e-02]), + 'Velocity': array([ 0.1714472 , -0.4306871 , 0.00047306]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13926.9599609375, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-20307.08398438, 7933.81103516, 119.28946686]), + 'frame': 21883, + 'frame_number': 21883, + 'framesequence': 88223, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 746.9837693497539, + 'timestamp_carla': 746983, + 'timestamp_device': 1617582, + 'timestamp_stream': 746.9837693497539, + 'transform': [array([-50.60739517, 87.51558685, -0.15738955]), + array([-8.98169819e-03, -8.57451935e+01, 8.82460270e-03])]} +{'AngularVelocity': array([-0.05316756, -0.06764308, -5.37386036]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.016878128051758, + 'FR_Wheel_Angle': 28.734546661376953, + 'Location': array([-4.52978020e+01, 9.32345581e+01, 2.04749573e-02]), + 'Rotation': array([-5.20323776e-02, 9.55819168e+01, -8.00781175e-02]), + 'Velocity': array([ 0.18361929, -0.45798078, 0.00062223]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13900.6298828125, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-20274.86132812, 7877.90576172, 119.3060379 ]), + 'frame': 21884, + 'frame_number': 21884, + 'framesequence': 88227, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.0158645510674, + 'timestamp_carla': 747015, + 'timestamp_device': 1617616, + 'timestamp_stream': 747.0158645510674, + 'transform': [array([-50.58317184, 87.56607056, -0.15733527]), + array([-8.79045296e-03, -8.55106049e+01, 8.66067968e-03])]} +{'AngularVelocity': array([-0.03638446, -0.03651131, -5.43551826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.127605438232422, + 'FR_Wheel_Angle': 29.34019660949707, + 'Location': array([-4.52779732e+01, 9.31735687e+01, 2.05472466e-02]), + 'Rotation': array([-5.68886437e-02, 9.50033112e+01, -7.92846680e-02]), + 'Velocity': array([ 1.71879247e-01, -4.52206135e-01, -1.24654762e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13865.69140625, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-20233.55273438, 7820.33056641, 119.3163681 ]), + 'frame': 21885, + 'frame_number': 21885, + 'framesequence': 88231, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.0495536513627, + 'timestamp_carla': 747049, + 'timestamp_device': 1617649, + 'timestamp_stream': 747.0495536513627, + 'transform': [array([-50.55802536, 87.61856079, -0.15732574]), + array([-8.72898102e-03, -8.52668533e+01, 8.60603899e-03])]} +{'AngularVelocity': array([-0.03467021, -0.0162955 , -5.32323313]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.031221389770508, + 'FR_Wheel_Angle': 29.135068893432617, + 'Location': array([-4.52594948e+01, 9.31151276e+01, 2.06228532e-02]), + 'Rotation': array([-6.04539998e-02, 9.44445801e+01, -7.85827637e-02]), + 'Velocity': array([ 1.59665897e-01, -4.33091104e-01, -9.69409957e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13746.2685546875, + 'focus_actor_name': 'BP_HighwayLight_multiple42_41', + 'focus_actor_pt': array([-20108.1328125 , 7772.61132812, 119.25961304]), + 'frame': 21886, + 'frame_number': 21886, + 'framesequence': 88235, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.0829829499125, + 'timestamp_carla': 747082, + 'timestamp_device': 1617682, + 'timestamp_stream': 747.0829829499125, + 'transform': [array([-50.53343582, 87.67046356, -0.15734246]), + array([-8.76313262e-03, -8.50263672e+01, 8.66751000e-03])]} +{'AngularVelocity': array([-0.05958409, -0.00868424, -4.5947566 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.05552864074707, + 'FR_Wheel_Angle': 29.12145233154297, + 'Location': array([-4.52413864e+01, 9.30555954e+01, 2.07292847e-02]), + 'Rotation': array([-6.75027594e-02, 9.38960876e+01, -7.55920336e-02]), + 'Velocity': array([ 1.68394566e-01, -4.82141942e-01, 3.56969831e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13791.38671875, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-20146.26171875, 7710.12402344, 119.25273132]), + 'frame': 21887, + 'frame_number': 21887, + 'framesequence': 88239, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.1160593517125, + 'timestamp_carla': 747115, + 'timestamp_device': 1617716, + 'timestamp_stream': 747.1160593517125, + 'transform': [array([-50.50940323, 87.72174835, -0.15735455]), + array([-8.81777331e-03, -8.47892456e+01, 8.72215256e-03])]} +{'AngularVelocity': array([-0.11526976, 0.23582791, -4.45127821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.0522518157959, + 'FR_Wheel_Angle': 29.115510940551758, + 'Location': array([-4.52225189e+01, 9.29910812e+01, 2.06376556e-02]), + 'Rotation': array([-8.22491348e-02, 9.32852020e+01, -9.52758715e-02]), + 'Velocity': array([ 0.16535878, -0.48056611, -0.00226544]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13766.3681640625, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-20114.33007812, 7654.15625 , 119.26364136]), + 'frame': 21888, + 'frame_number': 21888, + 'framesequence': 88243, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.1506359502673, + 'timestamp_carla': 747150, + 'timestamp_device': 1617749, + 'timestamp_stream': 747.1506359502673, + 'transform': [array([-50.48461914, 87.77518463, -0.15738223]), + array([-8.79728328e-03, -8.45425720e+01, 8.79728328e-03])]} +{'AngularVelocity': array([-0.13920251, 0.16052446, -4.45637369]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.05341339111328, + 'FR_Wheel_Angle': 29.089258193969727, + 'Location': array([-4.52039871e+01, 9.29256363e+01, 2.04102602e-02]), + 'Rotation': array([-0.09722774, 92.66065979, -0.11849973]), + 'Velocity': array([ 0.1649593 , -0.48461017, -0.00271642]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13734.419921875, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-20075.37695312, 7599.85888672, 119.2721405 ]), + 'frame': 21889, + 'frame_number': 21889, + 'framesequence': 88247, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.182448849082, + 'timestamp_carla': 747182, + 'timestamp_device': 1617782, + 'timestamp_stream': 747.182448849082, + 'transform': [array([-50.46171951, 87.82569122, -0.15728173]), + array([-8.47626384e-03, -8.43101120e+01, 8.46943632e-03])]} +{'AngularVelocity': array([-4.18683700e-02, -3.28655820e-03, -3.96033978e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.042831420898438, + 'FR_Wheel_Angle': 29.105911254882812, + 'Location': array([-4.51856270e+01, 9.28575821e+01, 2.02777758e-02]), + 'Rotation': array([-0.11324453, 92.02856445, -0.13516232]), + 'Velocity': array([ 0.16858178, -0.51648039, -0.00057189]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13701.6123046875, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-20035.05078125, 7543.65478516, 119.28404999]), + 'frame': 21890, + 'frame_number': 21890, + 'framesequence': 88251, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.2174698524177, + 'timestamp_carla': 747217, + 'timestamp_device': 1617816, + 'timestamp_stream': 747.2174698524177, + 'transform': [array([-50.43680954, 87.88061523, -0.15727319]), + array([-8.35332088e-03, -8.40575867e+01, 8.38064216e-03])]} +{'AngularVelocity': array([ 0.00480785, -0.06345527, -3.63210487]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.053421020507812, + 'FR_Wheel_Angle': 29.122411727905273, + 'Location': array([-4.51682358e+01, 9.27906494e+01, 2.03985497e-02]), + 'Rotation': array([-0.11331283, 91.40805817, -0.13037108]), + 'Velocity': array([ 0.15312926, -0.49059939, 0.00126614]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13671.0556640625, + 'focus_actor_name': 'BP_RepSpline106_5', + 'focus_actor_pt': array([-19997.2265625 , 7490.9375 , 119.20241547]), + 'frame': 21891, + 'frame_number': 21891, + 'framesequence': 88255, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.2495734505355, + 'timestamp_carla': 747249, + 'timestamp_device': 1617849, + 'timestamp_stream': 747.2495734505355, + 'transform': [array([-50.41413498, 87.9316864 , -0.15722315]), + array([-8.24403763e-03, -8.38233719e+01, 8.23720545e-03])]} +{'AngularVelocity': array([ 0.00457897, -0.04333156, -3.42359853]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.05478286743164, + 'FR_Wheel_Angle': 29.12604522705078, + 'Location': array([-4.51525078e+01, 9.27270355e+01, 2.05852799e-02]), + 'Rotation': array([-0.11349725, 90.81485748, -0.12374876]), + 'Velocity': array([ 0.13880184, -0.46816906, 0.00127234]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10737.76171875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-17071.3671875 , 7734.23339844, 118.75054932]), + 'frame': 21892, + 'frame_number': 21892, + 'framesequence': 88259, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.2830268517137, + 'timestamp_carla': 747282, + 'timestamp_device': 1617882, + 'timestamp_stream': 747.2830268517137, + 'transform': [array([-50.39077377, 87.98438263, -0.15722995]), + array([-8.29867925e-03, -8.35820312e+01, 8.25086795e-03])]} +{'AngularVelocity': array([-0.00329002, -0.01447132, -3.03584981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.48001480102539, + 'FR_Wheel_Angle': 25.095905303955078, + 'Location': array([-4.51373634e+01, 9.26631241e+01, 2.07535829e-02]), + 'Rotation': array([-0.11514332, 90.22724152, -0.11666871]), + 'Velocity': array([ 0.12961712, -0.46427637, 0.00118784]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10298.83203125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-16628.30859375, 7737.41064453, 118.66184235]), + 'frame': 21893, + 'frame_number': 21893, + 'framesequence': 88263, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.3157244510949, + 'timestamp_carla': 747315, + 'timestamp_device': 1617916, + 'timestamp_stream': 747.3157244510949, + 'transform': [array([-50.36827087, 88.0357132 , -0.15725319]), + array([-8.43528286e-03, -8.33473358e+01, 8.35332088e-03])]} +{'AngularVelocity': array([-0.03814503, -0.07987436, -4.03727007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.553354263305664, + 'FR_Wheel_Angle': 24.720096588134766, + 'Location': array([-4.51248856e+01, 9.25986786e+01, 2.09446624e-02]), + 'Rotation': array([-0.11956245, 89.70264435, -0.1116333 ]), + 'Velocity': array([ 0.11620794, -0.52017379, 0.0011484 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 9631.86328125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-15958.63476562, 7768.43359375, 118.56809235]), + 'frame': 21894, + 'frame_number': 21894, + 'framesequence': 88267, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.3505673520267, + 'timestamp_carla': 747350, + 'timestamp_device': 1617949, + 'timestamp_stream': 747.3505673520267, + 'transform': [array([-50.34466553, 88.09018707, -0.1573064 ]), + array([-8.50358512e-03, -8.30987167e+01, 8.51041544e-03])]} +{'AngularVelocity': array([-0.01728632, -0.07117498, -4.05781841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.73961067199707, + 'FR_Wheel_Angle': 25.217670440673828, + 'Location': array([-4.51127739e+01, 9.25320892e+01, 2.11156365e-02]), + 'Rotation': array([-0.12069627, 89.18257904, -0.10317993]), + 'Velocity': array([ 0.1188688 , -0.50891715, 0.00111836]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 9193.0283203125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-15516.19433594, 7779.68457031, 118.52186584]), + 'frame': 21895, + 'frame_number': 21895, + 'framesequence': 88271, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.3829907514155, + 'timestamp_carla': 747382, + 'timestamp_device': 1617982, + 'timestamp_stream': 747.3829907514155, + 'transform': [array([-50.32276154, 88.1418457 , -0.15726158]), + array([-8.36698152e-03, -8.28635101e+01, 8.38064216e-03])]} +{'AngularVelocity': array([-0.00828956, -0.0474159 , -3.59910989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.146421432495117, + 'FR_Wheel_Angle': 24.909202575683594, + 'Location': array([-4.51011963e+01, 9.24670105e+01, 2.12458316e-02]), + 'Rotation': array([-0.12054601, 88.66955566, -0.09857177]), + 'Velocity': array([ 0.10244545, -0.4685187 , 0.00072122]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8888.126953125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-15206.59960938, 7776.31054688, 118.50035095]), + 'frame': 21896, + 'frame_number': 21896, + 'framesequence': 88275, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.4175103493035, + 'timestamp_carla': 747417, + 'timestamp_device': 1618016, + 'timestamp_stream': 747.4175103493035, + 'transform': [array([-50.29977417, 88.19612885, -0.15728132]), + array([-8.38064123e-03, -8.26165848e+01, 8.42162408e-03])]} +{'AngularVelocity': array([-0.0061199 , -0.04063616, -2.86564422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.350189208984375, + 'FR_Wheel_Angle': 24.923686981201172, + 'Location': array([-4.50906715e+01, 9.24028168e+01, 2.14280225e-02]), + 'Rotation': array([-0.12366056, 88.16786194, -0.09179687]), + 'Velocity': array([ 0.10113348, -0.48479134, 0.00106571]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8619.4716796875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-14933.50976562, 7773.09814453, 118.44189453]), + 'frame': 21897, + 'frame_number': 21897, + 'framesequence': 88279, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4782494604587555, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.4508570507169, + 'timestamp_carla': 747450, + 'timestamp_device': 1618049, + 'timestamp_stream': 747.4508570507169, + 'transform': [array([-50.27772903, 88.24922943, -0.15725528]), + array([-8.32600053e-03, -8.23757172e+01, 8.33282992e-03])]} +{'AngularVelocity': array([-0.01082648, -0.03939101, -2.80214977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.346216201782227, + 'FR_Wheel_Angle': 25.00606346130371, + 'Location': array([-4.50805664e+01, 9.23384857e+01, 2.15750411e-02]), + 'Rotation': array([-1.24999285e-01, 8.76647186e+01, -8.64868090e-02]), + 'Velocity': array([ 0.09436294, -0.47919163, 0.0007456 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8023.4677734375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-14335.57226562, 7812.46289062, 118.35949707]), + 'frame': 21898, + 'frame_number': 21898, + 'framesequence': 88283, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46524858474731445, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.4837287515402, + 'timestamp_carla': 747483, + 'timestamp_device': 1618082, + 'timestamp_stream': 747.4837287515402, + 'transform': [array([-50.25622559, 88.30012512, -0.15725882]), + array([-8.87924526e-03, -8.21452942e+01, 8.31233896e-03])]} +{'AngularVelocity': array([-0.01505634, -0.04042046, -2.61073899]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.31553077697754, + 'FR_Wheel_Angle': 24.984657287597656, + 'Location': array([-4.50714607e+01, 9.22770691e+01, 2.17348374e-02]), + 'Rotation': array([-1.26194566e-01, 8.71842728e+01, -8.10241625e-02]), + 'Velocity': array([ 0.08935016, -0.46584678, 0.00110077]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7687.8935546875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13996.44335938, 7823.1796875 , 118.29862213]), + 'frame': 21899, + 'frame_number': 21899, + 'framesequence': 88287, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.44311046600341797, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.5174708515406, + 'timestamp_carla': 747517, + 'timestamp_device': 1618116, + 'timestamp_stream': 747.5174708515406, + 'transform': [array([-50.23429489, 88.35038757, -0.15727991]), + array([-9.95841529e-03, -8.19185486e+01, 8.27135798e-03])]} +{'AngularVelocity': array([-0.0337228 , -0.07263279, -4.61964989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.313453674316406, + 'FR_Wheel_Angle': 24.97484016418457, + 'Location': array([-4.50634613e+01, 9.22182693e+01, 2.18755621e-02]), + 'Rotation': array([-1.27929434e-01, 8.67080688e+01, -7.57751390e-02]), + 'Velocity': array([ 0.08465402, -0.46549967, 0.00139457]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7644.37939453125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13947.08398438, 7798.15576172, 118.29063416]), + 'frame': 21900, + 'frame_number': 21900, + 'framesequence': 88291, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41958069801330566, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.5506252497435, + 'timestamp_carla': 747550, + 'timestamp_device': 1618149, + 'timestamp_stream': 747.5506252497435, + 'transform': [array([-50.21268082, 88.39838409, -0.15724249]), + array([-1.11195473e-02, -8.17031631e+01, 7.99815170e-03])]} +{'AngularVelocity': array([-0.03782143, -0.0860025 , -4.88031244]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.30562400817871, + 'FR_Wheel_Angle': 24.97030258178711, + 'Location': array([-4.50551414e+01, 9.21538773e+01, 2.20484827e-02]), + 'Rotation': array([-1.32048041e-01, 8.62049637e+01, -6.82372898e-02]), + 'Velocity': array([ 0.08915368, -0.50721556, 0.00088682]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7644.6953125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13941.05078125, 7767.84130859, 118.28585815]), + 'frame': 21901, + 'frame_number': 21901, + 'framesequence': 88295, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.39844968914985657, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.5822326503694, + 'timestamp_carla': 747581, + 'timestamp_device': 1618182, + 'timestamp_stream': 747.5822326503694, + 'transform': [array([-50.19207001, 88.44184113, -0.15720996]), + array([-1.23353209e-02, -8.15092087e+01, 7.77958659e-03])]} +{'AngularVelocity': array([ 3.27535563e-05, -4.15918268e-02, -4.40843534e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.317415237426758, + 'FR_Wheel_Angle': 24.9862060546875, + 'Location': array([-4.50474892e+01, 9.20908661e+01, 2.21917629e-02]), + 'Rotation': array([-1.31351367e-01, 8.57162323e+01, -6.50329590e-02]), + 'Velocity': array([ 0.07450647, -0.45404536, 0.00127035]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7658.73583984375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13948.70800781, 7737.09277344, 118.25273895]), + 'frame': 21902, + 'frame_number': 21902, + 'framesequence': 88299, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3939085304737091, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.6179452501237, + 'timestamp_carla': 747617, + 'timestamp_device': 1618216, + 'timestamp_stream': 747.6179452501237, + 'transform': [array([-50.16892624, 88.48969269, -0.15724032]), + array([-1.27997734e-02, -8.12963562e+01, 7.75226671e-03])]} +{'AngularVelocity': array([-0.01751514, -0.04777892, -4.25700188]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.321800231933594, + 'FR_Wheel_Angle': 24.99170684814453, + 'Location': array([-4.50407372e+01, 9.20318375e+01, 2.23443117e-02]), + 'Rotation': array([-1.32471517e-01, 8.52507706e+01, -5.99365346e-02]), + 'Velocity': array([ 0.0694701 , -0.44415623, 0.00163311]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7684.3935546875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13968.24023438, 7707.43554688, 118.22935486]), + 'frame': 21903, + 'frame_number': 21903, + 'framesequence': 88303, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4037599265575409, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.6496432498097, + 'timestamp_carla': 747649, + 'timestamp_device': 1618249, + 'timestamp_stream': 747.6496432498097, + 'transform': [array([-50.14838409, 88.53372955, -0.15715949]), + array([-1.21167554e-02, -8.11011200e+01, 7.55419116e-03])]} +{'AngularVelocity': array([-0.07019457, -0.13568594, -4.27201509]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.0601863861084, + 'FR_Wheel_Angle': 23.364643096923828, + 'Location': array([-4.50342712e+01, 9.19710617e+01, 2.24970151e-02]), + 'Rotation': array([-1.36412531e-01, 8.47724609e+01, -5.22766002e-02]), + 'Velocity': array([ 0.08030212, -0.49878347, 0.00102439]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7685.8125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13963.04296875, 7678.76367188, 118.22379303]), + 'frame': 21904, + 'frame_number': 21904, + 'framesequence': 88307, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41571706533432007, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.6832563504577, + 'timestamp_carla': 747682, + 'timestamp_device': 1618282, + 'timestamp_stream': 747.6832563504577, + 'transform': [array([-50.12688828, 88.58086395, -0.15716052]), + array([-1.10102640e-02, -8.08919220e+01, 7.66347349e-03])]} +{'AngularVelocity': array([-0.01812152, -0.02558471, -2.34868312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.294057846069336, + 'FR_Wheel_Angle': 19.257417678833008, + 'Location': array([-4.50288124e+01, 9.19034424e+01, 2.26661954e-02]), + 'Rotation': array([-1.41384915e-01, 8.43134613e+01, -4.82482873e-02]), + 'Velocity': array([ 0.05591537, -0.55539399, 0.00154961]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7675.3525390625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13946.61621094, 7654.30859375, 118.19697571]), + 'frame': 21905, + 'frame_number': 21905, + 'framesequence': 88311, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42879119515419006, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.716562051326, + 'timestamp_carla': 747716, + 'timestamp_device': 1618316, + 'timestamp_stream': 747.716562051326, + 'transform': [array([-50.1060257 , 88.62854004, -0.15720759]), + array([-9.82181169e-03, -8.06802368e+01, 7.99132045e-03])]} +{'AngularVelocity': array([-0.01030601, -0.05199567, -3.5539341 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.907155990600586, + 'FR_Wheel_Angle': 21.62985610961914, + 'Location': array([-4.50251656e+01, 9.18310547e+01, 2.28517428e-02]), + 'Rotation': array([-1.41139016e-01, 8.38576126e+01, -4.34875451e-02]), + 'Velocity': array([ 0.04671756, -0.54430711, 0.00210227]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7670.3671875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13935.10742188, 7627.20898438, 118.20956421]), + 'frame': 21906, + 'frame_number': 21906, + 'framesequence': 88315, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.43311262130737305, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.7497412525117, + 'timestamp_carla': 747749, + 'timestamp_device': 1618349, + 'timestamp_stream': 747.7497412525117, + 'transform': [array([-50.08558655, 88.67655182, -0.157259 ]), + array([-8.96803755e-03, -8.04670715e+01, 8.30550864e-03])]} +{'AngularVelocity': array([-0.09542775, -0.18819688, -3.58756518]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.226715087890625, + 'FR_Wheel_Angle': 20.432050704956055, + 'Location': array([-4.50214691e+01, 9.17624893e+01, 2.28206161e-02]), + 'Rotation': array([-1.48959592e-01, 8.33955994e+01, -1.87377986e-02]), + 'Velocity': array([ 0.04476634, -0.50645685, -0.00121794]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7679.06396484375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13936.99316406, 7597.62011719, 118.25351715]), + 'frame': 21907, + 'frame_number': 21907, + 'framesequence': 88319, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42915740609169006, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.7833313494921, + 'timestamp_carla': 747782, + 'timestamp_device': 1618382, + 'timestamp_stream': 747.7833313494921, + 'transform': [array([-50.06513977, 88.72492981, -0.15730509]), + array([-8.64018872e-03, -8.02525635e+01, 8.52407515e-03])]} +{'AngularVelocity': array([-0.08510654, -0.22359103, -3.96371865]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.52701187133789, + 'FR_Wheel_Angle': 20.922330856323242, + 'Location': array([-4.50184059e+01, 9.16878662e+01, 2.27853674e-02]), + 'Rotation': array([-1.62169173e-01, 8.29123688e+01, 7.45936343e-03]), + 'Velocity': array([ 0.04837636, -0.54973823, -0.0008416 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7695.97900390625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13946.86132812, 7566.41748047, 118.29730988]), + 'frame': 21908, + 'frame_number': 21908, + 'framesequence': 88323, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42219915986061096, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.8174591511488, + 'timestamp_carla': 747817, + 'timestamp_device': 1618416, + 'timestamp_stream': 747.8174591511488, + 'transform': [array([-50.04442215, 88.77425385, -0.15729247]), + array([-8.57188739e-03, -8.00343933e+01, 8.45577475e-03])]} +{'AngularVelocity': array([-0.09457035, -0.21785609, -3.81631041]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.387065887451172, + 'FR_Wheel_Angle': 20.807266235351562, + 'Location': array([-4.50157623e+01, 9.16169281e+01, 2.27366928e-02]), + 'Rotation': array([-1.69525281e-01, 8.24432373e+01, 2.82808933e-02]), + 'Velocity': array([ 0.04215985, -0.51690286, -0.00090927]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7694.451171875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13938.37695312, 7538.0625 , 118.32581329]), + 'frame': 21909, + 'frame_number': 21909, + 'framesequence': 88327, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41608327627182007, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.8504934497178, + 'timestamp_carla': 747850, + 'timestamp_device': 1618449, + 'timestamp_stream': 747.8504934497178, + 'transform': [array([-50.02444839, 88.82167053, -0.15725982]), + array([-8.76313262e-03, -7.98253632e+01, 8.31917208e-03])]} +{'AngularVelocity': array([-0.02136795, -0.01494358, -3.45065093]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.407772064208984, + 'FR_Wheel_Angle': 20.788793563842773, + 'Location': array([-4.50139084e+01, 9.15480347e+01, 2.28573121e-02]), + 'Rotation': array([-1.73978567e-01, 8.19908218e+01, 3.60074379e-02]), + 'Velocity': array([ 0.03276413, -0.54770559, 0.00151693]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7721.7939453125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13958.08984375, 7504.25976562, 118.32008362]), + 'frame': 21910, + 'frame_number': 21910, + 'framesequence': 88331, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4135563373565674, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.8848008513451, + 'timestamp_carla': 747884, + 'timestamp_device': 1618482, + 'timestamp_stream': 747.8848008513451, + 'transform': [array([-50.00389862, 88.86997223, -0.15727445]), + array([-8.94754753e-03, -7.96128082e+01, 8.33282992e-03])]} +{'AngularVelocity': array([ 0.04192427, 0.02625435, -3.26801705]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.417652130126953, + 'FR_Wheel_Angle': 20.797344207763672, + 'Location': array([-4.50127869e+01, 9.14770279e+01, 2.31014527e-02]), + 'Rotation': array([-1.71874866e-01, 8.15287933e+01, 3.49194258e-02]), + 'Velocity': array([ 0.02382662, -0.50687557, 0.00171448]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7734.5830078125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13963.61132812, 7474.08740234, 118.30428314]), + 'frame': 21911, + 'frame_number': 21911, + 'framesequence': 88335, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41562551259994507, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.9200825504959, + 'timestamp_carla': 747919, + 'timestamp_device': 1618516, + 'timestamp_stream': 747.9200825504959, + 'transform': [array([-49.98287964, 88.9203186 , -0.15725738]), + array([-8.72215070e-03, -7.93915634e+01, 8.23720824e-03])]} +{'AngularVelocity': array([-0.00883307, -0.02763528, -3.01522541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.425397872924805, + 'FR_Wheel_Angle': 20.811376571655273, + 'Location': array([-4.50122337e+01, 9.14113541e+01, 2.33428851e-02]), + 'Rotation': array([-1.69948757e-01, 8.10991287e+01, 3.51999812e-02]), + 'Velocity': array([ 0.02219459, -0.49529895, 0.00208859]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7718.52392578125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13940.47460938, 7448.578125 , 118.30327606]), + 'frame': 21912, + 'frame_number': 21912, + 'framesequence': 88339, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41919615864753723, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.9516060501337, + 'timestamp_carla': 747951, + 'timestamp_device': 1618549, + 'timestamp_stream': 747.9516060501337, + 'transform': [array([-49.96422577, 88.96590424, -0.15720044]), + array([-8.53773579e-03, -7.91917648e+01, 8.10743403e-03])]} +{'AngularVelocity': array([-0.01405638, 0.02164992, -3.22792363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.4190616607666, + 'FR_Wheel_Angle': 20.802722930908203, + 'Location': array([-4.50122681e+01, 9.13460312e+01, 2.35730652e-02]), + 'Rotation': array([-1.70898154e-01, 8.06728363e+01, 3.70898098e-02]), + 'Velocity': array([ 0.01267662, -0.50993073, 0.00167128]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7713.08056640625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13927.40234375, 7420.10742188, 118.28831482]), + 'frame': 21913, + 'frame_number': 21913, + 'framesequence': 88343, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42207100987434387, + 'throttle_input': 0.2896620035171509, + 'timestamp': 747.9841076508164, + 'timestamp_carla': 747983, + 'timestamp_device': 1618582, + 'timestamp_stream': 747.9841076508164, + 'transform': [array([-49.9451828 , 89.01263428, -0.15719451]), + array([-8.29867925e-03, -7.89868851e+01, 8.13475717e-03])]} +{'AngularVelocity': array([ 0.01201577, 0.0455888 , -3.27400589]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.42337989807129, + 'FR_Wheel_Angle': 20.809513092041016, + 'Location': array([-4.50124931e+01, 9.12794189e+01, 2.37769224e-02]), + 'Rotation': array([-1.70037553e-01, 8.02334671e+01, 3.81162502e-02]), + 'Velocity': array([ 0.00856624, -0.48630032, 0.00150665]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7741.97216796875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13948.72851562, 7388.11621094, 118.27698517]), + 'frame': 21914, + 'frame_number': 21914, + 'framesequence': 88347, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4223090410232544, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.0167175494134, + 'timestamp_carla': 748016, + 'timestamp_device': 1618616, + 'timestamp_stream': 748.0167175494134, + 'transform': [array([-49.92634583, 89.05962372, -0.15721342]), + array([-8.12109467e-03, -7.87811203e+01, 8.24403670e-03])]} +{'AngularVelocity': array([ 0.01487393, 0.05045866, -2.98019218]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.430360794067383, + 'FR_Wheel_Angle': 20.813980102539062, + 'Location': array([-4.50132217e+01, 9.12167435e+01, 2.39859670e-02]), + 'Rotation': array([-1.69375017e-01, 7.98217316e+01, 3.89942229e-02]), + 'Velocity': array([ 0.00412127, -0.47058803, 0.00175543]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7763.52880859375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13962.53320312, 7356.66845703, 118.28413391]), + 'frame': 21915, + 'frame_number': 21915, + 'framesequence': 88351, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42089909315109253, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.0504693500698, + 'timestamp_carla': 748050, + 'timestamp_device': 1618649, + 'timestamp_stream': 748.0504693500698, + 'transform': [array([-49.90710831, 89.10805511, -0.15725888]), + array([-8.09377339e-03, -7.85693817e+01, 8.40796344e-03])]} +{'AngularVelocity': array([-0.03491054, -0.01362816, -2.13056684]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.972867012023926, + 'FR_Wheel_Angle': 15.69279956817627, + 'Location': array([-4.50146370e+01, 9.11520386e+01, 2.42007338e-02]), + 'Rotation': array([-1.71171367e-01, 7.94019699e+01, 4.09328751e-02]), + 'Velocity': array([ 0.00100134, -0.51978385, 0.00184881]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7763.10888671875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13954.6328125 , 7329.25537109, 118.29892731]), + 'frame': 21916, + 'frame_number': 21916, + 'framesequence': 88355, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41897645592689514, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.0824560523033, + 'timestamp_carla': 748082, + 'timestamp_device': 1618682, + 'timestamp_stream': 748.0824560523033, + 'transform': [array([-49.88906479, 89.15372467, -0.15713067]), + array([-7.24000018e-03, -7.83699493e+01, 8.02547205e-03])]} +{'AngularVelocity': array([ 0.01165924, 0.00260084, -1.3485918 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.783546447753906, + 'FR_Wheel_Angle': 16.782493591308594, + 'Location': array([-4.50186920e+01, 9.10852814e+01, 2.44223680e-02]), + 'Rotation': array([-1.70864001e-01, 7.90559540e+01, 3.88746001e-02]), + 'Velocity': array([-0.02496834, -0.50379068, 0.00187304]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7750.13330078125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13934.1015625 , 7303.56054688, 118.31840515]), + 'frame': 21917, + 'frame_number': 21917, + 'framesequence': 88359, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41870173811912537, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.1162737496197, + 'timestamp_carla': 748115, + 'timestamp_device': 1618716, + 'timestamp_stream': 748.1162737496197, + 'transform': [array([-49.87022018, 89.20173645, -0.1566111 ]), + array([-4.04347200e-03, -7.81606445e+01, 6.28377264e-03])]} +{'AngularVelocity': array([ 0.00448481, -0.01792416, -1.6198324 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.762857437133789, + 'FR_Wheel_Angle': 16.668930053710938, + 'Location': array([-4.50229836e+01, 9.10190277e+01, 2.46152785e-02]), + 'Rotation': array([-1.69340864e-01, 7.87062759e+01, 4.29096073e-02]), + 'Velocity': array([-0.01358028, -0.49106902, 0.00157286]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5098.44921875, + 'focus_actor_name': 'AmericanLights_Town04_35_TrafficLight', + 'focus_actor_pt': array([-11329.40625 , 7811.56884766, 117.89621735]), + 'frame': 21918, + 'frame_number': 21918, + 'framesequence': 88363, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4194525182247162, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.1505211517215, + 'timestamp_carla': 748150, + 'timestamp_device': 1618749, + 'timestamp_stream': 748.1505211517215, + 'transform': [array([-49.85133362, 89.25102997, -0.15632796]), + array([-2.71158502e-03, -7.79460678e+01, 5.29339537e-03])]} +{'AngularVelocity': array([-0.01541083, -0.02784792, -1.70556545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.277328491210938, + 'FR_Wheel_Angle': 16.723169326782227, + 'Location': array([-4.50276489e+01, 9.09539719e+01, 2.48004049e-02]), + 'Rotation': array([-1.68275356e-01, 7.83684540e+01, 4.30207066e-02]), + 'Velocity': array([-0.02130222, -0.47610563, 0.00274667]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5100.72607421875, + 'focus_actor_name': 'AmericanLights_Town04_35_TrafficLight', + 'focus_actor_pt': array([-11325.68164062, 7792.75390625, 117.74190521]), + 'frame': 21919, + 'frame_number': 21919, + 'framesequence': 88367, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4202765226364136, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.1819870509207, + 'timestamp_carla': 748181, + 'timestamp_device': 1618782, + 'timestamp_stream': 748.1819870509207, + 'transform': [array([-49.83407974, 89.29660797, -0.15615614]), + array([-2.19932082e-03, -7.77480698e+01, 4.74015018e-03])]} +{'AngularVelocity': array([-0.00891361, -0.01922051, -1.48734868]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.410026550292969, + 'FR_Wheel_Angle': 16.572368621826172, + 'Location': array([-4.50321388e+01, 9.08954697e+01, 2.50160489e-02]), + 'Rotation': array([-1.67476222e-01, 7.80589066e+01, 4.46292162e-02]), + 'Velocity': array([-0.02010224, -0.45155612, 0.00153924]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7788.189453125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13947.73632812, 7212.72607422, 117.90266418]), + 'frame': 21920, + 'frame_number': 21920, + 'framesequence': 88371, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4202765226364136, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.2174572497606, + 'timestamp_carla': 748217, + 'timestamp_device': 1618816, + 'timestamp_stream': 748.2174572497606, + 'transform': [array([-49.81485367, 89.34760284, -0.15610661]), + array([-1.84415095e-03, -7.75267105e+01, 4.51475475e-03])]} +{'AngularVelocity': array([ 3.98857845e-03, -4.51441127e-04, -1.07470036e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.42893123626709, + 'FR_Wheel_Angle': 16.675537109375, + 'Location': array([-4.50368996e+01, 9.08376770e+01, 2.51862239e-02]), + 'Rotation': array([-1.67018607e-01, 7.77587357e+01, 4.51939516e-02]), + 'Velocity': array([-0.02456321, -0.42396683, 0.00132768]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7807.4580078125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13958.87304688, 7182.23388672, 117.83161163]), + 'frame': 21921, + 'frame_number': 21921, + 'framesequence': 88375, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41980043053627014, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.249604549259, + 'timestamp_carla': 748249, + 'timestamp_device': 1618849, + 'timestamp_stream': 748.249604549259, + 'transform': [array([-49.79738998, 89.39496613, -0.15532739]), + array([ 2.71841511e-03, -7.73213272e+01, 1.94660341e-03])]} +{'AngularVelocity': array([-0.12197021, -0.03887859, -2.16782951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.38000774383545, + 'FR_Wheel_Angle': 16.645111083984375, + 'Location': array([-4.50420341e+01, 9.07786102e+01, 2.53962614e-02]), + 'Rotation': array([-1.70105845e-01, 7.74605331e+01, 4.79994118e-02]), + 'Velocity': array([-0.03634141, -0.52826679, 0.00172228]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7820.4150390625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13962.78417969, 7149.87353516, 117.80040741]), + 'frame': 21922, + 'frame_number': 21922, + 'framesequence': 88379, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4195989966392517, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.2816095501184, + 'timestamp_carla': 748281, + 'timestamp_device': 1618882, + 'timestamp_stream': 748.2816095501184, + 'transform': [array([-49.78017044, 89.44120789, -0.15385875]), + array([ 1.10512450e-02, -7.71210861e+01, -2.92968866e-03])]} +{'AngularVelocity': array([ 0.0374189 , 0.04542454, -2.4545362 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.39052963256836, + 'FR_Wheel_Angle': 16.637889862060547, + 'Location': array([-4.50481339e+01, 9.07118225e+01, 2.56084725e-02]), + 'Rotation': array([-1.69791669e-01, 7.71108704e+01, 4.90927622e-02]), + 'Velocity': array([-0.03532154, -0.48090461, 0.00162304]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7814.1357421875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13948.46386719, 7123.8125 , 117.45207977]), + 'frame': 21923, + 'frame_number': 21923, + 'framesequence': 88383, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4195989966392517, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.3163519501686, + 'timestamp_carla': 748315, + 'timestamp_device': 1618916, + 'timestamp_stream': 748.3163519501686, + 'transform': [array([-49.76179123, 89.49108887, -0.15195227]), + array([ 2.16107182e-02, -7.69052734e+01, -9.33838449e-03])]} +{'AngularVelocity': array([ 0.02307656, 0.03920931, -2.71407795]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.375843048095703, + 'FR_Wheel_Angle': 16.641841888427734, + 'Location': array([-4.50548248e+01, 9.06437378e+01, 2.58402154e-02]), + 'Rotation': array([-1.71321630e-01, 7.67380447e+01, 5.10787964e-02]), + 'Velocity': array([-0.04217807, -0.53648674, 0.00226911]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7817.49072265625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13943.62695312, 7096.37353516, 116.7914505 ]), + 'frame': 21924, + 'frame_number': 21924, + 'framesequence': 88387, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41967225074768066, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.3484547510743, + 'timestamp_carla': 748348, + 'timestamp_device': 1618949, + 'timestamp_stream': 748.3484547510743, + 'transform': [array([-49.74505615, 89.53770447, -0.14995486]), + array([ 3.20472457e-02, -7.67039185e+01, -1.59912165e-02])]} +{'AngularVelocity': array([ 0.03770163, 0.04198942, -2.58411694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.386420249938965, + 'FR_Wheel_Angle': 16.651351928710938, + 'Location': array([-4.50618477e+01, 9.05751419e+01, 2.60385796e-02]), + 'Rotation': array([-1.68090940e-01, 7.63779297e+01, 5.05030006e-02]), + 'Velocity': array([-0.04277758, -0.49849257, 0.00218674]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7835.72900390625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13952.54882812, 7063.4921875 , 115.91940308]), + 'frame': 21925, + 'frame_number': 21925, + 'framesequence': 88391, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.3822635523975, + 'timestamp_carla': 748381, + 'timestamp_device': 1618982, + 'timestamp_stream': 748.3822635523975, + 'transform': [array([-49.72766495, 89.58615112, -0.14785147]), + array([ 4.29413952e-02, -7.64949799e+01, -2.30407827e-02])]} +{'AngularVelocity': array([-0.01684125, 0.01956154, -1.85358047]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.386911392211914, + 'FR_Wheel_Angle': 16.646547317504883, + 'Location': array([-4.50688858e+01, 9.05101242e+01, 2.62199305e-02]), + 'Rotation': array([-1.66813701e-01, 7.60312424e+01, 5.14706001e-02]), + 'Velocity': array([-0.04402801, -0.49785891, 0.0011254 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7851.25146484375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13959.3203125 , 7033.07080078, 115.01415253]), + 'frame': 21926, + 'frame_number': 21926, + 'framesequence': 88395, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.4160252511501, + 'timestamp_carla': 748415, + 'timestamp_device': 1619015, + 'timestamp_stream': 748.4160252511501, + 'transform': [array([-49.71060562, 89.63404083, -0.14576997]), + array([ 5.35896607e-02, -7.62885818e+01, -2.99987961e-02])]} +{'AngularVelocity': array([ 1.27941519e-02, -1.52701186e-03, -2.25790811e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.812539100646973, + 'FR_Wheel_Angle': 14.464126586914062, + 'Location': array([-4.50765991e+01, 9.04450684e+01, 2.64307298e-02]), + 'Rotation': array([-1.66841015e-01, 7.56839981e+01, 5.22674806e-02]), + 'Velocity': array([-0.04406086, -0.48259628, 0.00161163]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4805.10986328125, + 'focus_actor_name': 'Cypress_Small22', + 'focus_actor_pt': array([-10988.625 , 7716.546875 , 115.28117371]), + 'frame': 21927, + 'frame_number': 21927, + 'framesequence': 88399, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.4494779519737, + 'timestamp_carla': 748449, + 'timestamp_device': 1619049, + 'timestamp_stream': 748.4494779519737, + 'transform': [array([-49.69383621, 89.68241119, -0.14358482]), + array([ 6.46682307e-02, -7.60805206e+01, -3.73230278e-02])]} +{'AngularVelocity': array([ 1.38047850e-04, -1.92301329e-02, -1.96588993e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.761577606201172, + 'FR_Wheel_Angle': 11.209424018859863, + 'Location': array([-4.50860176e+01, 9.03795776e+01, 2.66462229e-02]), + 'Rotation': array([-1.67605996e-01, 7.53873138e+01, 5.10643497e-02]), + 'Velocity': array([-0.06610715, -0.49817064, 0.00130527]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4806.13720703125, + 'focus_actor_name': 'Cypress_Small22', + 'focus_actor_pt': array([-10983.42382812, 7699.45117188, 114.70695496]), + 'frame': 21928, + 'frame_number': 21928, + 'framesequence': 88403, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.4829195514321, + 'timestamp_carla': 748482, + 'timestamp_device': 1619082, + 'timestamp_stream': 748.4829195514321, + 'transform': [array([-49.67729568, 89.73001099, -0.14149562]), + array([ 7.51935467e-02, -7.58760300e+01, -4.43115607e-02])]} +{'AngularVelocity': array([-0.01119485, -0.06332541, -1.96906066]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.839964866638184, + 'FR_Wheel_Angle': 13.228577613830566, + 'Location': array([-4.50966721e+01, 9.03154602e+01, 2.68399715e-02]), + 'Rotation': array([-1.65891632e-01, 7.51442642e+01, 5.29396199e-02]), + 'Velocity': array([-0.06045476, -0.47364113, 0.00131323]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4810.51513671875, + 'focus_actor_name': 'Cypress_Small22', + 'focus_actor_pt': array([-10981.38867188, 7681.42773438, 114.09970093]), + 'frame': 21929, + 'frame_number': 21929, + 'framesequence': 88407, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.5157615505159, + 'timestamp_carla': 748515, + 'timestamp_device': 1619115, + 'timestamp_stream': 748.5157615505159, + 'transform': [array([-49.6611824 , 89.77770233, -0.13935518]), + array([ 8.59647542e-02, -7.56713562e+01, -5.14832102e-02])]} +{'AngularVelocity': array([-0.00231901, -0.03234218, -2.11830235]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.843781471252441, + 'FR_Wheel_Angle': 12.185822486877441, + 'Location': array([-4.51072464e+01, 9.02499084e+01, 2.70664878e-02]), + 'Rotation': array([-1.67325959e-01, 7.48796616e+01, 5.54922186e-02]), + 'Velocity': array([-0.06734305, -0.50435674, 0.00153685]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4810.29052734375, + 'focus_actor_name': 'Cypress_Small22', + 'focus_actor_pt': array([-10974.90820312, 7664.81396484, 113.52256775]), + 'frame': 21930, + 'frame_number': 21930, + 'framesequence': 88411, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.5487525500357, + 'timestamp_carla': 748548, + 'timestamp_device': 1619149, + 'timestamp_stream': 748.5487525500357, + 'transform': [array([-49.6451683 , 89.82489014, -0.13732028]), + array([ 9.62510183e-02, -7.54692154e+01, -5.82886636e-02])]} +{'AngularVelocity': array([-0.00831103, -0.04166442, -2.00532246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.302172660827637, + 'FR_Wheel_Angle': 12.587934494018555, + 'Location': array([-4.51183662e+01, 9.01844101e+01, 2.72538271e-02]), + 'Rotation': array([-1.65707216e-01, 7.46143341e+01, 5.59153445e-02]), + 'Velocity': array([-0.06664561, -0.48257437, 0.00144579]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7879.03662109375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13941.88671875, 6888.68115234, 110.1737442 ]), + 'frame': 21931, + 'frame_number': 21931, + 'framesequence': 88415, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.5821931511164, + 'timestamp_carla': 748581, + 'timestamp_device': 1619182, + 'timestamp_stream': 748.5821931511164, + 'transform': [array([-49.62919998, 89.87242889, -0.13532136]), + array([ 1.06475815e-01, -7.52656784e+01, -6.49720430e-02])]} +{'AngularVelocity': array([-0.01160923, 0.0101071 , -1.79277003]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.12947940826416, + 'FR_Wheel_Angle': 12.495255470275879, + 'Location': array([-4.51289139e+01, 9.01235657e+01, 2.74496749e-02]), + 'Rotation': array([-1.64764643e-01, 7.43679733e+01, 5.61762340e-02]), + 'Velocity': array([-0.07361591, -0.46598929, 0.00115977]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7882.21484375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13935.95605469, 6860.96386719, 109.24363708]), + 'frame': 21932, + 'frame_number': 21932, + 'framesequence': 88419, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.6160719506443, + 'timestamp_carla': 748615, + 'timestamp_device': 1619215, + 'timestamp_stream': 748.6160719506443, + 'transform': [array([-49.61316299, 89.92142487, -0.1332127 ]), + array([ 1.17315322e-01, -7.50561676e+01, -7.20521510e-02])]} +{'AngularVelocity': array([ 0.02443633, 0.00322413, -2.05421782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.138132095336914, + 'FR_Wheel_Angle': 12.467191696166992, + 'Location': array([-4.51408348e+01, 9.00577927e+01, 2.76813786e-02]), + 'Rotation': array([-1.67114228e-01, 7.40977554e+01, 5.81580251e-02]), + 'Velocity': array([-0.07924256, -0.49628356, 0.0017853 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7931.0712890625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13974.03515625, 6821.45214844, 108.27829742]), + 'frame': 21933, + 'frame_number': 21933, + 'framesequence': 88423, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.6492184512317, + 'timestamp_carla': 748648, + 'timestamp_device': 1619249, + 'timestamp_stream': 748.6492184512317, + 'transform': [array([-49.5976944 , 89.96884918, -0.13109775]), + array([ 0.12594868, -74.85381317, -0.0793459 ])]} +{'AngularVelocity': array([-0.00372747, -0.01767895, -1.67799318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.150959968566895, + 'FR_Wheel_Angle': 12.48195743560791, + 'Location': array([-4.51526031e+01, 8.99937897e+01, 2.78740209e-02]), + 'Rotation': array([-1.64914906e-01, 7.38404846e+01, 5.83405122e-02]), + 'Velocity': array([-0.07670434, -0.47788736, 0.00168877]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7932.07861328125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13965.44433594, 6793.17089844, 107.30522919]), + 'frame': 21934, + 'frame_number': 21934, + 'framesequence': 88427, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.6819554492831, + 'timestamp_carla': 748681, + 'timestamp_device': 1619282, + 'timestamp_stream': 748.6819554492831, + 'transform': [array([-49.58259964, 90.01673889, -0.12964778]), + array([ 0.12832558, -74.64974213, -0.08465598])]} +{'AngularVelocity': array([-0.01473306, -0.01645579, -1.67061329]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.151670455932617, + 'FR_Wheel_Angle': 12.468664169311523, + 'Location': array([-4.51643562e+01, 8.99316101e+01, 2.80663576e-02]), + 'Rotation': array([-1.64518759e-01, 7.35893860e+01, 5.91150522e-02]), + 'Velocity': array([-0.0782049 , -0.47084835, 0.00160446]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7922.5048828125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13946.85253906, 6768.64013672, 106.32047272]), + 'frame': 21935, + 'frame_number': 21935, + 'framesequence': 88431, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.7162918522954, + 'timestamp_carla': 748715, + 'timestamp_device': 1619315, + 'timestamp_stream': 748.7162918522954, + 'transform': [array([-49.56690216, 90.06607056, -0.12911461]), + array([ 0.12857148, -74.43967438, -0.08663962])]} +{'AngularVelocity': array([ 0.00981386, 0.01879958, -1.77124083]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.140022277832031, + 'FR_Wheel_Angle': 12.46712589263916, + 'Location': array([-4.51768150e+01, 8.98674469e+01, 2.82768141e-02]), + 'Rotation': array([-1.65618420e-01, 7.33462982e+01, 5.99235557e-02]), + 'Velocity': array([-0.08845185, -0.48444122, 0.00165467]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7926.75537109375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13941.45898438, 6740.30761719, 105.59347534]), + 'frame': 21936, + 'frame_number': 21936, + 'framesequence': 88435, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.7508515492082, + 'timestamp_carla': 748750, + 'timestamp_device': 1619349, + 'timestamp_stream': 748.7508515492082, + 'transform': [array([-49.55120468, 90.11669922, -0.12894483]), + array([ 0.12822996, -74.22433472, -0.08731101])]} +{'AngularVelocity': array([ 0.01542694, -0.03911799, -2.13595986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.144866943359375, + 'FR_Wheel_Angle': 12.469438552856445, + 'Location': array([-4.51902542e+01, 8.97993011e+01, 2.84735002e-02]), + 'Rotation': array([-1.65645733e-01, 7.30663834e+01, 6.16530068e-02]), + 'Velocity': array([-0.08161835, -0.49407363, 0.00113684]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7958.65576171875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13962.2734375 , 6703.76220703, 105.2765274 ]), + 'frame': 21937, + 'frame_number': 21937, + 'framesequence': 88439, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.7813598513603, + 'timestamp_carla': 748780, + 'timestamp_device': 1619382, + 'timestamp_stream': 748.7813598513603, + 'transform': [array([-49.53733826, 90.1619873 , -0.12888703]), + array([ 0.1277177 , -74.03198242, -0.08749411])]} +{'AngularVelocity': array([-0.06205641, -0.01136425, -2.78242922]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.12992000579834, + 'FR_Wheel_Angle': 12.155885696411133, + 'Location': array([-4.52044029e+01, 8.97302551e+01, 2.87457164e-02]), + 'Rotation': array([-1.67756274e-01, 7.27755966e+01, 6.29052892e-02]), + 'Velocity': array([-0.10895316, -0.58736861, 0.00216461]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4105.001953125, + 'focus_actor_name': 'Cypress_Small21', + 'focus_actor_pt': array([-10243.49414062, 7722.70410156, 111.05844879]), + 'frame': 21938, + 'frame_number': 21938, + 'framesequence': 88443, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.8157891519368, + 'timestamp_carla': 748815, + 'timestamp_device': 1619415, + 'timestamp_stream': 748.8157891519368, + 'transform': [array([-49.52176666, 90.21248627, -0.12901372]), + array([ 0.12701419, -73.81774902, -0.08712789])]} +{'AngularVelocity': array([ 0.03197971, -0.00414161, -2.02108216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.222533702850342, + 'FR_Wheel_Angle': 6.669049263000488, + 'Location': array([-4.52211571e+01, 8.96525040e+01, 2.89369486e-02]), + 'Rotation': array([-1.65768683e-01, 7.24707336e+01, 6.16463833e-02]), + 'Velocity': array([-0.11202956, -0.54521775, 0.00122032]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4112.75927734375, + 'focus_actor_name': 'Cypress_Small21', + 'focus_actor_pt': array([-10245.20898438, 7707.35351562, 111.03668976]), + 'frame': 21939, + 'frame_number': 21939, + 'framesequence': 88447, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.848628949374, + 'timestamp_carla': 748848, + 'timestamp_device': 1619449, + 'timestamp_stream': 748.848628949374, + 'transform': [array([-49.50714874, 90.26163483, -0.1291368 ]), + array([ 0.12652925, -73.60939789, -0.08670066])]} +{'AngularVelocity': array([-0.00383515, -0.04327147, -1.4962095 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.687149524688721, + 'FR_Wheel_Angle': 9.08658218383789, + 'Location': array([-4.52377739e+01, 8.95861816e+01, 2.91604139e-02]), + 'Rotation': array([-1.62599474e-01, 7.23059769e+01, 5.98068014e-02]), + 'Velocity': array([-0.11803093, -0.50213009, 0.00136321]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4124.9404296875, + 'focus_actor_name': 'Cypress_Small21', + 'focus_actor_pt': array([-10250.41796875, 7689.23046875, 111.04292297]), + 'frame': 21940, + 'frame_number': 21940, + 'framesequence': 88451, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.881683550775, + 'timestamp_carla': 748881, + 'timestamp_device': 1619482, + 'timestamp_stream': 748.881683550775, + 'transform': [array([-49.49260712, 90.31034851, -0.12932059]), + array([ 0.12588722, -73.40304565, -0.08605977])]} +{'AngularVelocity': array([-0.00352271, -0.02909035, -1.64023542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.787435531616211, + 'FR_Wheel_Angle': 8.027295112609863, + 'Location': array([-4.52532997e+01, 8.95231094e+01, 2.93433275e-02]), + 'Rotation': array([-1.60885096e-01, 7.21197586e+01, 6.28467798e-02]), + 'Velocity': array([-0.10139555, -0.45706743, 0.00120599]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4119.0439453125, + 'focus_actor_name': 'Cypress_Small21', + 'focus_actor_pt': array([-10238.41992188, 7676.54980469, 111.08213806]), + 'frame': 21941, + 'frame_number': 21941, + 'framesequence': 88455, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.9160765521228, + 'timestamp_carla': 748915, + 'timestamp_device': 1619515, + 'timestamp_stream': 748.9160765521228, + 'transform': [array([-49.47780609, 90.36094666, -0.12865907]), + array([ 0.12200766, -73.18903351, -0.08911153])]} +{'AngularVelocity': array([-0.02291372, -0.03135864, -1.36550093]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.729800701141357, + 'FR_Wheel_Angle': 8.486495971679688, + 'Location': array([-4.52684326e+01, 8.94630737e+01, 2.95337960e-02]), + 'Rotation': array([-1.61615923e-01, 7.19536514e+01, 6.35045841e-02]), + 'Velocity': array([-0.10456148, -0.4528535 , 0.00111013]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4147.29833984375, + 'focus_actor_name': 'Cypress_Small21', + 'focus_actor_pt': array([-10259.14550781, 7654.31689453, 111.08413696]), + 'frame': 21942, + 'frame_number': 21942, + 'framesequence': 88459, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4195989966392517, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.9498081505299, + 'timestamp_carla': 748949, + 'timestamp_device': 1619549, + 'timestamp_stream': 748.9498081505299, + 'transform': [array([-49.46360397, 90.41117859, -0.1265572 ]), + array([ 0.12243114, -72.97666168, -0.09732077])]} +{'AngularVelocity': array([-0.09277272, -0.01208243, -0.81440455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.640744209289551, + 'FR_Wheel_Angle': 8.282676696777344, + 'Location': array([-4.52837334e+01, 8.94029160e+01, 2.97449771e-02]), + 'Rotation': array([-1.63664982e-01, 7.17824326e+01, 6.50955588e-02]), + 'Velocity': array([-0.12087721, -0.50862974, 0.00172213]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8011.271484375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13951.32519531, 6522.01074219, 104.86182404]), + 'frame': 21943, + 'frame_number': 21943, + 'framesequence': 88463, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4117984473705292, + 'throttle_input': 0.2896620035171509, + 'timestamp': 748.9833011515439, + 'timestamp_carla': 748982, + 'timestamp_device': 1619582, + 'timestamp_stream': 748.9833011515439, + 'transform': [array([-49.44960403, 90.46062469, -0.12377232]), + array([ 0.12414551, -72.76818848, -0.10800197])]} +{'AngularVelocity': array([ 0.01413074, -0.0119577 , -1.34297967]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.712590217590332, + 'FR_Wheel_Angle': 8.329279899597168, + 'Location': array([-4.53010101e+01, 8.93363266e+01, 2.99508572e-02]), + 'Rotation': array([-1.64300188e-01, 7.15997162e+01, 6.57793283e-02]), + 'Velocity': array([-0.11728369, -0.48586288, 0.001199 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8025.7978515625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13954.42871094, 6489.41796875, 103.70671082]), + 'frame': 21944, + 'frame_number': 21944, + 'framesequence': 88467, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3931577503681183, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.0153724513948, + 'timestamp_carla': 749014, + 'timestamp_device': 1619615, + 'timestamp_stream': 749.0153724513948, + 'transform': [array([-49.4360199 , 90.50698853, -0.1207351 ]), + array([ 0.12582573, -72.57388306, -0.11959867])]} +{'AngularVelocity': array([-0.03948823, 0.02065587, -1.5106349 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.703321933746338, + 'FR_Wheel_Angle': 8.320246696472168, + 'Location': array([-4.53179245e+01, 8.92721558e+01, 3.01697813e-02]), + 'Rotation': array([-1.65003702e-01, 7.14179993e+01, 6.65600896e-02]), + 'Velocity': array([-0.13635167, -0.53828055, 0.00186304]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8021.02197265625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13939.14453125, 6463.01367188, 102.24315643]), + 'frame': 21945, + 'frame_number': 21945, + 'framesequence': 88471, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.37158727645874023, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.0493786521256, + 'timestamp_carla': 749048, + 'timestamp_device': 1619649, + 'timestamp_stream': 749.0493786521256, + 'transform': [array([-49.42132568, 90.5532074 , -0.11750372]), + array([ 0.12689124, -72.38179016, -0.13201939])]} +{'AngularVelocity': array([ 0.02853737, 0.01522619, -0.93632841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.707424163818359, + 'FR_Wheel_Angle': 8.327486038208008, + 'Location': array([-4.53362846e+01, 8.92029800e+01, 3.03814970e-02]), + 'Rotation': array([-1.63699135e-01, 7.12203140e+01, 6.68660775e-02]), + 'Velocity': array([-0.12755449, -0.50072205, 0.00174107]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8031.072265625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13938.58496094, 6434.14306641, 100.6282959 ]), + 'frame': 21946, + 'frame_number': 21946, + 'framesequence': 88475, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.34723350405693054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.0825455524027, + 'timestamp_carla': 749082, + 'timestamp_device': 1619682, + 'timestamp_stream': 749.0825455524027, + 'transform': [array([-49.40672684, 90.59661102, -0.11425881]), + array([ 0.12792943, -72.20326233, -0.14444007])]} +{'AngularVelocity': array([-0.02760757, -0.00805221, -0.68753874]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.702143669128418, + 'FR_Wheel_Angle': 8.316974639892578, + 'Location': array([-4.53534813e+01, 8.91390228e+01, 3.05726901e-02]), + 'Rotation': array([-1.61677405e-01, 7.10403671e+01, 6.68695644e-02]), + 'Velocity': array([-0.12520108, -0.49218619, 0.00164053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8060.40625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13956.27441406, 6399.73730469, 98.84840393]), + 'frame': 21947, + 'frame_number': 21947, + 'framesequence': 88479, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3345072865486145, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.1145096495748, + 'timestamp_carla': 749114, + 'timestamp_device': 1619715, + 'timestamp_stream': 749.1145096495748, + 'transform': [array([-49.39242935, 90.63652039, -0.11115181]), + array([ 0.12890615, -72.04070282, -0.15628091])]} +{'AngularVelocity': array([-0.03990056, 0.00518197, -1.11290073]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.700070381164551, + 'FR_Wheel_Angle': 8.317036628723145, + 'Location': array([-4.53730507e+01, 8.90669937e+01, 3.08169462e-02]), + 'Rotation': array([-1.65502310e-01, 7.08543243e+01, 6.87807426e-02]), + 'Velocity': array([-0.14892176, -0.57771081, 0.0019484 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8065.41943359375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13951.2890625 , 6374.45703125, 97.1214447 ]), + 'frame': 21948, + 'frame_number': 21948, + 'framesequence': 88483, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33822447061538696, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.1490235514939, + 'timestamp_carla': 749148, + 'timestamp_device': 1619749, + 'timestamp_stream': 749.1490235514939, + 'transform': [array([-49.37715149, 90.67900085, -0.10788351]), + array([ 0.13091423, -71.86814117, -0.16870163])]} +{'AngularVelocity': array([ 0.04171272, 0.00274064, -0.27312261]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7048492431640625, + 'FR_Wheel_Angle': 8.323317527770996, + 'Location': array([-4.53930855e+01, 8.89944534e+01, 3.10395323e-02]), + 'Rotation': array([-1.62872687e-01, 7.06495438e+01, 6.83158115e-02]), + 'Velocity': array([-0.13736992, -0.52032727, 0.00161791]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8063.966796875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13940.84375 , 6353.33740234, 95.48778534]), + 'frame': 21949, + 'frame_number': 21949, + 'framesequence': 88487, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35036471486091614, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.1826608516276, + 'timestamp_carla': 749182, + 'timestamp_device': 1619782, + 'timestamp_stream': 749.1826608516276, + 'transform': [array([-49.3626709 , 90.72195435, -0.10463113]), + array([ 0.13406295, -71.69313812, -0.18090869])]} +{'AngularVelocity': array([-4.22641123e-03, 1.67407998e-04, -3.84290010e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.2677741050720215, + 'FR_Wheel_Angle': 4.711829662322998, + 'Location': array([-4.54118843e+01, 8.89275665e+01, 3.12314499e-02]), + 'Rotation': array([-1.60031319e-01, 7.04650574e+01, 6.82821870e-02]), + 'Velocity': array([-0.13078003, -0.48815182, 0.00159866]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8062.59326171875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13929.828125 , 6330.90283203, 93.7747345 ]), + 'frame': 21950, + 'frame_number': 21950, + 'framesequence': 88491, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3623218536376953, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.2151843495667, + 'timestamp_carla': 749214, + 'timestamp_device': 1619815, + 'timestamp_stream': 749.2151843495667, + 'transform': [array([-49.3490715 , 90.76475525, -0.10148339]), + array([ 0.13748486, -71.51805878, -0.19265801])]} +{'AngularVelocity': array([-0.02310666, 0.01073223, -0.35417086]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.861344814300537, + 'FR_Wheel_Angle': 3.691798686981201, + 'Location': array([-4.54332771e+01, 8.88591003e+01, 3.14681157e-02]), + 'Rotation': array([-1.61773026e-01, 7.03541260e+01, 6.55731708e-02]), + 'Velocity': array([-0.16270079, -0.49804541, 0.00190861]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8087.41943359375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13943.57128906, 6299.94335938, 92.00881958]), + 'frame': 21951, + 'frame_number': 21951, + 'framesequence': 88495, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3716605305671692, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.2481676489115, + 'timestamp_carla': 749247, + 'timestamp_device': 1619849, + 'timestamp_stream': 749.2481676489115, + 'transform': [array([-49.33563232, 90.80841827, -0.09840041]), + array([ 0.14065407, -71.3388443 , -0.20419371])]} +{'AngularVelocity': array([-0.01442466, -0.02435206, -0.50905704]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.654430389404297, + 'FR_Wheel_Angle': 4.509204864501953, + 'Location': array([-4.54535408e+01, 8.87964630e+01, 3.16565968e-02]), + 'Rotation': array([-1.60885096e-01, 7.02714310e+01, 6.88360408e-02]), + 'Velocity': array([-0.14351599, -0.47184619, 0.00140239]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8125.08740234375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13969.44335938, 6264.765625 , 90.25318909]), + 'frame': 21952, + 'frame_number': 21952, + 'framesequence': 88499, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3709647059440613, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.2818930521607, + 'timestamp_carla': 749281, + 'timestamp_device': 1619882, + 'timestamp_stream': 749.2818930521607, + 'transform': [array([-49.32215881, 90.85289001, -0.09533784]), + array([ 0.14328369, -71.15625 , -0.21572939])]} +{'AngularVelocity': array([ 0.00999026, -0.00122344, -0.52453643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.727440118789673, + 'FR_Wheel_Angle': 4.041179180145264, + 'Location': array([-4.54732742e+01, 8.87345428e+01, 3.18405814e-02]), + 'Rotation': array([-1.60639212e-01, 7.01784134e+01, 6.91924989e-02]), + 'Velocity': array([-0.14288352, -0.45199326, 0.00092545]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8111.81787109375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13946.70703125, 6245.12792969, 88.69413757]), + 'frame': 21953, + 'frame_number': 21953, + 'framesequence': 88503, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3655812442302704, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.3149287514389, + 'timestamp_carla': 749314, + 'timestamp_device': 1619915, + 'timestamp_stream': 749.3149287514389, + 'transform': [array([-49.30897522, 90.89716339, -0.09220229]), + array([ 0.14583819, -70.97476196, -0.22757025])]} +{'AngularVelocity': array([-0.02660848, -0.00274184, -0.5279671 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.072145938873291, + 'FR_Wheel_Angle': 4.119931697845459, + 'Location': array([-4.54927902e+01, 8.86744385e+01, 3.20516489e-02]), + 'Rotation': array([-0.1613154 , 70.08891296, 0.07016298]), + 'Velocity': array([-0.14797294, -0.47221163, 0.00174198]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3471.524169921875, + 'focus_actor_name': 'Cypress_Small20', + 'focus_actor_pt': array([-9544.75292969, 7719.65234375, 104.56047821]), + 'frame': 21954, + 'frame_number': 21954, + 'framesequence': 88507, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3600695729255676, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.3485840521753, + 'timestamp_carla': 749348, + 'timestamp_device': 1619949, + 'timestamp_stream': 749.3485840521753, + 'transform': [array([-4.92955055e+01, 9.09409256e+01, -8.99100602e-02]), + array([ 0.14312661, -70.79618073, -0.236634 ])]} +{'AngularVelocity': array([ 0.00605854, -0.00757575, -1.74509382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.033907890319824, + 'FR_Wheel_Angle': 4.174221992492676, + 'Location': array([-4.55142365e+01, 8.86085205e+01, 3.22682075e-02]), + 'Rotation': array([-0.16320737, 69.99121094, 0.07067837]), + 'Velocity': array([-0.15847667, -0.49819565, 0.00176249]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3427.3076171875, + 'focus_actor_name': 'SM_PlantPot28', + 'focus_actor_pt': array([-9497.30859375, 7723.88525391, 104.04737091]), + 'frame': 21955, + 'frame_number': 21955, + 'framesequence': 88511, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3549974262714386, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.3824231512845, + 'timestamp_carla': 749381, + 'timestamp_device': 1619982, + 'timestamp_stream': 749.3824231512845, + 'transform': [array([-4.92813950e+01, 9.09864502e+01, -8.86926278e-02]), + array([ 0.14221136, -70.61083221, -0.24139477])]} +{'AngularVelocity': array([ 0.00594689, -0.01732728, -1.52499402]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.983076572418213, + 'FR_Wheel_Angle': 4.142681121826172, + 'Location': array([-4.55349541e+01, 8.85454941e+01, 3.24492529e-02]), + 'Rotation': array([-0.16058457, 69.90354919, 0.07063656]), + 'Velocity': array([-0.14630026, -0.45825014, 0.00166337]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3430.182861328125, + 'focus_actor_name': 'SM_PlantPot28', + 'focus_actor_pt': array([-9494.41210938, 7713.07519531, 103.52072906]), + 'frame': 21956, + 'frame_number': 21956, + 'framesequence': 88515, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35534530878067017, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.4145151488483, + 'timestamp_carla': 749414, + 'timestamp_device': 1620015, + 'timestamp_stream': 749.4145151488483, + 'transform': [array([-4.92680016e+01, 9.10289536e+01, -8.83912146e-02]), + array([ 0.1416308 , -70.43823242, -0.24249336])]} +{'AngularVelocity': array([ 1.47876954e-02, 2.17862340e-04, -1.72592449e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9823544025421143, + 'FR_Wheel_Angle': 4.143277168273926, + 'Location': array([-4.55550461e+01, 8.84843216e+01, 3.26531120e-02]), + 'Rotation': array([-0.1607963 , 69.81018829, 0.07120864]), + 'Velocity': array([-0.1468721 , -0.45596921, 0.00177617]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3433.2412109375, + 'focus_actor_name': 'SM_PlantPot28', + 'focus_actor_pt': array([-9491.40234375, 7701.84619141, 103.23680878]), + 'frame': 21957, + 'frame_number': 21957, + 'framesequence': 88519, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3576158881187439, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.449126649648, + 'timestamp_carla': 749448, + 'timestamp_device': 1620049, + 'timestamp_stream': 749.449126649648, + 'transform': [array([-4.92538376e+01, 9.10746918e+01, -8.85501206e-02]), + array([ 0.14129612, -70.25254822, -0.2418831 ])]} +{'AngularVelocity': array([-0.01524434, 0.0027236 , 0.14691405]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.983638048171997, + 'FR_Wheel_Angle': 4.140483856201172, + 'Location': array([-4.55746346e+01, 8.84248199e+01, 3.27920057e-02]), + 'Rotation': array([-0.15958053, 69.73912048, 0.07125451]), + 'Velocity': array([-0.14166108, -0.43988886, 0.00248062]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3436.171142578125, + 'focus_actor_name': 'SM_PlantPot28', + 'focus_actor_pt': array([-9488.59667969, 7691.37451172, 103.16464996]), + 'frame': 21958, + 'frame_number': 21958, + 'framesequence': 88523, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3606555461883545, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.481763549149, + 'timestamp_carla': 749481, + 'timestamp_device': 1620082, + 'timestamp_stream': 749.481763549149, + 'transform': [array([-4.92408257e+01, 9.11186295e+01, -8.78422335e-02]), + array([ 0.14730668, -70.0737915 , -0.24401936])]} +{'AngularVelocity': array([-0.00275 , -0.00161312, 0.20087831]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9824931621551514, + 'FR_Wheel_Angle': 4.143031597137451, + 'Location': array([-4.55956345e+01, 8.83619232e+01, 3.30459476e-02]), + 'Rotation': array([-0.16204622, 69.64821625, 0.07181966]), + 'Velocity': array([-0.15424536, -0.47557947, 0.00184296]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3444.99951171875, + 'focus_actor_name': 'SM_PlantPot28', + 'focus_actor_pt': array([-9490.88964844, 7678.18701172, 103.16414642]), + 'frame': 21959, + 'frame_number': 21959, + 'framesequence': 88527, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3620838224887848, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.5150727517903, + 'timestamp_carla': 749514, + 'timestamp_device': 1620115, + 'timestamp_stream': 749.5150727517903, + 'transform': [array([-4.92277222e+01, 9.11627579e+01, -8.65807906e-02]), + array([ 0.1563157 , -69.89453888, -0.24804783])]} +{'AngularVelocity': array([-0.00060609, 0.00189774, 0.29167628]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9841771125793457, + 'FR_Wheel_Angle': 4.1410627365112305, + 'Location': array([-4.56154442e+01, 8.83024979e+01, 3.32311913e-02]), + 'Rotation': array([-0.16005865, 69.56477356, 0.07191235]), + 'Velocity': array([-0.14478281, -0.44458953, 0.00159979]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3454.9072265625, + 'focus_actor_name': 'SM_PlantPot28', + 'focus_actor_pt': array([-9494.4296875 , 7664.9765625 , 102.99370575]), + 'frame': 21960, + 'frame_number': 21960, + 'framesequence': 88531, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3611316382884979, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.5480756498873, + 'timestamp_carla': 749547, + 'timestamp_device': 1620149, + 'timestamp_stream': 749.5480756498873, + 'transform': [array([-4.92149811e+01, 9.12061081e+01, -8.50496143e-02]), + array([ 0.16611019, -69.71860504, -0.25302225])]} +{'AngularVelocity': array([-0.01856654, -0.00629616, -1.0804199 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.5726633071899414, + 'FR_Wheel_Angle': 2.4194774627685547, + 'Location': array([-4.56362877e+01, 8.82404251e+01, 3.34136859e-02]), + 'Rotation': array([-0.16134273, 69.46609497, 0.07232636]), + 'Velocity': array([-0.15381551, -0.47142729, 0.00123276]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3464.931396484375, + 'focus_actor_name': 'SM_PlantPot28', + 'focus_actor_pt': array([-9497.99609375, 7651.66455078, 102.70899963]), + 'frame': 21961, + 'frame_number': 21961, + 'framesequence': 88535, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3594287037849426, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.5801623500884, + 'timestamp_carla': 749579, + 'timestamp_device': 1620182, + 'timestamp_stream': 749.5801623500884, + 'transform': [array([-4.92027588e+01, 9.12481003e+01, -8.33843127e-02]), + array([ 0.17593883, -69.54849243, -0.25848508])]} +{'AngularVelocity': array([-0.00689746, 0.03119283, -0.00857952]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.6659679412841797, + 'FR_Wheel_Angle': -1.4852803945541382, + 'Location': array([-4.56573219e+01, 8.81809540e+01, 3.36078145e-02]), + 'Rotation': array([-0.16061188, 69.42546844, 0.06965316]), + 'Velocity': array([-0.17095499, -0.45273119, 0.00157277]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3238.62353515625, + 'focus_actor_name': 'BP_StreetLight_simple20', + 'focus_actor_pt': array([-9279.9453125 , 7720.41943359, 103.4107132 ]), + 'frame': 21962, + 'frame_number': 21962, + 'framesequence': 88539, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35884273052215576, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.6155214495957, + 'timestamp_carla': 749615, + 'timestamp_device': 1620215, + 'timestamp_stream': 749.6155214495957, + 'transform': [array([-4.91894684e+01, 9.12937469e+01, -8.15170333e-02]), + array([ 0.18686031, -69.36381531, -0.26471084])]} +{'AngularVelocity': array([-0.01930761, -0.02439252, -0.23099965]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.8057757616043091, + 'FR_Wheel_Angle': 0.8527837991714478, + 'Location': array([-4.56801567e+01, 8.81211929e+01, 3.38030905e-02]), + 'Rotation': array([-0.16113782, 69.44994354, 0.07054148]), + 'Velocity': array([-0.17119914, -0.45659408, 0.00155663]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8214.083984375, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13936.33886719, 5973.15332031, 80.66123962]), + 'frame': 21963, + 'frame_number': 21963, + 'framesequence': 88543, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3596118092536926, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.6469983495772, + 'timestamp_carla': 749646, + 'timestamp_device': 1620249, + 'timestamp_stream': 749.6469983495772, + 'transform': [array([-4.91778069e+01, 9.13359375e+01, -7.95793980e-02]), + array([ 0.19722854, -69.19302368, -0.27115026])]} +{'AngularVelocity': array([0.00823551, 0.00286052, 0.24611689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.3661526143550873, + 'FR_Wheel_Angle': -0.3736667335033417, + 'Location': array([-4.57017517e+01, 8.80627823e+01, 3.39749046e-02]), + 'Rotation': array([-0.15996985, 69.43947601, 0.07200585]), + 'Velocity': array([-0.15953727, -0.42749685, 0.00128249]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8245.17578125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13953.9140625 , 5937.72265625, 79.6295929 ]), + 'frame': 21964, + 'frame_number': 21964, + 'framesequence': 88547, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36027100682258606, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.6809774525464, + 'timestamp_carla': 749680, + 'timestamp_device': 1620282, + 'timestamp_stream': 749.6809774525464, + 'transform': [array([-4.91652336e+01, 9.13806305e+01, -7.76161626e-02]), + array([ 0.20795193, -69.01251221, -0.27771181])]} +{'AngularVelocity': array([ 0.00330795, -0.00670483, 0.56638318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18005479872226715, + 'FR_Wheel_Angle': 0.12181173264980316, + 'Location': array([-4.57239571e+01, 8.80037460e+01, 3.41601446e-02]), + 'Rotation': array([-0.16201891, 69.44179535, 0.07209946]), + 'Velocity': array([-0.17063774, -0.45592353, 0.00123857]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8240.7666015625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13939.0859375 , 5916.60058594, 78.7305603 ]), + 'frame': 21965, + 'frame_number': 21965, + 'framesequence': 88551, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3601977527141571, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.7150654494762, + 'timestamp_carla': 749714, + 'timestamp_device': 1620315, + 'timestamp_stream': 749.7150654494762, + 'transform': [array([-4.91528549e+01, 9.14248428e+01, -7.57422894e-02]), + array([ 0.2181699 , -68.83410645, -0.28393763])]} +{'AngularVelocity': array([ 0.01466596, -0.00514848, -0.02774017]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04062283784151077, + 'FR_Wheel_Angle': 0.030471470206975937, + 'Location': array([-4.57493439e+01, 8.79360657e+01, 3.43864709e-02]), + 'Rotation': array([-0.16427287, 69.43582916, 0.07232539]), + 'Velocity': array([-0.19209054, -0.51118863, 0.00123767]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8258.0869140625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13943.83496094, 5886.46777344, 77.71005249]), + 'frame': 21966, + 'frame_number': 21966, + 'framesequence': 88555, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36003297567367554, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.7468644492328, + 'timestamp_carla': 749746, + 'timestamp_device': 1620349, + 'timestamp_stream': 749.7468644492328, + 'transform': [array([-4.91414719e+01, 9.14674454e+01, -7.37914741e-02]), + array([ 0.22832638, -68.66212463, -0.29043806])]} +{'AngularVelocity': array([ 0.01740709, -0.00611283, -0.13273066]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02286357432603836, + 'FR_Wheel_Angle': -0.016517052426934242, + 'Location': array([-4.57734718e+01, 8.78717880e+01, 3.45831960e-02]), + 'Rotation': array([-0.1608851 , 69.43209076, 0.07251011]), + 'Velocity': array([-0.17746696, -0.47286233, 0.00149734]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8302.0185546875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13973.40722656, 5846.93652344, 76.60162354]), + 'frame': 21967, + 'frame_number': 21967, + 'framesequence': 88559, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.7812918499112, + 'timestamp_carla': 749780, + 'timestamp_device': 1620382, + 'timestamp_stream': 749.7812918499112, + 'transform': [array([-4.91292267e+01, 9.15127029e+01, -7.16626048e-02]), + array([ 0.23699389, -68.47980499, -0.29785407])]} +{'AngularVelocity': array([ 0.00234239, 0.00075944, -0.04622196]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016522711142897606, + 'FR_Wheel_Angle': -0.01651812717318535, + 'Location': array([-4.57964058e+01, 8.78106308e+01, 3.47516164e-02]), + 'Rotation': array([-0.15932782, 69.4330368 , 0.07256892]), + 'Velocity': array([-0.16805904, -0.4477106 , 0.00081157]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8296.919921875, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13957.59960938, 5825.88476562, 75.69487 ]), + 'frame': 21968, + 'frame_number': 21968, + 'framesequence': 88563, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.814374152571, + 'timestamp_carla': 749813, + 'timestamp_device': 1620415, + 'timestamp_stream': 749.814374152571, + 'transform': [array([-4.91178589e+01, 9.15569229e+01, -6.90978095e-02]), + array([ 0.24107835, -68.30169678, -0.30737585])]} +{'AngularVelocity': array([-0.00201446, 0.00106406, -0.13372019]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016520990058779716, + 'FR_Wheel_Angle': -0.01651613786816597, + 'Location': array([-4.58184814e+01, 8.77519150e+01, 3.49467359e-02]), + 'Rotation': array([-0.15960786, 69.43164825, 0.07255893]), + 'Velocity': array([-0.16471845, -0.43821776, 0.00159385]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8291.4453125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13940.68261719, 5803.66210938, 74.65940857]), + 'frame': 21969, + 'frame_number': 21969, + 'framesequence': 88567, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.8479699492455, + 'timestamp_carla': 749847, + 'timestamp_device': 1620449, + 'timestamp_stream': 749.8479699492455, + 'transform': [array([-4.91064644e+01, 9.16009903e+01, -6.64163381e-02]), + array([ 0.24258098, -68.12438202, -0.31759927])]} +{'AngularVelocity': array([ 0.03780485, -0.00812699, 0.6403417 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016513610258698463, + 'FR_Wheel_Angle': -0.01650777831673622, + 'Location': array([-4.58407249e+01, 8.76925659e+01, 3.51266749e-02]), + 'Rotation': array([-0.16012011, 69.43516541, 0.07258702]), + 'Velocity': array([-0.15726519, -0.41802537, 0.00079763]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8294.3203125, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13931.77929688, 5778.96582031, 73.28565979]), + 'frame': 21970, + 'frame_number': 21970, + 'framesequence': 88571, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.880331851542, + 'timestamp_carla': 749879, + 'timestamp_device': 1620482, + 'timestamp_stream': 749.880331851542, + 'transform': [array([-4.90955086e+01, 9.16453476e+01, -6.43052384e-02]), + array([ 0.23876974, -67.94587708, -0.3261137 ])]} +{'AngularVelocity': array([5.06322773e-04, 2.92628491e-03, 5.74756145e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016513418406248093, + 'FR_Wheel_Angle': -0.016514403745532036, + 'Location': array([-4.58645210e+01, 8.76292496e+01, 3.53457145e-02]), + 'Rotation': array([-0.16231944, 69.4310379 , 0.07257342]), + 'Velocity': array([-0.18019427, -0.47922882, 0.00118324]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8323.6640625, + 'focus_actor_name': 'BP_RepSpline89_2', + 'focus_actor_pt': array([-13947.38867188, 5744.53222656, 71.66860962]), + 'frame': 21971, + 'frame_number': 21971, + 'framesequence': 88575, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.9140516519547, + 'timestamp_carla': 749913, + 'timestamp_device': 1620515, + 'timestamp_stream': 749.9140516519547, + 'transform': [array([-4.90841217e+01, 9.16906738e+01, -6.28062487e-02]), + array([ 0.23155706, -67.76387024, -0.33258328])]} +{'AngularVelocity': array([ 0.03059334, -0.01165246, -0.11801663]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016520099714398384, + 'FR_Wheel_Angle': -0.030495986342430115, + 'Location': array([-4.58874664e+01, 8.75681000e+01, 3.55114266e-02]), + 'Rotation': array([-0.1599357 , 69.43057251, 0.07261589]), + 'Velocity': array([-0.16136588, -0.42996436, 0.00074122]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2873.444091796875, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8884.3203125 , 7767.36572266, 101.47869873]), + 'frame': 21972, + 'frame_number': 21972, + 'framesequence': 88579, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.9472012519836, + 'timestamp_carla': 749946, + 'timestamp_device': 1620548, + 'timestamp_stream': 749.9472012519836, + 'transform': [array([-4.90731735e+01, 9.17348022e+01, -6.16604313e-02]), + array([ 0.22347695, -67.58667755, -0.33774063])]} +{'AngularVelocity': array([ 0.02227061, -0.00074698, 0.23864824]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6286683082580566, + 'FR_Wheel_Angle': -4.923964977264404, + 'Location': array([-4.59097786e+01, 8.75093079e+01, 3.57042588e-02]), + 'Rotation': array([-0.15988106, 69.44181824, 0.0716778 ]), + 'Velocity': array([-0.16543593, -0.42273688, 0.00085876]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2863.587158203125, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8869.60351562, 7762.98974609, 101.23550415]), + 'frame': 21973, + 'frame_number': 21973, + 'framesequence': 88583, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2896620035171509, + 'timestamp': 749.9801808521152, + 'timestamp_carla': 749979, + 'timestamp_device': 1620582, + 'timestamp_stream': 749.9801808521152, + 'transform': [array([-4.90625000e+01, 9.17784805e+01, -6.06490895e-02]), + array([ 0.21520559, -67.41149139, -0.34240967])]} +{'AngularVelocity': array([-0.02070235, -0.00901371, 1.00598037]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.793789386749268, + 'FR_Wheel_Angle': -3.8601396083831787, + 'Location': array([-4.59337158e+01, 8.74517288e+01, 3.59116644e-02]), + 'Rotation': array([-1.61438346e-01, 6.95465775e+01, 6.88983724e-02]), + 'Velocity': array([-0.19498388, -0.44918418, 0.00125443]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2853.93994140625, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8855.2265625 , 7758.81884766, 101.05660248]), + 'frame': 21974, + 'frame_number': 21974, + 'framesequence': 88587, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2856946587562561, + 'timestamp': 750.0135488510132, + 'timestamp_carla': 750013, + 'timestamp_device': 1620615, + 'timestamp_stream': 750.0135488510132, + 'transform': [array([-4.90518951e+01, 9.18224716e+01, -5.96707314e-02]), + array([ 0.20690691, -67.23510742, -0.34698707])]} +{'AngularVelocity': array([ 0.00850492, -0.02204444, 0.82701844]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.704451560974121, + 'FR_Wheel_Angle': -3.976687431335449, + 'Location': array([-4.59580498e+01, 8.73925400e+01, 3.60962972e-02]), + 'Rotation': array([-0.16116513, 69.6311264 , 0.07182082]), + 'Velocity': array([-0.17805293, -0.43523493, 0.00152248]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2849.281982421875, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8845.51660156, 7752.89111328, 100.87257385]), + 'frame': 21975, + 'frame_number': 21975, + 'framesequence': 88591, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.27775996923446655, + 'timestamp': 750.0475080497563, + 'timestamp_carla': 750046, + 'timestamp_device': 1620648, + 'timestamp_stream': 750.0475080497563, + 'transform': [array([-4.90412636e+01, 9.18680954e+01, -5.86153492e-02]), + array([ 0.1987585 , -67.05210114, -0.35190031])]} +{'AngularVelocity': array([-0.02685206, 0.02661257, 0.60690498]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.324817657470703, + 'FR_Wheel_Angle': -3.961413860321045, + 'Location': array([-4.59824562e+01, 8.73327026e+01, 3.62699404e-02]), + 'Rotation': array([-0.16177303, 69.72293854, 0.07116954]), + 'Velocity': array([-0.19665806, -0.46656173, 0.00200969]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2847.914794921875, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8838.79101562, 7745.68066406, 100.67306519]), + 'frame': 21976, + 'frame_number': 21976, + 'framesequence': 88595, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.27775996923446655, + 'timestamp': 750.079795949161, + 'timestamp_carla': 750079, + 'timestamp_device': 1620682, + 'timestamp_stream': 750.079795949161, + 'transform': [array([-4.90312080e+01, 9.19111023e+01, -5.76096326e-02]), + array([ 0.19088328, -66.87989807, -0.3565388 ])]} +{'AngularVelocity': array([0.01028519, 0.00607721, 0.90615046]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.168699264526367, + 'FR_Wheel_Angle': -4.069521427154541, + 'Location': array([-4.60076256e+01, 8.72709045e+01, 3.64751332e-02]), + 'Rotation': array([-0.16201891, 69.81664276, 0.07139555]), + 'Velocity': array([-0.19087549, -0.45701128, 0.0011387 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2846.52783203125, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8831.84570312, 7738.20800781, 100.45661926]), + 'frame': 21977, + 'frame_number': 21977, + 'framesequence': 88599, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.27775996923446655, + 'timestamp': 750.1152165494859, + 'timestamp_carla': 750114, + 'timestamp_device': 1620715, + 'timestamp_stream': 750.1152165494859, + 'transform': [array([-4.90203552e+01, 9.19577103e+01, -5.66005893e-02]), + array([ 0.18252313, -66.69347382, -0.36133 ])]} +{'AngularVelocity': array([-0.01130107, -0.00581069, -0.74905497]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.132653713226318, + 'FR_Wheel_Angle': -4.008565902709961, + 'Location': array([-4.60320358e+01, 8.72109756e+01, 3.66660953e-02]), + 'Rotation': array([-0.16204622, 69.89260101, 0.07118894]), + 'Velocity': array([-0.19259483, -0.46626386, 0.00141805]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2845.27392578125, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8825.31640625, 7731.18603516, 100.25363159]), + 'frame': 21978, + 'frame_number': 21978, + 'framesequence': 88603, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.27775996923446655, + 'timestamp': 750.1487361490726, + 'timestamp_carla': 750148, + 'timestamp_device': 1620748, + 'timestamp_stream': 750.1487361490726, + 'transform': [array([-4.90103455e+01, 9.20028076e+01, -5.48035428e-02]), + array([ 0.17944272, -66.51283264, -0.36862361])]} +{'AngularVelocity': array([-0.00158243, -0.00659565, -0.16750804]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.176965713500977, + 'FR_Wheel_Angle': -4.014955997467041, + 'Location': array([-4.60569000e+01, 8.71492462e+01, 3.68573293e-02]), + 'Rotation': array([-0.16146566, 69.97671509, 0.07124668]), + 'Velocity': array([-0.18514416, -0.45248473, 0.00152337]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2846.79345703125, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8820.85742188, 7722.47216797, 100.02403259]), + 'frame': 21979, + 'frame_number': 21979, + 'framesequence': 88607, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.27775996923446655, + 'timestamp': 750.1800176501274, + 'timestamp_carla': 750179, + 'timestamp_device': 1620782, + 'timestamp_stream': 750.1800176501274, + 'transform': [array([-4.90010834e+01, 9.20446625e+01, -5.24411201e-02]), + array([ 0.18005061, -66.34558105, -0.37768739])]} +{'AngularVelocity': array([-0.00993764, 0.00289691, -0.56113333]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.173983573913574, + 'FR_Wheel_Angle': -4.012641906738281, + 'Location': array([-4.60806236e+01, 8.70902252e+01, 3.70381437e-02]), + 'Rotation': array([-0.16134273, 70.06290436, 0.07079274]), + 'Velocity': array([-0.18587326, -0.45128879, 0.00119836]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2850.903564453125, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8818.97167969, 7712.98535156, 99.65584564]), + 'frame': 21980, + 'frame_number': 21980, + 'framesequence': 88611, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.27775996923446655, + 'timestamp': 750.2140007503331, + 'timestamp_carla': 750213, + 'timestamp_device': 1620815, + 'timestamp_stream': 750.2140007503331, + 'transform': [array([-4.89911766e+01, 9.20894623e+01, -4.96539101e-02]), + array([ 0.18191525, -66.16668701, -0.38833809])]} +{'AngularVelocity': array([ 0.02174519, -0.01100273, 0.54096502]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.175801753997803, + 'FR_Wheel_Angle': -4.0141448974609375, + 'Location': array([-4.61056061e+01, 8.70276413e+01, 3.72483730e-02]), + 'Rotation': array([-0.1623809 , 70.1629715 , 0.07065456]), + 'Velocity': array([-0.1858426 , -0.45602611, 0.00160555]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2854.944091796875, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8817.40234375, 7704.11181641, 99.20114136]), + 'frame': 21981, + 'frame_number': 21981, + 'framesequence': 88615, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.27775996923446655, + 'timestamp': 750.2475717514753, + 'timestamp_carla': 750247, + 'timestamp_device': 1620848, + 'timestamp_stream': 750.2475717514753, + 'transform': [array([-4.89815178e+01, 9.21339493e+01, -4.70678881e-02]), + array([ 0.18844491, -65.9890213 , -0.3976768 ])]} +{'AngularVelocity': array([ 0.01195368, -0.00185321, 0.54700214]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.179170608520508, + 'FR_Wheel_Angle': -4.017364501953125, + 'Location': array([-4.61291084e+01, 8.69685059e+01, 3.74223590e-02]), + 'Rotation': array([-0.16055726, 70.2516098 , 0.07058652]), + 'Velocity': array([-0.17379175, -0.42720711, 0.00141578]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2859.39697265625, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8815.79980469, 7694.56152344, 98.66414642]), + 'frame': 21982, + 'frame_number': 21982, + 'framesequence': 88619, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.2800774499774, + 'timestamp_carla': 750279, + 'timestamp_device': 1620882, + 'timestamp_stream': 750.2800774499774, + 'transform': [array([-4.89721870e+01, 9.21762695e+01, -4.49531749e-02]), + array([ 0.19707827, -65.82039642, -0.40490961])]} +{'AngularVelocity': array([-0.02260945, 0.0220819 , 0.94293833]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.17802619934082, + 'FR_Wheel_Angle': -4.014838695526123, + 'Location': array([-4.61518478e+01, 8.69110794e+01, 3.75975706e-02]), + 'Rotation': array([-1.61199287e-01, 7.03412018e+01, 7.00821951e-02]), + 'Velocity': array([-0.17893764, -0.43907955, 0.00137311]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2866.428955078125, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8816.56152344, 7684.01269531, 98.16784668]), + 'frame': 21983, + 'frame_number': 21983, + 'framesequence': 88623, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.3140605501831, + 'timestamp_carla': 750313, + 'timestamp_device': 1620915, + 'timestamp_stream': 750.3140605501831, + 'transform': [array([-4.89625816e+01, 9.22198792e+01, -4.30095941e-02]), + array([ 0.20683861, -65.64678955, -0.41141021])]} +{'AngularVelocity': array([-0.02589308, 0.0178101 , 2.18183279]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.9221978187561035, + 'FR_Wheel_Angle': -6.848483562469482, + 'Location': array([-4.61773224e+01, 8.68465500e+01, 3.78041342e-02]), + 'Rotation': array([-1.63507894e-01, 7.04373169e+01, 6.96280375e-02]), + 'Velocity': array([-0.19178565, -0.47634086, 0.00147059]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2876.56591796875, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8820.375 , 7672.57470703, 97.74714661]), + 'frame': 21984, + 'frame_number': 21984, + 'framesequence': 88626, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.3463157489896, + 'timestamp_carla': 750345, + 'timestamp_device': 1620940, + 'timestamp_stream': 750.3463157489896, + 'transform': [array([-4.89537697e+01, 9.22622375e+01, -4.11282927e-02]), + array([ 0.21676287, -65.47801208, -0.41763607])]} +{'AngularVelocity': array([0.00419003, 0.02487925, 1.51872122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.8412446975708, + 'FR_Wheel_Angle': -8.357890129089355, + 'Location': array([-4.62031288e+01, 8.67848740e+01, 3.80288959e-02]), + 'Rotation': array([-1.64177254e-01, 7.06014862e+01, 6.56620115e-02]), + 'Velocity': array([-0.2181263 , -0.47477537, 0.00203045]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2887.000244140625, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8824.23828125, 7660.76074219, 97.35531616]), + 'frame': 21985, + 'frame_number': 21985, + 'framesequence': 88631, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.3799153491855, + 'timestamp_carla': 750379, + 'timestamp_device': 1620982, + 'timestamp_stream': 750.3799153491855, + 'transform': [array([-4.89445953e+01, 9.23052597e+01, -3.93365845e-02]), + array([ 0.22667347, -65.30692291, -0.42355666])]} +{'AngularVelocity': array([ 0.01446838, -0.03846697, 1.26623023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.450173377990723, + 'FR_Wheel_Angle': -7.26980447769165, + 'Location': array([-4.62303352e+01, 8.67219009e+01, 3.82046774e-02]), + 'Rotation': array([-1.62777066e-01, 7.07907944e+01, 6.79879859e-02]), + 'Velocity': array([-0.1956408 , -0.44971126, 0.00127692]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2903.4345703125, + 'focus_actor_name': 'SM_PlantPot27', + 'focus_actor_pt': array([-8833.70800781, 7646.62109375, 96.9308548 ]), + 'frame': 21986, + 'frame_number': 21986, + 'framesequence': 88635, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.4137044511735, + 'timestamp_carla': 750413, + 'timestamp_device': 1621015, + 'timestamp_stream': 750.4137044511735, + 'transform': [array([-4.89356537e+01, 9.23490906e+01, -3.75130847e-02]), + array([ 0.23678215, -65.13262939, -0.42959958])]} +{'AngularVelocity': array([ 0.00827231, -0.00163933, 1.40852427]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.716187477111816, + 'FR_Wheel_Angle': -7.880643844604492, + 'Location': array([-4.62556953e+01, 8.66611633e+01, 3.84029299e-02]), + 'Rotation': array([-1.62599474e-01, 7.09623184e+01, 6.79058135e-02]), + 'Velocity': array([-0.19745548, -0.45011505, 0.0015375 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4010.24267578125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9833.63183594, 7176.78808594, 88.45586395]), + 'frame': 21987, + 'frame_number': 21987, + 'framesequence': 88639, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.4466492496431, + 'timestamp_carla': 750446, + 'timestamp_device': 1621048, + 'timestamp_stream': 750.4466492496431, + 'transform': [array([-4.89271622e+01, 9.23920212e+01, -3.57269943e-02]), + array([ 0.24646053, -64.96187592, -0.43552041])]} +{'AngularVelocity': array([-2.87362258e-03, 6.97599724e-04, 1.29818678e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.180255889892578, + 'FR_Wheel_Angle': -7.683283805847168, + 'Location': array([-4.62816887e+01, 8.65990677e+01, 3.86036970e-02]), + 'Rotation': array([-1.63118571e-01, 7.11472855e+01, 6.76263794e-02]), + 'Velocity': array([-0.20063356, -0.46314371, 0.00187218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3984.975830078125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9803.55859375, 7176.78808594, 88.22891998]), + 'frame': 21988, + 'frame_number': 21988, + 'framesequence': 88643, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35801875591278076, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.4813747517765, + 'timestamp_carla': 750480, + 'timestamp_device': 1621082, + 'timestamp_stream': 750.4813747517765, + 'transform': [array([-4.89183922e+01, 9.24377518e+01, -3.33601646e-02]), + array([ 0.25252575, -64.78014374, -0.44415706])]} +{'AngularVelocity': array([ 1.27886923e-03, -1.19177601e-03, 1.67377508e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.31474781036377, + 'FR_Wheel_Angle': -7.669873237609863, + 'Location': array([-4.63073807e+01, 8.65369186e+01, 3.87988165e-02]), + 'Rotation': array([-1.63637668e-01, 7.13280258e+01, 6.70368448e-02]), + 'Velocity': array([-0.20173012, -0.4681558 , 0.00157899]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3960.5859375, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9774.47167969, 7176.78808594, 88.01019287]), + 'frame': 21989, + 'frame_number': 21989, + 'framesequence': 88647, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3438642621040344, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.5143298506737, + 'timestamp_carla': 750513, + 'timestamp_device': 1621115, + 'timestamp_stream': 750.5143298506737, + 'transform': [array([-4.89099388e+01, 9.24797440e+01, -3.08541283e-02]), + array([ 0.25481385, -64.61444092, -0.45361787])]} +{'AngularVelocity': array([-0.01244528, -0.00674153, 1.12091792]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.33265209197998, + 'FR_Wheel_Angle': -7.71542501449585, + 'Location': array([-4.63337059e+01, 8.64726181e+01, 3.90127450e-02]), + 'Rotation': array([-1.65645733e-01, 7.15105133e+01, 6.63212240e-02]), + 'Velocity': array([-0.21498616, -0.5097872 , 0.00196223]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3935.002197265625, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9743.8984375 , 7176.78808594, 87.62571716]), + 'frame': 21990, + 'frame_number': 21990, + 'framesequence': 88651, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.32117679715156555, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.5464567504823, + 'timestamp_carla': 750545, + 'timestamp_device': 1621148, + 'timestamp_stream': 750.5464567504823, + 'transform': [array([-4.89011803e+01, 9.25197601e+01, -2.87966523e-02]), + array([ 0.25163782, -64.45841217, -0.46185759])]} +{'AngularVelocity': array([ 0.00183888, -0.02173059, 1.17368639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.33638858795166, + 'FR_Wheel_Angle': -7.717239856719971, + 'Location': array([-4.63608284e+01, 8.64062347e+01, 3.91979106e-02]), + 'Rotation': array([-1.64033815e-01, 7.17070541e+01, 6.60618693e-02]), + 'Velocity': array([-0.20393325, -0.4853031 , 0.00133763]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3912.0712890625, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9716.35351562, 7176.78808594, 87.18028259]), + 'frame': 21991, + 'frame_number': 21991, + 'framesequence': 88655, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29894712567329407, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.5815025493503, + 'timestamp_carla': 750580, + 'timestamp_device': 1621182, + 'timestamp_stream': 750.5815025493503, + 'transform': [array([-4.88908195e+01, 9.25599213e+01, -2.73526758e-02]), + array([ 0.24367382, -64.30484772, -0.46823537])]} +{'AngularVelocity': array([ 0.00499238, -0.02389449, 0.86707729]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.339317321777344, + 'FR_Wheel_Angle': -7.721981048583984, + 'Location': array([-4.63863335e+01, 8.63432083e+01, 3.94022651e-02]), + 'Rotation': array([-1.62872687e-01, 7.18935852e+01, 6.60146326e-02]), + 'Velocity': array([-0.19193144, -0.46193922, 0.00155986]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3890.8662109375, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9690.69628906, 7176.78808594, 86.81298065]), + 'frame': 21992, + 'frame_number': 21992, + 'framesequence': 88659, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.277651309967041, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.6145420521498, + 'timestamp_carla': 750613, + 'timestamp_device': 1621215, + 'timestamp_stream': 750.6145420521498, + 'transform': [array([-4.88807106e+01, 9.25965424e+01, -2.62495130e-02]), + array([ 0.23487653, -64.16682434, -0.4733012 ])]} +{'AngularVelocity': array([ 0.0110677 , -0.03493537, 1.02034307]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.338714599609375, + 'FR_Wheel_Angle': -7.721524238586426, + 'Location': array([-4.64102631e+01, 8.62834778e+01, 3.95712554e-02]), + 'Rotation': array([-1.61588609e-01, 7.20705414e+01, 6.59202486e-02]), + 'Velocity': array([-0.17227052, -0.42081934, 0.00122005]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3870.427001953125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9665.66601562, 7176.78857422, 86.57001495]), + 'frame': 21993, + 'frame_number': 21993, + 'framesequence': 88663, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.27530747652053833, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.6463784500957, + 'timestamp_carla': 750645, + 'timestamp_device': 1621248, + 'timestamp_stream': 750.6463784500957, + 'transform': [array([-4.88708572e+01, 9.26313782e+01, -2.52648350e-02]), + array([ 0.22670762, -64.03655243, -0.47784802])]} +{'AngularVelocity': array([-0.00838744, -0.00730973, 1.70797193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.343317031860352, + 'FR_Wheel_Angle': -7.723252296447754, + 'Location': array([-4.64341011e+01, 8.62232590e+01, 3.97666842e-02]), + 'Rotation': array([-1.63084418e-01, 7.22502518e+01, 6.48662522e-02]), + 'Velocity': array([-0.17960975, -0.43866107, 0.00131228]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3852.3984375, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9643.40722656, 7176.78808594, 86.39915466]), + 'frame': 21994, + 'frame_number': 21994, + 'framesequence': 88667, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2839869558811188, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.6798194497824, + 'timestamp_carla': 750679, + 'timestamp_device': 1621282, + 'timestamp_stream': 750.6798194497824, + 'transform': [array([-4.88606644e+01, 9.26683273e+01, -2.42684837e-02]), + array([ 0.21913978, -63.89812469, -0.48245588])]} +{'AngularVelocity': array([ 6.57667464e-04, -2.53813546e-02, 1.21655166e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.355622291564941, + 'FR_Wheel_Angle': -8.282099723815918, + 'Location': array([-4.64568748e+01, 8.61654205e+01, 3.99476513e-02]), + 'Rotation': array([-1.63084418e-01, 7.24166412e+01, 6.45092875e-02]), + 'Velocity': array([-0.16962977, -0.4212276 , 0.00090809]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3835.6376953125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9622.60546875, 7176.78808594, 86.25378418]), + 'frame': 21995, + 'frame_number': 21995, + 'framesequence': 88671, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29636526107788086, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.713654551655, + 'timestamp_carla': 750713, + 'timestamp_device': 1621315, + 'timestamp_stream': 750.713654551655, + 'transform': [array([-4.88508835e+01, 9.27064056e+01, -2.33140849e-02]), + array([ 0.21205688, -63.7543602 , -0.48685032])]} +{'AngularVelocity': array([0.01381588, 0.05509528, 1.65652072]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.37851619720459, + 'FR_Wheel_Angle': -12.544525146484375, + 'Location': array([-4.64782982e+01, 8.61119537e+01, 4.01072577e-02]), + 'Rotation': array([-1.62626788e-01, 7.25978317e+01, 6.22477345e-02]), + 'Velocity': array([-0.1781204 , -0.394916 , 0.00161315]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3818.011474609375, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9600.70410156, 7176.78808594, 86.11235809]), + 'frame': 21996, + 'frame_number': 21996, + 'framesequence': 88675, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30773645639419556, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.7469948492944, + 'timestamp_carla': 750746, + 'timestamp_device': 1621348, + 'timestamp_stream': 750.7469948492944, + 'transform': [array([-4.88408470e+01, 9.27464447e+01, -2.18836684e-02]), + array([ 0.20556135, -63.60253906, -0.49313679])]} +{'AngularVelocity': array([-0.02171632, 0.03133357, 2.36374712]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.260112762451172, + 'FR_Wheel_Angle': -10.437713623046875, + 'Location': array([-4.65031471e+01, 8.60543213e+01, 4.03448008e-02]), + 'Rotation': array([-1.68152422e-01, 7.28659973e+01, 5.83512709e-02]), + 'Velocity': array([-0.22577628, -0.48252556, 0.00192121]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3799.857666015625, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9578.1875 , 7176.78808594, 85.99092102]), + 'frame': 21997, + 'frame_number': 21997, + 'framesequence': 88679, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.31183815002441406, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.7806803509593, + 'timestamp_carla': 750780, + 'timestamp_device': 1621382, + 'timestamp_stream': 750.7806803509593, + 'transform': [array([-4.88306618e+01, 9.27905273e+01, -2.03247629e-02]), + array([ 0.19847846, -63.43429184, -0.50000298])]} +{'AngularVelocity': array([0.02962509, 0.01728306, 2.2188108 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.491649627685547, + 'FR_Wheel_Angle': -11.4806547164917, + 'Location': array([-4.65297432e+01, 8.59902115e+01, 4.05393504e-02]), + 'Rotation': array([-1.66841015e-01, 7.31368256e+01, 6.11365475e-02]), + 'Velocity': array([-0.20634633, -0.46313593, 0.00152972]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3780.870849609375, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9554.61621094, 7176.78808594, 85.75653076]), + 'frame': 21998, + 'frame_number': 21998, + 'framesequence': 88683, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3085421323776245, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.8133378513157, + 'timestamp_carla': 750812, + 'timestamp_device': 1621415, + 'timestamp_stream': 750.8133378513157, + 'transform': [array([-4.88210335e+01, 9.28330383e+01, -1.91198066e-02]), + array([ 0.1913614 , -63.271698 , -0.50537395])]} +{'AngularVelocity': array([0.00906829, 0.02995977, 2.2897501 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.464859008789062, + 'FR_Wheel_Angle': -10.999679565429688, + 'Location': array([-4.65545692e+01, 8.59300690e+01, 4.07076143e-02]), + 'Rotation': array([-1.64764643e-01, 7.34051208e+01, 6.07425645e-02]), + 'Velocity': array([-0.19865233, -0.44321868, 0.00142094]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3760.04541015625, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9528.79394531, 7176.78857422, 85.50511169]), + 'frame': 21999, + 'frame_number': 21999, + 'framesequence': 88687, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3024628460407257, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.8473600521684, + 'timestamp_carla': 750846, + 'timestamp_device': 1621448, + 'timestamp_stream': 750.8473600521684, + 'transform': [array([-4.88110924e+01, 9.28765640e+01, -1.76833346e-02]), + array([ 0.18548061, -63.10583496, -0.51153845])]} +{'AngularVelocity': array([0.00894175, 0.03159941, 2.21707678]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.582680702209473, + 'FR_Wheel_Angle': -11.207111358642578, + 'Location': array([-4.65783539e+01, 8.58716583e+01, 4.08672243e-02]), + 'Rotation': array([-1.64177254e-01, 7.36558990e+01, 6.06733337e-02]), + 'Velocity': array([-0.18630357, -0.42209914, 0.0021258 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3740.171142578125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9504.09960938, 7176.78808594, 85.34837341]), + 'frame': 22000, + 'frame_number': 22000, + 'framesequence': 88691, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2968047261238098, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.8797753490508, + 'timestamp_carla': 750879, + 'timestamp_device': 1621482, + 'timestamp_stream': 750.8797753490508, + 'transform': [array([-4.88015404e+01, 9.29172440e+01, -1.66061111e-02]), + array([ 0.17763954, -62.95154953, -0.51642096])]} +{'AngularVelocity': array([0.01232883, 0.03295698, 2.21822882]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.499489784240723, + 'FR_Wheel_Angle': -11.179977416992188, + 'Location': array([-4.66013947e+01, 8.58141937e+01, 4.10714224e-02]), + 'Rotation': array([-1.65413514e-01, 7.39073868e+01, 5.96958883e-02]), + 'Velocity': array([-0.186892 , -0.42884067, 0.00125226]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3720.202392578125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9479.18261719, 7176.78857422, 85.14430237]), + 'frame': 22001, + 'frame_number': 22001, + 'framesequence': 88695, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2945341467857361, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.9130886495113, + 'timestamp_carla': 750912, + 'timestamp_device': 1621515, + 'timestamp_stream': 750.9130886495113, + 'transform': [array([-4.87916832e+01, 9.29581604e+01, -1.62175652e-02]), + array([ 0.17290623, -62.79709625, -0.51831293])]} +{'AngularVelocity': array([0.01309619, 0.03456488, 2.06346154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.504417419433594, + 'FR_Wheel_Angle': -11.171282768249512, + 'Location': array([-4.66253929e+01, 8.57535858e+01, 4.12656292e-02]), + 'Rotation': array([-1.67080075e-01, 7.41681747e+01, 5.83560057e-02]), + 'Velocity': array([-0.19588335, -0.45476902, 0.00142674]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3701.905517578125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9456.234375 , 7176.78857422, 85.01307678]), + 'frame': 22002, + 'frame_number': 22002, + 'framesequence': 88699, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2962004542350769, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.9473334513605, + 'timestamp_carla': 750946, + 'timestamp_device': 1621548, + 'timestamp_stream': 750.9473334513605, + 'transform': [array([-4.87816010e+01, 9.29997253e+01, -1.63283627e-02]), + array([ 0.17076838, -62.64040756, -0.51803821])]} +{'AngularVelocity': array([0.01649787, 0.03447116, 1.94735038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.506321907043457, + 'FR_Wheel_Angle': -11.175305366516113, + 'Location': array([-4.66485634e+01, 8.56944046e+01, 4.14464474e-02]), + 'Rotation': array([-1.65953100e-01, 7.44222565e+01, 5.81487529e-02]), + 'Velocity': array([-0.18519601, -0.43400508, 0.00128356]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3683.8720703125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9433.49023438, 7176.7890625 , 85.06503296]), + 'frame': 22003, + 'frame_number': 22003, + 'framesequence': 88703, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299203485250473, + 'throttle_input': 0.2737926244735718, + 'timestamp': 750.9805886521935, + 'timestamp_carla': 750980, + 'timestamp_device': 1621582, + 'timestamp_stream': 750.9805886521935, + 'transform': [array([-4.87720604e+01, 9.30402603e+01, -1.66304484e-02]), + array([ 0.16972336, -62.48731232, -0.51690894])]} +{'AngularVelocity': array([0.00568388, 0.0373457 , 2.15144968]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.510361671447754, + 'FR_Wheel_Angle': -11.1776123046875, + 'Location': array([-4.66709671e+01, 8.56365128e+01, 4.16231044e-02]), + 'Rotation': array([-1.65864304e-01, 7.46716690e+01, 5.72608486e-02]), + 'Velocity': array([-0.18132859, -0.42875195, 0.00122316]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3665.82666015625, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9410.64257812, 7176.7890625 , 85.24887085]), + 'frame': 22004, + 'frame_number': 22004, + 'framesequence': 88707, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3016205430030823, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.0148567520082, + 'timestamp_carla': 751014, + 'timestamp_device': 1621615, + 'timestamp_stream': 751.0148567520082, + 'transform': [array([-4.87624893e+01, 9.30820389e+01, -1.70839597e-02]), + array([ 0.16881494, -62.32939148, -0.51523048])]} +{'AngularVelocity': array([-0.02534038, 0.02083674, 0.98675096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.497885704040527, + 'FR_Wheel_Angle': -11.167945861816406, + 'Location': array([-4.66933327e+01, 8.55777817e+01, 4.18090709e-02]), + 'Rotation': array([-1.68090940e-01, 7.49152756e+01, 5.62521480e-02]), + 'Velocity': array([-0.18932059, -0.46990716, 0.0014288 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3648.401611328125, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9388.54296875, 7176.78857422, 85.47786713]), + 'frame': 22005, + 'frame_number': 22005, + 'framesequence': 88711, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3016205430030823, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.0477509498596, + 'timestamp_carla': 751047, + 'timestamp_device': 1621648, + 'timestamp_stream': 751.0477509498596, + 'transform': [array([-4.87534981e+01, 9.31221848e+01, -1.74980443e-02]), + array([ 0.1680568 , -62.17754364, -0.51367396])]} +{'AngularVelocity': array([ 0.0178293 , -0.01549663, 0.72751778]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.505290985107422, + 'FR_Wheel_Angle': -11.171538352966309, + 'Location': array([-4.67160835e+01, 8.55170746e+01, 4.20240685e-02]), + 'Rotation': array([-1.67694792e-01, 7.51758347e+01, 5.56138419e-02]), + 'Velocity': array([-0.17881811, -0.44808498, 0.00130214]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3630.6416015625, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9365.97558594, 7176.78857422, 85.74105072]), + 'frame': 22006, + 'frame_number': 22006, + 'framesequence': 88715, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.300283819437027, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.0803726501763, + 'timestamp_carla': 751079, + 'timestamp_device': 1621682, + 'timestamp_stream': 751.0803726501763, + 'transform': [array([-4.87447052e+01, 9.31618042e+01, -1.79301538e-02]), + array([ 0.16701178, -62.02796173, -0.51208699])]} +{'AngularVelocity': array([0.00158954, 0.00793029, 0.74295998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.416728973388672, + 'FR_Wheel_Angle': -13.942595481872559, + 'Location': array([-4.67382660e+01, 8.54570160e+01, 4.21955772e-02]), + 'Rotation': array([-1.67052761e-01, 7.54304581e+01, 5.50439879e-02]), + 'Velocity': array([-0.17707284, -0.44653007, 0.00136863]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3613.765625, + 'focus_actor_name': 'MultipleFloorBuilding18', + 'focus_actor_pt': array([-9344.484375 , 7176.7890625 , 85.98895264]), + 'frame': 22007, + 'frame_number': 22007, + 'framesequence': 88719, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2988738715648651, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.1124312505126, + 'timestamp_carla': 751111, + 'timestamp_device': 1621715, + 'timestamp_stream': 751.1124312505126, + 'transform': [array([-4.87361641e+01, 9.32005234e+01, -1.83264147e-02]), + array([ 0.16591895, -61.88190842, -0.51065272])]} +{'AngularVelocity': array([0.01787198, 0.00311925, 1.55240059]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.008960723876953, + 'FR_Wheel_Angle': -14.758354187011719, + 'Location': array([-4.67610588e+01, 8.53985138e+01, 4.23703268e-02]), + 'Rotation': array([-1.66321933e-01, 7.57486496e+01, 5.15858866e-02]), + 'Velocity': array([-0.18331857, -0.41193998, 0.00114229]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2355.555908203125, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8226.85058594, 7759.24755859, 97.3310318 ]), + 'frame': 22008, + 'frame_number': 22008, + 'framesequence': 88723, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299203485250473, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.1474567502737, + 'timestamp_carla': 751146, + 'timestamp_device': 1621748, + 'timestamp_stream': 751.1474567502737, + 'transform': [array([-4.87270088e+01, 9.32426147e+01, -1.86413098e-02]), + array([ 0.16567306, -61.7232399 , -0.50955415])]} +{'AngularVelocity': array([-0.0029307 , -0.01544108, 2.56678152]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.873404502868652, + 'FR_Wheel_Angle': -14.116950035095215, + 'Location': array([-4.67854080e+01, 8.53366013e+01, 4.25967313e-02]), + 'Rotation': array([-1.69709697e-01, 7.61148758e+01, 5.12394942e-02]), + 'Velocity': array([-0.1994648 , -0.47780854, 0.00157537]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2344.906494140625, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8212.62304688, 7759.59814453, 97.48278809]), + 'frame': 22009, + 'frame_number': 22009, + 'framesequence': 88727, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30008241534233093, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.1798182502389, + 'timestamp_carla': 751179, + 'timestamp_device': 1621782, + 'timestamp_stream': 751.1798182502389, + 'transform': [array([-4.87187080e+01, 9.32816467e+01, -1.87416747e-02]), + array([ 0.16607603, -61.57598877, -0.50912678])]} +{'AngularVelocity': array([ 0.01437282, -0.00672253, 2.46242714]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.983518600463867, + 'FR_Wheel_Angle': -14.476228713989258, + 'Location': array([-4.68089638e+01, 8.52750778e+01, 4.27644625e-02]), + 'Rotation': array([-1.67571858e-01, 7.64549637e+01, 5.16269431e-02]), + 'Velocity': array([-0.18395178, -0.43940112, 0.00120351]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2339.580810546875, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8202.68164062, 7757.08984375, 97.56982422]), + 'frame': 22010, + 'frame_number': 22010, + 'framesequence': 88731, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3004302978515625, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.2132400497794, + 'timestamp_carla': 751212, + 'timestamp_device': 1621815, + 'timestamp_stream': 751.2132400497794, + 'transform': [array([-4.87101974e+01, 9.33216553e+01, -1.88370887e-02]), + array([ 0.16634242, -61.42529297, -0.50876063])]} +{'AngularVelocity': array([5.65878465e-04, 6.70874026e-03, 2.39636922e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.570985794067383, + 'FR_Wheel_Angle': -14.407684326171875, + 'Location': array([-4.68310966e+01, 8.52166672e+01, 4.29569520e-02]), + 'Rotation': array([-1.67052761e-01, 7.67873154e+01, 5.14645502e-02]), + 'Velocity': array([-0.17581405, -0.4295266 , 0.00153575]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2334.734375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8193.55078125, 7754.74804688, 97.62902832]), + 'frame': 22011, + 'frame_number': 22011, + 'framesequence': 88735, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30004578828811646, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.245529152453, + 'timestamp_carla': 751244, + 'timestamp_device': 1621848, + 'timestamp_stream': 751.245529152453, + 'transform': [array([-4.87021065e+01, 9.33602982e+01, -1.88582893e-02]), + array([ 0.16674539, -61.27982712, -0.50863856])]} +{'AngularVelocity': array([-0.00465857, -0.00741141, 2.53399038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.621868133544922, + 'FR_Wheel_Angle': -14.38630199432373, + 'Location': array([-4.68521309e+01, 8.51600571e+01, 4.31353264e-02]), + 'Rotation': array([-1.67694792e-01, 7.71036835e+01, 5.03006317e-02]), + 'Velocity': array([-0.17008917, -0.42544684, 0.00150764]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2329.84521484375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8184.25585938, 7752.35791016, 97.68523407]), + 'frame': 22012, + 'frame_number': 22012, + 'framesequence': 88739, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.2795779518783, + 'timestamp_carla': 751278, + 'timestamp_device': 1621882, + 'timestamp_stream': 751.2795779518783, + 'transform': [array([-4.86938210e+01, 9.34009247e+01, -1.83325857e-02]), + array([ 0.17080253, -61.12680054, -0.51034772])]} +{'AngularVelocity': array([-0.0316502 , 0.07681186, 3.343472 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.660175323486328, + 'FR_Wheel_Angle': -14.392773628234863, + 'Location': array([-4.68738823e+01, 8.51006317e+01, 4.32913490e-02]), + 'Rotation': array([-1.69217929e-01, 7.74354172e+01, 4.82368432e-02]), + 'Velocity': array([-0.18494156, -0.45534781, 0.00091809]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2329.476318359375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8179.10205078, 7747.99267578, 97.69286346]), + 'frame': 22013, + 'frame_number': 22013, + 'framesequence': 88743, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.3121031522751, + 'timestamp_carla': 751311, + 'timestamp_device': 1621915, + 'timestamp_stream': 751.3121031522751, + 'transform': [array([-4.86859741e+01, 9.34396286e+01, -1.66886523e-02]), + array([ 0.18077461, -60.9811554 , -0.51578009])]} +{'AngularVelocity': array([0.02153154, 0.0401225 , 2.99191713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.663650512695312, + 'FR_Wheel_Angle': -14.397489547729492, + 'Location': array([-4.68965225e+01, 8.50378189e+01, 4.35491838e-02]), + 'Rotation': array([-1.71444565e-01, 7.77867279e+01, 4.64327857e-02]), + 'Velocity': array([-0.19490668, -0.48108414, 0.00151914]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2329.837158203125, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8174.34228516, 7743.05419922, 97.61924744]), + 'frame': 22014, + 'frame_number': 22014, + 'framesequence': 88747, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.3475104495883, + 'timestamp_carla': 751346, + 'timestamp_device': 1621948, + 'timestamp_stream': 751.3475104495883, + 'transform': [array([-4.86778221e+01, 9.34819031e+01, -1.42747872e-02]), + array([ 0.19106087, -60.82199097, -0.52423388])]} +{'AngularVelocity': array([0.02155311, 0.03858574, 2.96234918]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.67056655883789, + 'FR_Wheel_Angle': -14.402783393859863, + 'Location': array([-4.69186554e+01, 8.49754257e+01, 4.37168032e-02]), + 'Rotation': array([-1.69060826e-01, 7.81394577e+01, 4.67769057e-02]), + 'Velocity': array([-0.17968065, -0.45098585, 0.00135367]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2330.474365234375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8170.05957031, 7738.22851562, 97.39582062]), + 'frame': 22015, + 'frame_number': 22015, + 'framesequence': 88751, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.3824015520513, + 'timestamp_carla': 751381, + 'timestamp_device': 1621982, + 'timestamp_stream': 751.3824015520513, + 'transform': [array([-4.86700859e+01, 9.35238419e+01, -1.10736750e-02]), + array([ 0.19805498, -60.66389084, -0.5360139 ])]} +{'AngularVelocity': array([0.01487485, 0.04649079, 2.81622005]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.681381225585938, + 'FR_Wheel_Angle': -14.407462120056152, + 'Location': array([-4.69394112e+01, 8.49158096e+01, 4.38947566e-02]), + 'Rotation': array([-1.68152422e-01, 7.84703445e+01, 4.63101007e-02]), + 'Velocity': array([-0.16913298, -0.43085662, 0.00122191]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2331.335205078125, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8165.54394531, 7732.87841797, 97.05291748]), + 'frame': 22016, + 'frame_number': 22016, + 'framesequence': 88755, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.4163203500211, + 'timestamp_carla': 751415, + 'timestamp_device': 1622015, + 'timestamp_stream': 751.4163203500211, + 'transform': [array([-4.86626778e+01, 9.35645294e+01, -7.59883877e-03]), + array([ 0.20384699, -60.51062393, -0.54889256])]} +{'AngularVelocity': array([-0.021016 , 0.07057883, 3.20007062]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.648353576660156, + 'FR_Wheel_Angle': -14.386796951293945, + 'Location': array([-4.69610519e+01, 8.48522339e+01, 4.41232212e-02]), + 'Rotation': array([-1.73158944e-01, 7.88290329e+01, 4.26099114e-02]), + 'Velocity': array([-0.20133987, -0.52698076, 0.0015778 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2332.392822265625, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8161.24511719, 7727.45849609, 96.58507538]), + 'frame': 22017, + 'frame_number': 22017, + 'framesequence': 88759, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.4469208493829, + 'timestamp_carla': 751446, + 'timestamp_device': 1622048, + 'timestamp_stream': 751.4469208493829, + 'transform': [array([-4.86560326e+01, 9.36012573e+01, -4.56727995e-03]), + array([ 0.20683861, -60.37255096, -0.56021488])]} +{'AngularVelocity': array([0.03339371, 0.03316762, 2.83603215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.700485229492188, + 'FR_Wheel_Angle': -15.011621475219727, + 'Location': array([-4.69838181e+01, 8.47842255e+01, 4.43334095e-02]), + 'Rotation': array([-1.71260148e-01, 7.92056503e+01, 4.29796129e-02]), + 'Velocity': array([-0.18458928, -0.48933092, 0.00173694]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2334.210693359375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8157.75 , 7721.82226562, 96.07113647]), + 'frame': 22018, + 'frame_number': 22018, + 'framesequence': 88763, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.4802964515984, + 'timestamp_carla': 751479, + 'timestamp_device': 1622081, + 'timestamp_stream': 751.4802964515984, + 'transform': [array([-4.86488762e+01, 9.36413956e+01, -2.44574551e-03]), + array([ 0.20290442, -60.22162247, -0.56872916])]} +{'AngularVelocity': array([0.03567541, 0.07037295, 3.27231622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.074249267578125, + 'FR_Wheel_Angle': -18.622108459472656, + 'Location': array([-4.70050812e+01, 8.47210999e+01, 4.45149876e-02]), + 'Rotation': array([-1.68610036e-01, 7.95845184e+01, 4.13333923e-02]), + 'Velocity': array([-0.18018968, -0.44215775, 0.00139094]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2337.8427734375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8156.3125 , 7715.76318359, 95.60292816]), + 'frame': 22019, + 'frame_number': 22019, + 'framesequence': 88767, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.5116344504058, + 'timestamp_carla': 751511, + 'timestamp_device': 1622115, + 'timestamp_stream': 751.5116344504058, + 'transform': [array([-4.86422348e+01, 9.36789856e+01, -1.07522961e-03]), + array([ 0.19640207, -60.08034134, -0.57452732])]} +{'AngularVelocity': array([ 0.02133139, -0.09991636, 2.48011684]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.412479400634766, + 'FR_Wheel_Angle': -16.83528709411621, + 'Location': array([-4.70264359e+01, 8.46615143e+01, 4.46985513e-02]), + 'Rotation': array([-1.69060826e-01, 8.00291824e+01, 4.00380045e-02]), + 'Velocity': array([-0.1618845 , -0.42343956, 0.00130045]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2341.78271484375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8154.68115234, 7709.14453125, 95.24383545]), + 'frame': 22020, + 'frame_number': 22020, + 'framesequence': 88770, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.5451510511339, + 'timestamp_carla': 751544, + 'timestamp_device': 1622140, + 'timestamp_stream': 751.5451510511339, + 'transform': [array([-4.86351814e+01, 9.37188263e+01, 2.20298762e-06]), + array([ 0.18822634, -59.93082047, -0.5794403 ])]} +{'AngularVelocity': array([-1.44293578e-03, -3.27045098e-02, 2.46921301e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.924758911132812, + 'FR_Wheel_Angle': -17.684534072875977, + 'Location': array([-4.70475807e+01, 8.45990524e+01, 4.49112579e-02]), + 'Rotation': array([-1.70836687e-01, 8.04422302e+01, 3.94154117e-02]), + 'Velocity': array([-0.16995522, -0.46050113, 0.00163245]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2345.464111328125, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8153.11914062, 7702.94433594, 94.99420166]), + 'frame': 22021, + 'frame_number': 22021, + 'framesequence': 88774, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.5781784504652, + 'timestamp_carla': 751577, + 'timestamp_device': 1622173, + 'timestamp_stream': 751.5781784504652, + 'transform': [array([-4.86283455e+01, 9.37580185e+01, 9.18731675e-04]), + array([ 0.18001646, -59.783741 , -0.58374316])]} +{'AngularVelocity': array([ 0.01695229, -0.06289191, 3.44479895]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.685335159301758, + 'FR_Wheel_Angle': -17.33418083190918, + 'Location': array([-4.70692902e+01, 8.45339737e+01, 4.51057702e-02]), + 'Rotation': array([-1.72824264e-01, 8.08943481e+01, 3.73809151e-02]), + 'Velocity': array([-0.17257486, -0.48184276, 0.00142017]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2349.37939453125, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8151.44482422, 7696.37304688, 94.77498627]), + 'frame': 22022, + 'frame_number': 22022, + 'framesequence': 88779, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.6123970523477, + 'timestamp_carla': 751611, + 'timestamp_device': 1622215, + 'timestamp_stream': 751.6123970523477, + 'transform': [array([-4.86214676e+01, 9.37985458e+01, 1.73723220e-03]), + array([ 0.17119186, -59.63160706, -0.58777112])]} +{'AngularVelocity': array([ 0.01634986, -0.00637559, 4.3677001 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.850337982177734, + 'FR_Wheel_Angle': -17.41748809814453, + 'Location': array([-4.70898132e+01, 8.44701614e+01, 4.53236662e-02]), + 'Rotation': array([-1.72366649e-01, 8.13345184e+01, 3.65321897e-02]), + 'Velocity': array([-0.17472406, -0.48596027, 0.00202984]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2353.243896484375, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8149.78710938, 7689.89648438, 94.57881165]), + 'frame': 22023, + 'frame_number': 22023, + 'framesequence': 88782, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.6451057493687, + 'timestamp_carla': 751644, + 'timestamp_device': 1622240, + 'timestamp_stream': 751.6451057493687, + 'transform': [array([-4.86150055e+01, 9.38373642e+01, 2.54055019e-03]), + array([ 0.16307759, -59.48588181, -0.59164667])]} +{'AngularVelocity': array([0.00615336, 0.02068189, 4.04507017]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.823949813842773, + 'FR_Wheel_Angle': -17.437026977539062, + 'Location': array([-4.71098022e+01, 8.44071884e+01, 4.55156229e-02]), + 'Rotation': array([-1.70624942e-01, 8.17604675e+01, 3.61252241e-02]), + 'Velocity': array([-0.16426775, -0.45962995, 0.00146627]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2361.599853515625, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8151.81835938, 7680.98632812, 94.34565735]), + 'frame': 22024, + 'frame_number': 22024, + 'framesequence': 88787, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.678656950593, + 'timestamp_carla': 751678, + 'timestamp_device': 1622281, + 'timestamp_stream': 751.678656950593, + 'transform': [array([-4.86084862e+01, 9.38769226e+01, 3.29438201e-03]), + array([ 0.15456717, -59.33755112, -0.59540021])]} +{'AngularVelocity': array([ 5.78391412e-03, -3.05570918e-03, 4.13222551e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.83119010925293, + 'FR_Wheel_Angle': -17.433055877685547, + 'Location': array([-4.71285248e+01, 8.43467941e+01, 4.56946455e-02]), + 'Rotation': array([-1.69914603e-01, 8.21726227e+01, 3.54460254e-02]), + 'Velocity': array([-0.1499968 , -0.43380672, 0.00143345]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2370.251220703125, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8154.29150391, 7672.09912109, 94.11466217]), + 'frame': 22025, + 'frame_number': 22025, + 'framesequence': 88791, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.7121064513922, + 'timestamp_carla': 751711, + 'timestamp_device': 1622315, + 'timestamp_stream': 751.7121064513922, + 'transform': [array([-4.86021080e+01, 9.39162216e+01, 4.05333517e-03]), + array([ 0.14629582, -59.19029236, -0.59915352])]} +{'AngularVelocity': array([-0.00771274, -0.03544813, 2.64986277]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.821195602416992, + 'FR_Wheel_Angle': -17.437843322753906, + 'Location': array([-4.71469231e+01, 8.42853012e+01, 4.59030047e-02]), + 'Rotation': array([-1.72332495e-01, 8.25906067e+01, 3.27732638e-02]), + 'Velocity': array([-0.15320471, -0.46650565, 0.00151576]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2379.115478515625, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8156.82128906, 7663. , 93.88465118]), + 'frame': 22026, + 'frame_number': 22026, + 'framesequence': 88795, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.7455089502037, + 'timestamp_carla': 751744, + 'timestamp_device': 1622348, + 'timestamp_stream': 751.7455089502037, + 'transform': [array([-4.85959663e+01, 9.39556122e+01, 6.04401575e-03]), + array([ 0.14595431, -59.04242706, -0.60696602])]} +{'AngularVelocity': array([0.01715894, 0.06710964, 3.39990544]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.839221954345703, + 'FR_Wheel_Angle': -17.445005416870117, + 'Location': array([-4.71647415e+01, 8.42252808e+01, 4.60319035e-02]), + 'Rotation': array([-1.71116725e-01, 8.30085144e+01, 3.19196954e-02]), + 'Velocity': array([-1.53285205e-01, -4.35050577e-01, 8.92353055e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2388.676513671875, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8159.94726562, 7653.55078125, 93.64556885]), + 'frame': 22027, + 'frame_number': 22027, + 'framesequence': 88799, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.77953325212, + 'timestamp_carla': 751778, + 'timestamp_device': 1622381, + 'timestamp_stream': 751.77953325212, + 'transform': [array([-4.85899048e+01, 9.39952164e+01, 9.66907479e-03]), + array([ 0.16182083, -58.89390564, -0.61950922])]} +{'AngularVelocity': array([-0.01283754, -0.04197755, 3.18337417]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.826507568359375, + 'FR_Wheel_Angle': -17.441364288330078, + 'Location': array([-4.71818428e+01, 8.41654892e+01, 4.62806970e-02]), + 'Rotation': array([-1.72605708e-01, 8.34189377e+01, 3.01584825e-02]), + 'Velocity': array([-0.14280844, -0.45854804, 0.00147318]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2417.8623046875, + 'focus_actor_name': 'SM_PlantPot26', + 'focus_actor_pt': array([-8179.87304688, 7633.95898438, 93.02875519]), + 'frame': 22028, + 'frame_number': 22028, + 'framesequence': 88803, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.8123232498765, + 'timestamp_carla': 751811, + 'timestamp_device': 1622415, + 'timestamp_stream': 751.8123232498765, + 'transform': [array([-4.85838203e+01, 9.40325775e+01, 1.37147047e-02]), + array([ 0.18565819, -58.75433731, -0.63266319])]} +{'AngularVelocity': array([-0.01015277, -0.03772539, 3.20873785]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.83075523376465, + 'FR_Wheel_Angle': -17.442140579223633, + 'Location': array([-4.71984177e+01, 8.41064987e+01, 4.64651398e-02]), + 'Rotation': array([-1.71902195e-01, 8.38235092e+01, 2.94752326e-02]), + 'Velocity': array([-0.13450836, -0.44182181, 0.00117446]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3293.8232421875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8924.66992188, 7176.79003906, 83.04395294]), + 'frame': 22029, + 'frame_number': 22029, + 'framesequence': 88807, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.8481223508716, + 'timestamp_carla': 751847, + 'timestamp_device': 1622448, + 'timestamp_stream': 751.8481223508716, + 'transform': [array([-4.85774498e+01, 9.40733261e+01, 1.81510821e-02]), + array([ 0.21562223, -58.60210419, -0.64651948])]} +{'AngularVelocity': array([ 0.01392395, -0.05638715, 2.56547189]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.276729583740234, + 'FR_Wheel_Angle': -20.27861976623535, + 'Location': array([-4.72142563e+01, 8.40485687e+01, 4.66454588e-02]), + 'Rotation': array([-1.71232834e-01, 8.42222214e+01, 2.86801234e-02]), + 'Velocity': array([-0.12303776, -0.40967736, 0.00155925]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3281.9765625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8908.54003906, 7176.79003906, 82.43432617]), + 'frame': 22030, + 'frame_number': 22030, + 'framesequence': 88810, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.878513649106, + 'timestamp_carla': 751877, + 'timestamp_device': 1622473, + 'timestamp_stream': 751.878513649106, + 'transform': [array([-4.85720901e+01, 9.41078415e+01, 2.22643949e-02]), + array([ 0.23945276, -58.473526 , -0.65973479])]} +{'AngularVelocity': array([3.00897006e-03, 9.54765379e-02, 4.40451145e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.127967834472656, + 'FR_Wheel_Angle': -20.53975486755371, + 'Location': array([-4.72318497e+01, 8.39892197e+01, 4.68273833e-02]), + 'Rotation': array([-1.73097476e-01, 8.46965027e+01, 2.21818462e-02]), + 'Velocity': array([-0.16950336, -0.4433319 , 0.0010097 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3269.20068359375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8891.10546875, 7176.79052734, 81.80239868]), + 'frame': 22031, + 'frame_number': 22031, + 'framesequence': 88815, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.9120608493686, + 'timestamp_carla': 751911, + 'timestamp_device': 1622515, + 'timestamp_stream': 751.9120608493686, + 'transform': [array([-4.85664291e+01, 9.41464691e+01, 2.69431099e-02]), + array([ 0.26460153, -58.32927322, -0.67520851])]} +{'AngularVelocity': array([0.00800991, 0.06174419, 3.83220458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.297016143798828, + 'FR_Wheel_Angle': -20.119617462158203, + 'Location': array([-4.72488670e+01, 8.39312363e+01, 4.70170863e-02]), + 'Rotation': array([-1.72605708e-01, 8.51737900e+01, 2.42081061e-02]), + 'Velocity': array([-0.15044314, -0.43137297, 0.00124422]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3258.52783203125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8876.48730469, 7176.79003906, 81.19229126]), + 'frame': 22032, + 'frame_number': 22032, + 'framesequence': 88818, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.9456342495978, + 'timestamp_carla': 751945, + 'timestamp_device': 1622540, + 'timestamp_stream': 751.9456342495978, + 'transform': [array([-4.85609055e+01, 9.41852798e+01, 3.16616148e-02]), + array([ 0.28903994, -58.18427277, -0.69095725])]} +{'AngularVelocity': array([ 2.64102855e-05, -4.60927337e-02, 3.40500975e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.285573959350586, + 'FR_Wheel_Angle': -20.384117126464844, + 'Location': array([-4.72666016e+01, 8.38673782e+01, 4.72357087e-02]), + 'Rotation': array([-1.76027626e-01, 8.56774216e+01, 2.06546485e-02]), + 'Velocity': array([-0.15626675, -0.49753138, 0.00157557]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3246.655029296875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8860.21386719, 7176.79003906, 80.4728241 ]), + 'frame': 22033, + 'frame_number': 22033, + 'framesequence': 88823, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.2737926244735718, + 'timestamp': 751.9798594489694, + 'timestamp_carla': 751979, + 'timestamp_device': 1622581, + 'timestamp_stream': 751.9798594489694, + 'transform': [array([-4.85552521e+01, 9.42246475e+01, 3.59584503e-02]), + array([ 0.32004216, -58.03741837, -0.70399046])]} +{'AngularVelocity': array([ 0.02022371, -0.02445024, 2.77753115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.858173370361328, + 'FR_Wheel_Angle': -20.31196403503418, + 'Location': array([-4.72846031e+01, 8.38005219e+01, 4.74403650e-02]), + 'Rotation': array([-1.75078228e-01, 8.62149429e+01, 2.05715299e-02]), + 'Velocity': array([-0.15208712, -0.49456421, 0.00165096]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3234.832763671875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8843.97363281, 7176.79052734, 79.74330902]), + 'frame': 22034, + 'frame_number': 22034, + 'framesequence': 88827, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2967131733894348, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.011889949441, + 'timestamp_carla': 752011, + 'timestamp_device': 1622615, + 'timestamp_stream': 752.011889949441, + 'transform': [array([-4.85497932e+01, 9.42609940e+01, 3.74949463e-02]), + array([ 0.34103817, -57.90243912, -0.70670801])]} +{'AngularVelocity': array([0.01296172, 0.00307385, 2.64163947]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.93379020690918, + 'FR_Wheel_Angle': -20.303430557250977, + 'Location': array([-4.73009834e+01, 8.37369614e+01, 4.76375110e-02]), + 'Rotation': array([-1.72913060e-01, 8.67225952e+01, 2.05191728e-02]), + 'Velocity': array([-0.14227161, -0.46847084, 0.0017194 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3223.014404296875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8827.65820312, 7176.79052734, 79.17164612]), + 'frame': 22035, + 'frame_number': 22035, + 'framesequence': 88831, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.28098392486572266, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.0467686504126, + 'timestamp_carla': 752046, + 'timestamp_device': 1622648, + 'timestamp_stream': 752.0467686504126, + 'transform': [array([-4.85432701e+01, 9.42991562e+01, 3.74192521e-02]), + array([ 0.35764235, -57.76266098, -0.70338285])]} +{'AngularVelocity': array([0.00691168, 0.00547566, 2.44443965]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.996122360229492, + 'FR_Wheel_Angle': -20.324825286865234, + 'Location': array([-4.73160591e+01, 8.36761627e+01, 4.78211865e-02]), + 'Rotation': array([-1.71963662e-01, 8.72058334e+01, 1.97878387e-02]), + 'Velocity': array([-0.12980136, -0.44401842, 0.00166017]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3212.29541015625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8812.74804688, 7176.79003906, 79.16914368]), + 'frame': 22036, + 'frame_number': 22036, + 'framesequence': 88835, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25864437222480774, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.0793467499316, + 'timestamp_carla': 752078, + 'timestamp_device': 1622681, + 'timestamp_stream': 752.0793467499316, + 'transform': [array([-4.85365715e+01, 9.43334122e+01, 3.66267115e-02]), + array([ 0.37038746, -57.63954163, -0.69761574])]} +{'AngularVelocity': array([1.26189075e-03, 2.44504884e-02, 4.05982590e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.9825439453125, + 'FR_Wheel_Angle': -20.31904411315918, + 'Location': array([-4.73305473e+01, 8.36146469e+01, 4.80541885e-02]), + 'Rotation': array([-1.75044075e-01, 8.77031174e+01, 1.59973036e-02]), + 'Velocity': array([-0.13975458, -0.49333864, 0.00197481]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3201.402587890625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8797.39257812, 7176.79052734, 79.5019989 ]), + 'frame': 22037, + 'frame_number': 22037, + 'framesequence': 88839, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2349131852388382, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.1120254509151, + 'timestamp_carla': 752111, + 'timestamp_device': 1622715, + 'timestamp_stream': 752.1120254509151, + 'transform': [array([-4.85286598e+01, 9.43654938e+01, 3.55533101e-02]), + array([ 0.38196465, -57.52827454, -0.69093335])]} +{'AngularVelocity': array([-0.0270667 , 0.05584643, 4.43905115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.01117706298828, + 'FR_Wheel_Angle': -20.30575942993164, + 'Location': array([-4.73456497e+01, 8.35493927e+01, 4.82034199e-02]), + 'Rotation': array([-1.73889771e-01, 8.82224503e+01, 1.48347113e-02]), + 'Velocity': array([-0.13695398, -0.4929513 , 0.00266921]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3192.02392578125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8783.95507812, 7176.79003906, 79.94944763]), + 'frame': 22038, + 'frame_number': 22038, + 'framesequence': 88842, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21771906316280365, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.1455195508897, + 'timestamp_carla': 752144, + 'timestamp_device': 1622740, + 'timestamp_stream': 752.1455195508897, + 'transform': [array([-4.85198326e+01, 9.43967056e+01, 3.43024544e-02]), + array([ 0.39343253, -57.423172 , -0.68360978])]} +{'AngularVelocity': array([ 0.00782055, -0.01175138, 5.34060907]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.96280288696289, + 'FR_Wheel_Angle': -20.303518295288086, + 'Location': array([-4.73606758e+01, 8.34801178e+01, 4.84738424e-02]), + 'Rotation': array([-1.77093133e-01, 8.87600937e+01, 1.12194456e-02]), + 'Velocity': array([-0.1397776 , -0.54009515, 0.00179207]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3183.82763671875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8771.86132812, 7176.79052734, 80.42893982]), + 'frame': 22039, + 'frame_number': 22039, + 'framesequence': 88847, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2160893678665161, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.1790246516466, + 'timestamp_carla': 752178, + 'timestamp_device': 1622781, + 'timestamp_stream': 752.1790246516466, + 'transform': [array([-4.85108643e+01, 9.44276733e+01, 3.30458172e-02]), + array([ 0.40563807, -57.31995392, -0.67622548])]} +{'AngularVelocity': array([0.00596165, 0.02929396, 5.25323629]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.97453498840332, + 'FR_Wheel_Angle': -20.318105697631836, + 'Location': array([-4.73751030e+01, 8.34116669e+01, 4.86003011e-02]), + 'Rotation': array([-1.74743548e-01, 8.93020172e+01, 1.13155609e-02]), + 'Velocity': array([-0.13249077, -0.51904035, 0.00137728]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3176.3232421875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8760.50585938, 7176.79052734, 80.93173218]), + 'frame': 22040, + 'frame_number': 22040, + 'framesequence': 88851, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22493363916873932, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.212605651468, + 'timestamp_carla': 752212, + 'timestamp_device': 1622815, + 'timestamp_stream': 752.212605651468, + 'transform': [array([-4.85021973e+01, 9.44592590e+01, 3.18007730e-02]), + array([ 0.41879302, -57.21383667, -0.66881073])]} +{'AngularVelocity': array([0.0050299 , 0.08586597, 4.3922863 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.108993530273438, + 'FR_Wheel_Angle': -21.164413452148438, + 'Location': array([-4.73882179e+01, 8.33472443e+01, 4.87962626e-02]), + 'Rotation': array([-1.72366649e-01, 8.98100204e+01, 1.07817827e-02]), + 'Velocity': array([-0.12695706, -0.47533903, 0.00134432]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3169.06591796875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8749.421875 , 7176.79052734, 81.43138885]), + 'frame': 22041, + 'frame_number': 22041, + 'framesequence': 88855, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23720207810401917, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.2458572499454, + 'timestamp_carla': 752245, + 'timestamp_device': 1622848, + 'timestamp_stream': 752.2458572499454, + 'transform': [array([-4.84941406e+01, 9.44914017e+01, 3.06044482e-02]), + array([ 0.43215969, -57.10408783, -0.66157889])]} +{'AngularVelocity': array([0.01607076, 0.03161594, 4.30252981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.770137786865234, + 'FR_Wheel_Angle': -24.160429000854492, + 'Location': array([-4.74015923e+01, 8.32814560e+01, 4.90796939e-02]), + 'Rotation': array([-1.72544226e-01, 9.03719254e+01, 7.51072727e-03]), + 'Velocity': array([-0.12447929, -0.45748812, 0.00149897]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3161.61474609375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8738.09082031, 7176.79052734, 81.93154907]), + 'frame': 22042, + 'frame_number': 22042, + 'framesequence': 88858, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24890287220478058, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.2784774489701, + 'timestamp_carla': 752277, + 'timestamp_device': 1622873, + 'timestamp_stream': 752.2784774489701, + 'transform': [array([-4.84869423e+01, 9.45238724e+01, 3.04378029e-02]), + array([ 0.44863412, -56.99126434, -0.65810114])]} +{'AngularVelocity': array([-8.74363352e-03, -3.67903127e-03, 4.42675257e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.401453018188477, + 'FR_Wheel_Angle': -22.457305908203125, + 'Location': array([-4.74153099e+01, 8.32191620e+01, 4.92943078e-02]), + 'Rotation': array([-1.74156159e-01, 9.09686584e+01, 4.18509124e-03]), + 'Velocity': array([-0.12997614, -0.48720691, 0.00131084]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3153.87548828125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8726.43847656, 7176.79101562, 82.42280579]), + 'frame': 22043, + 'frame_number': 22043, + 'framesequence': 88863, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2517227828502655, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.3127012513578, + 'timestamp_carla': 752312, + 'timestamp_device': 1622915, + 'timestamp_stream': 752.3127012513578, + 'transform': [array([-4.84797401e+01, 9.45582962e+01, 3.22405137e-02]), + array([ 0.47881672, -56.87071609, -0.66094244])]} +{'AngularVelocity': array([0.0081345 , 0.02927073, 4.70050907]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.484729766845703, + 'FR_Wheel_Angle': -23.359453201293945, + 'Location': array([-4.74281921e+01, 8.31538391e+01, 4.94906493e-02]), + 'Rotation': array([-1.74156159e-01, 9.15641251e+01, 4.28737747e-03]), + 'Velocity': array([-0.12131765, -0.48124504, 0.00132732]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3145.874755859375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8714.53710938, 7176.79101562, 82.71315765]), + 'frame': 22044, + 'frame_number': 22044, + 'framesequence': 88867, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24837185442447662, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.3470758497715, + 'timestamp_carla': 752346, + 'timestamp_device': 1622948, + 'timestamp_stream': 752.3470758497715, + 'transform': [array([-4.84726105e+01, 9.45932693e+01, 3.27439383e-02]), + array([ 0.50039327, -56.74819946, -0.65944898])]} +{'AngularVelocity': array([-1.46411580e-03, 8.99900682e-03, 4.25866032e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.957408905029297, + 'FR_Wheel_Angle': -22.94769859313965, + 'Location': array([-4.74404907e+01, 8.30900269e+01, 4.96851616e-02]), + 'Rotation': array([-1.74094677e-01, 9.21527481e+01, 2.20318628e-03]), + 'Velocity': array([-0.11743823, -0.48450845, 0.00156201]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3137.356689453125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8701.9140625 , 7176.79101562, 82.66552734]), + 'frame': 22045, + 'frame_number': 22045, + 'framesequence': 88871, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24280525743961334, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.3792787492275, + 'timestamp_carla': 752378, + 'timestamp_device': 1622981, + 'timestamp_stream': 752.3792787492275, + 'transform': [array([-4.84653015e+01, 9.46243744e+01, 3.23429778e-02]), + array([ 0.51552898, -56.64120483, -0.65508646])]} +{'AngularVelocity': array([-0.05779094, 0.06421983, 4.68554926]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.179948806762695, + 'FR_Wheel_Angle': -23.053476333618164, + 'Location': array([-4.74524269e+01, 8.30226440e+01, 4.99023721e-02]), + 'Rotation': array([-1.76177889e-01, 9.27656479e+01, -9.76568204e-04]), + 'Velocity': array([-0.12527387, -0.55463046, 0.00152934]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3128.7685546875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8689.15332031, 7176.79003906, 82.85647583]), + 'frame': 22046, + 'frame_number': 22046, + 'framesequence': 88874, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23696401715278625, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.4111953489482, + 'timestamp_carla': 752410, + 'timestamp_device': 1623006, + 'timestamp_stream': 752.4111953489482, + 'transform': [array([-4.84580994e+01, 9.46549988e+01, 3.15119252e-02]), + array([ 0.52867711, -56.53623199, -0.64928907])]} +{'AngularVelocity': array([0.01425436, 0.01572094, 4.8938179 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.13684844970703, + 'FR_Wheel_Angle': -23.071008682250977, + 'Location': array([-4.74640465e+01, 8.29542542e+01, 5.01195043e-02]), + 'Rotation': array([-1.74347401e-01, 9.33992691e+01, -1.31224946e-03]), + 'Velocity': array([-0.11087445, -0.50531811, 0.00162471]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3121.425537109375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8678.02832031, 7176.79052734, 83.18840027]), + 'frame': 22047, + 'frame_number': 22047, + 'framesequence': 88879, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23456527292728424, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.4454863518476, + 'timestamp_carla': 752444, + 'timestamp_device': 1623048, + 'timestamp_stream': 752.4454863518476, + 'transform': [array([-4.84503784e+01, 9.46877975e+01, 3.05338185e-02]), + array([ 0.54000157, -56.42419052, -0.64327818])]} +{'AngularVelocity': array([-0.01999667, 0.02854065, 4.77875328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.15266227722168, + 'FR_Wheel_Angle': -23.077260971069336, + 'Location': array([-4.74745483e+01, 8.28878632e+01, 5.03202714e-02]), + 'Rotation': array([-1.73220411e-01, 9.40126343e+01, -2.47192592e-03]), + 'Velocity': array([-0.10318585, -0.50468618, 0.00177336]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3114.298583984375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8667.17578125, 7176.79052734, 83.59159851]), + 'frame': 22048, + 'frame_number': 22048, + 'framesequence': 88883, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23612171411514282, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.4802235513926, + 'timestamp_carla': 752479, + 'timestamp_device': 1623081, + 'timestamp_stream': 752.4802235513926, + 'transform': [array([-4.84428978e+01, 9.47220078e+01, 3.00239455e-02]), + array([ 0.54390842, -56.30653763, -0.64044029])]} +{'AngularVelocity': array([0.00781665, 0.02090385, 4.4218564 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.172271728515625, + 'FR_Wheel_Angle': -23.085744857788086, + 'Location': array([-4.74839134e+01, 8.28243027e+01, 5.05107008e-02]), + 'Rotation': array([-1.72059283e-01, 9.45943756e+01, -3.38745560e-03]), + 'Velocity': array([-0.09164783, -0.46261504, 0.00132821]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3106.76806640625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8655.65136719, 7176.79052734, 84.00600433]), + 'frame': 22049, + 'frame_number': 22049, + 'framesequence': 88887, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23899656534194946, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.5124343521893, + 'timestamp_carla': 752511, + 'timestamp_device': 1623115, + 'timestamp_stream': 752.5124343521893, + 'transform': [array([-4.84359055e+01, 9.47537308e+01, 2.97902394e-02]), + array([ 0.54489195, -56.19755936, -0.63925004])]} +{'AngularVelocity': array([-0.01651764, 0.02964519, 4.03938866]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.16072654724121, + 'FR_Wheel_Angle': -23.064586639404297, + 'Location': array([-4.74922981e+01, 8.27636490e+01, 5.07129580e-02]), + 'Rotation': array([-1.72271028e-01, 9.51458817e+01, -5.58471866e-03]), + 'Velocity': array([-0.08675351, -0.46567351, 0.00148719]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3098.85546875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8643.60742188, 7176.79052734, 84.25016785]), + 'frame': 22050, + 'frame_number': 22050, + 'framesequence': 88891, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24159672856330872, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.5459033511579, + 'timestamp_carla': 752545, + 'timestamp_device': 1623148, + 'timestamp_stream': 752.5459033511579, + 'transform': [array([-4.84288368e+01, 9.47868958e+01, 2.96046156e-02]), + array([ 0.54503542, -56.08321762, -0.63854808])]} +{'AngularVelocity': array([-2.94344779e-03, -3.33965532e-02, 3.92130113e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.128511428833008, + 'FR_Wheel_Angle': -23.065494537353516, + 'Location': array([-4.75011673e+01, 8.26947479e+01, 5.09260446e-02]), + 'Rotation': array([-1.75208002e-01, 9.57747955e+01, -1.04675135e-02]), + 'Velocity': array([-0.08700781, -0.52005208, 0.00102517]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3091.579345703125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8632.48925781, 7176.79052734, 84.39661407]), + 'frame': 22051, + 'frame_number': 22051, + 'framesequence': 88894, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2418714016675949, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.5787538513541, + 'timestamp_carla': 752578, + 'timestamp_device': 1623173, + 'timestamp_stream': 752.5787538513541, + 'transform': [array([-4.84220467e+01, 9.48198700e+01, 2.94771474e-02]), + array([ 0.5448578 , -55.96920013, -0.63818175])]} +{'AngularVelocity': array([ 0.0130765 , -0.04812198, 4.11771441]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.145214080810547, + 'FR_Wheel_Angle': -23.06956672668457, + 'Location': array([-4.75093880e+01, 8.26265488e+01, 5.11608794e-02]), + 'Rotation': array([-1.74408868e-01, 9.64003372e+01, -1.12915086e-02]), + 'Velocity': array([-0.08028131, -0.52078354, 0.00193832]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3083.983642578125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8620.88476562, 7176.79101562, 84.51612854]), + 'frame': 22052, + 'frame_number': 22052, + 'framesequence': 88899, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2404431253671646, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.613353151828, + 'timestamp_carla': 752612, + 'timestamp_device': 1623215, + 'timestamp_stream': 752.613353151828, + 'transform': [array([-4.84149933e+01, 9.48548355e+01, 2.93389596e-02]), + array([ 0.54348493, -55.84822464, -0.63799852])]} +{'AngularVelocity': array([0.01749494, 0.01416015, 3.56871247]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.067413330078125, + 'FR_Wheel_Angle': -26.42795753479004, + 'Location': array([-4.75179100e+01, 8.25495682e+01, 5.13811782e-02]), + 'Rotation': array([-1.72667176e-01, 9.71105576e+01, -1.31530697e-02]), + 'Velocity': array([-0.0831989 , -0.49592036, 0.00141265]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3076.450439453125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8609.375 , 7176.79101562, 84.61630249]), + 'frame': 22053, + 'frame_number': 22053, + 'framesequence': 88903, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23895993828773499, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.6461507491767, + 'timestamp_carla': 752645, + 'timestamp_device': 1623248, + 'timestamp_stream': 752.6461507491767, + 'transform': [array([-4.84080353e+01, 9.48874130e+01, 2.92313285e-02]), + array([ 0.54189354, -55.7365036 , -0.63787621])]} +{'AngularVelocity': array([ 0.01489256, -0.0698994 , 5.44973421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.99098205566406, + 'FR_Wheel_Angle': -25.628238677978516, + 'Location': array([-4.75258141e+01, 8.24866791e+01, 5.16123846e-02]), + 'Rotation': array([-1.73889771e-01, 9.77832642e+01, -1.95312537e-02]), + 'Velocity': array([-0.09535351, -0.53429443, 0.00259787]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3068.515625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8597.2265625 , 7176.79101562, 84.70975494]), + 'frame': 22054, + 'frame_number': 22054, + 'framesequence': 88907, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23921628296375275, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.6795731522143, + 'timestamp_carla': 752678, + 'timestamp_device': 1623281, + 'timestamp_stream': 752.6795731522143, + 'transform': [array([-4.84011269e+01, 9.49206238e+01, 2.90697385e-02]), + array([ 0.54013133, -55.62240601, -0.63757104])]} +{'AngularVelocity': array([2.87460070e-03, 6.64399937e-02, 5.62826204e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.792240142822266, + 'FR_Wheel_Angle': -25.672269821166992, + 'Location': array([-4.75338669e+01, 8.24197540e+01, 5.18239103e-02]), + 'Rotation': array([-1.72824264e-01, 9.84926605e+01, -1.83105376e-02]), + 'Velocity': array([-0.09596167, -0.52438182, 0.00205551]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3061.301513671875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8586.05957031, 7176.79101562, 84.79423523]), + 'frame': 22055, + 'frame_number': 22055, + 'framesequence': 88911, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2400769144296646, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.7127181515098, + 'timestamp_carla': 752712, + 'timestamp_device': 1623315, + 'timestamp_stream': 752.7127181515098, + 'transform': [array([-4.83942757e+01, 9.49534225e+01, 2.85453312e-02]), + array([ 0.54553401, -55.50977325, -0.63467252])]} +{'AngularVelocity': array([-0.0489179 , 0.11948106, 6.56614065]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.502845764160156, + 'FR_Wheel_Angle': -25.693544387817383, + 'Location': array([-4.75408821e+01, 8.23521652e+01, 5.20299412e-02]), + 'Rotation': array([-1.71724603e-01, 9.92047348e+01, -1.98364239e-02]), + 'Velocity': array([-0.09262448, -0.53131288, 0.00185198]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3053.982177734375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8574.71582031, 7176.79101562, 84.88879395]), + 'frame': 22056, + 'frame_number': 22056, + 'framesequence': 88915, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2404431253671646, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.7453793510795, + 'timestamp_carla': 752744, + 'timestamp_device': 1623348, + 'timestamp_stream': 752.7453793510795, + 'transform': [array([-4.83875084e+01, 9.49854965e+01, 2.76654717e-02]), + array([ 0.5554446 , -55.39996338, -0.62948513])]} +{'AngularVelocity': array([-0.03279271, 0.01096018, 6.39312267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.262516021728516, + 'FR_Wheel_Angle': -25.741065979003906, + 'Location': array([-4.75471535e+01, 8.22826462e+01, 5.22327684e-02]), + 'Rotation': array([-1.71690449e-01, 9.99401398e+01, -2.08129864e-02]), + 'Velocity': array([-0.07048678, -0.53285247, 0.0013203 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3046.835205078125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8563.58496094, 7176.79101562, 85.11914062]), + 'frame': 22057, + 'frame_number': 22057, + 'framesequence': 88918, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23994874954223633, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.7783307507634, + 'timestamp_carla': 752777, + 'timestamp_device': 1623373, + 'timestamp_stream': 752.7783307507634, + 'transform': [array([-4.83807220e+01, 9.50175858e+01, 2.65651606e-02]), + array([ 0.56682372, -55.29032516, -0.62304688])]} +{'AngularVelocity': array([ 0.01540462, -0.00803915, 6.27399731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.24827194213867, + 'FR_Wheel_Angle': -25.702394485473633, + 'Location': array([-4.75522346e+01, 8.22151566e+01, 5.24531826e-02]), + 'Rotation': array([-1.70993775e-01, 1.00639374e+02, -2.28271335e-02]), + 'Velocity': array([-0.06238421, -0.50432867, 0.00129165]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3039.9560546875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8552.79882812, 7176.79101562, 85.4690094 ]), + 'frame': 22058, + 'frame_number': 22058, + 'framesequence': 88923, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.8123694509268, + 'timestamp_carla': 752811, + 'timestamp_device': 1623415, + 'timestamp_stream': 752.8123694509268, + 'transform': [array([-4.83738594e+01, 9.50506134e+01, 2.53348053e-02]), + array([ 0.57906342, -55.17755508, -0.61587632])]} +{'AngularVelocity': array([ 0.05392776, -0.04744554, 5.73921204]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.32546615600586, + 'FR_Wheel_Angle': -25.729923248291016, + 'Location': array([-4.75562935e+01, 8.21493912e+01, 5.25966547e-02]), + 'Rotation': array([-1.67325959e-01, 1.01318283e+02, -2.01415867e-02]), + 'Velocity': array([-0.05215979, -0.47568506, 0.00107553]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3033.15869140625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8542.08789062, 7176.79101562, 85.88496399]), + 'frame': 22059, + 'frame_number': 22059, + 'framesequence': 88926, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.8448519520462, + 'timestamp_carla': 752844, + 'timestamp_device': 1623440, + 'timestamp_stream': 752.8448519520462, + 'transform': [array([-4.83676758e+01, 9.50826721e+01, 2.43843161e-02]), + array([ 0.58922672, -55.0674324 , -0.6099565 ])]} +{'AngularVelocity': array([ 0.03064928, -0.03721001, 5.55527115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.34804916381836, + 'FR_Wheel_Angle': -25.737289428710938, + 'Location': array([-4.75594292e+01, 8.20884094e+01, 5.27204424e-02]), + 'Rotation': array([-1.63883552e-01, 1.01948586e+02, -1.84326246e-02]), + 'Velocity': array([-0.04419474, -0.45324463, 0.00102556]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3026.227783203125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8531.13476562, 7176.79101562, 86.3412323 ]), + 'frame': 22060, + 'frame_number': 22060, + 'framesequence': 88931, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.8780189491808, + 'timestamp_carla': 752877, + 'timestamp_device': 1623481, + 'timestamp_stream': 752.8780189491808, + 'transform': [array([-4.83615570e+01, 9.51154785e+01, 2.39926241e-02]), + array([ 0.5945406 , -54.95474625, -0.60669166])]} +{'AngularVelocity': array([-0.09472455, 0.10723089, 5.65888977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.28804016113281, + 'FR_Wheel_Angle': -25.711318969726562, + 'Location': array([-4.75617828e+01, 8.20290680e+01, 5.28624989e-02]), + 'Rotation': array([-1.63180038e-01, 1.02562584e+02, -1.97753906e-02]), + 'Velocity': array([-0.04846141, -0.51420712, 0.00130836]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3019.47509765625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8520.50195312, 7176.79052734, 86.73365784]), + 'frame': 22061, + 'frame_number': 22061, + 'framesequence': 88934, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.9115599505603, + 'timestamp_carla': 752910, + 'timestamp_device': 1623506, + 'timestamp_stream': 752.9115599505603, + 'transform': [array([-4.83555565e+01, 9.51487579e+01, 2.39350591e-02]), + array([ 0.59823573, -54.84011459, -0.60486084])]} +{'AngularVelocity': array([ 0.02249302, -0.00828029, 5.90095901]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.296974182128906, + 'FR_Wheel_Angle': -25.710174560546875, + 'Location': array([-4.75635338e+01, 8.19579010e+01, 5.30255027e-02]), + 'Rotation': array([-1.63446411e-01, 1.03312820e+02, -2.08740272e-02]), + 'Velocity': array([-0.04443251, -0.54686314, 0.00130016]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3012.597412109375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8509.66992188, 7176.79101562, 86.9970932 ]), + 'frame': 22062, + 'frame_number': 22062, + 'framesequence': 88939, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.9452656507492, + 'timestamp_carla': 752944, + 'timestamp_device': 1623548, + 'timestamp_stream': 752.9452656507492, + 'transform': [array([-4.83497162e+01, 9.51824570e+01, 2.40608118e-02]), + array([ 0.60143912, -54.72384262, -0.60376251])]} +{'AngularVelocity': array([0.02559952, 0.02131152, 5.5490675 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.32332229614258, + 'FR_Wheel_Angle': -25.700841903686523, + 'Location': array([-4.75645561e+01, 8.18900070e+01, 5.31564988e-02]), + 'Rotation': array([-1.57893479e-01, 1.04017807e+02, -1.65405199e-02]), + 'Velocity': array([-0.03778841, -0.50580186, 0.00080396]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3005.6357421875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8498.70214844, 7176.79101562, 87.19132996]), + 'frame': 22063, + 'frame_number': 22063, + 'framesequence': 88942, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 752.9778195507824, + 'timestamp_carla': 752977, + 'timestamp_device': 1623573, + 'timestamp_stream': 752.9778195507824, + 'transform': [array([-4.83439980e+01, 9.52147446e+01, 2.42762472e-02]), + array([ 0.60417801, -54.61278915, -0.6030609 ])]} +{'AngularVelocity': array([0.00663168, 0.1409034 , 6.06134987]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.86331558227539, + 'FR_Wheel_Angle': -26.849937438964844, + 'Location': array([-4.75648232e+01, 8.18202438e+01, 5.32677732e-02]), + 'Rotation': array([-1.54881358e-01, 1.04739349e+02, -1.95007324e-02]), + 'Velocity': array([-4.52183299e-02, -5.38561821e-01, 2.16569897e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2998.6181640625, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8487.640625 , 7176.79101562, 87.34967804]), + 'frame': 22064, + 'frame_number': 22064, + 'framesequence': 88947, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.0118979513645, + 'timestamp_carla': 753011, + 'timestamp_device': 1623614, + 'timestamp_stream': 753.0118979513645, + 'transform': [array([-4.83381691e+01, 9.52484970e+01, 2.45009139e-02]), + array([ 0.6068691 , -54.49659729, -0.60238969])]} +{'AngularVelocity': array([0.0370932 , 0.02336149, 6.14015913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.142086029052734, + 'FR_Wheel_Angle': -29.119720458984375, + 'Location': array([-4.75654984e+01, 8.17533035e+01, 5.33896536e-02]), + 'Rotation': array([-1.48802489e-01, 1.05488075e+02, -2.23388746e-02]), + 'Velocity': array([-0.04586117, -0.52030009, 0.00147558]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2991.982421875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8477.11523438, 7176.79101562, 87.484375 ]), + 'frame': 22065, + 'frame_number': 22065, + 'framesequence': 88950, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.045585449785, + 'timestamp_carla': 753044, + 'timestamp_device': 1623639, + 'timestamp_stream': 753.045585449785, + 'transform': [array([-4.83324509e+01, 9.52817230e+01, 2.47480478e-02]), + array([ 0.60951924, -54.38226318, -0.6018101 ])]} +{'AngularVelocity': array([ 4.35935743e-02, -1.98996277e-03, 5.80129147e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.6566276550293, + 'FR_Wheel_Angle': -27.828296661376953, + 'Location': array([-4.75666389e+01, 8.16872864e+01, 5.34793735e-02]), + 'Rotation': array([-1.43126607e-01, 1.06279633e+02, -2.07519587e-02]), + 'Velocity': array([-0.03527592, -0.48655832, 0.00110141]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2985.091552734375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8466.16308594, 7176.79101562, 87.62093353]), + 'frame': 22066, + 'frame_number': 22066, + 'framesequence': 88955, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.0788598507643, + 'timestamp_carla': 753078, + 'timestamp_device': 1623681, + 'timestamp_stream': 753.0788598507643, + 'transform': [array([-4.83269234e+01, 9.53145676e+01, 2.49986742e-02]), + array([ 0.61214882, -54.26924896, -0.60126108])]} +{'AngularVelocity': array([0.03012375, 0.02707311, 5.73668671]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.864540100097656, + 'FR_Wheel_Angle': -28.48227882385254, + 'Location': array([-4.75661545e+01, 8.16222458e+01, 5.35823330e-02]), + 'Rotation': array([-1.39404148e-01, 1.07029961e+02, -2.18505859e-02]), + 'Velocity': array([-0.02933794, -0.49063036, 0.00086632]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2978.365234375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8455.43359375, 7176.79150391, 87.75085449]), + 'frame': 22067, + 'frame_number': 22067, + 'framesequence': 88959, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.1119954511523, + 'timestamp_carla': 753111, + 'timestamp_device': 1623714, + 'timestamp_stream': 753.1119954511523, + 'transform': [array([-4.83214836e+01, 9.53471985e+01, 2.52441298e-02]), + array([ 0.6147716 , -54.15703201, -0.600712 ])]} +{'AngularVelocity': array([3.81536186e-02, 2.00159894e-03, 5.18428755e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.33401870727539, + 'FR_Wheel_Angle': -28.21940803527832, + 'Location': array([-4.75652275e+01, 8.15608978e+01, 5.36763668e-02]), + 'Rotation': array([-1.34315670e-01, 1.07748161e+02, -2.17285175e-02]), + 'Velocity': array([-0.01966493, -0.45619428, 0.00125479]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2971.7705078125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8444.88378906, 7176.79101562, 87.8772583 ]), + 'frame': 22068, + 'frame_number': 22068, + 'framesequence': 88963, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.1478646509349, + 'timestamp_carla': 753147, + 'timestamp_device': 1623748, + 'timestamp_stream': 753.1478646509349, + 'transform': [array([-4.83156738e+01, 9.53828278e+01, 2.55681705e-02]), + array([ 0.61782473, -54.03439713, -0.60043776])]} +{'AngularVelocity': array([0.02736489, 0.02335186, 5.48210144]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.5118408203125, + 'FR_Wheel_Angle': -28.27202033996582, + 'Location': array([-4.75633965e+01, 8.14990768e+01, 5.37769981e-02]), + 'Rotation': array([-1.31474301e-01, 1.08470078e+02, -2.45666560e-02]), + 'Velocity': array([-0.01700119, -0.47234839, 0.00081818]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2965.27685546875, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8434.4609375 , 7176.79101562, 88.00191498]), + 'frame': 22069, + 'frame_number': 22069, + 'framesequence': 88967, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.1805790513754, + 'timestamp_carla': 753179, + 'timestamp_device': 1623781, + 'timestamp_stream': 753.1805790513754, + 'transform': [array([-4.83097725e+01, 9.54136124e+01, 2.55302712e-02]), + array([ 0.619744 , -53.93023682, -0.5991562 ])]} +{'AngularVelocity': array([0.03482646, 0.00810528, 5.36129856]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.48344802856445, + 'FR_Wheel_Angle': -28.265079498291016, + 'Location': array([-4.75607643e+01, 8.14378281e+01, 5.38754910e-02]), + 'Rotation': array([-1.27745017e-01, 1.09187798e+02, -2.60620210e-02]), + 'Velocity': array([-0.00900084, -0.47244522, 0.00111311]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2958.231689453125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8423.125 , 7176.79101562, 88.11847687]), + 'frame': 22070, + 'frame_number': 22070, + 'framesequence': 88971, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.2137601524591, + 'timestamp_carla': 753213, + 'timestamp_device': 1623814, + 'timestamp_stream': 753.2137601524591, + 'transform': [array([-4.83043289e+01, 9.54460449e+01, 2.54725739e-02]), + array([ 0.62020165, -53.81900024, -0.59845436])]} +{'AngularVelocity': array([-0.01251976, 0.1198661 , 6.74337149]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.46063232421875, + 'FR_Wheel_Angle': -28.274099349975586, + 'Location': array([-4.75570450e+01, 8.13712006e+01, 5.39964177e-02]), + 'Rotation': array([-1.25122234e-01, 1.09967003e+02, -3.03649884e-02]), + 'Velocity': array([-0.01616844, -0.52845478, 0.0009623 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2952.384521484375, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8413.51074219, 7176.79101562, 88.26533508]), + 'frame': 22071, + 'frame_number': 22071, + 'framesequence': 88975, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.2453109510243, + 'timestamp_carla': 753244, + 'timestamp_device': 1623848, + 'timestamp_stream': 753.2453109510243, + 'transform': [array([-4.82988548e+01, 9.54762573e+01, 2.52426807e-02]), + array([ 0.61901319, -53.71624374, -0.59741646])]} +{'AngularVelocity': array([-0.00992229, 0.11914244, 6.35994196]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.47393798828125, + 'FR_Wheel_Angle': -28.27324104309082, + 'Location': array([-4.75527840e+01, 8.13036957e+01, 5.40976599e-02]), + 'Rotation': array([-1.19384870e-01, 1.10764725e+02, -3.01208422e-02]), + 'Velocity': array([-0.00990993, -0.51671171, 0.00093177]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2946.106689453125, + 'focus_actor_name': 'MultipleFloorBuilding19', + 'focus_actor_pt': array([-8403.30273438, 7176.79101562, 88.37581635]), + 'frame': 22072, + 'frame_number': 22072, + 'framesequence': 88979, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.2785404510796, + 'timestamp_carla': 753277, + 'timestamp_device': 1623881, + 'timestamp_stream': 753.2785404510796, + 'transform': [array([-4.82934265e+01, 9.55085144e+01, 2.45976541e-02]), + array([ 0.61486727, -53.60597992, -0.59506607])]} +{'AngularVelocity': array([-5.25414292e-03, 1.08510233e-01, 6.28704977e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.47508239746094, + 'FR_Wheel_Angle': -28.274099349975586, + 'Location': array([-4.75480499e+01, 8.12396164e+01, 5.42118736e-02]), + 'Rotation': array([-1.14473961e-01, 1.11515823e+02, -3.06091234e-02]), + 'Velocity': array([-0.00371444, -0.50643152, 0.00108257]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2940.392333984375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8393.89550781, 7176.79199219, 88.49409485]), + 'frame': 22073, + 'frame_number': 22073, + 'framesequence': 88983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.3125823512673, + 'timestamp_carla': 753311, + 'timestamp_device': 1623914, + 'timestamp_stream': 753.3125823512673, + 'transform': [array([-4.82876892e+01, 9.55412903e+01, 2.38684937e-02]), + array([ 0.61764032, -53.49431992, -0.59158707])]} +{'AngularVelocity': array([0.04123113, 0.0183634 , 6.1550765 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.46259689331055, + 'FR_Wheel_Angle': -28.270984649658203, + 'Location': array([-4.75417824e+01, 8.11723633e+01, 5.43247871e-02]), + 'Rotation': array([-1.11113511e-01, 1.12303802e+02, -3.21349949e-02]), + 'Velocity': array([ 0.01776259, -0.52220857, 0.00132382]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2934.2734375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8383.85351562, 7176.79199219, 88.68286133]), + 'frame': 22074, + 'frame_number': 22074, + 'framesequence': 88987, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.3454349525273, + 'timestamp_carla': 753344, + 'timestamp_device': 1623948, + 'timestamp_stream': 753.3454349525273, + 'transform': [array([-4.82821999e+01, 9.55725937e+01, 2.28358749e-02]), + array([ 0.62664932, -53.38781738, -0.58591163])]} +{'AngularVelocity': array([0.02778431, 0.04074276, 6.01549006]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.484737396240234, + 'FR_Wheel_Angle': -28.574874877929688, + 'Location': array([-4.75345993e+01, 8.11061096e+01, 5.44083677e-02]), + 'Rotation': array([-1.04645319e-01, 1.13082138e+02, -3.12805213e-02]), + 'Velocity': array([ 0.02253266, -0.49066317, 0.00072373]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2928.160888671875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8373.73339844, 7176.79150391, 88.9225769 ]), + 'frame': 22075, + 'frame_number': 22075, + 'framesequence': 88991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.3789252489805, + 'timestamp_carla': 753378, + 'timestamp_device': 1623981, + 'timestamp_stream': 753.3789252489805, + 'transform': [array([-4.82766800e+01, 9.56046295e+01, 2.16729827e-02]), + array([ 0.63854754, -53.27885056, -0.57925969])]} +{'AngularVelocity': array([0.0324781 , 0.03776997, 6.08870363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.653648376464844, + 'FR_Wheel_Angle': -30.784080505371094, + 'Location': array([-4.75271492e+01, 8.10421524e+01, 5.45270443e-02]), + 'Rotation': array([-1.00431100e-01, 1.13854439e+02, -3.48205604e-02]), + 'Velocity': array([ 0.01802647, -0.4903321 , 0.001072 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2922.402587890625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8364.14160156, 7176.79199219, 89.26972961]), + 'frame': 22076, + 'frame_number': 22076, + 'framesequence': 88994, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.4115203507245, + 'timestamp_carla': 753410, + 'timestamp_device': 1624006, + 'timestamp_stream': 753.4115203507245, + 'transform': [array([-4.82714844e+01, 9.56358795e+01, 2.04509627e-02]), + array([ 0.65060282, -53.1724968 , -0.57224149])]} +{'AngularVelocity': array([ 4.29812297e-02, -1.14585168e-03, 5.70142031e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.78050231933594, + 'FR_Wheel_Angle': -30.57407569885254, + 'Location': array([-4.75206795e+01, 8.09810562e+01, 5.46272546e-02]), + 'Rotation': array([-9.50967222e-02, 1.14644882e+02, -3.51257212e-02]), + 'Velocity': array([ 0.01957215, -0.46227154, 0.00089189]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1948.1077880859375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7578.21582031, 7755.91015625, 99.45588684]), + 'frame': 22077, + 'frame_number': 22077, + 'framesequence': 88999, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.4466018490493, + 'timestamp_carla': 753446, + 'timestamp_device': 1624048, + 'timestamp_stream': 753.4466018490493, + 'transform': [array([-4.82659187e+01, 9.56696854e+01, 1.91566367e-02]), + array([ 0.66427684, -53.05737305, -0.56473529])]} +{'AngularVelocity': array([-0.05553955, 0.13545313, 7.10673952]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.64670181274414, + 'FR_Wheel_Angle': -30.76362419128418, + 'Location': array([-4.75133972e+01, 8.09198685e+01, 5.47348671e-02]), + 'Rotation': array([-9.26788300e-02, 1.15446625e+02, -3.95202748e-02]), + 'Velocity': array([ 0.01249898, -0.50926679, 0.00133415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1938.820556640625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7566.91503906, 7759.52734375, 99.78677368]), + 'frame': 22078, + 'frame_number': 22078, + 'framesequence': 89003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.4795870520175, + 'timestamp_carla': 753478, + 'timestamp_device': 1624081, + 'timestamp_stream': 753.4795870520175, + 'transform': [array([-4.82599945e+01, 9.57023239e+01, 1.89403053e-02]), + array([ 0.66748017, -52.9482193 , -0.56244659])]} +{'AngularVelocity': array([5.73812947e-02, 4.42285091e-03, 6.55617285e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.65648651123047, + 'FR_Wheel_Angle': -30.784337997436523, + 'Location': array([-4.75047531e+01, 8.08539886e+01, 5.48614413e-02]), + 'Rotation': array([-8.89017358e-02, 1.16313759e+02, -4.00085486e-02]), + 'Velocity': array([ 0.03215772, -0.50416106, 0.00143118]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1928.9150390625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7554.81835938, 7763.39111328, 100.13658142]), + 'frame': 22079, + 'frame_number': 22079, + 'framesequence': 89007, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2394726574420929, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.5144252516329, + 'timestamp_carla': 753513, + 'timestamp_device': 1624114, + 'timestamp_stream': 753.5144252516329, + 'transform': [array([-4.82553062e+01, 9.57392883e+01, 1.87172033e-02]), + array([ 0.65557516, -52.82116699, -0.5610109 ])]} +{'AngularVelocity': array([0.02805748, 0.03530722, 6.38170958]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66478729248047, + 'FR_Wheel_Angle': -30.78700065612793, + 'Location': array([-4.74955711e+01, 8.07910309e+01, 5.49622253e-02]), + 'Rotation': array([-8.29184949e-02, 1.17139595e+02, -3.88488770e-02]), + 'Velocity': array([ 0.03754384, -0.48303077, 0.00125342]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1920.7105712890625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7544.23925781, 7766.41308594, 100.3147583 ]), + 'frame': 22080, + 'frame_number': 22080, + 'framesequence': 89010, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2285592257976532, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.5451651513577, + 'timestamp_carla': 753544, + 'timestamp_device': 1624139, + 'timestamp_stream': 753.5451651513577, + 'transform': [array([-4.82510719e+01, 9.57711105e+01, 1.85319986e-02]), + array([ 0.64068538, -52.71247101, -0.55975789])]} +{'AngularVelocity': array([-0.06010972, 0.03380745, 5.9568305 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.637451171875, + 'FR_Wheel_Angle': -30.77414321899414, + 'Location': array([-4.74857674e+01, 8.07298050e+01, 5.50506115e-02]), + 'Rotation': array([-7.83354342e-02, 1.17942268e+02, -4.00695838e-02]), + 'Velocity': array([ 0.05739131, -0.50668716, 0.00095961]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1919.06396484375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7538.4375 , 7765.06640625, 100.43157196]), + 'frame': 22081, + 'frame_number': 22081, + 'framesequence': 89015, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2106509804725647, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.5782245509326, + 'timestamp_carla': 753577, + 'timestamp_device': 1624181, + 'timestamp_stream': 753.5782245509326, + 'transform': [array([-4.82458572e+01, 9.58035049e+01, 1.83703899e-02]), + array([ 0.62237364, -52.6047287 , -0.55871838])]} +{'AngularVelocity': array([-0.02837489, 0.12843247, 7.75108957]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.61899185180664, + 'FR_Wheel_Angle': -30.759952545166016, + 'Location': array([-4.74732895e+01, 8.06612549e+01, 5.51891997e-02]), + 'Rotation': array([-7.63615072e-02, 1.18837418e+02, -4.57763746e-02]), + 'Velocity': array([ 0.04848731, -0.55142361, 0.00148847]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1917.6605224609375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7533.44482422, 7763.93798828, 100.5493927 ]), + 'frame': 22082, + 'frame_number': 22082, + 'framesequence': 89019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18675497174263, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.6121976524591, + 'timestamp_carla': 753611, + 'timestamp_device': 1624214, + 'timestamp_stream': 753.6121976524591, + 'transform': [array([-4.82397118e+01, 9.58349762e+01, 1.83258913e-02]), + array([ 0.60299641, -52.50360107, -0.55813658])]} +{'AngularVelocity': array([-1.85739109e-03, 1.05431102e-01, 7.27356100e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.63045120239258, + 'FR_Wheel_Angle': -30.76482582092285, + 'Location': array([-4.74606743e+01, 8.05928116e+01, 5.53002432e-02]), + 'Rotation': array([-6.97635487e-02, 1.19747581e+02, -4.54101488e-02]), + 'Velocity': array([ 0.0503451, -0.5300436, 0.0012451]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1916.41015625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7528.49609375, 7762.82324219, 100.66779327]), + 'frame': 22083, + 'frame_number': 22083, + 'framesequence': 89023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16326183080673218, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.6460910513997, + 'timestamp_carla': 753645, + 'timestamp_device': 1624248, + 'timestamp_stream': 753.6460910513997, + 'transform': [array([-4.82322159e+01, 9.58634644e+01, 1.83906257e-02]), + array([ 0.5833118 , -52.41762543, -0.55801249])]} +{'AngularVelocity': array([-0.01554233, 0.10944709, 7.21871042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.633792877197266, + 'FR_Wheel_Angle': -30.76873016357422, + 'Location': array([-4.74473801e+01, 8.05261688e+01, 5.54165542e-02]), + 'Rotation': array([-6.42379224e-02, 1.20640556e+02, -4.54711914e-02]), + 'Velocity': array([ 0.05793694, -0.52157891, 0.00127878]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1915.43115234375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7523.87109375, 7761.77099609, 100.77293396]), + 'frame': 22084, + 'frame_number': 22084, + 'framesequence': 89027, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15394148230552673, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.6786016523838, + 'timestamp_carla': 753678, + 'timestamp_device': 1624281, + 'timestamp_stream': 753.6786016523838, + 'transform': [array([-4.82248077e+01, 9.58899231e+01, 1.85348988e-02]), + array([ 0.56506151, -52.33966064, -0.55813271])]} +{'AngularVelocity': array([-0.01855257, 0.11139017, 7.14562464]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.63949966430664, + 'FR_Wheel_Angle': -30.770191192626953, + 'Location': array([-4.74331093e+01, 8.04600143e+01, 5.55272549e-02]), + 'Rotation': array([-5.92655465e-02, 1.21532555e+02, -4.65698168e-02]), + 'Velocity': array([ 0.06464922, -0.51470399, 0.00111232]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1914.8955078125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7519.93994141, 7760.87158203, 100.85951996]), + 'frame': 22085, + 'frame_number': 22085, + 'framesequence': 89031, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15883053839206696, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.7124518491328, + 'timestamp_carla': 753711, + 'timestamp_device': 1624314, + 'timestamp_stream': 753.7124518491328, + 'transform': [array([-4.82171364e+01, 9.59172821e+01, 1.87711418e-02]), + array([ 0.54727572, -52.25930786, -0.55855834])]} +{'AngularVelocity': array([-0.01018246, 0.05363223, 7.32255554]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.616539001464844, + 'FR_Wheel_Angle': -30.761951446533203, + 'Location': array([-4.74172935e+01, 8.03934860e+01, 5.56521118e-02]), + 'Rotation': array([-5.57821505e-02, 1.22426186e+02, -4.87976037e-02]), + 'Velocity': array([ 0.09237133, -0.54231668, 0.00097207]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1914.516845703125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7516.39404297, 7760.05419922, 100.93411255]), + 'frame': 22086, + 'frame_number': 22086, + 'framesequence': 89035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17108066380023956, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.7453210502863, + 'timestamp_carla': 753744, + 'timestamp_device': 1624348, + 'timestamp_stream': 753.7453210502863, + 'transform': [array([-4.82099609e+01, 9.59435806e+01, 1.90082453e-02]), + array([ 0.53079444, -52.18138885, -0.55892301])]} +{'AngularVelocity': array([0.0219029 , 0.04933809, 6.94855642]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.64958953857422, + 'FR_Wheel_Angle': -30.77741050720215, + 'Location': array([-4.74001389e+01, 8.03270035e+01, 5.57511039e-02]), + 'Rotation': array([-4.96827923e-02, 1.23322639e+02, -4.83398400e-02]), + 'Velocity': array([ 0.09359889, -0.50854111, 0.00088755]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1914.177490234375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7512.77246094, 7759.19824219, 100.99828339]), + 'frame': 22087, + 'frame_number': 22087, + 'framesequence': 89039, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18391674757003784, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.778508450836, + 'timestamp_carla': 753778, + 'timestamp_device': 1624381, + 'timestamp_stream': 753.778508450836, + 'transform': [array([-4.82037163e+01, 9.59716568e+01, 1.94974504e-02]), + array([ 0.51120549, -52.09455109, -0.56084383])]} +{'AngularVelocity': array([0.04482424, 0.01615368, 6.30689573]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.65410614013672, + 'FR_Wheel_Angle': -30.78635597229004, + 'Location': array([-4.73829231e+01, 8.02642136e+01, 5.58653548e-02]), + 'Rotation': array([-4.42527942e-02, 1.24173294e+02, -4.87365648e-02]), + 'Velocity': array([ 0.09918567, -0.48158854, 0.00113689]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1913.8140869140625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7509.25585938, 7758.36914062, 101.06194305]), + 'frame': 22088, + 'frame_number': 22088, + 'framesequence': 89043, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1923215538263321, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.8121135495603, + 'timestamp_carla': 753811, + 'timestamp_device': 1624414, + 'timestamp_stream': 753.8121135495603, + 'transform': [array([-4.81981468e+01, 9.60010223e+01, 2.03607641e-02]), + array([ 0.48615235, -52.00127411, -0.56523645])]} +{'AngularVelocity': array([0.01190864, 0.04806751, 6.25214148]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.682613372802734, + 'FR_Wheel_Angle': -30.789791107177734, + 'Location': array([-4.73655167e+01, 8.02040939e+01, 5.59586212e-02]), + 'Rotation': array([-3.88774350e-02, 1.24989777e+02, -4.91027758e-02]), + 'Velocity': array([ 0.09753368, -0.45188558, 0.0010982 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1913.3336181640625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7505.44824219, 7757.37060547, 101.07421112]), + 'frame': 22089, + 'frame_number': 22089, + 'framesequence': 89047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19157080352306366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.8456615507603, + 'timestamp_carla': 753845, + 'timestamp_device': 1624448, + 'timestamp_stream': 753.8456615507603, + 'transform': [array([-4.81927299e+01, 9.60302048e+01, 2.13833135e-02]), + array([ 0.45905015, -51.90824127, -0.57072759])]} +{'AngularVelocity': array([-0.06488788, 0.02284973, 5.96553421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.64032745361328, + 'FR_Wheel_Angle': -30.771427154541016, + 'Location': array([-4.73479919e+01, 8.01468582e+01, 5.60858063e-02]), + 'Rotation': array([-3.60702276e-02, 1.25765457e+02, -5.24291880e-02]), + 'Velocity': array([ 0.12643951, -0.49517852, 0.00083849]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1914.8001708984375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7503.02587891, 7754.99414062, 100.98342896]), + 'frame': 22090, + 'frame_number': 22090, + 'framesequence': 89051, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18593096733093262, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.8800378516316, + 'timestamp_carla': 753879, + 'timestamp_device': 1624481, + 'timestamp_stream': 753.8800378516316, + 'transform': [array([-4.81871910e+01, 9.60597763e+01, 2.25738138e-02]), + array([ 0.43018579, -51.8142395 , -0.57722574])]} +{'AngularVelocity': array([0.03481168, 0.03503046, 6.3781085 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66083526611328, + 'FR_Wheel_Angle': -30.787311553955078, + 'Location': array([-4.73278542e+01, 8.00848007e+01, 5.61941788e-02]), + 'Rotation': array([-3.22248302e-02, 1.26615829e+02, -5.48400730e-02]), + 'Velocity': array([ 0.11627533, -0.47612318, 0.00091112]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1916.5137939453125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7500.81005859, 7752.45507812, 100.85076141]), + 'frame': 22091, + 'frame_number': 22091, + 'framesequence': 89055, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17911924421787262, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.9116801507771, + 'timestamp_carla': 753911, + 'timestamp_device': 1624514, + 'timestamp_stream': 753.9116801507771, + 'transform': [array([-4.81810455e+01, 9.60853958e+01, 2.28756703e-02]), + array([ 0.4118672 , -51.73566818, -0.57923877])]} +{'AngularVelocity': array([0.0132872 , 0.04039278, 6.28664351]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.657623291015625, + 'FR_Wheel_Angle': -30.782386779785156, + 'Location': array([-4.73082008e+01, 8.00263672e+01, 5.62947728e-02]), + 'Rotation': array([-2.64533218e-02, 1.27422195e+02, -5.43212779e-02]), + 'Velocity': array([ 0.11856181, -0.45146561, 0.00089206]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1918.32080078125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7498.61328125, 7749.84912109, 100.68238831]), + 'frame': 22092, + 'frame_number': 22092, + 'framesequence': 89059, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17444992065429688, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.9459611512721, + 'timestamp_carla': 753945, + 'timestamp_device': 1624548, + 'timestamp_stream': 753.9459611512721, + 'transform': [array([-4.81740570e+01, 9.61131821e+01, 2.23561767e-02]), + array([ 0.39789948, -51.65143585, -0.57771158])]} +{'AngularVelocity': array([-0.02635087, 0.09676156, 6.63518095]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.669769287109375, + 'FR_Wheel_Angle': -30.771848678588867, + 'Location': array([-4.72877693e+01, 7.99676819e+01, 5.64134866e-02]), + 'Rotation': array([-2.27991696e-02, 1.28235977e+02, -5.75866699e-02]), + 'Velocity': array([ 0.11743379, -0.46880862, 0.00119732]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1919.837158203125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7496.62451172, 7747.77294922, 100.64634705]), + 'frame': 22093, + 'frame_number': 22093, + 'framesequence': 89063, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17452315986156464, + 'throttle_input': 0.2737926244735718, + 'timestamp': 753.9780521504581, + 'timestamp_carla': 753977, + 'timestamp_device': 1624581, + 'timestamp_stream': 753.9780521504581, + 'transform': [array([-4.81670303e+01, 9.61385803e+01, 2.13916115e-02]), + array([ 0.38690969, -51.57610321, -0.57417077])]} +{'AngularVelocity': array([-0.0298421 , -0.02297682, 6.21951056]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.61160659790039, + 'FR_Wheel_Angle': -30.759117126464844, + 'Location': array([-4.72643852e+01, 7.99053421e+01, 5.64996600e-02]), + 'Rotation': array([-2.20615100e-02, 1.29073227e+02, -5.52368090e-02]), + 'Velocity': array([ 1.72997430e-01, -5.21713316e-01, 4.33874113e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1921.3424072265625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7494.35058594, 7745.66357422, 100.71413422]), + 'frame': 22094, + 'frame_number': 22094, + 'framesequence': 89067, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17732475697994232, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.0139379501343, + 'timestamp_carla': 754013, + 'timestamp_device': 1624614, + 'timestamp_stream': 754.0139379501343, + 'transform': [array([-4.81590919e+01, 9.61667175e+01, 2.05604266e-02]), + array([ 0.38175291, -51.49300003, -0.57099658])]} +{'AngularVelocity': array([0.00749786, 0.04268831, 7.46635151]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6181640625, + 'FR_Wheel_Angle': -30.760875701904297, + 'Location': array([-4.72390327e+01, 7.98394241e+01, 5.65469638e-02]), + 'Rotation': array([-1.93772465e-02, 1.29989807e+02, -5.24291843e-02]), + 'Velocity': array([ 0.14733654, -0.51758671, 0.00066819]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1922.6754150390625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7492.22119141, 7743.84863281, 100.84343719]), + 'frame': 22095, + 'frame_number': 22095, + 'framesequence': 89071, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18078556656837463, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.04618595168, + 'timestamp_carla': 754045, + 'timestamp_device': 1624648, + 'timestamp_stream': 754.04618595168, + 'transform': [array([-4.81521873e+01, 9.61922607e+01, 2.02525128e-02]), + array([ 0.38126796, -51.41675949, -0.56968421])]} +{'AngularVelocity': array([ 0.13849558, -0.12370048, 6.36850166]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.627777099609375, + 'FR_Wheel_Angle': -30.762941360473633, + 'Location': array([-4.72130127e+01, 7.97739563e+01, 5.65534085e-02]), + 'Rotation': array([-1.67817734e-02, 1.30914017e+02, -4.55627441e-02]), + 'Velocity': array([ 1.78673536e-01, -5.05189538e-01, 2.41222369e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1924.2470703125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7489.93359375, 7741.80273438, 100.94303894]), + 'frame': 22096, + 'frame_number': 22096, + 'framesequence': 89075, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18259835243225098, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.0790941491723, + 'timestamp_carla': 754078, + 'timestamp_device': 1624681, + 'timestamp_stream': 754.0790941491723, + 'transform': [array([-4.81456108e+01, 9.62192535e+01, 1.99902523e-02]), + array([ 0.3839249 , -51.33452988, -0.56834161])]} +{'AngularVelocity': array([ 0.09292161, -0.08345468, 6.36350203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.627506256103516, + 'FR_Wheel_Angle': -30.75861167907715, + 'Location': array([-4.71863213e+01, 7.97097473e+01, 5.66368364e-02]), + 'Rotation': array([-1.38243018e-02, 1.31828796e+02, -3.95202637e-02]), + 'Velocity': array([ 0.18188722, -0.49780864, 0.00063166]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1925.75146484375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7487.91845703, 7739.86279297, 100.97360229]), + 'frame': 22097, + 'frame_number': 22097, + 'framesequence': 89079, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1816461682319641, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.1122880503535, + 'timestamp_carla': 754111, + 'timestamp_device': 1624714, + 'timestamp_stream': 754.1122880503535, + 'transform': [array([-4.81383057e+01, 9.62448883e+01, 1.92732997e-02]), + array([ 0.39233971, -51.25894165, -0.56428325])]} +{'AngularVelocity': array([ 0.11807289, -0.10250985, 6.34565449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.635807037353516, + 'FR_Wheel_Angle': -30.768306732177734, + 'Location': array([-4.71585579e+01, 7.96458206e+01, 5.66795617e-02]), + 'Rotation': array([-1.16932830e-02, 1.32749405e+02, -3.46679650e-02]), + 'Velocity': array([ 1.91291466e-01, -4.91837293e-01, 3.21197513e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1927.2916259765625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7485.76513672, 7737.77246094, 100.99946594]), + 'frame': 22098, + 'frame_number': 22098, + 'framesequence': 89083, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17972351610660553, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.1462314501405, + 'timestamp_carla': 754145, + 'timestamp_device': 1624748, + 'timestamp_stream': 754.1462314501405, + 'transform': [array([-4.81313324e+01, 9.62719040e+01, 1.83712374e-02]), + array([ 0.40393737, -51.17785645, -0.55894339])]} +{'AngularVelocity': array([ 0.07977853, -0.07157928, 6.04291868]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.63161849975586, + 'FR_Wheel_Angle': -30.76326560974121, + 'Location': array([-4.71306190e+01, 7.95839844e+01, 5.67322448e-02]), + 'Rotation': array([-9.24807601e-03, 1.33643005e+02, -3.00292950e-02]), + 'Velocity': array([ 1.94901913e-01, -4.87675071e-01, 3.22103500e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1928.70654296875, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7483.65429688, 7735.94384766, 101.11581421]), + 'frame': 22099, + 'frame_number': 22099, + 'framesequence': 89087, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1787347048521042, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.1781787499785, + 'timestamp_carla': 754177, + 'timestamp_device': 1624781, + 'timestamp_stream': 754.1781787499785, + 'transform': [array([-4.81243973e+01, 9.62966003e+01, 1.74362939e-02]), + array([ 0.41513887, -51.10519791, -0.55335921])]} +{'AngularVelocity': array([ 0.11405052, -0.05363068, 5.61766052]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.615055084228516, + 'FR_Wheel_Angle': -30.72243881225586, + 'Location': array([-4.71006393e+01, 7.95207748e+01, 5.67801185e-02]), + 'Rotation': array([-7.60200014e-03, 1.34561676e+02, -2.58789025e-02]), + 'Velocity': array([ 1.96870163e-01, -4.80893970e-01, 2.11677543e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1930.0745849609375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7481.35449219, 7734.03515625, 101.27646637]), + 'frame': 22100, + 'frame_number': 22100, + 'framesequence': 89090, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17932066321372986, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.2114707492292, + 'timestamp_carla': 754210, + 'timestamp_device': 1624806, + 'timestamp_stream': 754.2114707492292, + 'transform': [array([-4.81183357e+01, 9.63240738e+01, 1.74112413e-02]), + array([ 0.41766605, -51.02132416, -0.5521692 ])]} +{'AngularVelocity': array([ 0.06474991, -0.04535207, 7.6837039 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.56996154785156, + 'FR_Wheel_Angle': -30.734664916992188, + 'Location': array([-4.70659180e+01, 7.94521332e+01, 5.68650700e-02]), + 'Rotation': array([-8.66751000e-03, 1.35532471e+02, -2.59094238e-02]), + 'Velocity': array([ 0.24763647, -0.57474989, 0.00075371]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1931.3392333984375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7479.24804688, 7732.3515625 , 101.45043945]), + 'frame': 22101, + 'frame_number': 22101, + 'framesequence': 89095, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1803094744682312, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.2452777512372, + 'timestamp_carla': 754244, + 'timestamp_device': 1624848, + 'timestamp_stream': 754.2452777512372, + 'transform': [array([-4.81123276e+01, 9.63518524e+01, 1.81648731e-02]), + array([ 0.41511154, -50.9364624 , -0.55445784])]} +{'AngularVelocity': array([ 0.10127217, -0.03922135, 7.09060574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.60997772216797, + 'FR_Wheel_Angle': -30.757036209106445, + 'Location': array([-4.70296555e+01, 7.93826065e+01, 5.68802916e-02]), + 'Rotation': array([-2.86867935e-03, 1.36550522e+02, -1.58386249e-02]), + 'Velocity': array([ 2.34267592e-01, -5.18957257e-01, -1.84078206e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1932.856201171875, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7477.04199219, 7730.24707031, 101.49237061]), + 'frame': 22102, + 'frame_number': 22102, + 'framesequence': 89099, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18045595288276672, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.2787445522845, + 'timestamp_carla': 754278, + 'timestamp_device': 1624881, + 'timestamp_stream': 754.2787445522845, + 'transform': [array([-4.81062622e+01, 9.63791656e+01, 1.89038273e-02]), + array([ 0.41446951, -50.85337448, -0.55638045])]} +{'AngularVelocity': array([ 0.04000884, -0.01616794, 6.69139528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.62950897216797, + 'FR_Wheel_Angle': -30.770055770874023, + 'Location': array([-4.69964180e+01, 7.93216095e+01, 5.69530763e-02]), + 'Rotation': array([ 1.35920756e-03, 1.37454712e+02, -8.78906250e-03]), + 'Velocity': array([ 0.22803348, -0.48409972, 0.00086501]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1935.1541748046875, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7475.40478516, 7727.625 , 101.42404175]), + 'frame': 22103, + 'frame_number': 22103, + 'framesequence': 89103, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17992493510246277, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.3115732520819, + 'timestamp_carla': 754311, + 'timestamp_device': 1624914, + 'timestamp_stream': 754.3115732520819, + 'transform': [array([-4.80996704e+01, 9.64049759e+01, 1.87956616e-02]), + array([ 0.42224911, -50.77644348, -0.55409211])]} +{'AngularVelocity': array([ 0.16406305, -0.07687885, 6.31689787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.634090423583984, + 'FR_Wheel_Angle': -30.762060165405273, + 'Location': array([-4.69632454e+01, 7.92629700e+01, 5.69933988e-02]), + 'Rotation': array([ 3.63366050e-03, 1.38329758e+02, -4.27246047e-03]), + 'Velocity': array([ 0.2199945 , -0.43253517, 0.00061542]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1938.5302734375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7474.6484375 , 7724.36035156, 101.3575058 ]), + 'frame': 22104, + 'frame_number': 22104, + 'framesequence': 89107, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.345274951309, + 'timestamp_carla': 754344, + 'timestamp_device': 1624948, + 'timestamp_stream': 754.345274951309, + 'transform': [array([-4.8092762e+01, 9.6431221e+01, 1.8239269e-02]), + array([ 0.43213922, -50.69882584, -0.54985088])]} +{'AngularVelocity': array([0.02590054, 0.0113375 , 6.81345558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.62908935546875, + 'FR_Wheel_Angle': -30.772005081176758, + 'Location': array([-4.69277954e+01, 7.92036972e+01, 5.70566058e-02]), + 'Rotation': array([ 3.81124532e-03, 1.39205032e+02, -2.56347656e-03]), + 'Velocity': array([ 2.39314422e-01, -4.73317444e-01, 4.33168403e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1941.547119140625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7473.76123047, 7721.47265625, 101.42115784]), + 'frame': 22105, + 'frame_number': 22105, + 'framesequence': 89111, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.3783433511853, + 'timestamp_carla': 754377, + 'timestamp_device': 1624981, + 'timestamp_stream': 754.3783433511853, + 'transform': [array([-4.80860519e+01, 9.64568558e+01, 1.74760912e-02]), + array([ 0.44242549, -50.62297821, -0.5447855 ])]} +{'AngularVelocity': array([ 3.30649726e-02, -6.17171777e-03, 6.42916822e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.8182373046875, + 'FR_Wheel_Angle': -27.943004608154297, + 'Location': array([-4.68897896e+01, 7.91411438e+01, 5.71153536e-02]), + 'Rotation': array([7.44490558e-03, 1.40153000e+02, 3.09838401e-03]), + 'Velocity': array([ 0.23360084, -0.44426748, 0.00063026]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1944.5230712890625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7472.77685547, 7718.62353516, 101.54537964]), + 'frame': 22106, + 'frame_number': 22106, + 'framesequence': 89115, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.4127846509218, + 'timestamp_carla': 754412, + 'timestamp_device': 1625014, + 'timestamp_stream': 754.4127846509218, + 'transform': [array([-4.80789528e+01, 9.64833145e+01, 1.65595822e-02]), + array([ 0.45318985, -50.54520035, -0.53910983])]} +{'AngularVelocity': array([ 0.066231 , -0.02540465, 4.77029371]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.66973114013672, + 'FR_Wheel_Angle': -23.415395736694336, + 'Location': array([-4.68576241e+01, 7.90936813e+01, 5.71013540e-02]), + 'Rotation': array([9.13879275e-03, 1.40814117e+02, 1.12602096e-02]), + 'Velocity': array([ 2.53138602e-01, -3.98610741e-01, -3.03268433e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1947.6326904296875, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7471.96582031, 7715.71142578, 101.69403076]), + 'frame': 22107, + 'frame_number': 22107, + 'framesequence': 89119, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.4448123499751, + 'timestamp_carla': 754444, + 'timestamp_device': 1625048, + 'timestamp_stream': 754.4448123499751, + 'transform': [array([-4.80727043e+01, 9.65079346e+01, 1.51575943e-02]), + array([ 0.45853791, -50.47234726, -0.53181636])]} +{'AngularVelocity': array([ 0.0177251 , -0.00409963, 3.20444965]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.58820343017578, + 'FR_Wheel_Angle': -17.98771858215332, + 'Location': array([-4.68167725e+01, 7.90416489e+01, 5.71914576e-02]), + 'Rotation': array([9.05000046e-03, 1.41411758e+02, 1.59498565e-02]), + 'Velocity': array([ 0.30254748, -0.4010081 , 0.0004108 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1950.894775390625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7471.15771484, 7712.69482422, 101.85969543]), + 'frame': 22108, + 'frame_number': 22108, + 'framesequence': 89123, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.4785842522979, + 'timestamp_carla': 754478, + 'timestamp_device': 1625081, + 'timestamp_stream': 754.4785842522979, + 'transform': [array([-4.80660553e+01, 9.65337982e+01, 1.31702321e-02]), + array([ 0.46033424, -50.39612961, -0.52226424])]} +{'AngularVelocity': array([-0.03396844, 0.00919875, 2.16386533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.353689193725586, + 'FR_Wheel_Angle': -11.905501365661621, + 'Location': array([-4.67712898e+01, 7.89914627e+01, 5.71662411e-02]), + 'Rotation': array([8.36698152e-03, 1.41857880e+02, 1.57604832e-02]), + 'Velocity': array([ 0.33916301, -0.37892345, -0.00091717]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1953.919189453125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7470.39941406, 7709.86425781, 102.09133911]), + 'frame': 22109, + 'frame_number': 22109, + 'framesequence': 89127, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.5127682499588, + 'timestamp_carla': 754512, + 'timestamp_device': 1625114, + 'timestamp_stream': 754.5127682499588, + 'transform': [array([-4.80593834e+01, 9.65597992e+01, 1.09927552e-02]), + array([ 0.46086016, -50.31949234, -0.51191837])]} +{'AngularVelocity': array([-0.01991588, -0.01028073, 1.82673955]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.3045268058776855, + 'FR_Wheel_Angle': -4.842874526977539, + 'Location': array([-4.67246704e+01, 7.89465332e+01, 5.71817271e-02]), + 'Rotation': array([8.26452859e-03, 1.42127350e+02, 1.64239909e-02]), + 'Velocity': array([ 3.73177111e-01, -3.50327432e-01, 3.61151673e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1957.11181640625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7469.6015625 , 7706.88964844, 102.4055481 ]), + 'frame': 22110, + 'frame_number': 22110, + 'framesequence': 89131, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.5463078506291, + 'timestamp_carla': 754545, + 'timestamp_device': 1625147, + 'timestamp_stream': 754.5463078506291, + 'transform': [array([-4.80528069e+01, 9.65853195e+01, 8.77781864e-03]), + array([ 0.46107191, -50.24455261, -0.50138956])]} +{'AngularVelocity': array([0.0029485 , 0.01420763, 0.49119824]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3782452642917633, + 'FR_Wheel_Angle': 0.8596492409706116, + 'Location': array([-4.66705055e+01, 7.89010162e+01, 5.71913794e-02]), + 'Rotation': array([6.93264185e-03, 1.42243347e+02, 1.65789649e-02]), + 'Velocity': array([ 4.15554076e-01, -3.32886457e-01, 1.12833972e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1960.3349609375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7468.79785156, 7703.88916016, 102.75180817]), + 'frame': 22111, + 'frame_number': 22111, + 'framesequence': 89135, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.5785777494311, + 'timestamp_carla': 754578, + 'timestamp_device': 1625181, + 'timestamp_stream': 754.5785777494311, + 'transform': [array([-4.80467072e+01, 9.66098633e+01, 6.83378195e-03]), + array([ 0.45728797, -50.17217636, -0.49259987])]} +{'AngularVelocity': array([-0.02986237, 0.03576937, 0.1408187 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1610884964466095, + 'FR_Wheel_Angle': -0.02413296513259411, + 'Location': array([-4.66153488e+01, 7.88586349e+01, 5.71686812e-02]), + 'Rotation': array([9.23441537e-03, 1.42234604e+02, 1.29815117e-02]), + 'Velocity': array([ 4.02221143e-01, -3.07140023e-01, -6.27231566e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1963.5050048828125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7468.00976562, 7700.94824219, 103.10736084]), + 'frame': 22112, + 'frame_number': 22112, + 'framesequence': 89138, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.6111224517226, + 'timestamp_carla': 754610, + 'timestamp_device': 1625206, + 'timestamp_stream': 754.6111224517226, + 'transform': [array([-4.80409317e+01, 9.66351852e+01, 5.24004921e-03]), + array([ 0.44938543, -50.09630203, -0.48597696])]} +{'AngularVelocity': array([-0.00449826, 0.02962026, -0.13450898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038129060994833708, + 'FR_Wheel_Angle': 0.003813120536506176, + 'Location': array([-4.65640030e+01, 7.88190384e+01, 5.71543016e-02]), + 'Rotation': array([1.10990563e-02, 1.42234421e+02, 8.30857735e-03]), + 'Velocity': array([ 3.63444000e-01, -2.80772150e-01, -3.65734086e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1966.5458984375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7467.24707031, 7698.10107422, 103.40622711]), + 'frame': 22113, + 'frame_number': 22113, + 'framesequence': 89142, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.6438460499048, + 'timestamp_carla': 754643, + 'timestamp_device': 1625239, + 'timestamp_stream': 754.6438460499048, + 'transform': [array([-4.80350037e+01, 9.66607590e+01, 3.83231160e-03]), + array([ 0.43986416, -50.01990891, -0.48045239])]} +{'AngularVelocity': array([-0.00252879, 0.01116783, -0.02342907]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003813963383436203, + 'FR_Wheel_Angle': 0.0038114620838314295, + 'Location': array([-4.65143929e+01, 7.87806396e+01, 5.71242794e-02]), + 'Rotation': array([1.11946799e-02, 1.42231949e+02, 6.35300204e-03]), + 'Velocity': array([ 0.35053936, -0.27114683, -0.00078614]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1969.666748046875, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7466.44433594, 7695.10546875, 103.62921143]), + 'frame': 22114, + 'frame_number': 22114, + 'framesequence': 89147, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.6782143525779, + 'timestamp_carla': 754677, + 'timestamp_device': 1625281, + 'timestamp_stream': 754.6782143525779, + 'transform': [array([-4.80286865e+01, 9.66874771e+01, 2.40808493e-03]), + array([ 0.42931151, -49.94044495, -0.47508052])]} +{'AngularVelocity': array([0.0096584 , 0.00786193, 1.12669909]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038130662869662046, + 'FR_Wheel_Angle': 0.0038133696652948856, + 'Location': array([-4.64652328e+01, 7.87425461e+01, 5.71792871e-02]), + 'Rotation': array([8.92022625e-03, 1.42232391e+02, 5.49210561e-03]), + 'Velocity': array([ 3.74232203e-01, -2.88920194e-01, 3.64065170e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1972.8311767578125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7465.63330078, 7692.07763672, 103.81328583]), + 'frame': 22115, + 'frame_number': 22115, + 'framesequence': 89151, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.7121485508978, + 'timestamp_carla': 754711, + 'timestamp_device': 1625314, + 'timestamp_stream': 754.7121485508978, + 'transform': [array([-4.80225334e+01, 9.67138290e+01, 1.03286735e-03]), + array([ 0.41890231, -49.8619957 , -0.46992221])]} +{'AngularVelocity': array([-0.03929341, -0.02890896, 0.68486732]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038097184151411057, + 'FR_Wheel_Angle': 0.0038035742472857237, + 'Location': array([-4.64168739e+01, 7.87051468e+01, 5.71813472e-02]), + 'Rotation': array([9.07732081e-03, 1.42233444e+02, 5.10583445e-03]), + 'Velocity': array([ 3.90523911e-01, -3.03516507e-01, 2.65064242e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1976.264892578125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7464.86962891, 7688.84277344, 103.98917389]), + 'frame': 22116, + 'frame_number': 22116, + 'framesequence': 89154, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.7446605488658, + 'timestamp_carla': 754744, + 'timestamp_device': 1625339, + 'timestamp_stream': 754.7446605488658, + 'transform': [array([-4.80160599e+01, 9.67414017e+01, 5.37872293e-05]), + array([ 0.40864336, -49.78044891, -0.46638158])]} +{'AngularVelocity': array([0.01415976, 0.01698192, 0.0967577 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038059393409639597, + 'FR_Wheel_Angle': 0.00380646251142025, + 'Location': array([-4.63581429e+01, 7.86596146e+01, 5.72170541e-02]), + 'Rotation': array([3.92052857e-03, 1.42220596e+02, 4.88032261e-03]), + 'Velocity': array([ 4.59090501e-01, -3.55056286e-01, 3.10635573e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1986.4036865234375, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7469.27392578, 7681.29345703, 104.10253906]), + 'frame': 22117, + 'frame_number': 22117, + 'framesequence': 89159, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.7783380523324, + 'timestamp_carla': 754777, + 'timestamp_device': 1625381, + 'timestamp_stream': 754.7783380523324, + 'transform': [array([-4.80088387e+01, 9.67700653e+01, -1.31394388e-03]), + array([ 0.39778337, -49.69681168, -0.46128431])]} +{'AngularVelocity': array([0.0196325 , 0.02333986, 0.14143555]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038088453002274036, + 'FR_Wheel_Angle': 0.00381046487018466, + 'Location': array([-4.62986946e+01, 7.86136627e+01, 5.71704358e-02]), + 'Rotation': array([8.60603806e-03, 1.42223419e+02, 4.81012277e-03]), + 'Velocity': array([ 4.18269068e-01, -3.23214740e-01, 3.03463923e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2003.93408203125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7479.16015625, 7668.92724609, 104.10253906]), + 'frame': 22118, + 'frame_number': 22118, + 'framesequence': 89162, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.8103205524385, + 'timestamp_carla': 754809, + 'timestamp_device': 1625406, + 'timestamp_stream': 754.8103205524385, + 'transform': [array([-4.80027733e+01, 9.67977524e+01, -2.78597814e-03]), + array([ 0.38755858, -49.61392975, -0.45566848])]} +{'AngularVelocity': array([ 0.0126174 , 0.01088751, -0.05379342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003811441594734788, + 'FR_Wheel_Angle': 0.0038113908376544714, + 'Location': array([-4.62447205e+01, 7.85719070e+01, 5.71501814e-02]), + 'Rotation': array([1.09419627e-02, 1.42223679e+02, 4.74875560e-03]), + 'Velocity': array([ 0.38617381, -0.29811651, -0.00041571]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2063.2392578125, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7520.71337891, 7629.51757812, 103.82310486]), + 'frame': 22119, + 'frame_number': 22119, + 'framesequence': 89166, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.8447552509606, + 'timestamp_carla': 754844, + 'timestamp_device': 1625439, + 'timestamp_stream': 754.8447552509606, + 'transform': [array([-4.79959641e+01, 9.68270416e+01, -4.39876551e-03]), + array([ 0.37651417, -49.52721024, -0.44959474])]} +{'AngularVelocity': array([-0.0025919 , -0.00328563, 0.14113638]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003811970353126526, + 'FR_Wheel_Angle': 0.003813411109149456, + 'Location': array([-4.61940460e+01, 7.85327377e+01, 5.71595654e-02]), + 'Rotation': array([1.08668301e-02, 1.42225220e+02, 4.74122725e-03]), + 'Velocity': array([ 3.80149990e-01, -2.93859273e-01, 2.78506282e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2058.556884765625, + 'focus_actor_name': 'SM_PlantPot25', + 'focus_actor_pt': array([-7513.55859375, 7631.38330078, 104.08149719]), + 'frame': 22120, + 'frame_number': 22120, + 'framesequence': 89171, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.8785138502717, + 'timestamp_carla': 754878, + 'timestamp_device': 1625481, + 'timestamp_stream': 754.8785138502717, + 'transform': [array([-4.79893494e+01, 9.68554153e+01, -6.04724884e-03]), + array([ 0.36638498, -49.44338989, -0.44321588])]} +{'AngularVelocity': array([-0.00246106, -0.0078392 , 0.19499762]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038123696576803923, + 'FR_Wheel_Angle': 0.0038131950423121452, + 'Location': array([-4.61434479e+01, 7.84936066e+01, 5.71546443e-02]), + 'Rotation': array([1.05663016e-02, 1.42226440e+02, 4.72172908e-03]), + 'Velocity': array([ 3.71953875e-01, -2.87193626e-01, 2.28691097e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2757.06884765625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8041.08203125, 7176.79248047, 98.83712006]), + 'frame': 22121, + 'frame_number': 22121, + 'framesequence': 89175, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.9120258502662, + 'timestamp_carla': 754911, + 'timestamp_device': 1625514, + 'timestamp_stream': 754.9120258502662, + 'transform': [array([-4.79830208e+01, 9.68833542e+01, -7.84386601e-03]), + array([ 0.35945234, -49.36048126, -0.4357385 ])]} +{'AngularVelocity': array([ 0.00176754, -0.00051284, 0.14057353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038135030772536993, + 'FR_Wheel_Angle': 0.0038132446352392435, + 'Location': array([-4.60952835e+01, 7.84563904e+01, 5.71678802e-02]), + 'Rotation': array([1.04023777e-02, 1.42228485e+02, 4.71326895e-03]), + 'Velocity': array([ 3.60444695e-01, -2.78423905e-01, 8.01372516e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2754.138671875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8034.50683594, 7176.79248047, 99.18556976]), + 'frame': 22122, + 'frame_number': 22122, + 'framesequence': 89178, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.9447358511388, + 'timestamp_carla': 754944, + 'timestamp_device': 1625539, + 'timestamp_stream': 754.9447358511388, + 'transform': [array([-4.79770851e+01, 9.69108582e+01, -9.21352394e-03]), + array([ 0.35221916, -49.27836227, -0.43021449])]} +{'AngularVelocity': array([ 0.00048684, -0.0003961 , 0.0257801 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038136558141559362, + 'FR_Wheel_Angle': 0.003814026480540633, + 'Location': array([-4.60471382e+01, 7.84191360e+01, 5.71686812e-02]), + 'Rotation': array([1.00813583e-02, 1.42227859e+02, 4.69167437e-03]), + 'Velocity': array([ 0.3568289 , -0.27595258, 0.0003675 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2751.24755859375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8028.03125 , 7176.79199219, 99.58525085]), + 'frame': 22123, + 'frame_number': 22123, + 'framesequence': 89183, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 754.978937651962, + 'timestamp_carla': 754978, + 'timestamp_device': 1625581, + 'timestamp_stream': 754.978937651962, + 'transform': [array([-4.79705009e+01, 9.69390411e+01, -9.75313131e-03]), + array([ 0.34938464, -49.19525528, -0.4281086 ])]} +{'AngularVelocity': array([-0.01090967, -0.00796748, -0.15782592]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812517737969756, + 'FR_Wheel_Angle': 0.0038075579795986414, + 'Location': array([-4.59984474e+01, 7.83814316e+01, 5.71548752e-02]), + 'Rotation': array([9.48713254e-03, 1.42221451e+02, 4.69362643e-03]), + 'Velocity': array([ 0.36382833, -0.28170335, -0.00046473]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2748.368896484375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8021.63867188, 7176.79248047, 99.88893127]), + 'frame': 22124, + 'frame_number': 22124, + 'framesequence': 89187, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.0122729502618, + 'timestamp_carla': 755011, + 'timestamp_device': 1625614, + 'timestamp_stream': 755.0122729502618, + 'transform': [array([-4.79642067e+01, 9.69666367e+01, -9.90319252e-03]), + array([ 0.34792298, -49.11366272, -0.42768124])]} +{'AngularVelocity': array([0.00784016, 0.01063016, 0.000317 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003809526562690735, + 'FR_Wheel_Angle': 0.0038106783758848906, + 'Location': array([-4.59436035e+01, 7.83389816e+01, 5.71898147e-02]), + 'Rotation': array([5.77150937e-03, 1.42222473e+02, 4.65579564e-03]), + 'Velocity': array([ 4.20098096e-01, -3.25452864e-01, 3.26876645e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2745.528564453125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8015.17529297, 7176.79248047, 100.01598358]), + 'frame': 22125, + 'frame_number': 22125, + 'framesequence': 89190, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17792902886867523, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.0448693521321, + 'timestamp_carla': 755044, + 'timestamp_device': 1625639, + 'timestamp_stream': 755.0448693521321, + 'transform': [array([-4.79583473e+01, 9.69937668e+01, -9.93288029e-03]), + array([ 0.3467277 , -49.03290558, -0.42783377])]} +{'AngularVelocity': array([ 0.01833114, 0.0230878 , -0.117993 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038115058559924364, + 'FR_Wheel_Angle': 0.0038090767338871956, + 'Location': array([-4.58914452e+01, 7.82985992e+01, 5.71727268e-02]), + 'Rotation': array([9.52128321e-03, 1.42219421e+02, 4.70093405e-03]), + 'Velocity': array([ 3.76387179e-01, -2.91266412e-01, -4.55474838e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2742.74462890625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8008.85058594, 7176.79296875, 100.05706024]), + 'frame': 22126, + 'frame_number': 22126, + 'framesequence': 89195, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16566058993339539, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.0786376520991, + 'timestamp_carla': 755078, + 'timestamp_device': 1625681, + 'timestamp_stream': 755.0786376520991, + 'transform': [array([-4.79516792e+01, 9.70212250e+01, -9.85970441e-03]), + array([ 0.34535483, -48.95346451, -0.42856619])]} +{'AngularVelocity': array([0.00529413, 0.00456929, 1.16756535]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003810896072536707, + 'FR_Wheel_Angle': 0.003811214119195938, + 'Location': array([-4.58376274e+01, 7.82570114e+01, 5.71826808e-02]), + 'Rotation': array([8.05962272e-03, 1.42234222e+02, 4.73526213e-03]), + 'Velocity': array([ 4.07783300e-01, -3.15277368e-01, 6.35337783e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2739.978271484375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-8002.61914062, 7176.79248047, 100.0684433 ]), + 'frame': 22127, + 'frame_number': 22127, + 'framesequence': 89199, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14357738196849823, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.1109056510031, + 'timestamp_carla': 755110, + 'timestamp_device': 1625714, + 'timestamp_stream': 755.1109056510031, + 'transform': [array([-4.79446373e+01, 9.70463181e+01, -9.82521009e-03]), + array([ 0.34328529, -48.88420486, -0.42917648])]} +{'AngularVelocity': array([0.01342804, 0.01565344, 1.15213728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003811221569776535, + 'FR_Wheel_Angle': 0.0038101018872112036, + 'Location': array([-4.57857552e+01, 7.82168121e+01, 5.71678802e-02]), + 'Rotation': array([1.01633212e-02, 1.42232697e+02, 4.64423327e-03]), + 'Velocity': array([ 3.74000132e-01, -2.90054351e-01, 1.57761577e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2737.388916015625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7996.49951172, 7176.79248047, 100.0478363 ]), + 'frame': 22128, + 'frame_number': 22128, + 'framesequence': 89203, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12105472385883331, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.1448628492653, + 'timestamp_carla': 755144, + 'timestamp_device': 1625747, + 'timestamp_stream': 755.1448628492653, + 'transform': [array([-4.79356537e+01, 9.70706635e+01, -9.74418595e-03]), + array([ 0.34105182, -48.82352829, -0.43009192])]} +{'AngularVelocity': array([-0.01214827, 0.00138429, 0.9926182 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003809822490438819, + 'FR_Wheel_Angle': 0.0038111323956400156, + 'Location': array([-4.57321053e+01, 7.81753082e+01, 5.71720004e-02]), + 'Rotation': array([8.11426435e-03, 1.42228165e+02, 4.48745815e-03]), + 'Velocity': array([ 4.09726948e-01, -3.19792300e-01, -2.75020604e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2735.31591796875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7991.17675781, 7176.79248047, 100.03039551]), + 'frame': 22129, + 'frame_number': 22129, + 'framesequence': 89206, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09919127076864243, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.1768659502268, + 'timestamp_carla': 755176, + 'timestamp_device': 1625772, + 'timestamp_stream': 755.1768659502268, + 'transform': [array([-4.79262505e+01, 9.70922928e+01, -1.02039427e-02]), + array([ 0.33391428, -48.77457428, -0.4289929 ])]} +{'AngularVelocity': array([0.00541251, 0.01643049, 0.92494386]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812517737969756, + 'FR_Wheel_Angle': 0.003812868380919099, + 'Location': array([-4.56801682e+01, 7.81350555e+01, 5.71669266e-02]), + 'Rotation': array([1.01974718e-02, 1.42228485e+02, 4.65855049e-03]), + 'Velocity': array([ 3.75128180e-01, -2.91433215e-01, 4.46510312e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2733.867919921875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7986.50878906, 7176.79199219, 99.99202728]), + 'frame': 22130, + 'frame_number': 22130, + 'framesequence': 89211, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0940641537308693, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.2113693505526, + 'timestamp_carla': 755210, + 'timestamp_device': 1625814, + 'timestamp_stream': 755.2113693505526, + 'transform': [array([-4.79154816e+01, 9.71148605e+01, -1.12409685e-02]), + array([ 0.32301328, -48.72687149, -0.42572695])]} +{'AngularVelocity': array([ 0.006558 , 0.00937886, -1.48085904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038143331184983253, + 'FR_Wheel_Angle': 0.0038129871245473623, + 'Location': array([-4.56316872e+01, 7.80974274e+01, 5.71094006e-02]), + 'Rotation': array([1.07165659e-02, 1.42217102e+02, 4.79798904e-03]), + 'Velocity': array([ 0.36215344, -0.27982426, -0.00133386]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2733.000732421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7982.74267578, 7176.79248047, 100.05496216]), + 'frame': 22131, + 'frame_number': 22131, + 'framesequence': 89215, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10206610709428787, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.2448058500886, + 'timestamp_carla': 755244, + 'timestamp_device': 1625847, + 'timestamp_stream': 755.2448058500886, + 'transform': [array([-4.79053688e+01, 9.71369476e+01, -1.25002377e-02]), + array([ 0.31230354, -48.679039 , -0.42130145])]} +{'AngularVelocity': array([-0.02272552, -0.01999501, -0.010917 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00381199037656188, + 'FR_Wheel_Angle': 0.0038126332219690084, + 'Location': array([-4.55827332e+01, 7.80595322e+01, 5.71493432e-02]), + 'Rotation': array([9.45981126e-03, 1.42209274e+02, 4.79873130e-03]), + 'Velocity': array([ 0.38327509, -0.29686713, 0.00163288]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2732.381103515625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7979.07470703, 7176.79296875, 100.22529602]), + 'frame': 22132, + 'frame_number': 22132, + 'framesequence': 89218, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11565294861793518, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.2768781520426, + 'timestamp_carla': 755276, + 'timestamp_device': 1625872, + 'timestamp_stream': 755.2768781520426, + 'transform': [array([-4.78961525e+01, 9.71588364e+01, -1.38089657e-02]), + array([ 0.30305547, -48.62914658, -0.41635719])]} +{'AngularVelocity': array([-0.01861213, 0.00038443, 0.05129736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003811221569776535, + 'FR_Wheel_Angle': 0.003812151961028576, + 'Location': array([-4.55324554e+01, 7.80206604e+01, 5.71395755e-02]), + 'Rotation': array([8.12792499e-03, 1.42205032e+02, 4.68963059e-03]), + 'Velocity': array([ 0.39192718, -0.30515769, -0.00093606]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2731.688232421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7975.40917969, 7176.79199219, 100.45596313]), + 'frame': 22133, + 'frame_number': 22133, + 'framesequence': 89223, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12810449302196503, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.3111974522471, + 'timestamp_carla': 755310, + 'timestamp_device': 1625914, + 'timestamp_stream': 755.3111974522471, + 'transform': [array([-4.78871269e+01, 9.71835556e+01, -1.53065203e-02]), + array([ 0.29375276, -48.56858826, -0.41058886])]} +{'AngularVelocity': array([ 0.00748629, 0.00960614, -0.17337167]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038141615223139524, + 'FR_Wheel_Angle': 0.0038134765345603228, + 'Location': array([-4.54821510e+01, 7.79816132e+01, 5.71163446e-02]), + 'Rotation': array([9.93109494e-03, 1.42198517e+02, 4.66655288e-03]), + 'Velocity': array([ 0.36249208, -0.28080004, -0.00083744]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2730.796630859375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7971.59179688, 7176.79248047, 100.71447754]), + 'frame': 22134, + 'frame_number': 22134, + 'framesequence': 89227, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13348796963691711, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.345185149461, + 'timestamp_carla': 755344, + 'timestamp_device': 1625947, + 'timestamp_stream': 755.345185149461, + 'transform': [array([-4.78784752e+01, 9.72083359e+01, -1.68376248e-02]), + array([ 0.28438857, -48.50646591, -0.40460697])]} +{'AngularVelocity': array([-0.01506802, -0.0235145 , 0.04320694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003813103074207902, + 'FR_Wheel_Angle': 0.003811021102592349, + 'Location': array([-4.54333153e+01, 7.79437943e+01, 5.71197383e-02]), + 'Rotation': array([9.39150993e-03, 1.42205856e+02, 4.72495565e-03]), + 'Velocity': array([ 0.38127494, -0.29488191, -0.0007851 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2729.443359375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7966.97167969, 7176.79296875, 101.01571655]), + 'frame': 22135, + 'frame_number': 22135, + 'framesequence': 89230, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.130027174949646, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.3770544491708, + 'timestamp_carla': 755376, + 'timestamp_device': 1625972, + 'timestamp_stream': 755.3770544491708, + 'transform': [array([-4.78706398e+01, 9.72316208e+01, -1.82913113e-02]), + array([ 0.27535224, -48.44744873, -0.39886937])]} +{'AngularVelocity': array([-0.05381229, -0.07596033, -0.07773945]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038052923046052456, + 'FR_Wheel_Angle': 0.0038061088416725397, + 'Location': array([-4.53820801e+01, 7.79040909e+01, 5.71315289e-02]), + 'Rotation': array([6.46135863e-03, 1.42201874e+02, 4.83809970e-03]), + 'Velocity': array([ 4.47150588e-01, -3.44733715e-01, 4.97531873e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2727.97998046875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7962.234375 , 7176.79296875, 101.32969666]), + 'frame': 22136, + 'frame_number': 22136, + 'framesequence': 89235, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12418592721223831, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.4120581522584, + 'timestamp_carla': 755411, + 'timestamp_device': 1626014, + 'timestamp_stream': 755.4120581522584, + 'transform': [array([-4.78617287e+01, 9.72569504e+01, -1.99274346e-02]), + array([ 0.26637736, -48.384552 , -0.39236876])]} +{'AngularVelocity': array([0.01431704, 0.0229244 , 0.40260327]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00380873354151845, + 'FR_Wheel_Angle': 0.0038094318006187677, + 'Location': array([-4.53203926e+01, 7.78563614e+01, 5.72116375e-02]), + 'Rotation': array([6.67309435e-03, 1.42203598e+02, 4.71048383e-03]), + 'Velocity': array([ 4.27668780e-01, -3.31495166e-01, -2.87513714e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2726.557861328125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7957.74804688, 7176.79248047, 101.63227081]), + 'frame': 22137, + 'frame_number': 22137, + 'framesequence': 89239, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11684317141771317, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.4444031491876, + 'timestamp_carla': 755443, + 'timestamp_device': 1626047, + 'timestamp_stream': 755.4444031491876, + 'transform': [array([-4.78524590e+01, 9.72782974e+01, -2.19098944e-02]), + array([ 0.26466981, -48.33637238, -0.38327429])]} +{'AngularVelocity': array([ 0.00868127, 0.00685948, -0.38954815]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038105237763375044, + 'FR_Wheel_Angle': 0.0038110301829874516, + 'Location': array([-4.52680931e+01, 7.78158875e+01, 5.71283996e-02]), + 'Rotation': array([9.58958548e-03, 1.42202606e+02, 4.74657863e-03]), + 'Velocity': array([ 0.4023031 , -0.31075427, -0.00076973]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2725.1279296875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7952.97167969, 7176.79296875, 101.96998596]), + 'frame': 22138, + 'frame_number': 22138, + 'framesequence': 89243, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11349223554134369, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.4790718518198, + 'timestamp_carla': 755478, + 'timestamp_device': 1626081, + 'timestamp_stream': 755.4790718518198, + 'transform': [array([-4.78428307e+01, 9.73014145e+01, -2.43342780e-02]), + array([ 0.2677229 , -48.28360367, -0.37155551])]} +{'AngularVelocity': array([0.01365951, 0.0235512 , 0.80790311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003808851120993495, + 'FR_Wheel_Angle': 0.0038104653358459473, + 'Location': array([-4.52145309e+01, 7.77743759e+01, 5.71575053e-02]), + 'Rotation': array([9.86279268e-03, 1.42204437e+02, 4.53453092e-03]), + 'Velocity': array([ 3.85189801e-01, -2.99942940e-01, -1.28221509e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2724.354248046875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7949.31005859, 7176.79199219, 102.42745972]), + 'frame': 22139, + 'frame_number': 22139, + 'framesequence': 89247, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11537828296422958, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.5131886489689, + 'timestamp_carla': 755512, + 'timestamp_device': 1626114, + 'timestamp_stream': 755.5131886489689, + 'transform': [array([-4.78331223e+01, 9.73234558e+01, -2.68605612e-02]), + array([ 0.27206007, -48.23481369, -0.35910437])]} +{'AngularVelocity': array([ 0.00267655, -0.00414674, -0.40763015]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038039912469685078, + 'FR_Wheel_Angle': 0.003801667597144842, + 'Location': array([-4.51603317e+01, 7.77324905e+01, 5.71382418e-02]), + 'Rotation': array([7.17852823e-03, 1.42210739e+02, 4.86655068e-03]), + 'Velocity': array([ 0.43627104, -0.33624232, 0.00057773]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2723.481201171875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7945.33496094, 7176.79296875, 103.01086426]), + 'frame': 22140, + 'frame_number': 22140, + 'framesequence': 89251, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1186559721827507, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.5444789491594, + 'timestamp_carla': 755543, + 'timestamp_device': 1626147, + 'timestamp_stream': 755.5444789491594, + 'transform': [array([-4.78244781e+01, 9.73436890e+01, -2.91703511e-02]), + array([ 0.27660215, -48.18938446, -0.34750772])]} +{'AngularVelocity': array([0.01562094, 0.02039853, 0.03743679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003803645959123969, + 'FR_Wheel_Angle': 0.003804295090958476, + 'Location': array([-4.50993156e+01, 7.76850967e+01, 5.72350584e-02]), + 'Rotation': array([5.07483026e-03, 1.42189011e+02, 4.60288627e-03]), + 'Velocity': array([ 4.78924394e-01, -3.71354222e-01, 3.52606759e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2722.78955078125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7941.6640625 , 7176.79248047, 103.62931824]), + 'frame': 22141, + 'frame_number': 22141, + 'framesequence': 89255, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12175054848194122, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.5790664516389, + 'timestamp_carla': 755578, + 'timestamp_device': 1626181, + 'timestamp_stream': 755.5790664516389, + 'transform': [array([-4.78155327e+01, 9.73669586e+01, -3.17130461e-02]), + array([ 0.28228489, -48.13434601, -0.33475131])]} +{'AngularVelocity': array([0.01912409, 0.02541001, 0.23704651]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003806711407378316, + 'FR_Wheel_Angle': 0.003807021537795663, + 'Location': array([-4.50388756e+01, 7.76382828e+01, 5.71921058e-02]), + 'Rotation': array([9.02950950e-03, 1.42190262e+02, 4.68503498e-03]), + 'Velocity': array([ 4.42268312e-01, -3.42638612e-01, 1.76854126e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2722.10107421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7938.25097656, 7176.79296875, 104.20787048]), + 'frame': 22142, + 'frame_number': 22142, + 'framesequence': 89258, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12250129878520966, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.6101368516684, + 'timestamp_carla': 755609, + 'timestamp_device': 1626206, + 'timestamp_stream': 755.6101368516684, + 'transform': [array([-4.78070145e+01, 9.73866577e+01, -3.39888558e-02]), + array([ 0.28637615, -48.09030914, -0.32333776])]} +{'AngularVelocity': array([-0.00414277, -0.00343443, 0.43960124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003806539112702012, + 'FR_Wheel_Angle': 0.0038070036098361015, + 'Location': array([-4.49797401e+01, 7.75924835e+01, 5.71557507e-02]), + 'Rotation': array([1.00608682e-02, 1.42190979e+02, 4.68522776e-03]), + 'Velocity': array([ 4.38268691e-01, -3.39674324e-01, -3.17554455e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2721.091552734375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7934.13867188, 7176.79248047, 104.84365845]), + 'frame': 22143, + 'frame_number': 22143, + 'framesequence': 89262, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12103641033172607, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.6437562517822, + 'timestamp_carla': 755643, + 'timestamp_device': 1626239, + 'timestamp_stream': 755.6437562517822, + 'transform': [array([-4.77983589e+01, 9.74085541e+01, -3.60491090e-02]), + array([ 0.28908774, -48.03931427, -0.31317535])]} +{'AngularVelocity': array([-0.00222222, -0.00168492, 0.41518432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038069935981184244, + 'FR_Wheel_Angle': 0.0038068885914981365, + 'Location': array([-4.49218254e+01, 7.75476151e+01, 5.71664311e-02]), + 'Rotation': array([1.00608682e-02, 1.42190094e+02, 4.68480727e-03]), + 'Velocity': array([ 4.31563944e-01, -3.34463596e-01, -4.70638261e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2720.4482421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7930.83056641, 7176.79248047, 105.41358948]), + 'frame': 22144, + 'frame_number': 22144, + 'framesequence': 89266, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11922361701726913, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.6769913509488, + 'timestamp_carla': 755676, + 'timestamp_device': 1626272, + 'timestamp_stream': 755.6769913509488, + 'transform': [array([-4.77901649e+01, 9.74312668e+01, -3.66826430e-02]), + array([ 0.28972977, -47.98432922, -0.30991 ])]} +{'AngularVelocity': array([-0.07430044, -0.09572712, -0.71791923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037913492415100336, + 'FR_Wheel_Angle': 0.0037930284161120653, + 'Location': array([-4.48570557e+01, 7.74972992e+01, 5.72015271e-02]), + 'Rotation': array([3.59950960e-03, 1.42175293e+02, 4.67266887e-03]), + 'Velocity': array([ 5.76497972e-01, -4.46845263e-01, 3.83543957e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2719.56103515625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7927.01660156, 7176.79296875, 105.92208099]), + 'frame': 22145, + 'frame_number': 22145, + 'framesequence': 89271, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11876583099365234, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.7109194509685, + 'timestamp_carla': 755710, + 'timestamp_device': 1626314, + 'timestamp_stream': 755.7109194509685, + 'transform': [array([-4.77815742e+01, 9.74544144e+01, -3.68006714e-02]), + array([ 0.28915605, -47.9289856 , -0.30936065])]} +{'AngularVelocity': array([ 0.03271406, 0.04218926, -0.0025246 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003796021221205592, + 'FR_Wheel_Angle': 0.0037970971316099167, + 'Location': array([-4.47810440e+01, 7.74384003e+01, 5.72156049e-02]), + 'Rotation': array([3.11456621e-03, 1.42176086e+02, 4.70789336e-03]), + 'Velocity': array([ 5.67552507e-01, -4.39821690e-01, -1.39112468e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2718.452880859375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7922.90820312, 7176.79248047, 106.09356689]), + 'frame': 22146, + 'frame_number': 22146, + 'framesequence': 89274, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11960814148187637, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.7436363510787, + 'timestamp_carla': 755743, + 'timestamp_device': 1626339, + 'timestamp_stream': 755.7436363510787, + 'transform': [array([-4.77730026e+01, 9.74768143e+01, -3.66976932e-02]), + array([ 0.28813833, -47.87619781, -0.30997097])]} +{'AngularVelocity': array([0.0156023 , 0.02018586, 0.0012362 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003798638004809618, + 'FR_Wheel_Angle': 0.0037991702556610107, + 'Location': array([-4.47078934e+01, 7.73817139e+01, 5.71787544e-02]), + 'Rotation': array([8.40113219e-03, 1.42176086e+02, 4.70286189e-03]), + 'Velocity': array([ 5.36371231e-01, -4.15661663e-01, 9.71698755e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2717.376708984375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7918.76806641, 7176.79248047, 106.12830353]), + 'frame': 22147, + 'frame_number': 22147, + 'framesequence': 89278, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12041383236646652, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.7776042521, + 'timestamp_carla': 755777, + 'timestamp_device': 1626372, + 'timestamp_stream': 755.7776042521, + 'transform': [array([-4.77641068e+01, 9.75000381e+01, -3.65888216e-02]), + array([ 0.28707284, -47.82143021, -0.31079489])]} +{'AngularVelocity': array([0.00344737, 0.0047109 , 0.07120691]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038000044878572226, + 'FR_Wheel_Angle': 0.0038006361573934555, + 'Location': array([-4.46375084e+01, 7.73271637e+01, 5.71632646e-02]), + 'Rotation': array([1.02452831e-02, 1.42176331e+02, 4.69961762e-03]), + 'Velocity': array([ 5.18322110e-01, -4.01706576e-01, 3.42082967e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2716.3994140625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7914.81738281, 7176.79296875, 106.10430908]), + 'frame': 22148, + 'frame_number': 22148, + 'framesequence': 89283, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12030397355556488, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.81123945117, + 'timestamp_carla': 755810, + 'timestamp_device': 1626414, + 'timestamp_stream': 755.81123945117, + 'transform': [array([-4.77554207e+01, 9.75231781e+01, -3.64936329e-02]), + array([ 0.28585705, -47.76649857, -0.3116188 ])]} +{'AngularVelocity': array([-0.00159082, -0.00204743, -0.05700192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003801231039687991, + 'FR_Wheel_Angle': 0.003801673650741577, + 'Location': array([-4.45699615e+01, 7.72748260e+01, 5.71652874e-02]), + 'Rotation': array([1.07029062e-02, 1.42176193e+02, 4.70284652e-03]), + 'Velocity': array([ 5.05011797e-01, -3.91348034e-01, 3.35597979e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2715.389892578125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7910.72119141, 7176.79296875, 106.06629181]), + 'frame': 22149, + 'frame_number': 22149, + 'framesequence': 89286, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11982788145542145, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.8437373489141, + 'timestamp_carla': 755843, + 'timestamp_device': 1626439, + 'timestamp_stream': 755.8437373489141, + 'transform': [array([-4.77471771e+01, 9.75456848e+01, -3.64153944e-02]), + array([ 0.28460714, -47.71263504, -0.31235126])]} +{'AngularVelocity': array([-0.00330346, -0.00391121, -0.01399593]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003802340244874358, + 'FR_Wheel_Angle': 0.0038022224325686693, + 'Location': array([-4.45036278e+01, 7.72234192e+01, 5.71689494e-02]), + 'Rotation': array([1.05936229e-02, 1.42176331e+02, 4.69815731e-03]), + 'Velocity': array([ 4.95199233e-01, -3.83829057e-01, 1.87911981e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2714.361328125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7906.62158203, 7176.79248047, 106.02725983]), + 'frame': 22150, + 'frame_number': 22150, + 'framesequence': 89291, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.878341652453, + 'timestamp_carla': 755877, + 'timestamp_device': 1626481, + 'timestamp_stream': 755.878341652453, + 'transform': [array([-4.77381783e+01, 9.75697250e+01, -3.63039114e-02]), + array([ 0.28337771, -47.65568161, -0.31332779])]} +{'AngularVelocity': array([ 0.21227343, 0.27390286, -0.00033472]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.44435158e+01, 7.71768265e+01, 5.71140163e-02]), + 'Rotation': array([1.85781140e-02, 1.42176285e+02, 4.69310768e-03]), + 'Velocity': array([ 2.20048442e-01, -1.70543954e-01, -2.62832637e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2713.3271484375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7902.609375 , 7176.79248047, 105.99334717]), + 'frame': 22151, + 'frame_number': 22151, + 'framesequence': 89295, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.9108547493815, + 'timestamp_carla': 755910, + 'timestamp_device': 1626514, + 'timestamp_stream': 755.9108547493815, + 'transform': [array([-4.77300529e+01, 9.75924988e+01, -3.62991132e-02]), + array([ 0.2819775 , -47.60074997, -0.31375498])]} +{'AngularVelocity': array([ 1.41991135e-02, 1.84018947e-02, -3.75358613e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.44559364e+01, 7.71864471e+01, 5.69467433e-02]), + 'Rotation': array([4.77498509e-02, 1.42176361e+02, 4.67157923e-03]), + 'Velocity': array([-2.52900571e-01, 1.96003109e-01, -4.87327543e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2712.277099609375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7898.36865234, 7176.79296875, 105.94543457]), + 'frame': 22152, + 'frame_number': 22152, + 'framesequence': 89298, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.9444694519043, + 'timestamp_carla': 755944, + 'timestamp_device': 1626539, + 'timestamp_stream': 755.9444694519043, + 'transform': [array([-4.77214737e+01, 9.76161499e+01, -3.62500288e-02]), + array([ 0.28074807, -47.5442009 , -0.31439584])]} +{'AngularVelocity': array([-7.16943890e-02, -9.23555344e-02, -4.70038322e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.44973526e+01, 7.72185516e+01, 5.70078567e-02]), + 'Rotation': array([3.69103402e-02, 1.42176468e+02, 4.68003890e-03]), + 'Velocity': array([-3.35546911e-01, 2.60055780e-01, 4.46796403e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2711.209716796875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7894.29101562, 7176.79296875, 105.92627716]), + 'frame': 22153, + 'frame_number': 22153, + 'framesequence': 89303, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 755.9770648516715, + 'timestamp_carla': 755976, + 'timestamp_device': 1626581, + 'timestamp_stream': 755.9770648516715, + 'transform': [array([-4.77132072e+01, 9.76390686e+01, -3.64803672e-02]), + array([ 0.28346649, -47.48926926, -0.31323624])]} +{'AngularVelocity': array([-5.19957468e-02, -6.71218932e-02, 1.67935025e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.45422935e+01, 7.72533722e+01, 5.70899099e-02]), + 'Rotation': array([2.30040755e-02, 1.42176636e+02, 4.69254376e-03]), + 'Velocity': array([-3.36150169e-01, 2.60523021e-01, -1.99460977e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2710.147216796875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7890.09765625, 7176.79296875, 105.89624023]), + 'frame': 22154, + 'frame_number': 22154, + 'framesequence': 89307, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.011459749192, + 'timestamp_carla': 756011, + 'timestamp_device': 1626614, + 'timestamp_stream': 756.011459749192, + 'transform': [array([-4.77036400e+01, 9.76617966e+01, -3.79338525e-02]), + array([ 0.30440786, -47.43825531, -0.30420351])]} +{'AngularVelocity': array([-2.71276031e-02, -3.49455029e-02, 2.86070076e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.45861206e+01, 7.72873306e+01, 5.71378991e-02]), + 'Rotation': array([1.46849062e-02, 1.42176743e+02, 4.69888886e-03]), + 'Velocity': array([-3.21498513e-01, 2.49167338e-01, -1.32684698e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2709.125732421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7886.04101562, 7176.79296875, 105.95103455]), + 'frame': 22155, + 'frame_number': 22155, + 'framesequence': 89311, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.0449942499399, + 'timestamp_carla': 756044, + 'timestamp_device': 1626647, + 'timestamp_stream': 756.0449942499399, + 'transform': [array([-4.76941605e+01, 9.76834488e+01, -3.99356261e-02]), + array([ 0.32994592, -47.39095306, -0.29184446])]} +{'AngularVelocity': array([-1.24982512e-02, -1.62384585e-02, 3.10288056e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003844689577817917, + 'FR_Wheel_Angle': 0.0038453242741525173, + 'Location': array([-4.46276550e+01, 7.73195190e+01, 5.71596809e-02]), + 'Rotation': array([1.06209433e-02, 1.42176880e+02, 4.70137177e-03]), + 'Velocity': array([-3.04726183e-01, 2.36168623e-01, -8.23688461e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2708.451904296875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7882.29980469, 7176.79248047, 106.37477112]), + 'frame': 22156, + 'frame_number': 22156, + 'framesequence': 89314, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.0773083493114, + 'timestamp_carla': 756076, + 'timestamp_device': 1626672, + 'timestamp_stream': 756.0773083493114, + 'transform': [array([-4.76853104e+01, 9.77045212e+01, -4.21152860e-02]), + array([ 0.35672027, -47.34415817, -0.27832574])]} +{'AngularVelocity': array([ 2.80179288e-02, 3.61550227e-02, -8.20783555e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451857399195433, + 'FR_Wheel_Angle': 0.003845329163596034, + 'Location': array([-4.46307564e+01, 7.73219299e+01, 5.72547056e-02]), + 'Rotation': array([-6.89849071e-03, 1.42177002e+02, 4.71615512e-03]), + 'Velocity': array([ 2.54089118e-05, -1.99594579e-05, -1.87540049e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2707.94091796875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7878.85644531, 7176.79199219, 106.96108246]), + 'frame': 22157, + 'frame_number': 22157, + 'framesequence': 89318, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.1102372519672, + 'timestamp_carla': 756109, + 'timestamp_device': 1626705, + 'timestamp_stream': 756.1102372519672, + 'transform': [array([-4.76761208e+01, 9.77251358e+01, -4.45701778e-02]), + array([ 0.38210124, -47.29997253, -0.26364729])]} +{'AngularVelocity': array([ 3.01582944e-02, 3.89948636e-02, -2.79726493e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451869040727615, + 'FR_Wheel_Angle': 0.0038453303277492523, + 'Location': array([-4.46307983e+01, 7.73219528e+01, 5.72196841e-02]), + 'Rotation': array([7.10339635e-04, 1.42177124e+02, 4.71012108e-03]), + 'Velocity': array([ 2.71217341e-05, -2.11729202e-05, 6.72245005e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2707.390625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7875.46875 , 7176.79296875, 107.60753632]), + 'frame': 22158, + 'frame_number': 22158, + 'framesequence': 89323, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.1454894505441, + 'timestamp_carla': 756145, + 'timestamp_device': 1626747, + 'timestamp_stream': 756.1454894505441, + 'transform': [array([-4.76665421e+01, 9.77473145e+01, -4.78688814e-02]), + array([ 0.4046272 , -47.25175858, -0.24530642])]} +{'AngularVelocity': array([1.69992130e-02, 2.20040139e-02, 4.16035881e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46309891e+01, 7.73220978e+01, 5.72034717e-02]), + 'Rotation': array([5.50513202e-03, 1.42177124e+02, 4.70596598e-03]), + 'Velocity': array([-0.00434992, 0.00337134, 0.00044354]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2706.989990234375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7872.27050781, 7176.79248047, 108.31145477]), + 'frame': 22159, + 'frame_number': 22159, + 'framesequence': 89326, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.1770154498518, + 'timestamp_carla': 756176, + 'timestamp_device': 1626772, + 'timestamp_stream': 756.1770154498518, + 'transform': [array([-4.76594620e+01, 9.77695389e+01, -5.09843342e-02]), + array([ 0.42223543, -47.19715881, -0.22818618])]} +{'AngularVelocity': array([6.58830721e-03, 8.51459987e-03, 4.21864684e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46318779e+01, 7.73227768e+01, 5.71718477e-02]), + 'Rotation': array([7.87520781e-03, 1.42177124e+02, 4.70393384e-03]), + 'Velocity': array([-7.60157732e-03, 5.89142647e-03, 8.74710095e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2706.5048828125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7868.78076172, 7176.79296875, 109.19995117]), + 'frame': 22160, + 'frame_number': 22160, + 'framesequence': 89330, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.2106252498925, + 'timestamp_carla': 756210, + 'timestamp_device': 1626805, + 'timestamp_stream': 756.2106252498925, + 'transform': [array([-4.76504326e+01, 9.77945175e+01, -5.42202555e-02]), + array([ 0.44210446, -47.13875961, -0.21005882])]} +{'AngularVelocity': array([2.59119109e-03, 3.35633638e-03, 1.01200662e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46328888e+01, 7.73235703e+01, 5.71659356e-02]), + 'Rotation': array([8.70166067e-03, 1.42177124e+02, 4.70488705e-03]), + 'Velocity': array([-0.00785962, 0.00609141, -0.00036481]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2705.5068359375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7864.86767578, 7176.79296875, 110.03927612]), + 'frame': 22161, + 'frame_number': 22161, + 'framesequence': 89334, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.2442777492106, + 'timestamp_carla': 756243, + 'timestamp_device': 1626839, + 'timestamp_stream': 756.2442777492106, + 'transform': [array([-4.76408348e+01, 9.78193817e+01, -5.79115190e-02]), + array([ 0.46228084, -47.08223343, -0.18982556])]} +{'AngularVelocity': array([1.10389397e-03, 1.46443292e-03, 1.76480572e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46338768e+01, 7.73243408e+01, 5.71726896e-02]), + 'Rotation': array([8.80411360e-03, 1.42177124e+02, 4.70519811e-03]), + 'Velocity': array([-7.49584520e-03, 5.80948265e-03, -2.33077990e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2704.6298828125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7860.67675781, 7176.79296875, 110.9282074 ]), + 'frame': 22162, + 'frame_number': 22162, + 'framesequence': 89339, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.2773723490536, + 'timestamp_carla': 756276, + 'timestamp_device': 1626880, + 'timestamp_stream': 756.2773723490536, + 'transform': [array([-4.76318169e+01, 9.78437195e+01, -6.06284887e-02]), + array([ 0.46343514, -47.02620316, -0.176489 ])]} +{'AngularVelocity': array([6.90398156e-04, 8.85883812e-04, 2.42882403e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46348267e+01, 7.73250809e+01, 5.71652502e-02]), + 'Rotation': array([8.80411360e-03, 1.42177124e+02, 4.70519811e-03]), + 'Velocity': array([-0.00717111, 0.0055578 , -0.0002545 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2703.895263671875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7856.61474609, 7176.79296875, 111.91846466]), + 'frame': 22163, + 'frame_number': 22163, + 'framesequence': 89343, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.31070465222, + 'timestamp_carla': 756310, + 'timestamp_device': 1626914, + 'timestamp_stream': 756.31070465222, + 'transform': [array([-4.76227341e+01, 9.78677597e+01, -6.26723543e-02]), + array([ 0.45642054, -46.97122574, -0.16745533])]} +{'AngularVelocity': array([-0.00185745, -0.00236986, -0.00010234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71711622e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-5.22580376e-05, 4.09109525e-05, 1.37977593e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2703.0703125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7852.546875 , 7176.79296875, 112.58551025]), + 'frame': 22164, + 'frame_number': 22164, + 'framesequence': 89347, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.3446373492479, + 'timestamp_carla': 756344, + 'timestamp_device': 1626947, + 'timestamp_stream': 756.3446373492479, + 'transform': [array([-4.76140862e+01, 9.78925095e+01, -6.43561035e-02]), + array([ 0.44628453, -46.91275406, -0.16064948])]} +{'AngularVelocity': array([ 9.91588808e-04, 1.28933450e-03, -6.52113231e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71559034e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-3.25601904e-05, 2.55806171e-05, 4.78382106e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2702.259765625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7848.52197266, 7176.79296875, 113.04418182]), + 'frame': 22165, + 'frame_number': 22165, + 'framesequence': 89350, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.3773532509804, + 'timestamp_carla': 756376, + 'timestamp_device': 1626972, + 'timestamp_stream': 756.3773532509804, + 'transform': [array([-4.76055984e+01, 9.79158096e+01, -6.57734200e-02]), + array([ 0.43569773, -46.85859299, -0.15521695])]} +{'AngularVelocity': array([6.14351593e-04, 7.00573495e-04, 7.60258558e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71860000e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 3.66272559e-07, -3.35509469e-07, 3.12714576e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2701.26904296875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7844.24609375, 7176.79296875, 113.39300537]), + 'frame': 22166, + 'frame_number': 22166, + 'framesequence': 89355, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.4107246510684, + 'timestamp_carla': 756410, + 'timestamp_device': 1627014, + 'timestamp_stream': 756.4107246510684, + 'transform': [array([-4.75971413e+01, 9.79421539e+01, -6.68161288e-02]), + array([ 0.42416155, -46.79442215, -0.15158503])]} +{'AngularVelocity': array([2.70620920e-04, 3.39194317e-04, 8.09521589e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71762361e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 2.76247476e-07, -1.76142493e-07, 1.89805025e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1903.541015625, + 'focus_actor_name': 'BP_StreetLight_simple18_45', + 'focus_actor_pt': array([-7258.84130859, 7721.70068359, 115.8317337 ]), + 'frame': 22167, + 'frame_number': 22167, + 'framesequence': 89359, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.4439523518085, + 'timestamp_carla': 756443, + 'timestamp_device': 1627047, + 'timestamp_stream': 756.4439523518085, + 'transform': [array([-4.75879593e+01, 9.79684753e+01, -6.80176988e-02]), + array([ 0.41210628, -46.7324028 , -0.14737323])]} +{'AngularVelocity': array([9.29165617e-05, 1.69350198e-04, 5.15299034e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71622364e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 1.94423842e-06, -5.70793645e-07, 2.17552180e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1903.9202880859375, + 'focus_actor_name': 'BP_StreetLight_simple18_45', + 'focus_actor_pt': array([-7255.93115234, 7721.26953125, 115.9716568 ]), + 'frame': 22168, + 'frame_number': 22168, + 'framesequence': 89363, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.4767568521202, + 'timestamp_carla': 756476, + 'timestamp_device': 1627080, + 'timestamp_stream': 756.4767568521202, + 'transform': [array([-4.75792160e+01, 9.79945068e+01, -6.93823770e-02]), + array([ 0.40038568, -46.67012405, -0.1424596 ])]} +{'AngularVelocity': array([2.65252966e-05, 7.47098311e-05, 7.91384780e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71591072e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 3.24807388e-06, -9.74845420e-07, -3.94020084e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1905.1768798828125, + 'focus_actor_name': 'BP_StreetLight_simple18_45', + 'focus_actor_pt': array([-7253.65966797, 7720.32763672, 116.12783813]), + 'frame': 22169, + 'frame_number': 22169, + 'framesequence': 89367, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11973632872104645, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.5101693496108, + 'timestamp_carla': 756509, + 'timestamp_device': 1627114, + 'timestamp_stream': 756.5101693496108, + 'transform': [array([-4.75702820e+01, 9.80207138e+01, -7.08559677e-02]), + array([ 0.3886036 , -46.60783386, -0.13711867])]} +{'AngularVelocity': array([-2.56873682e-05, 9.14985139e-05, 1.41228491e-03]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71707413e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 5.13880559e-06, -1.40233908e-06, -3.35216500e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1907.9664306640625, + 'focus_actor_name': 'BP_StreetLight_simple18_45', + 'focus_actor_pt': array([-7252.53222656, 7718.29589844, 116.30269623]), + 'frame': 22170, + 'frame_number': 22170, + 'framesequence': 89371, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.5442164503038, + 'timestamp_carla': 756543, + 'timestamp_device': 1627147, + 'timestamp_stream': 756.5442164503038, + 'transform': [array([-4.75612488e+01, 9.80472260e+01, -7.22498223e-02]), + array([ 0.37813973, -46.5448761 , -0.13202198])]} +{'AngularVelocity': array([2.03388045e-05, 1.16397714e-05, 7.00863412e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71702085e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.28866890e-08, -4.02142426e-08, 2.04615586e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1911.0731201171875, + 'focus_actor_name': 'BP_StreetLight_simple18_45', + 'focus_actor_pt': array([-7251.60742188, 7716.06201172, 116.49088287]), + 'frame': 22171, + 'frame_number': 22171, + 'framesequence': 89374, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11405988037586212, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.5774659514427, + 'timestamp_carla': 756576, + 'timestamp_device': 1627172, + 'timestamp_stream': 756.5774659514427, + 'transform': [array([-4.75513420e+01, 9.80712509e+01, -7.38484263e-02]), + array([ 0.38971007, -46.49216843, -0.12329393])]} +{'AngularVelocity': array([-4.95542336e-05, 2.95277714e-05, 3.28371264e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71672730e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 2.12027693e-08, 3.67642841e-08, -4.25815560e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1917.5794677734375, + 'focus_actor_name': 'BP_StreetLight_simple18_45', + 'focus_actor_pt': array([-7253.11132812, 7711.49072266, 116.66134644]), + 'frame': 22172, + 'frame_number': 22172, + 'framesequence': 89378, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09774468839168549, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.6099816523492, + 'timestamp_carla': 756609, + 'timestamp_device': 1627205, + 'timestamp_stream': 756.6099816523492, + 'transform': [array([-4.75412483e+01, 9.80936127e+01, -7.53414035e-02]), + array([ 0.40322703, -46.44639969, -0.11471847])]} +{'AngularVelocity': array([-1.04183391e-05, -1.13893648e-05, 1.24776109e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71568571e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-3.44576847e-08, -2.53837698e-08, -3.18689330e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2694.438232421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7813.63085938, 7176.79296875, 115.28530121]), + 'frame': 22173, + 'frame_number': 22173, + 'framesequence': 89382, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07379376143217087, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.6439939513803, + 'timestamp_carla': 756643, + 'timestamp_device': 1627239, + 'timestamp_stream': 756.6439939513803, + 'transform': [array([-4.75299644e+01, 9.81161957e+01, -7.61228725e-02]), + array([ 0.40820622, -46.40450287, -0.11050702])]} +{'AngularVelocity': array([-4.06078798e-05, 4.56499110e-05, -7.91477550e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71691394e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([3.19946309e-08, 2.69720761e-08, 1.26876825e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2694.1923828125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7810.35058594, 7176.79296875, 115.69296265]), + 'frame': 22174, + 'frame_number': 22174, + 'framesequence': 89386, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.049311812967061996, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.6773935519159, + 'timestamp_carla': 756676, + 'timestamp_device': 1627272, + 'timestamp_stream': 756.6773935519159, + 'transform': [array([-4.75174217e+01, 9.81365051e+01, -7.64940456e-02]), + array([ 0.40942201, -46.37496185, -0.10867591])]} +{'AngularVelocity': array([-1.28706670e-05, 3.55610905e-06, 2.84337798e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71668893e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-6.96610636e-09, -3.16031668e-09, 2.11715687e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2694.250732421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7807.34033203, 7176.79296875, 115.89346313]), + 'frame': 22175, + 'frame_number': 22175, + 'framesequence': 89391, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03475447744131088, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.7114870510995, + 'timestamp_carla': 756711, + 'timestamp_device': 1627314, + 'timestamp_stream': 756.7114870510995, + 'transform': [array([-4.75034561e+01, 9.81557617e+01, -7.66799599e-02]), + array([ 0.40972936, -46.35386276, -0.10791296])]} +{'AngularVelocity': array([-1.59364336e-05, 5.60900799e-06, 3.88614962e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71707040e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-5.49738166e-09, -9.22104837e-10, -6.74152325e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2694.918701171875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7805.21044922, 7176.79296875, 115.97959137]), + 'frame': 22176, + 'frame_number': 22176, + 'framesequence': 89394, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03671376779675484, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.7457122504711, + 'timestamp_carla': 756745, + 'timestamp_device': 1627339, + 'timestamp_stream': 756.7457122504711, + 'transform': [array([-4.74892731e+01, 9.81748734e+01, -7.67729655e-02]), + array([ 0.41052166, -46.33423233, -0.10757725])]} +{'AngularVelocity': array([-2.80797958e-05, 1.56198639e-05, -2.76325851e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71716949e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([1.08869260e-08, 1.95957774e-08, 2.80261040e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2696.082275390625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7803.68408203, 7176.79296875, 116.01150513]), + 'frame': 22177, + 'frame_number': 22177, + 'framesequence': 89399, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04749900847673416, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.7786389514804, + 'timestamp_carla': 756778, + 'timestamp_device': 1627380, + 'timestamp_stream': 756.7786389514804, + 'transform': [array([-4.74758682e+01, 9.81934128e+01, -7.68423826e-02]), + array([ 0.41189453, -46.31385422, -0.10727213])]} +{'AngularVelocity': array([ 3.77076212e-05, -5.83845258e-06, -2.74780332e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71568571e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 6.18316554e-09, -1.32606299e-08, -1.90248480e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2697.337646484375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7802.27050781, 7176.79296875, 116.02100372]), + 'frame': 22178, + 'frame_number': 22178, + 'framesequence': 89402, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06214789301156998, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.810612551868, + 'timestamp_carla': 756810, + 'timestamp_device': 1627405, + 'timestamp_stream': 756.810612551868, + 'transform': [array([-4.74638748e+01, 9.82127914e+01, -7.68749863e-02]), + array([ 0.41356793, -46.28619385, -0.10708904])]} +{'AngularVelocity': array([-1.02451859e-05, 4.52543645e-06, -2.35123609e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71802780e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([3.33257733e-09, 7.37999217e-09, 2.65269278e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2698.4560546875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7800.80175781, 7176.79248047, 116.0284729 ]), + 'frame': 22179, + 'frame_number': 22179, + 'framesequence': 89406, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07207251340150833, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.8446039520204, + 'timestamp_carla': 756844, + 'timestamp_device': 1627439, + 'timestamp_stream': 756.8446039520204, + 'transform': [array([-4.74519615e+01, 9.82345505e+01, -7.69336522e-02]), + array([ 0.41515937, -46.25014114, -0.10690597])]} +{'AngularVelocity': array([ 1.07481446e-06, -5.98287215e-06, -1.10535281e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71631528e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-3.93228516e-09, -4.17355733e-10, -2.02198018e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2699.129638671875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7798.81542969, 7176.79296875, 116.03078461]), + 'frame': 22180, + 'frame_number': 22180, + 'framesequence': 89410, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07254860550165176, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.8765606507659, + 'timestamp_carla': 756876, + 'timestamp_device': 1627472, + 'timestamp_stream': 756.8765606507659, + 'transform': [array([-4.74409447e+01, 9.82552414e+01, -7.70236403e-02]), + array([ 0.41625902, -46.21474457, -0.10653974])]} +{'AngularVelocity': array([ 3.28503711e-06, -6.49068988e-06, -1.09188270e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71708195e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-3.24819993e-09, -6.36229625e-10, 5.45501680e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2699.503173828125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7796.22998047, 7176.79248047, 116.03199768]), + 'frame': 22181, + 'frame_number': 22181, + 'framesequence': 89414, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06703696399927139, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.9098872505128, + 'timestamp_carla': 756909, + 'timestamp_device': 1627505, + 'timestamp_stream': 756.9098872505128, + 'transform': [array([-4.74292412e+01, 9.82766113e+01, -7.71082640e-02]), + array([ 0.41610193, -46.17932129, -0.10641769])]} +{'AngularVelocity': array([-1.93583514e-06, -2.76878563e-06, 2.13177231e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71638756e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-6.50339738e-09, -4.52069671e-09, -1.53274537e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2699.775146484375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7793.69042969, 7176.79296875, 116.04429626]), + 'frame': 22182, + 'frame_number': 22182, + 'framesequence': 89419, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0600421167910099, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.945313449949, + 'timestamp_carla': 756944, + 'timestamp_device': 1627547, + 'timestamp_stream': 756.945313449949, + 'transform': [array([-4.74164162e+01, 9.82988815e+01, -7.72091746e-02]), + array([ 0.41525498, -46.14457321, -0.10638714])]} +{'AngularVelocity': array([ 4.51222004e-05, -1.27403000e-05, -2.64655631e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71581163e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 5.39667866e-09, -1.32297693e-08, -9.90676854e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2700.13818359375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7791.14355469, 7176.79296875, 116.04431915]), + 'frame': 22183, + 'frame_number': 22183, + 'framesequence': 89422, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.054200876504182816, + 'throttle_input': 0.2737926244735718, + 'timestamp': 756.977347549051, + 'timestamp_carla': 756976, + 'timestamp_device': 1627572, + 'timestamp_stream': 756.977347549051, + 'transform': [array([-4.74042282e+01, 9.83181152e+01, -7.73025006e-02]), + array([ 0.41427144, -46.11808777, -0.10623454])]} +{'AngularVelocity': array([-2.63190213e-05, 1.51453560e-05, -8.42590886e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71707413e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 1.30492035e-08, 2.16226930e-08, -8.04901138e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2700.6845703125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7788.64501953, 7176.79296875, 116.03816223]), + 'frame': 22184, + 'frame_number': 22184, + 'framesequence': 89426, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.054200876504182816, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.0097591504455, + 'timestamp_carla': 757009, + 'timestamp_device': 1627605, + 'timestamp_stream': 757.0097591504455, + 'transform': [array([-4.73919258e+01, 9.83376236e+01, -7.74730593e-02]), + array([ 0.41259804, -46.09124756, -0.10583775])]} +{'AngularVelocity': array([-9.95412029e-06, 2.90714866e-06, 3.57011287e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71702458e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-5.69921310e-09, -2.96663982e-09, -4.61578347e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2701.4248046875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7786.73242188, 7176.79296875, 116.04179382]), + 'frame': 22185, + 'frame_number': 22185, + 'framesequence': 89431, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0570940300822258, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.0456955507398, + 'timestamp_carla': 757045, + 'timestamp_device': 1627647, + 'timestamp_stream': 757.0456955507398, + 'transform': [array([-4.73783493e+01, 9.83594513e+01, -7.78992549e-02]), + array([ 0.40929908, -46.06071854, -0.10458647])]} +{'AngularVelocity': array([-8.61306580e-06, 2.86419049e-06, -4.84652229e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71694076e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 1.20489592e-08, 2.02856292e-08, -3.05175781e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2702.178466796875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7784.79785156, 7176.79296875, 116.0570755 ]), + 'frame': 22186, + 'frame_number': 22186, + 'framesequence': 89435, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.060573142021894455, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.077933549881, + 'timestamp_carla': 757077, + 'timestamp_device': 1627680, + 'timestamp_stream': 757.077933549881, + 'transform': [array([-4.73661423e+01, 9.83790436e+01, -7.80163854e-02]), + array([ 0.40881413, -46.03310394, -0.10422026])]} +{'AngularVelocity': array([ 4.82615324e-05, -1.72950913e-05, 5.63544589e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71558662e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-2.08353530e-08, -4.64816665e-08, -4.15802015e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2702.9814453125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7782.59521484, 7176.79296875, 116.11245728]), + 'frame': 22187, + 'frame_number': 22187, + 'framesequence': 89438, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06262398511171341, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.1098137497902, + 'timestamp_carla': 757109, + 'timestamp_device': 1627705, + 'timestamp_stream': 757.1098137497902, + 'transform': [array([-4.73543854e+01, 9.83986511e+01, -7.80439824e-02]), + array([ 0.40932637, -46.00412369, -0.10418975])]} +{'AngularVelocity': array([-1.06206380e-05, 3.69586246e-06, -4.19244001e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71711995e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-2.14600937e-09, 1.33954869e-09, -9.04178596e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2703.690673828125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7780.6015625 , 7176.79248047, 116.12708282]), + 'frame': 22188, + 'frame_number': 22188, + 'framesequence': 89442, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0617450512945652, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.1441120505333, + 'timestamp_carla': 757143, + 'timestamp_device': 1627739, + 'timestamp_stream': 757.1441120505333, + 'transform': [array([-4.73421326e+01, 9.84200592e+01, -7.80570507e-02]), + array([ 0.41006404, -45.97089386, -0.10434235])]} +{'AngularVelocity': array([ 4.65938574e-05, -1.56228107e-05, 1.13612109e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71722314e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.86457783e-08, -4.40334667e-08, 2.13909152e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2704.2978515625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7778.51708984, 7176.79296875, 116.12342072]), + 'frame': 22189, + 'frame_number': 22189, + 'framesequence': 89447, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.1774431504309, + 'timestamp_carla': 757176, + 'timestamp_device': 1627780, + 'timestamp_stream': 757.1774431504309, + 'transform': [array([-4.73300629e+01, 9.84406357e+01, -7.79876038e-02]), + array([ 0.41082904, -45.93989182, -0.10480012])]} +{'AngularVelocity': array([-1.43561547e-05, 3.81476048e-06, 2.24822339e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71758933e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-5.07725390e-11, 6.48836229e-09, 5.45773481e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2704.838134765625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7776.13720703, 7176.79296875, 116.10795593]), + 'frame': 22190, + 'frame_number': 22190, + 'framesequence': 89450, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0588885173201561, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.2091041505337, + 'timestamp_carla': 757208, + 'timestamp_device': 1627805, + 'timestamp_stream': 757.2091041505337, + 'transform': [array([-4.73183670e+01, 9.84598999e+01, -7.78933540e-02]), + array([ 0.4115257 , -45.91205215, -0.10531896])]} +{'AngularVelocity': array([-2.57201646e-05, 1.40196316e-05, -6.27938881e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71528152e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 1.36648612e-08, 2.30502106e-08, -3.55138764e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2705.433349609375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7773.91748047, 7176.79296875, 116.07858276]), + 'frame': 22191, + 'frame_number': 22191, + 'framesequence': 89454, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05938291549682617, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.2442943491042, + 'timestamp_carla': 757243, + 'timestamp_device': 1627839, + 'timestamp_stream': 757.2442943491042, + 'transform': [array([-4.73056374e+01, 9.84817963e+01, -7.77914152e-02]), + array([ 0.41237947, -45.87889099, -0.10602088])]} +{'AngularVelocity': array([ 4.89964659e-05, -1.79040690e-05, 1.36078337e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71133681e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.12856169e-08, -3.43031168e-08, -6.25143060e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2706.078857421875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7771.91650391, 7176.79296875, 116.04812622]), + 'frame': 22192, + 'frame_number': 22192, + 'framesequence': 89459, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06035340577363968, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.2775151506066, + 'timestamp_carla': 757277, + 'timestamp_device': 1627880, + 'timestamp_stream': 757.2775151506066, + 'transform': [array([-4.72934380e+01, 9.85021362e+01, -7.77123719e-02]), + array([ 0.41320592, -45.8492012 , -0.10650919])]} +{'AngularVelocity': array([-1.79582930e-05, 1.12514062e-05, -7.39197425e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71713150e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([1.47944137e-08, 2.15740688e-08, 2.72769918e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2706.69873046875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7769.54589844, 7176.79296875, 116.00497437]), + 'frame': 22193, + 'frame_number': 22193, + 'framesequence': 89462, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06033509597182274, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.3096801489592, + 'timestamp_carla': 757309, + 'timestamp_device': 1627905, + 'timestamp_stream': 757.3096801489592, + 'transform': [array([-4.72817268e+01, 9.85220108e+01, -7.76196942e-02]), + array([ 0.41397092, -45.8196106 , -0.10702801])]} +{'AngularVelocity': array([-2.56007934e-05, 1.41921946e-05, 1.04071279e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71447648e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.82031112e-09, 2.74664291e-09, 1.35879513e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2707.358642578125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7767.41552734, 7176.79296875, 115.97386932]), + 'frame': 22194, + 'frame_number': 22194, + 'framesequence': 89467, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059859007596969604, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.3439293503761, + 'timestamp_carla': 757343, + 'timestamp_device': 1627947, + 'timestamp_stream': 757.3439293503761, + 'transform': [array([-4.72692871e+01, 9.85433502e+01, -7.75466636e-02]), + array([ 0.41454464, -45.78753662, -0.10757735])]} +{'AngularVelocity': array([ 4.41695665e-05, -1.50526512e-05, 5.11564702e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71686067e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.38693501e-08, -3.66165480e-08, -2.93607707e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2707.959716796875, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7765.29589844, 7176.79248047, 115.94276428]), + 'frame': 22195, + 'frame_number': 22195, + 'framesequence': 89470, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.3764205500484, + 'timestamp_carla': 757375, + 'timestamp_device': 1627972, + 'timestamp_stream': 757.3764205500484, + 'transform': [array([-4.72574120e+01, 9.85634613e+01, -7.75753036e-02]), + array([ 0.41424412, -45.75780869, -0.10766887])]} +{'AngularVelocity': array([-3.06783804e-05, 1.56504721e-05, 9.05797048e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71705513e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 6.37895115e-09, 1.56574913e-08, -2.35462183e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2708.582275390625, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7763.00195312, 7176.79296875, 115.90859985]), + 'frame': 22196, + 'frame_number': 22196, + 'framesequence': 89475, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.4107244499028, + 'timestamp_carla': 757410, + 'timestamp_device': 1628014, + 'timestamp_stream': 757.4107244499028, + 'transform': [array([-4.72449303e+01, 9.85848694e+01, -7.76770487e-02]), + array([ 0.4135406 , -45.72573853, -0.10754682])]} +{'AngularVelocity': array([-2.13294334e-05, 7.83349606e-06, 7.23937443e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71559034e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.44061074e-08, -1.20477939e-08, -5.60026150e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2709.2080078125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7760.87255859, 7176.79296875, 115.8989563 ]), + 'frame': 22197, + 'frame_number': 22197, + 'framesequence': 89478, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.4436055496335, + 'timestamp_carla': 757443, + 'timestamp_device': 1628039, + 'timestamp_stream': 757.4436055496335, + 'transform': [array([-4.72329178e+01, 9.86053085e+01, -7.77963251e-02]), + array([ 0.41275513, -45.69546127, -0.10727213])]} +{'AngularVelocity': array([-1.74195884e-05, 7.64026026e-06, 1.15723686e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71655147e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-7.01822378e-10, 4.41359926e-09, 3.80039201e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2709.839111328125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7758.57519531, 7176.79248047, 115.89868164]), + 'frame': 22198, + 'frame_number': 22198, + 'framesequence': 89482, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.4765543490648, + 'timestamp_carla': 757476, + 'timestamp_device': 1628072, + 'timestamp_stream': 757.4765543490648, + 'transform': [array([-4.72208939e+01, 9.86258469e+01, -7.79249668e-02]), + array([ 0.41189453, -45.66499329, -0.10696695])]} +{'AngularVelocity': array([ 3.49297588e-05, -5.94950507e-06, 1.29039823e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71686439e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-9.29534227e-09, -3.24828946e-08, 1.54085152e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2710.469970703125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7756.40625 , 7176.79296875, 115.90763855]), + 'frame': 22199, + 'frame_number': 22199, + 'framesequence': 89486, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.5099352523685, + 'timestamp_carla': 757509, + 'timestamp_device': 1628105, + 'timestamp_stream': 757.5099352523685, + 'transform': [array([-4.72087135e+01, 9.86467133e+01, -7.80571699e-02]), + array([ 0.41104075, -45.63393402, -0.10666174])]} +{'AngularVelocity': array([ 4.86784884e-05, -1.56678125e-05, -3.26486149e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71684912e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 4.39656000e-09, -1.43665488e-08, 1.19981763e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2711.099609375, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7754.22460938, 7176.79296875, 115.91819 ]), + 'frame': 22200, + 'frame_number': 22200, + 'framesequence': 89491, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.543901052326, + 'timestamp_carla': 757543, + 'timestamp_device': 1628147, + 'timestamp_stream': 757.543901052326, + 'transform': [array([-4.71963387e+01, 9.86679840e+01, -7.82002509e-02]), + array([ 0.41018015, -45.6022377 , -0.106326 ])]} +{'AngularVelocity': array([ 4.51487067e-05, -1.44289852e-05, 3.13486859e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71694821e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-7.45323270e-09, -2.95353040e-08, 1.10292429e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2711.7314453125, + 'focus_actor_name': 'MultipleFloorBuilding16', + 'focus_actor_pt': array([-7752.00048828, 7176.79296875, 115.92808533]), + 'frame': 22201, + 'frame_number': 22201, + 'framesequence': 89494, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2737926244735718, + 'timestamp': 757.5768735520542, + 'timestamp_carla': 757576, + 'timestamp_device': 1628172, + 'timestamp_stream': 757.5768735520542, + 'transform': [array([-4.71842651e+01, 9.86885605e+01, -7.85159767e-02]), + array([ 0.40755737, -45.5719986 , -0.10534945])]} \ No newline at end of file diff --git a/PythonAPI/data/vehicle_logs/backward_1.txt b/PythonAPI/data/vehicle_logs/backward_1.txt new file mode 100644 index 0000000..3492af5 --- /dev/null +++ b/PythonAPI/data/vehicle_logs/backward_1.txt @@ -0,0 +1,44462 @@ +{'AngularVelocity': array([ 2.43634659e-05, -4.46915180e-07, -1.38809515e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71770258e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 3.82551342e-08, -4.50882958e-08, 7.50589388e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97772217]), + 'frame': 27928, + 'frame_number': 27928, + 'framesequence': 112424, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.6163867525756, + 'timestamp_carla': 948616, + 'timestamp_device': 1819214, + 'timestamp_stream': 948.6163867525756, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01371117e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-1.22238152e-05, -1.58660059e-05, 2.50463028e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71571514e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-3.59687782e-08, 2.42791316e-08, -2.13727952e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97814941]), + 'frame': 27929, + 'frame_number': 27929, + 'framesequence': 112428, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.6511293500662, + 'timestamp_carla': 948650, + 'timestamp_device': 1819247, + 'timestamp_stream': 948.6511293500662, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01389006e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-7.33939351e-06, -1.27100657e-05, 1.07324043e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71428090e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-4.48983322e-08, 2.93803488e-08, -1.51100161e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97847748]), + 'frame': 27930, + 'frame_number': 27930, + 'framesequence': 112432, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.6844396516681, + 'timestamp_carla': 948684, + 'timestamp_device': 1819280, + 'timestamp_stream': 948.6844396516681, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01387821e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-4.22715357e-06, -9.23612424e-06, -3.63525365e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71452491e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-8.51859561e-09, 4.34708447e-09, -3.47804998e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97668457]), + 'frame': 27931, + 'frame_number': 27931, + 'framesequence': 112436, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.7172152511775, + 'timestamp_carla': 948716, + 'timestamp_device': 1819314, + 'timestamp_stream': 948.7172152511775, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01383209e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-1.16264137e-05, -1.99928982e-05, 1.48289141e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71155362e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-4.87063581e-08, 3.15159632e-08, -4.58288181e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97680664]), + 'frame': 27932, + 'frame_number': 27932, + 'framesequence': 112440, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.7501545511186, + 'timestamp_carla': 948749, + 'timestamp_device': 1819347, + 'timestamp_stream': 948.7501545511186, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01381756e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-4.32044435e-05, -4.10491266e-05, 5.88949245e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71684055e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-2.09833697e-08, 2.61385456e-08, -2.53963462e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.9772644 ]), + 'frame': 27933, + 'frame_number': 27933, + 'framesequence': 112444, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.7844066508114, + 'timestamp_carla': 948784, + 'timestamp_device': 1819380, + 'timestamp_stream': 948.7844066508114, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01390988e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-6.40226608e-06, -1.66862374e-05, 3.21935256e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71850017e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-6.35220854e-09, 8.70077177e-10, -4.53853609e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97740936]), + 'frame': 27934, + 'frame_number': 27934, + 'framesequence': 112449, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.8179930523038, + 'timestamp_carla': 948817, + 'timestamp_device': 1819422, + 'timestamp_stream': 948.8179930523038, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01390988e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 3.06010297e-05, 3.77347169e-06, -2.37719511e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71589060e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-9.06944120e-09, -1.36674903e-08, -1.34696951e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97648621]), + 'frame': 27935, + 'frame_number': 27935, + 'framesequence': 112452, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.8508253507316, + 'timestamp_carla': 948850, + 'timestamp_device': 1819447, + 'timestamp_stream': 948.8508253507316, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01385228e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 3.31296615e-05, 1.14293080e-05, -1.64000920e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71586415e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 3.30549099e-08, -4.21878283e-08, -6.73103350e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97648621]), + 'frame': 27936, + 'frame_number': 27936, + 'framesequence': 112457, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.8863413520157, + 'timestamp_carla': 948886, + 'timestamp_device': 1819489, + 'timestamp_stream': 948.8863413520157, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01403005e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 5.89909141e-05, 8.04926967e-05, -7.50144746e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71312904e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 7.38832213e-08, -5.31772635e-08, -7.53278728e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97706604]), + 'frame': 27937, + 'frame_number': 27937, + 'framesequence': 112461, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.9201173521578, + 'timestamp_carla': 948919, + 'timestamp_device': 1819522, + 'timestamp_stream': 948.9201173521578, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01398274e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-5.14462226e-05, -4.79461160e-05, 7.81944021e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.70969172e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-5.15407059e-08, 5.04786115e-08, -3.15437297e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97528839]), + 'frame': 27938, + 'frame_number': 27938, + 'framesequence': 112465, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.9551966525614, + 'timestamp_carla': 948954, + 'timestamp_device': 1819555, + 'timestamp_stream': 948.9551966525614, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01405330e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-2.55997998e-06, -5.19897230e-06, -7.30758298e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71519658e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 3.21352402e-08, -2.33994673e-08, 1.09043118e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97576141]), + 'frame': 27939, + 'frame_number': 27939, + 'framesequence': 112469, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 948.9901798516512, + 'timestamp_carla': 948989, + 'timestamp_device': 1819589, + 'timestamp_stream': 948.9901798516512, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01407699e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-1.39387876e-05, -1.72538566e-05, -8.89883811e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71776740e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 1.98212255e-08, -1.27127526e-08, 2.29539859e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97505188]), + 'frame': 27940, + 'frame_number': 27940, + 'framesequence': 112473, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.0249231494963, + 'timestamp_carla': 949024, + 'timestamp_device': 1819622, + 'timestamp_stream': 949.0249231494963, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01406246e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-9.26158737e-06, -1.52699540e-05, -2.36609154e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71742803e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-1.67537237e-08, 1.05001945e-08, 3.96251671e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97481537]), + 'frame': 27941, + 'frame_number': 27941, + 'framesequence': 112478, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.060789052397, + 'timestamp_carla': 949060, + 'timestamp_device': 1819664, + 'timestamp_stream': 949.060789052397, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01413995e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 3.54272038e-06, 4.36440532e-05, -2.79426193e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71431145e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 3.62996602e-08, -3.23258620e-09, 4.55369940e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97496033]), + 'frame': 27942, + 'frame_number': 27942, + 'framesequence': 112482, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.0946150496602, + 'timestamp_carla': 949094, + 'timestamp_device': 1819697, + 'timestamp_stream': 949.0946150496602, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01401173e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 2.25970216e-05, 5.55997167e-06, -1.62805982e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71904927e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 3.62258881e-08, -3.96246023e-08, 9.13381591e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97418976]), + 'frame': 27943, + 'frame_number': 27943, + 'framesequence': 112486, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.1296570524573, + 'timestamp_carla': 949129, + 'timestamp_device': 1819730, + 'timestamp_stream': 949.1296570524573, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01402894e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 4.82743271e-05, 6.98067524e-05, -5.13655785e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71815670e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 6.12922122e-08, -4.02945872e-08, 2.38943088e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.9754715 ]), + 'frame': 27944, + 'frame_number': 27944, + 'framesequence': 112490, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.1643295511603, + 'timestamp_carla': 949164, + 'timestamp_device': 1819764, + 'timestamp_stream': 949.1643295511603, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01400524e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-4.10095709e-06, -7.26851204e-06, -1.36157281e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71459383e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 2.03256061e-08, -1.53557256e-08, -3.82089609e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97529602]), + 'frame': 27945, + 'frame_number': 27945, + 'framesequence': 112494, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.198432251811, + 'timestamp_carla': 949198, + 'timestamp_device': 1819797, + 'timestamp_stream': 949.198432251811, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01394497e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-1.46615985e-05, -2.10811613e-05, -9.47632106e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71533777e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([ 1.89671390e-08, -1.34261198e-08, -3.24096676e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97553253]), + 'frame': 27946, + 'frame_number': 27946, + 'framesequence': 112499, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.2404923513532, + 'timestamp_carla': 949240, + 'timestamp_device': 1819839, + 'timestamp_stream': 949.2404923513532, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01386562e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.02498085, -0.01466983, 0.6475476 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125787574797869, + 'FR_Wheel_Angle': 0.00512559013441205, + 'Location': array([-5.56526146e+01, 1.13080894e+02, 5.71713448e-02]), + 'Rotation': array([7.28098117e-03, 5.60037918e+01, 4.47667204e-03]), + 'Velocity': array([0.01165318, 0.01685643, 0.00040314]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97613525]), + 'frame': 27947, + 'frame_number': 27947, + 'framesequence': 112507, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.3108321502805, + 'timestamp_carla': 949310, + 'timestamp_device': 1819905, + 'timestamp_stream': 949.3108321502805, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01400487e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.02438318, -0.0159009 , 0.68915814]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051246401853859425, + 'FR_Wheel_Angle': 0.005124534480273724, + 'Location': array([-5.56527443e+01, 1.13080704e+02, 5.71647435e-02]), + 'Rotation': array([7.07607577e-03, 5.60031776e+01, 4.40024678e-03]), + 'Velocity': array([6.94297440e-03, 1.04944743e-02, 3.90148161e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97692871]), + 'frame': 27948, + 'frame_number': 27948, + 'framesequence': 112513, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.3583002500236, + 'timestamp_carla': 949358, + 'timestamp_device': 1819955, + 'timestamp_stream': 949.3583002500236, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01432607e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.02548837, -0.01638073, 0.70674074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005123605020344257, + 'FR_Wheel_Angle': 0.005123605486005545, + 'Location': array([-5.56539917e+01, 1.13078827e+02, 5.71647063e-02]), + 'Rotation': array([6.89849071e-03, 5.60029564e+01, 4.40628873e-03]), + 'Velocity': array([ 3.87626438e-04, 5.56515355e-04, -8.42857335e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97554016]), + 'frame': 27949, + 'frame_number': 27949, + 'framesequence': 112519, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.4011355489492, + 'timestamp_carla': 949400, + 'timestamp_device': 1820005, + 'timestamp_stream': 949.4011355489492, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01408310e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.02573427, -0.0165481 , 0.68503541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005122425500303507, + 'FR_Wheel_Angle': 0.005122336558997631, + 'Location': array([-5.56566544e+01, 1.13074783e+02, 5.71715720e-02]), + 'Rotation': array([6.76188711e-03, 5.60025291e+01, 4.39415779e-03]), + 'Velocity': array([-7.52536999e-03, -1.12426896e-02, -4.38213356e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97232819]), + 'frame': 27950, + 'frame_number': 27950, + 'framesequence': 112523, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.4393584504724, + 'timestamp_carla': 949439, + 'timestamp_device': 1820039, + 'timestamp_stream': 949.4393584504724, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01431921e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.02498907, -0.01734276, 0.6801585 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005121092312037945, + 'FR_Wheel_Angle': 0.005120972171425819, + 'Location': array([-5.56601944e+01, 1.13069519e+02, 5.71458228e-02]), + 'Rotation': array([6.72773598e-03, 5.60013733e+01, 4.36220132e-03]), + 'Velocity': array([-0.01380282, -0.02072993, 0.0004516 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97475433]), + 'frame': 27951, + 'frame_number': 27951, + 'framesequence': 112527, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.4714924506843, + 'timestamp_carla': 949471, + 'timestamp_device': 1820072, + 'timestamp_stream': 949.4714924506843, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01395264e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.02962925, 0.016958 , 0.10179955]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00511053204536438, + 'FR_Wheel_Angle': 0.005106550641357899, + 'Location': array([-5.56699409e+01, 1.13054939e+02, 5.72135337e-02]), + 'Rotation': array([1.14747172e-03, 5.60013924e+01, 4.39833244e-03]), + 'Velocity': array([-1.01669058e-01, -1.52110204e-01, -1.12848276e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97239685]), + 'frame': 27952, + 'frame_number': 27952, + 'framesequence': 112531, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.5044953487813, + 'timestamp_carla': 949504, + 'timestamp_device': 1820105, + 'timestamp_stream': 949.5044953487813, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01379737e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.02082851, 0.00148264, 0.61835951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0050934539176523685, + 'FR_Wheel_Angle': 0.005091527476906776, + 'Location': array([-5.56983109e+01, 1.13012505e+02, 5.72271161e-02]), + 'Rotation': array([-3.78392451e-03, 5.60207825e+01, 4.44503268e-03]), + 'Velocity': array([-2.13469207e-01, -3.19928944e-01, 2.53295893e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97605896]), + 'frame': 27953, + 'frame_number': 27953, + 'framesequence': 112535, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.5386673510075, + 'timestamp_carla': 949538, + 'timestamp_device': 1820138, + 'timestamp_stream': 949.5386673510075, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01379737e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.0242318 , -0.01563438, 0.05662823]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005079662427306175, + 'FR_Wheel_Angle': 0.005078848917037249, + 'Location': array([-5.57412720e+01, 1.12948532e+02, 5.72327971e-02]), + 'Rotation': array([-3.94101907e-03, 5.60221138e+01, 4.37840633e-03]), + 'Velocity': array([-2.87662417e-01, -4.27984148e-01, 2.93245306e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97761536]), + 'frame': 27954, + 'frame_number': 27954, + 'framesequence': 112539, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.5714054517448, + 'timestamp_carla': 949571, + 'timestamp_device': 1820172, + 'timestamp_stream': 949.5714054517448, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01370387e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.02877068, 0.02575511, -0.26462376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005065882112830877, + 'FR_Wheel_Angle': 0.005056657828390598, + 'Location': array([-5.57988358e+01, 1.12863159e+02, 5.71861826e-02]), + 'Rotation': array([-3.48339626e-03, 5.60099297e+01, 4.16207220e-03]), + 'Velocity': array([-3.88665915e-01, -5.75228095e-01, 1.92441934e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97761536]), + 'frame': 27955, + 'frame_number': 27955, + 'framesequence': 112543, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.604075152427, + 'timestamp_carla': 949603, + 'timestamp_device': 1820205, + 'timestamp_stream': 949.604075152427, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01365544e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-4.46814013, -4.27232409, -0.86185306]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005062268581241369, + 'FR_Wheel_Angle': 0.005058657843619585, + 'Location': array([-5.58824387e+01, 1.12771385e+02, 8.37565884e-02]), + 'Rotation': array([-1.05343366, 55.83821869, -1.775635 ]), + 'Velocity': array([-0.45160034, -0.54173523, 0.0998093 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97854614]), + 'frame': 27956, + 'frame_number': 27956, + 'framesequence': 112547, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.6362265497446, + 'timestamp_carla': 949635, + 'timestamp_device': 1820238, + 'timestamp_stream': 949.6362265497446, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01360396e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.13360965, 2.02596426, -1.15315711]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005060128401964903, + 'FR_Wheel_Angle': 0.005060182884335518, + 'Location': array([-5.59543457e+01, 1.12669014e+02, 9.42532644e-02]), + 'Rotation': array([-1.28756571, 55.79508209, -1.94107056]), + 'Velocity': array([-0.39119864, -0.60120797, 0.0258904 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97903442]), + 'frame': 27957, + 'frame_number': 27957, + 'framesequence': 112551, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.668832950294, + 'timestamp_carla': 949668, + 'timestamp_device': 1820272, + 'timestamp_stream': 949.668832950294, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01361923e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.25486973, 0.74058264, -0.08772712]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0050561088137328625, + 'FR_Wheel_Angle': 0.005056653171777725, + 'Location': array([-5.60220451e+01, 1.12570343e+02, 9.52862054e-02]), + 'Rotation': array([-1.32254314, 55.73397827, -2.00946045]), + 'Velocity': array([-4.31330204e-01, -6.31983757e-01, -3.08561313e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97954559]), + 'frame': 27958, + 'frame_number': 27958, + 'framesequence': 112554, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.7013166509569, + 'timestamp_carla': 949700, + 'timestamp_device': 1820297, + 'timestamp_stream': 949.7013166509569, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01363145e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.09207202, 0.6214087 , 0.28001446]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005058939103037119, + 'FR_Wheel_Angle': -0.0012651016004383564, + 'Location': array([-5.60913239e+01, 1.12468643e+02, 9.66982916e-02]), + 'Rotation': array([-1.39089966, 55.73822021, -2.13943481]), + 'Velocity': array([-0.4062582 , -0.60566217, 0.00652447]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97939301]), + 'frame': 27959, + 'frame_number': 27959, + 'framesequence': 112558, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.7339909523726, + 'timestamp_carla': 949733, + 'timestamp_device': 1820330, + 'timestamp_stream': 949.7339909523726, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01366267e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.08808924, 0.41480684, 0.27248099]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.395407199859619, + 'FR_Wheel_Angle': -8.715362548828125, + 'Location': array([-5.61638641e+01, 1.12365082e+02, 9.76844653e-02]), + 'Rotation': array([-1.42865014, 55.82551193, -2.20822191]), + 'Velocity': array([-0.46571451, -0.62296897, 0.00284748]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97927094]), + 'frame': 27960, + 'frame_number': 27960, + 'framesequence': 112562, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.7665805518627, + 'timestamp_carla': 949766, + 'timestamp_device': 1820363, + 'timestamp_stream': 949.7665805518627, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01368405e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.06843579, 0.24967827, 2.59391475]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.12518882751465, + 'FR_Wheel_Angle': -16.192514419555664, + 'Location': array([-5.62557907e+01, 1.12250839e+02, 9.80673879e-02]), + 'Rotation': array([-1.44195533, 56.34676743, -2.2471621 ]), + 'Velocity': array([-4.73356187e-01, -5.11425078e-01, 1.55544272e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97895813]), + 'frame': 27961, + 'frame_number': 27961, + 'framesequence': 112566, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.799899648875, + 'timestamp_carla': 949799, + 'timestamp_device': 1820397, + 'timestamp_stream': 949.799899648875, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01375692e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.05580259, 0.19869943, 4.32535028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.05488395690918, + 'FR_Wheel_Angle': -22.957950592041016, + 'Location': array([-5.63314819e+01, 1.12169098e+02, 9.81474221e-02]), + 'Rotation': array([-1.44494009, 57.10879898, -2.25628662]), + 'Velocity': array([-4.72072363e-01, -4.34301287e-01, 2.92797078e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97874451]), + 'frame': 27962, + 'frame_number': 27962, + 'framesequence': 112570, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.8336279504001, + 'timestamp_carla': 949833, + 'timestamp_device': 1820430, + 'timestamp_stream': 949.8336279504001, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01383395e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.08483753, -0.16249894, 7.1252079 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.98710632324219, + 'FR_Wheel_Angle': -29.221637725830078, + 'Location': array([-5.64093781e+01, 1.12094566e+02, 9.81915146e-02]), + 'Rotation': array([-1.4484235 , 58.1901207 , -2.26101661]), + 'Velocity': array([-5.11006594e-01, -4.09543842e-01, -3.87191767e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97801971]), + 'frame': 27963, + 'frame_number': 27963, + 'framesequence': 112574, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.8675360493362, + 'timestamp_carla': 949867, + 'timestamp_device': 1820463, + 'timestamp_stream': 949.8675360493362, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01389237e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.11594427, -0.21375984, 8.13125992]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.2271842956543, + 'FR_Wheel_Angle': -30.209543228149414, + 'Location': array([-5.64889259e+01, 1.12024780e+02, 9.82129201e-02]), + 'Rotation': array([-1.44860792, 59.51866913, -2.25439453]), + 'Velocity': array([-5.19935548e-01, -4.02677685e-01, 4.28199746e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97724915]), + 'frame': 27964, + 'frame_number': 27964, + 'framesequence': 112578, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.9009601511061, + 'timestamp_carla': 949900, + 'timestamp_device': 1820497, + 'timestamp_stream': 949.9009601511061, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01389237e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-2.11925944e-04, 4.01575072e-03, 8.38655376e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.55830383300781, + 'FR_Wheel_Angle': -30.723695755004883, + 'Location': array([-5.65856857e+01, 1.11937225e+02, 9.82188284e-02]), + 'Rotation': array([-1.44982374, 61.18836975, -2.24655175]), + 'Velocity': array([-5.03109694e-01, -3.86580586e-01, 2.40836132e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97666168]), + 'frame': 27965, + 'frame_number': 27965, + 'framesequence': 112583, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.9349669516087, + 'timestamp_carla': 949934, + 'timestamp_device': 1820538, + 'timestamp_stream': 949.9349669516087, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01393163e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.01813945, 0.152244 , 7.61799145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.59983825683594, + 'FR_Wheel_Angle': -30.74823570251465, + 'Location': array([-5.66577721e+01, 1.11869286e+02, 9.81992260e-02]), + 'Rotation': array([-1.44873083, 62.48117447, -2.23843384]), + 'Velocity': array([-4.48654473e-01, -3.57864231e-01, 5.83934780e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97666168]), + 'frame': 27966, + 'frame_number': 27966, + 'framesequence': 112586, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 949.9678279496729, + 'timestamp_carla': 949967, + 'timestamp_device': 1820563, + 'timestamp_stream': 949.9678279496729, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01386636e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.07110181, -0.22744545, 7.15621376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.634979248046875, + 'FR_Wheel_Angle': -30.7885684967041, + 'Location': array([-5.67262115e+01, 1.11801964e+02, 9.81490985e-02]), + 'Rotation': array([-1.44968021, 63.74111938, -2.23638916]), + 'Velocity': array([-3.94398123e-01, -3.55845660e-01, 6.78443903e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97627258]), + 'frame': 27967, + 'frame_number': 27967, + 'framesequence': 112590, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.0011609494686, + 'timestamp_carla': 950000, + 'timestamp_device': 1820597, + 'timestamp_stream': 950.0011609494686, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01386636e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.02698214, -0.0130117 , 6.83405781]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.922569274902344, + 'FR_Wheel_Angle': -28.704639434814453, + 'Location': array([-5.67901802e+01, 1.11735809e+02, 9.82291326e-02]), + 'Rotation': array([-1.45235765, 64.90914917, -2.24871874]), + 'Velocity': array([-4.10327405e-01, -3.74197543e-01, -8.72898090e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97692108]), + 'frame': 27968, + 'frame_number': 27968, + 'framesequence': 112595, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.0349080525339, + 'timestamp_carla': 950034, + 'timestamp_device': 1820638, + 'timestamp_stream': 950.0349080525339, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01389498e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.05296475, 0.06208742, 5.5092454 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.145591735839844, + 'FR_Wheel_Angle': -28.63463592529297, + 'Location': array([-5.68619270e+01, 1.11653709e+02, 9.82138738e-02]), + 'Rotation': array([-1.45025396, 66.17556763, -2.24035645]), + 'Velocity': array([-0.33649075, -0.35151979, 0.00046461]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97692108]), + 'frame': 27969, + 'frame_number': 27969, + 'framesequence': 112598, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.0668747499585, + 'timestamp_carla': 950066, + 'timestamp_device': 1820663, + 'timestamp_stream': 950.0668747499585, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01378441e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.0481303 , -0.03524049, 6.39407969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.2409782409668, + 'FR_Wheel_Angle': -28.005279541015625, + 'Location': array([-5.69131088e+01, 1.11592499e+02, 9.82247442e-02]), + 'Rotation': array([-1.44978952, 67.11756134, -2.24212646]), + 'Velocity': array([-3.38573933e-01, -3.52825165e-01, 2.38995548e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97663879]), + 'frame': 27970, + 'frame_number': 27970, + 'framesequence': 112602, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.1003406494856, + 'timestamp_carla': 950100, + 'timestamp_device': 1820697, + 'timestamp_stream': 950.1003406494856, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01382904e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.06436447, -0.30074853, 7.18610382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.59400939941406, + 'FR_Wheel_Angle': -28.285062789916992, + 'Location': array([-5.69684753e+01, 1.11523560e+02, 9.82211158e-02]), + 'Rotation': array([-1.45251477, 68.11968231, -2.25070167]), + 'Velocity': array([-3.70898575e-01, -4.14536595e-01, 1.86061861e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97774506]), + 'frame': 27971, + 'frame_number': 27971, + 'framesequence': 112606, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.1335583515465, + 'timestamp_carla': 950133, + 'timestamp_device': 1820730, + 'timestamp_stream': 950.1335583515465, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01382904e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-3.58058396e-03, 1.20161295e-01, 5.92534161e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.51099395751953, + 'FR_Wheel_Angle': -28.293611526489258, + 'Location': array([-5.70219917e+01, 1.11455154e+02, 9.82159674e-02]), + 'Rotation': array([-1.44964612, 69.12811279, -2.24295044]), + 'Velocity': array([-3.29049438e-01, -3.57802123e-01, 1.78832997e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97729492]), + 'frame': 27972, + 'frame_number': 27972, + 'framesequence': 112610, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.1655573509634, + 'timestamp_carla': 950165, + 'timestamp_device': 1820763, + 'timestamp_stream': 950.1655573509634, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01374969e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.02532079, 0.14855829, 4.37460232]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.496253967285156, + 'FR_Wheel_Angle': -28.289791107177734, + 'Location': array([-5.70683823e+01, 1.11393669e+02, 9.82051715e-02]), + 'Rotation': array([-1.44970763, 70.02835083, -2.24117994]), + 'Velocity': array([-2.98298776e-01, -3.50902885e-01, -1.35335926e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97729492]), + 'frame': 27973, + 'frame_number': 27973, + 'framesequence': 112614, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.1989147514105, + 'timestamp_carla': 950198, + 'timestamp_device': 1820797, + 'timestamp_stream': 950.1989147514105, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01380348e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-6.12176085, -6.93499374, 2.02912354]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.62404251098633, + 'FR_Wheel_Angle': -28.369792938232422, + 'Location': array([-5.71106033e+01, 1.11335297e+02, 9.56976563e-02]), + 'Rotation': array([-1.57375741, 70.78926849, -1.93634057]), + 'Velocity': array([-0.21459705, -0.1994759 , -0.09218892]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97808838]), + 'frame': 27974, + 'frame_number': 27974, + 'framesequence': 112619, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.2361519522965, + 'timestamp_carla': 950235, + 'timestamp_device': 1820838, + 'timestamp_stream': 950.2361519522965, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01416856e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([5.04287481, 4.97925377, 4.79294252]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.516353607177734, + 'FR_Wheel_Angle': -28.268430709838867, + 'Location': array([-57.15504837, 111.30134583, 0.11681282]), + 'Rotation': array([-0.62826806, 71.27404785, -3.98986888]), + 'Velocity': array([-0.24948876, -0.37126172, 0.11470372]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97755432]), + 'frame': 27975, + 'frame_number': 27975, + 'framesequence': 112623, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.2734046503901, + 'timestamp_carla': 950273, + 'timestamp_device': 1820872, + 'timestamp_stream': 950.2734046503901, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01435088e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([2.34612203, 2.39050412, 5.9454999 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.4890022277832, + 'FR_Wheel_Angle': -28.288835525512695, + 'Location': array([-57.19906235, 111.23739624, 0.12796703]), + 'Rotation': array([-0.23922737, 72.1958847 , -4.74371576]), + 'Velocity': array([-0.27793953, -0.37614816, 0.04762338]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97389984]), + 'frame': 27976, + 'frame_number': 27976, + 'framesequence': 112627, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.3078682497144, + 'timestamp_carla': 950307, + 'timestamp_device': 1820905, + 'timestamp_stream': 950.3078682497144, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01419367e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.83506542, 0.85055196, 5.43502617]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.911190032958984, + 'FR_Wheel_Angle': -25.64155387878418, + 'Location': array([-57.2416153 , 111.17260742, 0.13187531]), + 'Rotation': array([-0.08560275, 73.08042908, -5.0597558 ]), + 'Velocity': array([-0.27534708, -0.4112176 , 0.01481117]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97207642]), + 'frame': 27977, + 'frame_number': 27977, + 'framesequence': 112631, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.3423096500337, + 'timestamp_carla': 950341, + 'timestamp_device': 1820938, + 'timestamp_stream': 950.3423096500337, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01408996e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.39400184, 0.34145066, 5.0065794 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.00994110107422, + 'FR_Wheel_Angle': -26.292198181152344, + 'Location': array([-57.28260803, 111.1036911 , 0.13303177]), + 'Rotation': array([-3.62546407e-02, 7.38544693e+01, -5.20099068e+00]), + 'Velocity': array([-0.25776204, -0.39578834, 0.00387293]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97364807]), + 'frame': 27978, + 'frame_number': 27978, + 'framesequence': 112636, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.3803515508771, + 'timestamp_carla': 950379, + 'timestamp_device': 1820980, + 'timestamp_stream': 950.3803515508771, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01433791e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.09258018, -0.05761597, 4.42717886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.04541778564453, + 'FR_Wheel_Angle': -25.7161865234375, + 'Location': array([-57.32997894, 111.02229309, 0.1333046 ]), + 'Rotation': array([-9.12513211e-03, 7.48219452e+01, -5.25003338e+00]), + 'Velocity': array([-0.24017157, -0.38596874, 0.0010113 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97468567]), + 'frame': 27979, + 'frame_number': 27979, + 'framesequence': 112641, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.4190381504595, + 'timestamp_carla': 950418, + 'timestamp_device': 1821022, + 'timestamp_stream': 950.4190381504595, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01451226e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.0167918 , -0.11741008, 3.83573532]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.2813835144043, + 'FR_Wheel_Angle': -25.68731689453125, + 'Location': array([-57.37249374, 110.9471817 , 0.13334744]), + 'Rotation': array([ 4.37132083e-04, 7.57235641e+01, -5.26571894e+00]), + 'Velocity': array([-2.11604744e-01, -3.51819068e-01, 3.38435173e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97220612]), + 'frame': 27980, + 'frame_number': 27980, + 'framesequence': 112645, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.4584245495498, + 'timestamp_carla': 950458, + 'timestamp_device': 1821055, + 'timestamp_stream': 950.4584245495498, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01464495e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.02795572, -0.14585942, 5.2283473 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.283790588378906, + 'FR_Wheel_Angle': -25.701520919799805, + 'Location': array([-57.40745544, 110.88323975, 0.13335846]), + 'Rotation': array([-1.61875470e-03, 7.64792862e+01, -5.27569866e+00]), + 'Velocity': array([-2.60607779e-01, -4.39779729e-01, -2.96401966e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97046661]), + 'frame': 27981, + 'frame_number': 27981, + 'framesequence': 112650, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.4971871487796, + 'timestamp_carla': 950496, + 'timestamp_device': 1821097, + 'timestamp_stream': 950.4971871487796, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01461791e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.02449193, -0.19771102, 4.84256983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.30980682373047, + 'FR_Wheel_Angle': -25.715925216674805, + 'Location': array([-57.44538879, 110.8114624 , 0.13336849]), + 'Rotation': array([ 5.94226411e-04, 7.73219757e+01, -5.27517939e+00]), + 'Velocity': array([-2.45799705e-01, -4.18875307e-01, 4.83036019e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.9691391 ]), + 'frame': 27982, + 'frame_number': 27982, + 'framesequence': 112654, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.5312673524022, + 'timestamp_carla': 950530, + 'timestamp_device': 1821130, + 'timestamp_stream': 950.5312673524022, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01419181e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.08036962, -0.15626261, 5.87921143]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.30650329589844, + 'FR_Wheel_Angle': -25.71271324157715, + 'Location': array([-57.48167038, 110.73951721, 0.13335578]), + 'Rotation': array([ 1.97392446e-03, 7.81572800e+01, -5.27633858e+00]), + 'Velocity': array([-2.41063416e-01, -4.27716404e-01, 2.63199792e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.96940613]), + 'frame': 27983, + 'frame_number': 27983, + 'framesequence': 112658, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.5662746503949, + 'timestamp_carla': 950565, + 'timestamp_device': 1821163, + 'timestamp_stream': 950.5662746503949, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01401404e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.0567289 , 0.06638128, 5.73232317]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.3210334777832, + 'FR_Wheel_Angle': -25.722396850585938, + 'Location': array([-57.51808167, 110.66501617, 0.13334937]), + 'Rotation': array([ 3.05309449e-03, 7.90064011e+01, -5.27920866e+00]), + 'Velocity': array([-2.36470774e-01, -4.16893035e-01, 3.65734086e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97367096]), + 'frame': 27984, + 'frame_number': 27984, + 'framesequence': 112663, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.6018140502274, + 'timestamp_carla': 950601, + 'timestamp_device': 1821205, + 'timestamp_stream': 950.6018140502274, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01396173e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.05498912, 0.03145682, 4.66782522]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.02606964111328, + 'FR_Wheel_Angle': -24.78525161743164, + 'Location': array([-57.55911636, 110.5769577 , 0.13333805]), + 'Rotation': array([ 3.35362274e-03, 8.00116577e+01, -5.27679682e+00]), + 'Velocity': array([-2.18555242e-01, -4.18506682e-01, 4.58335853e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97544861]), + 'frame': 27985, + 'frame_number': 27985, + 'framesequence': 112667, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.6359564512968, + 'timestamp_carla': 950635, + 'timestamp_device': 1821238, + 'timestamp_stream': 950.6359564512968, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01382941e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.06931168, 0.09118245, 4.17279053]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.63847541809082, + 'FR_Wheel_Angle': -22.664478302001953, + 'Location': array([-57.5860939 , 110.5105896 , 0.13333736]), + 'Rotation': array([ 4.91090585e-03, 8.06382980e+01, -5.27267790e+00]), + 'Velocity': array([-1.67367518e-01, -3.67688239e-01, 7.61222836e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97596741]), + 'frame': 27986, + 'frame_number': 27986, + 'framesequence': 112671, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.6710999496281, + 'timestamp_carla': 950670, + 'timestamp_device': 1821272, + 'timestamp_stream': 950.6710999496281, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01384431e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.04922283, -0.16453505, 5.66532135]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.496164321899414, + 'FR_Wheel_Angle': -23.026613235473633, + 'Location': array([-57.61368179, 110.4409256 , 0.1333562 ]), + 'Rotation': array([ 1.21577363e-03, 8.13338547e+01, -5.27908564e+00]), + 'Velocity': array([-2.06311181e-01, -4.56282467e-01, 7.78579706e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97729492]), + 'frame': 27987, + 'frame_number': 27987, + 'framesequence': 112675, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.7044312506914, + 'timestamp_carla': 950704, + 'timestamp_device': 1821305, + 'timestamp_stream': 950.7044312506914, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01372488e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.10771168, -0.23825073, 5.38227844]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.22853660583496, + 'FR_Wheel_Angle': -23.186601638793945, + 'Location': array([-57.64217758, 110.36671448, 0.13333783]), + 'Rotation': array([ 2.11052829e-03, 8.20422897e+01, -5.27859783e+00]), + 'Velocity': array([-1.83979794e-01, -4.26892430e-01, -3.36036668e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97714233]), + 'frame': 27988, + 'frame_number': 27988, + 'framesequence': 112679, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.7395124509931, + 'timestamp_carla': 950739, + 'timestamp_device': 1821338, + 'timestamp_stream': 950.7395124509931, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01380572e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.08697077, -0.1376971 , 4.79521704]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.19805335998535, + 'FR_Wheel_Angle': -23.097126007080078, + 'Location': array([-57.66778183, 110.29813385, 0.13335311]), + 'Rotation': array([ 3.79758491e-03, 8.26933594e+01, -5.27893448e+00]), + 'Velocity': array([-1.70068949e-01, -3.99563164e-01, 2.84557347e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97834015]), + 'frame': 27989, + 'frame_number': 27989, + 'framesequence': 112683, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.7725346498191, + 'timestamp_carla': 950772, + 'timestamp_device': 1821372, + 'timestamp_stream': 950.7725346498191, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01370469e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.07902262, 0.14570145, 2.97093821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.14237403869629, + 'FR_Wheel_Angle': -23.067604064941406, + 'Location': array([-57.69807434, 110.21352386, 0.13336101]), + 'Rotation': array([ 1.84415095e-03, 8.34895020e+01, -5.28180170e+00]), + 'Velocity': array([-1.76545978e-01, -4.27654535e-01, -4.53472130e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97753143]), + 'frame': 27990, + 'frame_number': 27990, + 'framesequence': 112687, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.8072929494083, + 'timestamp_carla': 950806, + 'timestamp_device': 1821405, + 'timestamp_stream': 950.8072929494083, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01379238e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.13153943, 0.24293156, 3.51962185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.14213752746582, + 'FR_Wheel_Angle': -23.06910514831543, + 'Location': array([-57.72218323, 110.14302826, 0.13338879]), + 'Rotation': array([-1.01086800e-03, 8.41478882e+01, -5.28610468e+00]), + 'Velocity': array([-1.80003881e-01, -4.72763211e-01, 4.56094749e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97853851]), + 'frame': 27991, + 'frame_number': 27991, + 'framesequence': 112691, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.8414997495711, + 'timestamp_carla': 950841, + 'timestamp_device': 1821438, + 'timestamp_stream': 950.8414997495711, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01380728e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.05797205, 0.06576762, 3.39808774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.15143394470215, + 'FR_Wheel_Angle': -23.071937561035156, + 'Location': array([-57.75126648, 110.05437469, 0.13334675]), + 'Rotation': array([ 1.22260384e-03, 8.50008698e+01, -5.28198576e+00]), + 'Velocity': array([-1.58738345e-01, -4.29020345e-01, 3.41186504e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97766113]), + 'frame': 27992, + 'frame_number': 27992, + 'framesequence': 112695, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.8742883503437, + 'timestamp_carla': 950873, + 'timestamp_device': 1821472, + 'timestamp_stream': 950.8742883503437, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01371877e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.050742 , 0.06006088, 3.20069528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.156604766845703, + 'FR_Wheel_Angle': -23.077402114868164, + 'Location': array([-57.77351761, 109.98438263, 0.13335781]), + 'Rotation': array([ 2.61596241e-03, 8.56748047e+01, -5.27951336e+00]), + 'Velocity': array([-1.45907685e-01, -4.10011917e-01, 8.77284983e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97751617]), + 'frame': 27993, + 'frame_number': 27993, + 'framesequence': 112699, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.9081965498626, + 'timestamp_carla': 950907, + 'timestamp_device': 1821505, + 'timestamp_stream': 950.9081965498626, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01376034e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.01583753, 0.02007663, 3.89573741]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.944337844848633, + 'FR_Wheel_Angle': -19.28916358947754, + 'Location': array([-57.80021667, 109.89286041, 0.13335666]), + 'Rotation': array([ 1.65290572e-03, 8.65151596e+01, -5.27774334e+00]), + 'Velocity': array([-1.45981893e-01, -4.38657165e-01, 3.85065068e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97840118]), + 'frame': 27994, + 'frame_number': 27994, + 'framesequence': 112703, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.9413905516267, + 'timestamp_carla': 950940, + 'timestamp_device': 1821538, + 'timestamp_stream': 950.9413905516267, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01373859e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.02528841, 0.08196966, 4.3496027 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.871334075927734, + 'FR_Wheel_Angle': -20.731597900390625, + 'Location': array([-57.8203125 , 109.81090546, 0.13337627]), + 'Rotation': array([ 1.03135849e-03, 8.71603851e+01, -5.27795696e+00]), + 'Velocity': array([-1.52263507e-01, -5.07834435e-01, 3.69186397e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97798157]), + 'frame': 27995, + 'frame_number': 27995, + 'framesequence': 112708, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 950.9766095504165, + 'timestamp_carla': 950976, + 'timestamp_device': 1821580, + 'timestamp_stream': 950.9766095504165, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01389498e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.01510276, 0.09675867, 3.5387578 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.924240112304688, + 'FR_Wheel_Angle': -20.43407440185547, + 'Location': array([-57.84354782, 109.7137146 , 0.13335204]), + 'Rotation': array([ 3.79075482e-03, 8.79423447e+01, -5.27612591e+00]), + 'Velocity': array([-1.26510009e-01, -4.55668092e-01, -4.17041774e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97820282]), + 'frame': 27996, + 'frame_number': 27996, + 'framesequence': 112712, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.0152283497155, + 'timestamp_carla': 951014, + 'timestamp_device': 1821613, + 'timestamp_stream': 951.0152283497155, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01430126e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.06336223, 0.08782217, 3.20912695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.9894962310791, + 'FR_Wheel_Angle': -20.336727142333984, + 'Location': array([-57.86393738, 109.62284851, 0.13334724]), + 'Rotation': array([ 3.11456621e-03, 8.86590576e+01, -5.27664423e+00]), + 'Velocity': array([-1.17126450e-01, -4.52206939e-01, -1.68895713e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97663879]), + 'frame': 27997, + 'frame_number': 27997, + 'framesequence': 112716, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.0486410520971, + 'timestamp_carla': 951048, + 'timestamp_device': 1821647, + 'timestamp_stream': 951.0486410520971, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01405941e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.03899834, 0.12864473, 3.32186818]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.969005584716797, + 'FR_Wheel_Angle': -20.310192108154297, + 'Location': array([-57.88304901, 109.53187561, 0.13334458]), + 'Rotation': array([ 3.79758491e-03, 8.93972168e+01, -5.27395916e+00]), + 'Velocity': array([-1.19149685e-01, -4.59729224e-01, -4.00543200e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97257233]), + 'frame': 27998, + 'frame_number': 27998, + 'framesequence': 112721, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.08600115031, + 'timestamp_carla': 951085, + 'timestamp_device': 1821688, + 'timestamp_stream': 951.08600115031, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01424024e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.06702671, 0.0663063 , 2.90971541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.96697998046875, + 'FR_Wheel_Angle': -20.307783126831055, + 'Location': array([-57.89892578, 109.45079041, 0.13334739]), + 'Rotation': array([ 4.94505651e-03, 9.00495605e+01, -5.26904535e+00]), + 'Velocity': array([-0.11822868, -0.49408522, 0.00049763]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97499084]), + 'frame': 27999, + 'frame_number': 27999, + 'framesequence': 112725, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.1200337521732, + 'timestamp_carla': 951119, + 'timestamp_device': 1821721, + 'timestamp_stream': 951.1200337521732, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01405025e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.02816568, -0.06506659, 3.73981047]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.97294044494629, + 'FR_Wheel_Angle': -20.312734603881836, + 'Location': array([-57.91654587, 109.35600281, 0.13334171]), + 'Rotation': array([ 4.92456602e-03, 9.07989807e+01, -5.27484369e+00]), + 'Velocity': array([-1.07932121e-01, -4.78601754e-01, -1.08861917e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97318268]), + 'frame': 28000, + 'frame_number': 28000, + 'framesequence': 112729, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.154901150614, + 'timestamp_carla': 951154, + 'timestamp_device': 1821755, + 'timestamp_stream': 951.154901150614, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01400256e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.01183512, -0.12323959, 3.34242606]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.992881774902344, + 'FR_Wheel_Angle': -20.32419776916504, + 'Location': array([-57.92940903, 109.28111267, 0.1333458 ]), + 'Rotation': array([ 5.07483026e-03, 9.13909760e+01, -5.27456951e+00]), + 'Velocity': array([-9.13726762e-02, -4.34363306e-01, 7.47632948e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.9750824 ]), + 'frame': 28001, + 'frame_number': 28001, + 'framesequence': 112733, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.1871497519314, + 'timestamp_carla': 951186, + 'timestamp_device': 1821788, + 'timestamp_stream': 951.1871497519314, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01378709e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.00545862, 0.04086965, 3.96680045]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.972814559936523, + 'FR_Wheel_Angle': -16.163856506347656, + 'Location': array([-57.94278336, 109.19496918, 0.13333443]), + 'Rotation': array([ 4.21422627e-03, 9.20534363e+01, -5.27408075e+00]), + 'Velocity': array([-7.83543587e-02, -4.54574466e-01, 2.30655671e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97556305]), + 'frame': 28002, + 'frame_number': 28002, + 'framesequence': 112737, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.2188320495188, + 'timestamp_carla': 951218, + 'timestamp_device': 1821821, + 'timestamp_stream': 951.2188320495188, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01363182e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.14568089, -0.11240039, 4.60487127]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.669179916381836, + 'FR_Wheel_Angle': -17.962570190429688, + 'Location': array([-57.9536705 , 109.09939575, 0.13334805]), + 'Rotation': array([ 1.61875470e-03, 9.26645508e+01, -5.27765131e+00]), + 'Velocity': array([-7.53560886e-02, -4.94613409e-01, -2.88457872e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': True, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97771454]), + 'frame': 28003, + 'frame_number': 28003, + 'framesequence': 112740, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.2515063509345, + 'timestamp_carla': 951251, + 'timestamp_device': 1821846, + 'timestamp_stream': 951.2515063509345, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01362035e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.12859108, -0.1228755 , 4.06721115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.46613883972168, + 'FR_Wheel_Angle': -17.329540252685547, + 'Location': array([-57.96244049, 109.0202713 , 0.13335727]), + 'Rotation': array([ 3.63366050e-03, 9.31792679e+01, -5.27859735e+00]), + 'Velocity': array([-6.51365072e-02, -4.68917727e-01, 2.46071810e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97927094]), + 'frame': 28004, + 'frame_number': 28004, + 'framesequence': 112744, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.2834480516613, + 'timestamp_carla': 951282, + 'timestamp_device': 1821880, + 'timestamp_stream': 951.2834480516613, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01357646e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.01311604, -0.0755879 , 2.73388529]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.772056579589844, + 'FR_Wheel_Angle': -17.370330810546875, + 'Location': array([-57.97056198, 108.93975067, 0.13334937]), + 'Rotation': array([ 3.66781140e-03, 9.37069702e+01, -5.27725506e+00]), + 'Velocity': array([-5.81289195e-02, -4.74643767e-01, -9.64641586e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97938538]), + 'frame': 28005, + 'frame_number': 28005, + 'framesequence': 112748, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.3151942491531, + 'timestamp_carla': 951314, + 'timestamp_device': 1821913, + 'timestamp_stream': 951.3151942491531, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01355128e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-3.59725046, 5.30680561, 0.73940146]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.78293228149414, + 'FR_Wheel_Angle': -17.407751083374023, + 'Location': array([-57.97579575, 108.84919739, 0.12558731]), + 'Rotation': array([-0.37264827, 94.14283752, -6.02365541]), + 'Velocity': array([ 0.02335427, -0.51677567, -0.09935151]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97982025]), + 'frame': 28006, + 'frame_number': 28006, + 'framesequence': 112752, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.3503214493394, + 'timestamp_carla': 951349, + 'timestamp_device': 1821946, + 'timestamp_stream': 951.3503214493394, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01381034e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.04133428, 0.33496824, -0.15067659]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.806684494018555, + 'FR_Wheel_Angle': -17.42732048034668, + 'Location': array([-57.97145844, 108.76712799, 0.12528534]), + 'Rotation': array([-0.29876611, 94.34111786, -5.71722794]), + 'Velocity': array([ 0.01022731, -0.46636015, 0.01001508]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.98007202]), + 'frame': 28007, + 'frame_number': 28007, + 'framesequence': 112757, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.3856018520892, + 'timestamp_carla': 951385, + 'timestamp_device': 1821988, + 'timestamp_stream': 951.3856018520892, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01397172e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.06685431, 0.06977038, -0.43711665]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.822986602783203, + 'FR_Wheel_Angle': -17.43532371520996, + 'Location': array([-57.96802521, 108.69493866, 0.12689026]), + 'Rotation': array([-0.26211533, 94.45796204, -5.64050627]), + 'Velocity': array([ 0.0176321 , -0.42008168, 0.0050186 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97748566]), + 'frame': 28008, + 'frame_number': 28008, + 'framesequence': 112761, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.4193499498069, + 'timestamp_carla': 951418, + 'timestamp_device': 1822021, + 'timestamp_stream': 951.4193499498069, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01393618e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.04946124, -0.32343888, -0.15302803]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.82449722290039, + 'FR_Wheel_Angle': -17.43321418762207, + 'Location': array([-57.96451187, 108.62497711, 0.12732528]), + 'Rotation': array([-0.25897345, 94.56968689, -5.62268353]), + 'Velocity': array([ 1.89783275e-02, -4.28924292e-01, 2.36129752e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97586823]), + 'frame': 28009, + 'frame_number': 28009, + 'framesequence': 112764, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.4508937522769, + 'timestamp_carla': 951450, + 'timestamp_device': 1822046, + 'timestamp_stream': 951.4508937522769, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01376191e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.00192131, 0.04443251, -0.26883131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.815311431884766, + 'FR_Wheel_Angle': -17.427120208740234, + 'Location': array([-57.96070862, 108.55365753, 0.12775016]), + 'Rotation': array([-0.24167258, 94.69389343, -5.57443619]), + 'Velocity': array([ 0.01669789, -0.44091532, 0.00388962]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97622681]), + 'frame': 28010, + 'frame_number': 28010, + 'framesequence': 112768, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.4824663512409, + 'timestamp_carla': 951481, + 'timestamp_device': 1822080, + 'timestamp_stream': 951.4824663512409, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01366572e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-0.03912055, -0.23842652, -0.3287513 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.51455307006836, + 'FR_Wheel_Angle': -13.858419418334961, + 'Location': array([-57.95666885, 108.47940063, 0.12864265]), + 'Rotation': array([-0.20660639, 94.83132172, -5.51327896]), + 'Velocity': array([ 2.98235025e-02, -4.55428600e-01, -2.03561780e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97796631]), + 'frame': 28011, + 'frame_number': 28011, + 'framesequence': 112772, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.5150825493038, + 'timestamp_carla': 951514, + 'timestamp_device': 1822113, + 'timestamp_stream': 951.5150825493038, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01368785e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-1.02822042, 2.33855605, 0.97345173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.70949935913086, + 'FR_Wheel_Angle': -14.906601905822754, + 'Location': array([-57.95166016, 108.39533234, 0.12687747]), + 'Rotation': array([-0.29098654, 94.94561768, -5.68924236]), + 'Velocity': array([ 0.03184915, -0.51607704, -0.02337399]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97892761]), + 'frame': 28012, + 'frame_number': 28012, + 'framesequence': 112776, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.5484588518739, + 'timestamp_carla': 951547, + 'timestamp_device': 1822146, + 'timestamp_stream': 951.5484588518739, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01376452e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.01947298, -0.1002518 , -0.55248332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.330387115478516, + 'FR_Wheel_Angle': -14.108011245727539, + 'Location': array([-57.94609833, 108.30243683, 0.12630592]), + 'Rotation': array([-0.29705173, 95.09741211, -5.68249941]), + 'Velocity': array([ 0.03375163, -0.5534541 , 0.00162973]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97870636]), + 'frame': 28013, + 'frame_number': 28013, + 'framesequence': 112780, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.5814302489161, + 'timestamp_carla': 951580, + 'timestamp_device': 1822180, + 'timestamp_stream': 951.5814302489161, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01378210e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.03637801, -0.11757978, -0.09155197]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.64056968688965, + 'FR_Wheel_Angle': -14.305655479431152, + 'Location': array([-57.93949509, 108.19283295, 0.12587127]), + 'Rotation': array([-0.31710517, 95.2922287 , -5.71942616]), + 'Velocity': array([ 0.03207735, -0.6057421 , 0.00335702]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97794342]), + 'frame': 28014, + 'frame_number': 28014, + 'framesequence': 112784, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.6170537509024, + 'timestamp_carla': 951616, + 'timestamp_device': 1822213, + 'timestamp_stream': 951.6170537509024, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01400681e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.04915815, -0.51984394, 0.13972145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.592069625854492, + 'FR_Wheel_Angle': -14.34256649017334, + 'Location': array([-57.93349838, 108.09142303, 0.12549846]), + 'Rotation': array([-0.33755475, 95.46606445, -5.767735 ]), + 'Velocity': array([ 0.03453278, -0.61321551, -0.00111433]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97776794]), + 'frame': 28015, + 'frame_number': 28015, + 'framesequence': 112788, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.6489773504436, + 'timestamp_carla': 951648, + 'timestamp_device': 1822246, + 'timestamp_stream': 951.6489773504436, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01384774e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.05375572, -0.54102778, 0.10961526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.5906925201416, + 'FR_Wheel_Angle': -14.341031074523926, + 'Location': array([-57.92608643, 107.97102356, 0.12496158]), + 'Rotation': array([-0.35797021, 95.67821503, -5.80881071]), + 'Velocity': array([ 0.03711428, -0.61809468, -0.00122056]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97551727]), + 'frame': 28016, + 'frame_number': 28016, + 'framesequence': 112792, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.6844335496426, + 'timestamp_carla': 951683, + 'timestamp_device': 1822280, + 'timestamp_stream': 951.6844335496426, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01402201e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.06517302, -0.50131577, 0.20323811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.587238311767578, + 'FR_Wheel_Angle': -14.337942123413086, + 'Location': array([-57.91952515, 107.86873627, 0.12449226]), + 'Rotation': array([-0.37671223, 95.86795807, -5.84643793]), + 'Velocity': array([ 3.79994847e-02, -6.28177881e-01, -2.50871177e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97711182]), + 'frame': 28017, + 'frame_number': 28017, + 'framesequence': 112796, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.7155698500574, + 'timestamp_carla': 951715, + 'timestamp_device': 1822313, + 'timestamp_stream': 951.7155698500574, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01380117e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.07071914, -0.59879452, 0.3474772 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.581157684326172, + 'FR_Wheel_Angle': -14.333048820495605, + 'Location': array([-57.91062546, 107.73818207, 0.12379944]), + 'Rotation': array([-0.40414912, 96.12399292, -5.90076065]), + 'Velocity': array([ 0.04368547, -0.65318608, -0.00070549]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97536469]), + 'frame': 28018, + 'frame_number': 28018, + 'framesequence': 112800, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.7482001520693, + 'timestamp_carla': 951747, + 'timestamp_device': 1822346, + 'timestamp_stream': 951.7482001520693, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01376988e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.09949472, -0.65216863, 0.50233245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.57127571105957, + 'FR_Wheel_Angle': -14.238495826721191, + 'Location': array([-57.90233231, 107.62224579, 0.12309566]), + 'Rotation': array([-0.43536305, 96.3628006 , -5.9586525 ]), + 'Velocity': array([ 4.54775952e-02, -6.84875906e-01, -5.35578700e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97757721]), + 'frame': 28019, + 'frame_number': 28019, + 'framesequence': 112804, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.7838509492576, + 'timestamp_carla': 951783, + 'timestamp_device': 1822380, + 'timestamp_stream': 951.7838509492576, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01399496e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-2.73174477, 5.07384396, 0.27537954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.858570098876953, + 'FR_Wheel_Angle': -9.730392456054688, + 'Location': array([-57.89324188, 107.50314331, 0.12101181]), + 'Rotation': array([-0.5380823 , 96.57322693, -6.2034049 ]), + 'Velocity': array([ 0.07025798, -0.66704863, -0.05303065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97789001]), + 'frame': 28020, + 'frame_number': 28020, + 'framesequence': 112808, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.8152941502631, + 'timestamp_carla': 951814, + 'timestamp_device': 1822413, + 'timestamp_stream': 951.8152941502631, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01380423e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([0.68830258, 0.56216955, 0.61274868]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.369834899902344, + 'FR_Wheel_Angle': -11.618077278137207, + 'Location': array([-57.88108826, 107.40960693, 0.11607059]), + 'Rotation': array([-0.51028341, 96.67892456, -6.39230824]), + 'Velocity': array([ 0.06651843, -0.47176552, -0.01619358]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97563934]), + 'frame': 28021, + 'frame_number': 28021, + 'framesequence': 112812, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.8502168506384, + 'timestamp_carla': 951849, + 'timestamp_device': 1822446, + 'timestamp_stream': 951.8502168506384, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01394765e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-1.60532677, 2.28548527, 0.14607197]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.252311706542969, + 'FR_Wheel_Angle': -11.176053047180176, + 'Location': array([-57.87541199, 107.33274841, 0.11648243]), + 'Rotation': array([-0.49267519, 96.8719635 , -6.43985462]), + 'Velocity': array([ 0.06397967, -0.41875294, -0.02869869]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97754669]), + 'frame': 28022, + 'frame_number': 28022, + 'framesequence': 112816, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.8828373514116, + 'timestamp_carla': 951882, + 'timestamp_device': 1822480, + 'timestamp_stream': 951.8828373514116, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01385117e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-2.64257836, 4.51039982, 0.91204697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.432246208190918, + 'FR_Wheel_Angle': -11.165452003479004, + 'Location': array([-57.86942291, 107.25800323, 0.1171426 ]), + 'Rotation': array([-0.49887016, 97.05885315, -6.43747473]), + 'Velocity': array([ 0.02994287, -0.46428153, -0.03164236]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97611237]), + 'frame': 28023, + 'frame_number': 28023, + 'framesequence': 112820, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.9169499501586, + 'timestamp_carla': 951916, + 'timestamp_device': 1822513, + 'timestamp_stream': 951.9169499501586, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01390570e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 1.90685594, -3.44323516, 1.5353111 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.495739936828613, + 'FR_Wheel_Angle': -11.152859687805176, + 'Location': array([-57.86118698, 107.16274261, 0.11773212]), + 'Rotation': array([-0.45706257, 97.2759552 , -6.35208559]), + 'Velocity': array([-0.01221934, -0.4070532 , 0.04425915]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97707367]), + 'frame': 28024, + 'frame_number': 28024, + 'framesequence': 112825, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 951.9507985524833, + 'timestamp_carla': 951950, + 'timestamp_device': 1822555, + 'timestamp_stream': 951.9507985524833, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01390570e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([ 0.61936271, -0.64781725, 2.41689777]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.50288200378418, + 'FR_Wheel_Angle': -11.171926498413086, + 'Location': array([-57.85508728, 107.09186554, 0.11703045]), + 'Rotation': array([-0.48416477, 97.47888184, -6.47244835]), + 'Velocity': array([ 0.03785809, -0.36373633, -0.00060956]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97653198]), + 'frame': 28025, + 'frame_number': 28025, + 'framesequence': 112828, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.019836727529764175, + 'timestamp': 951.984487850219, + 'timestamp_carla': 951983, + 'timestamp_device': 1822580, + 'timestamp_stream': 951.984487850219, + 'transform': [array([-6.42667007e+01, 1.02939606e+02, -1.01390570e-01]), + array([-4.40547196e-03, 1.46001022e+02, 6.93947170e-03])]} +{'AngularVelocity': array([-1.27469552, 1.85502934, 0.90009201]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.50352954864502, + 'FR_Wheel_Angle': -11.178613662719727, + 'Location': array([-57.84959793, 107.02894592, 0.11736496]), + 'Rotation': array([-0.49413684, 97.65632629, -6.46210289]), + 'Velocity': array([ 0.05325246, -0.36848798, -0.02571563]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97653198]), + 'frame': 28026, + 'frame_number': 28026, + 'framesequence': 112832, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.027771420776844025, + 'timestamp': 952.0159764513373, + 'timestamp_carla': 952015, + 'timestamp_device': 1822613, + 'timestamp_stream': 952.0159764513373, + 'transform': [array([-6.42660065e+01, 1.02939400e+02, -1.01457544e-01]), + array([-4.48060408e-03, 1.46003784e+02, 7.28098117e-03])]} +{'AngularVelocity': array([ 0.13902561, -0.26695025, 0.48087665]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.496893882751465, + 'FR_Wheel_Angle': -11.156682968139648, + 'Location': array([-57.84344101, 106.96998596, 0.11721092]), + 'Rotation': array([-0.48760718, 97.82602692, -6.47073746]), + 'Velocity': array([ 0.06501085, -0.38899329, -0.01006247]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.380126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61572266, 13038.828125 , 122.97653198]), + 'frame': 28027, + 'frame_number': 28027, + 'framesequence': 112836, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.03967345505952835, + 'timestamp': 952.0498567521572, + 'timestamp_carla': 952049, + 'timestamp_device': 1822646, + 'timestamp_stream': 952.0498567521572, + 'transform': [array([-6.42660446e+01, 1.02939507e+02, -1.01442851e-01]), + array([-4.41230182e-03, 1.46003433e+02, 7.19218887e-03])]} +{'AngularVelocity': array([ 1.40664041, -2.05863118, 0.62990272]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.13018798828125, + 'FR_Wheel_Angle': -7.808115482330322, + 'Location': array([-57.83601379, 106.89111328, 0.11764038]), + 'Rotation': array([-0.48153514, 98.05430603, -6.43826818]), + 'Velocity': array([ 0.02279613, -0.28689849, 0.01496728]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.40625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.66503906, 13038.9296875 , 122.99062347]), + 'frame': 28028, + 'frame_number': 28028, + 'framesequence': 112840, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.09919890016317368, + 'timestamp': 952.081549551338, + 'timestamp_carla': 952081, + 'timestamp_device': 1822680, + 'timestamp_stream': 952.081549551338, + 'transform': [array([-6.42660370e+01, 1.02939529e+02, -1.01431593e-01]), + array([-4.41230182e-03, 1.46003433e+02, 7.19218887e-03])]} +{'AngularVelocity': array([ 2.07740521, -3.39689898, -0.3133302 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.023710250854492, + 'FR_Wheel_Angle': -8.203828811645508, + 'Location': array([-57.82961655, 106.82579803, 0.12276966]), + 'Rotation': array([-0.31748083, 98.19978333, -6.00018787]), + 'Velocity': array([-0.00292383, -0.36162248, 0.0662737 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.3935546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65917969, 13038.91601562, 122.98651123]), + 'frame': 28029, + 'frame_number': 28029, + 'framesequence': 112844, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.15078964829444885, + 'timestamp': 952.1153220497072, + 'timestamp_carla': 952114, + 'timestamp_device': 1822713, + 'timestamp_stream': 952.1153220497072, + 'transform': [array([-6.42661133e+01, 1.02939522e+02, -1.01412863e-01]), + array([-4.39864164e-03, 1.46003174e+02, 7.07607623e-03])]} +{'AngularVelocity': array([ 2.02770257, -3.56581998, 1.26078379]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.123832702636719, + 'FR_Wheel_Angle': -7.355318546295166, + 'Location': array([-57.82398987, 106.75963593, 0.12167679]), + 'Rotation': array([-0.45980832, 98.35884857, -6.23151016]), + 'Velocity': array([ 0.00281318, -0.38880309, 0.03296531]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.3916015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65917969, 13038.91699219, 122.98764038]), + 'frame': 28030, + 'frame_number': 28030, + 'framesequence': 112848, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.18252842128276825, + 'timestamp': 952.1489579491317, + 'timestamp_carla': 952148, + 'timestamp_device': 1822746, + 'timestamp_stream': 952.1489579491317, + 'transform': [array([-6.42661667e+01, 1.02939430e+02, -1.01416759e-01]), + array([-4.39864164e-03, 1.46003174e+02, 7.07607623e-03])]} +{'AngularVelocity': array([-2.46304798, 4.86121607, 1.97575974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.461627960205078, + 'FR_Wheel_Angle': -7.712823390960693, + 'Location': array([-57.81753159, 106.67933655, 0.12762398]), + 'Rotation': array([-0.22948751, 98.58388519, -5.77456999]), + 'Velocity': array([ 0.04240365, -0.53196806, -0.02370819]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.39208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65332031, 13038.90722656, 122.9825058 ]), + 'frame': 28031, + 'frame_number': 28031, + 'framesequence': 112852, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2063324898481369, + 'timestamp': 952.1820560507476, + 'timestamp_carla': 952181, + 'timestamp_device': 1822780, + 'timestamp_stream': 952.1820560507476, + 'transform': [array([-6.42662430e+01, 1.02939301e+02, -1.01414889e-01]), + array([-4.39864164e-03, 1.46003174e+02, 7.07607623e-03])]} +{'AngularVelocity': array([ 2.12584639, -3.19162083, 0.00338564]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.367851257324219, + 'FR_Wheel_Angle': -7.709315299987793, + 'Location': array([-57.80924606, 106.5954895 , 0.123904 ]), + 'Rotation': array([-0.36874139, 98.78177643, -6.01169252]), + 'Velocity': array([ 0.009505 , -0.46002382, 0.04327993]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.40185546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65332031, 13038.90625 , 122.9821167 ]), + 'frame': 28032, + 'frame_number': 28032, + 'framesequence': 112856, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.21824978291988373, + 'timestamp': 952.2153817489743, + 'timestamp_carla': 952214, + 'timestamp_device': 1822813, + 'timestamp_stream': 952.2153817489743, + 'transform': [array([-6.42663574e+01, 1.02939140e+02, -1.01415381e-01]), + array([-4.39864164e-03, 1.46003174e+02, 7.07607623e-03])]} +{'AngularVelocity': array([ 1.0657649 , -1.51821172, 0.12832634]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.321700096130371, + 'FR_Wheel_Angle': -7.705758571624756, + 'Location': array([-57.80321503, 106.5253067 , 0.12938224]), + 'Rotation': array([-0.14630264, 98.96764374, -5.59241104]), + 'Velocity': array([ 0.01975479, -0.43294951, 0.03334142]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.416259765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65332031, 13038.90527344, 122.98230743]), + 'frame': 28033, + 'frame_number': 28033, + 'framesequence': 112860, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 952.2511911503971, + 'timestamp_carla': 952250, + 'timestamp_device': 1822846, + 'timestamp_stream': 952.2511911503971, + 'transform': [array([-6.42665787e+01, 1.02938911e+02, -1.01419874e-01]), + array([-4.39864164e-03, 1.46002930e+02, 7.00777350e-03])]} +{'AngularVelocity': array([ 0.38178474, -0.67528057, 1.01476979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.313569068908691, + 'FR_Wheel_Angle': -7.698745250701904, + 'Location': array([-57.79673767, 106.45272064, 0.13217129]), + 'Rotation': array([-5.32823019e-02, 9.91634140e+01, -5.41058588e+00]), + 'Velocity': array([ 0.03260883, -0.48843214, 0.01237689]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.43701171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65332031, 13038.90625 , 122.98226166]), + 'frame': 28034, + 'frame_number': 28034, + 'framesequence': 112865, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.2855378501117, + 'timestamp_carla': 952285, + 'timestamp_device': 1822888, + 'timestamp_stream': 952.2855378501117, + 'transform': [array([-6.42667770e+01, 1.02938629e+02, -1.01417929e-01]), + array([-4.39864164e-03, 1.46002930e+02, 7.00777350e-03])]} +{'AngularVelocity': array([ 0.21841753, -0.323309 , 1.26856077]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.318000793457031, + 'FR_Wheel_Angle': -7.703803062438965, + 'Location': array([-57.78943634, 106.37698364, 0.13306239]), + 'Rotation': array([-1.73076987e-02, 9.93691101e+01, -5.33258390e+00]), + 'Velocity': array([ 0.03488682, -0.441221 , 0.0037854 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.46337890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.64941406, 13038.89746094, 122.97770691]), + 'frame': 28035, + 'frame_number': 28035, + 'framesequence': 112869, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.3200545497239, + 'timestamp_carla': 952319, + 'timestamp_device': 1822921, + 'timestamp_stream': 952.3200545497239, + 'transform': [array([-6.42669983e+01, 1.02938286e+02, -1.01417281e-01]), + array([-4.39864164e-03, 1.46002930e+02, 7.00777350e-03])]} +{'AngularVelocity': array([ 0.15711229, -0.13790092, 1.72741401]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.321250915527344, + 'FR_Wheel_Angle': -7.701901912689209, + 'Location': array([-57.78070068, 106.29012299, 0.13330349]), + 'Rotation': array([-1.80316984e-03, 9.96130829e+01, -5.29745722e+00]), + 'Velocity': array([ 0.0340243 , -0.40145484, 0.00058264]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.497802734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.64990234, 13038.8984375 , 122.97790527]), + 'frame': 28036, + 'frame_number': 28036, + 'framesequence': 112872, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.3517069518566, + 'timestamp_carla': 952351, + 'timestamp_device': 1822946, + 'timestamp_stream': 952.3517069518566, + 'transform': [array([-6.42671890e+01, 1.02937897e+02, -1.01386920e-01]), + array([-4.41230182e-03, 1.46003143e+02, 6.96679298e-03])]} +{'AngularVelocity': array([ 0.0432025 , -0.04072292, 0.77132183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.508421897888184, + 'FR_Wheel_Angle': -3.746364116668701, + 'Location': array([-57.7718544 , 106.21101379, 0.1333514 ]), + 'Rotation': array([ 9.49396228e-04, 9.98225937e+01, -5.28570795e+00]), + 'Velocity': array([ 5.38890027e-02, -4.70926642e-01, 1.88970560e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.538330078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.64941406, 13038.89746094, 122.97798157]), + 'frame': 28037, + 'frame_number': 28037, + 'framesequence': 112877, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.3855866491795, + 'timestamp_carla': 952385, + 'timestamp_device': 1822988, + 'timestamp_stream': 952.3855866491795, + 'transform': [array([-6.42675323e+01, 1.02937462e+02, -1.01374090e-01]), + array([-4.40547196e-03, 1.46002945e+02, 6.89849025e-03])]} +{'AngularVelocity': array([-0.01817937, 0.02909835, 0.56392938]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.14914608001709, + 'FR_Wheel_Angle': -4.632800579071045, + 'Location': array([-57.760746 , 106.13506317, 0.13334747]), + 'Rotation': array([ 4.26203758e-03, 9.99085464e+01, -5.27997112e+00]), + 'Velocity': array([ 5.91211990e-02, -4.41006511e-01, 3.99579993e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.584228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65283203, 13038.90429688, 122.97859192]), + 'frame': 28038, + 'frame_number': 28038, + 'framesequence': 112880, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.41727675125, + 'timestamp_carla': 952416, + 'timestamp_device': 1823013, + 'timestamp_stream': 952.41727675125, + 'transform': [array([-6.42678223e+01, 1.02936951e+02, -1.01349667e-01]), + array([-4.41230182e-03, 1.46003082e+02, 6.85067941e-03])]} +{'AngularVelocity': array([-0.01162459, 0.01253027, 0.64679962]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.893077850341797, + 'FR_Wheel_Angle': -3.671231985092163, + 'Location': array([-57.75112152, 106.06578827, 0.13333778]), + 'Rotation': array([ 4.29618871e-03, 1.00008705e+02, -5.27969646e+00]), + 'Velocity': array([ 0.0560238 , -0.41677904, -0.00042563]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.6357421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.6484375 , 13038.89550781, 122.97576904]), + 'frame': 28039, + 'frame_number': 28039, + 'framesequence': 112884, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.4490864500403, + 'timestamp_carla': 952448, + 'timestamp_device': 1823046, + 'timestamp_stream': 952.4490864500403, + 'transform': [array([-6.42681885e+01, 1.02936386e+02, -1.01343028e-01]), + array([-4.41230182e-03, 1.46003082e+02, 6.85067941e-03])]} +{'AngularVelocity': array([-0.1305393 , 0.00993293, -0.6187883 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.279423713684082, + 'FR_Wheel_Angle': -4.019546031951904, + 'Location': array([-57.74123001, 105.99740601, 0.13336189]), + 'Rotation': array([ 2.01490568e-03, 1.00101601e+02, -5.28051996e+00]), + 'Velocity': array([ 5.69139123e-02, -4.22752172e-01, -3.54194635e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.6953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.65039062, 13038.89941406, 122.97535706]), + 'frame': 28040, + 'frame_number': 28040, + 'framesequence': 112888, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.4823927506804, + 'timestamp_carla': 952481, + 'timestamp_device': 1823080, + 'timestamp_stream': 952.4823927506804, + 'transform': [array([-6.42686615e+01, 1.02935753e+02, -1.01338968e-01]), + array([-4.40547196e-03, 1.46002914e+02, 6.80286810e-03])]} +{'AngularVelocity': array([-0.08830025, 0.01382709, -0.49362779]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.187403202056885, + 'FR_Wheel_Angle': -3.995706081390381, + 'Location': array([-57.73026276, 105.92222595, 0.13337363]), + 'Rotation': array([-9.15245269e-04, 1.00199287e+02, -5.28201580e+00]), + 'Velocity': array([ 6.20944537e-02, -4.53430027e-01, 7.38620729e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.762939453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.64990234, 13038.89941406, 122.97602844]), + 'frame': 28041, + 'frame_number': 28041, + 'framesequence': 112892, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.5169244520366, + 'timestamp_carla': 952516, + 'timestamp_device': 1823113, + 'timestamp_stream': 952.5169244520366, + 'transform': [array([-6.42691956e+01, 1.02935036e+02, -1.01348467e-01]), + array([-4.39864164e-03, 1.46002716e+02, 6.78237760e-03])]} +{'AngularVelocity': array([-0.09810852, -0.00112989, 0.40487576]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.152559757232666, + 'FR_Wheel_Angle': -3.990401268005371, + 'Location': array([-57.71921158, 105.84801483, 0.13333522]), + 'Rotation': array([ 5.48464153e-03, 1.00322945e+02, -5.28198576e+00]), + 'Velocity': array([ 7.00446367e-02, -4.87072796e-01, 1.23748774e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.83837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.64599609, 13038.890625 , 122.97354889]), + 'frame': 28042, + 'frame_number': 28042, + 'framesequence': 112896, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.5490202493966, + 'timestamp_carla': 952548, + 'timestamp_device': 1823146, + 'timestamp_stream': 952.5490202493966, + 'transform': [array([-6.42696838e+01, 1.02934296e+02, -1.01338588e-01]), + array([-4.39864164e-03, 1.46002716e+02, 6.78237760e-03])]} +{'AngularVelocity': array([-0.10248338, 0.00291137, -0.54440981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.154355525970459, + 'FR_Wheel_Angle': -3.992912530899048, + 'Location': array([-57.70527649, 105.75488281, 0.13334621]), + 'Rotation': array([ 3.03260377e-03, 1.00444527e+02, -5.28290129e+00]), + 'Velocity': array([ 6.37980327e-02, -4.52293962e-01, -6.65950793e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2109.923095703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.64208984, 13038.8828125 , 122.97135162]), + 'frame': 28043, + 'frame_number': 28043, + 'framesequence': 112900, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 952.5821517519653, + 'timestamp_carla': 952581, + 'timestamp_device': 1823180, + 'timestamp_stream': 952.5821517519653, + 'transform': [array([-6.42702713e+01, 1.02933487e+02, -1.01335377e-01]), + array([-4.39864164e-03, 1.46002518e+02, 6.76188665e-03])]} +{'AngularVelocity': array([0.04132711, 0.03604285, 1.33756626]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.154888153076172, + 'FR_Wheel_Angle': -3.9932358264923096, + 'Location': array([-57.69338608, 105.67708588, 0.13335571]), + 'Rotation': array([ 2.47935858e-03, 1.00557304e+02, -5.28131437e+00]), + 'Velocity': array([ 0.06514107, -0.45952675, 0.00049081]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.011474609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.64160156, 13038.88183594, 122.97234344]), + 'frame': 28044, + 'frame_number': 28044, + 'framesequence': 112904, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2380865216255188, + 'timestamp': 952.6174450516701, + 'timestamp_carla': 952616, + 'timestamp_device': 1823213, + 'timestamp_stream': 952.6174450516701, + 'transform': [array([-6.42709732e+01, 1.02932579e+02, -1.01351850e-01]), + array([-4.38498100e-03, 1.46002151e+02, 6.75505726e-03])]} +{'AngularVelocity': array([ 0.0510323 , -0.01341568, 0.86648065]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.15272331237793, + 'FR_Wheel_Angle': -3.954702377319336, + 'Location': array([-57.68122864, 105.59786987, 0.13337623]), + 'Rotation': array([ 5.53245307e-04, 1.00658546e+02, -5.28122187e+00]), + 'Velocity': array([ 6.96366876e-02, -4.69751447e-01, 1.24077793e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.10693359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.63818359, 13038.87304688, 122.97143555]), + 'frame': 28045, + 'frame_number': 28045, + 'framesequence': 112908, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 952.64910935238, + 'timestamp_carla': 952648, + 'timestamp_device': 1823246, + 'timestamp_stream': 952.64910935238, + 'transform': [array([-6.42715683e+01, 1.02931679e+02, -1.01334877e-01]), + array([-4.38498100e-03, 1.46002151e+02, 6.75505726e-03])]} +{'AngularVelocity': array([-0.0793919 , -0.03502554, -1.23321927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.1539725065231323, + 'FR_Wheel_Angle': 1.7997685670852661, + 'Location': array([-57.66469574, 105.49983215, 0.13336624]), + 'Rotation': array([ 1.14747172e-03, 1.00741661e+02, -5.27850580e+00]), + 'Velocity': array([ 1.00614756e-01, -5.09436250e-01, -1.92518230e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.2158203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.63085938, 13038.86035156, 122.96935272]), + 'frame': 28046, + 'frame_number': 28046, + 'framesequence': 112912, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.269825279712677, + 'timestamp': 952.681972950697, + 'timestamp_carla': 952681, + 'timestamp_device': 1823279, + 'timestamp_stream': 952.681972950697, + 'transform': [array([-6.42722855e+01, 1.02930702e+02, -1.01326734e-01]), + array([-4.38498100e-03, 1.46001968e+02, 6.72773598e-03])]} +{'AngularVelocity': array([-9.52206999e-02, -5.89103802e-05, -1.01534939e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8807496428489685, + 'FR_Wheel_Angle': -0.7270358800888062, + 'Location': array([-57.64926529, 105.41989899, 0.13334396]), + 'Rotation': array([ 4.68550948e-03, 1.00725624e+02, -5.28174162e+00]), + 'Velocity': array([ 8.27956945e-02, -4.61182624e-01, -1.89237588e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.322509765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.63085938, 13038.859375 , 122.97106934]), + 'frame': 28047, + 'frame_number': 28047, + 'framesequence': 112917, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2737926244735718, + 'timestamp': 952.7200327515602, + 'timestamp_carla': 952719, + 'timestamp_device': 1823321, + 'timestamp_stream': 952.7200327515602, + 'transform': [array([-6.42732544e+01, 1.02929527e+02, -1.01370320e-01]), + array([-4.36449051e-03, 1.46001358e+02, 6.72773598e-03])]} +{'AngularVelocity': array([-0.10255834, -0.01431613, -0.99851286]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3206324279308319, + 'FR_Wheel_Angle': 0.12710009515285492, + 'Location': array([-57.63527679, 105.34495544, 0.13334189]), + 'Rotation': array([ 5.34120761e-03, 1.00728630e+02, -5.28158760e+00]), + 'Velocity': array([ 8.80555809e-02, -4.54448998e-01, -1.61762233e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.43896484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.62695312, 13038.85058594, 122.97025299]), + 'frame': 28048, + 'frame_number': 28048, + 'framesequence': 112921, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.27775996923446655, + 'timestamp': 952.7533495500684, + 'timestamp_carla': 952752, + 'timestamp_device': 1823354, + 'timestamp_stream': 952.7533495500684, + 'transform': [array([-6.42740173e+01, 1.02928398e+02, -1.01352431e-01]), + array([-4.36449051e-03, 1.46001358e+02, 6.72773598e-03])]} +{'AngularVelocity': array([ 0.02082817, -0.00323223, 0.14258285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0787762850522995, + 'FR_Wheel_Angle': 0.015259508974850178, + 'Location': array([-57.6206665 , 105.26821899, 0.13334663]), + 'Rotation': array([ 3.60633968e-03, 1.00733727e+02, -5.28079557e+00]), + 'Velocity': array([ 8.54976848e-02, -4.48194176e-01, 1.04923245e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.581787109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61523438, 13038.82910156, 122.96583557]), + 'frame': 28049, + 'frame_number': 28049, + 'framesequence': 112925, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.28172731399536133, + 'timestamp': 952.7850902490318, + 'timestamp_carla': 952784, + 'timestamp_device': 1823388, + 'timestamp_stream': 952.7850902490318, + 'transform': [array([-6.42748566e+01, 1.02927231e+02, -1.01313263e-01]), + array([-4.38498100e-03, 1.46001114e+02, 6.65260386e-03])]} +{'AngularVelocity': array([-0.0784932 , -0.01141415, -0.94205028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.013987500220537186, + 'FR_Wheel_Angle': 0.003815283766016364, + 'Location': array([-57.60444641, 105.18219757, 0.13335803]), + 'Rotation': array([ 3.23750940e-03, 1.00723198e+02, -5.28067398e+00]), + 'Velocity': array([ 8.17127526e-02, -4.29172665e-01, 2.17370980e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.718017578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61523438, 13038.828125 , 122.96764374]), + 'frame': 28050, + 'frame_number': 28050, + 'framesequence': 112929, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.3015792965888977, + 'timestamp': 952.8176470510662, + 'timestamp_carla': 952817, + 'timestamp_device': 1823421, + 'timestamp_stream': 952.8176470510662, + 'transform': [array([-6.42757721e+01, 1.02925926e+02, -1.01286754e-01]), + array([-4.37815115e-03, 1.46000977e+02, 6.57064142e-03])]} +{'AngularVelocity': array([-0.01057456, -0.00116757, 0.03156302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0025415164418518543, + 'FR_Wheel_Angle': 0.002540837274864316, + 'Location': array([-57.58943558, 105.10372925, 0.13337959]), + 'Rotation': array([ 9.63056635e-04, 1.00729141e+02, -5.28070354e+00]), + 'Velocity': array([ 9.16156247e-02, -4.77560520e-01, 8.81242740e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2110.856201171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61083984, 13038.81933594, 122.96711731]), + 'frame': 28051, + 'frame_number': 28051, + 'framesequence': 112933, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.31348133087158203, + 'timestamp': 952.8503584489226, + 'timestamp_carla': 952849, + 'timestamp_device': 1823454, + 'timestamp_stream': 952.8503584489226, + 'transform': [array([-6.42767792e+01, 1.02924545e+02, -1.01267800e-01]), + array([-4.37132083e-03, 1.46000671e+02, 6.50233962e-03])]} +{'AngularVelocity': array([-3.90991475e-03, 3.55483317e-05, -1.06223285e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.002542405389249325, + 'FR_Wheel_Angle': 0.0025426058564335108, + 'Location': array([-57.57488251, 105.02752686, 0.13335872]), + 'Rotation': array([ 2.99845287e-03, 1.00728127e+02, -5.28009319e+00]), + 'Velocity': array([ 8.56420472e-02, -4.47155863e-01, 1.76563262e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2111.01220703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.60791016, 13038.8125 , 122.96485138]), + 'frame': 28052, + 'frame_number': 28052, + 'framesequence': 112936, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.32538339495658875, + 'timestamp': 952.8830601498485, + 'timestamp_carla': 952882, + 'timestamp_device': 1823479, + 'timestamp_stream': 952.8830601498485, + 'transform': [array([-6.42785416e+01, 1.02923286e+02, -1.01153389e-01]), + array([-4.37132083e-03, 1.45997421e+02, 6.02422608e-03])]} +{'AngularVelocity': array([-0.0004828 , -0.0023821 , -0.16579573]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0025438375305384398, + 'FR_Wheel_Angle': 0.0025446149520576, + 'Location': array([-57.5616188 , 104.95818329, 0.13335903]), + 'Rotation': array([ 4.48060408e-03, 1.00731361e+02, -5.27975750e+00]), + 'Velocity': array([ 7.86273181e-02, -4.12315249e-01, 1.14073751e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2111.176513671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.6015625 , 13038.79980469, 122.96263123]), + 'frame': 28053, + 'frame_number': 28053, + 'framesequence': 112940, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.3293507397174835, + 'timestamp': 952.9148216508329, + 'timestamp_carla': 952914, + 'timestamp_device': 1823513, + 'timestamp_stream': 952.9148216508329, + 'transform': [array([-6.42819672e+01, 1.02920135e+02, -1.00456044e-01]), + array([-4.34400002e-03, 1.45992798e+02, 3.10773659e-03])]} +{'AngularVelocity': array([-0.11779576, -0.03290699, -1.1578517 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.002542385132983327, + 'FR_Wheel_Angle': 0.09661902487277985, + 'Location': array([-57.54854202, 104.88882446, 0.13333568]), + 'Rotation': array([ 3.17603769e-03, 1.00724831e+02, -5.28052044e+00]), + 'Velocity': array([ 8.32196027e-02, -4.46799874e-01, -2.97183986e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2111.32080078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.54052734, 13038.67578125, 122.94532776]), + 'frame': 28054, + 'frame_number': 28054, + 'framesequence': 112944, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.3333180844783783, + 'timestamp': 952.947633150965, + 'timestamp_carla': 952947, + 'timestamp_device': 1823546, + 'timestamp_stream': 952.947633150965, + 'transform': [array([-6.42837677e+01, 1.02913795e+02, -9.99976993e-02]), + array([-4.39864164e-03, 1.46001373e+02, 1.14747218e-03])]} +{'AngularVelocity': array([-0.08927182, -0.05809272, -1.92251611]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.280522346496582, + 'FR_Wheel_Angle': 5.95628547668457, + 'Location': array([-57.53359604, 104.81599426, 0.13331927]), + 'Rotation': array([ 4.38498100e-03, 1.00667168e+02, -5.27966595e+00]), + 'Velocity': array([ 0.10204446, -0.42037371, -0.00058978]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2111.686279296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.45410156, 13038.5 , 122.83959961]), + 'frame': 28055, + 'frame_number': 28055, + 'framesequence': 112948, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 952.9822050519288, + 'timestamp_carla': 952981, + 'timestamp_device': 1823579, + 'timestamp_stream': 952.9822050519288, + 'transform': [array([-6.42875671e+01, 1.02907539e+02, -9.96865705e-02]), + array([-4.46011312e-03, 1.46002701e+02, -2.44140057e-04])]} +{'AngularVelocity': array([-0.08514176, -0.01755593, -1.40549481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.3577256202697754, + 'FR_Wheel_Angle': 3.9433493614196777, + 'Location': array([-57.51825714, 104.74809265, 0.13335045]), + 'Rotation': array([ 5.33437729e-03, 1.00565079e+02, -5.28259563e+00]), + 'Velocity': array([ 9.04883370e-02, -4.08544898e-01, 1.11250876e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2112.45654296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.61230469, 13038.82226562, 122.76773071]), + 'frame': 28056, + 'frame_number': 28056, + 'framesequence': 112952, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.0148820504546, + 'timestamp_carla': 953014, + 'timestamp_device': 1823613, + 'timestamp_stream': 953.0148820504546, + 'transform': [array([-6.42897568e+01, 1.02896759e+02, -9.89855677e-02]), + array([-4.36449051e-03, 1.46020432e+02, -3.17382696e-03])]} +{'AngularVelocity': array([-0.09362648, -0.02897712, -1.8036921 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.064178466796875, + 'FR_Wheel_Angle': 3.983623504638672, + 'Location': array([-57.49978256, 104.66407776, 0.13335006]), + 'Rotation': array([ 3.14188679e-03, 1.00441780e+02, -5.28265619e+00]), + 'Velocity': array([ 8.98868665e-02, -3.95007521e-01, -2.86512368e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2113.204833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.63476562, 13038.86816406, 122.71527863]), + 'frame': 28057, + 'frame_number': 28057, + 'framesequence': 112956, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.0479103513062, + 'timestamp_carla': 953047, + 'timestamp_device': 1823646, + 'timestamp_stream': 953.0479103513062, + 'transform': [array([-6.42944489e+01, 1.02886856e+02, -9.87637714e-02]), + array([-4.46011312e-03, 1.46027252e+02, -4.11987165e-03])]} +{'AngularVelocity': array([-0.09313878, -0.02866581, -1.66750169]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.090860366821289, + 'FR_Wheel_Angle': 4.186323642730713, + 'Location': array([-57.48386765, 104.59022522, 0.133358 ]), + 'Rotation': array([ 3.14871711e-03, 1.00338577e+02, -5.28283930e+00]), + 'Velocity': array([ 1.03716038e-01, -4.57347751e-01, -9.42134866e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2114.525390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.96289062, 13039.53710938, 122.60866547]), + 'frame': 28058, + 'frame_number': 28058, + 'framesequence': 112960, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.0816666521132, + 'timestamp_carla': 953081, + 'timestamp_device': 1823679, + 'timestamp_stream': 953.0816666521132, + 'transform': [array([-6.43021393e+01, 1.02878487e+02, -9.87915769e-02]), + array([-4.21422627e-03, 1.46020172e+02, -3.99780134e-03])]} +{'AngularVelocity': array([-0.0546862 , -0.00210634, -0.93528414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.024442672729492, + 'FR_Wheel_Angle': 4.1513190269470215, + 'Location': array([-57.46816254, 104.51741028, 0.13333805]), + 'Rotation': array([ 3.68147180e-03, 1.00235909e+02, -5.28363371e+00]), + 'Velocity': array([ 1.00524023e-01, -4.44110215e-01, -2.77280807e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2115.724853515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4338.08837891, 13039.79199219, 122.57426453]), + 'frame': 28059, + 'frame_number': 28059, + 'framesequence': 112964, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.1149205490947, + 'timestamp_carla': 953114, + 'timestamp_device': 1823713, + 'timestamp_stream': 953.1149205490947, + 'transform': [array([-6.43087082e+01, 1.02868439e+02, -9.88470614e-02]), + array([-4.44645295e-03, 1.46020767e+02, -3.78417806e-03])]} +{'AngularVelocity': array([ 0.00759749, 0.01092115, -0.60799611]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.988900661468506, + 'FR_Wheel_Angle': 4.147883892059326, + 'Location': array([-57.45187378, 104.4425354 , 0.13329414]), + 'Rotation': array([ 4.64452850e-03, 1.00141533e+02, -5.28354216e+00]), + 'Velocity': array([ 0.0996083 , -0.45204413, -0.00137959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2116.725830078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.95751953, 13039.52734375, 122.57771301]), + 'frame': 28060, + 'frame_number': 28060, + 'framesequence': 112968, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.1489401496947, + 'timestamp_carla': 953148, + 'timestamp_device': 1823746, + 'timestamp_stream': 953.1489401496947, + 'transform': [array([-6.43165665e+01, 1.02858116e+02, -9.89806354e-02]), + array([-4.37815115e-03, 1.46017578e+02, -3.23486282e-03])]} +{'AngularVelocity': array([-0.03415179, -0.01354133, -0.97472495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9909284114837646, + 'FR_Wheel_Angle': 4.1501898765563965, + 'Location': array([-57.43528748, 104.36528778, 0.13335064]), + 'Rotation': array([ 4.52158507e-03, 1.00032005e+02, -5.28283930e+00]), + 'Velocity': array([ 9.67562348e-02, -4.41555738e-01, 2.01234812e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2117.936279296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.96777344, 13039.546875 , 122.58592224]), + 'frame': 28061, + 'frame_number': 28061, + 'framesequence': 112972, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.1825496517122, + 'timestamp_carla': 953182, + 'timestamp_device': 1823779, + 'timestamp_stream': 953.1825496517122, + 'transform': [array([-6.43230667e+01, 1.02844948e+02, -9.88152474e-02]), + array([-4.43279231e-03, 1.46025742e+02, -3.93676665e-03])]} +{'AngularVelocity': array([ 0.00570492, -0.01565524, -0.81956154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9872047901153564, + 'FR_Wheel_Angle': 4.146962642669678, + 'Location': array([-57.41844177, 104.28440857, 0.13338234]), + 'Rotation': array([-1.49581139e-03, 9.98964081e+01, -5.28204679e+00]), + 'Velocity': array([ 1.09521031e-01, -4.95241582e-01, -4.60433948e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2119.17578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.90722656, 13039.42382812, 122.60526276]), + 'frame': 28062, + 'frame_number': 28062, + 'framesequence': 112976, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.2152511514723, + 'timestamp_carla': 953214, + 'timestamp_device': 1823813, + 'timestamp_stream': 953.2152511514723, + 'transform': [array([-6.43314209e+01, 1.02831238e+02, -9.85559076e-02]), + array([-4.45328327e-03, 1.46028702e+02, -5.00488188e-03])]} +{'AngularVelocity': array([0.08447647, 0.02336667, 0.32326975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9852328300476074, + 'FR_Wheel_Angle': 4.2891154289245605, + 'Location': array([-57.40110397, 104.20162964, 0.13333812]), + 'Rotation': array([ 2.79354723e-03, 9.97929382e+01, -5.28195477e+00]), + 'Velocity': array([ 1.13827407e-01, -5.26322067e-01, -3.15599435e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2120.7705078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4338.05761719, 13039.73046875, 122.57949829]), + 'frame': 28063, + 'frame_number': 28063, + 'framesequence': 112980, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.2497192509472, + 'timestamp_carla': 953249, + 'timestamp_device': 1823846, + 'timestamp_stream': 953.2497192509472, + 'transform': [array([-6.43411636e+01, 1.02817085e+02, -9.86426622e-02]), + array([-4.39181132e-03, 1.46027939e+02, -4.66918852e-03])]} +{'AngularVelocity': array([ 0.01913336, 0.02184029, -1.26552367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.930209159851074, + 'FR_Wheel_Angle': 10.102465629577637, + 'Location': array([-57.38262558, 104.11943817, 0.1333448 ]), + 'Rotation': array([ 3.92735843e-03, 9.96155853e+01, -5.27951384e+00]), + 'Velocity': array([ 1.24614954e-01, -4.80151385e-01, -4.55102912e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2122.42236328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4338.11132812, 13039.83886719, 122.54103851]), + 'frame': 28064, + 'frame_number': 28064, + 'framesequence': 112984, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.2819286510348, + 'timestamp_carla': 953281, + 'timestamp_device': 1823879, + 'timestamp_stream': 953.2819286510348, + 'transform': [array([-6.43514404e+01, 1.02804268e+02, -9.88044515e-02]), + array([-4.37815115e-03, 1.46022110e+02, -3.93676618e-03])]} +{'AngularVelocity': array([ 0.00914139, 0.04955858, -0.94815719]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.905999183654785, + 'FR_Wheel_Angle': 7.691247463226318, + 'Location': array([-57.36348343, 104.04032135, 0.13335751]), + 'Rotation': array([ 3.12139629e-03, 9.93824005e+01, -5.28183222e+00]), + 'Velocity': array([ 1.11118421e-01, -4.66274887e-01, -2.31208789e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2124.12646484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4338.09570312, 13039.80859375, 122.55223083]), + 'frame': 28065, + 'frame_number': 28065, + 'framesequence': 112988, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.3154824487865, + 'timestamp_carla': 953315, + 'timestamp_device': 1823913, + 'timestamp_stream': 953.3154824487865, + 'transform': [array([-6.43609924e+01, 1.02789337e+02, -9.90240946e-02]), + array([-4.38498100e-03, 1.46023773e+02, -3.02123907e-03])]} +{'AngularVelocity': array([-2.93327626e-02, 7.25419901e-04, -1.43172634e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.724114418029785, + 'FR_Wheel_Angle': 8.151040077209473, + 'Location': array([-57.34596634, 103.96544647, 0.13334259]), + 'Rotation': array([ 5.03384927e-03, 9.91756134e+01, -5.28213739e+00]), + 'Velocity': array([ 1.04864798e-01, -4.27143276e-01, -2.11925508e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2125.661376953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.98681641, 13039.58496094, 122.5800705 ]), + 'frame': 28066, + 'frame_number': 28066, + 'framesequence': 112992, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.3491313494742, + 'timestamp_carla': 953348, + 'timestamp_device': 1823946, + 'timestamp_stream': 953.3491313494742, + 'transform': [array([-6.43702011e+01, 1.02773193e+02, -9.91218537e-02]), + array([-4.44645295e-03, 1.46029526e+02, -2.62451079e-03])]} +{'AngularVelocity': array([-0.0289142 , -0.00678365, -1.34158027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.710787296295166, + 'FR_Wheel_Angle': 8.2723970413208, + 'Location': array([-57.32624054, 103.87973022, 0.1333432 ]), + 'Rotation': array([ 4.05030185e-03, 9.89344788e+01, -5.28259516e+00]), + 'Velocity': array([ 1.02653876e-01, -4.26678836e-01, 1.02033613e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2127.464111328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4338.01611328, 13039.64550781, 122.61330414]), + 'frame': 28067, + 'frame_number': 28067, + 'framesequence': 112996, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.3807629495859, + 'timestamp_carla': 953380, + 'timestamp_device': 1823979, + 'timestamp_stream': 953.3807629495859, + 'transform': [array([-6.43832779e+01, 1.02758904e+02, -9.88389924e-02]), + array([-4.33033984e-03, 1.46017365e+02, -3.75366071e-03])]} +{'AngularVelocity': array([-0.07077578, -0.06982169, -1.73066115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.710431098937988, + 'FR_Wheel_Angle': 8.326299667358398, + 'Location': array([-57.30674362, 103.79341888, 0.13334553]), + 'Rotation': array([ 2.71841511e-03, 9.86919556e+01, -5.28222990e+00]), + 'Velocity': array([ 1.08423166e-01, -4.46470171e-01, 4.05883766e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2129.418212890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4338.12207031, 13039.86132812, 122.62783813]), + 'frame': 28068, + 'frame_number': 28068, + 'framesequence': 113001, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.4199721515179, + 'timestamp_carla': 953419, + 'timestamp_device': 1824021, + 'timestamp_stream': 953.4199721515179, + 'transform': [array([-6.43980637e+01, 1.02739906e+02, -9.90376323e-02]), + array([-4.15275479e-03, 1.46010483e+02, -3.14330938e-03])]} +{'AngularVelocity': array([ 0.03720902, -0.00330321, -1.12218487]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.711888313293457, + 'FR_Wheel_Angle': 8.327364921569824, + 'Location': array([-57.29090118, 103.72176361, 0.1333641 ]), + 'Rotation': array([ 2.29494344e-03, 9.84914780e+01, -5.28207636e+00]), + 'Velocity': array([ 1.01717420e-01, -4.17517871e-01, 3.38931073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2131.114990234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.89404297, 13039.39648438, 122.58718109]), + 'frame': 28069, + 'frame_number': 28069, + 'framesequence': 113005, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.4553088508546, + 'timestamp_carla': 953454, + 'timestamp_device': 1824054, + 'timestamp_stream': 953.4553088508546, + 'transform': [array([-6.44111633e+01, 1.02720734e+02, -9.89511684e-02]), + array([-4.16641496e-03, 1.46009903e+02, -3.47900274e-03])]} +{'AngularVelocity': array([ 0.00409798, -0.01898066, -1.48714316]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.709137439727783, + 'FR_Wheel_Angle': 8.32810115814209, + 'Location': array([-57.27466583, 103.64711761, 0.13336955]), + 'Rotation': array([ 2.73207552e-03, 9.82807236e+01, -5.28198576e+00]), + 'Velocity': array([ 1.05841383e-01, -4.43652749e-01, 2.18143454e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2133.396240234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.76611328, 13039.13476562, 122.60366058]), + 'frame': 28070, + 'frame_number': 28070, + 'framesequence': 113009, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.4871869497001, + 'timestamp_carla': 953486, + 'timestamp_device': 1824088, + 'timestamp_stream': 953.4871869497001, + 'transform': [array([-6.44251022e+01, 1.02701561e+02, -9.84606370e-02]), + array([-4.23471723e-03, 1.46006287e+02, -5.43212797e-03])]} +{'AngularVelocity': array([-0.06769186, -0.03735908, -1.23565364]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7013349533081055, + 'FR_Wheel_Angle': 8.319326400756836, + 'Location': array([-57.25596237, 103.55958557, 0.13335609]), + 'Rotation': array([ 2.31543393e-03, 9.80439987e+01, -5.28180170e+00]), + 'Velocity': array([ 1.11398771e-01, -4.92325366e-01, -1.17588042e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2135.707763671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.75585938, 13039.11328125, 122.5916748 ]), + 'frame': 28071, + 'frame_number': 28071, + 'framesequence': 113013, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.5192925520241, + 'timestamp_carla': 953518, + 'timestamp_device': 1824121, + 'timestamp_stream': 953.5192925520241, + 'transform': [array([-6.44385757e+01, 1.02681229e+02, -9.84320343e-02]), + array([-4.33033984e-03, 1.46006973e+02, -5.49316267e-03])]} +{'AngularVelocity': array([ 0.13514295, 0.07474935, -0.51283532]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.595458984375, + 'FR_Wheel_Angle': 13.299140930175781, + 'Location': array([-57.23507309, 103.46039581, 0.13335098]), + 'Rotation': array([ 2.69792462e-03, 9.77361221e+01, -5.28219843e+00]), + 'Velocity': array([ 0.10884847, -0.44132739, 0.00052419]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2138.006591796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.68701172, 13038.97265625, 122.52246094]), + 'frame': 28072, + 'frame_number': 28072, + 'framesequence': 113016, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.5502407513559, + 'timestamp_carla': 953549, + 'timestamp_device': 1824146, + 'timestamp_stream': 953.5502407513559, + 'transform': [array([-64.46390533, 102.67562103, -0.10451397]), + array([-3.37069817e-02, 1.45932892e+02, 1.57982316e-02])]} +{'AngularVelocity': array([ 0.05314117, 0.05532546, -1.07425809]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.55178165435791, + 'FR_Wheel_Angle': 11.77916145324707, + 'Location': array([-57.21785355, 103.38809967, 0.13336502]), + 'Rotation': array([ 4.51475475e-03, 9.74129639e+01, -5.28357267e+00]), + 'Velocity': array([ 1.10797003e-01, -4.31201160e-01, 7.18307492e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2140.456787109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.69824219, 13038.99707031, 122.5219574 ]), + 'frame': 28073, + 'frame_number': 28073, + 'framesequence': 113021, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.33728542923927307, + 'timestamp': 953.5842868499458, + 'timestamp_carla': 953583, + 'timestamp_device': 1824188, + 'timestamp_stream': 953.5842868499458, + 'transform': [array([-64.50793457, 102.67272949, 0.1615964 ]), + array([ 1.76268053, 145.83625793, -0.8529734 ])]} +{'AngularVelocity': array([-0.06550345, -0.07023066, -2.96108627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.43421459197998, + 'FR_Wheel_Angle': 12.677123069763184, + 'Location': array([-57.19796371, 103.29883575, 0.13336089]), + 'Rotation': array([ 3.49022658e-03, 9.70532684e+01, -5.28332758e+00]), + 'Velocity': array([ 1.15155593e-01, -4.71051425e-01, -3.47490306e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2141.12841796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4336.35839844, 13036.26464844, 123.30615997]), + 'frame': 28074, + 'frame_number': 28074, + 'framesequence': 113025, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.3174487054347992, + 'timestamp': 953.618971850723, + 'timestamp_carla': 953618, + 'timestamp_device': 1824221, + 'timestamp_stream': 953.618971850723, + 'transform': [array([-64.52845764, 102.65731049, 0.21571147]), + array([ 1.77532995, 145.80555725, -1.05394244])]} +{'AngularVelocity': array([-0.0788475 , -0.06712868, -2.8249321 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.152437210083008, + 'FR_Wheel_Angle': 12.57013988494873, + 'Location': array([-57.18143463, 103.22337341, 0.13333903]), + 'Rotation': array([ 5.42317005e-03, 9.67467041e+01, -5.28412199e+00]), + 'Velocity': array([ 1.05852284e-01, -4.47242677e-01, -1.79328912e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2139.76806640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.89648438, 13031.24414062, 91.00952148]), + 'frame': 28075, + 'frame_number': 28075, + 'framesequence': 113029, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.30951398611068726, + 'timestamp': 953.6522905491292, + 'timestamp_carla': 953651, + 'timestamp_device': 1824254, + 'timestamp_stream': 953.6522905491292, + 'transform': [array([-64.54332733, 102.63763428, 0.22876331]), + array([ 1.71040905, 145.80349731, -1.10413003])]} +{'AngularVelocity': array([-0.09767761, -0.06787687, -2.86117983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.156492233276367, + 'FR_Wheel_Angle': 12.521303176879883, + 'Location': array([-57.16628265, 103.15242004, 0.1333406 ]), + 'Rotation': array([ 5.81932068e-03, 9.64533005e+01, -5.28467226e+00]), + 'Velocity': array([ 1.01108350e-01, -4.28700447e-01, -1.45692815e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2141.65966796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.55664062, 13030.55078125, 84.15597534]), + 'frame': 28076, + 'frame_number': 28076, + 'framesequence': 113033, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.3015792965888977, + 'timestamp': 953.6867012493312, + 'timestamp_carla': 953686, + 'timestamp_device': 1824288, + 'timestamp_stream': 953.6867012493312, + 'transform': [array([-64.56006622, 102.61869812, 0.24483089]), + array([ 1.74759257, 145.79032898, -1.15846753])]} +{'AngularVelocity': array([-0.08877322, -0.06425398, -2.45710111]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.169601440429688, + 'FR_Wheel_Angle': 12.498470306396484, + 'Location': array([-57.15081024, 103.07952118, 0.13329521]), + 'Rotation': array([ 8.14158469e-03, 9.61828842e+01, -5.28372574e+00]), + 'Velocity': array([ 0.10424814, -0.45419043, -0.00046822]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2144.1640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.63867188, 13030.71875 , 82.59338379]), + 'frame': 28077, + 'frame_number': 28077, + 'framesequence': 113037, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.29761195182800293, + 'timestamp': 953.7228769510984, + 'timestamp_carla': 953722, + 'timestamp_device': 1824321, + 'timestamp_stream': 953.7228769510984, + 'transform': [array([-64.57765198, 102.59909058, 0.26087067]), + array([ 1.81697369, 145.77372742, -1.21121109])]} +{'AngularVelocity': array([-0.11667647, -0.07206634, -2.99216366]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.169647216796875, + 'FR_Wheel_Angle': 12.508050918579102, + 'Location': array([-57.13589096, 103.00681305, 0.13333923]), + 'Rotation': array([ 5.21143386e-03, 9.58844147e+01, -5.28448868e+00]), + 'Velocity': array([ 9.86722484e-02, -4.35277462e-01, 1.23014441e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2146.41943359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.42822266, 13030.2890625 , 80.7260437 ]), + 'frame': 28078, + 'frame_number': 28078, + 'framesequence': 113041, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.7579052522779, + 'timestamp_carla': 953757, + 'timestamp_device': 1824354, + 'timestamp_stream': 953.7579052522779, + 'transform': [array([-64.59350586, 102.57970428, 0.2742247 ]), + array([ 1.8852551 , 145.7620697 , -1.25473809])]} +{'AngularVelocity': array([-0.07766119, -0.04513965, -2.70624208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.175366401672363, + 'FR_Wheel_Angle': 12.503164291381836, + 'Location': array([-57.1218605 , 102.93635559, 0.13334416]), + 'Rotation': array([ 4.13226429e-03, 9.55914154e+01, -5.28488398e+00]), + 'Velocity': array([ 9.09833908e-02, -4.11121696e-01, -5.89752199e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2148.6767578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.11230469, 13029.64550781, 78.83691406]), + 'frame': 28079, + 'frame_number': 28079, + 'framesequence': 113045, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.7893987521529, + 'timestamp_carla': 953788, + 'timestamp_device': 1824388, + 'timestamp_stream': 953.7893987521529, + 'transform': [array([-64.60781097, 102.5622406 , 0.28450248]), + array([ 1.94057953, 145.75143433, -1.28830647])]} +{'AngularVelocity': array([-0.06577577, 0.0139174 , -2.47217393]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.168207168579102, + 'FR_Wheel_Angle': 12.496828079223633, + 'Location': array([-57.10692215, 102.85792542, 0.13249058]), + 'Rotation': array([ 3.17057371e-02, 9.52419968e+01, -5.23108196e+00]), + 'Velocity': array([ 0.0996874 , -0.4882386 , -0.00154452]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2150.90576171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4332.87792969, 13029.16699219, 77.24047089]), + 'frame': 28080, + 'frame_number': 28080, + 'framesequence': 113049, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.820979449898, + 'timestamp_carla': 953820, + 'timestamp_device': 1824421, + 'timestamp_stream': 953.820979449898, + 'transform': [array([-64.62201691, 102.54447174, 0.29320449]), + array([ 1.98903298, 145.74194336, -1.31686425])]} +{'AngularVelocity': array([-0.07101644, 0.04727414, -2.25440454]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.26063060760498, + 'FR_Wheel_Angle': 18.475046157836914, + 'Location': array([-57.09219742, 102.78262329, 0.13285622]), + 'Rotation': array([ 1.93567555e-02, 9.49117050e+01, -5.25613737e+00]), + 'Velocity': array([ 0.1033112 , -0.42596784, 0.00239155]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2152.917724609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4332.66308594, 13028.72851562, 75.98901367]), + 'frame': 28081, + 'frame_number': 28081, + 'framesequence': 113053, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.8534663505852, + 'timestamp_carla': 953852, + 'timestamp_device': 1824454, + 'timestamp_stream': 953.8534663505852, + 'transform': [array([-64.63671112, 102.52623749, 0.30068532]), + array([ 2.03185129, 145.73196411, -1.34154212])]} +{'AngularVelocity': array([-0.13115101, -0.0217167 , -3.41114736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.730168342590332, + 'FR_Wheel_Angle': 16.022266387939453, + 'Location': array([-57.07242966, 102.69081116, 0.1331668 ]), + 'Rotation': array([ 6.91898121e-03, 9.43930511e+01, -5.27572918e+00]), + 'Velocity': array([ 0.09626175, -0.41756433, 0.00090523]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2154.97509765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4332.46923828, 13028.33300781, 74.90565491]), + 'frame': 28082, + 'frame_number': 28082, + 'framesequence': 113057, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.8850753493607, + 'timestamp_carla': 953884, + 'timestamp_device': 1824488, + 'timestamp_stream': 953.8850753493607, + 'transform': [array([-64.65091705, 102.50843811, 0.30670822]), + array([ 2.06707478, 145.72293091, -1.36145163])]} +{'AngularVelocity': array([-0.10962533, -0.06486874, -3.46813202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.465327262878418, + 'FR_Wheel_Angle': 16.505971908569336, + 'Location': array([-57.05857468, 102.62228394, 0.13333473]), + 'Rotation': array([ 5.13630174e-03, 9.40265350e+01, -5.28006315e+00]), + 'Velocity': array([ 9.91679952e-02, -4.21293199e-01, 2.98032741e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2157.095458984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4332.26708984, 13027.92089844, 73.95288086]), + 'frame': 28083, + 'frame_number': 28083, + 'framesequence': 113060, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.9168660491705, + 'timestamp_carla': 953916, + 'timestamp_device': 1824513, + 'timestamp_stream': 953.9168660491705, + 'transform': [array([-64.6702652 , 102.49300385, 0.29429379]), + array([ 1.9904604 , 145.69500732, -1.32037699])]} +{'AngularVelocity': array([ 8.90562344, -12.49900532, -3.32080865]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.44395923614502, + 'FR_Wheel_Angle': 16.68523597717285, + 'Location': array([-57.037117 , 102.53131866, 0.11952289]), + 'Rotation': array([ 0.54528815, 93.59044647, -4.37722969]), + 'Velocity': array([ 0.02439584, -0.50461292, -0.15963265]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2159.176025390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4332.08447266, 13027.54785156, 73.17004395]), + 'frame': 28084, + 'frame_number': 28084, + 'framesequence': 113065, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.9503562487662, + 'timestamp_carla': 953949, + 'timestamp_device': 1824554, + 'timestamp_stream': 953.9503562487662, + 'transform': [array([-64.68630219, 102.4730072 , 0.29536715]), + array([ 2.00891566, 145.68757629, -1.32335413])]} +{'AngularVelocity': array([ 0.82104164, -0.6787852 , -3.43537664]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.405961036682129, + 'FR_Wheel_Angle': 16.657777786254883, + 'Location': array([-5.70248337e+01, 1.02459198e+02, 9.01931003e-02]), + 'Rotation': array([ 1.53537858, 93.17639923, -2.97784472]), + 'Velocity': array([ 0.08125991, -0.45075831, -0.04116212]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2158.431396484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.08007812, 13024.30175781, 74.71604919]), + 'frame': 28085, + 'frame_number': 28085, + 'framesequence': 113068, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2896620035171509, + 'timestamp': 953.9832274504006, + 'timestamp_carla': 953982, + 'timestamp_device': 1824579, + 'timestamp_stream': 953.9832274504006, + 'transform': [array([-64.70088959, 102.45253754, 0.29924992]), + array([ 2.03804636, 145.68484497, -1.3361727 ])]} +{'AngularVelocity': array([-0.22645374, 0.07556988, -3.10434747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.388053894042969, + 'FR_Wheel_Angle': 16.65349578857422, + 'Location': array([-5.70072098e+01, 1.02360397e+02, 9.01407972e-02]), + 'Rotation': array([ 1.503106 , 92.62995911, -2.99844408]), + 'Velocity': array([ 0.11108997, -0.50961649, 0.00955735]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2158.673095703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.1796875 , 13022.22363281, 74.57214355]), + 'frame': 28086, + 'frame_number': 28086, + 'framesequence': 113072, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2856946587562561, + 'timestamp': 954.0143797509372, + 'timestamp_carla': 954013, + 'timestamp_device': 1824613, + 'timestamp_stream': 954.0143797509372, + 'transform': [array([-64.71421051, 102.43276978, 0.30368313]), + array([ 2.06632328, 145.68437195, -1.3510071 ])]} +{'AngularVelocity': array([-0.03721486, 0.04793837, -2.58548903]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.396151542663574, + 'FR_Wheel_Angle': 16.662986755371094, + 'Location': array([-5.69934425e+01, 1.02280937e+02, 9.15087461e-02]), + 'Rotation': array([ 1.47808695, 92.19811249, -3.01535082]), + 'Velocity': array([ 0.09823684, -0.46384111, 0.00465151]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2161.078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.14941406, 13022.07421875, 74.02212524]), + 'frame': 28087, + 'frame_number': 28087, + 'framesequence': 113076, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2856946587562561, + 'timestamp': 954.0465671494603, + 'timestamp_carla': 954046, + 'timestamp_device': 1824646, + 'timestamp_stream': 954.0465671494603, + 'transform': [array([-64.72758484, 102.41239929, 0.30815035]), + array([ 2.09327531, 145.68510437, -1.3659935 ])]} +{'AngularVelocity': array([-0.07802393, 0.08805407, -2.07554865]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.39564037322998, + 'FR_Wheel_Angle': 16.656471252441406, + 'Location': array([-5.69808807e+01, 1.02205307e+02, 9.20640901e-02]), + 'Rotation': array([ 1.46802616, 91.79066467, -3.02270532]), + 'Velocity': array([ 0.08828788, -0.47182006, 0.00223784]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2163.435791015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.13427734, 13022.04492188, 73.40660095]), + 'frame': 28088, + 'frame_number': 28088, + 'framesequence': 113080, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.2856946587562561, + 'timestamp': 954.0804741494358, + 'timestamp_carla': 954079, + 'timestamp_device': 1824679, + 'timestamp_stream': 954.0804741494358, + 'transform': [array([-64.7414856 , 102.39125824, 0.31235412]), + array([ 2.11821914, 145.68579102, -1.3800633 ])]} +{'AngularVelocity': array([-0.03222739, 0.08447263, -2.08446336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.257596969604492, + 'FR_Wheel_Angle': 19.37519073486328, + 'Location': array([-5.69677963e+01, 1.02122803e+02, 9.22209173e-02]), + 'Rotation': array([ 1.46358657, 91.35276794, -3.0259707 ]), + 'Velocity': array([ 8.75262842e-02, -4.79210109e-01, 2.53744132e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2165.865478515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.14257812, 13022.06054688, 72.78712463]), + 'frame': 28089, + 'frame_number': 28089, + 'framesequence': 113084, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 7.32444241293706e-05, + 'throttle_input': 0.28172731399536133, + 'timestamp': 954.1132825501263, + 'timestamp_carla': 954112, + 'timestamp_device': 1824713, + 'timestamp_stream': 954.1132825501263, + 'transform': [array([-64.75484467, 102.37107086, 0.31590128]), + array([ 2.13880539, 145.68624878, -1.39186954])]} +{'AngularVelocity': array([-0.02728318, 0.03603458, -3.28311634]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.490013122558594, + 'FR_Wheel_Angle': 20.109033584594727, + 'Location': array([-5.69498558e+01, 1.02021286e+02, 9.22894254e-02]), + 'Rotation': array([ 1.46057439, 90.68578339, -3.02514696]), + 'Velocity': array([ 9.97159183e-02, -4.73861217e-01, 1.52626031e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2168.3896484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.14990234, 13022.07617188, 72.20083618]), + 'frame': 28090, + 'frame_number': 28090, + 'framesequence': 113088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -1.831110603234265e-05, + 'throttle_input': 0.28172731399536133, + 'timestamp': 954.1487916521728, + 'timestamp_carla': 954148, + 'timestamp_device': 1824746, + 'timestamp_stream': 954.1487916521728, + 'transform': [array([-64.76889038, 102.3494873 , 0.31907916]), + array([ 2.15740395, 145.68766785, -1.4024533 ])]} +{'AngularVelocity': array([-0.05996992, 0.02877449, -3.20316434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.670900344848633, + 'FR_Wheel_Angle': 21.25299644470215, + 'Location': array([-5.69344673e+01, 1.01928444e+02, 9.23270360e-02]), + 'Rotation': array([ 1.45774674, 90.08000183, -3.02703857]), + 'Velocity': array([ 1.01245642e-01, -5.06628036e-01, 6.95896160e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2170.804443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.15332031, 13022.08398438, 71.70373535]), + 'frame': 28091, + 'frame_number': 28091, + 'framesequence': 113092, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00906399730592966, + 'throttle_input': 0.27775996923446655, + 'timestamp': 954.1818844489753, + 'timestamp_carla': 954181, + 'timestamp_device': 1824779, + 'timestamp_stream': 954.1818844489753, + 'transform': [array([-64.78191376, 102.32937622, 0.32171521]), + array([ 2.17264891, 145.68968201, -1.41117144])]} +{'AngularVelocity': array([ 0.00733983, -0.01417771, -3.60077739]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.312789916992188, + 'FR_Wheel_Angle': 20.800804138183594, + 'Location': array([-5.69208908e+01, 1.01843399e+02, 9.23055261e-02]), + 'Rotation': array([ 1.45870972, 89.52866364, -3.02908373]), + 'Velocity': array([ 9.80660617e-02, -4.93959755e-01, -1.69639578e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2173.39111328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.17578125, 13022.12890625, 71.24629211]), + 'frame': 28092, + 'frame_number': 28092, + 'framesequence': 113096, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.02849208191037178, + 'throttle_input': 0.2737926244735718, + 'timestamp': 954.2132986523211, + 'timestamp_carla': 954212, + 'timestamp_device': 1824812, + 'timestamp_stream': 954.2132986523211, + 'transform': [array([-64.79245758, 102.3085556 , 0.32388335]), + array([ 2.18533254, 145.70314026, -1.41829884])]} +{'AngularVelocity': array([ 0.05751313, -0.0334798 , -3.20573902]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.39206314086914, + 'FR_Wheel_Angle': 20.79319190979004, + 'Location': array([-5.69090576e+01, 1.01764793e+02, 9.23024341e-02]), + 'Rotation': array([ 1.46144867, 89.01634216, -3.03088474]), + 'Velocity': array([ 9.06639919e-02, -4.67773974e-01, 2.68888456e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2176.048583984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.08544922, 13022.40136719, 70.85804749]), + 'frame': 28093, + 'frame_number': 28093, + 'framesequence': 113100, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05231482908129692, + 'throttle_input': 0.269825279712677, + 'timestamp': 954.2483577504754, + 'timestamp_carla': 954247, + 'timestamp_device': 1824846, + 'timestamp_stream': 954.2483577504754, + 'transform': [array([-64.80431366, 102.28240967, 0.32604545]), + array([ 2.19835091, 145.72676086, -1.42554903])]} +{'AngularVelocity': array([ 7.04059899e-02, -1.32273871e-03, -3.28418922e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.433685302734375, + 'FR_Wheel_Angle': 20.825044631958008, + 'Location': array([-5.68974686e+01, 1.01682648e+02, 9.22654718e-02]), + 'Rotation': array([ 1.46073151, 88.46885681, -3.02856493]), + 'Velocity': array([ 0.09141834, -0.4903385 , -0.00079546]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2183.088623046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4331.83886719, 13026.64941406, 70.42037201]), + 'frame': 28094, + 'frame_number': 28094, + 'framesequence': 113104, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07879269123077393, + 'throttle_input': 0.2658579349517822, + 'timestamp': 954.281665649265, + 'timestamp_carla': 954281, + 'timestamp_device': 1824879, + 'timestamp_stream': 954.281665649265, + 'transform': [array([-64.8119812 , 102.25455475, 0.32737041]), + array([ 2.20753741, 145.770401 , -1.42971158])]} +{'AngularVelocity': array([ 0.07536278, -0.01923016, -3.22047353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.44232749938965, + 'FR_Wheel_Angle': 20.831342697143555, + 'Location': array([-5.68874893e+01, 1.01605827e+02, 9.23278034e-02]), + 'Rotation': array([ 1.46079302, 87.9605484 , -3.02804589]), + 'Velocity': array([ 8.21498632e-02, -4.66211468e-01, 1.22785568e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2186.58203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4332.21582031, 13027.81738281, 70.05924988]), + 'frame': 28095, + 'frame_number': 28095, + 'framesequence': 113108, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10711997747421265, + 'throttle_input': 0.26189059019088745, + 'timestamp': 954.3171583488584, + 'timestamp_carla': 954316, + 'timestamp_device': 1824912, + 'timestamp_stream': 954.3171583488584, + 'transform': [array([-64.81819153, 102.2241745 , 0.32851261]), + array([ 2.21735239, 145.82739258, -1.43317175])]} +{'AngularVelocity': array([ 0.04500635, -0.04255451, -2.93217587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.447816848754883, + 'FR_Wheel_Angle': 20.835952758789062, + 'Location': array([-5.68766975e+01, 1.01517365e+02, 9.23017859e-02]), + 'Rotation': array([ 1.46303332, 87.38186646, -3.0286262 ]), + 'Velocity': array([ 0.07032163, -0.42647991, 0.00067842]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2190.162353515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.10742188, 13029.63378906, 69.81479645]), + 'frame': 28096, + 'frame_number': 28096, + 'framesequence': 113113, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1377178281545639, + 'throttle_input': 0.2539559006690979, + 'timestamp': 954.3505046516657, + 'timestamp_carla': 954350, + 'timestamp_device': 1824954, + 'timestamp_stream': 954.3505046516657, + 'transform': [array([-64.82154083, 102.19437408, 0.32943633]), + array([ 2.22561693, 145.89442444, -1.43586755])]} +{'AngularVelocity': array([ 0.11296129, 0.1743153 , -2.09508562]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.430625915527344, + 'FR_Wheel_Angle': 20.817989349365234, + 'Location': array([-5.68661461e+01, 1.01420937e+02, 9.23048407e-02]), + 'Rotation': array([ 1.4585253 , 86.74998474, -3.02804589]), + 'Velocity': array([ 6.98234737e-02, -4.86711234e-01, -2.53238686e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2194.14794921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4334.28369141, 13032.03222656, 69.58248901]), + 'frame': 28097, + 'frame_number': 28097, + 'framesequence': 113116, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16588030755519867, + 'throttle_input': 0.2539559006690979, + 'timestamp': 954.3831428512931, + 'timestamp_carla': 954382, + 'timestamp_device': 1824979, + 'timestamp_stream': 954.3831428512931, + 'transform': [array([-64.82234192, 102.16357422, 0.33020812]), + array([ 2.23241997, 145.97425842, -1.43813431])]} +{'AngularVelocity': array([ 0.15852149, 0.19594426, -4.7943759 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.97615623474121, + 'FR_Wheel_Angle': 26.7825984954834, + 'Location': array([-5.68568573e+01, 1.01337227e+02, 9.21043754e-02]), + 'Rotation': array([ 1.46778703, 86.13866425, -3.04129076]), + 'Velocity': array([ 0.08987699, -0.50530338, -0.00354756]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2198.137451171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4335.67431641, 13034.86914062, 69.38037872]), + 'frame': 28098, + 'frame_number': 28098, + 'framesequence': 113120, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19160741567611694, + 'throttle_input': 0.2539559006690979, + 'timestamp': 954.4145155511796, + 'timestamp_carla': 954414, + 'timestamp_device': 1825012, + 'timestamp_stream': 954.4145155511796, + 'transform': [array([-64.82109833, 102.1326828 , 0.33086669]), + array([ 2.23793864, 146.06254578, -1.44009435])]} +{'AngularVelocity': array([ 0.01305111, 0.01656853, -3.10281038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.77693748474121, + 'FR_Wheel_Angle': 24.286535263061523, + 'Location': array([-5.68474388e+01, 1.01262680e+02, 9.18038189e-02]), + 'Rotation': array([ 1.48116744, 85.53866577, -3.05371141]), + 'Velocity': array([ 0.05159076, -0.36714622, -0.00044455]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2202.331787109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4337.33642578, 13038.2578125 , 69.18922424]), + 'frame': 28099, + 'frame_number': 28099, + 'framesequence': 113124, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21837826073169708, + 'throttle_input': 0.24998855590820312, + 'timestamp': 954.4465838521719, + 'timestamp_carla': 954446, + 'timestamp_device': 1825046, + 'timestamp_stream': 954.4465838521719, + 'transform': [array([-64.81765747, 102.09966278, 0.33139956]), + array([ 2.24238515, 146.1651001 , -1.44171727])]} +{'AngularVelocity': array([ 1.45309349e-03, 5.92658892e-02, -3.15000558e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.43043327331543, + 'FR_Wheel_Angle': 24.904375076293945, + 'Location': array([-5.68405266e+01, 1.01197205e+02, 9.18332636e-02]), + 'Rotation': array([ 1.47558713, 85.03268433, -3.04776096]), + 'Velocity': array([ 6.46135360e-02, -4.24052268e-01, 1.15847586e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2206.60546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4339.18017578, 13042.01953125, 69.00763702]), + 'frame': 28100, + 'frame_number': 28100, + 'framesequence': 113128, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24774926900863647, + 'throttle_input': 0.24602121114730835, + 'timestamp': 954.4818028509617, + 'timestamp_carla': 954481, + 'timestamp_device': 1825079, + 'timestamp_stream': 954.4818028509617, + 'transform': [array([-64.81157684, 102.06214905, 0.33182651]), + array([ 2.24644232, 146.29019165, -1.44306517])]} +{'AngularVelocity': array([ 0.11615994, 0.16553755, -2.14423943]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.390958786010742, + 'FR_Wheel_Angle': 25.05786895751953, + 'Location': array([-5.68324203e+01, 1.01116035e+02, 9.18046907e-02]), + 'Rotation': array([ 1.47673464, 84.40549469, -3.04962182]), + 'Velocity': array([ 5.85511252e-02, -4.07802910e-01, -1.87492362e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2208.038330078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4343.10644531, 13043.74023438, 68.90912628]), + 'frame': 28101, + 'frame_number': 28101, + 'framesequence': 113132, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2761681079864502, + 'throttle_input': 0.24602121114730835, + 'timestamp': 954.5140759497881, + 'timestamp_carla': 954513, + 'timestamp_device': 1825112, + 'timestamp_stream': 954.5140759497881, + 'transform': [array([-64.80376434, 102.02651978, 0.33214492]), + array([ 2.24924946, 146.41694641, -1.44398403])]} +{'AngularVelocity': array([ 0.0807444 , -0.01365243, -3.77194142]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.336212158203125, + 'FR_Wheel_Angle': 25.000450134277344, + 'Location': array([-5.68258591e+01, 1.01042488e+02, 9.18000787e-02]), + 'Rotation': array([ 1.47627699, 83.82318115, -3.04837084]), + 'Velocity': array([ 6.86097965e-02, -4.70543623e-01, 1.62029261e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2211.64599609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4346.69238281, 13047.65429688, 68.7635498 ]), + 'frame': 28102, + 'frame_number': 28102, + 'framesequence': 113136, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30376294255256653, + 'throttle_input': 0.24205386638641357, + 'timestamp': 954.5478492490947, + 'timestamp_carla': 954547, + 'timestamp_device': 1825146, + 'timestamp_stream': 954.5478492490947, + 'transform': [array([-64.79362488, 101.9881897 , 0.33239418]), + array([ 2.25150347, 146.56013489, -1.44474995])]} +{'AngularVelocity': array([-0.08151679, 0.06041002, -3.44896841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.320850372314453, + 'FR_Wheel_Angle': 24.997289657592773, + 'Location': array([-5.68199806e+01, 1.00966728e+02, 9.17810053e-02]), + 'Rotation': array([ 1.47455585, 83.23484802, -3.04666185]), + 'Velocity': array([ 5.36338426e-02, -5.08185089e-01, -2.68745425e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2227.189697265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4343.62011719, 13061.76074219, 68.3374176 ]), + 'frame': 28103, + 'frame_number': 28103, + 'framesequence': 113140, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33306071162223816, + 'throttle_input': 0.24205386638641357, + 'timestamp': 954.5796433500946, + 'timestamp_carla': 954579, + 'timestamp_device': 1825179, + 'timestamp_stream': 954.5796433500946, + 'transform': [array([-64.78196716, 101.95079041, 0.33262217]), + array([ 2.25330663, 146.706604 , -1.44542348])]} +{'AngularVelocity': array([ 0.26017222, 0.28180173, -3.86559534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.32551383972168, + 'FR_Wheel_Angle': 24.994953155517578, + 'Location': array([-5.68143387e+01, 1.00871559e+02, 9.07783136e-02]), + 'Rotation': array([ 1.44025457, 82.4841156 , -2.97613621]), + 'Velocity': array([ 0.05491488, -0.46309081, 0.00488573]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2232.820556640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4346.66015625, 13067.9609375 , 68.16496277]), + 'frame': 28104, + 'frame_number': 28104, + 'framesequence': 113144, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3597949147224426, + 'throttle_input': 0.2380865216255188, + 'timestamp': 954.6151068508625, + 'timestamp_carla': 954614, + 'timestamp_device': 1825212, + 'timestamp_stream': 954.6151068508625, + 'transform': [array([-64.76700592, 101.90828705, 0.33271986]), + array([ 2.25446773, 146.87962341, -1.44576085])]} +{'AngularVelocity': array([ 0.25604451, 0.21423291, -3.71752834]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.330402374267578, + 'FR_Wheel_Angle': 24.98929786682129, + 'Location': array([-5.68093872e+01, 1.00782478e+02, 9.14072022e-02]), + 'Rotation': array([ 1.46996593, 81.78577423, -3.02676439]), + 'Velocity': array([ 0.04965939, -0.4525305 , 0.00120645]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2238.396484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4349.78173828, 13074.32714844, 67.99941254]), + 'frame': 28105, + 'frame_number': 28105, + 'framesequence': 113148, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3909055292606354, + 'throttle_input': 0.2380865216255188, + 'timestamp': 954.6486155502498, + 'timestamp_carla': 954648, + 'timestamp_device': 1825246, + 'timestamp_stream': 954.6486155502498, + 'transform': [array([-64.75101471, 101.86754608, 0.33283168]), + array([ 2.25556731, 147.05186462, -1.44606733])]} +{'AngularVelocity': array([ 0.36833844, 0.2817772 , -4.05510092]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.141937255859375, + 'FR_Wheel_Angle': 27.722787857055664, + 'Location': array([-5.68058548e+01, 1.00701530e+02, 9.04693231e-02]), + 'Rotation': array([ 1.51839876, 81.14152527, -3.1048584 ]), + 'Velocity': array([ 0.05459058, -0.48697543, -0.00456877]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2244.82470703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4353.48388672, 13081.87597656, 67.82185364]), + 'frame': 28106, + 'frame_number': 28106, + 'framesequence': 113153, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41851863265037537, + 'throttle_input': 0.23411917686462402, + 'timestamp': 954.68378084898, + 'timestamp_carla': 954683, + 'timestamp_device': 1825287, + 'timestamp_stream': 954.68378084898, + 'transform': [array([-64.73227692, 101.82407379, 0.33288184]), + array([ 2.25627089, 147.24211121, -1.44622064])]} +{'AngularVelocity': array([ -8.28871059, -13.23947048, -6.51706266]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.669710159301758, + 'FR_Wheel_Angle': 29.224987030029297, + 'Location': array([-5.67977486e+01, 1.00617447e+02, 8.50624442e-02]), + 'Rotation': array([ 1.33802032, 80.31668091, -2.63107324]), + 'Velocity': array([ 0.03284866, -0.54660565, -0.15960304]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2251.08544921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4357.18652344, 13089.42675781, 67.65239716]), + 'frame': 28107, + 'frame_number': 28107, + 'framesequence': 113156, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4488418400287628, + 'throttle_input': 0.23015183210372925, + 'timestamp': 954.7175380513072, + 'timestamp_carla': 954717, + 'timestamp_device': 1825312, + 'timestamp_stream': 954.7175380513072, + 'transform': [array([-64.71240997, 101.7815094 , 0.33295768]), + array([ 2.25685143, 147.43426514, -1.44643521])]} +{'AngularVelocity': array([-1.95663881, -2.00170994, -4.42865896]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.982812881469727, + 'FR_Wheel_Angle': 29.432598114013672, + 'Location': array([-5.67945786e+01, 1.00525261e+02, 5.70351407e-02]), + 'Rotation': array([ 0.31957769, 79.51177979, -0.57022095]), + 'Velocity': array([ 0.02116473, -0.46007052, -0.08865053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2257.875244140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4361.29589844, 13097.80761719, 67.47397614]), + 'frame': 28108, + 'frame_number': 28108, + 'framesequence': 113161, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4782494604587555, + 'throttle_input': 0.23015183210372925, + 'timestamp': 954.751522552222, + 'timestamp_carla': 954751, + 'timestamp_device': 1825354, + 'timestamp_stream': 954.751522552222, + 'transform': [array([-64.6884613 , 101.73552704, 0.33324707]), + array([ 2.25831318, 147.65057373, -1.44747484])]} +{'AngularVelocity': array([-0.35101414, -0.93556434, -4.32445812]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.98015785217285, + 'FR_Wheel_Angle': 29.01877784729004, + 'Location': array([-5.67921829e+01, 1.00451645e+02, 5.13741300e-02]), + 'Rotation': array([ 0.24408363, 78.84765625, -0.33242795]), + 'Velocity': array([ 0.02949364, -0.4362191 , -0.01022257]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2264.6328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4365.46728516, 13106.31542969, 67.29600525]), + 'frame': 28109, + 'frame_number': 28109, + 'framesequence': 113164, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5067964792251587, + 'throttle_input': 0.23015183210372925, + 'timestamp': 954.784593552351, + 'timestamp_carla': 954784, + 'timestamp_device': 1825379, + 'timestamp_stream': 954.784593552351, + 'transform': [array([-64.66170502, 101.68704987, 0.33355907]), + array([ 2.25961781, 147.88395691, -1.44860625])]} +{'AngularVelocity': array([-0.06409619, -0.46008092, -3.48250103]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.10184097290039, + 'FR_Wheel_Angle': 29.146106719970703, + 'Location': array([-5.67906036e+01, 1.00382515e+02, 5.06676473e-02]), + 'Rotation': array([ 0.24123544, 78.23693085, -0.21011354]), + 'Velocity': array([ 0.02441872, -0.40643421, -0.00155461]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2272.056884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4370.17773438, 13115.921875 , 67.06687927]), + 'frame': 28110, + 'frame_number': 28110, + 'framesequence': 113169, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5345377922058105, + 'throttle_input': 0.23015183210372925, + 'timestamp': 954.8185340501368, + 'timestamp_carla': 954818, + 'timestamp_device': 1825421, + 'timestamp_stream': 954.8185340501368, + 'transform': [array([-64.63300323, 101.63598633, 0.33380046]), + array([ 2.26028705, 148.13294983, -1.44955349])]} +{'AngularVelocity': array([ 0.01899865, -0.29170436, -3.39435434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.10613441467285, + 'FR_Wheel_Angle': 29.20473289489746, + 'Location': array([-5.67896042e+01, 1.00315529e+02, 5.02397902e-02]), + 'Rotation': array([ 0.25445184, 77.64315796, -0.13827515]), + 'Velocity': array([ 0.0215808 , -0.39938694, -0.00176591]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2280.011474609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4375.28564453, 13126.33789062, 66.82148743]), + 'frame': 28111, + 'frame_number': 28111, + 'framesequence': 113173, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5640186667442322, + 'throttle_input': 0.23015183210372925, + 'timestamp': 954.8536428511143, + 'timestamp_carla': 954853, + 'timestamp_device': 1825454, + 'timestamp_stream': 954.8536428511143, + 'transform': [array([-64.60118866, 101.58287811, 0.33364281]), + array([ 2.25900984, 148.39874268, -1.44906378])]} +{'AngularVelocity': array([ 0.09936212, -0.34810501, -2.49259949]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.098203659057617, + 'FR_Wheel_Angle': 29.195289611816406, + 'Location': array([-5.67893639e+01, 1.00245392e+02, 4.96377945e-02]), + 'Rotation': array([ 0.27483997, 77.02560425, -0.08175658]), + 'Velocity': array([ 0.01913404, -0.42455241, -0.00366001]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2288.558349609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4380.78466797, 13137.55273438, 66.56736755]), + 'frame': 28112, + 'frame_number': 28112, + 'framesequence': 113177, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5939207673072815, + 'throttle_input': 0.23015183210372925, + 'timestamp': 954.8860034495592, + 'timestamp_carla': 954885, + 'timestamp_device': 1825487, + 'timestamp_stream': 954.8860034495592, + 'transform': [array([-64.56890106, 101.53208923, 0.33363008]), + array([ 2.25900984, 148.65965271, -1.44894147])]} +{'AngularVelocity': array([ 0.02563598, 0.02683143, -2.35491157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.106277465820312, + 'FR_Wheel_Angle': 29.207035064697266, + 'Location': array([-5.67899933e+01, 1.00175591e+02, 4.91138846e-02]), + 'Rotation': array([ 2.92632610e-01, 7.64076920e+01, -4.84618954e-02]), + 'Velocity': array([ 0.0140013 , -0.40065238, -0.00046907]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2297.615966796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4386.68505859, 13149.58691406, 66.35829163]), + 'frame': 28113, + 'frame_number': 28113, + 'framesequence': 113180, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.23015183210372925, + 'timestamp': 954.9168941490352, + 'timestamp_carla': 954916, + 'timestamp_device': 1825512, + 'timestamp_stream': 954.9168941490352, + 'transform': [array([-64.53686523, 101.48291016, 0.33371884]), + array([ 2.25892091, 148.91551208, -1.44924676])]} +{'AngularVelocity': array([-0.00852911, 0.05531284, -2.31959319]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.110595703125, + 'FR_Wheel_Angle': 29.205705642700195, + 'Location': array([-5.67912140e+01, 1.00109833e+02, 4.92491908e-02]), + 'Rotation': array([ 2.88042724e-01, 7.58171310e+01, -5.02929613e-02]), + 'Velocity': array([ 0.00959994, -0.39038581, 0.00107757]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2306.454833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4392.51220703, 13161.47070312, 66.14146423]), + 'frame': 28114, + 'frame_number': 28114, + 'framesequence': 113185, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.22618448734283447, + 'timestamp': 954.9502785503864, + 'timestamp_carla': 954949, + 'timestamp_device': 1825554, + 'timestamp_stream': 954.9502785503864, + 'transform': [array([-64.50196838, 101.42984009, 0.33388224]), + array([ 2.25876403, 149.19290161, -1.44997931])]} +{'AngularVelocity': array([-0.05603508, -0.05830766, -4.72036839]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.142627716064453, + 'FR_Wheel_Angle': 32.556495666503906, + 'Location': array([-5.67936401e+01, 1.00026733e+02, 4.93943766e-02]), + 'Rotation': array([ 2.81069100e-01, 7.50407562e+01, -4.80041392e-02]), + 'Velocity': array([ 1.62940826e-02, -4.51924086e-01, 3.23276501e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2315.17529296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4398.26953125, 13173.21191406, 65.91052246]), + 'frame': 28115, + 'frame_number': 28115, + 'framesequence': 113188, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5840876698493958, + 'throttle_input': 0.22618448734283447, + 'timestamp': 954.9828918501735, + 'timestamp_carla': 954982, + 'timestamp_device': 1825579, + 'timestamp_stream': 954.9828918501735, + 'transform': [array([-64.4678421 , 101.37833405, 0.33369356]), + array([ 2.25366855, 149.4616394 , -1.44973016])]} +{'AngularVelocity': array([ 0.00751158, 0.01621316, -4.3648591 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.26238250732422, + 'FR_Wheel_Angle': 33.27627182006836, + 'Location': array([-5.67942162e+01, 9.99589691e+01, 4.94814292e-02]), + 'Rotation': array([ 2.80877858e-01, 7.43296356e+01, -4.88280952e-02]), + 'Velocity': array([ 0.02127532, -0.4077372 , 0.00044773]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2324.74169921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4404.56005859, 13186.04101562, 65.63919067]), + 'frame': 28116, + 'frame_number': 28116, + 'framesequence': 113192, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.581084668636322, + 'throttle_input': 0.22618448734283447, + 'timestamp': 955.0171184502542, + 'timestamp_carla': 955016, + 'timestamp_device': 1825612, + 'timestamp_stream': 955.0171184502542, + 'transform': [array([-64.43249512, 101.32500458, 0.33363631]), + array([ 2.25021935, 149.73956299, -1.44990993])]} +{'AngularVelocity': array([-0.00977799, -0.0095453 , -5.40569401]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.734392166137695, + 'FR_Wheel_Angle': 33.779052734375, + 'Location': array([-5.67961807e+01, 9.98893661e+01, 4.95146923e-02]), + 'Rotation': array([ 2.77968198e-01, 7.36111984e+01, -4.94689755e-02]), + 'Velocity': array([ 8.53601005e-03, -4.27567810e-01, -3.07941445e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2334.123779296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4410.68701172, 13198.53613281, 65.41650391]), + 'frame': 28117, + 'frame_number': 28117, + 'framesequence': 113197, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5878231525421143, + 'throttle_input': 0.22618448734283447, + 'timestamp': 955.0527090504766, + 'timestamp_carla': 955052, + 'timestamp_device': 1825654, + 'timestamp_stream': 955.0527090504766, + 'transform': [array([-64.39519501, 101.26958466, 0.3336159 ]), + array([ 2.24814296, 150.02990723, -1.45012188])]} +{'AngularVelocity': array([-0.0124547 , -0.01417389, -5.36135769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.603103637695312, + 'FR_Wheel_Angle': 33.19369125366211, + 'Location': array([-5.67986717e+01, 9.98187561e+01, 4.95705791e-02]), + 'Rotation': array([ 2.76895851e-01, 7.28745651e+01, -4.97131385e-02]), + 'Velocity': array([ 4.91061993e-03, -4.26453084e-01, -2.28595727e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2343.974853515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4417.07128906, 13211.55566406, 65.16209412]), + 'frame': 28118, + 'frame_number': 28118, + 'framesequence': 113201, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5986999273300171, + 'throttle_input': 0.22618448734283447, + 'timestamp': 955.0858733505011, + 'timestamp_carla': 955085, + 'timestamp_device': 1825687, + 'timestamp_stream': 955.0858733505011, + 'transform': [array([-64.35915375, 101.21685028, 0.33410624]), + array([ 2.25186539, 150.30883789, -1.45174444])]} +{'AngularVelocity': array([-0.03011609, -0.03652804, -4.56849861]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.737951278686523, + 'FR_Wheel_Angle': 33.309261322021484, + 'Location': array([-5.68019867e+01, 9.97519531e+01, 4.96241376e-02]), + 'Rotation': array([ 2.75980622e-01, 7.21895218e+01, -5.02013937e-02]), + 'Velocity': array([ 3.39363841e-03, -4.13868368e-01, 1.91221232e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2354.373046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4423.78710938, 13225.25195312, 64.89077759]), + 'frame': 28119, + 'frame_number': 28119, + 'framesequence': 113205, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.22618448734283447, + 'timestamp': 955.1194670498371, + 'timestamp_carla': 955118, + 'timestamp_device': 1825721, + 'timestamp_stream': 955.1194670498371, + 'transform': [array([-64.32212067, 101.16340637, 0.33422646]), + array([ 2.25138044, 150.59281921, -1.45229375])]} +{'AngularVelocity': array([-0.02010044, -0.02964853, -4.46506357]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.746700286865234, + 'FR_Wheel_Angle': 33.36685562133789, + 'Location': array([-5.68061867e+01, 9.96832199e+01, 4.96555306e-02]), + 'Rotation': array([ 2.74273068e-01, 7.14735794e+01, -4.97131310e-02]), + 'Velocity': array([-0.00063189, -0.40741023, 0.00084061]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2364.472900390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4430.29931641, 13238.53320312, 64.56674194]), + 'frame': 28120, + 'frame_number': 28120, + 'framesequence': 113209, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.22618448734283447, + 'timestamp': 955.1524736508727, + 'timestamp_carla': 955151, + 'timestamp_device': 1825754, + 'timestamp_stream': 955.1524736508727, + 'transform': [array([-64.28582764, 101.1114502 , 0.33429283]), + array([ 2.25092292, 150.86990356, -1.45259821])]} +{'AngularVelocity': array([-0.05035333, -0.05527857, -4.92332268]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.745540618896484, + 'FR_Wheel_Angle': 33.3662223815918, + 'Location': array([-5.68109589e+01, 9.96183701e+01, 4.97069545e-02]), + 'Rotation': array([ 2.72155702e-01, 7.07986145e+01, -4.88586314e-02]), + 'Velocity': array([-6.48501143e-03, -4.17606145e-01, 6.85119594e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2374.86767578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4436.9765625 , 13252.15039062, 64.28187561]), + 'frame': 28121, + 'frame_number': 28121, + 'framesequence': 113213, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.22618448734283447, + 'timestamp': 955.1847247518599, + 'timestamp_carla': 955184, + 'timestamp_device': 1825787, + 'timestamp_stream': 955.1847247518599, + 'transform': [array([-64.25099945, 101.06279755, 0.33377928]), + array([ 2.24583435, 151.13148499, -1.45094419])]} +{'AngularVelocity': array([-0.01361456, -0.02315514, -4.33676767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.744712829589844, + 'FR_Wheel_Angle': 33.36468505859375, + 'Location': array([-5.68167458e+01, 9.95521469e+01, 4.97476943e-02]), + 'Rotation': array([ 2.70181775e-01, 7.01044159e+01, -4.83398475e-02]), + 'Velocity': array([-1.10316966e-02, -4.08056796e-01, 1.48534775e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2385.14306640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4443.54492188, 13265.54589844, 64.01028442]), + 'frame': 28122, + 'frame_number': 28122, + 'framesequence': 113217, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.22618448734283447, + 'timestamp': 955.218707550317, + 'timestamp_carla': 955218, + 'timestamp_device': 1825821, + 'timestamp_stream': 955.218707550317, + 'transform': [array([-64.2144928 , 101.01225281, 0.3335776 ]), + array([ 2.24363494, 151.40429688, -1.45036149])]} +{'AngularVelocity': array([ 0.01001653, 0.05631546, -4.91327429]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.71137237548828, + 'FR_Wheel_Angle': 33.309078216552734, + 'Location': array([-5.68235970e+01, 9.94829254e+01, 4.98305485e-02]), + 'Rotation': array([ 2.65352845e-01, 6.93942032e+01, -4.54101525e-02]), + 'Velocity': array([-2.62728855e-02, -4.63840127e-01, 4.49414249e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2394.90576171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4449.77929688, 13278.25976562, 63.83685303]), + 'frame': 28123, + 'frame_number': 28123, + 'framesequence': 113221, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5977477431297302, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.2520370520651, + 'timestamp_carla': 955251, + 'timestamp_device': 1825854, + 'timestamp_stream': 955.2520370520651, + 'transform': [array([-64.17941284, 100.9641571 , 0.33351427]), + array([ 2.24226213, 151.66487122, -1.45023811])]} +{'AngularVelocity': array([-0.02471776, -0.02338023, -3.55167127]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.999893188476562, + 'FR_Wheel_Angle': 34.95327377319336, + 'Location': array([-5.68320198e+01, 9.94104462e+01, 4.98671718e-02]), + 'Rotation': array([ 2.66274899e-01, 6.86546936e+01, -4.86450195e-02]), + 'Velocity': array([-0.02316656, -0.4260141 , 0.00057348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2405.2109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4456.33203125, 13291.62304688, 63.60131073]), + 'frame': 28124, + 'frame_number': 28124, + 'framesequence': 113225, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5974181890487671, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.2864511497319, + 'timestamp_carla': 955285, + 'timestamp_device': 1825887, + 'timestamp_stream': 955.2864511497319, + 'transform': [array([-64.14406586, 100.91615295, 0.33331507]), + array([ 2.23905873, 151.92544556, -1.44977641])]} +{'AngularVelocity': array([ 0.01869169, 0.0288738 , -3.71186948]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.233224868774414, + 'FR_Wheel_Angle': 38.27955627441406, + 'Location': array([-5.68388062e+01, 9.93407135e+01, 4.99029532e-02]), + 'Rotation': array([ 2.65373319e-01, 6.78549423e+01, -4.53185961e-02]), + 'Velocity': array([-5.52028045e-03, -4.10511881e-01, 2.04372409e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2415.16748046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4462.63867188, 13304.484375 , 63.35603333]), + 'frame': 28125, + 'frame_number': 28125, + 'framesequence': 113229, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5989745855331421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.3203883506358, + 'timestamp_carla': 955319, + 'timestamp_device': 1825921, + 'timestamp_stream': 955.3203883506358, + 'transform': [array([-64.10973358, 100.86991882, 0.33327204]), + array([ 2.23795915, 152.17723083, -1.44971466])]} +{'AngularVelocity': array([-0.05432886, -0.06226333, -5.5251627 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.094228744506836, + 'FR_Wheel_Angle': 37.628543853759766, + 'Location': array([-5.68459625e+01, 9.92730865e+01, 4.99663539e-02]), + 'Rotation': array([ 2.63556480e-01, 6.70595016e+01, -4.69055139e-02]), + 'Velocity': array([-1.87062919e-02, -4.15265083e-01, 3.68342386e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2425.237548828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4468.98535156, 13317.42871094, 63.12279892]), + 'frame': 28126, + 'frame_number': 28126, + 'framesequence': 113233, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.3540757521987, + 'timestamp_carla': 955353, + 'timestamp_device': 1825954, + 'timestamp_stream': 955.3540757521987, + 'transform': [array([-64.07578278, 100.82467651, 0.33329716]), + array([ 2.23772001, 152.42454529, -1.44983673])]} +{'AngularVelocity': array([ 2.79563828e-03, 1.00483201e-01, -3.63963294e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.276472091674805, + 'FR_Wheel_Angle': 37.324562072753906, + 'Location': array([-5.68536568e+01, 9.92094116e+01, 5.00108711e-02]), + 'Rotation': array([ 2.60810763e-01, 6.63368683e+01, -4.74548303e-02]), + 'Velocity': array([-4.03902568e-02, -4.05160010e-01, 1.54848094e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2435.078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4475.16455078, 13330.02929688, 62.8776207 ]), + 'frame': 28127, + 'frame_number': 28127, + 'framesequence': 113237, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.3869959525764, + 'timestamp_carla': 955386, + 'timestamp_device': 1825987, + 'timestamp_stream': 955.3869959525764, + 'transform': [array([-64.04266357, 100.78096771, 0.3333731 ]), + array([ 2.23786354, 152.66427612, -1.45011199])]} +{'AngularVelocity': array([-0.03904288, 0.09131508, -5.12434626]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.279743194580078, + 'FR_Wheel_Angle': 37.41640090942383, + 'Location': array([-5.68628120e+01, 9.91402969e+01, 5.00674434e-02]), + 'Rotation': array([ 2.56589711e-01, 6.55295029e+01, -4.31518704e-02]), + 'Velocity': array([-5.06975651e-02, -4.76431578e-01, -2.02932351e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2444.846923828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4481.27392578, 13342.49121094, 62.62594223]), + 'frame': 28128, + 'frame_number': 28128, + 'framesequence': 113241, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.4205381497741, + 'timestamp_carla': 955420, + 'timestamp_device': 1826021, + 'timestamp_stream': 955.4205381497741, + 'transform': [array([-64.00911713, 100.73704529, 0.33343655]), + array([ 2.23811626, 152.90592957, -1.45035625])]} +{'AngularVelocity': array([ 0.04425311, 0.05485131, -5.24185467]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.2770938873291, + 'FR_Wheel_Angle': 37.490909576416016, + 'Location': array([-5.68766136e+01, 9.90469589e+01, 5.01392335e-02]), + 'Rotation': array([ 2.54677236e-01, 6.44374466e+01, -4.36706617e-02]), + 'Velocity': array([-4.61569764e-02, -4.72818792e-01, 2.95066820e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2454.414306640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4487.23730469, 13354.65234375, 62.37300491]), + 'frame': 28129, + 'frame_number': 28129, + 'framesequence': 113245, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.4561342522502, + 'timestamp_carla': 955455, + 'timestamp_device': 1826054, + 'timestamp_stream': 955.4561342522502, + 'transform': [array([-63.97344971, 100.69086456, 0.33356202]), + array([ 2.23914075, 153.16120911, -1.45084572])]} +{'AngularVelocity': array([ 9.11846058e-04, 2.80577615e-02, -5.11899853e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.293752670288086, + 'FR_Wheel_Angle': 37.50590133666992, + 'Location': array([-5.68890381e+01, 9.89716797e+01, 5.02021015e-02]), + 'Rotation': array([ 2.55565166e-01, 6.35452080e+01, -4.60510179e-02]), + 'Velocity': array([-0.05083258, -0.44152525, 0.00086162]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2464.16015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4493.29052734, 13366.99609375, 62.1157608 ]), + 'frame': 28130, + 'frame_number': 28130, + 'framesequence': 113250, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.4956222511828, + 'timestamp_carla': 955495, + 'timestamp_device': 1826096, + 'timestamp_stream': 955.4956222511828, + 'transform': [array([-63.93520737, 100.64170837, 0.33362514]), + array([ 2.23890185, 153.43408203, -1.45133436])]} +{'AngularVelocity': array([-0.0546282 , 0.02689163, -4.57086277]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.307037353515625, + 'FR_Wheel_Angle': 37.491539001464844, + 'Location': array([-5.69037094e+01, 9.88909760e+01, 5.02284244e-02]), + 'Rotation': array([ 2.53680050e-01, 6.25903320e+01, -4.62341234e-02]), + 'Velocity': array([-0.04751907, -0.42380127, -0.00100152]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2474.563232421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4499.72949219, 13380.12792969, 61.82920456]), + 'frame': 28131, + 'frame_number': 28131, + 'framesequence': 113254, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.5327987521887, + 'timestamp_carla': 955532, + 'timestamp_device': 1826129, + 'timestamp_stream': 955.5327987521887, + 'transform': [array([-63.89957047, 100.59690857, 0.33341265]), + array([ 2.23567104, 153.68449402, -1.45078123])]} +{'AngularVelocity': array([ 0.00959338, 0.33756372, -4.51529551]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.288379669189453, + 'FR_Wheel_Angle': 37.48838806152344, + 'Location': array([-5.69180717e+01, 9.88185043e+01, 4.99465950e-02]), + 'Rotation': array([ 0.23101747, 61.72940826, -0.08172609]), + 'Velocity': array([-0.06729993, -0.45694098, -0.00394534]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2485.824462890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4506.67236328, 13394.28710938, 61.51875687]), + 'frame': 28132, + 'frame_number': 28132, + 'framesequence': 113259, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.5696823522449, + 'timestamp_carla': 955569, + 'timestamp_device': 1826171, + 'timestamp_stream': 955.5696823522449, + 'transform': [array([-63.86601257, 100.55458832, 0.33360019]), + array([ 2.23820496, 153.92155457, -1.45127249])]} +{'AngularVelocity': array([-0.06328651, -0.11959895, -6.53066778]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.786344528198242, + 'FR_Wheel_Angle': 41.5452995300293, + 'Location': array([-5.69367065e+01, 9.87279053e+01, 4.98423763e-02]), + 'Rotation': array([ 0.22444001, 60.62156677, -0.08435057]), + 'Velocity': array([-0.04377278, -0.47140878, 0.00055621]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2496.230712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4513.078125 , 13407.35253906, 61.28215408]), + 'frame': 28133, + 'frame_number': 28133, + 'framesequence': 113263, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.602830350399, + 'timestamp_carla': 955602, + 'timestamp_device': 1826204, + 'timestamp_stream': 955.602830350399, + 'transform': [array([-63.83818054, 100.51754761, 0.33378601]), + array([ 2.24015164, 154.12258911, -1.45170176])]} +{'AngularVelocity': array([-0.03500919, -0.07187348, -6.65376759]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75592041015625, + 'FR_Wheel_Angle': 41.666404724121094, + 'Location': array([-5.69543991e+01, 9.86384048e+01, 4.99478504e-02]), + 'Rotation': array([ 0.22228849, 59.43512726, -0.08520506]), + 'Velocity': array([-5.14891744e-02, -4.78783935e-01, 2.19373702e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2506.2333984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4519.20263672, 13419.84277344, 61.00662994]), + 'frame': 28134, + 'frame_number': 28134, + 'framesequence': 113267, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.6356055513024, + 'timestamp_carla': 955635, + 'timestamp_device': 1826237, + 'timestamp_stream': 955.6356055513024, + 'transform': [array([-63.8045845 , 100.47478485, 0.33429828]), + array([ 2.24539733, 154.35868835, -1.45320368])]} +{'AngularVelocity': array([ 0.0089367 , 0.00800145, -5.91519737]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.794408798217773, + 'FR_Wheel_Angle': 41.68947982788086, + 'Location': array([-5.69708977e+01, 9.85636902e+01, 4.99893948e-02]), + 'Rotation': array([ 0.22051264, 58.43849564, -0.08874512]), + 'Velocity': array([-6.85368702e-02, -4.49137598e-01, 2.55203249e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2514.955322265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4524.43798828, 13430.51855469, 60.76873398]), + 'frame': 28135, + 'frame_number': 28135, + 'framesequence': 113271, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.6695477515459, + 'timestamp_carla': 955668, + 'timestamp_device': 1826270, + 'timestamp_stream': 955.6695477515459, + 'transform': [array([-63.76918793, 100.43049622, 0.33453381]), + array([ 2.24851179, 154.60604858, -1.45384836])]} +{'AngularVelocity': array([-0.03804856, -0.06043636, -6.83572054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.781288146972656, + 'FR_Wheel_Angle': 41.661476135253906, + 'Location': array([-5.69886475e+01, 9.84885254e+01, 5.00577539e-02]), + 'Rotation': array([ 0.21624377, 57.42671967, -0.08706664]), + 'Velocity': array([-6.98942840e-02, -4.82918143e-01, 2.66404153e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2525.178466796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4530.60400391, 13443.09472656, 60.44185638]), + 'frame': 28136, + 'frame_number': 28136, + 'framesequence': 113275, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5940306186676025, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.7040379494429, + 'timestamp_carla': 955703, + 'timestamp_device': 1826304, + 'timestamp_stream': 955.7040379494429, + 'transform': [array([-63.73364639, 100.38689423, 0.33442989]), + array([ 2.24799275, 154.85211182, -1.45348144])]} +{'AngularVelocity': array([-0.03186809, -0.05434234, -6.41882467]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.789138793945312, + 'FR_Wheel_Angle': 41.67383575439453, + 'Location': array([-5.70075951e+01, 9.84128723e+01, 5.01012020e-02]), + 'Rotation': array([ 0.21411958, 56.40253067, -0.08950803]), + 'Velocity': array([-0.074894 , -0.46363437, 0.00054836]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2535.98193359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4537.12060547, 13456.3828125 , 60.13729095]), + 'frame': 28137, + 'frame_number': 28137, + 'framesequence': 113279, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5755546689033508, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.7389773502946, + 'timestamp_carla': 955738, + 'timestamp_device': 1826337, + 'timestamp_stream': 955.7389773502946, + 'transform': [array([-63.69796753, 100.34309387, 0.33435836]), + array([ 2.24631238, 155.09823608, -1.45338786])]} +{'AngularVelocity': array([ 0.07650152, 0.76765162, -6.75445223]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.788820266723633, + 'FR_Wheel_Angle': 41.672271728515625, + 'Location': array([-5.70275917e+01, 9.83395081e+01, 4.93215919e-02]), + 'Rotation': array([ 0.17178608, 55.39071655, -0.17446896]), + 'Velocity': array([-0.07799688, -0.46790561, -0.01039844]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2546.81396484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4543.64941406, 13469.69726562, 59.87906647]), + 'frame': 28138, + 'frame_number': 28138, + 'framesequence': 113283, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5505966544151306, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.7750384509563, + 'timestamp_carla': 955774, + 'timestamp_device': 1826370, + 'timestamp_stream': 955.7750384509563, + 'transform': [array([-63.66398239, 100.29994965, 0.3341091 ]), + array([ 2.2416749 , 155.33517456, -1.45289481])]} +{'AngularVelocity': array([ 0.08174207, 0.60504866, -6.69736814]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.769577026367188, + 'FR_Wheel_Angle': 41.63451385498047, + 'Location': array([-5.70550041e+01, 9.82466660e+01, 4.78893258e-02]), + 'Rotation': array([ 0.10526004, 54.11968994, -0.29446414]), + 'Velocity': array([-0.11019281, -0.50450897, -0.00861014]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2557.79541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4550.22509766, 13483.10839844, 59.60559082]), + 'frame': 28139, + 'frame_number': 28139, + 'framesequence': 113288, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5251259207725525, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.8113145492971, + 'timestamp_carla': 955810, + 'timestamp_device': 1826412, + 'timestamp_stream': 955.8113145492971, + 'transform': [array([-63.6350174 , 100.26079559, 0.33420172]), + array([ 2.24222803, 155.54371643, -1.45326138])]} +{'AngularVelocity': array([ 0.03699112, 0.55296713, -6.6444211 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.778459548950195, + 'FR_Wheel_Angle': 41.65394592285156, + 'Location': array([-5.70806389e+01, 9.81668243e+01, 4.67339680e-02]), + 'Rotation': array([ 0.05404045, 53.01382446, -0.39715573]), + 'Velocity': array([-0.11700741, -0.48474929, -0.00774148]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2568.608642578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4556.60253906, 13496.11621094, 59.35638428]), + 'frame': 28140, + 'frame_number': 28140, + 'framesequence': 113292, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5135166645050049, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.847183149308, + 'timestamp_carla': 955846, + 'timestamp_device': 1826445, + 'timestamp_stream': 955.847183149308, + 'transform': [array([-63.60629654, 100.22288513, 0.33394927]), + array([ 2.2394824 , 155.74636841, -1.45249522])]} +{'AngularVelocity': array([-0.00595676, -0.04938608, -5.8777194 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.787302017211914, + 'FR_Wheel_Angle': 41.67060852050781, + 'Location': array([-5.71106491e+01, 9.80788574e+01, 4.63025272e-02]), + 'Rotation': array([ 3.57423797e-02, 5.18049164e+01, -3.86657655e-01]), + 'Velocity': array([-0.1233131 , -0.44999182, 0.00107264]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2578.4208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4562.28320312, 13507.69921875, 59.08999634]), + 'frame': 28141, + 'frame_number': 28141, + 'framesequence': 113296, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5215552449226379, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.8821062520146, + 'timestamp_carla': 955881, + 'timestamp_device': 1826479, + 'timestamp_stream': 955.8821062520146, + 'transform': [array([-63.57907104, 100.18739319, 0.33404872]), + array([ 2.24159288, 155.9379425 , -1.45265031])]} +{'AngularVelocity': array([-0.0674989 , -0.0494157 , -6.64787149]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78815269470215, + 'FR_Wheel_Angle': 41.661865234375, + 'Location': array([-5.71368065e+01, 9.80067062e+01, 4.65274043e-02]), + 'Rotation': array([ 3.68352085e-02, 5.08067245e+01, -3.78082275e-01]), + 'Velocity': array([-0.13465631, -0.46469593, 0.00129036]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2587.98876953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4567.81445312, 13518.98046875, 58.88432312]), + 'frame': 28142, + 'frame_number': 28142, + 'framesequence': 113300, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5350139141082764, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.9151483513415, + 'timestamp_carla': 955914, + 'timestamp_device': 1826512, + 'timestamp_stream': 955.9151483513415, + 'transform': [array([-63.55286407, 100.15408325, 0.33371338]), + array([ 2.23963261, 156.11882019, -1.45136547])]} +{'AngularVelocity': array([ 1.54107797e-03, -7.30907824e-03, -5.68357992e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.794452667236328, + 'FR_Wheel_Angle': 41.68536376953125, + 'Location': array([-5.71640625e+01, 9.79356537e+01, 4.66872007e-02]), + 'Rotation': array([ 3.67327556e-02, 4.98142166e+01, -3.73565584e-01]), + 'Velocity': array([-0.13427052, -0.42881325, 0.00066348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2597.105712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4573.08642578, 13529.73144531, 58.64552307]), + 'frame': 28143, + 'frame_number': 28143, + 'framesequence': 113304, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5483260750770569, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.9488502517343, + 'timestamp_carla': 955948, + 'timestamp_device': 1826545, + 'timestamp_stream': 955.9488502517343, + 'transform': [array([-63.52491379, 100.11953735, 0.33360571]), + array([ 2.24028134, 156.30938721, -1.45081615])]} +{'AngularVelocity': array([-0.0788969 , -0.02327753, -5.80937529]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79988670349121, + 'FR_Wheel_Angle': 41.69316101074219, + 'Location': array([-5.71911201e+01, 9.78688660e+01, 4.68051918e-02]), + 'Rotation': array([ 3.48544531e-02, 4.88755341e+01, -3.68560761e-01]), + 'Velocity': array([-0.15034983, -0.43556702, 0.0008061 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2605.730224609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4578.07373047, 13539.90332031, 58.48840332]), + 'frame': 28144, + 'frame_number': 28144, + 'framesequence': 113308, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5534898042678833, + 'throttle_input': 0.2222171425819397, + 'timestamp': 955.9823486506939, + 'timestamp_carla': 955981, + 'timestamp_device': 1826579, + 'timestamp_stream': 955.9823486506939, + 'transform': [array([-63.4974556 , 100.08577728, 0.33370864]), + array([ 2.24213934, 156.49679565, -1.45103228])]} +{'AngularVelocity': array([-0.09033225, -0.19838527, -5.64878035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.793899536132812, + 'FR_Wheel_Angle': 41.6709098815918, + 'Location': array([-5.72201843e+01, 9.78007278e+01, 4.68648896e-02]), + 'Rotation': array([ 3.24980393e-02, 4.79126740e+01, -3.59802186e-01]), + 'Velocity': array([-0.16472682, -0.44525433, -0.0015803 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2614.83984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4583.359375 , 13550.68261719, 58.28256989]), + 'frame': 28145, + 'frame_number': 28145, + 'framesequence': 113313, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5497726798057556, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.0168835520744, + 'timestamp_carla': 956016, + 'timestamp_device': 1826620, + 'timestamp_stream': 956.0168835520744, + 'transform': [array([-63.46922684, 100.05085754, 0.33369887]), + array([ 2.24205041, 156.68948364, -1.45103168])]} +{'AngularVelocity': array([-0.07518142, -0.44275001, -5.75397968]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.778579711914062, + 'FR_Wheel_Angle': 41.64918899536133, + 'Location': array([-5.72526360e+01, 9.77289810e+01, 4.59691212e-02]), + 'Rotation': array([ 0.06693585, 46.88211823, -0.29586789]), + 'Velocity': array([-0.1878172 , -0.46489865, -0.00568553]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2623.8837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4588.59960938, 13561.36914062, 58.04312134]), + 'frame': 28146, + 'frame_number': 28146, + 'framesequence': 113317, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5426862835884094, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.0507308505476, + 'timestamp_carla': 956050, + 'timestamp_device': 1826654, + 'timestamp_stream': 956.0507308505476, + 'transform': [array([-63.44145966, 100.01699829, 0.33354911]), + array([ 2.24152446, 156.87750244, -1.45045114])]} +{'AngularVelocity': array([-0.01823343, 0.02466062, -5.90574217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.788305282592773, + 'FR_Wheel_Angle': 41.67084503173828, + 'Location': array([-5.72865181e+01, 9.76571274e+01, 4.55020517e-02]), + 'Rotation': array([ 0.08270676, 45.83713913, -0.27297977]), + 'Velocity': array([-0.17410602, -0.44334742, 0.000553 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2633.295166015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4594.02001953, 13572.42382812, 57.80433655]), + 'frame': 28147, + 'frame_number': 28147, + 'framesequence': 113320, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5360759496688843, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.083227250725, + 'timestamp_carla': 956082, + 'timestamp_device': 1826679, + 'timestamp_stream': 956.083227250725, + 'transform': [array([-63.4140892 , 99.98442078, 0.33366424]), + array([ 2.24140167, 157.06079102, -1.45090938])]} +{'AngularVelocity': array([-0.13897188, -0.4444102 , -5.70153189]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79647445678711, + 'FR_Wheel_Angle': 41.69270324707031, + 'Location': array([-5.73197899e+01, 9.75905228e+01, 4.49276343e-02]), + 'Rotation': array([ 0.10718615, 44.85579681, -0.227478 ]), + 'Velocity': array([-0.17934346, -0.41505024, -0.0043462 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2642.537109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4599.33837891, 13583.27050781, 57.59764862]), + 'frame': 28148, + 'frame_number': 28148, + 'framesequence': 113324, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5335490107536316, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.1161228492856, + 'timestamp_carla': 956115, + 'timestamp_device': 1826712, + 'timestamp_stream': 956.1161228492856, + 'transform': [array([-63.39236832, 99.95471191, 0.3336997 ]), + array([ 2.24100542, 157.21618652, -1.45109224])]} +{'AngularVelocity': array([-0.74315387, -0.55017734, -6.81550026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.800350189208984, + 'FR_Wheel_Angle': 41.66395950317383, + 'Location': array([-5.73533745e+01, 9.75260696e+01, 4.36389931e-02]), + 'Rotation': array([ 0.11521845, 43.88833237, -0.12322999]), + 'Velocity': array([-0.1936298 , -0.42963207, -0.01109573]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2651.580810546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4604.55371094, 13593.90625 , 57.34897614]), + 'frame': 28149, + 'frame_number': 28149, + 'framesequence': 113328, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5354899764060974, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.1490739509463, + 'timestamp_carla': 956148, + 'timestamp_device': 1826745, + 'timestamp_stream': 956.1490739509463, + 'transform': [array([-63.36349487, 99.91971588, 0.33388749]), + array([ 2.24350524, 157.40997314, -1.45161378])]} +{'AngularVelocity': array([-0.64565128, -0.47124401, -6.584095 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77920150756836, + 'FR_Wheel_Angle': 41.65814208984375, + 'Location': array([-5.73909264e+01, 9.74568253e+01, 4.17570099e-02]), + 'Rotation': array([1.10519283e-01, 4.28679733e+01, 1.60904657e-02]), + 'Velocity': array([-0.20767018, -0.44612521, -0.0108575 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2647.843017578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4613.58398438, 13592.1875 , 57.43538666]), + 'frame': 28150, + 'frame_number': 28150, + 'framesequence': 113333, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5388409495353699, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.1845336519182, + 'timestamp_carla': 956183, + 'timestamp_device': 1826787, + 'timestamp_stream': 956.1845336519182, + 'transform': [array([-63.33202362, 99.8816452 , 0.33400905]), + array([ 2.24539733, 157.62133789, -1.45201254])]} +{'AngularVelocity': array([-0.63307291, -0.46302879, -6.22728205]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.784456253051758, + 'FR_Wheel_Angle': 41.66507339477539, + 'Location': array([-5.74290504e+01, 9.73890686e+01, 4.00284193e-02]), + 'Rotation': array([ 0.10731593, 41.84914398, 0.14210746]), + 'Velocity': array([-0.20942613, -0.42852491, -0.01034685]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2658.732666015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4618.69921875, 13604.55859375, 57.13359833]), + 'frame': 28151, + 'frame_number': 28151, + 'framesequence': 113337, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5422101616859436, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.2190311513841, + 'timestamp_carla': 956218, + 'timestamp_device': 1826820, + 'timestamp_stream': 956.2190311513841, + 'transform': [array([-63.29846954, 99.84220123, 0.33423704]), + array([ 2.24765801, 157.84368896, -1.4527477 ])]} +{'AngularVelocity': array([-0.57784051, -0.4332597 , -6.06220102]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.790559768676758, + 'FR_Wheel_Angle': 41.678340911865234, + 'Location': array([-5.74676323e+01, 9.73232727e+01, 3.83589529e-02]), + 'Rotation': array([ 0.10587475, 40.84809113, 0.26646104]), + 'Velocity': array([-0.20957872, -0.40663514, -0.00925415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2666.372314453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4625.99072266, 13614.12792969, 56.91833496]), + 'frame': 28152, + 'frame_number': 28152, + 'framesequence': 113341, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5422101616859436, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.2530018500984, + 'timestamp_carla': 956252, + 'timestamp_device': 1826854, + 'timestamp_stream': 956.2530018500984, + 'transform': [array([-63.26545334, 99.80358887, 0.33450815]), + array([ 2.24997354, 158.06259155, -1.45363581])]} +{'AngularVelocity': array([-0.08406209, -0.29350275, -6.02003622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.801982879638672, + 'FR_Wheel_Angle': 41.69371795654297, + 'Location': array([-5.75125656e+01, 9.72503510e+01, 3.71880718e-02]), + 'Rotation': array([ 0.13705456, 39.71892548, 0.33903959]), + 'Velocity': array([-0.20795944, -0.39081675, -0.00268306]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2671.635986328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4634.74121094, 13621.65820312, 56.74841309]), + 'frame': 28153, + 'frame_number': 28153, + 'framesequence': 113345, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5406537055969238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.2882868498564, + 'timestamp_carla': 956287, + 'timestamp_device': 1826887, + 'timestamp_stream': 956.2882868498564, + 'transform': [array([-63.23274231, 99.76473236, 0.33462203]), + array([ 2.25055408, 158.28068542, -1.45409429])]} +{'AngularVelocity': array([-0.06480206, -0.25818226, -5.31869841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.813478469848633, + 'FR_Wheel_Angle': 41.70503234863281, + 'Location': array([-5.75498123e+01, 9.71922760e+01, 3.64828110e-02]), + 'Rotation': array([ 0.17134212, 38.8145752 , 0.38640383]), + 'Velocity': array([-0.19806875, -0.3531208 , -0.00242682]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4244.5888671875, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4059.34667969, 15083.421875 , 16.83338928]), + 'frame': 28154, + 'frame_number': 28154, + 'framesequence': 113349, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5388409495353699, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.3233972489834, + 'timestamp_carla': 956322, + 'timestamp_device': 1826920, + 'timestamp_stream': 956.3233972489834, + 'transform': [array([-63.20037842, 99.72676849, 0.33462116]), + array([ 2.25064278, 158.49497986, -1.45409477])]} +{'AngularVelocity': array([-0.06916723, 0.00775132, -6.82289505]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.799776077270508, + 'FR_Wheel_Angle': 41.65940475463867, + 'Location': array([-5.75967712e+01, 9.71212311e+01, 3.60250473e-02]), + 'Rotation': array([ 0.19096525, 37.69371414, 0.42481264]), + 'Velocity': array([-0.2291628 , -0.41384873, 0.00129325]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4241.6845703125, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4076.58984375, 15085.43164062, 16.87181091]), + 'frame': 28155, + 'frame_number': 28155, + 'framesequence': 113353, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5387493968009949, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.3576789498329, + 'timestamp_carla': 956357, + 'timestamp_device': 1826954, + 'timestamp_stream': 956.3576789498329, + 'transform': [array([-63.16947174, 99.69137573, 0.33406872]), + array([ 2.24586177, 158.69673157, -1.45225728])]} +{'AngularVelocity': array([-0.05644318, -0.16502249, -6.68676662]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.769201278686523, + 'FR_Wheel_Angle': 41.64242172241211, + 'Location': array([-5.76425705e+01, 9.70545425e+01, 3.59558873e-02]), + 'Rotation': array([ 0.19888143, 36.64885712, 0.44687644]), + 'Velocity': array([-0.26308194, -0.44343144, -0.00053312]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4240.32568359375, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4092.97558594, 15088.73828125, 16.90583801]), + 'frame': 28156, + 'frame_number': 28156, + 'framesequence': 113357, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5397015810012817, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.3906230516732, + 'timestamp_carla': 956390, + 'timestamp_device': 1826987, + 'timestamp_stream': 956.3906230516732, + 'transform': [array([-63.14024353, 99.65827179, 0.33382866]), + array([ 2.24387407, 158.88667297, -1.45140016])]} +{'AngularVelocity': array([-0.0500902 , -0.16016197, -6.14486933]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.787260055541992, + 'FR_Wheel_Angle': 41.667911529541016, + 'Location': array([-5.76887741e+01, 9.69895325e+01, 3.55840661e-02]), + 'Rotation': array([ 0.21942665, 35.61505508, 0.47243115]), + 'Velocity': array([-0.24978809, -0.40164164, -0.00125549]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4245.22265625, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4106.13085938, 15097.5703125 , 16.92214203]), + 'frame': 28157, + 'frame_number': 28157, + 'framesequence': 113361, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5402874946594238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.423692651093, + 'timestamp_carla': 956423, + 'timestamp_device': 1827020, + 'timestamp_stream': 956.423692651093, + 'transform': [array([-63.11171722, 99.62615204, 0.3336415 ]), + array([ 2.24223495, 159.07131958, -1.45075738])]} +{'AngularVelocity': array([-0.04879398, -0.14163157, -5.45404673]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.777435302734375, + 'FR_Wheel_Angle': 41.64408493041992, + 'Location': array([-5.77413864e+01, 9.69188080e+01, 3.51351164e-02]), + 'Rotation': array([ 0.24104419, 34.47504044, 0.50512928]), + 'Velocity': array([-0.23954657, -0.3525244 , -0.00111891]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4246.91162109375, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4119.61083984, 15103.13378906, 16.94506836]), + 'frame': 28158, + 'frame_number': 28158, + 'framesequence': 113365, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.4570974521339, + 'timestamp_carla': 956456, + 'timestamp_device': 1827054, + 'timestamp_stream': 956.4570974521339, + 'transform': [array([-63.08344269, 99.59437561, 0.33360922]), + array([ 2.24205041, 159.25411987, -1.45063519])]} +{'AngularVelocity': array([-0.08404811, -0.20856768, -5.06686115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78598976135254, + 'FR_Wheel_Angle': 41.669307708740234, + 'Location': array([-5.77990990e+01, 9.68451080e+01, 3.46240215e-02]), + 'Rotation': array([ 0.26222461, 33.29559708, 0.54980314]), + 'Velocity': array([-0.26589087, -0.38886496, -0.00179133]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4247.9228515625, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4132.96337891, 15107.91113281, 16.96909332]), + 'frame': 28159, + 'frame_number': 28159, + 'framesequence': 113369, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399395823478699, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.4906772524118, + 'timestamp_carla': 956490, + 'timestamp_device': 1827087, + 'timestamp_stream': 956.4906772524118, + 'transform': [array([-63.05582047, 99.5633316 , 0.33378726]), + array([ 2.24280858, 159.43293762, -1.45130754])]} +{'AngularVelocity': array([-0.12686707, -0.22609934, -4.91327381]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7921199798584, + 'FR_Wheel_Angle': 41.6807746887207, + 'Location': array([-5.78469505e+01, 9.67858276e+01, 3.42712775e-02]), + 'Rotation': array([ 0.2803041 , 32.30456161, 0.57774884]), + 'Velocity': array([-0.2642372 , -0.37513855, -0.00217442]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4247.21875, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4146.80957031, 15110.99707031, 16.99627686]), + 'frame': 28160, + 'frame_number': 28160, + 'framesequence': 113374, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.5247325487435, + 'timestamp_carla': 956524, + 'timestamp_device': 1827129, + 'timestamp_stream': 956.5247325487435, + 'transform': [array([-63.02840805, 99.5329895 , 0.33373821]), + array([ 2.24219394, 159.60894775, -1.45118487])]} +{'AngularVelocity': array([ 6.39362028e-03, 9.26368521e-04, -4.70787477e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79863929748535, + 'FR_Wheel_Angle': 41.67156219482422, + 'Location': array([-5.78943596e+01, 9.67289429e+01, 3.43250632e-02]), + 'Rotation': array([ 0.28264004, 31.34090233, 0.58274037]), + 'Velocity': array([-0.25965995, -0.35831076, 0.00093451]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4243.9169921875, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4161.296875 , 15111.52539062, 17.02968597]), + 'frame': 28161, + 'frame_number': 28161, + 'framesequence': 113378, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.5585664510727, + 'timestamp_carla': 956557, + 'timestamp_device': 1827162, + 'timestamp_stream': 956.5585664510727, + 'transform': [array([-63.00105286, 99.50254059, 0.33357546]), + array([ 2.24043179, 159.78437805, -1.45069468])]} +{'AngularVelocity': array([-0.0429364 , -0.01862348, -5.61367798]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.801982879638672, + 'FR_Wheel_Angle': 41.689292907714844, + 'Location': array([-5.79428902e+01, 9.66723633e+01, 3.44933309e-02]), + 'Rotation': array([ 0.28157455, 30.36545944, 0.5863992 ]), + 'Velocity': array([-0.27471468, -0.36880738, 0.00115252]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4243.23876953125, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4174.63720703, 15114.41601562, 17.05607605]), + 'frame': 28162, + 'frame_number': 28162, + 'framesequence': 113382, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.5931001491845, + 'timestamp_carla': 956592, + 'timestamp_device': 1827195, + 'timestamp_stream': 956.5931001491845, + 'transform': [array([-62.97150421, 99.47044373, 0.33359915]), + array([ 2.24045897, 159.97161865, -1.45081663])]} +{'AngularVelocity': array([ 0.45463338, -0.08937217, -5.48308372]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.813365936279297, + 'FR_Wheel_Angle': 41.7290153503418, + 'Location': array([-5.80010529e+01, 9.66076660e+01, 3.39839943e-02]), + 'Rotation': array([ 0.30832839, 29.21688461, 0.54560953]), + 'Velocity': array([-0.26904684, -0.35023791, -0.00605472]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4243.791015625, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4187.51953125, 15118.37988281, 17.07936859]), + 'frame': 28163, + 'frame_number': 28163, + 'framesequence': 113386, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.6252645514905, + 'timestamp_carla': 956624, + 'timestamp_device': 1827229, + 'timestamp_stream': 956.6252645514905, + 'transform': [array([-62.94493866, 99.44130707, 0.33358464]), + array([ 2.24049306, 160.14074707, -1.45069456])]} +{'AngularVelocity': array([ 4.07204665e-02, 2.10667308e-03, -5.31199121e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.797382354736328, + 'FR_Wheel_Angle': 41.68011474609375, + 'Location': array([-5.80489502e+01, 9.65565567e+01, 3.34725939e-02]), + 'Rotation': array([ 0.32556096, 28.3323822 , 0.52787954]), + 'Velocity': array([-2.75837481e-01, -3.36339474e-01, -1.02968217e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4242.20556640625, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4202.00683594, 15120.55859375, 17.10977936]), + 'frame': 28164, + 'frame_number': 28164, + 'framesequence': 113390, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.6585462503135, + 'timestamp_carla': 956657, + 'timestamp_device': 1827262, + 'timestamp_stream': 956.6585462503135, + 'transform': [array([-62.91603851, 99.41048431, 0.33374077]), + array([ 2.24205041, 160.32234192, -1.45118463])]} +{'AngularVelocity': array([ 0.66578299, -0.07769201, -5.84303522]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.812057495117188, + 'FR_Wheel_Angle': 41.66704177856445, + 'Location': array([-5.80996628e+01, 9.65049667e+01, 3.21563333e-02]), + 'Rotation': array([ 0.38038689, 27.37228966, 0.43951127]), + 'Velocity': array([-0.30759606, -0.35196617, -0.00832335]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4241.60693359375, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4214.83398438, 15123.24316406, 17.13530731]), + 'frame': 28165, + 'frame_number': 28165, + 'framesequence': 113393, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.691457349807, + 'timestamp_carla': 956690, + 'timestamp_device': 1827287, + 'timestamp_stream': 956.691457349807, + 'transform': [array([-62.88388443, 99.37654877, 0.33399913]), + array([ 2.24356675, 160.52250671, -1.4521023 ])]} +{'AngularVelocity': array([ 0.48124427, -0.17057264, -6.65643358]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78955841064453, + 'FR_Wheel_Angle': 41.66946792602539, + 'Location': array([-5.81532707e+01, 9.64516373e+01, 3.04021072e-02]), + 'Rotation': array([ 0.44558784, 26.35540199, 0.34862462]), + 'Velocity': array([-0.29744658, -0.35937634, -0.00696369]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4238.86181640625, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4229.29443359, 15124.14257812, 17.16762543]), + 'frame': 28166, + 'frame_number': 28166, + 'framesequence': 113398, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.7248155511916, + 'timestamp_carla': 956724, + 'timestamp_device': 1827329, + 'timestamp_stream': 956.7248155511916, + 'transform': [array([-62.86287308, 99.35006714, 0.33954448]), + array([ 2.14200187, 160.66500854, -1.49048257])]} +{'AngularVelocity': array([ 0.66952968, -0.10530324, -6.406775 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77545738220215, + 'FR_Wheel_Angle': 41.65363311767578, + 'Location': array([-5.82213402e+01, 9.63865433e+01, 2.83560548e-02]), + 'Rotation': array([ 0.52343154, 25.08555794, 0.23668942]), + 'Velocity': array([-0.34117308, -0.36700419, -0.00790712]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4234.64892578125, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4245.60302734, 15123.95117188, 17.20568085]), + 'frame': 28167, + 'frame_number': 28167, + 'framesequence': 113401, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.7580557502806, + 'timestamp_carla': 956757, + 'timestamp_device': 1827354, + 'timestamp_stream': 956.7580557502806, + 'transform': [array([-62.8542366 , 99.33486176, 0.35187271]), + array([ 1.93560719, 160.73605347, -1.57465994])]} +{'AngularVelocity': array([-0.08713805, -0.01847845, -6.39487028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.770044326782227, + 'FR_Wheel_Angle': 41.65238571166992, + 'Location': array([-5.82805252e+01, 9.63319626e+01, 2.73734666e-02]), + 'Rotation': array([ 0.56052625, 24.0255661 , 0.19134225]), + 'Velocity': array([-0.35549966, -0.37127733, 0.00041035]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4113.35009765625, + 'focus_actor_name': 'Town05_TerrainNode_4438', + 'focus_actor_pt': array([-4296.54882812, 15011.94042969, 17.53253174]), + 'frame': 28168, + 'frame_number': 28168, + 'framesequence': 113406, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.7922242507339, + 'timestamp_carla': 956791, + 'timestamp_device': 1827395, + 'timestamp_stream': 956.7922242507339, + 'transform': [array([-62.8485527 , 99.3225174 , 0.34921351]), + array([ 2.08840537, 160.79685974, -1.54750669])]} +{'AngularVelocity': array([ 0.30281705, -0.05792702, -6.29923439]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.786205291748047, + 'FR_Wheel_Angle': 41.67316436767578, + 'Location': array([-5.83395462e+01, 9.62791748e+01, 2.70899571e-02]), + 'Rotation': array([ 0.58028603, 22.9791832 , 0.16411559]), + 'Velocity': array([-0.34589413, -0.34614253, -0.00251314]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3870.075927734375, + 'focus_actor_name': 'Town05_TerrainNode_4476', + 'focus_actor_pt': array([-4382.20703125, 14783.29394531, 18.15350342]), + 'frame': 28169, + 'frame_number': 28169, + 'framesequence': 113410, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.8304506503046, + 'timestamp_carla': 956829, + 'timestamp_device': 1827429, + 'timestamp_stream': 956.8304506503046, + 'transform': [array([-62.85382843, 99.31410217, 0.26556814]), + array([ 3.55581689, 160.85444641, -0.9782635 ])]} +{'AngularVelocity': array([ 0.45256841, -0.08240147, -6.14827347]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.778303146362305, + 'FR_Wheel_Angle': 41.661842346191406, + 'Location': array([-5.84097939e+01, 9.62190399e+01, 2.61756126e-02]), + 'Rotation': array([ 0.62003088, 21.75574875, 0.10964011]), + 'Velocity': array([-0.33493412, -0.31981543, -0.00401936]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3938.110107421875, + 'focus_actor_name': 'Town05_TerrainNode_4476', + 'focus_actor_pt': array([-4364.43847656, 14848.31542969, 17.99264526]), + 'frame': 28170, + 'frame_number': 28170, + 'framesequence': 113414, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.863579750061, + 'timestamp_carla': 956863, + 'timestamp_device': 1827462, + 'timestamp_stream': 956.863579750061, + 'transform': [array([-62.84721375, 99.30232239, 0.2426291 ]), + array([ 3.62099719, 160.92066956, -0.85363328])]} +{'AngularVelocity': array([-0.0060951 , -0.01747214, -5.78009558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.811803817749023, + 'FR_Wheel_Angle': 41.68898391723633, + 'Location': array([-5.84664726e+01, 9.61723328e+01, 2.54230108e-02]), + 'Rotation': array([ 0.65090334, 20.80093193, 0.06840298]), + 'Velocity': array([-0.34502125, -0.31582886, -0.00159759]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2807.088623046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4737.11523438, 13779.64257812, 76.17094421]), + 'frame': 28171, + 'frame_number': 28171, + 'framesequence': 113418, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.8985150493681, + 'timestamp_carla': 956897, + 'timestamp_device': 1827495, + 'timestamp_stream': 956.8985150493681, + 'transform': [array([-62.82411575, 99.2779007 , 0.22421043]), + array([ 3.78503108, 161.07264709, -0.73897851])]} +{'AngularVelocity': array([-0.12354989, -0.02681606, -6.32080364]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8173885345459, + 'FR_Wheel_Angle': 41.677589416503906, + 'Location': array([-5.85214729e+01, 9.61284485e+01, 2.55071260e-02]), + 'Rotation': array([ 0.65199614, 19.89011002, 0.07235006]), + 'Velocity': array([-0.32392108, -0.29525763, 0.00089409]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2810.125244140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4739.36914062, 13782.78222656, 82.59791565]), + 'frame': 28172, + 'frame_number': 28172, + 'framesequence': 113422, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.9316511489451, + 'timestamp_carla': 956931, + 'timestamp_device': 1827529, + 'timestamp_stream': 956.9316511489451, + 'transform': [array([-62.80026245, 99.25191498, 0.20769569]), + array([ 3.98962259, 161.23020935, -0.62979233])]} +{'AngularVelocity': array([-0.0802376 , -0.18008164, -5.23810339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.808263778686523, + 'FR_Wheel_Angle': 41.704139709472656, + 'Location': array([-5.85906372e+01, 9.60754700e+01, 2.55340561e-02]), + 'Rotation': array([ 0.6588605 , 18.76564217, 0.08851871]), + 'Velocity': array([-0.32623228, -0.27925551, -0.00125731]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2816.48291015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4744.59912109, 13790.06640625, 88.37657166]), + 'frame': 28173, + 'frame_number': 28173, + 'framesequence': 113426, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.9659543521702, + 'timestamp_carla': 956965, + 'timestamp_device': 1827562, + 'timestamp_stream': 956.9659543521702, + 'transform': [array([-62.76857376, 99.21972656, 0.19198459]), + array([ 4.19407082, 161.43023682, -0.52527243])]} +{'AngularVelocity': array([-0.08744425, -0.07619511, -6.38318348]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.791475296020508, + 'FR_Wheel_Angle': 41.673744201660156, + 'Location': array([-5.86580849e+01, 9.60250931e+01, 2.54500192e-02]), + 'Rotation': array([ 0.66752803, 17.66134453, 0.10312968]), + 'Velocity': array([-3.43808860e-01, -3.07862371e-01, -5.52940364e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4109.05615234375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4337.20507812, 15015.35742188, 79.72399902]), + 'frame': 28174, + 'frame_number': 28174, + 'framesequence': 113431, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 956.9994001500309, + 'timestamp_carla': 956998, + 'timestamp_device': 1827604, + 'timestamp_stream': 956.9994001500309, + 'transform': [array([-62.7388916 , 99.18894196, 0.17825 ]), + array([ 4.36729765, 161.61917114, -0.43497944])]} +{'AngularVelocity': array([ 3.74056734e-02, -4.91353543e-03, -5.69407225e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79145050048828, + 'FR_Wheel_Angle': 41.681556701660156, + 'Location': array([-5.87181854e+01, 9.59814301e+01, 2.55084224e-02]), + 'Rotation': array([ 0.67187202, 16.68554115, 0.10266267]), + 'Velocity': array([-0.35851166, -0.289141 , 0.00046641]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4121.76318359375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4346.93945312, 15030.50585938, 87.22213745]), + 'frame': 28175, + 'frame_number': 28175, + 'framesequence': 113434, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.0325313508511, + 'timestamp_carla': 957031, + 'timestamp_device': 1827629, + 'timestamp_stream': 957.0325313508511, + 'transform': [array([-62.70902634, 99.15848541, 0.16658928]), + array([ 4.51409912, 161.80752563, -0.35850421])]} +{'AngularVelocity': array([ 0.02386198, -0.02682745, -5.28225327]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.807682037353516, + 'FR_Wheel_Angle': 41.70514678955078, + 'Location': array([-5.87780800e+01, 9.59399261e+01, 2.55758278e-02]), + 'Rotation': array([ 0.67687851, 15.72845936, 0.10202932]), + 'Velocity': array([-0.34233555, -0.26914242, 0.00088482]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2849.095703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4760.65429688, 13825.42578125, 103.44464111]), + 'frame': 28176, + 'frame_number': 28176, + 'framesequence': 113438, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.0662294514477, + 'timestamp_carla': 957065, + 'timestamp_device': 1827662, + 'timestamp_stream': 957.0662294514477, + 'transform': [array([-62.67945099, 99.1282196 , 0.15659599]), + array([ 4.63982248, 161.99378967, -0.29313654])]} +{'AngularVelocity': array([-0.01762671, -0.02080647, -5.19576836]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8144474029541, + 'FR_Wheel_Angle': 41.716285705566406, + 'Location': array([-5.88462372e+01, 9.58943939e+01, 2.56229769e-02]), + 'Rotation': array([ 0.68211049, 14.65397072, 0.10227873]), + 'Velocity': array([-3.30416590e-01, -2.50681847e-01, 2.96173093e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2847.914794921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4770.30517578, 13825.875 , 107.3303833 ]), + 'frame': 28177, + 'frame_number': 28177, + 'framesequence': 113442, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.0992798507214, + 'timestamp_carla': 957098, + 'timestamp_device': 1827695, + 'timestamp_stream': 957.0992798507214, + 'transform': [array([-62.65032196, 99.09867096, 0.14850834]), + array([ 4.74366856, 162.17602539, -0.24005 ])]} +{'AngularVelocity': array([ 0.02283514, -0.01831145, -5.18488836]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.807228088378906, + 'FR_Wheel_Angle': 41.703041076660156, + 'Location': array([-5.89027214e+01, 9.58582916e+01, 2.56841648e-02]), + 'Rotation': array([ 0.68392044, 13.77973557, 0.1047028 ]), + 'Velocity': array([-0.34259608, -0.24778438, 0.00063328]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2856.12890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4777.01318359, 13835.21972656, 110.59571075]), + 'frame': 28178, + 'frame_number': 28178, + 'framesequence': 113446, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.1317808516324, + 'timestamp_carla': 957131, + 'timestamp_device': 1827729, + 'timestamp_stream': 957.1317808516324, + 'transform': [array([-62.62232208, 99.07044983, 0.14177142]), + array([ 4.82798052, 162.35002136, -0.19631493])]} +{'AngularVelocity': array([ 0.21739562, -0.08490247, -4.56119013]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.29056739807129, + 'FR_Wheel_Angle': 35.861175537109375, + 'Location': array([-5.89614449e+01, 9.58233643e+01, 2.55537797e-02]), + 'Rotation': array([ 0.69555229, 12.9357748 , 0.08925918]), + 'Velocity': array([-0.35047162, -0.21993735, -0.00121317]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2864.260498046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4783.65966797, 13844.47851562, 113.25077057]), + 'frame': 28179, + 'frame_number': 28179, + 'framesequence': 113450, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399212837219238, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.165814049542, + 'timestamp_carla': 957165, + 'timestamp_device': 1827762, + 'timestamp_stream': 957.165814049542, + 'transform': [array([-62.5928688 , 99.04106903, 0.13603847]), + array([ 4.90298939e+00, 1.62531845e+02, -1.58846051e-01])]} +{'AngularVelocity': array([-0.03663189, -0.01302892, -5.19256067]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.61124610900879, + 'FR_Wheel_Angle': 37.550140380859375, + 'Location': array([-5.90234604e+01, 9.57900238e+01, 2.50596236e-02]), + 'Rotation': array([ 0.71333808, 12.13210773, 0.06746339]), + 'Velocity': array([-0.42657652, -0.27245426, -0.0005815 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7176.77099609375, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-3486.08398438, 17955.78515625, 100.74531555]), + 'frame': 28180, + 'frame_number': 28180, + 'framesequence': 113454, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538236677646637, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.1994027495384, + 'timestamp_carla': 957198, + 'timestamp_device': 1827795, + 'timestamp_stream': 957.1994027495384, + 'transform': [array([-62.5658989 , 99.01279449, 0.13162094]), + array([ 4.96370316e+00, 1.62700653e+02, -1.29576027e-01])]} +{'AngularVelocity': array([-0.02437272, -0.02630362, -5.55768824]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.280628204345703, + 'FR_Wheel_Angle': 37.68144989013672, + 'Location': array([-5.91068573e+01, 9.57455750e+01, 2.50957869e-02]), + 'Rotation': array([ 0.7218895 , 11.02300072, 0.06814548]), + 'Velocity': array([-0.40445346, -0.24280345, 0.00064509]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2902.8447265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4790.10986328, 13884.25683594, 117.25389099]), + 'frame': 28181, + 'frame_number': 28181, + 'framesequence': 113459, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5256386399269104, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.2338072508574, + 'timestamp_carla': 957233, + 'timestamp_device': 1827837, + 'timestamp_stream': 957.2338072508574, + 'transform': [array([-62.53338242, 98.98072052, 0.12801971]), + array([ 5.01719713e+00, 1.62897842e+02, -1.05323792e-01])]} +{'AngularVelocity': array([-0.032084 , -0.09364497, -4.88520861]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.252355575561523, + 'FR_Wheel_Angle': 37.529937744140625, + 'Location': array([-5.91711159e+01, 9.57125549e+01, 2.49077603e-02]), + 'Rotation': array([ 0.73794729, 10.18286896, 0.08549565]), + 'Velocity': array([-0.37714338, -0.21623655, -0.00099238]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2892.552978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4801.93847656, 13875.76464844, 118.77281189]), + 'frame': 28182, + 'frame_number': 28182, + 'framesequence': 113463, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5027497410774231, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.2671506516635, + 'timestamp_carla': 957266, + 'timestamp_device': 1827870, + 'timestamp_stream': 957.2671506516635, + 'transform': [array([-62.50498962, 98.95121765, 0.12511532]), + array([ 5.05974245e+00, 1.63072830e+02, -8.59375000e-02])]} +{'AngularVelocity': array([ 0.04826789, -0.00910315, -4.05617952]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.306711196899414, + 'FR_Wheel_Angle': 37.54006576538086, + 'Location': array([-5.92347946e+01, 9.56812057e+01, 2.49071885e-02]), + 'Rotation': array([0.74303573, 9.35422039, 0.08854432]), + 'Velocity': array([-0.37542552, -0.21310131, 0.00088575]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2897.491943359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4810.69384766, 13882.13574219, 119.9928894 ]), + 'frame': 28183, + 'frame_number': 28183, + 'framesequence': 113467, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4777916967868805, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.301289152354, + 'timestamp_carla': 957300, + 'timestamp_device': 1827903, + 'timestamp_stream': 957.301289152354, + 'transform': [array([-62.47982407, 98.92362976, 0.12275371]), + array([ 5.09688473e+00, 1.63230637e+02, -6.99492246e-02])]} +{'AngularVelocity': array([ 0.00576712, -0.02726426, -4.85857487]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.31348991394043, + 'FR_Wheel_Angle': 37.515411376953125, + 'Location': array([-5.93113136e+01, 9.56450882e+01, 2.49971766e-02]), + 'Rotation': array([0.74659425, 8.36418533, 0.08953583]), + 'Velocity': array([-0.37920475, -0.20538712, 0.00043891]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2905.870849609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4817.40722656, 13891.48828125, 120.96231079]), + 'frame': 28184, + 'frame_number': 28184, + 'framesequence': 113471, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4573931097984314, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.3361095525324, + 'timestamp_carla': 957335, + 'timestamp_device': 1827937, + 'timestamp_stream': 957.3361095525324, + 'transform': [array([-62.45566177, 98.89610291, 0.12106834]), + array([ 5.12908936e+00, 1.63383163e+02, -5.77884987e-02])]} +{'AngularVelocity': array([ 0.28324181, -0.17226195, -5.75858068]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.28831672668457, + 'FR_Wheel_Angle': 37.48511505126953, + 'Location': array([-5.93957329e+01, 9.56072540e+01, 2.44906619e-02]), + 'Rotation': array([0.7711215 , 7.29278564, 0.05528752]), + 'Velocity': array([-0.43325126, -0.22793603, -0.0033233 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2913.613037109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4823.51269531, 13899.99121094, 121.76075745]), + 'frame': 28185, + 'frame_number': 28185, + 'framesequence': 113475, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4543534815311432, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.3695594519377, + 'timestamp_carla': 957368, + 'timestamp_device': 1827970, + 'timestamp_stream': 957.3695594519377, + 'transform': [array([-62.43236542, 98.86972809, 0.12003055]), + array([ 5.15771484e+00, 1.63529510e+02, -4.90886718e-02])]} +{'AngularVelocity': array([-0.18375768, -0.16626658, -6.03890276]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.28977394104004, + 'FR_Wheel_Angle': 37.499752044677734, + 'Location': array([-5.94693069e+01, 9.55750198e+01, 2.42617801e-02]), + 'Rotation': array([0.78685826, 6.35055876, 0.05922776]), + 'Velocity': array([-0.42801026, -0.22684433, -0.00079326]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7144.0166015625, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-3622.24145508, 17954.79296875, 118.12386322]), + 'frame': 28186, + 'frame_number': 28186, + 'framesequence': 113479, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.463948518037796, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.4021673500538, + 'timestamp_carla': 957401, + 'timestamp_device': 1828003, + 'timestamp_stream': 957.4021673500538, + 'transform': [array([-62.40775681, 98.84156799, 0.11957325]), + array([ 5.18212557e+00, 1.63683762e+02, -4.35750000e-02])]} +{'AngularVelocity': array([-0.06584885, -0.06451537, -6.00873613]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.166383743286133, + 'FR_Wheel_Angle': 32.31932830810547, + 'Location': array([-5.95439835e+01, 9.55441666e+01, 2.41458509e-02]), + 'Rotation': array([0.7984764 , 5.40266418, 0.07413673]), + 'Velocity': array([-0.45296049, -0.22274074, 0.00104087]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2949.411865234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4829.31201172, 13936.18945312, 122.77758789]), + 'frame': 28187, + 'frame_number': 28187, + 'framesequence': 113483, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47726067900657654, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.4361987523735, + 'timestamp_carla': 957435, + 'timestamp_device': 1828037, + 'timestamp_stream': 957.4361987523735, + 'transform': [array([-62.3804512 , 98.81233978, 0.11852756]), + array([ 5.20098400e+00, 1.63851166e+02, -3.64059769e-02])]} +{'AngularVelocity': array([ 0.25933337, -0.19470379, -5.40145826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.27781867980957, + 'FR_Wheel_Angle': 34.07015609741211, + 'Location': array([-5.96391258e+01, 9.55107269e+01, 2.37771217e-02]), + 'Rotation': array([0.82225227, 4.36909199, 0.04184691]), + 'Velocity': array([-0.45929897, -0.1907955 , -0.00300163]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2940.247314453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4840.25439453, 13928.33398438, 123.06105804]), + 'frame': 28188, + 'frame_number': 28188, + 'framesequence': 113487, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49011507630348206, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.4698766507208, + 'timestamp_carla': 957469, + 'timestamp_device': 1828070, + 'timestamp_stream': 957.4698766507208, + 'transform': [array([-62.35341644, 98.78388214, 0.1173648 ]), + array([ 5.21386576e+00, 1.64015625e+02, -2.95423642e-02])]} +{'AngularVelocity': array([-0.02571384, -0.02244006, -4.84709883]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.49631690979004, + 'FR_Wheel_Angle': 33.219120025634766, + 'Location': array([-5.97302628e+01, 9.54799576e+01, 2.35751718e-02]), + 'Rotation': array([0.83680743, 3.36778116, 0.03179355]), + 'Velocity': array([-0.43439823, -0.17079216, 0.00070552]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2945.011474609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4847.94335938, 13934.0234375 , 123.41786957]), + 'frame': 28189, + 'frame_number': 28189, + 'framesequence': 113491, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49324628710746765, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.5032158493996, + 'timestamp_carla': 957502, + 'timestamp_device': 1828103, + 'timestamp_stream': 957.5032158493996, + 'transform': [array([-62.32764816, 98.75610352, 0.11647968]), + array([ 5.22341442e+00, 1.64173065e+02, -2.43327450e-02])]} +{'AngularVelocity': array([-0.03868741, -0.01453702, -4.64075708]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.719362258911133, + 'FR_Wheel_Angle': 33.26087951660156, + 'Location': array([-5.97993889e+01, 9.54579544e+01, 2.37081908e-02]), + 'Rotation': array([0.83973753, 2.61365938, 0.03439194]), + 'Velocity': array([-0.40605271, -0.15567166, 0.00064378]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2953.385986328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4854.50878906, 13943.16796875, 123.7611084 ]), + 'frame': 28190, + 'frame_number': 28190, + 'framesequence': 113495, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4888332784175873, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.5362410508096, + 'timestamp_carla': 957535, + 'timestamp_device': 1828137, + 'timestamp_stream': 957.5362410508096, + 'transform': [array([-62.30040741, 98.72835541, 0.11579712]), + array([ 5.23342705e+00, 1.64337097e+02, -2.00120471e-02])]} +{'AngularVelocity': array([ 0.00830371, -0.0220388 , -4.16727924]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.730480194091797, + 'FR_Wheel_Angle': 33.3314094543457, + 'Location': array([-5.98652000e+01, 9.54380722e+01, 2.38206089e-02]), + 'Rotation': array([0.84189588, 1.89896286, 0.03634063]), + 'Velocity': array([-0.38506529, -0.13844246, 0.00076971]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2961.534423828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4860.8359375 , 13951.98242188, 124.02283478]), + 'frame': 28191, + 'frame_number': 28191, + 'framesequence': 113499, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.481984943151474, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.5704372487962, + 'timestamp_carla': 957569, + 'timestamp_device': 1828170, + 'timestamp_stream': 957.5704372487962, + 'transform': [array([-62.2720871 , 98.69991302, 0.11500701]), + array([ 5.24029160e+00, 1.64506561e+02, -1.56911872e-02])]} +{'AngularVelocity': array([ 0.00877293, -0.01644393, -4.17063189]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.745887756347656, + 'FR_Wheel_Angle': 33.33449172973633, + 'Location': array([-5.99300728e+01, 9.54193039e+01, 2.39005275e-02]), + 'Rotation': array([0.84376055, 1.19710803, 0.03862687]), + 'Velocity': array([-0.39320931, -0.13637343, 0.00057226]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7124.29052734375, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-3746.02148438, 17961.31054688, 122.79244232]), + 'frame': 28192, + 'frame_number': 28192, + 'framesequence': 113503, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4751182496547699, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.6040939502418, + 'timestamp_carla': 957603, + 'timestamp_device': 1828203, + 'timestamp_stream': 957.6040939502418, + 'transform': [array([-62.24504852, 98.67253876, 0.11436825]), + array([ 5.24599457e+00, 1.64668549e+02, -1.21671325e-02])]} +{'AngularVelocity': array([ 0.24149482, -0.0917996 , -4.49738264]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.737274169921875, + 'FR_Wheel_Angle': 33.35279083251953, + 'Location': array([-6.00171165e+01, 9.53951035e+01, 2.39764396e-02]), + 'Rotation': array([0.84814554, 0.254217 , 0.03830568]), + 'Velocity': array([-0.4356401 , -0.13503836, -0.00074433]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2995.60546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4869.84472656, 13987.06738281, 124.44982147]), + 'frame': 28193, + 'frame_number': 28193, + 'framesequence': 113507, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.473323792219162, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.6368337497115, + 'timestamp_carla': 957636, + 'timestamp_device': 1828237, + 'timestamp_stream': 957.6368337497115, + 'transform': [array([-62.21957779, 98.64663696, 0.11380443]), + array([ 5.25003147e+00, 1.64821091e+02, -9.16411076e-03])]} +{'AngularVelocity': array([ 0.14143808, -0.25941187, -3.75644255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.742210388183594, + 'FR_Wheel_Angle': 33.357643127441406, + 'Location': array([-6.00875587e+01, 9.53765793e+01, 2.32780073e-02]), + 'Rotation': array([ 0.8817637 , -0.50378424, 0.01537889]), + 'Velocity': array([-0.42017013, -0.12421793, -0.00522137]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2987.20703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4880.97460938, 13980.03417969, 124.63224792]), + 'frame': 28194, + 'frame_number': 28194, + 'framesequence': 113511, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4757225513458252, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.6714789494872, + 'timestamp_carla': 957670, + 'timestamp_device': 1828270, + 'timestamp_stream': 957.6714789494872, + 'transform': [array([-62.19288254, 98.61972809, 0.11329887]), + array([ 5.25384283e+00, 1.64980286e+02, -6.52880827e-03])]} +{'AngularVelocity': array([-0.06597678, -0.02330443, -5.34238338]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.7431583404541, + 'FR_Wheel_Angle': 33.31907653808594, + 'Location': array([-6.01591377e+01, 9.53588638e+01, 2.30107494e-02]), + 'Rotation': array([ 0.8951987 , -1.26962292, 0.01981704]), + 'Velocity': array([-0.42294723, -0.12642944, 0.00069382]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2995.265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4887.24658203, 13988.77050781, 124.78557587]), + 'frame': 28195, + 'frame_number': 28195, + 'framesequence': 113515, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47953125834465027, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.7048530504107, + 'timestamp_carla': 957704, + 'timestamp_device': 1828303, + 'timestamp_stream': 957.7048530504107, + 'transform': [array([-62.16708374, 98.59406281, 0.11297348]), + array([ 5.25763321e+00, 1.65133347e+02, -4.62889206e-03])]} +{'AngularVelocity': array([-0.05507527, -0.01192824, -4.74569893]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.980148315429688, + 'FR_Wheel_Angle': 27.91202163696289, + 'Location': array([-6.02280617e+01, 9.53438873e+01, 2.31527705e-02]), + 'Rotation': array([ 0.8974663 , -1.95098853, 0.01873216]), + 'Velocity': array([-0.41269302, -0.09672462, 0.00081291]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3003.729736328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4893.82373047, 13997.93359375, 124.91841888]), + 'frame': 28196, + 'frame_number': 28196, + 'framesequence': 113519, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48247936367988586, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.7375945523381, + 'timestamp_carla': 957736, + 'timestamp_device': 1828337, + 'timestamp_stream': 957.7375945523381, + 'transform': [array([-62.14200592, 98.56934357, 0.11262187]), + array([ 5.25994873e+00, 1.65281494e+02, -2.78982031e-03])]} +{'AngularVelocity': array([ 0.00895689, -0.02043872, -3.8744719 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.308109283447266, + 'FR_Wheel_Angle': 29.057310104370117, + 'Location': array([-6.03091354e+01, 9.53291550e+01, 2.32826993e-02]), + 'Rotation': array([ 0.90085411, -2.68676805, 0.01922634]), + 'Velocity': array([-0.39695135, -0.09489959, 0.00066588]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3011.9072265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4900.18066406, 14006.7890625 , 125.01470947]), + 'frame': 28197, + 'frame_number': 28197, + 'framesequence': 113523, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48242440819740295, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.7726502493024, + 'timestamp_carla': 957771, + 'timestamp_device': 1828370, + 'timestamp_stream': 957.7726502493024, + 'transform': [array([-62.11510468, 98.54325104, 0.11235245]), + array([ 5.26242161e+00, 1.65439606e+02, -1.38039386e-03])]} +{'AngularVelocity': array([ 0.27857786, 0.10573608, -2.71684003]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.14628028869629, + 'FR_Wheel_Angle': 29.342811584472656, + 'Location': array([-6.03929176e+01, 9.53150101e+01, 2.24522781e-02]), + 'Rotation': array([ 0.86209279, -3.44537401, -0.06723021]), + 'Velocity': array([-0.41733769, -0.09507994, -0.0054756 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4220.69580078125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4601.27392578, 15176.82324219, 125.0513382 ]), + 'frame': 28198, + 'frame_number': 28198, + 'framesequence': 113527, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4807397723197937, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.8049369491637, + 'timestamp_carla': 957804, + 'timestamp_device': 1828403, + 'timestamp_stream': 957.8049369491637, + 'transform': [array([-62.09052658, 98.51933289, 0.11225719]), + array([ 5.26486683e+00, 1.65583969e+02, -6.13731041e-04])]} +{'AngularVelocity': array([-0.138317 , 0.7069217 , -4.19946384]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.0509090423584, + 'FR_Wheel_Angle': 29.165882110595703, + 'Location': array([-6.04677315e+01, 9.53033218e+01, 2.16744989e-02]), + 'Rotation': array([ 0.82643235, -4.12292671, -0.0522766 ]), + 'Velocity': array([-0.48355228, -0.09743916, -0.01782993]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3042.92041015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4909.34472656, 14038.68652344, 125.17995453]), + 'frame': 28199, + 'frame_number': 28199, + 'framesequence': 113531, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47887206077575684, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.8373043499887, + 'timestamp_carla': 957836, + 'timestamp_device': 1828437, + 'timestamp_stream': 957.8373043499887, + 'transform': [array([-62.0667572 , 98.49612427, 0.11204517]), + array([5.26571369e+00, 1.65723602e+02, 4.38073708e-04])]} +{'AngularVelocity': array([ 0.90449446, 0.52548075, -5.65183496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.05033302307129, + 'FR_Wheel_Angle': 29.126373291015625, + 'Location': array([-6.05535202e+01, 9.52914124e+01, 1.89854037e-02]), + 'Rotation': array([ 0.71684879, -4.91293621, -0.15991211]), + 'Velocity': array([-0.50972658, -0.0997951 , -0.0189673 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3036.267578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4919.08105469, 14033.11523438, 125.21967316]), + 'frame': 28200, + 'frame_number': 28200, + 'framesequence': 113535, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47859737277030945, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.8708983510733, + 'timestamp_carla': 957870, + 'timestamp_device': 1828470, + 'timestamp_stream': 957.8708983510733, + 'transform': [array([-62.04293823, 98.47272491, 0.11197051]), + array([5.26767397e+00, 1.65863831e+02, 9.72660608e-04])]} +{'AngularVelocity': array([ 0.49753252, 0.77687454, -5.52549124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.05378532409668, + 'FR_Wheel_Angle': 29.12542724609375, + 'Location': array([-6.06383934e+01, 9.52804260e+01, 1.58190541e-02]), + 'Rotation': array([ 0.58682251, -5.6697731 , -0.20407102]), + 'Velocity': array([-0.51378012, -0.08935766, -0.02518609]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3043.938720703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4924.99658203, 14041.35546875, 125.27555847]), + 'frame': 28201, + 'frame_number': 28201, + 'framesequence': 113539, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4795495569705963, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.9045213498175, + 'timestamp_carla': 957903, + 'timestamp_device': 1828503, + 'timestamp_stream': 957.9045213498175, + 'transform': [array([-62.01918411, 98.44972229, 0.11184547]), + array([5.26885557e+00, 1.66002762e+02, 1.63864507e-03])]} +{'AngularVelocity': array([-0.66774732, 0.34633946, -5.42456675]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.05722999572754, + 'FR_Wheel_Angle': 29.135286331176758, + 'Location': array([-6.07242813e+01, 9.52701416e+01, 1.30282976e-02]), + 'Rotation': array([ 0.48271677, -6.42511559, -0.16049191]), + 'Velocity': array([-0.50279176, -0.07534517, -0.01030138]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3051.716064453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4930.97119141, 14049.67773438, 125.30181122]), + 'frame': 28202, + 'frame_number': 28202, + 'framesequence': 113543, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48030033707618713, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.9367309510708, + 'timestamp_carla': 957935, + 'timestamp_device': 1828537, + 'timestamp_stream': 957.9367309510708, + 'transform': [array([-61.99611664, 98.42754364, 0.11192554]), + array([5.27105474e+00, 1.66137451e+02, 1.59063644e-03])]} +{'AngularVelocity': array([-0.05236538, 0.50087392, -5.22315454]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.066566467285156, + 'FR_Wheel_Angle': 29.136404037475586, + 'Location': array([-6.08065033e+01, 9.52616501e+01, 1.13586420e-02]), + 'Rotation': array([ 0.41173062, -7.14502668, -0.08099366]), + 'Velocity': array([-0.47996426, -0.06815145, -0.01465381]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3059.45068359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4936.91259766, 14057.95507812, 125.33592224]), + 'frame': 28203, + 'frame_number': 28203, + 'framesequence': 113547, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4801538288593292, + 'throttle_input': 0.2222171425819397, + 'timestamp': 957.9704950489104, + 'timestamp_carla': 957969, + 'timestamp_device': 1828570, + 'timestamp_stream': 957.9704950489104, + 'transform': [array([-61.97037506, 98.40200806, 0.11247718]), + array([ 5.27410793e+00, 1.66288452e+02, -4.30255837e-04])]} +{'AngularVelocity': array([ 0.17195965, 0.42717674, -5.28622627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.82200813293457, + 'FR_Wheel_Angle': 27.698307037353516, + 'Location': array([-6.08872185e+01, 9.52542496e+01, 9.27082077e-03]), + 'Rotation': array([ 0.32246688, -7.85904932, -0.03930664]), + 'Velocity': array([-0.48272318, -0.06295393, -0.01348805]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7095.86572265625, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-3977.40136719, 17977.54296875, 125.44391632]), + 'frame': 28204, + 'frame_number': 28204, + 'framesequence': 113551, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4796777367591858, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.0054103508592, + 'timestamp_carla': 958004, + 'timestamp_device': 1828603, + 'timestamp_stream': 958.0054103508592, + 'transform': [array([-61.93708801, 98.37134552, 0.11278808]), + array([ 5.27569246e+00, 1.66479111e+02, -1.62542693e-03])]} +{'AngularVelocity': array([-0.22403672, 0.13598698, -4.49789953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.207624435424805, + 'FR_Wheel_Angle': 24.116928100585938, + 'Location': array([-6.09669609e+01, 9.52500534e+01, 8.40869918e-03]), + 'Rotation': array([ 0.29142368, -8.48716259, -0.07363892]), + 'Velocity': array([-0.47530231, -0.0330906 , -0.00302893]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3094.18701171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4944.82519531, 14093.19238281, 125.22200012]), + 'frame': 28205, + 'frame_number': 28205, + 'framesequence': 113555, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47965940833091736, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.040529049933, + 'timestamp_carla': 958039, + 'timestamp_device': 1828637, + 'timestamp_stream': 958.040529049933, + 'transform': [array([-61.90525436, 98.34152222, 0.11267822]), + array([ 5.27511168e+00, 1.66662582e+02, -1.25727721e-03])]} +{'AngularVelocity': array([-0.22732072, 0.14603205, -4.46814394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.67749786376953, + 'FR_Wheel_Angle': 25.03264617919922, + 'Location': array([-6.10422058e+01, 9.52471008e+01, 7.98309315e-03]), + 'Rotation': array([ 0.27114484, -9.05439377, -0.01779174]), + 'Velocity': array([-0.44611439, -0.03268803, -0.00321891]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3086.327392578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4957.49755859, 14086.62988281, 125.15525818]), + 'frame': 28206, + 'frame_number': 28206, + 'framesequence': 113559, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.0738316513598, + 'timestamp_carla': 958073, + 'timestamp_device': 1828670, + 'timestamp_stream': 958.0738316513598, + 'transform': [array([-61.87633514, 98.31414795, 0.11259197]), + array([ 5.27553558e+00, 1.66829834e+02, -7.98030233e-04])]} +{'AngularVelocity': array([-0.33290133, 0.18093698, -4.35690498]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.373754501342773, + 'FR_Wheel_Angle': 25.210147857666016, + 'Location': array([-6.11165581e+01, 9.52450180e+01, 7.45357480e-03]), + 'Rotation': array([ 0.24738944, -9.6196413 , 0.03837169]), + 'Velocity': array([-0.44308311, -0.02807662, -0.00332697]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3084.048828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4968.45166016, 14085.3671875 , 125.17483521]), + 'frame': 28207, + 'frame_number': 28207, + 'framesequence': 113563, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.1069999523461, + 'timestamp_carla': 958106, + 'timestamp_device': 1828703, + 'timestamp_stream': 958.1069999523461, + 'transform': [array([-61.84775162, 98.28755951, 0.11231041]), + array([5.27462673e+00, 1.66993973e+02, 3.28546623e-04])]} +{'AngularVelocity': array([-0.35334828, 0.21389769, -3.54562187]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.290576934814453, + 'FR_Wheel_Angle': 25.015033721923828, + 'Location': array([-6.11872826e+01, 9.52435150e+01, 6.88831322e-03]), + 'Rotation': array([ 0.22405069, -10.1526022 , 0.08901178]), + 'Velocity': array([-0.41222933, -0.03090074, -0.00447097]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3097.072021484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4975.00390625, 14098.85742188, 125.19976807]), + 'frame': 28208, + 'frame_number': 28208, + 'framesequence': 113567, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.1394691504538, + 'timestamp_carla': 958138, + 'timestamp_device': 1828737, + 'timestamp_stream': 958.1394691504538, + 'transform': [array([-61.81834793, 98.26072693, 0.1122596 ]), + array([5.27477741e+00, 1.67161606e+02, 6.03130437e-04])]} +{'AngularVelocity': array([ 0.01501908, 0.04011742, -3.4767437 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.30147933959961, + 'FR_Wheel_Angle': 24.952680587768555, + 'Location': array([-6.12627411e+01, 9.52427902e+01, 6.72061928e-03]), + 'Rotation': array([ 0.21165389, -10.74919033, 0.10152124]), + 'Velocity': array([-5.35131693e-01, -2.59349439e-02, 2.24823947e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3101.5712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4983.35742188, 14104.03417969, 125.26164246]), + 'frame': 28209, + 'frame_number': 28209, + 'framesequence': 113571, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.172370351851, + 'timestamp_carla': 958171, + 'timestamp_device': 1828770, + 'timestamp_stream': 958.172370351851, + 'transform': [array([-61.7905159 , 98.23430634, 0.11227413]), + array([5.27518034e+00, 1.67322021e+02, 5.95842954e-04])]} +{'AngularVelocity': array([ 0.04371113, -0.04095175, -2.9339478 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.31251335144043, + 'FR_Wheel_Angle': 24.982763290405273, + 'Location': array([-6.13541946e+01, 9.52430191e+01, 6.72611222e-03]), + 'Rotation': array([ 0.21318385, -11.44334507, 0.09615366]), + 'Velocity': array([-5.21777570e-01, -1.91076063e-02, 1.33323672e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3118.479248046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4989.17041016, 14121.33203125, 125.27733612]), + 'frame': 28210, + 'frame_number': 28210, + 'framesequence': 113575, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.20613675192, + 'timestamp_carla': 958205, + 'timestamp_device': 1828803, + 'timestamp_stream': 958.20613675192, + 'transform': [array([-61.76093292, 98.20700836, 0.11223205]), + array([5.27535772e+00, 1.67490845e+02, 7.73808279e-04])]} +{'AngularVelocity': array([ 0.05122593, -0.03083305, -2.70016074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.32970428466797, + 'FR_Wheel_Angle': 25.002840042114258, + 'Location': array([-6.14358788e+01, 9.52441559e+01, 6.71009067e-03]), + 'Rotation': array([ 0.21639404, -12.07255936, 0.09054991]), + 'Velocity': array([-4.70429599e-01, -1.17010064e-02, 2.98166269e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3135.351318359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4994.71484375, 14138.47265625, 125.2769928 ]), + 'frame': 28211, + 'frame_number': 28211, + 'framesequence': 113579, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.2408462502062, + 'timestamp_carla': 958240, + 'timestamp_device': 1828837, + 'timestamp_stream': 958.2408462502062, + 'transform': [array([-61.73137665, 98.17990875, 0.1119677 ]), + array([5.27401209e+00, 1.67658875e+02, 1.70049898e-03])]} +{'AngularVelocity': array([ 0.28606662, 0.09482624, -2.62905145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.339303970336914, + 'FR_Wheel_Angle': 25.016429901123047, + 'Location': array([-6.15104790e+01, 9.52460556e+01, 6.52256003e-03]), + 'Rotation': array([ 0.20756944, -12.65043926, 0.0685581 ]), + 'Velocity': array([-0.44291526, -0.01061492, -0.00344368]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3145.4091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5002.29638672, 14149.03320312, 125.28608704]), + 'frame': 28212, + 'frame_number': 28212, + 'framesequence': 113583, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.2740854509175, + 'timestamp_carla': 958273, + 'timestamp_device': 1828870, + 'timestamp_stream': 958.2740854509175, + 'transform': [array([-61.70277023, 98.15406036, 0.11191273]), + array([5.27474308e+00, 1.67820663e+02, 2.04362348e-03])]} +{'AngularVelocity': array([ 0.07304322, 0.03024191, -2.18488646]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.33555030822754, + 'FR_Wheel_Angle': 24.502262115478516, + 'Location': array([-6.15834274e+01, 9.52486343e+01, 5.93158696e-03]), + 'Rotation': array([ 0.18281001, -13.22310448, 0.02573376]), + 'Velocity': array([-0.42695013, -0.00333569, -0.00233674]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3146.80615234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5011.73681641, 14151.10742188, 125.33668518]), + 'frame': 28213, + 'frame_number': 28213, + 'framesequence': 113588, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.308731649071, + 'timestamp_carla': 958307, + 'timestamp_device': 1828912, + 'timestamp_stream': 958.308731649071, + 'transform': [array([-61.67305374, 98.12716675, 0.11196274]), + array([5.27556944e+00, 1.67988770e+02, 1.89250859e-03])]} +{'AngularVelocity': array([ 0.02337979, 0.02023924, -1.9263531 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.216449737548828, + 'FR_Wheel_Angle': 19.409019470214844, + 'Location': array([-6.16531105e+01, 9.52529678e+01, 5.86189236e-03]), + 'Rotation': array([ 0.18069264, -13.70714474, 0.0254679 ]), + 'Velocity': array([-4.33679372e-01, 2.65576076e-02, 2.11162565e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3150.52880859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5020.32763672, 14155.42382812, 125.3553772 ]), + 'frame': 28214, + 'frame_number': 28214, + 'framesequence': 113591, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.3413389511406, + 'timestamp_carla': 958340, + 'timestamp_device': 1828937, + 'timestamp_stream': 958.3413389511406, + 'transform': [array([-61.64298248, 98.10034943, 0.11197303]), + array([5.27633429e+00, 1.68157455e+02, 1.98109169e-03])]} +{'AngularVelocity': array([ 0.03630754, 0.01186535, -3.23141623]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.983823776245117, + 'FR_Wheel_Angle': 21.23409652709961, + 'Location': array([-6.17275658e+01, 9.52589493e+01, 5.85926045e-03]), + 'Rotation': array([ 0.1789646 , -14.19740772, 0.0309058 ]), + 'Velocity': array([-4.58781689e-01, 2.32806969e-02, 2.15930937e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3158.838623046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5028.36425781, 14164.21679688, 125.34588623]), + 'frame': 28215, + 'frame_number': 28215, + 'framesequence': 113596, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.3787450492382, + 'timestamp_carla': 958377, + 'timestamp_device': 1828978, + 'timestamp_stream': 958.3787450492382, + 'transform': [array([-61.60966492, 98.07041168, 0.11191928]), + array([5.27761841e+00, 1.68345139e+02, 2.20793393e-03])]} +{'AngularVelocity': array([ 0.06472411, -0.02184768, -2.37017989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.500940322875977, + 'FR_Wheel_Angle': 21.018112182617188, + 'Location': array([-6.18010635e+01, 9.52655029e+01, 5.83461765e-03]), + 'Rotation': array([ 0.17903973, -14.68092537, 0.03015339]), + 'Velocity': array([-0.42391178, 0.03175304, -0.00049075]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3167.215576171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5036.45166016, 14173.06640625, 125.35138702]), + 'frame': 28216, + 'frame_number': 28216, + 'framesequence': 113600, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.4134827516973, + 'timestamp_carla': 958412, + 'timestamp_device': 1829012, + 'timestamp_stream': 958.4134827516973, + 'transform': [array([-61.57844543, 98.04252625, 0.11203216]), + array([5.27993393e+00, 1.68520737e+02, 2.01625703e-03])]} +{'AngularVelocity': array([-0.05587628, 0.09874615, -4.56530333]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.38252830505371, + 'FR_Wheel_Angle': 20.801029205322266, + 'Location': array([-6.18950996e+01, 9.52748718e+01, 5.81203448e-03]), + 'Rotation': array([ 0.17393759, -15.29957867, 0.03383088]), + 'Velocity': array([-0.53818029, 0.03481697, -0.00064738]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7073.36572265625, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4258.29833984, 17999.35351562, 125.50900269]), + 'frame': 28217, + 'frame_number': 28217, + 'framesequence': 113604, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.446689851582, + 'timestamp_carla': 958445, + 'timestamp_device': 1829045, + 'timestamp_stream': 958.446689851582, + 'transform': [array([-61.54850769, 98.01612854, 0.11187519]), + array([5.27856112e+00, 1.68688019e+02, 2.59189587e-03])]} +{'AngularVelocity': array([ 0.30731606, 0.1562393 , -3.50005722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.411521911621094, + 'FR_Wheel_Angle': 20.8124942779541, + 'Location': array([-6.19794426e+01, 9.52841949e+01, 4.92286682e-03]), + 'Rotation': array([ 0.1345752 , -15.84486294, 0.02181156]), + 'Velocity': array([-0.50666672, 0.02960591, -0.00817964]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3199.984130859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5051.15625 , 14206.45898438, 125.34803009]), + 'frame': 28218, + 'frame_number': 28218, + 'framesequence': 113608, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.479937851429, + 'timestamp_carla': 958479, + 'timestamp_device': 1829078, + 'timestamp_stream': 958.479937851429, + 'transform': [array([-61.51986313, 97.99069214, 0.11177051]), + array([5.27798080e+00, 1.68848389e+02, 3.01057706e-03])]} +{'AngularVelocity': array([-0.02846041, 0.02277301, -3.63852739]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.419301986694336, + 'FR_Wheel_Angle': 20.803287506103516, + 'Location': array([-6.20624352e+01, 9.52942581e+01, 4.49485751e-03]), + 'Rotation': array([ 1.22936569e-01, -1.63778210e+01, 7.95844384e-03]), + 'Velocity': array([-5.24441898e-01, 4.50904109e-02, -7.10678069e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3194.05712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5062.18066406, 14201.21875 , 125.38246918]), + 'frame': 28219, + 'frame_number': 28219, + 'framesequence': 113612, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.5136863514781, + 'timestamp_carla': 958512, + 'timestamp_device': 1829112, + 'timestamp_stream': 958.5136863514781, + 'transform': [array([-61.49163437, 97.96557617, 0.11179157]), + array([5.27920341e+00, 1.69006668e+02, 3.06518911e-03])]} +{'AngularVelocity': array([ 0.00321286, -0.02511386, -2.92199087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.431209564208984, + 'FR_Wheel_Angle': 20.821218490600586, + 'Location': array([-6.21438408e+01, 9.53048935e+01, 4.50950628e-03]), + 'Rotation': array([ 1.25614002e-01, -1.69138336e+01, 7.79078901e-03]), + 'Velocity': array([-4.68156189e-01, 4.58878130e-02, 3.08427814e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3202.312744140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5070.03613281, 14209.81445312, 125.4074707 ]), + 'frame': 28220, + 'frame_number': 28220, + 'framesequence': 113616, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.5465833507478, + 'timestamp_carla': 958545, + 'timestamp_device': 1829145, + 'timestamp_stream': 958.5465833507478, + 'transform': [array([-61.46232605, 97.94036102, 0.1117683 ]), + array([5.27899122e+00, 1.69168808e+02, 3.16797034e-03])]} +{'AngularVelocity': array([ 0.32308558, 0.09034979, -3.29423261]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.434600830078125, + 'FR_Wheel_Angle': 20.804101943969727, + 'Location': array([-6.22201958e+01, 9.53156357e+01, 4.22138209e-03]), + 'Rotation': array([ 0.11129793, -17.4223423 , -0.02218628]), + 'Velocity': array([-0.46586332, 0.04020458, -0.00458801]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3210.5341796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5077.83251953, 14218.34472656, 125.40989685]), + 'frame': 28221, + 'frame_number': 28221, + 'framesequence': 113620, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.5823910497129, + 'timestamp_carla': 958581, + 'timestamp_device': 1829178, + 'timestamp_stream': 958.5823910497129, + 'transform': [array([-61.43121338, 97.91334534, 0.11184776]), + array([5.27951050e+00, 1.69341446e+02, 2.80416291e-03])]} +{'AngularVelocity': array([-0.05470374, 0.00953473, -3.34452844]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.40240478515625, + 'FR_Wheel_Angle': 20.177690505981445, + 'Location': array([-6.23035088e+01, 9.53278503e+01, 3.71490465e-03]), + 'Rotation': array([ 0.08933887, -17.96940231, -0.05581665]), + 'Velocity': array([-0.49605232, 0.04854035, -0.00096361]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7067.8037109375, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4362.55664062, 18007.38671875, 125.62892151]), + 'frame': 28222, + 'frame_number': 28222, + 'framesequence': 113625, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.6246032491326, + 'timestamp_carla': 958623, + 'timestamp_device': 1829220, + 'timestamp_stream': 958.6246032491326, + 'transform': [array([-61.39461136, 97.88227081, 0.11162075]), + array([5.27645731e+00, 1.69542725e+02, 3.45615298e-03])]} +{'AngularVelocity': array([ 0.02068326, 0.02530461, -2.40172577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.36269474029541, + 'FR_Wheel_Angle': 16.173263549804688, + 'Location': array([-6.23830261e+01, 9.53419418e+01, 3.70727526e-03]), + 'Rotation': array([ 0.09019947, -18.40961456, -0.05523682]), + 'Velocity': array([-5.07236183e-01, 9.37099457e-02, 3.35845951e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7066.87841796875, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4384.37646484, 18009.11328125, 125.58184814]), + 'frame': 28223, + 'frame_number': 28223, + 'framesequence': 113629, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.6564416512847, + 'timestamp_carla': 958655, + 'timestamp_device': 1829253, + 'timestamp_stream': 958.6564416512847, + 'transform': [array([-61.36859894, 97.85958862, 0.11172867]), + array([5.27740669e+00, 1.69687119e+02, 3.17482161e-03])]} +{'AngularVelocity': array([-0.14484416, 0.17296019, -2.71296024]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.609456062316895, + 'FR_Wheel_Angle': 16.474872589111328, + 'Location': array([-6.24790382e+01, 9.53607407e+01, 3.39107495e-03]), + 'Rotation': array([ 7.72972479e-02, -1.89210548e+01, -1.73339806e-02]), + 'Velocity': array([-0.45615405, 0.08221948, -0.00416094]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3240.6591796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5104.08203125, 14249.46875 , 125.43549347]), + 'frame': 28224, + 'frame_number': 28224, + 'framesequence': 113634, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.6921326518059, + 'timestamp_carla': 958691, + 'timestamp_device': 1829295, + 'timestamp_stream': 958.6921326518059, + 'transform': [array([-61.33805466, 97.83399963, 0.1115858 ]), + array([5.27624559e+00, 1.69854294e+02, 3.56606091e-03])]} +{'AngularVelocity': array([-0.02899412, 0.00945185, -3.28070807]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.49151611328125, + 'FR_Wheel_Angle': 16.831024169921875, + 'Location': array([-6.25572205e+01, 9.53770370e+01, 3.25981132e-03]), + 'Rotation': array([ 7.29600787e-02, -1.93288326e+01, -1.13525381e-02]), + 'Velocity': array([-4.65952247e-01, 8.10712352e-02, 1.65624617e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3246.362548828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5111.70556641, 14255.40722656, 125.42079926]), + 'frame': 28225, + 'frame_number': 28225, + 'framesequence': 113638, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47528308629989624, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.7263324521482, + 'timestamp_carla': 958725, + 'timestamp_device': 1829328, + 'timestamp_stream': 958.7263324521482, + 'transform': [array([-61.30925751, 97.80975342, 0.1116486 ]), + array([5.27679205e+00, 1.70011963e+02, 3.36703844e-03])]} +{'AngularVelocity': array([ 0.25722992, 0.01185557, -3.49910736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.377238273620605, + 'FR_Wheel_Angle': 16.695980072021484, + 'Location': array([-6.26298370e+01, 9.53925781e+01, 3.23524466e-03]), + 'Rotation': array([ 7.25366026e-02, -1.97231140e+01, -1.62048340e-02]), + 'Velocity': array([-0.4301905 , 0.07936116, -0.00165533]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.299072265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5120.12109375, 14264.61621094, 125.44241333]), + 'frame': 28226, + 'frame_number': 28226, + 'framesequence': 113642, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45807063579559326, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.7618126496673, + 'timestamp_carla': 958761, + 'timestamp_device': 1829361, + 'timestamp_stream': 958.7618126496673, + 'transform': [array([-61.28067398, 97.78546906, 0.11140388]), + array([5.27556944e+00, 1.70168030e+02, 4.23113583e-03])]} +{'AngularVelocity': array([ 0.37824774, 0.08057612, -3.56779361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.388021469116211, + 'FR_Wheel_Angle': 16.657060623168945, + 'Location': array([-6.27001991e+01, 9.54082794e+01, 2.78087612e-03]), + 'Rotation': array([ 0.04861728, -20.1118145 , -0.05996703]), + 'Velocity': array([-0.46421179, 0.08791536, -0.00494415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3263.810302734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5128.09960938, 14273.34667969, 125.43133545]), + 'frame': 28227, + 'frame_number': 28227, + 'framesequence': 113646, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.43302106857299805, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.7949657514691, + 'timestamp_carla': 958794, + 'timestamp_device': 1829395, + 'timestamp_stream': 958.7949657514691, + 'transform': [array([-61.25938034, 97.76438904, 0.11149315]), + array([5.27364349e+00, 1.70288345e+02, 3.69629054e-03])]} +{'AngularVelocity': array([-0.11648248, 0.11061623, -3.3732934 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.393996238708496, + 'FR_Wheel_Angle': 16.66621208190918, + 'Location': array([-6.27741241e+01, 9.54249878e+01, 2.14149477e-03]), + 'Rotation': array([ 0.02428815, -20.50240707, -0.04092407]), + 'Velocity': array([-0.43230405, 0.08869256, -0.0027984 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7063.09521484375, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4488.69042969, 18017.109375 , 125.75980377]), + 'frame': 28228, + 'frame_number': 28228, + 'framesequence': 113650, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4096194803714752, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.8287786506116, + 'timestamp_carla': 958828, + 'timestamp_device': 1829428, + 'timestamp_stream': 958.8287786506116, + 'transform': [array([-61.23704529, 97.74332428, 0.11150493]), + array([5.27280331e+00, 1.70412140e+02, 3.56547860e-03])]} +{'AngularVelocity': array([-0.04032503, 0.02173479, -1.9044857 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.401215553283691, + 'FR_Wheel_Angle': 16.672752380371094, + 'Location': array([-6.28461990e+01, 9.54421539e+01, 2.06691748e-03]), + 'Rotation': array([ 0.02378272, -20.87828827, -0.03549195]), + 'Velocity': array([-4.41691041e-01, 9.00942311e-02, 3.12299730e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3299.94091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5138.70263672, 14309.20800781, 125.45585632]), + 'frame': 28229, + 'frame_number': 28229, + 'framesequence': 113654, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3944578766822815, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.86301555112, + 'timestamp_carla': 958862, + 'timestamp_device': 1829461, + 'timestamp_stream': 958.86301555112, + 'transform': [array([-61.21852875, 97.72310638, 0.11173023]), + array([5.27273512e+00, 1.70518417e+02, 2.59848987e-03])]} +{'AngularVelocity': array([-7.04180449e-03, -1.94582669e-03, -2.77878928e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.390032768249512, + 'FR_Wheel_Angle': 16.65730094909668, + 'Location': array([-6.29220657e+01, 9.54607010e+01, 2.11502076e-03]), + 'Rotation': array([ 0.02263525, -21.29924393, -0.03604126]), + 'Velocity': array([-4.58691329e-01, 9.19739157e-02, 6.62708262e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3291.627197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5147.65429688, 14301.02734375, 125.4491272 ]), + 'frame': 28230, + 'frame_number': 28230, + 'framesequence': 113658, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3974059522151947, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.8967328518629, + 'timestamp_carla': 958895, + 'timestamp_device': 1829495, + 'timestamp_stream': 958.8967328518629, + 'transform': [array([-61.1963768 , 97.70314026, 0.11118225]), + array([5.27267361e+00, 1.70638748e+02, 4.93043428e-03])]} +{'AngularVelocity': array([-0.03287406, -0.00866984, -2.5278964 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.109715461730957, + 'FR_Wheel_Angle': 15.164855003356934, + 'Location': array([-6.29966927e+01, 9.54791260e+01, 2.11032853e-03]), + 'Rotation': array([ 0.02349585, -21.70851707, -0.03674316]), + 'Velocity': array([-4.43280756e-01, 9.32871103e-02, 3.80401616e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3292.5712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5154.05224609, 14301.74316406, 125.39416504]), + 'frame': 28231, + 'frame_number': 28231, + 'framesequence': 113662, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4106997847557068, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.92986305058, + 'timestamp_carla': 958929, + 'timestamp_device': 1829528, + 'timestamp_stream': 958.92986305058, + 'transform': [array([-61.17544174, 97.68286896, 0.1116946 ]), + array([5.27642345e+00, 1.70754517e+02, 3.20187840e-03])]} +{'AngularVelocity': array([-0.00206555, 0.05957005, -1.59914184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.957708358764648, + 'FR_Wheel_Angle': 11.616982460021973, + 'Location': array([-6.30694847e+01, 9.54998016e+01, 2.13150028e-03]), + 'Rotation': array([ 0.02289479, -22.02235413, -0.03903198]), + 'Velocity': array([-4.76659685e-01, 1.35729119e-01, 1.76610949e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3299.39794921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5160.22363281, 14308.49609375, 125.52771759]), + 'frame': 28232, + 'frame_number': 28232, + 'framesequence': 113666, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4237556457519531, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.9635127522051, + 'timestamp_carla': 958962, + 'timestamp_device': 1829561, + 'timestamp_stream': 958.9635127522051, + 'transform': [array([-61.15074158, 97.66099548, 0.11185196]), + array([5.27776861e+00, 1.70888672e+02, 2.67463247e-03])]} +{'AngularVelocity': array([ 0.02870447, -0.03295153, -2.24936724]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.560826301574707, + 'FR_Wheel_Angle': 12.578926086425781, + 'Location': array([-6.31513786e+01, 9.55242004e+01, 2.13287352e-03]), + 'Rotation': array([ 2.07501128e-02, -2.23760204e+01, -3.45764123e-02]), + 'Velocity': array([-4.98976320e-01, 1.37691826e-01, -8.43715679e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3306.1435546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5166.22314453, 14315.06054688, 125.42646027]), + 'frame': 28233, + 'frame_number': 28233, + 'framesequence': 113670, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.43238016963005066, + 'throttle_input': 0.2222171425819397, + 'timestamp': 958.9976105503738, + 'timestamp_carla': 958996, + 'timestamp_device': 1829595, + 'timestamp_stream': 958.9976105503738, + 'transform': [array([-61.12504578, 97.6386795 , 0.11203255]), + array([5.27966070e+00, 1.71028412e+02, 2.09797802e-03])]} +{'AngularVelocity': array([ 0.02899534, -0.04057325, -1.68170822]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.18552017211914, + 'FR_Wheel_Angle': 12.671881675720215, + 'Location': array([-6.32309494e+01, 9.55482712e+01, 2.08808901e-03]), + 'Rotation': array([ 0.02419253, -22.70799065, -0.03555298]), + 'Velocity': array([-4.41962421e-01, 1.28333330e-01, -1.37128824e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3313.828857421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5173.18554688, 14322.67871094, 125.39509583]), + 'frame': 28234, + 'frame_number': 28234, + 'framesequence': 113675, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4310983717441559, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.032278649509, + 'timestamp_carla': 959031, + 'timestamp_device': 1829636, + 'timestamp_stream': 959.032278649509, + 'transform': [array([-61.09799194, 97.61552429, 0.11208095]), + array([5.27972889e+00, 1.71174789e+02, 1.86468195e-03])]} +{'AngularVelocity': array([-0.01772973, 0.08404146, -1.71714187]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.109249114990234, + 'FR_Wheel_Angle': 12.480907440185547, + 'Location': array([-6.33069420e+01, 9.55716324e+01, 1.75369263e-03]), + 'Rotation': array([ 5.74418856e-03, -2.30252171e+01, -1.22070342e-04]), + 'Velocity': array([-0.49407223, 0.14708568, -0.00168997]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7062.68310546875, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4597.10693359, 18025.72070312, 125.49645996]), + 'frame': 28235, + 'frame_number': 28235, + 'framesequence': 113678, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42507404088974, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.0659168511629, + 'timestamp_carla': 959065, + 'timestamp_device': 1829661, + 'timestamp_stream': 959.0659168511629, + 'transform': [array([-61.06822586, 97.5905838 , 0.11221942]), + array([5.27908039e+00, 1.71333954e+02, 1.21958600e-03])]} +{'AngularVelocity': array([ 0.00907212, -0.01581548, -3.32161927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.151250839233398, + 'FR_Wheel_Angle': 12.483135223388672, + 'Location': array([-6.33868523e+01, 9.55968246e+01, 1.67518610e-03]), + 'Rotation': array([ 5.66222658e-03, -2.33680820e+01, 6.04437737e-05]), + 'Velocity': array([-4.82415915e-01, 1.40905917e-01, 9.47380031e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3349.568115234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5185.19433594, 14358.09667969, 125.34664917]), + 'frame': 28236, + 'frame_number': 28236, + 'framesequence': 113682, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4189581274986267, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.0979711525142, + 'timestamp_carla': 959097, + 'timestamp_device': 1829695, + 'timestamp_stream': 959.0979711525142, + 'transform': [array([-61.04285431, 97.56777954, 0.11236267]), + array([5.27929878e+00, 1.71472305e+02, 6.91796478e-04])]} +{'AngularVelocity': array([-0.02075927, 0.01924232, -2.56664562]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.162457466125488, + 'FR_Wheel_Angle': 12.49570369720459, + 'Location': array([-6.34770889e+01, 9.56258698e+01, 1.69765472e-03]), + 'Rotation': array([ 9.00218915e-03, -2.37397881e+01, -2.13623047e-03]), + 'Velocity': array([-4.39035952e-01, 1.29920468e-01, 1.18236538e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3339.502197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5196.51416016, 14348.20410156, 125.31011963]), + 'frame': 28237, + 'frame_number': 28237, + 'framesequence': 113686, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41441696882247925, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.1315016523004, + 'timestamp_carla': 959130, + 'timestamp_device': 1829728, + 'timestamp_stream': 959.1315016523004, + 'transform': [array([-61.0174408 , 97.5447464 , 0.11220997]), + array([5.27792597e+00, 1.71610962e+02, 1.17223861e-03])]} +{'AngularVelocity': array([-0.01824514, 0.00576533, -2.72550249]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.162671089172363, + 'FR_Wheel_Angle': 12.493770599365234, + 'Location': array([-6.35483742e+01, 9.56495132e+01, 1.70524593e-03]), + 'Rotation': array([ 8.04596208e-03, -2.40365086e+01, -1.46484387e-03]), + 'Velocity': array([-4.26097184e-01, 1.29829481e-01, -3.48024361e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3347.709716796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5203.84667969, 14356.22753906, 125.2808609 ]), + 'frame': 28238, + 'frame_number': 28238, + 'framesequence': 113690, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4150029122829437, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.1648078523576, + 'timestamp_carla': 959164, + 'timestamp_device': 1829761, + 'timestamp_stream': 959.1648078523576, + 'transform': [array([-60.99175262, 97.52188873, 0.11222892]), + array([5.27926445e+00, 1.71750488e+02, 1.24061969e-03])]} +{'AngularVelocity': array([ 1.71523367e-03, 5.44023663e-02, -3.01010799e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.156418800354004, + 'FR_Wheel_Angle': 12.489083290100098, + 'Location': array([-6.36168556e+01, 9.56725159e+01, 1.71291351e-03]), + 'Rotation': array([ 7.13754725e-03, -2.43282547e+01, -7.32421817e-04]), + 'Velocity': array([-4.50452656e-01, 1.41988680e-01, 8.07285323e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3356.014404296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5211.22851562, 14364.3046875 , 125.30982208]), + 'frame': 28239, + 'frame_number': 28239, + 'framesequence': 113694, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41800594329833984, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.199011951685, + 'timestamp_carla': 959198, + 'timestamp_device': 1829795, + 'timestamp_stream': 959.199011951685, + 'transform': [array([-60.96566772, 97.49876404, 0.11205146]), + array([5.27810335e+00, 1.71891586e+02, 1.83048809e-03])]} +{'AngularVelocity': array([ 2.40522364e-04, -6.30736258e-03, -2.34443593e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.537619590759277, + 'FR_Wheel_Angle': 7.634101390838623, + 'Location': array([-6.37026939e+01, 9.57019882e+01, 1.70829764e-03]), + 'Rotation': array([ 7.85471685e-03, -2.46818027e+01, -1.52587867e-03]), + 'Velocity': array([-4.07725453e-01, 1.34097442e-01, 1.96466441e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3364.387451171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5218.68212891, 14372.45996094, 125.31262207]), + 'frame': 28240, + 'frame_number': 28240, + 'framesequence': 113699, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4210089445114136, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.2344993501902, + 'timestamp_carla': 959233, + 'timestamp_device': 1829836, + 'timestamp_stream': 959.2344993501902, + 'transform': [array([-60.93757248, 97.47464752, 0.11198173]), + array([5.27858829e+00, 1.72042465e+02, 2.11836491e-03])]} +{'AngularVelocity': array([-0.03547916, 0.03539575, -1.93684435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.884974956512451, + 'FR_Wheel_Angle': 9.154205322265625, + 'Location': array([-6.37863350e+01, 9.57342300e+01, 1.70852663e-03]), + 'Rotation': array([ 7.34928297e-03, -2.49084854e+01, -2.10571266e-03]), + 'Velocity': array([-4.19830322e-01, 1.52382940e-01, 5.72395329e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5725.37646484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4894.43554688, 16709.68554688, 125.42240906]), + 'frame': 28241, + 'frame_number': 28241, + 'framesequence': 113703, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4223090410232544, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.26729125157, + 'timestamp_carla': 959266, + 'timestamp_device': 1829870, + 'timestamp_stream': 959.26729125157, + 'transform': [array([-60.91360092, 97.45326996, 0.11195663]), + array([5.27905273e+00, 1.72172455e+02, 2.33127200e-03])]} +{'AngularVelocity': array([ 0.00060685, 0.00329157, -0.39293531]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.398539066314697, + 'FR_Wheel_Angle': 7.998687267303467, + 'Location': array([-6.38580017e+01, 9.57618179e+01, 1.72508240e-03]), + 'Rotation': array([ 5.58026414e-03, -2.51172295e+01, -8.54492188e-04]), + 'Velocity': array([-4.45063442e-01, 1.66811675e-01, 9.93156427e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3399.4111328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5231.96630859, 14406.84570312, 125.36333466]), + 'frame': 28242, + 'frame_number': 28242, + 'framesequence': 113707, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42122867703437805, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.3012694492936, + 'timestamp_carla': 959300, + 'timestamp_device': 1829903, + 'timestamp_stream': 959.3012694492936, + 'transform': [array([-60.88805389, 97.43122101, 0.11188664]), + array([5.27914190e+00, 1.72309769e+02, 2.63308082e-03])]} +{'AngularVelocity': array([-0.00197792, -0.0136555 , -0.02151211]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.802678108215332, + 'FR_Wheel_Angle': 8.312504768371582, + 'Location': array([-6.39281464e+01, 9.57893219e+01, 1.71558373e-03]), + 'Rotation': array([ 7.54735852e-03, -2.53175163e+01, -7.32421933e-04]), + 'Velocity': array([-4.09853280e-01, 1.54146284e-01, 1.31177905e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3391.012939453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5241.28320312, 14398.33105469, 125.37630463]), + 'frame': 28243, + 'frame_number': 28243, + 'framesequence': 113711, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4193609654903412, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.3350998498499, + 'timestamp_carla': 959334, + 'timestamp_device': 1829936, + 'timestamp_stream': 959.3350998498499, + 'transform': [array([-60.86389542, 97.41015625, 0.11171352]), + array([5.27838373e+00, 1.72439697e+02, 3.28505714e-03])]} +{'AngularVelocity': array([ 0.00070149, -0.01509396, 0.02997215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.698779582977295, + 'FR_Wheel_Angle': 8.313511848449707, + 'Location': array([-6.39955711e+01, 9.58160172e+01, 1.70112611e-03]), + 'Rotation': array([ 8.20988696e-03, -2.55118828e+01, -8.54492013e-04]), + 'Velocity': array([-3.86721194e-01, 1.47797018e-01, -4.15229806e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3398.43994140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5248.88574219, 14405.5078125 , 125.39409637]), + 'frame': 28244, + 'frame_number': 28244, + 'framesequence': 113715, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4187200665473938, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.3688665516675, + 'timestamp_carla': 959368, + 'timestamp_device': 1829970, + 'timestamp_stream': 959.3688665516675, + 'transform': [array([-60.8393898 , 97.38930511, 0.1116111 ]), + array([5.27831507e+00, 1.72570679e+02, 3.71732516e-03])]} +{'AngularVelocity': array([ 0.01706177, -0.02290039, -1.63633311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.696726322174072, + 'FR_Wheel_Angle': 8.314462661743164, + 'Location': array([-6.40847397e+01, 9.58516693e+01, 1.71482086e-03]), + 'Rotation': array([ 3.41509446e-03, -2.57714043e+01, 5.64729096e-04]), + 'Velocity': array([-4.74440157e-01, 1.84036955e-01, 1.93386077e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3406.492431640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5255.98291016, 14413.27539062, 125.43362427]), + 'frame': 28245, + 'frame_number': 28245, + 'framesequence': 113719, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4194525182247162, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.401070151478, + 'timestamp_carla': 959400, + 'timestamp_device': 1830003, + 'timestamp_stream': 959.401070151478, + 'transform': [array([-60.81647491, 97.36945343, 0.11161632]), + array([5.27893019e+00, 1.72693695e+02, 3.81301041e-03])]} +{'AngularVelocity': array([ 0.01933012, -0.04064717, -0.9934293 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.703527450561523, + 'FR_Wheel_Angle': 8.322793006896973, + 'Location': array([-6.41710892e+01, 9.58865814e+01, 1.70040131e-03]), + 'Rotation': array([ 8.11426435e-03, -2.60227146e+01, -8.23974493e-04]), + 'Velocity': array([-4.07068938e-01, 1.61502585e-01, -1.39913551e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3414.61474609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5263.16162109, 14421.12988281, 125.45973969]), + 'frame': 28246, + 'frame_number': 28246, + 'framesequence': 113722, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.4336299523711, + 'timestamp_carla': 959432, + 'timestamp_device': 1830028, + 'timestamp_stream': 959.4336299523711, + 'transform': [array([-60.79423523, 97.34999847, 0.1116415 ]), + array([5.27953768e+00, 1.72813293e+02, 3.79240932e-03])]} +{'AngularVelocity': array([-0.00951473, 0.05132489, -1.67687702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.696288108825684, + 'FR_Wheel_Angle': 8.313332557678223, + 'Location': array([-6.42406769e+01, 9.59151077e+01, 1.71096798e-03]), + 'Rotation': array([ 5.23192482e-03, -2.62387791e+01, 2.12584200e-04]), + 'Velocity': array([-4.73961830e-01, 1.83988526e-01, -4.40645206e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5764.91796875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4972.01269531, 16752.11328125, 125.62174225]), + 'frame': 28247, + 'frame_number': 28247, + 'framesequence': 113727, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4201849699020386, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.4670078493655, + 'timestamp_carla': 959466, + 'timestamp_device': 1830070, + 'timestamp_stream': 959.4670078493655, + 'transform': [array([-60.76885605, 97.32897949, 0.11173175]), + array([5.27962685e+00, 1.72947495e+02, 3.40153789e-03])]} +{'AngularVelocity': array([ 1.43685762e-03, 3.54547822e-03, -2.20421243e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.56927490234375, + 'FR_Wheel_Angle': 7.148162364959717, + 'Location': array([-6.43160019e+01, 9.59463654e+01, 1.73377991e-03]), + 'Rotation': array([ 4.81528323e-03, -2.64680004e+01, 1.90599327e-04]), + 'Velocity': array([-4.79516894e-01, 1.90643743e-01, 2.99830426e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3454.586181640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5273.4765625 , 14460.28808594, 125.4671936 ]), + 'frame': 28248, + 'frame_number': 28248, + 'framesequence': 113731, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4198187291622162, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.4996334500611, + 'timestamp_carla': 959498, + 'timestamp_device': 1830103, + 'timestamp_stream': 959.4996334500611, + 'transform': [array([-60.7444191 , 97.30752563, 0.11218593]), + array([5.28088331e+00, 1.73078308e+02, 1.62466348e-03])]} +{'AngularVelocity': array([-0.00764926, -0.01609823, -1.49308336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.467473268508911, + 'FR_Wheel_Angle': 3.10904598236084, + 'Location': array([-6.44118423e+01, 9.59889145e+01, 1.71092979e-03]), + 'Rotation': array([ 6.61845272e-03, -2.66704845e+01, -4.08935500e-03]), + 'Velocity': array([-4.53353256e-01, 2.11614057e-01, -1.27792358e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3445.97998046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5283.06835938, 14451.52148438, 125.44284058]), + 'frame': 28249, + 'frame_number': 28249, + 'framesequence': 113734, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.533008351922, + 'timestamp_carla': 959532, + 'timestamp_device': 1830128, + 'timestamp_stream': 959.533008351922, + 'transform': [array([-60.71888351, 97.28562927, 0.11227032]), + array([5.28170967e+00, 1.73214386e+02, 1.33670855e-03])]} +{'AngularVelocity': array([-0.00642284, 0.01617771, -1.7268517 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.574633598327637, + 'FR_Wheel_Angle': 4.353869438171387, + 'Location': array([-6.44826813e+01, 9.60217133e+01, 1.70158385e-03]), + 'Rotation': array([ 9.04317014e-03, -2.67738781e+01, -1.00707996e-03]), + 'Velocity': array([-4.19691503e-01, 1.86874792e-01, 2.29721059e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3446.741943359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5291.31884766, 14451.93945312, 125.33611298]), + 'frame': 28250, + 'frame_number': 28250, + 'framesequence': 113738, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.5660493522882, + 'timestamp_carla': 959565, + 'timestamp_device': 1830161, + 'timestamp_stream': 959.5660493522882, + 'transform': [array([-60.69267273, 97.26386261, 0.11221951]), + array([5.28164148e+00, 1.73352936e+02, 1.54251454e-03])]} +{'AngularVelocity': array([ 0.00906024, 0.04618744, -0.39996251]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.969813346862793, + 'FR_Wheel_Angle': 4.333040714263916, + 'Location': array([-6.45573425e+01, 9.60562668e+01, 1.69486995e-03]), + 'Rotation': array([ 6.74139615e-03, -2.68694592e+01, -5.18798770e-04]), + 'Velocity': array([-4.50959951e-01, 2.05067441e-01, -2.93989171e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3455.490478515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5298.9453125 , 14460.28320312, 125.31784058]), + 'frame': 28251, + 'frame_number': 28251, + 'framesequence': 113742, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.5992709510028, + 'timestamp_carla': 959598, + 'timestamp_device': 1830195, + 'timestamp_stream': 959.5992709510028, + 'transform': [array([-60.66682434, 97.24234009, 0.11214924]), + array([5.28179884e+00, 1.73489670e+02, 1.85067498e-03])]} +{'AngularVelocity': array([-0.00938033, -0.02538492, -1.81651258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9398953914642334, + 'FR_Wheel_Angle': 4.17130184173584, + 'Location': array([-6.46253586e+01, 9.60879211e+01, 1.69799803e-03]), + 'Rotation': array([ 7.65664177e-03, -2.69805126e+01, -5.18798886e-04]), + 'Velocity': array([-4.09670025e-01, 1.87400848e-01, 1.72014232e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3464.399169921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5306.73730469, 14468.80957031, 125.33035278]), + 'frame': 28252, + 'frame_number': 28252, + 'framesequence': 113746, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.6318552494049, + 'timestamp_carla': 959631, + 'timestamp_device': 1830228, + 'timestamp_stream': 959.6318552494049, + 'transform': [array([-60.64176559, 97.22154236, 0.11210006]), + array([5.28183270e+00, 1.73621933e+02, 2.07756832e-03])]} +{'AngularVelocity': array([ 0.00581349, 0.01412094, -1.66641128]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.99948787689209, + 'FR_Wheel_Angle': 4.162312984466553, + 'Location': array([-6.46916428e+01, 9.61188354e+01, 1.71710970e-03]), + 'Rotation': array([ 8.18939600e-03, -2.70789642e+01, -2.13623076e-04]), + 'Velocity': array([-0.40593463, 0.18577571, 0.00042192]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5765.57421875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5054.54833984, 16754.796875 , 125.42255402]), + 'frame': 28253, + 'frame_number': 28253, + 'framesequence': 113750, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.6646726503968, + 'timestamp_carla': 959663, + 'timestamp_device': 1830261, + 'timestamp_stream': 959.6646726503968, + 'transform': [array([-60.61703873, 97.20113373, 0.11192569]), + array([5.28072643e+00, 1.73752029e+02, 2.69490178e-03])]} +{'AngularVelocity': array([-0.00218556, -0.01569849, -1.80451584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.0041375160217285, + 'FR_Wheel_Angle': 4.165048599243164, + 'Location': array([-6.47566757e+01, 9.61492691e+01, 1.69567100e-03]), + 'Rotation': array([ 8.62652808e-03, -2.71726856e+01, -4.57763759e-04]), + 'Velocity': array([-0.36863303, 0.17034645, -0.00042496]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3506.3876953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5319.25195312, 14509.83203125, 125.36386871]), + 'frame': 28254, + 'frame_number': 28254, + 'framesequence': 113754, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.6969670504332, + 'timestamp_carla': 959696, + 'timestamp_device': 1830295, + 'timestamp_stream': 959.6969670504332, + 'transform': [array([-60.59144211, 97.18087006, 0.11188659]), + array([5.28106785e+00, 1.73885452e+02, 2.91424012e-03])]} +{'AngularVelocity': array([-0.00185533, 0.0015976 , -0.55629426]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.00004243850708, + 'FR_Wheel_Angle': 4.161016941070557, + 'Location': array([-6.48236618e+01, 9.61807785e+01, 1.72645564e-03]), + 'Rotation': array([ 5.00652846e-03, -2.72643604e+01, 1.06225089e-04]), + 'Velocity': array([-4.27668571e-01, 1.97669029e-01, -2.25830081e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3498.216064453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5328.53759766, 14501.34570312, 125.40198517]), + 'frame': 28255, + 'frame_number': 28255, + 'framesequence': 113758, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.7297702506185, + 'timestamp_carla': 959728, + 'timestamp_device': 1830328, + 'timestamp_stream': 959.7297702506185, + 'transform': [array([-60.56636047, 97.15981293, 0.11220615]), + array([5.28246784e+00, 1.74017426e+02, 1.70676515e-03])]} +{'AngularVelocity': array([-0.002177 , 0.00828076, -0.31443644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.003019332885742, + 'FR_Wheel_Angle': 4.163580417633057, + 'Location': array([-6.48910217e+01, 9.62127151e+01, 1.72309869e-03]), + 'Rotation': array([ 7.63615128e-03, -2.73695526e+01, -2.13622872e-04]), + 'Velocity': array([-3.98341238e-01, 1.84981406e-01, 3.89237393e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3499.14453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5337.01269531, 14501.93652344, 125.41532898]), + 'frame': 28256, + 'frame_number': 28256, + 'framesequence': 113762, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.7618334516883, + 'timestamp_carla': 959760, + 'timestamp_device': 1830361, + 'timestamp_stream': 959.7618334516883, + 'transform': [array([-60.5416832 , 97.13858032, 0.11294605]), + array([ 5.28609467e+00, 1.74147781e+02, -1.01242564e-03])]} +{'AngularVelocity': array([ 0.02194039, 0.05847383, -0.12738644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.985435724258423, + 'FR_Wheel_Angle': 3.5208890438079834, + 'Location': array([-6.49572067e+01, 9.62441559e+01, 1.71253202e-03]), + 'Rotation': array([ 6.07886817e-03, -2.74739571e+01, 1.65051359e-04]), + 'Velocity': array([-4.41888571e-01, 2.06126139e-01, -2.28462217e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3507.961181640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5344.61376953, 14510.25292969, 125.34103394]), + 'frame': 28257, + 'frame_number': 28257, + 'framesequence': 113766, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.7950396500528, + 'timestamp_carla': 959794, + 'timestamp_device': 1830395, + 'timestamp_stream': 959.7950396500528, + 'transform': [array([-60.51231384, 97.1164856 , 0.11277126]), + array([ 5.28634071e+00, 1.74298920e+02, -2.76544888e-04])]} +{'AngularVelocity': array([-0.0086847 , -0.03121212, 0.15318233]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.7464734315872192, + 'FR_Wheel_Angle': -1.353799819946289, + 'Location': array([-6.50276871e+01, 9.62798386e+01, 1.71913148e-03]), + 'Rotation': array([ 6.17449079e-03, -2.75139332e+01, -3.50952148e-03]), + 'Velocity': array([-4.01597142e-01, 2.16185406e-01, -1.02930069e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3516.781982421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5352.16894531, 14518.52050781, 125.17256927]), + 'frame': 28258, + 'frame_number': 28258, + 'framesequence': 113770, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.828206948936, + 'timestamp_carla': 959827, + 'timestamp_device': 1830428, + 'timestamp_stream': 959.828206948936, + 'transform': [array([-60.48529816, 97.0951767 , 0.1125634 ]), + array([5.28474951e+00, 1.74439041e+02, 4.10140667e-04])]} +{'AngularVelocity': array([-5.13488007, -0.10395916, -0.91118217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7306854128837585, + 'FR_Wheel_Angle': 0.3549491763114929, + 'Location': array([-6.50911179e+01, 9.63122177e+01, 4.01535013e-04]), + 'Rotation': array([ 0.06694268, -27.5299263 , 0.11063501]), + 'Velocity': array([-0.34473029, 0.1882644 , -0.04282039]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4676.85888671875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5246.66259766, 15672.48242188, 125.21101379]), + 'frame': 28259, + 'frame_number': 28259, + 'framesequence': 113774, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.8625377491117, + 'timestamp_carla': 959861, + 'timestamp_device': 1830461, + 'timestamp_stream': 959.8625377491117, + 'transform': [array([-60.45837784, 97.07376099, 0.11234757]), + array([5.28317165e+00, 1.74578827e+02, 1.10330700e-03])]} +{'AngularVelocity': array([ 1.49669111, 1.04769886, -0.09953522]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.11691639572381973, + 'FR_Wheel_Angle': 0.10169236361980438, + 'Location': array([-6.51556702e+01, 9.63679047e+01, 3.28186490e-02]), + 'Rotation': array([ -1.13103831, -27.61638451, -1.73352051]), + 'Velocity': array([-0.41371849, 0.22998261, 0.0693265 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3556.78955078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5367.07861328, 14557.50195312, 125.25967407]), + 'frame': 28260, + 'frame_number': 28260, + 'framesequence': 113779, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.9006660506129, + 'timestamp_carla': 959899, + 'timestamp_device': 1830503, + 'timestamp_stream': 959.9006660506129, + 'transform': [array([-60.42874908, 97.0503006 , 0.11216911]), + array([5.28244066e+00, 1.74732635e+02, 1.61086849e-03])]} +{'AngularVelocity': array([ 1.4627775 , -0.00641207, 0.24045365]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.08138560503721237, + 'FR_Wheel_Angle': -0.02162083238363266, + 'Location': array([-6.52246933e+01, 9.64045105e+01, 4.00388800e-02]), + 'Rotation': array([ -1.32394326, -27.62956619, -2.01098609]), + 'Velocity': array([-0.38212639, 0.18702413, 0.01696873]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3548.151611328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5377.02929688, 14548.40722656, 125.30258179]), + 'frame': 28261, + 'frame_number': 28261, + 'framesequence': 113783, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.9340068511665, + 'timestamp_carla': 959933, + 'timestamp_device': 1830536, + 'timestamp_stream': 959.9340068511665, + 'transform': [array([-60.40306473, 97.02986145, 0.11215442]), + array([5.28112936e+00, 1.74865448e+02, 1.61761732e-03])]} +{'AngularVelocity': array([ 0.5487743 , -0.0698308 , 0.19496427]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02414744906127453, + 'FR_Wheel_Angle': -0.008898655883967876, + 'Location': array([-6.52934723e+01, 9.64404755e+01, 4.20187861e-02]), + 'Rotation': array([ -1.40658176, -27.65330887, -2.15679955]), + 'Velocity': array([-0.40952826, 0.20788595, 0.00388301]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3543.906005859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5387.45214844, 14543.609375 , 125.33036804]), + 'frame': 28262, + 'frame_number': 28262, + 'framesequence': 113787, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 959.9673536494374, + 'timestamp_carla': 959966, + 'timestamp_device': 1830570, + 'timestamp_stream': 959.9673536494374, + 'transform': [array([-60.37686539, 97.00939941, 0.11228306]), + array([5.28198290e+00, 1.75000961e+02, 1.22693321e-03])]} +{'AngularVelocity': array([ 3.39164883e-01, -4.81181458e-04, -9.36982810e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.00889655388891697, + 'FR_Wheel_Angle': -0.008892529644072056, + 'Location': array([-6.53584366e+01, 9.64742661e+01, 4.25475761e-02]), + 'Rotation': array([ -1.43554854, -27.65673256, -2.21362352]), + 'Velocity': array([-0.40258586, 0.20961504, 0.0008535 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3556.7734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5394.95214844, 14555.88867188, 125.33460999]), + 'frame': 28263, + 'frame_number': 28263, + 'framesequence': 113791, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.0030141510069, + 'timestamp_carla': 960002, + 'timestamp_device': 1830603, + 'timestamp_stream': 960.0030141510069, + 'transform': [array([-60.34751892, 96.98724365, 0.11224888]), + array([5.28161430e+00, 1.75151489e+02, 1.28843857e-03])]} +{'AngularVelocity': array([ 1.07157528, -0.04969379, -1.31098628]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.008893285878002644, + 'FR_Wheel_Angle': -0.008896369487047195, + 'Location': array([-6.54303436e+01, 9.65143814e+01, 3.93649377e-02]), + 'Rotation': array([ -1.33047295, -27.73616409, -2.06033278]), + 'Velocity': array([-0.4296484 , 0.22370556, 0.0031818 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3564.538330078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5403.13769531, 14563.09179688, 125.31130981]), + 'frame': 28264, + 'frame_number': 28264, + 'framesequence': 113795, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.0353702493012, + 'timestamp_carla': 960034, + 'timestamp_device': 1830636, + 'timestamp_stream': 960.0353702493012, + 'transform': [array([-60.32155609, 96.9675293 , 0.11210323]), + array([5.28024149e+00, 1.75284622e+02, 1.83756801e-03])]} +{'AngularVelocity': array([ 0.5421446 , 0.05481853, -0.17203498]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.008900072425603867, + 'FR_Wheel_Angle': -0.008895564824342728, + 'Location': array([-6.55001373e+01, 9.65512543e+01, 4.11546044e-02]), + 'Rotation': array([ -1.39785278, -27.74593163, -2.17245483]), + 'Velocity': array([-0.40399069, 0.20872642, 0.00783764]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3567.848876953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5412.69921875, 14565.82421875, 125.31455231]), + 'frame': 28265, + 'frame_number': 28265, + 'framesequence': 113799, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.068954449147, + 'timestamp_carla': 960067, + 'timestamp_device': 1830670, + 'timestamp_stream': 960.068954449147, + 'transform': [array([-60.29656219, 96.94793701, 0.11205215]), + array([5.28012514e+00, 1.75413712e+02, 2.05651578e-03])]} +{'AngularVelocity': array([0.15143366, 0.01905927, 0.55953908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.008903611451387405, + 'FR_Wheel_Angle': -0.19930166006088257, + 'Location': array([-6.55630264e+01, 9.65841751e+01, 4.21994850e-02]), + 'Rotation': array([ -1.42892325, -27.73928261, -2.21929932]), + 'Velocity': array([-0.37738195, 0.19690596, 0.00303002]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3586.703369140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5419.86132812, 14584.07421875, 125.3523407 ]), + 'frame': 28266, + 'frame_number': 28266, + 'framesequence': 113803, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.1022981517017, + 'timestamp_carla': 960101, + 'timestamp_device': 1830703, + 'timestamp_stream': 960.1022981517017, + 'transform': [array([-60.27115631, 96.92861938, 0.11197082]), + array([5.27978373e+00, 1.75544022e+02, 2.37943721e-03])]} +{'AngularVelocity': array([ 0.08988446, -0.01635935, 0.63047099]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.737161159515381, + 'FR_Wheel_Angle': -5.49941349029541, + 'Location': array([-6.56259537e+01, 9.66187973e+01, 4.25986201e-02]), + 'Rotation': array([ -1.4438746 , -27.69166756, -2.24295068]), + 'Velocity': array([-0.38746256, 0.228633 , 0.0009518 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3603.692626953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5427.01611328, 14600.41699219, 125.36703491]), + 'frame': 28267, + 'frame_number': 28267, + 'framesequence': 113807, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.1354399509728, + 'timestamp_carla': 960134, + 'timestamp_device': 1830736, + 'timestamp_stream': 960.1354399509728, + 'transform': [array([-60.24549484, 96.90943146, 0.11190879]), + array([5.27951050e+00, 1.75675034e+02, 2.62603560e-03])]} +{'AngularVelocity': array([ 0.11795095, -0.02046811, -0.55059743]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.2700893878936768, + 'FR_Wheel_Angle': -3.434314012527466, + 'Location': array([-6.56929626e+01, 9.66571045e+01, 4.27387320e-02]), + 'Rotation': array([ -1.45146978, -27.59810448, -2.24948168]), + 'Velocity': array([-0.39981788, 0.22730865, 0.00058497]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3612.936767578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5434.91259766, 14609.05761719, 125.38819122]), + 'frame': 28268, + 'frame_number': 28268, + 'framesequence': 113811, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.1675589494407, + 'timestamp_carla': 960166, + 'timestamp_device': 1830770, + 'timestamp_stream': 960.1675589494407, + 'transform': [array([-60.21868896, 96.8897934 , 0.11203476]), + array([5.27959919e+00, 1.75810669e+02, 2.13965611e-03])]} +{'AngularVelocity': array([0.04108732, 0.04470972, 0.5441131 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.396124362945557, + 'FR_Wheel_Angle': -3.9941794872283936, + 'Location': array([-6.57584915e+01, 9.66941757e+01, 4.27486114e-02]), + 'Rotation': array([ -1.45126486, -27.49281502, -2.25064111]), + 'Velocity': array([-3.96156788e-01, 2.29601219e-01, -9.39464517e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3609.619384765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5443.83886719, 14605.17089844, 125.40406036]), + 'frame': 28269, + 'frame_number': 28269, + 'framesequence': 113815, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.2019142508507, + 'timestamp_carla': 960200, + 'timestamp_device': 1830803, + 'timestamp_stream': 960.2019142508507, + 'transform': [array([-60.19100571, 96.8691864 , 0.11197956]), + array([5.27944899e+00, 1.75951019e+02, 2.30378285e-03])]} +{'AngularVelocity': array([0.03234912, 0.04909641, 0.68502092]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.226548671722412, + 'FR_Wheel_Angle': -3.988764524459839, + 'Location': array([-6.58199081e+01, 9.67285156e+01, 4.27549444e-02]), + 'Rotation': array([ -1.44985104, -27.3960743 , -2.24981713]), + 'Velocity': array([-3.73954713e-01, 2.11758882e-01, -8.69846335e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3617.610595703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5452.21289062, 14612.54101562, 125.37477112]), + 'frame': 28270, + 'frame_number': 28270, + 'framesequence': 113819, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4189581274986267, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.2389470525086, + 'timestamp_carla': 960237, + 'timestamp_device': 1830836, + 'timestamp_stream': 960.2389470525086, + 'transform': [array([-60.16097641, 96.84559631, 0.11251839]), + array([5.28283691e+00, 1.76105103e+02, 2.66415125e-04])]} +{'AngularVelocity': array([-0.02988461, -0.02247429, 0.43510699]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.183629512786865, + 'FR_Wheel_Angle': -4.020297527313232, + 'Location': array([-6.58941116e+01, 9.67702255e+01, 4.27664667e-02]), + 'Rotation': array([ -1.45088923, -27.30586433, -2.25189233]), + 'Velocity': array([-3.61910850e-01, 2.06398964e-01, -2.05135348e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3625.9697265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5460.91503906, 14620.19824219, 125.38430786]), + 'frame': 28271, + 'frame_number': 28271, + 'framesequence': 113823, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4063417613506317, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.2742259502411, + 'timestamp_carla': 960273, + 'timestamp_device': 1830870, + 'timestamp_stream': 960.2742259502411, + 'transform': [array([-60.1313324 , 96.82337952, 0.11239086]), + array([5.28140259e+00, 1.76255493e+02, 6.44239190e-04])]} +{'AngularVelocity': array([0.06669369, 0.03892378, 0.27407646]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.184123516082764, + 'FR_Wheel_Angle': -4.021729946136475, + 'Location': array([-6.59566116e+01, 9.68054504e+01, 4.27399538e-02]), + 'Rotation': array([ -1.45260358, -27.24760437, -2.2577517 ]), + 'Velocity': array([-0.36230811, 0.20754789, 0.00069671]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3635.34423828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5470.55322266, 14628.6796875 , 125.25028229]), + 'frame': 28272, + 'frame_number': 28272, + 'framesequence': 113828, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.38407546281814575, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.3078342489898, + 'timestamp_carla': 960306, + 'timestamp_device': 1830911, + 'timestamp_stream': 960.3078342489898, + 'transform': [array([-60.10477066, 96.80273438, 0.11230167]), + array([5.28005695e+00, 1.76390564e+02, 9.32328054e-04])]} +{'AngularVelocity': array([-0.02884423, 0.04894206, 1.09523296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.184169769287109, + 'FR_Wheel_Angle': -4.0170745849609375, + 'Location': array([-6.60168839e+01, 9.68389359e+01, 4.27776426e-02]), + 'Rotation': array([ -1.45257628, -27.15126228, -2.25430322]), + 'Velocity': array([-3.80301893e-01, 2.15088710e-01, -1.63555145e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 11611.708984375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4959.64794922, 22587.2109375 , 125.36473846]), + 'frame': 28273, + 'frame_number': 28273, + 'framesequence': 113832, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3592455983161926, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.3405812494457, + 'timestamp_carla': 960339, + 'timestamp_device': 1830944, + 'timestamp_stream': 960.3405812494457, + 'transform': [array([-60.08016586, 96.78305817, 0.11208408]), + array([5.27774143e+00, 1.76515305e+02, 1.65943394e-03])]} +{'AngularVelocity': array([-0.02831964, 0.00710842, 1.19564772]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.18068790435791, + 'FR_Wheel_Angle': -4.014743328094482, + 'Location': array([-6.60866089e+01, 9.68773575e+01, 4.28002626e-02]), + 'Rotation': array([ -1.4550761 , -27.03260422, -2.25036573]), + 'Velocity': array([-4.18447375e-01, 2.36143798e-01, 2.60801316e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3666.89404296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5487.58642578, 14658.53710938, 125.29670715]), + 'frame': 28274, + 'frame_number': 28274, + 'framesequence': 113835, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33811458945274353, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.3746969513595, + 'timestamp_carla': 960373, + 'timestamp_device': 1830969, + 'timestamp_stream': 960.3746969513595, + 'transform': [array([-60.0564537 , 96.76312256, 0.111819 ]), + array([5.27470875e+00, 1.76635437e+02, 2.44120439e-03])]} +{'AngularVelocity': array([-8.03186819e-02, 5.76190476e-04, 1.45343351e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.177408695220947, + 'FR_Wheel_Angle': -4.453810214996338, + 'Location': array([-6.61603851e+01, 9.69180679e+01, 4.27703559e-02]), + 'Rotation': array([ -1.4529109 , -26.91779518, -2.25024366]), + 'Velocity': array([-4.24519837e-01, 2.39653155e-01, -1.76830290e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3660.56689453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5496.34912109, 14651.37792969, 125.34640503]), + 'frame': 28275, + 'frame_number': 28275, + 'framesequence': 113840, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3345072865486145, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.4093633517623, + 'timestamp_carla': 960408, + 'timestamp_device': 1831011, + 'timestamp_stream': 960.4093633517623, + 'transform': [array([-60.03010178, 96.74131012, 0.11181954]), + array([5.27441502e+00, 1.76768082e+02, 2.38666427e-03])]} +{'AngularVelocity': array([-0.08609273, -0.05870469, 1.48803151]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.052030563354492, + 'FR_Wheel_Angle': -8.970505714416504, + 'Location': array([-6.62275085e+01, 9.69566269e+01, 4.27625366e-02]), + 'Rotation': array([ -1.44976902, -26.74189377, -2.25384521]), + 'Velocity': array([-3.74131054e-01, 2.30990142e-01, 9.49478126e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3668.208740234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5503.95751953, 14658.07421875, 125.399086 ]), + 'frame': 28276, + 'frame_number': 28276, + 'framesequence': 113844, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.34373608231544495, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.442452352494, + 'timestamp_carla': 960441, + 'timestamp_device': 1831044, + 'timestamp_stream': 960.442452352494, + 'transform': [array([-60.00471497, 96.71969604, 0.11205444]), + array([5.27584267e+00, 1.76896454e+02, 1.59048813e-03])]} +{'AngularVelocity': array([-0.02097326, -0.01569646, 1.0635072 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.888735771179199, + 'FR_Wheel_Angle': -7.70326042175293, + 'Location': array([-6.62912216e+01, 9.69940872e+01, 4.27573845e-02]), + 'Rotation': array([ -1.45016515, -26.53248596, -2.25003099]), + 'Velocity': array([-3.70682627e-01, 2.20592394e-01, -1.15776056e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3676.667236328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5512.38134766, 14665.484375 , 125.39584351]), + 'frame': 28277, + 'frame_number': 28277, + 'framesequence': 113848, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3571581244468689, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.4765767492354, + 'timestamp_carla': 960475, + 'timestamp_device': 1831078, + 'timestamp_stream': 960.4765767492354, + 'transform': [array([-59.97927475, 96.69769287, 0.11222217]), + array([5.27758455e+00, 1.77025742e+02, 1.06222183e-03])]} +{'AngularVelocity': array([0.06698287, 0.03320539, 1.1328609 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.280986785888672, + 'FR_Wheel_Angle': -7.562337875366211, + 'Location': array([-6.63680191e+01, 9.70385513e+01, 4.27516252e-02]), + 'Rotation': array([ -1.44890845, -26.28767014, -2.24948168]), + 'Velocity': array([-3.71343672e-01, 2.25069493e-01, -2.29835514e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3684.96826171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5520.58203125, 14672.70117188, 125.34503937]), + 'frame': 28278, + 'frame_number': 28278, + 'framesequence': 113852, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3698843717575073, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.5082948505878, + 'timestamp_carla': 960507, + 'timestamp_device': 1831111, + 'timestamp_stream': 960.5082948505878, + 'transform': [array([-59.95248413, 96.67625427, 0.11225276]), + array([5.27795315e+00, 1.77160461e+02, 1.03482546e-03])]} +{'AngularVelocity': array([-0.24003604, -0.06865399, 1.81416178]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.366559982299805, + 'FR_Wheel_Angle': -7.686432361602783, + 'Location': array([-6.64325790e+01, 9.70755386e+01, 4.27359492e-02]), + 'Rotation': array([ -1.44634712, -26.08579636, -2.24548364]), + 'Velocity': array([-3.60153735e-01, 2.12141037e-01, -2.01797477e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16840.939453125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-4846.68017578, 27809.8203125 , 125.55249786]), + 'frame': 28279, + 'frame_number': 28279, + 'framesequence': 113855, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.37301552295684814, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.5407130494714, + 'timestamp_carla': 960539, + 'timestamp_device': 1831136, + 'timestamp_stream': 960.5407130494714, + 'transform': [array([-59.92509079, 96.6546936 , 0.11211937]), + array([5.27767992e+00, 1.77297852e+02, 1.58396841e-03])]} +{'AngularVelocity': array([0.00736417, 0.03633407, 1.64453137]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.349893569946289, + 'FR_Wheel_Angle': -7.7298688888549805, + 'Location': array([-6.64941101e+01, 9.71106720e+01, 4.27383892e-02]), + 'Rotation': array([ -1.44634712, -25.89710426, -2.24789429]), + 'Velocity': array([-3.86665374e-01, 2.26715729e-01, -1.25198363e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3720.493408203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5536.64550781, 14705.99902344, 125.30938721]), + 'frame': 28280, + 'frame_number': 28280, + 'framesequence': 113859, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36902374029159546, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.5745271518826, + 'timestamp_carla': 960573, + 'timestamp_device': 1831169, + 'timestamp_stream': 960.5745271518826, + 'transform': [array([-59.89720154, 96.63272858, 0.11191234]), + array([5.27703810e+00, 1.77437576e+02, 2.35180208e-03])]} +{'AngularVelocity': array([-0.11475641, -0.02478433, 1.29528522]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.344367027282715, + 'FR_Wheel_Angle': -7.725369453430176, + 'Location': array([-6.65667343e+01, 9.71519699e+01, 4.27697450e-02]), + 'Rotation': array([ -1.45082772, -25.68424606, -2.25170922]), + 'Velocity': array([-3.74881953e-01, 2.16092050e-01, 9.51004040e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3711.00390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5546.43261719, 14695.44726562, 125.34498596]), + 'frame': 28281, + 'frame_number': 28281, + 'framesequence': 113864, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3623584806919098, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.6084617488086, + 'timestamp_carla': 960607, + 'timestamp_device': 1831211, + 'timestamp_stream': 960.6084617488086, + 'transform': [array([-59.87022018, 96.61120605, 0.11176036]), + array([5.27655315e+00, 1.77572800e+02, 2.91416538e-03])]} +{'AngularVelocity': array([0.05157087, 0.03001511, 1.13842785]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.349851608276367, + 'FR_Wheel_Angle': -7.7322306632995605, + 'Location': array([-6.66322784e+01, 9.71888809e+01, 4.27679531e-02]), + 'Rotation': array([ -1.45156538, -25.4935112 , -2.25454736]), + 'Velocity': array([-3.76560360e-01, 2.21502960e-01, -1.28250118e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3720.116943359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5555.50048828, 14703.42773438, 125.39434814]), + 'frame': 28282, + 'frame_number': 28282, + 'framesequence': 113868, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35571157932281494, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.6419808492064, + 'timestamp_carla': 960641, + 'timestamp_device': 1831244, + 'timestamp_stream': 960.6419808492064, + 'transform': [array([-59.84425735, 96.59041595, 0.11160801]), + array([5.27580881e+00, 1.77702545e+02, 3.47665371e-03])]} +{'AngularVelocity': array([0.17478433, 0.05234864, 0.99564558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.339956283569336, + 'FR_Wheel_Angle': -7.7212443351745605, + 'Location': array([-6.66961365e+01, 9.72244186e+01, 4.27843928e-02]), + 'Rotation': array([ -1.45220745, -25.29960251, -2.25326586]), + 'Velocity': array([-4.33949679e-01, 2.51810044e-01, 1.76620480e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3729.02685546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5564.31689453, 14711.18457031, 125.43079376]), + 'frame': 28283, + 'frame_number': 28283, + 'framesequence': 113872, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35358747839927673, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.6744670495391, + 'timestamp_carla': 960673, + 'timestamp_device': 1831278, + 'timestamp_stream': 960.6744670495391, + 'transform': [array([-59.81995773, 96.57074738, 0.11152477]), + array([5.27551508e+00, 1.77823959e+02, 3.82643985e-03])]} +{'AngularVelocity': array([-0.10666884, -0.06855016, 1.65779722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.402597427368164, + 'FR_Wheel_Angle': -12.236319541931152, + 'Location': array([-6.67814865e+01, 9.72717972e+01, 4.27686013e-02]), + 'Rotation': array([ -1.45119655, -25.03391457, -2.25360131]), + 'Velocity': array([-3.95664245e-01, 2.31497899e-01, 2.21147537e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3737.64208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5572.80859375, 14718.65625 , 125.4682312 ]), + 'frame': 28284, + 'frame_number': 28284, + 'framesequence': 113875, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.355821430683136, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.707702152431, + 'timestamp_carla': 960706, + 'timestamp_device': 1831303, + 'timestamp_stream': 960.707702152431, + 'transform': [array([-59.79627228, 96.55120087, 0.11154457]), + array([5.27612257e+00, 1.77942688e+02, 3.80569161e-03])]} +{'AngularVelocity': array([-0.12929715, -0.03267508, 1.77164555]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.600253105163574, + 'FR_Wheel_Angle': -10.673868179321289, + 'Location': array([-6.68629456e+01, 9.73197632e+01, 4.27715406e-02]), + 'Rotation': array([ -1.45192742, -24.64008331, -2.25152612]), + 'Velocity': array([-3.93353343e-01, 2.36492440e-01, 1.47132872e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5204.56396484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5525.39160156, 16183.4140625 , 125.58943176]), + 'frame': 28285, + 'frame_number': 28285, + 'framesequence': 113880, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3590990900993347, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.7433558516204, + 'timestamp_carla': 960742, + 'timestamp_device': 1831344, + 'timestamp_stream': 960.7433558516204, + 'transform': [array([-59.77077103, 96.53079224, 0.11139129]), + array([5.27569246e+00, 1.78069672e+02, 4.32017958e-03])]} +{'AngularVelocity': array([ 0.14131205, -0.01520562, 0.9217298 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.743846893310547, + 'FR_Wheel_Angle': -11.192914009094238, + 'Location': array([-6.69418182e+01, 9.73651657e+01, 4.27745916e-02]), + 'Rotation': array([ -1.45156538, -24.28477097, -2.25064111]), + 'Velocity': array([-3.99679095e-01, 2.45331213e-01, 1.66082376e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3772.127197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5587.97802734, 14750.87695312, 125.49206543]), + 'frame': 28286, + 'frame_number': 28286, + 'framesequence': 113884, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3623584806919098, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.7762329503894, + 'timestamp_carla': 960775, + 'timestamp_device': 1831378, + 'timestamp_stream': 960.7762329503894, + 'transform': [array([-59.74712753, 96.5116806 , 0.11148327]), + array([5.27541924e+00, 1.78186890e+02, 3.94301955e-03])]} +{'AngularVelocity': array([0.07785436, 0.01828578, 1.87282109]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.559760093688965, + 'FR_Wheel_Angle': -11.219184875488281, + 'Location': array([-6.70091782e+01, 9.74034042e+01, 4.27594073e-02]), + 'Rotation': array([ -1.44873083, -23.9695549 , -2.24893212]), + 'Velocity': array([-3.91995877e-01, 2.38571063e-01, 1.00965495e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3763.025390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5597.02734375, 14740.59570312, 125.52326965]), + 'frame': 28287, + 'frame_number': 28287, + 'framesequence': 113888, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36234015226364136, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.8088500499725, + 'timestamp_carla': 960807, + 'timestamp_device': 1831411, + 'timestamp_stream': 960.8088500499725, + 'transform': [array([-59.72343063, 96.49298859, 0.11162364]), + array([5.27633429e+00, 1.78304672e+02, 3.48411198e-03])]} +{'AngularVelocity': array([ 0.14724678, -0.02570094, 0.72781384]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.520806312561035, + 'FR_Wheel_Angle': -11.168580055236816, + 'Location': array([-6.70752792e+01, 9.74405899e+01, 4.27567363e-02]), + 'Rotation': array([ -1.44854641, -23.67240715, -2.24813843]), + 'Velocity': array([-3.85156751e-01, 2.28717163e-01, -4.93812549e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3770.421630859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5604.84130859, 14746.84375 , 125.5005722 ]), + 'frame': 28288, + 'frame_number': 28288, + 'framesequence': 113892, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3608020544052124, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.8430863507092, + 'timestamp_carla': 960842, + 'timestamp_device': 1831444, + 'timestamp_stream': 960.8430863507092, + 'transform': [array([-59.6987114 , 96.47364807, 0.11170379]), + array([5.27691507e+00, 1.78427399e+02, 3.17460485e-03])]} +{'AngularVelocity': array([-0.05461991, -0.05212541, 1.59247994]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.501212120056152, + 'FR_Wheel_Angle': -11.172677993774414, + 'Location': array([-6.71470795e+01, 9.74807663e+01, 4.27682213e-02]), + 'Rotation': array([ -1.45220745, -23.36698914, -2.25360155]), + 'Velocity': array([-4.18144077e-01, 2.39733294e-01, -1.45092010e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3778.4677734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5612.70996094, 14753.76855469, 125.4710083 ]), + 'frame': 28289, + 'frame_number': 28289, + 'framesequence': 113896, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35887935757637024, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.8764710500836, + 'timestamp_carla': 960875, + 'timestamp_device': 1831478, + 'timestamp_stream': 960.8764710500836, + 'transform': [array([-59.67476273, 96.45523071, 0.11156536]), + array([5.27600002e+00, 1.78545654e+02, 3.66836553e-03])]} +{'AngularVelocity': array([0.00863707, 0.02725521, 2.27662468]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.513846397399902, + 'FR_Wheel_Angle': -11.177509307861328, + 'Location': array([-6.72129211e+01, 9.75169525e+01, 4.27705087e-02]), + 'Rotation': array([ -1.45037007, -23.06895065, -2.25155663]), + 'Velocity': array([-3.95569652e-01, 2.30213061e-01, 1.71909327e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3786.890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5620.94384766, 14761.01269531, 125.44993591]), + 'frame': 28290, + 'frame_number': 28290, + 'framesequence': 113900, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35871458053588867, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.9101664498448, + 'timestamp_carla': 960909, + 'timestamp_device': 1831511, + 'timestamp_stream': 960.9101664498448, + 'transform': [array([-59.6518631 , 96.4369278 , 0.11170898]), + array([5.27663517e+00, 1.78659332e+02, 3.12731182e-03])]} +{'AngularVelocity': array([ 0.52841359, -0.17317902, -0.62494999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.525177001953125, + 'FR_Wheel_Angle': -11.198248863220215, + 'Location': array([-6.72771683e+01, 9.75519028e+01, 4.24962305e-02]), + 'Rotation': array([ -1.45980263, -22.8334446 , -2.22805786]), + 'Velocity': array([-0.36502987, 0.20921166, -0.00280905]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5044.9384765625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5597.16601562, 16017.5234375 , 125.56360626]), + 'frame': 28291, + 'frame_number': 28291, + 'framesequence': 113904, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3597033619880676, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.9445215500891, + 'timestamp_carla': 960943, + 'timestamp_device': 1831544, + 'timestamp_stream': 960.9445215500891, + 'transform': [array([-59.62598419, 96.41770935, 0.11151218]), + array([5.27496862e+00, 1.78786011e+02, 3.75088141e-03])]} +{'AngularVelocity': array([ 0.15394829, -1.86953306, -2.16893339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.5396146774292, + 'FR_Wheel_Angle': -11.300264358520508, + 'Location': array([-6.73241425e+01, 9.75890121e+01, 5.30625656e-02]), + 'Rotation': array([ -0.93725902, -22.92475319, -3.42169261]), + 'Velocity': array([-0.28002909, 0.11860447, 0.08507756]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3827.700439453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5636.00732422, 14799.50976562, 125.44939423]), + 'frame': 28292, + 'frame_number': 28292, + 'framesequence': 113908, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3604358434677124, + 'throttle_input': 0.2222171425819397, + 'timestamp': 960.9767020493746, + 'timestamp_carla': 960975, + 'timestamp_device': 1831578, + 'timestamp_stream': 960.9767020493746, + 'transform': [array([-59.60065842, 96.39902496, 0.11142227]), + array([5.27331543e+00, 1.78909576e+02, 4.00513131e-03])]} +{'AngularVelocity': array([ 3.561795 , -4.43441868, 2.1000464 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.108213424682617, + 'FR_Wheel_Angle': -15.649636268615723, + 'Location': array([-6.73714905e+01, 9.76150665e+01, 6.63464516e-02]), + 'Rotation': array([ -0.4660033 , -22.7598381 , -4.34414816]), + 'Velocity': array([-0.34320879, 0.16605172, 0.08455923]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3818.677001953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5645.00878906, 14789.28125 , 125.49123383]), + 'frame': 28293, + 'frame_number': 28293, + 'framesequence': 113912, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3601611256599426, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.0088844522834, + 'timestamp_carla': 961007, + 'timestamp_device': 1831611, + 'timestamp_stream': 961.0088844522834, + 'transform': [array([-59.57697296, 96.38066101, 0.11153103]), + array([5.27395058e+00, 1.79026199e+02, 3.64788948e-03])]} +{'AngularVelocity': array([ 1.60088122, -1.82323229, 1.8637265 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.829527854919434, + 'FR_Wheel_Angle': -13.934903144836426, + 'Location': array([-6.74289627e+01, 9.76475296e+01, 7.42120519e-02]), + 'Rotation': array([ -0.17303601, -22.39952087, -4.89844036]), + 'Velocity': array([-0.36192158, 0.19751698, 0.03327225]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3820.2958984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5653.54980469, 14789.703125 , 125.51107788]), + 'frame': 28294, + 'frame_number': 28294, + 'framesequence': 113916, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3596118092536926, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.0421371497214, + 'timestamp_carla': 961041, + 'timestamp_device': 1831644, + 'timestamp_stream': 961.0421371497214, + 'transform': [array([-59.55203629, 96.36196899, 0.11145619]), + array([5.27370501e+00, 1.79148300e+02, 3.92250810e-03])]} +{'AngularVelocity': array([ 0.68463802, -0.65224481, 1.73976827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.810279846191406, + 'FR_Wheel_Angle': -14.356892585754395, + 'Location': array([-6.74978714e+01, 9.76860199e+01, 7.70222992e-02]), + 'Rotation': array([ -0.06311095, -22.00236702, -5.13757563]), + 'Velocity': array([-0.38261321, 0.22512989, 0.00994274]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3828.536865234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5661.52539062, 14796.72070312, 125.48819733]), + 'frame': 28295, + 'frame_number': 28295, + 'framesequence': 113920, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3597033619880676, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.0762460492551, + 'timestamp_carla': 961075, + 'timestamp_device': 1831678, + 'timestamp_stream': 961.0762460492551, + 'transform': [array([-59.52845001, 96.34355164, 0.1115329 ]), + array([5.27493429e+00, 1.79264542e+02, 3.69614433e-03])]} +{'AngularVelocity': array([ 0.61462766, -0.62669855, 2.7844274 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.727493286132812, + 'FR_Wheel_Angle': -14.424302101135254, + 'Location': array([-6.75656662e+01, 9.77241669e+01, 7.65092596e-02]), + 'Rotation': array([ -0.07241366, -21.5920887 , -5.12567425]), + 'Velocity': array([-0.39452747, 0.23586151, 0.00551244]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3837.1533203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5669.89501953, 14804.08691406, 125.50679779]), + 'frame': 28296, + 'frame_number': 28296, + 'framesequence': 113924, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.1097245514393, + 'timestamp_carla': 961108, + 'timestamp_device': 1831711, + 'timestamp_stream': 961.1097245514393, + 'transform': [array([-59.50094604, 96.32402039, 0.11147942]), + array([5.27395058e+00, 1.79397552e+02, 3.81284067e-03])]} +{'AngularVelocity': array([ 0.29947439, -0.31602597, 2.74263382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.68873405456543, + 'FR_Wheel_Angle': -14.415035247802734, + 'Location': array([-6.76301270e+01, 9.77597046e+01, 7.72947818e-02]), + 'Rotation': array([ -0.02626891, -21.20305443, -5.21603727]), + 'Velocity': array([-0.38328242, 0.22795522, 0.0048322 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5016.47412109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5662.87792969, 15982.03613281, 125.56546021]), + 'frame': 28297, + 'frame_number': 28297, + 'framesequence': 113928, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.1422579512, + 'timestamp_carla': 961141, + 'timestamp_device': 1831744, + 'timestamp_stream': 961.1422579512, + 'transform': [array([-59.47687912, 96.30445099, 0.11215866]), + array([5.27709961e+00, 1.79516022e+02, 1.30937702e-03])]} +{'AngularVelocity': array([ 0.11163342, -0.06146466, 2.38003159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.677478790283203, + 'FR_Wheel_Angle': -14.393786430358887, + 'Location': array([-6.77087936e+01, 9.78020706e+01, 7.77589157e-02]), + 'Rotation': array([-5.73735870e-03, -2.07217350e+01, -5.25580168e+00]), + 'Velocity': array([-0.43514541, 0.24744181, 0.00136364]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3880.7900390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5686.8125 , 14845.11816406, 125.50126648]), + 'frame': 28298, + 'frame_number': 28298, + 'framesequence': 113932, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.1748726516962, + 'timestamp_carla': 961173, + 'timestamp_device': 1831778, + 'timestamp_stream': 961.1748726516962, + 'transform': [array([-59.44970703, 96.28468323, 0.11214901]), + array([5.27615023e+00, 1.79647629e+02, 1.25448767e-03])]} +{'AngularVelocity': array([ 0.102025 , -0.0546554 , 3.25223517]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.664316177368164, + 'FR_Wheel_Angle': -14.394209861755371, + 'Location': array([-6.77854538e+01, 9.78421097e+01, 7.78556541e-02]), + 'Rotation': array([ 4.50792460e-04, -2.02609196e+01, -5.26883221e+00]), + 'Velocity': array([-4.65704829e-01, 2.60045022e-01, 2.68783566e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3872.599853515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5695.26757812, 14835.51074219, 125.33065033]), + 'frame': 28299, + 'frame_number': 28299, + 'framesequence': 113935, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.2071002498269, + 'timestamp_carla': 961206, + 'timestamp_device': 1831803, + 'timestamp_stream': 961.2071002498269, + 'transform': [array([-59.42245102, 96.26519012, 0.11184959]), + array([5.27377319e+00, 1.79779297e+02, 2.27635494e-03])]} +{'AngularVelocity': array([0.11832432, 0.02963739, 2.30445361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.67241096496582, + 'FR_Wheel_Angle': -14.400476455688477, + 'Location': array([-6.78598938e+01, 9.78806610e+01, 7.78932348e-02]), + 'Rotation': array([ 7.99132104e-04, -1.98392010e+01, -5.27728510e+00]), + 'Velocity': array([-4.55852807e-01, 2.51275808e-01, 5.31196565e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3873.043701171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5704.50634766, 14834.54296875, 125.32815552]), + 'frame': 28300, + 'frame_number': 28300, + 'framesequence': 113940, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.2421758510172, + 'timestamp_carla': 961241, + 'timestamp_device': 1831844, + 'timestamp_stream': 961.2421758510172, + 'transform': [array([-59.39319229, 96.24440002, 0.11129421]), + array([5.27047443e+00, 1.79920547e+02, 4.18314384e-03])]} +{'AngularVelocity': array([0.13526371, 0.06564042, 1.70193088]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.865821838378906, + 'FR_Wheel_Angle': -16.430147171020508, + 'Location': array([-6.79353333e+01, 9.79191208e+01, 7.78738111e-02]), + 'Rotation': array([ 4.71283030e-03, -1.93804054e+01, -5.27731657e+00]), + 'Velocity': array([-4.49395329e-01, 2.45105505e-01, -1.00831981e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3882.550048828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5713.70556641, 14842.63769531, 125.39975739]), + 'frame': 28301, + 'frame_number': 28301, + 'framesequence': 113943, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.2733410522342, + 'timestamp_carla': 961272, + 'timestamp_device': 1831869, + 'timestamp_stream': 961.2733410522342, + 'transform': [array([-59.36634445, 96.22537231, 0.11109058]), + array([ 5.26903963e+00, -1.79949982e+02, 4.96539939e-03])]} +{'AngularVelocity': array([0.10611898, 0.06007762, 2.39337969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.822891235351562, + 'FR_Wheel_Angle': -17.519880294799805, + 'Location': array([-6.80194778e+01, 9.79638138e+01, 7.78865144e-02]), + 'Rotation': array([ 5.55977365e-03, -1.87693825e+01, -5.28329897e+00]), + 'Velocity': array([-4.07219619e-01, 2.43638441e-01, -1.00183483e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3892.805419921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5723.61523438, 14851.35644531, 125.52983856]), + 'frame': 28302, + 'frame_number': 28302, + 'framesequence': 113947, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.3063009493053, + 'timestamp_carla': 961305, + 'timestamp_device': 1831903, + 'timestamp_stream': 961.3063009493053, + 'transform': [array([-59.34036636, 96.20592499, 0.11100796]), + array([ 5.26949739e+00, -1.79823868e+02, 5.36301080e-03])]} +{'AngularVelocity': array([0.10052419, 0.05823047, 1.85721815]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.70521354675293, + 'FR_Wheel_Angle': -17.63263702392578, + 'Location': array([-6.80898895e+01, 9.80006256e+01, 7.78890699e-02]), + 'Rotation': array([ 4.46011312e-03, -1.82648067e+01, -5.28226042e+00]), + 'Velocity': array([-4.09030169e-01, 2.31727093e-01, -1.87492369e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4981.96826171875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5733.67871094, 15939.08886719, 125.67974091]), + 'frame': 28303, + 'frame_number': 28303, + 'framesequence': 113952, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.3399798497558, + 'timestamp_carla': 961339, + 'timestamp_device': 1831944, + 'timestamp_stream': 961.3399798497558, + 'transform': [array([-59.3140564 , 96.18648529, 0.11099319]), + array([ 5.27090454e+00, -1.79696457e+02, 5.55459596e-03])]} +{'AngularVelocity': array([0.10747622, 0.07159583, 1.78627598]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.685901641845703, + 'FR_Wheel_Angle': -17.401884078979492, + 'Location': array([-6.81587219e+01, 9.80360413e+01, 7.79071152e-02]), + 'Rotation': array([ 4.88358503e-03, -1.77567577e+01, -5.28253460e+00]), + 'Velocity': array([-4.00570780e-01, 2.22172827e-01, 7.93504732e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3930.2822265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5741.75683594, 14885.89257812, 125.61542511]), + 'frame': 28304, + 'frame_number': 28304, + 'framesequence': 113955, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.3714904524386, + 'timestamp_carla': 961370, + 'timestamp_device': 1831969, + 'timestamp_stream': 961.3714904524386, + 'transform': [array([-59.28975296, 96.1685791 , 0.11105438]), + array([ 5.27243423e+00, -1.79578979e+02, 5.51353116e-03])]} +{'AngularVelocity': array([ 2.38590693, -3.66035271, 4.81604528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.798046112060547, + 'FR_Wheel_Angle': -17.441965103149414, + 'Location': array([-6.82388153e+01, 9.80750732e+01, 7.30686709e-02]), + 'Rotation': array([ 0.20614193, -17.08009148, -5.58359098]), + 'Velocity': array([-0.41857016, 0.17039856, -0.05749063]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3921.553466796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5750.78417969, 14875.63476562, 125.62557983]), + 'frame': 28305, + 'frame_number': 28305, + 'framesequence': 113959, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.4046428501606, + 'timestamp_carla': 961403, + 'timestamp_device': 1832003, + 'timestamp_stream': 961.4046428501606, + 'transform': [array([-59.26463699, 96.15026855, 0.11095558]), + array([ 5.27263927e+00, -1.79457977e+02, 5.93264261e-03])]} +{'AngularVelocity': array([-0.14187956, -0.09637055, 5.24024868]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.845855712890625, + 'FR_Wheel_Angle': -17.44223403930664, + 'Location': array([-6.83019409e+01, 9.80990295e+01, 6.20786399e-02]), + 'Rotation': array([ 0.57097644, -16.36085701, -6.00507021]), + 'Velocity': array([-0.42344931, 0.19011787, -0.0114127 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3930.0126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5759.19238281, 14882.66210938, 125.62320709]), + 'frame': 28306, + 'frame_number': 28306, + 'framesequence': 113963, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.4376390501857, + 'timestamp_carla': 961436, + 'timestamp_device': 1832036, + 'timestamp_stream': 961.4376390501857, + 'transform': [array([-59.23713684, 96.13136292, 0.11108127]), + array([ 5.27419662e+00, -1.79326599e+02, 5.56187052e-03])]} +{'AngularVelocity': array([ 1.07589567, -0.66430688, 4.77938032]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.858196258544922, + 'FR_Wheel_Angle': -17.466060638427734, + 'Location': array([-6.83752441e+01, 9.81230621e+01, 6.56109750e-02]), + 'Rotation': array([ 0.44049937, -15.52745247, -5.81015396]), + 'Velocity': array([-0.39180598, 0.16412237, 0.00126727]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3939.14501953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5767.88378906, 14890.30957031, 125.6517868 ]), + 'frame': 28307, + 'frame_number': 28307, + 'framesequence': 113967, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.47092115134, + 'timestamp_carla': 961470, + 'timestamp_device': 1832069, + 'timestamp_stream': 961.47092115134, + 'transform': [array([-59.21085739, 96.11252594, 0.11123928]), + array([ 5.27483892e+00, -1.79200577e+02, 4.94449493e-03])]} +{'AngularVelocity': array([ 0.75589722, -0.24534604, 4.70838594]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.840505599975586, + 'FR_Wheel_Angle': -17.455947875976562, + 'Location': array([-6.84407883e+01, 9.81441193e+01, 6.67615235e-02]), + 'Rotation': array([ 0.40005782, -14.80168343, -5.74579287]), + 'Velocity': array([-0.44117466, 0.19121006, 0.00305378]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3949.013671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5777.34667969, 14898.63671875, 125.62569427]), + 'frame': 28308, + 'frame_number': 28308, + 'framesequence': 113971, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.5039066523314, + 'timestamp_carla': 961502, + 'timestamp_device': 1832103, + 'timestamp_stream': 961.5039066523314, + 'transform': [array([-59.18542862, 96.09424591, 0.11134227]), + array([ 5.27533054e+00, -1.79078613e+02, 4.56045801e-03])]} +{'AngularVelocity': array([ 0.12683074, -0.1743506 , 4.26184177]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.849201202392578, + 'FR_Wheel_Angle': -17.476341247558594, + 'Location': array([-6.85241623e+01, 9.81690598e+01, 6.76812083e-02]), + 'Rotation': array([ 0.38325554, -13.8568325 , -5.73508072]), + 'Velocity': array([-0.40793276, 0.14164726, -0.00471055]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4970.146484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5800.58837891, 15918.09667969, 125.67024231]), + 'frame': 28309, + 'frame_number': 28309, + 'framesequence': 113975, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.5376421511173, + 'timestamp_carla': 961536, + 'timestamp_device': 1832136, + 'timestamp_stream': 961.5376421511173, + 'transform': [array([-59.15930939, 96.07585907, 0.1113097 ]), + array([ 5.27487278e+00, -1.78953934e+02, 4.62288456e-03])]} +{'AngularVelocity': array([ 2.6140213 , -2.21564579, 5.93885326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.761098861694336, + 'FR_Wheel_Angle': -21.167024612426758, + 'Location': array([-6.86043854e+01, 9.81936035e+01, 6.56124279e-02]), + 'Rotation': array([ 0.45828518, -12.90449905, -5.84448671]), + 'Velocity': array([-0.39679736, 0.16344519, -0.02853125]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3981.44677734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5795.58105469, 14927.94140625, 125.55830383]), + 'frame': 28310, + 'frame_number': 28310, + 'framesequence': 113979, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.5696618519723, + 'timestamp_carla': 961568, + 'timestamp_device': 1832169, + 'timestamp_stream': 961.5696618519723, + 'transform': [array([-59.13584518, 96.05890656, 0.111361 ]), + array([ 5.27541924e+00, -1.78841568e+02, 4.50569857e-03])]} +{'AngularVelocity': array([ 0.96445042, -0.92368525, 4.73559904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.2896785736084, + 'FR_Wheel_Angle': -20.14048957824707, + 'Location': array([-6.86789017e+01, 9.82171173e+01, 6.28945678e-02]), + 'Rotation': array([ 0.54858708, -11.96522808, -5.97385025]), + 'Velocity': array([-0.38699234, 0.13323848, -0.01427379]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3977.59619140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5804.47265625, 14922.50585938, 125.5621109 ]), + 'frame': 28311, + 'frame_number': 28311, + 'framesequence': 113983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.602549251169, + 'timestamp_carla': 961601, + 'timestamp_device': 1832203, + 'timestamp_stream': 961.602549251169, + 'transform': [array([-59.11107254, 96.04166412, 0.11126316]), + array([ 5.27487278e+00, -1.78723724e+02, 4.85543208e-03])]} +{'AngularVelocity': array([ 1.595788 , -1.43958366, 5.17086315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.104293823242188, + 'FR_Wheel_Angle': -20.24712371826172, + 'Location': array([-6.87523499e+01, 9.82398529e+01, 6.11557886e-02]), + 'Rotation': array([ 0.60950553, -11.08217049, -6.07443714]), + 'Velocity': array([-0.41840789, 0.14261606, -0.02053072]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.346923828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5812.72705078, 14929.76953125, 125.55514526]), + 'frame': 28312, + 'frame_number': 28312, + 'framesequence': 113987, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.6349219493568, + 'timestamp_carla': 961634, + 'timestamp_device': 1832236, + 'timestamp_stream': 961.6349219493568, + 'transform': [array([-59.08681488, 96.02495575, 0.11120155]), + array([ 5.27456570e+00, -1.78608566e+02, 5.09566674e-03])]} +{'AngularVelocity': array([ 2.2732861 , -1.77573848, 4.13958168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.038488388061523, + 'FR_Wheel_Angle': -20.319631576538086, + 'Location': array([-6.88171005e+01, 9.82584152e+01, 5.76063283e-02]), + 'Rotation': array([ 0.73944306, -10.31446934, -6.26922989]), + 'Velocity': array([-0.34962562, 0.11883794, -0.02769944]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3995.51025390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5821.40185547, 14937.40234375, 125.58048248]), + 'frame': 28313, + 'frame_number': 28313, + 'framesequence': 113991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.6669374518096, + 'timestamp_carla': 961666, + 'timestamp_device': 1832269, + 'timestamp_stream': 961.6669374518096, + 'transform': [array([-59.06405258, 96.00878906, 0.11130027]), + array([ 5.27526236e+00, -1.78499969e+02, 4.77281306e-03])]} +{'AngularVelocity': array([ 2.85808516, -2.3602562 , 3.59033751]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.040748596191406, + 'FR_Wheel_Angle': -20.345964431762695, + 'Location': array([-6.88834076e+01, 9.82760849e+01, 5.11880256e-02]), + 'Rotation': array([ 0.96902621, -9.51368427, -6.63559484]), + 'Velocity': array([-0.34884301, 0.10224105, -0.04259385]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4004.5048828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5829.91357422, 14944.89257812, 125.59848022]), + 'frame': 28314, + 'frame_number': 28314, + 'framesequence': 113995, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.7009726502001, + 'timestamp_carla': 961700, + 'timestamp_device': 1832303, + 'timestamp_stream': 961.7009726502001, + 'transform': [array([-59.03938293, 95.9917984 , 0.11129612]), + array([ 5.27529621e+00, -1.78382919e+02, 4.73903911e-03])]} +{'AngularVelocity': array([ 1.7049278 , -1.02653599, 4.28987932]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.00706672668457, + 'FR_Wheel_Angle': -20.333322525024414, + 'Location': array([-6.89488449e+01, 9.82938919e+01, 4.94762920e-02]), + 'Rotation': array([ 1.00567019, -8.80344772, -6.70508432]), + 'Velocity': array([-0.4069801 , 0.13683425, -0.01178044]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5008.083984375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5864.02832031, 15946.65039062, 125.65914154]), + 'frame': 28315, + 'frame_number': 28315, + 'framesequence': 113999, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3598315417766571, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.7367687523365, + 'timestamp_carla': 961735, + 'timestamp_device': 1832336, + 'timestamp_stream': 961.7367687523365, + 'transform': [array([-59.01330948, 95.97439575, 0.11112335]), + array([ 5.27429247e+00, -1.78259903e+02, 5.26697794e-03])]} +{'AngularVelocity': array([-0.26233134, 0.22142735, 2.89035416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.04368782043457, + 'FR_Wheel_Angle': -20.36971664428711, + 'Location': array([-6.90142975e+01, 9.83119965e+01, 4.97707874e-02]), + 'Rotation': array([ 1.00098467, -8.10236645, -6.72827768]), + 'Velocity': array([-0.35063076, 0.11932929, 0.00207092]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4035.30126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5847.07958984, 14972.62890625, 125.57471466]), + 'frame': 28316, + 'frame_number': 28316, + 'framesequence': 114003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35355085134506226, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.770522352308, + 'timestamp_carla': 961769, + 'timestamp_device': 1832369, + 'timestamp_stream': 961.770522352308, + 'transform': [array([-58.9906044 , 95.95836639, 0.11115257]), + array([ 5.27431965e+00, -1.78152267e+02, 5.17110340e-03])]} +{'AngularVelocity': array([ 1.97509766, -1.36040545, 4.59153318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.056072235107422, + 'FR_Wheel_Angle': -20.34857940673828, + 'Location': array([-6.90646057e+01, 9.83256912e+01, 5.01110218e-02]), + 'Rotation': array([ 0.99545902, -7.56833601, -6.73657656]), + 'Velocity': array([-0.35276207, 0.10912815, -0.01693166]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4029.058349609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5855.81787109, 14964.75683594, 125.60982513]), + 'frame': 28317, + 'frame_number': 28317, + 'framesequence': 114007, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33619192242622375, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.8048808500171, + 'timestamp_carla': 961803, + 'timestamp_device': 1832403, + 'timestamp_stream': 961.8048808500171, + 'transform': [array([-58.96746826, 95.94221497, 0.11115215]), + array([ 5.27390289e+00, -1.78043259e+02, 5.12301130e-03])]} +{'AngularVelocity': array([-0.84494823, 0.25501603, 4.97871208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.35776138305664, + 'FR_Wheel_Angle': -21.339136123657227, + 'Location': array([-6.91387863e+01, 9.83448105e+01, 4.96975854e-02]), + 'Rotation': array([ 1.0024941 , -6.81433821, -6.75510359]), + 'Velocity': array([-0.43651056, 0.14986265, 0.00160132]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4027.6474609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5863.58642578, 14961.82128906, 125.60355377]), + 'frame': 28318, + 'frame_number': 28318, + 'framesequence': 114011, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3110141158103943, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.8381222523749, + 'timestamp_carla': 961837, + 'timestamp_device': 1832436, + 'timestamp_stream': 961.8381222523749, + 'transform': [array([-58.94684982, 95.92632294, 0.11137626]), + array([ 5.27407360e+00, -1.77946182e+02, 4.23109857e-03])]} +{'AngularVelocity': array([-0.17858425, -0.26859793, 5.40426064]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.768890380859375, + 'FR_Wheel_Angle': -23.567197799682617, + 'Location': array([-6.92106781e+01, 9.83652725e+01, 4.98161837e-02]), + 'Rotation': array([ 1.00056803, -6.02334833, -6.75504065]), + 'Velocity': array([-0.44669628, 0.1413485 , -0.00836994]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4039.541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5871.890625 , 14972.15039062, 125.60163116]), + 'frame': 28319, + 'frame_number': 28319, + 'framesequence': 114015, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.28779566287994385, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.8703109510243, + 'timestamp_carla': 961869, + 'timestamp_device': 1832469, + 'timestamp_stream': 961.8703109510243, + 'transform': [array([-58.92679977, 95.90950775, 0.1117786 ]), + array([ 5.27426481e+00, -1.77852142e+02, 2.59843585e-03])]} +{'AngularVelocity': array([ 2.37885666, -1.62807834, 4.64010859]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.158349990844727, + 'FR_Wheel_Angle': -23.34954071044922, + 'Location': array([-6.92769547e+01, 9.83840027e+01, 5.16237766e-02]), + 'Rotation': array([ 0.93945152, -5.27679825, -6.66254234]), + 'Velocity': array([-0.4030318 , 0.10626662, -0.02051091]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4045.724853515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5879.16845703, 14976.77734375, 125.54055786]), + 'frame': 28320, + 'frame_number': 28320, + 'framesequence': 114019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2745018005371094, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.9036269523203, + 'timestamp_carla': 961902, + 'timestamp_device': 1832502, + 'timestamp_stream': 961.9036269523203, + 'transform': [array([-58.90616608, 95.89212799, 0.11192722]), + array([ 5.27453136e+00, -1.77755386e+02, 1.99560146e-03])]} +{'AngularVelocity': array([ 1.12506664, -0.26617074, 4.4072957 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.999954223632812, + 'FR_Wheel_Angle': -23.005569458007812, + 'Location': array([-6.93536911e+01, 9.84049301e+01, 5.27865365e-02]), + 'Rotation': array([ 0.8907181 , -4.44415474, -6.59509802]), + 'Velocity': array([-0.4013204 , 0.14139131, 0.0008582 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4046.709228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5886.05029297, 14976.10058594, 125.42752075]), + 'frame': 28321, + 'frame_number': 28321, + 'framesequence': 114023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.27812740206718445, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.938366651535, + 'timestamp_carla': 961937, + 'timestamp_device': 1832536, + 'timestamp_stream': 961.938366651535, + 'transform': [array([-58.88544846, 95.8745575 , 0.11184441]), + array([ 5.27446985e+00, -1.77658371e+02, 2.28998577e-03])]} +{'AngularVelocity': array([-4.05819845, 2.59308934, 3.58468509]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.14396095275879, + 'FR_Wheel_Angle': -23.052154541015625, + 'Location': array([-6.94203339e+01, 9.84222183e+01, 5.21085858e-02]), + 'Rotation': array([ 0.90736324, -3.74762082, -6.61633873]), + 'Velocity': array([-0.38143367, 0.14670774, 0.04041857]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4063.9833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5893.76074219, 14991.62890625, 125.38554382]), + 'frame': 28322, + 'frame_number': 28322, + 'framesequence': 114027, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2914029359817505, + 'throttle_input': 0.2222171425819397, + 'timestamp': 961.9704734496772, + 'timestamp_carla': 961969, + 'timestamp_device': 1832569, + 'timestamp_stream': 961.9704734496772, + 'transform': [array([-58.86617661, 95.85799408, 0.11207523]), + array([ 5.27556944e+00, -1.77567902e+02, 1.48750492e-03])]} +{'AngularVelocity': array([ 3.18563819, -1.7457459 , 3.57839942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.202489852905273, + 'FR_Wheel_Angle': -23.10368537902832, + 'Location': array([-6.94884720e+01, 9.84400635e+01, 5.34898117e-02]), + 'Rotation': array([ 0.86805552, -3.02563524, -6.58923817]), + 'Velocity': array([-0.3762109 , 0.10454375, -0.02305859]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4087.79296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5901.80908203, 15013.6484375 , 125.40609741]), + 'frame': 28323, + 'frame_number': 28323, + 'framesequence': 114031, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3033234775066376, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.0041669495404, + 'timestamp_carla': 962003, + 'timestamp_device': 1832602, + 'timestamp_stream': 962.0041669495404, + 'transform': [array([-58.84339523, 95.84002686, 0.11216038]), + array([ 5.27658033e+00, -1.77461517e+02, 1.22049206e-03])]} +{'AngularVelocity': array([-3.26051831, 2.01625204, 3.08253646]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.21000862121582, + 'FR_Wheel_Angle': -23.111793518066406, + 'Location': array([-6.95531998e+01, 9.84554291e+01, 5.32492585e-02]), + 'Rotation': array([ 0.86660755, -2.38919091, -6.5710206 ]), + 'Velocity': array([-0.32835773, 0.12325924, 0.03450518]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4089.909912109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5908.54296875, 15014.08007812, 125.349617 ]), + 'frame': 28324, + 'frame_number': 28324, + 'framesequence': 114035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3124057948589325, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.0390451513231, + 'timestamp_carla': 962038, + 'timestamp_device': 1832636, + 'timestamp_stream': 962.0390451513231, + 'transform': [array([-58.81616211, 95.82078552, 0.11208099]), + array([ 5.27765274e+00, -1.77335312e+02, 1.62525789e-03])]} +{'AngularVelocity': array([ 1.03480196, -0.06434686, 4.02750874]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.18035316467285, + 'FR_Wheel_Angle': -23.084802627563477, + 'Location': array([-6.96252213e+01, 9.84726868e+01, 5.64985424e-02]), + 'Rotation': array([ 0.74530339, -1.67352307, -6.41550159]), + 'Velocity': array([-0.43207034, 0.13977019, 0.00802804]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4098.986328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5916.74804688, 15021.30175781, 125.32945251]), + 'frame': 28325, + 'frame_number': 28325, + 'framesequence': 114039, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3108493387699127, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.0725946500897, + 'timestamp_carla': 962071, + 'timestamp_device': 1832669, + 'timestamp_stream': 962.0725946500897, + 'transform': [array([-58.79332733, 95.80273438, 0.11205535]), + array([ 5.27893019e+00, -1.77228271e+02, 1.89239811e-03])]} +{'AngularVelocity': array([ 1.45956481, -1.17613292, 4.09728003]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.174304962158203, + 'FR_Wheel_Angle': -23.103662490844727, + 'Location': array([-6.96984329e+01, 9.84896851e+01, 5.77836372e-02]), + 'Rotation': array([ 0.72699845, -0.9330138 , -6.40848303]), + 'Velocity': array([-0.45585287, 0.10964806, -0.02238662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4091.5859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5925.65136719, 15011.90039062, 125.3556366 ]), + 'frame': 28326, + 'frame_number': 28326, + 'framesequence': 114043, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30520951747894287, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.1054119504988, + 'timestamp_carla': 962104, + 'timestamp_device': 1832702, + 'timestamp_stream': 962.1054119504988, + 'transform': [array([-58.77067184, 95.78530121, 0.11192535]), + array([ 5.27905273e+00, -1.77122620e+02, 2.48902198e-03])]} +{'AngularVelocity': array([ 5.20183611, -2.78106022, 4.53985405]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.947284698486328, + 'FR_Wheel_Angle': -25.24211311340332, + 'Location': array([-6.97673492e+01, 9.85050278e+01, 6.16230518e-02]), + 'Rotation': array([ 0.59516215, -0.27069083, -6.22266102]), + 'Velocity': array([-0.45200858, 0.09050209, -0.04725116]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4098.705078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5933.85009766, 15017.11328125, 125.37385559]), + 'frame': 28327, + 'frame_number': 28327, + 'framesequence': 114047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29837948083877563, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.1383228488266, + 'timestamp_carla': 962137, + 'timestamp_device': 1832736, + 'timestamp_stream': 962.1383228488266, + 'transform': [array([-58.74888992, 95.76828003, 0.11173561]), + array([ 5.27852678e+00, -1.77021194e+02, 3.25017213e-03])]} +{'AngularVelocity': array([-1.59414577, 1.89799356, 3.66531658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.098758697509766, + 'FR_Wheel_Angle': -25.163034439086914, + 'Location': array([-6.98502197e+01, 9.85171204e+01, 6.60575256e-02]), + 'Rotation': array([ 0.18653929, 0.43691725, -5.79190445]), + 'Velocity': array([-0.47182187, 0.10705659, 0.03833164]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4105.72216796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5941.95898438, 15022.26757812, 125.41706085]), + 'frame': 28328, + 'frame_number': 28328, + 'framesequence': 114051, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2940397560596466, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.1720208488405, + 'timestamp_carla': 962171, + 'timestamp_device': 1832769, + 'timestamp_stream': 962.1720208488405, + 'transform': [array([-58.72603226, 95.7508316 , 0.1116468 ]), + array([ 5.27838373e+00, -1.76915314e+02, 3.59357730e-03])]} +{'AngularVelocity': array([2.74993515, 0.20651385, 2.40823746]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.686763763427734, + 'FR_Wheel_Angle': -25.832260131835938, + 'Location': array([-6.99441376e+01, 9.85110321e+01, 9.31893736e-02]), + 'Rotation': array([ 0.88653117, 1.14488304, -3.61010814]), + 'Velocity': array([-0.48607424, 0.04951417, 0.07949761]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4112.51953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5949.76318359, 15027.22851562, 125.47234344]), + 'frame': 28329, + 'frame_number': 28329, + 'framesequence': 114055, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29488205909729004, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.2039719521999, + 'timestamp_carla': 962203, + 'timestamp_device': 1832802, + 'timestamp_stream': 962.2039719521999, + 'transform': [array([-58.70561218, 95.73445892, 0.1116497 ]), + array([ 5.27858829e+00, -1.76820404e+02, 3.64802405e-03])]} +{'AngularVelocity': array([-0.4922165 , -0.05794044, 1.50672698]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.40214538574219, + 'FR_Wheel_Angle': -25.843849182128906, + 'Location': array([-70.01963043, 98.51364899, 0.10102025]), + 'Rotation': array([ 0.98018676, 1.4687463 , -3.29141283]), + 'Velocity': array([-0.29747736, 0.01667188, 0.01074047]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5138.43603515625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6012.74609375, 16049.765625 , 125.56056976]), + 'frame': 28330, + 'frame_number': 28330, + 'framesequence': 114059, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2977752089500427, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.239010348916, + 'timestamp_carla': 962238, + 'timestamp_device': 1832836, + 'timestamp_stream': 962.239010348916, + 'transform': [array([-58.68371582, 95.7168808 , 0.11164241]), + array([ 5.27941513e+00, -1.76718582e+02, 3.69660673e-03])]} +{'AngularVelocity': array([-2.60340881, -1.48370278, 3.99491501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.38160705566406, + 'FR_Wheel_Angle': -25.75065040588379, + 'Location': array([-70.07137299, 98.52344513, 0.107031 ]), + 'Rotation': array([ 1.2227267 , 1.9901315 , -2.74926805]), + 'Velocity': array([-0.34644198, 0.12381387, 0.0451856 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5153.6650390625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6022.2734375 , 16063.09375 , 125.56721497]), + 'frame': 28331, + 'frame_number': 28331, + 'framesequence': 114064, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30123600363731384, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.2756833508611, + 'timestamp_carla': 962274, + 'timestamp_device': 1832877, + 'timestamp_stream': 962.2756833508611, + 'transform': [array([-58.66007996, 95.69860077, 0.11160122]), + array([ 5.27993393e+00, -1.76609100e+02, 3.82653414e-03])]} +{'AngularVelocity': array([-1.16783774, -0.67373765, 4.27270555]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.35673141479492, + 'FR_Wheel_Angle': -25.75189971923828, + 'Location': array([-70.13741302, 98.53759766, 0.11116056]), + 'Rotation': array([ 1.36590111, 2.67946124, -2.45626831]), + 'Velocity': array([-0.38365608, 0.10336386, 0.01868828]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4149.03125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5974.11572266, 15058.06835938, 125.50437164]), + 'frame': 28332, + 'frame_number': 28332, + 'framesequence': 114068, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30235299468040466, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.3080877512693, + 'timestamp_carla': 962307, + 'timestamp_device': 1832911, + 'timestamp_stream': 962.3080877512693, + 'transform': [array([-58.63764954, 95.68175507, 0.11171874]), + array([ 5.27911425e+00, -1.76505814e+02, 3.32562719e-03])]} +{'AngularVelocity': array([-0.549142 , -0.20915636, 3.10943174]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.364871978759766, + 'FR_Wheel_Angle': -25.758317947387695, + 'Location': array([-70.19527435, 98.54927826, 0.11253919]), + 'Rotation': array([ 1.4305352 , 3.29951668, -2.331635 ]), + 'Velocity': array([-0.32055393, 0.07558177, 0.00519929]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4140.537109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5981.72949219, 15047.54882812, 125.51020813]), + 'frame': 28333, + 'frame_number': 28333, + 'framesequence': 114071, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30110782384872437, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.3397316522896, + 'timestamp_carla': 962338, + 'timestamp_device': 1832936, + 'timestamp_stream': 962.3397316522896, + 'transform': [array([-58.61500168, 95.66513824, 0.11169387]), + array([ 5.27804184e+00, -1.76401627e+02, 3.38791776e-03])]} +{'AngularVelocity': array([-0.24210167, -0.06182414, 4.21418524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.3902473449707, + 'FR_Wheel_Angle': -25.746448516845703, + 'Location': array([-70.27240753, 98.56368256, 0.11298593]), + 'Rotation': array([ 1.44931829, 4.10946178, -2.2797246 ]), + 'Velocity': array([-0.39296752, 0.085642 , 0.00128017]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4147.5810546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5989.796875 , 15052.67773438, 125.47772217]), + 'frame': 28334, + 'frame_number': 28334, + 'framesequence': 114075, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29931333661079407, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.3734301514924, + 'timestamp_carla': 962372, + 'timestamp_device': 1832969, + 'timestamp_stream': 962.3734301514924, + 'transform': [array([-58.5913353 , 95.64766693, 0.11159924]), + array([ 5.27724981e+00, -1.76292694e+02, 3.68250022e-03])]} +{'AngularVelocity': array([-0.68776429, -0.40901434, 4.39970493]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.432640075683594, + 'FR_Wheel_Angle': -27.314556121826172, + 'Location': array([-70.35626221, 98.57894135, 0.11159819]), + 'Rotation': array([ 1.40113127, 5.04078674, -2.37136865]), + 'Velocity': array([-0.40671641, 0.09009756, 0.00657015]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4154.67822265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5997.95117188, 15057.86132812, 125.48542023]), + 'frame': 28335, + 'frame_number': 28335, + 'framesequence': 114080, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29865413904190063, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.4073650501668, + 'timestamp_carla': 962406, + 'timestamp_device': 1833011, + 'timestamp_stream': 962.4073650501668, + 'transform': [array([-58.56871033, 95.63048553, 0.11156929]), + array([ 5.27731133e+00, -1.76188416e+02, 3.79918818e-03])]} +{'AngularVelocity': array([-0.34442699, -0.13321455, 4.7852416 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.64165496826172, + 'FR_Wheel_Angle': -28.46250343322754, + 'Location': array([-70.43482208, 98.59366608, 0.11256097]), + 'Rotation': array([ 1.44236517, 5.97670746, -2.29690576]), + 'Velocity': array([-0.39679819, 0.09493867, 0.00417725]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4162.1494140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6006.50732422, 15063.29882812, 125.50745392]), + 'frame': 28336, + 'frame_number': 28336, + 'framesequence': 114084, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29949644207954407, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.4430754519999, + 'timestamp_carla': 962442, + 'timestamp_device': 1833044, + 'timestamp_stream': 962.4430754519999, + 'transform': [array([-58.54590607, 95.61109924, 0.12813984]), + array([ 5.41799927e+00, -1.76088470e+02, -5.69263212e-02])]} +{'AngularVelocity': array([-0.05619 , -0.04634065, 4.15554571]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.35561752319336, + 'FR_Wheel_Angle': -28.475772857666016, + 'Location': array([-70.49995422, 98.60538483, 0.1128911 ]), + 'Rotation': array([ 1.45717978, 6.73989487, -2.26608324]), + 'Velocity': array([-0.38892165, 0.10166172, 0.00148031]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16461.04296875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-6831.75146484, 27333. , 126.32762146]), + 'frame': 28337, + 'frame_number': 28337, + 'framesequence': 114088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30044862627983093, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.476580452174, + 'timestamp_carla': 962475, + 'timestamp_device': 1833077, + 'timestamp_stream': 962.476580452174, + 'transform': [array([-58.52652359, 95.59162903, 0.15340473]), + array([ 5.61179256e+00, -1.76010025e+02, -1.53078735e-01])]} +{'AngularVelocity': array([ 0.10968619, -0.00792873, 5.41355324]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.3741455078125, + 'FR_Wheel_Angle': -28.18610954284668, + 'Location': array([-70.56629944, 98.61617279, 0.11301824]), + 'Rotation': array([ 1.45937908, 7.52850819, -2.25982666]), + 'Velocity': array([-4.12804067e-01, 9.59303007e-02, 3.48186499e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16406.517578125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-6858.25048828, 27274.96289062, 108.75002289]), + 'frame': 28338, + 'frame_number': 28338, + 'framesequence': 114092, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.300283819437027, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.5104503519833, + 'timestamp_carla': 962509, + 'timestamp_device': 1833111, + 'timestamp_stream': 962.5104503519833, + 'transform': [array([-58.50936508, 95.57139587, 0.18257533]), + array([ 5.82644463, -175.94514465, -0.26648387])]} +{'AngularVelocity': array([-0.07396322, -0.04475024, 5.89970779]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.499534606933594, + 'FR_Wheel_Angle': -28.261022567749023, + 'Location': array([-70.63768005, 98.62664795, 0.11305826]), + 'Rotation': array([ 1.45923567, 8.37226677, -2.25732446]), + 'Velocity': array([-4.37347680e-01, 8.17706734e-02, 1.37720112e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4198.58447265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6030.52539062, 15093.53417969, 113.40525055]), + 'frame': 28339, + 'frame_number': 28339, + 'framesequence': 114096, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.543007850647, + 'timestamp_carla': 962542, + 'timestamp_device': 1833144, + 'timestamp_stream': 962.543007850647, + 'transform': [array([-58.49559784, 95.55302429, 0.20995918]), + array([ 6.02352285, -175.89648438, -0.37472036])]} +{'AngularVelocity': array([-0.11061711, 0.01251843, 4.73104572]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.51904296875, + 'FR_Wheel_Angle': -28.302732467651367, + 'Location': array([-70.7117157 , 98.63629913, 0.11305986]), + 'Rotation': array([ 1.46040368, 9.24401093, -2.25488305]), + 'Velocity': array([-4.35118020e-01, 7.21495301e-02, 3.53245734e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4192.91259765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6035.43066406, 15085.81835938, 104.67389679]), + 'frame': 28340, + 'frame_number': 28340, + 'framesequence': 114099, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.5745045505464, + 'timestamp_carla': 962573, + 'timestamp_device': 1833169, + 'timestamp_stream': 962.5745045505464, + 'transform': [array([-58.48187256, 95.53621674, 0.21294978]), + array([ 5.99488401, -175.84417725, -0.39676288])]} +{'AngularVelocity': array([ 0.0788988 , -0.01954825, 5.44315004]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.52059555053711, + 'FR_Wheel_Angle': -28.305131912231445, + 'Location': array([-70.78272247, 98.64479065, 0.11305559]), + 'Rotation': array([ 1.46245956, 10.09739971, -2.25390625]), + 'Velocity': array([-4.38405484e-01, 8.72907490e-02, 1.89309110e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4193.2861328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6039.58837891, 15084.32910156, 96.31269836]), + 'frame': 28341, + 'frame_number': 28341, + 'framesequence': 114104, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.6079400517046, + 'timestamp_carla': 962606, + 'timestamp_device': 1833211, + 'timestamp_stream': 962.6079400517046, + 'transform': [array([-58.47119141, 95.51887512, 0.20489658]), + array([ 5.89733505, -175.79924011, -0.37352946])]} +{'AngularVelocity': array([-0.03141943, 0.0082694 , 4.06743383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.53287887573242, + 'FR_Wheel_Angle': -28.304920196533203, + 'Location': array([-70.85311127, 98.65196228, 0.1130491 ]), + 'Rotation': array([ 1.46251416, 10.92845821, -2.25213647]), + 'Velocity': array([-4.16362107e-01, 6.94977492e-02, -1.00135803e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4197.8515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6043.859375 , 15087.04296875, 94.56829834]), + 'frame': 28342, + 'frame_number': 28342, + 'framesequence': 114108, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.6411627493799, + 'timestamp_carla': 962640, + 'timestamp_device': 1833244, + 'timestamp_stream': 962.6411627493799, + 'transform': [array([-58.46160889, 95.5021286 , 0.19711331]), + array([ 5.82194376, -175.75804138, -0.3470363 ])]} +{'AngularVelocity': array([0.13507318, 0.01594991, 6.26341057]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.5026969909668, + 'FR_Wheel_Angle': -28.282100677490234, + 'Location': array([-70.94327545, 98.65943146, 0.11307111]), + 'Rotation': array([ 1.45825219, 11.97142315, -2.2553103 ]), + 'Velocity': array([-4.88761157e-01, 7.24047422e-02, -3.61156453e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4201.990234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6047.32958984, 15089.25 , 96.31858826]), + 'frame': 28343, + 'frame_number': 28343, + 'framesequence': 114112, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.6759243495762, + 'timestamp_carla': 962674, + 'timestamp_device': 1833277, + 'timestamp_stream': 962.6759243495762, + 'transform': [array([-58.45298767, 95.48510742, 0.18992244]), + array([ 5.75979567, -175.72129822, -0.32058898])]} +{'AngularVelocity': array([ 0.03119333, -0.01142156, 5.52649403]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.88801193237305, + 'FR_Wheel_Angle': -30.107824325561523, + 'Location': array([-71.02333832, 98.66491699, 0.11306093]), + 'Rotation': array([ 1.45986402, 12.90435791, -2.25546312]), + 'Velocity': array([-4.79330122e-01, 7.18371123e-02, 2.53391263e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4205.85595703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6050.47753906, 15091.25195312, 98.33427429]), + 'frame': 28344, + 'frame_number': 28344, + 'framesequence': 114116, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.7093777507544, + 'timestamp_carla': 962708, + 'timestamp_device': 1833311, + 'timestamp_stream': 962.7093777507544, + 'transform': [array([-58.4452095 , 95.46910095, 0.18469501]), + array([ 5.71714115, -175.688797 , -0.30026168])]} +{'AngularVelocity': array([ 0.05816685, -0.01190643, 6.13348722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.62810134887695, + 'FR_Wheel_Angle': -30.252002716064453, + 'Location': array([-71.09812164, 98.67072296, 0.11305574]), + 'Rotation': array([ 1.46050608, 13.86344337, -2.25622559]), + 'Velocity': array([-4.64718848e-01, 7.66527653e-02, -3.75652307e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4209.5068359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6053.26660156, 15093.0234375 , 100.36312866]), + 'frame': 28345, + 'frame_number': 28345, + 'framesequence': 114120, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.7434145510197, + 'timestamp_carla': 962742, + 'timestamp_device': 1833344, + 'timestamp_stream': 962.7434145510197, + 'transform': [array([-58.43849564, 95.45327759, 0.18115406]), + array([ 5.68919897, -175.66145325, -0.28583312])]} +{'AngularVelocity': array([0.04016332, 0.01795024, 5.33305407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.7011604309082, + 'FR_Wheel_Angle': -30.821165084838867, + 'Location': array([-71.16956329, 98.67575836, 0.1130472 ]), + 'Rotation': array([ 1.46248686, 14.79045582, -2.25369287]), + 'Velocity': array([-4.35579479e-01, 6.81995377e-02, -1.71947482e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4212.84033203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6055.75097656, 15094.60351562, 101.9339447 ]), + 'frame': 28346, + 'frame_number': 28346, + 'framesequence': 114124, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.7760886512697, + 'timestamp_carla': 962775, + 'timestamp_device': 1833377, + 'timestamp_stream': 962.7760886512697, + 'transform': [array([-58.43219757, 95.43844604, 0.17898266]), + array([ 5.67171383, -175.63616943, -0.27659291])]} +{'AngularVelocity': array([0.07304811, 0.17038564, 5.96739912]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67620086669922, + 'FR_Wheel_Angle': -30.790340423583984, + 'Location': array([-71.23719025, 98.6791687 , 0.11306822]), + 'Rotation': array([ 1.45947468, 15.66941833, -2.25631762]), + 'Velocity': array([-4.84650254e-01, 5.07833660e-02, 1.58967974e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4215.89208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6057.85986328, 15095.94335938, 103.05561066]), + 'frame': 28347, + 'frame_number': 28347, + 'framesequence': 114128, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.8077851496637, + 'timestamp_carla': 962806, + 'timestamp_device': 1833411, + 'timestamp_stream': 962.8077851496637, + 'transform': [array([-58.42674255, 95.42443848, 0.17742001]), + array([ 5.65831947, -175.61465454, -0.26987022])]} +{'AngularVelocity': array([0.05857835, 0.02600163, 6.08815193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6826286315918, + 'FR_Wheel_Angle': -30.770540237426758, + 'Location': array([-71.31319427, 98.68216705, 0.11307451]), + 'Rotation': array([ 1.45878494, 16.64606857, -2.25524926]), + 'Velocity': array([-4.76595730e-01, 5.38740866e-02, 2.46305455e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4218.74609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6059.83398438, 15097.19921875, 103.77809143]), + 'frame': 28348, + 'frame_number': 28348, + 'framesequence': 114132, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.8410617522895, + 'timestamp_carla': 962840, + 'timestamp_device': 1833444, + 'timestamp_stream': 962.8410617522895, + 'transform': [array([-58.41989136, 95.40982056, 0.17609291]), + array([ 5.64349127, -175.58779907, -0.26477298])]} +{'AngularVelocity': array([0.02940964, 0.0067265 , 6.1338625 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.666412353515625, + 'FR_Wheel_Angle': -30.793840408325195, + 'Location': array([-71.39352417, 98.68374634, 0.11306085]), + 'Rotation': array([ 1.45888054, 17.69047928, -2.25479102]), + 'Velocity': array([-4.94302243e-01, 4.57268991e-02, -3.05318827e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4221.32177734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6061.52734375, 15098.27539062, 104.30724335]), + 'frame': 28349, + 'frame_number': 28349, + 'framesequence': 114135, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.8733025491238, + 'timestamp_carla': 962872, + 'timestamp_device': 1833469, + 'timestamp_stream': 962.8733025491238, + 'transform': [array([-58.41463852, 95.39592743, 0.17586029]), + array([ 5.64043808, -175.56793213, -0.26339173])]} +{'AngularVelocity': array([-0.6753732 , 0.21662852, 1.5802809 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.995445251464844, + 'FR_Wheel_Angle': -30.980554580688477, + 'Location': array([-71.45404816, 98.68632507, 0.11273691]), + 'Rotation': array([ 1.45000124, 18.52018929, -2.22937012]), + 'Velocity': array([-0.01280532, 0.07209075, -0.01444921]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4224.25, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6063.64599609, 15099.62207031, 104.70613098]), + 'frame': 28350, + 'frame_number': 28350, + 'framesequence': 114139, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.9060812518001, + 'timestamp_carla': 962905, + 'timestamp_device': 1833502, + 'timestamp_stream': 962.9060812518001, + 'transform': [array([-58.40803528, 95.38172913, 0.17548312]), + array([ 5.63473511, -175.54231262, -0.26185575])]} +{'AngularVelocity': array([-0.26768485, -0.05184487, 0.42864349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99580764770508, + 'FR_Wheel_Angle': -30.982545852661133, + 'Location': array([-71.45461273, 98.6893158 , 0.11136641]), + 'Rotation': array([ 1.41145849, 18.58225822, -2.19589257]), + 'Velocity': array([-0.00603585, 0.01336834, -0.00457483]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4226.734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6065.23339844, 15100.63085938, 104.81585693]), + 'frame': 28351, + 'frame_number': 28351, + 'framesequence': 114143, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.9396268501878, + 'timestamp_carla': 962938, + 'timestamp_device': 1833536, + 'timestamp_stream': 962.9396268501878, + 'transform': [array([-58.40221405, 95.3674469 , 0.17535484]), + array([ 5.63271999, -175.52006531, -0.26108876])]} +{'AngularVelocity': array([ 0.22969723, -0.07037592, 0.34682435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99504852294922, + 'FR_Wheel_Angle': -30.980093002319336, + 'Location': array([-71.45472717, 98.6897049 , 0.1116889 ]), + 'Rotation': array([ 1.4282403 , 18.61854744, -2.22512865]), + 'Velocity': array([-0.00272651, 0.01681616, 0.0047766 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4229.56396484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6067.27441406, 15101.92773438, 104.93452454]), + 'frame': 28352, + 'frame_number': 28352, + 'framesequence': 114147, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 962.9732023514807, + 'timestamp_carla': 962972, + 'timestamp_device': 1833569, + 'timestamp_stream': 962.9732023514807, + 'transform': [array([-58.39609146, 95.35307312, 0.17523448]), + array([ 5.62939358, -175.4967804 , -0.26059622])]} +{'AngularVelocity': array([ 0.19692841, -0.06118857, 0.31645975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.9994010925293, + 'FR_Wheel_Angle': -30.98322868347168, + 'Location': array([-71.45476532, 98.69083405, 0.11192712]), + 'Rotation': array([ 1.43296683, 18.63492966, -2.2255249 ]), + 'Velocity': array([-0.00189598, 0.01531775, 0.0041354 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16219.826171875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7010.74511719, 27053.49609375, 50.62904358]), + 'frame': 28353, + 'frame_number': 28353, + 'framesequence': 114151, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.00556274876, + 'timestamp_carla': 963004, + 'timestamp_device': 1833602, + 'timestamp_stream': 963.00556274876, + 'transform': [array([-58.39036942, 95.33907318, 0.17510955]), + array([ 5.62539816, -175.47518921, -0.2601656 ])]} +{'AngularVelocity': array([0.08565447, 0.02365937, 0.45818892]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.999820709228516, + 'FR_Wheel_Angle': -30.983457565307617, + 'Location': array([-71.45488739, 98.69219208, 0.11198137]), + 'Rotation': array([ 1.43229747, 18.66049767, -2.22375488]), + 'Velocity': array([-0.00367052, 0.02163867, -0.00054771]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16221.8759765625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7017.39697266, 27053.625 , 50.76851654]), + 'frame': 28354, + 'frame_number': 28354, + 'framesequence': 114155, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.0376754514873, + 'timestamp_carla': 963036, + 'timestamp_device': 1833636, + 'timestamp_stream': 963.0376754514873, + 'transform': [array([-58.38518524, 95.32512665, 0.17510994]), + array([ 5.6226182 , -175.45579529, -0.26022539])]} +{'AngularVelocity': array([-0.06817213, 0.00411145, -0.45248598]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99737548828125, + 'FR_Wheel_Angle': -30.982179641723633, + 'Location': array([-71.4548645 , 98.69281006, 0.11221784]), + 'Rotation': array([ 1.43726981, 18.66072845, -2.22915602]), + 'Velocity': array([ 0.00312109, -0.01112742, 0.00137102]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16223.8369140625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7023.57373047, 27053.73828125, 50.89354706]), + 'frame': 28355, + 'frame_number': 28355, + 'framesequence': 114159, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.0707352496684, + 'timestamp_carla': 963069, + 'timestamp_device': 1833669, + 'timestamp_stream': 963.0707352496684, + 'transform': [array([-58.37916946, 95.31061554, 0.17450088]), + array([ 5.61321974, -175.43322754, -0.25844219])]} +{'AngularVelocity': array([-0.15941605, -0.02673862, -0.02999136]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99834060668945, + 'FR_Wheel_Angle': -30.982091903686523, + 'Location': array([-71.45502472, 98.69326019, 0.11233408]), + 'Rotation': array([ 1.44302082, 18.69709396, -2.23822069]), + 'Velocity': array([-0.00036769, -0.0018254 , 0.00020817]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16225.2685546875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7029.09667969, 27053.3671875 , 50.87840271]), + 'frame': 28356, + 'frame_number': 28356, + 'framesequence': 114163, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.1037325523794, + 'timestamp_carla': 963102, + 'timestamp_device': 1833702, + 'timestamp_stream': 963.1037325523794, + 'transform': [array([-58.37186432, 95.29595184, 0.17578612]), + array([ 5.6227684 , -175.40507507, -0.26326114])]} +{'AngularVelocity': array([ 0.15424319, -0.02096277, 0.33424577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99955749511719, + 'FR_Wheel_Angle': -30.983190536499023, + 'Location': array([-71.4551239 , 98.69441223, 0.11220598]), + 'Rotation': array([ 1.43950331, 18.71605301, -2.22802734]), + 'Velocity': array([-0.00281455, 0.01602525, 0.00199156]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16228.6318359375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7035.62451172, 27054.79882812, 51.37891388]), + 'frame': 28357, + 'frame_number': 28357, + 'framesequence': 114167, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.1363271512091, + 'timestamp_carla': 963135, + 'timestamp_device': 1833736, + 'timestamp_stream': 963.1363271512091, + 'transform': [array([-58.36517334, 95.28138733, 0.17395568]), + array([ 5.60526276, -175.37911987, -0.25672215])]} +{'AngularVelocity': array([-0.11839943, -0.05839748, -0.04321754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99843978881836, + 'FR_Wheel_Angle': -30.981220245361328, + 'Location': array([-71.45514679, 98.69503784, 0.11220232]), + 'Rotation': array([ 1.43706489, 18.71940422, -2.22402978]), + 'Velocity': array([-0.00069622, -0.00233498, 0.00195216]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16225.3505859375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7043.37744141, 27049.46484375, 50.01979828]), + 'frame': 28358, + 'frame_number': 28358, + 'framesequence': 114171, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.1676915511489, + 'timestamp_carla': 963166, + 'timestamp_device': 1833769, + 'timestamp_stream': 963.1676915511489, + 'transform': [array([-58.35874939, 95.26708984, 0.1713752 ]), + array([ 5.58246374, -175.35389709, -0.24711423])]} +{'AngularVelocity': array([0.23772874, 0.04644582, 0.14045568]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.9930419921875, + 'FR_Wheel_Angle': -30.983375549316406, + 'Location': array([-71.45537567, 98.69657135, 0.11199049]), + 'Rotation': array([ 1.43475628, 18.75969696, -2.22488427]), + 'Velocity': array([-0.00168612, 0.00719107, -0.00060188]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16233.5546875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7051.125 , 27055.64453125, 51.85497284]), + 'frame': 28359, + 'frame_number': 28359, + 'framesequence': 114175, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.1990338489413, + 'timestamp_carla': 963198, + 'timestamp_device': 1833802, + 'timestamp_stream': 963.1990338489413, + 'transform': [array([-58.35253906, 95.25289917, 0.17029567]), + array([ 5.57438326, -175.32969666, -0.24281804])]} +{'AngularVelocity': array([-0.0259652 , -0.03706262, -0.45498407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.9980354309082, + 'FR_Wheel_Angle': -30.98214340209961, + 'Location': array([-71.45539856, 98.69709778, 0.11224958]), + 'Rotation': array([ 1.44012487, 18.76938248, -2.23306298]), + 'Velocity': array([ 0.00338364, -0.01206295, 0.00380576]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4273.42626953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6084.14941406, 15133.3828125 , 105.94799805]), + 'frame': 28360, + 'frame_number': 28360, + 'framesequence': 114178, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29980775713920593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.231757748872, + 'timestamp_carla': 963230, + 'timestamp_device': 1833827, + 'timestamp_stream': 963.231757748872, + 'transform': [array([-58.34495926, 95.2379303 , 0.16832946]), + array([ 5.55762911, -175.2996521 , -0.23551399])]} +{'AngularVelocity': array([0.23399027, 0.00240467, 0.55342376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.996891021728516, + 'FR_Wheel_Angle': -30.983013153076172, + 'Location': array([-71.45539856, 98.69780731, 0.11241441]), + 'Rotation': array([ 1.44340336, 18.78022766, -2.23599267]), + 'Velocity': array([-0.01348204, 0.01111754, 0.00134811]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4272.3837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6085.78320312, 15130.81445312, 106.29236603]), + 'frame': 28361, + 'frame_number': 28361, + 'framesequence': 114183, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29967954754829407, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.2648427523673, + 'timestamp_carla': 963263, + 'timestamp_device': 1833869, + 'timestamp_stream': 963.2648427523673, + 'transform': [array([-58.33627701, 95.22237396, 0.16482498]), + array([ 5.52861452, -175.26449585, -0.22231835])]} +{'AngularVelocity': array([ 0.10900559, -0.00882251, 0.36746505]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99864196777344, + 'FR_Wheel_Angle': -30.982324600219727, + 'Location': array([-71.45539856, 98.69813538, 0.11265322]), + 'Rotation': array([ 1.44903827, 18.78034401, -2.24264526]), + 'Velocity': array([-0.00259898, 0.01745432, 0.00113353]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4270.8525390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6087.79394531, 15127.6484375 , 106.87424469]), + 'frame': 28362, + 'frame_number': 28362, + 'framesequence': 114186, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2921537160873413, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.2979387491941, + 'timestamp_carla': 963296, + 'timestamp_device': 1833894, + 'timestamp_stream': 963.2979387491941, + 'transform': [array([-58.32780075, 95.20697021, 0.16053733]), + array([ 5.49544716, -175.23005676, -0.20590274])]} +{'AngularVelocity': array([-0.03443401, 0.06715611, -0.63058096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.9997673034668, + 'FR_Wheel_Angle': -30.982770919799805, + 'Location': array([-71.45574188, 98.69992828, 0.11207941]), + 'Rotation': array([ 1.43323314, 18.83280182, -2.22686791]), + 'Velocity': array([-0.00255278, 0.0080315 , -0.00413089]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4268.91552734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6090.12304688, 15123.98730469, 107.92139435]), + 'frame': 28363, + 'frame_number': 28363, + 'framesequence': 114190, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2741355895996094, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.3295945487916, + 'timestamp_carla': 963328, + 'timestamp_device': 1833927, + 'timestamp_stream': 963.3295945487916, + 'transform': [array([-58.32244492, 95.19258881, 0.16010547]), + array([ 5.49856138, -175.20974731, -0.20296076])]} +{'AngularVelocity': array([-0.41854697, 0.02102703, 0.16272047]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99370193481445, + 'FR_Wheel_Angle': -30.981916427612305, + 'Location': array([-71.45600128, 98.70173645, 0.11184458]), + 'Rotation': array([ 1.42549455, 18.87520599, -2.21493578]), + 'Velocity': array([-0.0049697 , 0.00648984, -0.00378378]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4267.0673828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6092.38574219, 15120.42578125, 109.21681213]), + 'frame': 28364, + 'frame_number': 28364, + 'framesequence': 114194, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25230875611305237, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.3618173487484, + 'timestamp_carla': 963360, + 'timestamp_device': 1833960, + 'timestamp_stream': 963.3618173487484, + 'transform': [array([-58.31658173, 95.17771149, 0.16151638]), + array([ 5.51323938, -175.18862915, -0.20756473])]} +{'AngularVelocity': array([ 0.27048126, -0.01316763, 0.0225702 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.993839263916016, + 'FR_Wheel_Angle': -30.9820613861084, + 'Location': array([-71.45618439, 98.70233917, 0.11207674]), + 'Rotation': array([ 1.4326731 , 18.91270828, -2.23049927]), + 'Velocity': array([-0.00174078, 0.00176884, 0.00243177]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4266.9580078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6093.79052734, 15118.78320312, 109.44861603]), + 'frame': 28365, + 'frame_number': 28365, + 'framesequence': 114198, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22984100878238678, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.3953448496759, + 'timestamp_carla': 963394, + 'timestamp_device': 1833994, + 'timestamp_stream': 963.3953448496759, + 'transform': [array([-58.31136703, 95.16182709, 0.16414852]), + array([ 5.53666735, -175.1714325 , -0.21704733])]} +{'AngularVelocity': array([-0.02655445, 0.03115594, 0.2940208 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.998355865478516, + 'FR_Wheel_Angle': -30.982994079589844, + 'Location': array([-71.45623016, 98.70334625, 0.11227976]), + 'Rotation': array([ 1.43570566, 18.92737961, -2.22985864]), + 'Velocity': array([-0.00200469, 0.01367565, -0.00163594]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4269.640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6095.51611328, 15119.87988281, 109.07907104]), + 'frame': 28366, + 'frame_number': 28366, + 'framesequence': 114202, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21561327576637268, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.429696649313, + 'timestamp_carla': 963428, + 'timestamp_device': 1834027, + 'timestamp_stream': 963.429696649313, + 'transform': [array([-58.3066864 , 95.14461517, 0.17322582]), + array([ 5.61990643, -175.15771484, -0.2493993 ])]} +{'AngularVelocity': array([-0.18696974, 0.01538843, 0.44921005]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.99843215942383, + 'FR_Wheel_Angle': -30.982467651367188, + 'Location': array([-71.456604 , 98.70595551, 0.11158613]), + 'Rotation': array([ 1.41464818, 18.98408318, -2.20654273]), + 'Velocity': array([-0.00890609, 0.00123361, -0.00208047]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4272.21337890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6096.94628906, 15120.7890625 , 108.32504272]), + 'frame': 28367, + 'frame_number': 28367, + 'framesequence': 114206, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21881771087646484, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.4626904502511, + 'timestamp_carla': 963461, + 'timestamp_device': 1834060, + 'timestamp_stream': 963.4626904502511, + 'transform': [array([-58.29837799, 95.12833405, 0.17666766]), + array([ 5.64364862, -175.12892151, -0.26351526])]} +{'AngularVelocity': array([-0.23154297, -0.04918379, 0.1423613 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.24712371826172, + 'FR_Wheel_Angle': -29.38190460205078, + 'Location': array([-71.45695496, 98.70514679, 0.11218904]), + 'Rotation': array([ 1.43986523, 19.05961609, -2.25167847]), + 'Velocity': array([-0.0008491 , 0.00603817, 0.00071898]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4274.76806640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6098.21728516, 15121.59765625, 105.77037811]), + 'frame': 28368, + 'frame_number': 28368, + 'framesequence': 114210, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22951140999794006, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.4953348524868, + 'timestamp_carla': 963494, + 'timestamp_device': 1834094, + 'timestamp_stream': 963.4953348524868, + 'transform': [array([-58.29201508, 95.11093903, 0.18035598]), + array([ 5.66683006, -175.10757446, -0.27855352])]} +{'AngularVelocity': array([-0.09023511, 0.09997939, 0.37957004]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.6684627532959, + 'FR_Wheel_Angle': -22.5968017578125, + 'Location': array([-71.45696259, 98.70568848, 0.11223558]), + 'Rotation': array([ 1.44272029, 19.07245636, -2.24227858]), + 'Velocity': array([-0.0029802 , 0.01748204, -0.00528266]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4278.02978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6100.58398438, 15123.1015625 , 104.63820648]), + 'frame': 28369, + 'frame_number': 28369, + 'framesequence': 114214, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24113896489143372, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.5278157517314, + 'timestamp_carla': 963526, + 'timestamp_device': 1834127, + 'timestamp_stream': 963.5278157517314, + 'transform': [array([-58.28507614, 95.09303284, 0.18376872]), + array([ 5.68916464, -175.08335876, -0.29242644])]} +{'AngularVelocity': array([ 0.32344189, 0.01256145, -0.23192418]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.328052520751953, + 'FR_Wheel_Angle': -15.582554817199707, + 'Location': array([-71.45720673, 98.70602417, 0.11188734]), + 'Rotation': array([ 1.43469477, 19.11032295, -2.23538208]), + 'Velocity': array([-0.00232185, -0.0099711 , 0.00162691]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4281.02490234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6102.40869141, 15124.26171875, 103.44313049]), + 'frame': 28370, + 'frame_number': 28370, + 'framesequence': 114218, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25027620792388916, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.5604543499649, + 'timestamp_carla': 963559, + 'timestamp_device': 1834160, + 'timestamp_stream': 963.5604543499649, + 'transform': [array([-58.27753448, 95.07498932, 0.18311183]), + array([ 5.67616701, -175.05578613, -0.29171446])]} +{'AngularVelocity': array([-0.4457185 , 0.09355809, 0.03252936]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.995235443115234, + 'FR_Wheel_Angle': -7.429812908172607, + 'Location': array([-71.45737457, 98.70557404, 0.11171594]), + 'Rotation': array([ 1.42974293, 19.1341362 , -2.23031592]), + 'Velocity': array([-0.00038913, 0.0003558 , -0.00742617]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4284.232421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6104.46484375, 15125.56835938, 102.33428192]), + 'frame': 28371, + 'frame_number': 28371, + 'framesequence': 114222, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2509903311729431, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.595025151968, + 'timestamp_carla': 963594, + 'timestamp_device': 1834194, + 'timestamp_stream': 963.595025151968, + 'transform': [array([-58.27026367, 95.05569458, 0.18500514]), + array([ 5.68973827, -175.02966309, -0.29954183])]} +{'AngularVelocity': array([-0.02463643, 0.12342523, -0.41141972]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.8363752961158752, + 'FR_Wheel_Angle': 0.7510722279548645, + 'Location': array([-71.45730591, 98.70478058, 0.11123781]), + 'Rotation': array([ 1.41809058, 19.10683632, -2.21991014]), + 'Velocity': array([ 0.00234966, -0.0192735 , -0.00592836]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4287.61962890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6106.71972656, 15127.00292969, 102.36787415]), + 'frame': 28372, + 'frame_number': 28372, + 'framesequence': 114226, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2462843805551529, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.6270150505006, + 'timestamp_carla': 963626, + 'timestamp_device': 1834227, + 'timestamp_stream': 963.6270150505006, + 'transform': [array([-58.26102448, 95.03740692, 0.1840678 ]), + array([ 5.67887831, -174.99429321, -0.29680672])]} +{'AngularVelocity': array([ 0.00993552, 0.00918811, -0.40808308]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0076902564615011215, + 'FR_Wheel_Angle': 0.005126574542373419, + 'Location': array([-71.45726776, 98.70285034, 0.11122262]), + 'Rotation': array([ 1.41955912, 19.08794403, -2.24404955]), + 'Velocity': array([ 0.00277504, -0.01901909, -0.00036329]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4291.07568359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6108.91259766, 15128.39648438, 101.72614288]), + 'frame': 28373, + 'frame_number': 28373, + 'framesequence': 114230, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2404431253671646, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.6584989503026, + 'timestamp_carla': 963657, + 'timestamp_device': 1834260, + 'timestamp_stream': 963.6584989503026, + 'transform': [array([-58.25371933, 95.01958466, 0.18533859]), + array([ 5.69114542, -174.96737671, -0.30138287])]} +{'AngularVelocity': array([-0.31543893, 0.0787512 , -0.22785915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126474890857935, + 'FR_Wheel_Angle': 0.005126774311065674, + 'Location': array([-71.45713043, 98.70024109, 0.11055517]), + 'Rotation': array([ 1.40025699, 19.03401756, -2.23507714]), + 'Velocity': array([ 0.00137062, -0.01147854, -0.00581019]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4294.92431640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6111.78857422, 15130.22460938, 101.91910553]), + 'frame': 28374, + 'frame_number': 28374, + 'framesequence': 114234, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2357371747493744, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.6939878500998, + 'timestamp_carla': 963693, + 'timestamp_device': 1834294, + 'timestamp_stream': 963.6939878500998, + 'transform': [array([-58.24427032, 94.99930573, 0.18442474]), + array([ 5.68242359, -174.93214417, -0.2985259 ])]} +{'AngularVelocity': array([-0.02674567, -0.05328272, -0.45048681]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126677453517914, + 'FR_Wheel_Angle': 0.0051269386895000935, + 'Location': array([-71.45399475, 98.69884491, 0.11055288]), + 'Rotation': array([ 1.4003799 , 19.0251236 , -2.23895264]), + 'Velocity': array([ 0.00306121, -0.02127948, 0.00233336]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4298.2705078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6114.0234375 , 15131.64550781, 101.53694916]), + 'frame': 28375, + 'frame_number': 28375, + 'framesequence': 114239, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2350047379732132, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.7336398512125, + 'timestamp_carla': 963732, + 'timestamp_device': 1834335, + 'timestamp_stream': 963.7336398512125, + 'transform': [array([-58.23175049, 94.97618103, 0.18700576]), + array([ 5.70441675, -174.88508606, -0.30838183])]} +{'AngularVelocity': array([-0.16164124, 0.11918447, -0.52696371]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126551259309053, + 'FR_Wheel_Angle': 0.005126918200403452, + 'Location': array([-71.45380402, 98.6962204 , 0.11002806]), + 'Rotation': array([ 1.38489592, 18.96766472, -2.22848535]), + 'Velocity': array([ 0.00325565, -0.02494746, -0.00665588]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4302.31494140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6116.88330078, 15133.46386719, 101.73575592]), + 'frame': 28376, + 'frame_number': 28376, + 'framesequence': 114243, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23778803646564484, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.7703172490001, + 'timestamp_carla': 963769, + 'timestamp_device': 1834369, + 'timestamp_stream': 963.7703172490001, + 'transform': [array([-58.22286606, 94.95469666, 0.18619396]), + array([ 5.69541454, -174.85206604, -0.30558673])]} +{'AngularVelocity': array([-0.11455126, 0.02084751, -0.52431536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051265861839056015, + 'FR_Wheel_Angle': 0.005126731004565954, + 'Location': array([-71.45368195, 98.69379425, 0.10978021]), + 'Rotation': array([ 1.37749195, 18.93051338, -2.22576952]), + 'Velocity': array([ 0.00339993, -0.02478589, -0.00168489]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4307.35302734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6120.77539062, 15135.9375 , 100.92230225]), + 'frame': 28377, + 'frame_number': 28377, + 'framesequence': 114248, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24101077020168304, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.8078304491937, + 'timestamp_carla': 963806, + 'timestamp_device': 1834410, + 'timestamp_stream': 963.8078304491937, + 'transform': [array([-58.21372986, 94.93230438, 0.1886629 ]), + array([ 5.71560431, -174.8192749 , -0.31473735])]} +{'AngularVelocity': array([-0.07727506, 0.01760234, -0.41215712]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126534961163998, + 'FR_Wheel_Angle': 0.005126879550516605, + 'Location': array([-71.45346069, 98.69091797, 0.10939344]), + 'Rotation': array([ 1.36642706, 18.86732483, -2.22216821]), + 'Velocity': array([ 0.00266549, -0.01943636, -0.00132457]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4311.41845703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6123.48876953, 15137.66210938, 101.12557983]), + 'frame': 28378, + 'frame_number': 28378, + 'framesequence': 114252, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2419629544019699, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.8444763496518, + 'timestamp_carla': 963843, + 'timestamp_device': 1834444, + 'timestamp_stream': 963.8444763496518, + 'transform': [array([-58.20365143, 94.90991211, 0.19072986]), + array([ 5.7312932 , -174.78234863, -0.32262817])]} +{'AngularVelocity': array([-0.08970869, -0.01936441, -0.15566619]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126478150486946, + 'FR_Wheel_Angle': 0.005126517731696367, + 'Location': array([-71.45319366, 98.68869781, 0.10950033]), + 'Rotation': array([ 1.36824393, 18.82037926, -2.21688843]), + 'Velocity': array([ 0.00103297, -0.00754451, 0.0003297 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16208.779296875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7206.63574219, 26983.25390625, 35.37367249]), + 'frame': 28379, + 'frame_number': 28379, + 'framesequence': 114256, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24042482674121857, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.8784540519118, + 'timestamp_carla': 963877, + 'timestamp_device': 1834477, + 'timestamp_stream': 963.8784540519118, + 'transform': [array([-58.19244385, 94.88878632, 0.18957099]), + array([ 5.71933365, -174.73953247, -0.31869596])]} +{'AngularVelocity': array([ 0.09329141, -0.06221607, -0.34917679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051266225054860115, + 'FR_Wheel_Angle': 0.005126712378114462, + 'Location': array([-71.45284271, 98.68489075, 0.10906705]), + 'Rotation': array([ 1.35993159, 18.72731972, -2.22744775]), + 'Velocity': array([-0.00141746, -0.01621425, 0.00353695]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16200.8408203125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7216.40820312, 26972.1953125 , 33.164711 ]), + 'frame': 28380, + 'frame_number': 28380, + 'framesequence': 114260, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23897825181484222, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.9133185520768, + 'timestamp_carla': 963912, + 'timestamp_device': 1834510, + 'timestamp_stream': 963.9133185520768, + 'transform': [array([-58.18201447, 94.86714935, 0.19103923]), + array([ 5.73360872, -174.70048523, -0.32385677])]} +{'AngularVelocity': array([ 0.01033045, -0.13223498, -0.04030569]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126353818923235, + 'FR_Wheel_Angle': 0.005126851610839367, + 'Location': array([-71.45259857, 98.68260193, 0.10927019]), + 'Rotation': array([ 1.36261582, 18.6837635 , -2.22112989]), + 'Velocity': array([-0.00047674, -0.00224777, 0.00631096]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16208.474609375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7228.9375 , 26976.64453125, 34.24789429]), + 'frame': 28381, + 'frame_number': 28381, + 'framesequence': 114264, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23912473022937775, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.9467975497246, + 'timestamp_carla': 963945, + 'timestamp_device': 1834544, + 'timestamp_stream': 963.9467975497246, + 'transform': [array([-58.17326355, 94.84651947, 0.19092624]), + array([ 5.73455811, -174.66819763, -0.32312059])]} +{'AngularVelocity': array([ 0.20968609, 0.01968103, -0.53082615]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126176867634058, + 'FR_Wheel_Angle': 0.005126298405230045, + 'Location': array([-71.45225525, 98.67922974, 0.10896166]), + 'Rotation': array([ 1.35693312, 18.59837341, -2.22467041]), + 'Velocity': array([ 0.00324334, -0.02447632, 0.0004321 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16203.8994140625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7239.54394531, 26968.94921875, 32.79580688]), + 'frame': 28382, + 'frame_number': 28382, + 'framesequence': 114268, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24009522795677185, + 'throttle_input': 0.2222171425819397, + 'timestamp': 963.9787180498242, + 'timestamp_carla': 963977, + 'timestamp_device': 1834577, + 'timestamp_stream': 963.9787180498242, + 'transform': [array([-58.16466141, 94.82679749, 0.19276798]), + array([ 5.75047922, -174.63667297, -0.3297855 ])]} +{'AngularVelocity': array([-0.11232845, 0.05071992, -0.58616447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126541014760733, + 'FR_Wheel_Angle': 0.005126851610839367, + 'Location': array([-71.45180511, 98.6740799 , 0.1083835 ]), + 'Rotation': array([ 1.34388745, 18.47400856, -2.23016334]), + 'Velocity': array([ 0.00343175, -0.02792972, -0.00308819]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4354.27294921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6140.75830078, 15168.53710938, 99.49820709]), + 'frame': 28383, + 'frame_number': 28383, + 'framesequence': 114272, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24055300652980804, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.0110038518906, + 'timestamp_carla': 964010, + 'timestamp_device': 1834610, + 'timestamp_stream': 964.0110038518906, + 'transform': [array([-58.15565109, 94.80678558, 0.19419166]), + array([ 5.76100492, -174.6035614 , -0.33531275])]} +{'AngularVelocity': array([-0.22214258, 0.033276 , -0.41162041]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00512651214376092, + 'FR_Wheel_Angle': 0.005126745440065861, + 'Location': array([-71.45140839, 98.66962433, 0.10799032]), + 'Rotation': array([ 1.33260393, 18.36929893, -2.22262597]), + 'Velocity': array([ 0.00240591, -0.01987252, -0.00288706]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4352.96875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6142.94677734, 15165.09472656, 98.97437286]), + 'frame': 28384, + 'frame_number': 28384, + 'framesequence': 114276, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23994874954223633, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.0432750508189, + 'timestamp_carla': 964042, + 'timestamp_device': 1834644, + 'timestamp_stream': 964.0432750508189, + 'transform': [array([-58.14609909, 94.78670502, 0.19516422]), + array([ 5.7676301 , -174.56803894, -0.33927321])]} +{'AngularVelocity': array([ 0.20551161, 0.10026893, -0.90495956]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126205272972584, + 'FR_Wheel_Angle': 0.005126702133566141, + 'Location': array([-71.45101166, 98.665802 , 0.10785601]), + 'Rotation': array([ 1.3276726 , 18.27936554, -2.21496606]), + 'Velocity': array([ 0.00515228, -0.04211162, -0.0034593 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4351.546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6145.23535156, 15161.49414062, 98.54084015]), + 'frame': 28385, + 'frame_number': 28385, + 'framesequence': 114280, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.0769146494567, + 'timestamp_carla': 964076, + 'timestamp_device': 1834677, + 'timestamp_stream': 964.0769146494567, + 'transform': [array([-58.13618851, 94.76578522, 0.1959748 ]), + array([ 5.77351093, -174.53129578, -0.34265104])]} +{'AngularVelocity': array([ 0.20400637, 0.18277025, -1.11512184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126222036778927, + 'FR_Wheel_Angle': 0.005126766860485077, + 'Location': array([-71.45064545, 98.66131592, 0.1073979 ]), + 'Rotation': array([ 1.31637549, 18.1720047 , -2.21487474]), + 'Velocity': array([ 0.00623184, -0.05173415, -0.00736631]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4349.90576171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6147.67822266, 15157.65039062, 98.23303223]), + 'frame': 28386, + 'frame_number': 28386, + 'framesequence': 114284, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.108768850565, + 'timestamp_carla': 964107, + 'timestamp_device': 1834710, + 'timestamp_stream': 964.108768850565, + 'transform': [array([-58.12656021, 94.74597168, 0.19515896]), + array([ 5.76629114, -174.49505615, -0.33982477])]} +{'AngularVelocity': array([ 0.12402217, 0.112091 , -0.94589502]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00512644462287426, + 'FR_Wheel_Angle': 0.005126514937728643, + 'Location': array([-71.45024872, 98.65637207, 0.10681692]), + 'Rotation': array([ 1.30213451, 18.05353546, -2.21481347]), + 'Velocity': array([ 0.00529451, -0.04402334, -0.00456648]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4349.25537109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6150.29199219, 15154.69921875, 97.96359253]), + 'frame': 28387, + 'frame_number': 28387, + 'framesequence': 114288, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.1407675519586, + 'timestamp_carla': 964139, + 'timestamp_device': 1834744, + 'timestamp_stream': 964.1407675519586, + 'transform': [array([-58.11824417, 94.72623444, 0.19691619]), + array([ 5.78279305, -174.4646759 , -0.34606156])]} +{'AngularVelocity': array([-0.06519677, 0.2164751 , -0.95847124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051260581240057945, + 'FR_Wheel_Angle': 0.005126237869262695, + 'Location': array([-71.44984436, 98.65029144, 0.10591989]), + 'Rotation': array([ 1.2796905 , 17.9093895 , -2.21313477]), + 'Velocity': array([ 0.00492657, -0.04524286, -0.01053379]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4353.388671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6153.30224609, 15156.61523438, 98.16255951]), + 'frame': 28388, + 'frame_number': 28388, + 'framesequence': 114291, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.1718771494925, + 'timestamp_carla': 964170, + 'timestamp_device': 1834769, + 'timestamp_stream': 964.1718771494925, + 'transform': [array([-58.10899353, 94.70689392, 0.19816262]), + array([ 5.79221869, -174.4303894 , -0.35085198])]} +{'AngularVelocity': array([-0.25536951, 0.21283069, -1.26316512]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125811789184809, + 'FR_Wheel_Angle': 0.005126326344907284, + 'Location': array([-71.44929504, 98.64224243, 0.10484964]), + 'Rotation': array([ 1.25190532, 17.7192955 , -2.20642066]), + 'Velocity': array([ 0.00643509, -0.06014626, -0.01141644]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4357.20068359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6155.89306641, 15158.26074219, 97.63948059]), + 'frame': 28389, + 'frame_number': 28389, + 'framesequence': 114295, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.2047254517674, + 'timestamp_carla': 964203, + 'timestamp_device': 1834802, + 'timestamp_stream': 964.2047254517674, + 'transform': [array([-58.0993309 , 94.68643951, 0.19925137]), + array([ 5.8000598 , -174.39471436, -0.35524404])]} +{'AngularVelocity': array([ 0.01509813, 0.12134288, -1.02577984]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125740077346563, + 'FR_Wheel_Angle': 0.005126106087118387, + 'Location': array([-71.44844818, 98.63459015, 0.10355226]), + 'Rotation': array([ 1.21924329, 17.53773308, -2.2024231 ]), + 'Velocity': array([ 0.0050842 , -0.04853588, -0.00557192]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4361.203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6158.79785156, 15160.10742188, 97.23284149]), + 'frame': 28390, + 'frame_number': 28390, + 'framesequence': 114299, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.2380066514015, + 'timestamp_carla': 964237, + 'timestamp_device': 1834835, + 'timestamp_stream': 964.2380066514015, + 'transform': [array([-58.08942795, 94.66564178, 0.20039982]), + array([ 5.80869293, -174.35820007, -0.35981968])]} +{'AngularVelocity': array([-0.13570195, 0.13323914, -1.26740491]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125786177814007, + 'FR_Wheel_Angle': 0.005125970114022493, + 'Location': array([-71.44782257, 98.62432098, 0.10217313]), + 'Rotation': array([ 1.18535876, 17.29309464, -2.20251465]), + 'Velocity': array([ 0.00619556, -0.06007509, -0.00696098]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4365.40283203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6161.81884766, 15162.02734375, 96.85322571]), + 'frame': 28391, + 'frame_number': 28391, + 'framesequence': 114303, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.271866351366, + 'timestamp_carla': 964270, + 'timestamp_device': 1834869, + 'timestamp_stream': 964.271866351366, + 'transform': [array([-58.07930374, 94.64434052, 0.2016423 ]), + array([ 5.81820774, -174.32099915, -0.36473337])]} +{'AngularVelocity': array([-0.25708783, 0.05917401, -1.11605811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00512609351426363, + 'FR_Wheel_Angle': 0.005126040894538164, + 'Location': array([-71.44728088, 98.6160202 , 0.1013669 ]), + 'Rotation': array([ 1.15972507, 17.10157776, -2.17535448]), + 'Velocity': array([ 0.00540695, -0.05328776, -0.00404671]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4369.69580078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6164.91748047, 15163.99902344, 96.45713806]), + 'frame': 28392, + 'frame_number': 28392, + 'framesequence': 114307, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.304692748934, + 'timestamp_carla': 964303, + 'timestamp_device': 1834902, + 'timestamp_stream': 964.304692748934, + 'transform': [array([-58.06903839, 94.62351227, 0.20277943]), + array([ 5.82678604, -174.28292847, -0.3691873 ])]} +{'AngularVelocity': array([-0.14794159, 0.14927818, -1.31881881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125660449266434, + 'FR_Wheel_Angle': 0.005125890951603651, + 'Location': array([-71.44670105, 98.60701752, 0.1006225 ]), + 'Rotation': array([ 1.13984919, 16.88809776, -2.16809106]), + 'Velocity': array([ 0.00599495, -0.06255173, -0.00776686]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4374.083984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6168.07958984, 15166.0078125 , 96.03259277]), + 'frame': 28393, + 'frame_number': 28393, + 'framesequence': 114311, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.3362755514681, + 'timestamp_carla': 964335, + 'timestamp_device': 1834935, + 'timestamp_stream': 964.3362755514681, + 'transform': [array([-58.0586853 , 94.6033783 , 0.20355029]), + array([ 5.83248281, -174.24423218, -0.37222773])]} +{'AngularVelocity': array([-0.0646507 , 0.09196631, -1.37576342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125658120959997, + 'FR_Wheel_Angle': 0.005125894211232662, + 'Location': array([-71.44604492, 98.59550476, 0.09949651]), + 'Rotation': array([ 1.1098305 , 16.61554337, -2.15719581]), + 'Velocity': array([ 0.00608959, -0.06508704, -0.00462927]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4378.4833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6171.31542969, 15168.06542969, 95.64573669]), + 'frame': 28394, + 'frame_number': 28394, + 'framesequence': 114315, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.3682251498103, + 'timestamp_carla': 964367, + 'timestamp_device': 1834969, + 'timestamp_stream': 964.3682251498103, + 'transform': [array([-58.0486908 , 94.58306122, 0.2042987 ]), + array([ 5.83858871, -174.20718384, -0.37514651])]} +{'AngularVelocity': array([-0.00766886, 0.05172407, -1.46118116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125619005411863, + 'FR_Wheel_Angle': 0.005125895608216524, + 'Location': array([-71.44527435, 98.58357239, 0.09890261]), + 'Rotation': array([ 1.09482467, 16.32976151, -2.15539575]), + 'Velocity': array([ 0.0062624 , -0.06896846, -0.00249603]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4382.85009765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6174.59765625, 15170.15039062, 95.37265015]), + 'frame': 28395, + 'frame_number': 28395, + 'framesequence': 114319, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.3999111503363, + 'timestamp_carla': 964398, + 'timestamp_device': 1835002, + 'timestamp_stream': 964.3999111503363, + 'transform': [array([-58.03880692, 94.56292725, 0.20522629]), + array([ 5.84631395, -174.17060852, -0.37867928])]} +{'AngularVelocity': array([ 3.75820469e-04, 1.72226075e-02, -1.44935703e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125630181282759, + 'FR_Wheel_Angle': 0.00512588769197464, + 'Location': array([-71.4446106 , 98.5735321 , 0.09867281]), + 'Rotation': array([ 1.08940148, 16.08846855, -2.15649414]), + 'Velocity': array([ 0.00602215, -0.06837303, -0.00083017]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4387.14306640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6177.74804688, 15172.15429688, 95.10758972]), + 'frame': 28396, + 'frame_number': 28396, + 'framesequence': 114323, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.4333159513772, + 'timestamp_carla': 964432, + 'timestamp_device': 1835035, + 'timestamp_stream': 964.4333159513772, + 'transform': [array([-58.02871323, 94.54169464, 0.20650394]), + array([ 5.85658646, -174.13362122, -0.38362586])]} +{'AngularVelocity': array([-0.00211808, 0.01156308, -1.47874045]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125618539750576, + 'FR_Wheel_Angle': 0.005125859752297401, + 'Location': array([-7.14439545e+01, 9.85632324e+01, 9.85629857e-02]), + 'Rotation': array([ 1.08655322, 15.84114265, -2.15661645]), + 'Velocity': array([ 0.00585373, -0.06978615, -0.00057217]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4647.57958984375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6207.05957031, 15428.96972656, 93.10922241]), + 'frame': 28397, + 'frame_number': 28397, + 'framesequence': 114327, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.4678147509694, + 'timestamp_carla': 964466, + 'timestamp_device': 1835069, + 'timestamp_stream': 964.4678147509694, + 'transform': [array([-58.01817703, 94.5195694 , 0.20822029]), + array([ 5.86988497, -174.09519958, -0.39029202])]} +{'AngularVelocity': array([-0.00969847, 0.00893796, -1.46730936]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125627387315035, + 'FR_Wheel_Angle': 0.005125868134200573, + 'Location': array([-7.14433517e+01, 9.85533752e+01, 9.85377654e-02]), + 'Rotation': array([ 1.08577466, 15.60424614, -2.15594506]), + 'Velocity': array([ 0.00560095, -0.06901308, -0.00047129]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4649.896484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6210.18652344, 15428.89453125, 92.67106628]), + 'frame': 28398, + 'frame_number': 28398, + 'framesequence': 114331, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.4993907511234, + 'timestamp_carla': 964498, + 'timestamp_device': 1835102, + 'timestamp_stream': 964.4993907511234, + 'transform': [array([-58.00664902, 94.49900055, 0.20916878]), + array([ 5.87610722, -174.05181885, -0.39410067])]} +{'AngularVelocity': array([ 0.00256335, -0.00731889, -1.44991314]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125641357153654, + 'FR_Wheel_Angle': 0.005125878378748894, + 'Location': array([-7.14427567e+01, 9.85431061e+01, 9.85054150e-02]), + 'Rotation': array([ 1.08500278, 15.35739803, -2.1560061 ]), + 'Velocity': array([ 0.00522301, -0.0683924 , 0.00035277]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4652.31005859375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6213.44433594, 15428.81347656, 92.08570099]), + 'frame': 28399, + 'frame_number': 28399, + 'framesequence': 114335, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.5341343507171, + 'timestamp_carla': 964533, + 'timestamp_device': 1835135, + 'timestamp_stream': 964.5341343507171, + 'transform': [array([-57.99398422, 94.47638702, 0.20966186]), + array([ 5.8787365 , -174.00442505, -0.3964338 ])]} +{'AngularVelocity': array([-0.00277895, 0.00342357, -1.47626007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125613883137703, + 'FR_Wheel_Angle': 0.005125882104039192, + 'Location': array([-7.14422150e+01, 9.85330124e+01, 9.84898955e-02]), + 'Rotation': array([ 1.08456564, 15.1147995 , -2.15579247]), + 'Velocity': array([ 0.00504702, -0.0694469 , -0.00016214]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4654.6044921875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6217.08935547, 15428.7265625 , 91.74720001]), + 'frame': 28400, + 'frame_number': 28400, + 'framesequence': 114339, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.5677630491555, + 'timestamp_carla': 964566, + 'timestamp_device': 1835169, + 'timestamp_stream': 964.5677630491555, + 'transform': [array([-57.98225403, 94.454422 , 0.21069363]), + array([ 5.88767719, -173.96109009, -0.40033665])]} +{'AngularVelocity': array([-1.21331902e-03, 6.50316011e-03, -1.48236942e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125613417476416, + 'FR_Wheel_Angle': 0.005125867202877998, + 'Location': array([-7.14417191e+01, 9.85228043e+01, 9.84757021e-02]), + 'Rotation': array([ 1.08421731, 14.86941814, -2.15588379]), + 'Velocity': array([ 0.00470865, -0.06998401, -0.00031208]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4431.19482421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6197.29736328, 15203.95507812, 93.08187103]), + 'frame': 28401, + 'frame_number': 28401, + 'framesequence': 114343, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.601899150759, + 'timestamp_carla': 964600, + 'timestamp_device': 1835202, + 'timestamp_stream': 964.601899150759, + 'transform': [array([-57.97045898, 94.43200684, 0.21226791]), + array([ 5.90060711, -173.91778564, -0.4062978 ])]} +{'AngularVelocity': array([ 6.17971993e-04, -4.27061552e-03, -1.45929050e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051256343722343445, + 'FR_Wheel_Angle': 0.0051258634775877, + 'Location': array([-7.14412613e+01, 9.85126419e+01, 9.84681845e-02]), + 'Rotation': array([ 1.0840261 , 14.62525272, -2.15594482]), + 'Velocity': array([ 0.00437857, -0.06885753, 0.00020229]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4428.9912109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6200.27636719, 15199.26757812, 92.77728271]), + 'frame': 28402, + 'frame_number': 28402, + 'framesequence': 114347, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.6352127492428, + 'timestamp_carla': 964634, + 'timestamp_device': 1835235, + 'timestamp_stream': 964.6352127492428, + 'transform': [array([-57.95876694, 94.40988922, 0.21402396]), + array([ 5.9140625 , -173.87489319, -0.41299626])]} +{'AngularVelocity': array([ 1.83732074e-03, 7.32377637e-04, -1.47487783e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125618074089289, + 'FR_Wheel_Angle': 0.0051258634775877, + 'Location': array([-7.14408417e+01, 9.85023575e+01, 9.84510556e-02]), + 'Rotation': array([ 1.08360946, 14.37814331, -2.15615869]), + 'Velocity': array([ 4.06570407e-03, -6.98590204e-02, -4.09948807e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4426.83056640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6203.25927734, 15194.578125 , 92.3068924 ]), + 'frame': 28403, + 'frame_number': 28403, + 'framesequence': 114351, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.6703952513635, + 'timestamp_carla': 964669, + 'timestamp_device': 1835269, + 'timestamp_stream': 964.6703952513635, + 'transform': [array([-57.94579315, 94.38628387, 0.21576701]), + array([ 5.92608356, -173.82705688, -0.41996992])]} +{'AngularVelocity': array([ 6.95238530e-04, -5.27409324e-03, -1.46833205e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125628784298897, + 'FR_Wheel_Angle': 0.005125872325152159, + 'Location': array([-7.14404602e+01, 9.84920578e+01, 9.84445736e-02]), + 'Rotation': array([ 1.08349335, 14.13048744, -2.15625 ]), + 'Velocity': array([ 0.00382336, -0.06927586, 0.00022279]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4425.03076171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6206.25537109, 15190.27539062, 91.77714539]), + 'frame': 28404, + 'frame_number': 28404, + 'framesequence': 114355, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.7054053507745, + 'timestamp_carla': 964704, + 'timestamp_device': 1835302, + 'timestamp_stream': 964.7054053507745, + 'transform': [array([-57.9325676 , 94.36252594, 0.2173648 ]), + array([ 5.93714857, -173.77819824, -0.42636043])]} +{'AngularVelocity': array([-4.22751327e-04, 2.08182679e-03, -1.48513699e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125610623508692, + 'FR_Wheel_Angle': 0.005125891417264938, + 'Location': array([-7.14401321e+01, 9.84817581e+01, 9.84418690e-02]), + 'Rotation': array([ 1.08337724, 13.88327694, -2.15625024]), + 'Velocity': array([ 3.53263854e-03, -7.01242983e-02, -9.98461255e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4430.3955078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6210.39648438, 15192.90820312, 91.17203522]), + 'frame': 28405, + 'frame_number': 28405, + 'framesequence': 114359, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.7393429502845, + 'timestamp_carla': 964738, + 'timestamp_device': 1835335, + 'timestamp_stream': 964.7393429502845, + 'transform': [array([-57.91969681, 94.33932495, 0.21885662]), + array([ 5.94811106, -173.73062134, -0.43219823])]} +{'AngularVelocity': array([ 1.12353940e-03, -4.60057240e-03, -1.45042896e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125637631863356, + 'FR_Wheel_Angle': 0.005125915165990591, + 'Location': array([-71.43983459, 98.4716568 , 0.09847482]), + 'Rotation': array([ 1.08408761, 13.64070034, -2.15591407]), + 'Velocity': array([ 0.00317898, -0.0684818 , 0.0002168 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4435.84765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6214.63085938, 15195.59960938, 90.61234283]), + 'frame': 28406, + 'frame_number': 28406, + 'framesequence': 114363, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23971068859100342, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.7732450515032, + 'timestamp_carla': 964772, + 'timestamp_device': 1835369, + 'timestamp_stream': 964.7732450515032, + 'transform': [array([-57.90671921, 94.31600189, 0.22026385]), + array([ 5.95847225, -173.68263245, -0.43772927])]} +{'AngularVelocity': array([ 0.42035753, -0.20000832, -1.43897343]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125893745571375, + 'FR_Wheel_Angle': 0.005126033443957567, + 'Location': array([-71.43943024, 98.46292114, 0.09933523]), + 'Rotation': array([ 1.10887432, 13.42516994, -2.17306566]), + 'Velocity': array([ 0.00341043, -0.0668366 , 0.01025107]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4441.17529296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6218.75976562, 15198.22460938, 90.09793091]), + 'frame': 28407, + 'frame_number': 28407, + 'framesequence': 114368, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23802606761455536, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.8085753507912, + 'timestamp_carla': 964807, + 'timestamp_device': 1835410, + 'timestamp_stream': 964.8085753507912, + 'transform': [array([-57.89287567, 94.29154205, 0.22174007]), + array([ 5.96927786, -173.63146973, -0.44362974])]} +{'AngularVelocity': array([ 0.13099384, -0.15731582, -0.89297718]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125919356942177, + 'FR_Wheel_Angle': 0.005126189906150103, + 'Location': array([-71.43903351, 98.45471191, 0.10026647]), + 'Rotation': array([ 1.1308949 , 13.2283535 , -2.16909766]), + 'Velocity': array([ 0.00204218, -0.04193138, 0.00761872]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4446.54638671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6222.93066406, 15200.87597656, 89.60566711]), + 'frame': 28408, + 'frame_number': 28408, + 'framesequence': 114372, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22471390664577484, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.843143850565, + 'timestamp_carla': 964842, + 'timestamp_device': 1835444, + 'timestamp_stream': 964.843143850565, + 'transform': [array([-57.87971878, 94.26740265, 0.22369862]), + array([ 5.98531485, -173.58355713, -0.45106789])]} +{'AngularVelocity': array([-0.21958078, -0.00472976, -1.12626362]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126178730279207, + 'FR_Wheel_Angle': 0.0051259747706353664, + 'Location': array([-71.4388504 , 98.44609833, 0.1004466 ]), + 'Rotation': array([ 1.13465834, 13.02208328, -2.1663518 ]), + 'Velocity': array([ 0.00189419, -0.05368558, -0.00010965]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4452.2431640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6227.38378906, 15203.70605469, 89.07850647]), + 'frame': 28409, + 'frame_number': 28409, + 'framesequence': 114376, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.20224617421627045, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.8759156502783, + 'timestamp_carla': 964874, + 'timestamp_device': 1835477, + 'timestamp_stream': 964.8759156502783, + 'transform': [array([-57.86845016, 94.24432373, 0.2269987 ]), + array([ 6.01454115, -173.5440979 , -0.4631218 ])]} +{'AngularVelocity': array([-0.04964096, 0.11626011, -1.37632728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125667434185743, + 'FR_Wheel_Angle': 0.005125935189425945, + 'Location': array([-71.43888092, 98.43662262, 0.09978437]), + 'Rotation': array([ 1.11610746, 12.79798126, -2.15597558]), + 'Velocity': array([ 0.00155216, -0.06532889, -0.00556412]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4457.7216796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6231.57617188, 15206.37207031, 88.42687988]), + 'frame': 28410, + 'frame_number': 28410, + 'framesequence': 114380, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17803889513015747, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.9110706523061, + 'timestamp_carla': 964910, + 'timestamp_device': 1835510, + 'timestamp_stream': 964.9110706523061, + 'transform': [array([-57.8573761 , 94.21977997, 0.23672026]), + array([ 6.10285568, -173.50865173, -0.49855426])]} +{'AngularVelocity': array([-0.01511996, 0.07173102, -1.44617105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125624593347311, + 'FR_Wheel_Angle': 0.005125883966684341, + 'Location': array([-71.43894196, 98.42689514, 0.09916715]), + 'Rotation': array([ 1.10020685, 12.56587601, -2.1527102 ]), + 'Velocity': array([ 0.0015156 , -0.0683011 , -0.00339251]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4462.58544921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6235.07373047, 15208.59570312, 87.40093994]), + 'frame': 28411, + 'frame_number': 28411, + 'framesequence': 114384, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15701773762702942, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.9446877501905, + 'timestamp_carla': 964943, + 'timestamp_device': 1835543, + 'timestamp_stream': 964.9446877501905, + 'transform': [array([-57.84878922, 94.19722748, 0.24820568]), + array([ 6.20312262, -173.48526001, -0.54125595])]} +{'AngularVelocity': array([ 0.00367614, 0.03708069, -1.45914125]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125623662024736, + 'FR_Wheel_Angle': 0.005125859286636114, + 'Location': array([-71.43897247, 98.41673279, 0.09879599]), + 'Rotation': array([ 1.09133434, 12.32255173, -2.15396142]), + 'Velocity': array([ 0.00131151, -0.06910408, -0.00174538]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12638.1103515625, + 'focus_actor_name': 'BP_RepSpline5', + 'focus_actor_pt': array([-7.16957959e+03, 2.33278320e+04, 1.37574768e+01]), + 'frame': 28412, + 'frame_number': 28412, + 'framesequence': 114388, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15511338412761688, + 'throttle_input': 0.2222171425819397, + 'timestamp': 964.9779348522425, + 'timestamp_carla': 964976, + 'timestamp_device': 1835577, + 'timestamp_stream': 964.9779348522425, + 'transform': [array([-57.84103012, 94.17544556, 0.26325744]), + array([ 6.32396936, -173.46818542, -0.59910619])]} +{'AngularVelocity': array([-1.01284229e-03, 1.38700856e-02, -1.45522952e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125636700540781, + 'FR_Wheel_Angle': 0.005125907249748707, + 'Location': array([-71.43901062, 98.4066391 , 0.09863535]), + 'Rotation': array([ 1.0875231 , 12.08019829, -2.15475488]), + 'Velocity': array([ 0.00127028, -0.06867295, -0.00065843]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12624.0078125, + 'focus_actor_name': 'Town05_TerrainNode_4406', + 'focus_actor_pt': array([-7.17391992e+03, 2.33108770e+04, 4.34137726e+00]), + 'frame': 28413, + 'frame_number': 28413, + 'framesequence': 114392, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16436047852039337, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.0109846517444, + 'timestamp_carla': 965009, + 'timestamp_device': 1835610, + 'timestamp_stream': 965.0109846517444, + 'transform': [array([-57.83395386, 94.15643311, 0.26105368]), + array([ 6.34191895, -173.44863892, -0.5919106 ])]} +{'AngularVelocity': array([ 0.0026317 , 0.01155011, -1.4814378 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125601310282946, + 'FR_Wheel_Angle': 0.005125895142555237, + 'Location': array([-71.43906403, 98.39653778, 0.09855288]), + 'Rotation': array([ 1.08554244, 11.83774948, -2.15512085]), + 'Velocity': array([ 0.00100161, -0.06991181, -0.00054438]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 11140.248046875, + 'focus_actor_name': 'Town05_TerrainNode_4406', + 'focus_actor_pt': array([-7.00839209e+03, 2.18342422e+04, 6.84482574e+00]), + 'frame': 28414, + 'frame_number': 28414, + 'framesequence': 114396, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.177910715341568, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.0451747514307, + 'timestamp_carla': 965044, + 'timestamp_device': 1835643, + 'timestamp_stream': 965.0451747514307, + 'transform': [array([-57.82551956, 94.13861084, 0.25427306]), + array([ 6.35843468, -173.4203949 , -0.56472391])]} +{'AngularVelocity': array([ 3.57491022e-04, 3.97299230e-03, -1.46616673e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125627387315035, + 'FR_Wheel_Angle': 0.005125890020281076, + 'Location': array([-71.43914795, 98.38641357, 0.09852022]), + 'Rotation': array([ 1.08483207, 11.59428406, -2.15554833]), + 'Velocity': array([ 0.00070295, -0.06942116, -0.00018413]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 11287.576171875, + 'focus_actor_name': 'Town05_TerrainNode_4406', + 'focus_actor_pt': array([-7.02873438e+03, 2.19782812e+04, 6.60739136e+00]), + 'frame': 28415, + 'frame_number': 28415, + 'framesequence': 114400, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18931852281093597, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.0811900496483, + 'timestamp_carla': 965080, + 'timestamp_device': 1835677, + 'timestamp_stream': 965.0811900496483, + 'transform': [array([-57.81702042, 94.11981964, 0.24739994]), + array([ 6.36833811, -173.39306641, -0.53789628])]} +{'AngularVelocity': array([ 1.46459520e-03, 5.28746005e-03, -1.47695231e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125619005411863, + 'FR_Wheel_Angle': 0.005125890951603651, + 'Location': array([-71.43927765, 98.3762207 , 0.09849691]), + 'Rotation': array([ 1.08425832, 11.34985638, -2.15560961]), + 'Velocity': array([-4.79698174e-05, -6.99196532e-02, -2.45655770e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 11928.9091796875, + 'focus_actor_name': 'Town05_TerrainNode_4406', + 'focus_actor_pt': array([-7.10760693e+03, 2.26129531e+04, 5.54376221e+00]), + 'frame': 28416, + 'frame_number': 28416, + 'framesequence': 114404, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19276101887226105, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.1138631515205, + 'timestamp_carla': 965112, + 'timestamp_device': 1835710, + 'timestamp_stream': 965.1138631515205, + 'transform': [array([-57.81206894, 94.10379028, 0.24172409]), + array([ 6.39204597, -173.37823486, -0.51347804])]} +{'AngularVelocity': array([ 1.05538356, 0.85637456, -1.47309899]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051254951395094395, + 'FR_Wheel_Angle': 0.0051259384490549564, + 'Location': array([-7.14404144e+01, 9.83658981e+01, 9.44009200e-02]), + 'Rotation': array([ 1.03009498, 11.04980564, -2.37225342]), + 'Velocity': array([-0.00216759, -0.06684775, -0.04045596]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12622.166015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-7.19284180e+03, 2.32990586e+04, 4.52656555e+00]), + 'frame': 28417, + 'frame_number': 28417, + 'framesequence': 114408, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18832972645759583, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.1483515501022, + 'timestamp_carla': 965147, + 'timestamp_device': 1835743, + 'timestamp_stream': 965.1483515501022, + 'transform': [array([-57.79854202, 94.08719635, 0.23253345]), + array([ 6.35350323, -173.32258606, -0.47775805])]} +{'AngularVelocity': array([-0.51451492, -0.33312133, -1.40173483]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051257717423141, + 'FR_Wheel_Angle': 0.0051260171458125114, + 'Location': array([-7.14404526e+01, 9.83534470e+01, 9.53565016e-02]), + 'Rotation': array([ 1.03206885, 10.77584934, -2.27246118]), + 'Velocity': array([ 0.00062059, -0.06769928, 0.01583813]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4511.6845703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6252.04150391, 15242.04101562, 82.02052307]), + 'frame': 28418, + 'frame_number': 28418, + 'framesequence': 114412, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1814996898174286, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.1809745505452, + 'timestamp_carla': 965179, + 'timestamp_device': 1835777, + 'timestamp_stream': 965.1809745505452, + 'transform': [array([-57.79021454, 94.07217407, 0.23772506]), + array([ 6.41702366, -173.29251099, -0.494371 ])]} +{'AngularVelocity': array([-0.23089863, -0.16629054, -1.46742511]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051256390288472176, + 'FR_Wheel_Angle': 0.005125941708683968, + 'Location': array([-7.14402847e+01, 9.83429642e+01, 9.71795842e-02]), + 'Rotation': array([ 1.06291401, 10.53887463, -2.20761132]), + 'Velocity': array([-0.00013216, -0.06978349, 0.00796327]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4508.2236328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6255.57910156, 15236.4765625 , 84.89072418]), + 'frame': 28419, + 'frame_number': 28419, + 'framesequence': 114416, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1751457303762436, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.2144802510738, + 'timestamp_carla': 965213, + 'timestamp_device': 1835810, + 'timestamp_stream': 965.2144802510738, + 'transform': [array([-57.78245163, 94.0568924 , 0.2328826 ]), + array([ 6.3881526 , -173.26538086, -0.47653198])]} +{'AngularVelocity': array([-0.09488922, -0.05181591, -1.52513909]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051255966536700726, + 'FR_Wheel_Angle': 0.005125872325152159, + 'Location': array([-7.14404297e+01, 9.83322754e+01, 9.79588479e-02]), + 'Rotation': array([ 1.07578886, 10.28872871, -2.1786809 ]), + 'Velocity': array([-0.00076134, -0.07238451, 0.00251222]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4506.56396484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6257.734375 , 15233.0859375 , 83.51312256]), + 'frame': 28420, + 'frame_number': 28420, + 'framesequence': 114420, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17382733523845673, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.2481665499508, + 'timestamp_carla': 965247, + 'timestamp_device': 1835843, + 'timestamp_stream': 965.2481665499508, + 'transform': [array([-57.76815414, 94.04213715, 0.22275512]), + array([ 6.30361557, -173.20280457, -0.43752208])]} +{'AngularVelocity': array([-0.04854431, -0.02024047, -1.47981501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125623196363449, + 'FR_Wheel_Angle': 0.0051258634775877, + 'Location': array([-7.14406891e+01, 9.83223877e+01, 9.82680321e-02]), + 'Rotation': array([ 1.08076811, 10.05414104, -2.1664741 ]), + 'Velocity': array([-0.0011009 , -0.07011844, 0.00097433]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4505.6474609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6259.43310547, 15230.4140625 , 84.94764709]), + 'frame': 28421, + 'frame_number': 28421, + 'framesequence': 114425, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1763908863067627, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.281869251281, + 'timestamp_carla': 965280, + 'timestamp_device': 1835885, + 'timestamp_stream': 965.281869251281, + 'transform': [array([-57.76155472, 94.02720642, 0.23929909]), + array([ 6.43961143, -173.18365479, -0.49580517])]} +{'AngularVelocity': array([-0.02046087, -0.00499432, -1.48956299]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051256101578474045, + 'FR_Wheel_Angle': 0.005125869531184435, + 'Location': array([-71.44107819, 98.3120575 , 0.09836344]), + 'Rotation': array([ 1.0818882 , 9.80718613, -2.16101146]), + 'Velocity': array([-0.00145189, -0.07049096, 0.00023617]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4504.12060546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6263.83300781, 15226.87695312, 88.20165253]), + 'frame': 28422, + 'frame_number': 28422, + 'framesequence': 114429, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17996154725551605, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.3173817507923, + 'timestamp_carla': 965316, + 'timestamp_device': 1835918, + 'timestamp_stream': 965.3173817507923, + 'transform': [array([-57.75204849, 94.01264191, 0.23613837]), + array([ 6.41614962, -173.1506958 , -0.48537189])]} +{'AngularVelocity': array([-8.52055382e-03, -6.71873160e-04, -1.49589610e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125605501234531, + 'FR_Wheel_Angle': 0.005125859286636114, + 'Location': array([-71.44151306, 98.30172729, 0.09839136]), + 'Rotation': array([ 1.08206582, 9.55939865, -2.15872216]), + 'Velocity': array([-1.78155897e-03, -7.07267150e-02, 4.78970978e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4507.150390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6266. , 15228.25390625, 83.43908691]), + 'frame': 28423, + 'frame_number': 28423, + 'framesequence': 114433, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18270821869373322, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.3515404500067, + 'timestamp_carla': 965350, + 'timestamp_device': 1835952, + 'timestamp_stream': 965.3515404500067, + 'transform': [array([-57.740345 , 93.9985733 , 0.22818519]), + array([ 6.34256792, -173.09942627, -0.45521048])]} +{'AngularVelocity': array([-2.00890261e-03, -1.09619861e-04, -1.48558152e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005125612020492554, + 'FR_Wheel_Angle': 0.005125863943248987, + 'Location': array([-71.44200897, 98.29137421, 0.09840295]), + 'Rotation': array([ 1.08213413, 9.31097698, -2.15777588]), + 'Velocity': array([-2.05074297e-03, -7.04625323e-02, -1.93667402e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4510.6513671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6268.72460938, 15229.98730469, 84.234375 ]), + 'frame': 28424, + 'frame_number': 28424, + 'framesequence': 114437, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18190252780914307, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.3843195512891, + 'timestamp_carla': 965383, + 'timestamp_device': 1835985, + 'timestamp_stream': 965.3843195512891, + 'transform': [array([-57.73591614, 93.9833374 , 0.24193409]), + array([ 6.44816971, -173.09014893, -0.50487381])]} +{'AngularVelocity': array([ 7.78206205, 3.09483433, -3.17953134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005123540293425322, + 'FR_Wheel_Angle': 0.005122647620737553, + 'Location': array([-7.14446716e+01, 9.82766647e+01, 9.04969946e-02]), + 'Rotation': array([ 0.98081511, 8.85129452, -2.59158373]), + 'Velocity': array([-0.01382881, -0.12932764, -0.15981314]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4515.31103515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6273.06835938, 15232.74804688, 86.72486877]), + 'frame': 28425, + 'frame_number': 28425, + 'framesequence': 114441, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17996154725551605, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.4179029501975, + 'timestamp_carla': 965416, + 'timestamp_device': 1836018, + 'timestamp_stream': 965.4179029501975, + 'transform': [array([-57.72460175, 93.96797943, 0.23620266]), + array([ 6.39378071, -173.04670715, -0.4852283 ])]} +{'AngularVelocity': array([-3.30851436, 2.43322539, 0.53623235]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00512202363461256, + 'FR_Wheel_Angle': 0.0051262713968753815, + 'Location': array([-7.14603806e+01, 9.82743225e+01, 2.84979809e-02]), + 'Rotation': array([ 0.04664336, 8.10103226, -5.41824627]), + 'Velocity': array([ 0.00049908, -0.00140375, -0.12478513]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4517.708984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6274.31738281, 15233.54101562, 82.66120911]), + 'frame': 28426, + 'frame_number': 28426, + 'framesequence': 114445, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17862483859062195, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.4508012495935, + 'timestamp_carla': 965449, + 'timestamp_device': 1836052, + 'timestamp_stream': 965.4508012495935, + 'transform': [array([-57.71216583, 93.95291901, 0.24132766]), + array([ 6.43722057, -172.99743652, -0.50203705])]} +{'AngularVelocity': array([ 0.47601855, -0.59692639, -0.02221255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-7.14189606e+01, 9.82739716e+01, 3.79446596e-02]), + 'Rotation': array([ 0.07027581, 8.00031281, -5.18719816]), + 'Velocity': array([1.07308555, 0.14968088, 0.15982644]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4521.9833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6277.9609375 , 15235.85839844, 84.2401886 ]), + 'frame': 28427, + 'frame_number': 28427, + 'framesequence': 114449, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17910093069076538, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.4844568520784, + 'timestamp_carla': 965483, + 'timestamp_device': 1836085, + 'timestamp_stream': 965.4844568520784, + 'transform': [array([-57.70576859, 93.93763733, 0.24108601]), + array([ 6.43899679, -172.97875977, -0.50219291])]} +{'AngularVelocity': array([-4.14139175, -2.61514616, -1.54164636]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-7.11079407e+01, 9.83120956e+01, 7.44184703e-02]), + 'Rotation': array([ 0.47926068, 7.7029624 , -4.25506735]), + 'Velocity': array([1.61873949, 0.22818497, 0.16915677]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4526.83154296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6282.48388672, 15238.73242188, 82.84763336]), + 'frame': 28428, + 'frame_number': 28428, + 'framesequence': 114453, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18008972704410553, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.519311349839, + 'timestamp_carla': 965518, + 'timestamp_device': 1836118, + 'timestamp_stream': 965.519311349839, + 'transform': [array([-57.69352722, 93.92097473, 0.23403385]), + array([ 6.37679386, -172.92730713, -0.47581503])]} +{'AngularVelocity': array([-2.10354352, -1.2493093 , -2.12089849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-7.08439865e+01, 9.83354263e+01, 9.73083302e-02]), + 'Rotation': array([ 0.95190978, 7.40445042, -3.25943017]), + 'Velocity': array([1.4982655 , 0.15329669, 0.07252384]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4529.564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6284.08642578, 15239.75097656, 82.77772522]), + 'frame': 28429, + 'frame_number': 28429, + 'framesequence': 114457, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18063905835151672, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.5523117519915, + 'timestamp_carla': 965551, + 'timestamp_device': 1836152, + 'timestamp_stream': 965.5523117519915, + 'transform': [array([-57.68582535, 93.90496826, 0.24285388]), + array([ 6.45443296, -172.90306091, -0.5073368 ])]} +{'AngularVelocity': array([-2.5957427 , -1.83992565, -0.04999606]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-70.60246277, 98.36388397, 0.10586736]), + 'Rotation': array([ 1.18346 , 7.28919125, -2.77752709]), + 'Velocity': array([1.38897753, 0.20103435, 0.05381176]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4534.541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6288.48925781, 15242.55078125, 84.93717957]), + 'frame': 28430, + 'frame_number': 28430, + 'framesequence': 114462, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18005309998989105, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.590071849525, + 'timestamp_carla': 965588, + 'timestamp_device': 1836193, + 'timestamp_stream': 965.590071849525, + 'transform': [array([-57.66976547, 93.88916016, 0.23580302]), + array([ 6.40638924, -172.83639526, -0.48038664])]} +{'AngularVelocity': array([-1.09656584, -0.77058494, -0.01684213]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-70.3789978 , 98.39297485, 0.11079752]), + 'Rotation': array([ 1.34948134, 7.29005337, -2.46844506]), + 'Velocity': array([1.29998398, 0.17784469, 0.0224641 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4537.90966796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6290.89941406, 15244.08203125, 82.30271912]), + 'frame': 28431, + 'frame_number': 28431, + 'framesequence': 114466, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17972351610660553, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.6271516494453, + 'timestamp_carla': 965626, + 'timestamp_device': 1836227, + 'timestamp_stream': 965.6271516494453, + 'transform': [array([-57.66205978, 93.87294769, 0.24125816]), + array([ 6.45501995, -172.81228638, -0.50051898])]} +{'AngularVelocity': array([-0.36946172, -0.24050045, 0.01412231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-70.12992096, 98.42536926, 0.11265451]), + 'Rotation': array([ 1.42117107, 7.29098845, -2.32681298]), + 'Velocity': array([1.19714808, 0.15839967, 0.00581876]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12687.7451171875, + 'focus_actor_name': 'BP_RepSpline5', + 'focus_actor_pt': array([-7.31967188e+03, 2.33268672e+04, 1.66119003e+01]), + 'frame': 28432, + 'frame_number': 28432, + 'framesequence': 114470, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.6638582497835, + 'timestamp_carla': 965662, + 'timestamp_device': 1836260, + 'timestamp_stream': 965.6638582497835, + 'transform': [array([-57.65351486, 93.85823822, 0.23006366]), + array([ 6.35187769, -172.77493286, -0.45988563])]} +{'AngularVelocity': array([-0.14488249, -0.091336 , 0.03969336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-69.93608093, 98.45054626, 0.11300642]), + 'Rotation': array([ 1.44107425, 7.29154825, -2.28384423]), + 'Velocity': array([1.11627018, 0.14603989, 0.001865 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13760.509765625, + 'focus_actor_name': 'Town05_TerrainNode_4406', + 'focus_actor_pt': array([-7.46059277e+03, 2.43886875e+04, 2.78069305e+00]), + 'frame': 28433, + 'frame_number': 28433, + 'framesequence': 114474, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.6967060491443, + 'timestamp_carla': 965695, + 'timestamp_device': 1836293, + 'timestamp_stream': 965.6967060491443, + 'transform': [array([-57.63890457, 93.84368896, 0.23435791]), + array([ 6.3880229 , -172.71461487, -0.47266245])]} +{'AngularVelocity': array([-0.05462784, -0.03667457, 0.05382367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-69.75743103, 98.47371674, 0.1130858 ]), + 'Rotation': array([ 1.44854641, 7.29189253, -2.26681542]), + 'Velocity': array([1.04124069e+00, 1.35566309e-01, 4.90226725e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 15319.9794921875, + 'focus_actor_name': 'Town05_TerrainNode_4376', + 'focus_actor_pt': array([-7.66580420e+03, 2.59331211e+04, 2.13806152e-01]), + 'frame': 28434, + 'frame_number': 28434, + 'framesequence': 114479, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.7315410524607, + 'timestamp_carla': 965730, + 'timestamp_device': 1836335, + 'timestamp_stream': 965.7315410524607, + 'transform': [array([-57.6290741 , 93.82702637, 0.24327056]), + array([ 6.46352386, -172.68492126, -0.50633198])]} +{'AngularVelocity': array([-1.10754561e+00, -5.94079733e-01, 9.68722859e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-69.59094238, 98.4967041 , 0.11068002]), + 'Rotation': array([ 1.35358632, 7.34415817, -2.46051073]), + 'Velocity': array([0.96682709, 0.13527921, 0.00659273]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4576.9375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6310.10742188, 15274.90429688, 84.90264893]), + 'frame': 28435, + 'frame_number': 28435, + 'framesequence': 114483, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.7674916498363, + 'timestamp_carla': 965766, + 'timestamp_device': 1836368, + 'timestamp_stream': 965.7674916498363, + 'transform': [array([-57.61803055, 93.81289673, 0.23669747]), + array([ 6.44182444, -172.64321899, -0.48140365])]} +{'AngularVelocity': array([-0.41010618, -0.30019915, 0.09763885]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0037852053064852953, + 'Location': array([-69.43367767, 98.51730347, 0.11195573]), + 'Rotation': array([ 1.41400623, 7.34513569, -2.33679199]), + 'Velocity': array([0.90121311, 0.12127365, 0.00857233]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4575.4248046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6312.29638672, 15271.46191406, 82.08454895]), + 'frame': 28436, + 'frame_number': 28436, + 'framesequence': 114487, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.7995806522667, + 'timestamp_carla': 965798, + 'timestamp_device': 1836402, + 'timestamp_stream': 965.7995806522667, + 'transform': [array([-57.60765839, 93.80054474, 0.23405349]), + array([ 6.42694139, -172.59994507, -0.47011912])]} +{'AngularVelocity': array([-0.08338574, -0.22232157, 0.67610222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037837387062609196, + 'FR_Wheel_Angle': 0.003780877683311701, + 'Location': array([-69.29323578, 98.53568268, 0.11271669]), + 'Rotation': array([ 1.44123125, 7.34845924, -2.28878808]), + 'Velocity': array([0.8934145 , 0.11883686, 0.0031368 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4573.10400390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6314.91308594, 15267.34472656, 84.07935333]), + 'frame': 28437, + 'frame_number': 28437, + 'framesequence': 114490, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.831374950707, + 'timestamp_carla': 965830, + 'timestamp_device': 1836427, + 'timestamp_stream': 965.831374950707, + 'transform': [array([-57.60028839, 93.78826141, 0.23872344]), + array([ 6.47221184, -172.5760498 , -0.48726812])]} +{'AngularVelocity': array([-0.05997962, -0.24289654, -0.16549243]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.570870578289032, + 'FR_Wheel_Angle': -0.8362263441085815, + 'Location': array([-69.10079956, 98.56060028, 0.1127912 ]), + 'Rotation': array([ 1.48223972, 7.36481762, -2.27087426]), + 'Velocity': array([1.44458711e+00, 1.85490131e-01, 7.15894683e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4570.1591796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6317.82226562, 15262.76855469, 85.04930115]), + 'frame': 28438, + 'frame_number': 28438, + 'framesequence': 114495, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.866411048919, + 'timestamp_carla': 965865, + 'timestamp_device': 1836468, + 'timestamp_stream': 965.866411048919, + 'transform': [array([-57.59093475, 93.77552795, 0.23790096]), + array([ 6.46568203, -172.54081726, -0.48462003])]} +{'AngularVelocity': array([-0.06904057, -0.11318486, -1.72735512]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.1661462783813477, + 'FR_Wheel_Angle': -2.4136765003204346, + 'Location': array([-68.72892761, 98.60519409, 0.11270525]), + 'Rotation': array([ 1.51465583, 7.23389482, -2.25909424]), + 'Velocity': array([2.31769609e+00, 2.52767116e-01, 1.78680421e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4571.33740234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6319.84375 , 15262.48144531, 83.58712769]), + 'frame': 28439, + 'frame_number': 28439, + 'framesequence': 114499, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.8985364511609, + 'timestamp_carla': 965897, + 'timestamp_device': 1836502, + 'timestamp_stream': 965.8985364511609, + 'transform': [array([-57.58132553, 93.76433563, 0.23585273]), + array([ 6.43629885, -172.50354004, -0.47829631])]} +{'AngularVelocity': array([-0.05470848, 0.01597622, -3.38956571]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6016383171081543, + 'FR_Wheel_Angle': -3.7746145725250244, + 'Location': array([-68.28499603, 98.65106201, 0.11268961]), + 'Rotation': array([ 1.52136314, 6.80990982, -2.24829102]), + 'Velocity': array([2.98118854e+00, 2.64302641e-01, 3.73864168e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4574.982421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6322.97851562, 15264.47460938, 83.76924133]), + 'frame': 28440, + 'frame_number': 28440, + 'framesequence': 114503, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.9325978495181, + 'timestamp_carla': 965931, + 'timestamp_device': 1836535, + 'timestamp_stream': 965.9325978495181, + 'transform': [array([-57.573349 , 93.75158691, 0.23959674]), + array([ 6.4625268 , -172.4765625 , -0.49251047])]} +{'AngularVelocity': array([-9.02719116, 5.47344542, -5.02251625]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.659204006195068, + 'FR_Wheel_Angle': -5.780795574188232, + 'Location': array([-67.75800323, 98.68877411, 0.1324352 ]), + 'Rotation': array([ 0.72632909, 6.01742697, -0.94271845]), + 'Velocity': array([3.29046965, 0.24344328, 0.15303615]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4578.60498046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6326.28125 , 15266.57421875, 84.28781128]), + 'frame': 28441, + 'frame_number': 28441, + 'framesequence': 114507, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.9660265520215, + 'timestamp_carla': 965964, + 'timestamp_device': 1836568, + 'timestamp_stream': 965.9660265520215, + 'transform': [array([-57.56072998, 93.73899841, 0.23071602]), + array([ 6.37693071, -172.42372131, -0.46079895])]} +{'AngularVelocity': array([-2.24750233, 1.32922637, -8.26221943]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.4106574058532715, + 'FR_Wheel_Angle': -7.21783971786499, + 'Location': array([-67.19327545, 98.71550751, 0.14788759]), + 'Rotation': array([ 0.26077661, 4.91048956, -0.34771726]), + 'Velocity': array([3.50866079, 0.09082251, 0.03930268]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4581.78076171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6328.81298828, 15268.18261719, 83.082901 ]), + 'frame': 28442, + 'frame_number': 28442, + 'framesequence': 114511, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 965.9998034499586, + 'timestamp_carla': 965998, + 'timestamp_device': 1836602, + 'timestamp_stream': 965.9998034499586, + 'transform': [array([-57.55360413, 93.72621155, 0.2410939 ]), + array([ 6.46185732, -172.3996582 , -0.49730158])]} +{'AngularVelocity': array([ -0.89096302, 0.5505324 , -10.07485676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.041358947753906, + 'FR_Wheel_Angle': -8.447063446044922, + 'Location': array([-66.6087265 , 98.72422791, 0.15234426]), + 'Rotation': array([ 0.10042427, 3.36230397, -0.11877442]), + 'Velocity': array([ 3.50768781, -0.06589655, 0.01052346]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4586.49560546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6333.33398438, 15271.05664062, 85.71856689]), + 'frame': 28443, + 'frame_number': 28443, + 'framesequence': 114515, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.0349371507764, + 'timestamp_carla': 966033, + 'timestamp_device': 1836635, + 'timestamp_stream': 966.0349371507764, + 'transform': [array([-57.54541016, 93.71562195, 0.23940574]), + array([ 6.470716 , -172.37055969, -0.49027675])]} +{'AngularVelocity': array([ -0.31565288, 0.23804201, -10.10264874]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.27383041381836, + 'FR_Wheel_Angle': -8.519787788391113, + 'Location': array([-66.03727722, 98.71201324, 0.15363829]), + 'Rotation': array([ 0.03568774, 1.6755476 , -0.03271484]), + 'Velocity': array([ 3.39614487e+00, -1.80434585e-01, 3.01267137e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4589.63720703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6335.85400391, 15272.65820312, 82.67624664]), + 'frame': 28444, + 'frame_number': 28444, + 'framesequence': 114519, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.0673143491149, + 'timestamp_carla': 966066, + 'timestamp_device': 1836668, + 'timestamp_stream': 966.0673143491149, + 'transform': [array([-57.53367615, 93.70563507, 0.23458743]), + array([ 6.43502808, -172.32199097, -0.47203073])]} +{'AngularVelocity': array([-0.20120263, 0.10478557, -9.68204689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.563725471496582, + 'FR_Wheel_Angle': -8.805137634277344, + 'Location': array([-65.47879028, 98.6829834 , 0.15386209]), + 'Rotation': array([-0.00015709, 0.0083702 , -0.01879883]), + 'Velocity': array([ 3.21353531e+00, -2.71668345e-01, 2.35238069e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4592.5927734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6338.33251953, 15274.234375 , 83.1723175 ]), + 'frame': 28445, + 'frame_number': 28445, + 'framesequence': 114523, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.1005597524345, + 'timestamp_carla': 966099, + 'timestamp_device': 1836702, + 'timestamp_stream': 966.1005597524345, + 'transform': [array([-57.52539062, 93.69335938, 0.23832104]), + array([ 6.4697051 , -172.29364014, -0.48557675])]} +{'AngularVelocity': array([-0.0522395 , 0.01958414, -9.17313957]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.669242858886719, + 'FR_Wheel_Angle': -8.857346534729004, + 'Location': array([-64.86437988, 98.62995911, 0.15403727]), + 'Rotation': array([-0.00842162, -1.88485694, 0.00435661]), + 'Velocity': array([ 2.95978165e+00, -3.58254552e-01, 1.67118071e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4596.81298828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6342.55371094, 15276.91796875, 84.65976715]), + 'frame': 28446, + 'frame_number': 28446, + 'framesequence': 114527, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.1343728490174, + 'timestamp_carla': 966133, + 'timestamp_device': 1836735, + 'timestamp_stream': 966.1343728490174, + 'transform': [array([-57.51500702, 93.6805191 , 0.23271385]), + array([ 6.41333532, -172.25045776, -0.46516147])]} +{'AngularVelocity': array([ 3.68838263, 2.49340248, -8.70780277]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.991379737854004, + 'FR_Wheel_Angle': -9.211899757385254, + 'Location': array([-64.30853271, 98.56814575, 0.12265989]), + 'Rotation': array([-1.39236128, -3.51544309, -2.83331394]), + 'Velocity': array([ 2.71345639, -0.47413626, -0.12768848]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4600.046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6345.20654297, 15278.60449219, 83.48803711]), + 'frame': 28447, + 'frame_number': 28447, + 'framesequence': 114531, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.1671729497612, + 'timestamp_carla': 966166, + 'timestamp_device': 1836768, + 'timestamp_stream': 966.1671729497612, + 'transform': [array([-57.5080452 , 93.66818237, 0.23965567]), + array([ 6.47049761, -172.22927856, -0.49073744])]} +{'AngularVelocity': array([ 0.22291565, -0.06729549, -8.29770565]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.193963050842285, + 'FR_Wheel_Angle': -9.292043685913086, + 'Location': array([-63.87662125, 98.50191498, 0.11713243]), + 'Rotation': array([-1.48687744, -4.92926264, -2.98068309]), + 'Velocity': array([ 2.50738621e+00, -4.63318080e-01, 6.06956484e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4604.2421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6349.01123047, 15281.0234375 , 85.19662476]), + 'frame': 28448, + 'frame_number': 28448, + 'framesequence': 114535, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.2012395523489, + 'timestamp_carla': 966200, + 'timestamp_device': 1836802, + 'timestamp_stream': 966.2012395523489, + 'transform': [array([-57.4925766 , 93.6547699 , 0.22994655]), + array([ 6.38020229, -172.1647644 , -0.45631829])]} +{'AngularVelocity': array([ 0.08638892, -0.0689779 , -7.44033909]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.824174880981445, + 'FR_Wheel_Angle': -8.773842811584473, + 'Location': array([-63.46823502, 98.43012238, 0.11804266]), + 'Rotation': array([-1.47467196, -6.26526356, -3.00436425]), + 'Velocity': array([ 2.32367492, -0.47800189, 0.00580909]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5013.59814453125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6406.47949219, 15685.1015625 , 79.56787109]), + 'frame': 28449, + 'frame_number': 28449, + 'framesequence': 114539, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.2332481518388, + 'timestamp_carla': 966232, + 'timestamp_device': 1836835, + 'timestamp_stream': 966.2332481518388, + 'transform': [array([-57.48624039, 93.64092255, 0.24075557]), + array([ 6.46436405, -172.14533997, -0.49496937])]} +{'AngularVelocity': array([ 9.85135651, -7.45784569, -5.75216627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.611376762390137, + 'FR_Wheel_Angle': -7.796271324157715, + 'Location': array([-63.09540558, 98.35758209, 0.11349791]), + 'Rotation': array([-1.24814188, -7.30841827, -3.39740086]), + 'Velocity': array([ 2.15039897, -0.53591204, -0.11317052]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5017.73779296875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6412.27392578, 15687.11621094, 82.67674255]), + 'frame': 28450, + 'frame_number': 28450, + 'framesequence': 114543, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.2662728503346, + 'timestamp_carla': 966265, + 'timestamp_device': 1836868, + 'timestamp_stream': 966.2662728503346, + 'transform': [array([-57.47664261, 93.62738037, 0.2372752 ]), + array([ 6.42488527, -172.110672 , -0.484182 ])]} +{'AngularVelocity': array([-1.35090923, 0.42453429, -4.8264699 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.572869777679443, + 'FR_Wheel_Angle': -5.725541114807129, + 'Location': array([-6.26752090e+01, 9.82707367e+01, 6.67912066e-02]), + 'Rotation': array([ 0.36587271, -8.47956371, -5.77844572]), + 'Velocity': array([ 2.03534746, -0.45115635, -0.03035298]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5025.62109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6415.26806641, 15693.31445312, 79.13034058]), + 'frame': 28451, + 'frame_number': 28451, + 'framesequence': 114547, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.3010980524123, + 'timestamp_carla': 966299, + 'timestamp_device': 1836902, + 'timestamp_stream': 966.3010980524123, + 'transform': [array([-57.46134567, 93.61360931, 0.22748879]), + array([ 6.33372974, -172.04440308, -0.44786391])]} +{'AngularVelocity': array([-0.97892487, 0.85993302, -2.66241455]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.0932888984680176, + 'FR_Wheel_Angle': -2.11159348487854, + 'Location': array([-6.22193718e+01, 9.81806717e+01, 7.24422634e-02]), + 'Rotation': array([ 0.1745728 , -9.25492764, -5.4511447 ]), + 'Velocity': array([ 2.52357268, -0.48148474, 0.03046797]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4642.90087890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6365.15136719, 15312.51953125, 83.32723999]), + 'frame': 28452, + 'frame_number': 28452, + 'framesequence': 114551, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.178368479013443, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.3344117514789, + 'timestamp_carla': 966333, + 'timestamp_device': 1836935, + 'timestamp_stream': 966.3344117514789, + 'transform': [array([-57.45534897, 93.60066223, 0.24307685]), + array([ 6.46343517, -172.0279541 , -0.50356805])]} +{'AngularVelocity': array([-16.81900215, 10.31886864, 2.51929092]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07046802341938019, + 'FR_Wheel_Angle': 0.2670590877532959, + 'Location': array([-6.17709656e+01, 9.80997467e+01, 7.29159340e-02]), + 'Rotation': array([-0.07528234, -9.35236931, -4.83200264]), + 'Velocity': array([ 2.89641833, -0.36756012, -0.15765229]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4638.10302734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6369.50683594, 15305.66601562, 86.47808838]), + 'frame': 28453, + 'frame_number': 28453, + 'framesequence': 114555, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16613668203353882, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.3667426519096, + 'timestamp_carla': 966365, + 'timestamp_device': 1836968, + 'timestamp_stream': 966.3667426519096, + 'transform': [array([-57.44762421, 93.59072113, 0.2378453 ]), + array([ 6.43804026, -172.00004578, -0.48459384])]} +{'AngularVelocity': array([-2.16785145, 2.18164039, 1.26330698]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.0895458459854126, + 'FR_Wheel_Angle': 1.185947299003601, + 'Location': array([-6.12729034e+01, 9.80220490e+01, 4.45544608e-02]), + 'Rotation': array([-1.32718086, -9.16255093, -2.30426049]), + 'Velocity': array([ 3.2725091 , -0.45163459, -0.08222189]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4637.20166015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6371.00634766, 15303.30761719, 81.8092804 ]), + 'frame': 28454, + 'frame_number': 28454, + 'framesequence': 114559, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14553667604923248, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.3999042510986, + 'timestamp_carla': 966398, + 'timestamp_device': 1837002, + 'timestamp_stream': 966.3999042510986, + 'transform': [array([-57.4382019 , 93.58113861, 0.2273709 ]), + array([ 6.35317516, -171.95855713, -0.44542491])]} +{'AngularVelocity': array([ 2.14448214, -4.38571882, 1.34496689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.258284091949463, + 'FR_Wheel_Angle': 1.272411823272705, + 'Location': array([-6.06893845e+01, 9.79358673e+01, 4.73481938e-02]), + 'Rotation': array([-1.11718667, -8.93220043, -2.527771 ]), + 'Velocity': array([ 3.63290429, -0.55000538, 0.11451395]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4635.7724609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6372.73046875, 15300.59375 , 83.35446167]), + 'frame': 28455, + 'frame_number': 28455, + 'framesequence': 114563, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12136600911617279, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.432747349143, + 'timestamp_carla': 966431, + 'timestamp_device': 1837035, + 'timestamp_stream': 966.432747349143, + 'transform': [array([-57.43385696, 93.56955719, 0.24257869]), + array([ 6.472929 , -171.94993591, -0.50044483])]} +{'AngularVelocity': array([-0.60138428, 0.12901476, 1.71298516]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2504256963729858, + 'FR_Wheel_Angle': 1.2640888690948486, + 'Location': array([-5.99162941e+01, 9.78219376e+01, 6.47418424e-02]), + 'Rotation': array([-0.51174504, -8.65476418, -2.23437476]), + 'Velocity': array([ 4.02469635, -0.55283421, 0.02169732]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4634.47265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6375.53955078, 15297.88671875, 86.67773438]), + 'frame': 28456, + 'frame_number': 28456, + 'framesequence': 114567, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0993194431066513, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.465057451278, + 'timestamp_carla': 966463, + 'timestamp_device': 1837068, + 'timestamp_stream': 966.465057451278, + 'transform': [array([-57.42897034, 93.55922699, 0.2383696 ]), + array([ 6.40840435, -171.93325806, -0.48779005])]} +{'AngularVelocity': array([-0.00831908, 0.48225012, 1.84305072]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2423884868621826, + 'FR_Wheel_Angle': 1.2559456825256348, + 'Location': array([-5.92204323e+01, 9.77249374e+01, 6.44040853e-02]), + 'Rotation': array([-0.58200037, -8.35920048, -2.20614648]), + 'Velocity': array([ 4.35612154, -0.58672106, -0.0129225 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4636.54833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6376.81054688, 15298.6953125 , 82.05482483]), + 'frame': 28457, + 'frame_number': 28457, + 'framesequence': 114571, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09411908686161041, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.499484051019, + 'timestamp_carla': 966498, + 'timestamp_device': 1837101, + 'timestamp_stream': 966.499484051019, + 'transform': [array([-57.42119598, 93.54814148, 0.22402763]), + array([ 6.26800966, -171.89862061, -0.43561876])]} +{'AngularVelocity': array([-12.24219894, -5.66481066, 1.65824878]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2342723608016968, + 'FR_Wheel_Angle': 1.2474815845489502, + 'Location': array([-5.84763718e+01, 9.76234741e+01, 4.63444702e-02]), + 'Rotation': array([ 0.0129637 , -8.08628082, -1.01852417]), + 'Velocity': array([ 4.59103489, -0.48861316, -0.17689323]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4635.77734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6377.85839844, 15296.70898438, 83.18193054]), + 'frame': 28458, + 'frame_number': 28458, + 'framesequence': 114575, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10267037153244019, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.5328775495291, + 'timestamp_carla': 966531, + 'timestamp_device': 1837135, + 'timestamp_stream': 966.5328775495291, + 'transform': [array([-57.41558838, 93.53709412, 0.208382 ]), + array([ 6.12605762, -171.87147522, -0.37614185])]} +{'AngularVelocity': array([-0.11370157, 5.79193068, 2.09968519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.1597785949707031, + 'FR_Wheel_Angle': 1.0818657875061035, + 'Location': array([-5.75190010e+01, 9.75038834e+01, 3.78028303e-02]), + 'Rotation': array([ 0.07612246, -7.6785655 , -0.49371338]), + 'Velocity': array([ 4.94550371, -0.6101799 , 0.09736796]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4633.4169921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6379.88183594, 15292.86523438, 87.67196655]), + 'frame': 28459, + 'frame_number': 28459, + 'framesequence': 114579, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11537828296422958, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.5651004500687, + 'timestamp_carla': 966563, + 'timestamp_device': 1837168, + 'timestamp_stream': 966.5651004500687, + 'transform': [array([-57.40744019, 93.52609253, 0.19380119]), + array([ 6.00008869, -171.83360291, -0.31922439])]} +{'AngularVelocity': array([-0.78807157, -0.45814329, 0.85994351]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.33921343088150024, + 'FR_Wheel_Angle': 0.09557216614484787, + 'Location': array([-5.66823921e+01, 9.73989334e+01, 4.70667072e-02]), + 'Rotation': array([-0.25442454, -7.42618513, -0.0642395 ]), + 'Velocity': array([ 5.01994371, -0.61368972, -0.01502618]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4633.064453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6381.58007812, 15291.08691406, 92.77879333]), + 'frame': 28460, + 'frame_number': 28460, + 'framesequence': 114583, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12803125381469727, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.6000989489257, + 'timestamp_carla': 966598, + 'timestamp_device': 1837201, + 'timestamp_stream': 966.6000989489257, + 'transform': [array([-57.39657974, 93.51412964, 0.18333019]), + array([ 5.9167943 , -171.78529358, -0.27594608])]} +{'AngularVelocity': array([-0.3037163 , -0.34658754, -0.31158391]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.2048911303281784, + 'FR_Wheel_Angle': -0.16500306129455566, + 'Location': array([-5.58486061e+01, 9.72923584e+01, 4.28990722e-02]), + 'Rotation': array([-0.17285159, -7.41498613, 0.00874641]), + 'Velocity': array([ 5.07731533, -0.65995377, -0.02159483]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4636.2841796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6384.67871094, 15292.71972656, 97.65129852]), + 'frame': 28461, + 'frame_number': 28461, + 'framesequence': 114587, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13303019106388092, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.6325058490038, + 'timestamp_carla': 966631, + 'timestamp_device': 1837235, + 'timestamp_stream': 966.6325058490038, + 'transform': [array([-57.39215851, 93.50083923, 0.20895831]), + array([ 6.13641214, -171.77766418, -0.36574432])]} +{'AngularVelocity': array([-0.10772382, -0.14450291, -0.06757176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.015104614198207855, + 'FR_Wheel_Angle': -0.015093713067471981, + 'Location': array([-5.49865379e+01, 9.71801453e+01, 3.96396816e-02]), + 'Rotation': array([-0.13460936, -7.44751644, 0.03370337]), + 'Velocity': array([ 5.17512989, -0.67269164, -0.01535017]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4645.544921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6389.57080078, 15300.1171875 , 101.34642029]), + 'frame': 28462, + 'frame_number': 28462, + 'framesequence': 114591, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12931303679943085, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.6653847508132, + 'timestamp_carla': 966664, + 'timestamp_device': 1837268, + 'timestamp_stream': 966.6653847508132, + 'transform': [array([-57.3828125 , 93.48651886, 0.24089 ]), + array([ 6.37120008, -171.75845337, -0.48680276])]} +{'AngularVelocity': array([-0.04696725, -0.05784631, -0.03910721]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.022021731361746788, + 'FR_Wheel_Angle': -0.022002270445227623, + 'Location': array([-5.41096611e+01, 9.70661087e+01, 3.72446626e-02]), + 'Rotation': array([-0.12002691, -7.45417023, 0.04364375]), + 'Velocity': array([ 5.28021049, -0.68676871, -0.01281308]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4647.63623046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6390.91992188, 15300.82617188, 93.78380585]), + 'frame': 28463, + 'frame_number': 28463, + 'framesequence': 114595, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12317880988121033, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.6990559510887, + 'timestamp_carla': 966697, + 'timestamp_device': 1837301, + 'timestamp_stream': 966.6990559510887, + 'transform': [array([-57.3710289 , 93.47375488, 0.24227299]), + array([ 6.34198046, -171.71707153, -0.49887308])]} +{'AngularVelocity': array([-0.01505879, -0.0196243 , -0.03248262]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012722579762339592, + 'FR_Wheel_Angle': 0.055494461208581924, + 'Location': array([-5.30491753e+01, 9.69280930e+01, 3.47635448e-02]), + 'Rotation': array([-0.11407098, -7.46204376, 0.04823133]), + 'Velocity': array([ 5.40102959, -0.7033354 , -0.01209778]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4650.671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6393.53808594, 15302.20605469, 83.54383087]), + 'frame': 28464, + 'frame_number': 28464, + 'framesequence': 114599, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11693472415208817, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.7315905503929, + 'timestamp_carla': 966730, + 'timestamp_device': 1837335, + 'timestamp_stream': 966.7315905503929, + 'transform': [array([-57.36492157, 93.46141052, 0.23152995]), + array([ 6.23129749, -171.69136047, -0.46254256])]} +{'AngularVelocity': array([-0.00474141, -0.0221147 , 0.14270718]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.08650791645050049, + 'FR_Wheel_Angle': 0.08657214045524597, + 'Location': array([-5.21519508e+01, 9.68116760e+01, 3.27694900e-02]), + 'Rotation': array([-0.112944 , -7.44849348, 0.04885981]), + 'Velocity': array([ 5.49534845, -0.71027398, -0.01209302]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4654.49853515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6397.38623047, 15304.23242188, 82.49984741]), + 'frame': 28465, + 'frame_number': 28465, + 'framesequence': 114603, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11393170803785324, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.7666868492961, + 'timestamp_carla': 966765, + 'timestamp_device': 1837368, + 'timestamp_stream': 966.7666868492961, + 'transform': [array([-57.3519516 , 93.4467392 , 0.21511215]), + array([ 6.09058189, -171.63438416, -0.40198976])]} +{'AngularVelocity': array([ 0.00179857, -0.00364603, 0.24162185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1382102370262146, + 'FR_Wheel_Angle': 0.14068487286567688, + 'Location': array([-5.12211418e+01, 9.66915817e+01, 3.07319816e-02]), + 'Rotation': array([-0.11362019, -7.41773081, 0.04899502]), + 'Velocity': array([ 5.55494452, -0.71268207, -0.01216267]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4657.19970703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6399.53759766, 15305.36523438, 85.57479095]), + 'frame': 28466, + 'frame_number': 28466, + 'framesequence': 114607, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11576281487941742, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.7999647520483, + 'timestamp_carla': 966798, + 'timestamp_device': 1837401, + 'timestamp_stream': 966.7999647520483, + 'transform': [array([-57.34455872, 93.43244171, 0.20000167]), + array([ 5.96812344, -171.60076904, -0.34399781])]} +{'AngularVelocity': array([0.00096371, 0.00381859, 0.26898792]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.14047455787658691, + 'FR_Wheel_Angle': 0.1406634896993637, + 'Location': array([-5.02969437e+01, 9.65732117e+01, 2.87230108e-02]), + 'Rotation': array([-0.11578536, -7.37506723, 0.04902372]), + 'Velocity': array([ 5.57916784, -0.71091282, -0.01219654]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4660.97509765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6404.19287109, 15306.95507812, 90.70768738]), + 'frame': 28467, + 'frame_number': 28467, + 'framesequence': 114611, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11922361701726913, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.8344712518156, + 'timestamp_carla': 966833, + 'timestamp_device': 1837435, + 'timestamp_stream': 966.8344712518156, + 'transform': [array([-57.33067322, 93.41667938, 0.18522437]), + array([ 5.8542366 , -171.54057312, -0.28613058])]} +{'AngularVelocity': array([ 1.76474234e-04, -8.10789224e-03, 2.69604623e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.14046861231327057, + 'FR_Wheel_Angle': 0.14066225290298462, + 'Location': array([-4.93723412e+01, 9.64554825e+01, 2.67131999e-02]), + 'Rotation': array([-0.11773197, -7.33130455, 0.04905929]), + 'Velocity': array([ 5.58356142, -0.70711118, -0.01220414]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4661.5810546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6406.54833984, 15305.70800781, 95.66814423]), + 'frame': 28468, + 'frame_number': 28468, + 'framesequence': 114615, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1222449466586113, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.8696401491761, + 'timestamp_carla': 966868, + 'timestamp_device': 1837468, + 'timestamp_stream': 966.8696401491761, + 'transform': [array([-57.32060242, 93.40037537, 0.17270206]), + array([ 5.75733709, -171.49737549, -0.23636162])]} +{'AngularVelocity': array([ 0.00125086, -0.01338441, 0.29675555]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16002826392650604, + 'FR_Wheel_Angle': 0.1625823974609375, + 'Location': array([-4.84417915e+01, 9.63377838e+01, 2.46875193e-02]), + 'Rotation': array([-0.11920045, -7.28583479, 0.04892201]), + 'Velocity': array([ 5.57369137, -0.70073438, -0.01218348]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4665.05517578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6411.45898438, 15306.82617188, 100.60699463]), + 'frame': 28469, + 'frame_number': 28469, + 'framesequence': 114619, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12200690060853958, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.9057246521115, + 'timestamp_carla': 966904, + 'timestamp_device': 1837501, + 'timestamp_stream': 966.9057246521115, + 'transform': [array([-57.3061676 , 93.38264465, 0.17252502]), + array([ 5.77451468, -171.4393158 , -0.23066381])]} +{'AngularVelocity': array([ 0.00117335, -0.00605563, 0.31280965]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16350094974040985, + 'FR_Wheel_Angle': 0.1637580841779709, + 'Location': array([-4.75142632e+01, 9.62213287e+01, 2.26630215e-02]), + 'Rotation': array([-0.11981517, -7.23548031, 0.04875406]), + 'Velocity': array([ 5.56158972, -0.69385135, -0.01215934]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4680.365234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6416.82568359, 15319.79101562, 104.82730865]), + 'frame': 28470, + 'frame_number': 28470, + 'framesequence': 114624, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1201757863163948, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.939590152353, + 'timestamp_carla': 966938, + 'timestamp_device': 1837543, + 'timestamp_stream': 966.939590152353, + 'transform': [array([-57.29735184, 93.36388397, 0.2089019 ]), + array([ 6.08679104, -171.42010498, -0.36208874])]} +{'AngularVelocity': array([ 0.00103222, -0.00887144, 0.32055622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16811376810073853, + 'FR_Wheel_Angle': 0.16839416325092316, + 'Location': array([-4.64059792e+01, 9.60833359e+01, 2.02406496e-02]), + 'Rotation': array([-0.12006106, -7.17383289, 0.0486089 ]), + 'Velocity': array([ 5.55134583, -0.68629622, -0.01214248]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4685.69873046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6422.15039062, 15322.59570312, 105.32134247]), + 'frame': 28471, + 'frame_number': 28471, + 'framesequence': 114628, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11876583099365234, + 'throttle_input': 0.2222171425819397, + 'timestamp': 966.9732175506651, + 'timestamp_carla': 966972, + 'timestamp_device': 1837576, + 'timestamp_stream': 966.9732175506651, + 'transform': [array([-57.28655243, 93.34642029, 0.23635124]), + array([ 6.28430653, -171.39562988, -0.46958888])]} +{'AngularVelocity': array([1.27816677, 0.34045258, 0.24766627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.16812191903591156, + 'FR_Wheel_Angle': 0.16840851306915283, + 'Location': array([-4.54870987e+01, 9.59700546e+01, 1.79607961e-02]), + 'Rotation': array([-0.13577732, -7.12201548, 0.00852974]), + 'Velocity': array([ 5.54628277, -0.6841591 , -0.02460807]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4704.58544921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6427.11865234, 15339.24414062, 93.97812653]), + 'frame': 28472, + 'frame_number': 28472, + 'framesequence': 114632, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11913206428289413, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.0063887499273, + 'timestamp_carla': 967005, + 'timestamp_device': 1837610, + 'timestamp_stream': 967.0063887499273, + 'transform': [array([-57.2743988 , 93.33042145, 0.23482531]), + array([ 6.24236917, -171.3523407 , -0.4708713 ])]} +{'AngularVelocity': array([-0.34615785, -0.14330737, 0.44633663]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2531812787055969, + 'FR_Wheel_Angle': 0.25380802154541016, + 'Location': array([-4.45597878e+01, 9.58561478e+01, 1.58069413e-02]), + 'Rotation': array([-0.13339359, -7.06464291, 0.02552755]), + 'Velocity': array([ 5.52909708, -0.66853833, -0.00742438]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4703.04638671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6429.37402344, 15335.6953125 , 84.76095581]), + 'frame': 28473, + 'frame_number': 28473, + 'framesequence': 114636, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12015748023986816, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.0403532497585, + 'timestamp_carla': 967039, + 'timestamp_device': 1837643, + 'timestamp_stream': 967.0403532497585, + 'transform': [array([-57.26287842, 93.31519318, 0.22214049]), + array([ 6.13017654, -171.30459595, -0.42694193])]} +{'AngularVelocity': array([-0.03260222, -0.29574767, 0.53133649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26813390851020813, + 'FR_Wheel_Angle': 0.2688674330711365, + 'Location': array([-4.36443291e+01, 9.57454987e+01, 1.38023943e-02]), + 'Rotation': array([-0.13342774, -6.98816442, 0.12917431]), + 'Velocity': array([ 5.52483225e+00, -6.57050669e-01, -5.20943617e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4703.8291015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6432.86962891, 15334.33007812, 84.61769867]), + 'frame': 28474, + 'frame_number': 28474, + 'framesequence': 114639, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.120542012155056, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.0732749514282, + 'timestamp_carla': 967071, + 'timestamp_device': 1837668, + 'timestamp_stream': 967.0732749514282, + 'transform': [array([-57.25200653, 93.3008194 , 0.20706551]), + array([ 6.0115633 , -171.25704956, -0.37078404])]} +{'AngularVelocity': array([ 0.1315949 , -0.41482821, 0.60049325]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26819756627082825, + 'FR_Wheel_Angle': 0.2689008414745331, + 'Location': array([-4.27267723e+01, 9.56362991e+01, 1.30018806e-02]), + 'Rotation': array([-0.08185298, -6.90109873, 0.12421332]), + 'Velocity': array([ 5.51501513e+00, -6.50089800e-01, -3.47743020e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4708.6796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6437.07666016, 15337.00390625, 88.31861877]), + 'frame': 28475, + 'frame_number': 28475, + 'framesequence': 114643, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11995605379343033, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.1060074493289, + 'timestamp_carla': 967104, + 'timestamp_device': 1837701, + 'timestamp_stream': 967.1060074493289, + 'transform': [array([-57.24200439, 93.28662109, 0.1925056 ]), + array([ 5.9018569 , -171.21296692, -0.31471828])]} +{'AngularVelocity': array([0.60049611, 0.61630863, 0.56959343]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2682788670063019, + 'FR_Wheel_Angle': 0.26893582940101624, + 'Location': array([-4.18000107e+01, 9.55271072e+01, 1.08436011e-02]), + 'Rotation': array([-0.05649249, -6.81189489, 0.13595696]), + 'Velocity': array([ 5.50041103, -0.63566667, -0.02241353]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4713.400390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6441.20019531, 15339.62597656, 93.09680176]), + 'frame': 28476, + 'frame_number': 28476, + 'framesequence': 114647, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11969970911741257, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.1397763490677, + 'timestamp_carla': 967138, + 'timestamp_device': 1837735, + 'timestamp_stream': 967.1397763490677, + 'transform': [array([-57.23187256, 93.27251434, 0.17881516]), + array([ 5.80160999, -171.16879272, -0.26095068])]} +{'AngularVelocity': array([0.5627085 , 0.18504471, 0.47738147]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2682799696922302, + 'FR_Wheel_Angle': 0.2689777910709381, + 'Location': array([-4.08858490e+01, 9.54211807e+01, 6.58773398e-03]), + 'Rotation': array([-0.13665842, -6.72516394, 0.11855643]), + 'Velocity': array([ 5.49894285, -0.63031387, -0.01623299]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4717.884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6445.03271484, 15342.0625 , 97.89733124]), + 'frame': 28477, + 'frame_number': 28477, + 'framesequence': 114651, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.1714890487492, + 'timestamp_carla': 967170, + 'timestamp_device': 1837768, + 'timestamp_stream': 967.1714890487492, + 'transform': [array([-57.22263718, 93.25939941, 0.16789593]), + array([ 5.72182655, -171.12924194, -0.21739301])]} +{'AngularVelocity': array([-0.00644606, 0.01055115, 0.45742089]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2683356702327728, + 'FR_Wheel_Angle': 0.2691190838813782, + 'Location': array([-3.99783745e+01, 9.53172989e+01, 5.99618908e-03]), + 'Rotation': array([-0.17032441, -6.64633656, 0.06958535]), + 'Velocity': array([ 5.49086857e+00, -6.23346567e-01, 2.70809163e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4716.24365234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6447.95751953, 15338.4453125 , 102.5472641 ]), + 'frame': 28478, + 'frame_number': 28478, + 'framesequence': 114655, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.2037505507469, + 'timestamp_carla': 967202, + 'timestamp_device': 1837801, + 'timestamp_stream': 967.2037505507469, + 'transform': [array([-57.21244812, 93.24604034, 0.15842399]), + array([ 5.65237045, -171.08650208, -0.17937008])]} +{'AngularVelocity': array([-0.08350881, -0.25540745, 0.46158308]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26836588978767395, + 'FR_Wheel_Angle': 0.2690869867801666, + 'Location': array([-3.90684624e+01, 9.52142181e+01, 6.36899937e-03]), + 'Rotation': array([-0.16668393, -6.57047033, 0.08250411]), + 'Velocity': array([ 5.48705912e+00, -6.13619626e-01, -1.90374372e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4717.45947265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6451.02148438, 15337.8046875 , 106.31575012]), + 'frame': 28479, + 'frame_number': 28479, + 'framesequence': 114659, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.2367369495332, + 'timestamp_carla': 967235, + 'timestamp_device': 1837835, + 'timestamp_stream': 967.2367369495332, + 'transform': [array([-57.2027626 , 93.23228455, 0.1503804 ]), + array([ 5.59238100e+00, -1.71046677e+02, -1.47001371e-01])]} +{'AngularVelocity': array([ 0.30281928, -0.52030027, 0.50608873]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2684294879436493, + 'FR_Wheel_Angle': 0.2691705524921417, + 'Location': array([-3.81556625e+01, 9.51122818e+01, 2.70887371e-03]), + 'Rotation': array([-0.02600253, -6.49277258, 0.05608752]), + 'Velocity': array([ 5.47627592, -0.60762173, -0.01236155]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4721.41162109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6454.80712891, 15339.79882812, 109.60401154]), + 'frame': 28480, + 'frame_number': 28480, + 'framesequence': 114663, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.2677390500903, + 'timestamp_carla': 967266, + 'timestamp_device': 1837868, + 'timestamp_stream': 967.2677390500903, + 'transform': [array([-57.19356155, 93.21962738, 0.1440448 ]), + array([ 5.54490423e+00, -1.71009430e+02, -1.21418707e-01])]} +{'AngularVelocity': array([0.00658752, 0.00510617, 0.50643563]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2684992253780365, + 'FR_Wheel_Angle': 0.26921841502189636, + 'Location': array([-3.70642548e+01, 9.49917374e+01, 1.38925551e-03]), + 'Rotation': array([ 1.42341135e-02, -6.39487267e+00, -6.01196289e-03]), + 'Velocity': array([ 5.46282482e+00, -5.97134590e-01, 4.68764309e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4725.251953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6458.37402344, 15341.67773438, 112.41204071]), + 'frame': 28481, + 'frame_number': 28481, + 'framesequence': 114667, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.3012446500361, + 'timestamp_carla': 967299, + 'timestamp_device': 1837901, + 'timestamp_stream': 967.3012446500361, + 'transform': [array([-57.18259811, 93.20578003, 0.13827804]), + array([ 5.50130033e+00, -1.70965408e+02, -9.82925966e-02])]} +{'AngularVelocity': array([-0.00200704, 0.00902903, 0.50475055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2685880959033966, + 'FR_Wheel_Angle': 0.26928651332855225, + 'Location': array([-3.61491776e+01, 9.48920288e+01, 1.62614824e-03]), + 'Rotation': array([ 8.40796251e-03, -6.31161928e+00, -5.15747024e-03]), + 'Velocity': array([ 5.44772243e+00, -5.86396456e-01, 1.09982491e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4728.84375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6461.74365234, 15343.45410156, 114.63584137]), + 'frame': 28482, + 'frame_number': 28482, + 'framesequence': 114671, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.3346530497074, + 'timestamp_carla': 967333, + 'timestamp_device': 1837935, + 'timestamp_stream': 967.3346530497074, + 'transform': [array([-57.17303085, 93.19089508, 0.13386565]), + array([ 5.46569443e+00, -1.70928131e+02, -8.06596503e-02])]} +{'AngularVelocity': array([-0.0007253 , -0.00400483, 0.50559068]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26852691173553467, + 'FR_Wheel_Angle': 0.26923513412475586, + 'Location': array([-3.52450638e+01, 9.47948837e+01, 1.75516121e-03]), + 'Rotation': array([ 6.65260386e-03, -6.22958851e+00, -4.57763625e-03]), + 'Velocity': array([ 5.45526981e+00, -5.79236686e-01, 4.30173852e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4732.98974609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6465.76025391, 15345.56835938, 116.64627075]), + 'frame': 28483, + 'frame_number': 28483, + 'framesequence': 114675, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.3677983507514, + 'timestamp_carla': 967366, + 'timestamp_device': 1837968, + 'timestamp_stream': 967.3677983507514, + 'transform': [array([-57.16263962, 93.17669678, 0.12991478]), + array([ 5.43529367e+00, -1.70887497e+02, -6.49596676e-02])]} +{'AngularVelocity': array([-0.00052277, -0.01722534, 0.50594985]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26842477917671204, + 'FR_Wheel_Angle': 0.2691258490085602, + 'Location': array([-3.41537437e+01, 9.46793900e+01, 1.80303573e-03]), + 'Rotation': array([ 6.26328308e-03, -6.13061953e+00, -4.30297852e-03]), + 'Velocity': array([ 5.47467470e+00, -5.71750045e-01, 1.07040403e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4736.8544921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6469.21484375, 15347.38867188, 118.18762207]), + 'frame': 28484, + 'frame_number': 28484, + 'framesequence': 114679, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.4005177505314, + 'timestamp_carla': 967399, + 'timestamp_device': 1838001, + 'timestamp_stream': 967.4005177505314, + 'transform': [array([-57.15081024, 93.16181183, 0.12700734]), + array([ 5.41057491e+00, -1.70841629e+02, -5.35233654e-02])]} +{'AngularVelocity': array([-3.37653590e-04, -2.17384025e-02, 5.07002592e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2683144211769104, + 'FR_Wheel_Angle': 0.26900985836982727, + 'Location': array([-3.30580025e+01, 9.45653229e+01, 1.81364059e-03]), + 'Rotation': array([ 6.33841520e-03, -6.03128481e+00, -4.18090820e-03]), + 'Velocity': array([ 5.49851799e+00, -5.64638495e-01, 2.73609148e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4740.85986328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6472.97851562, 15349.37109375, 119.55470276]), + 'frame': 28485, + 'frame_number': 28485, + 'framesequence': 114683, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.4339875504375, + 'timestamp_carla': 967432, + 'timestamp_device': 1838035, + 'timestamp_stream': 967.4339875504375, + 'transform': [array([-57.13918686, 93.14632416, 0.12451027]), + array([ 5.38885498e+00, -1.70797119e+02, -4.38655727e-02])]} +{'AngularVelocity': array([ 2.94828176e-04, -1.86909605e-02, 5.09958804e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2681799530982971, + 'FR_Wheel_Angle': 0.26885855197906494, + 'Location': array([-3.19591236e+01, 9.44528809e+01, 1.81314466e-03]), + 'Rotation': array([ 6.85750972e-03, -5.93176651e+00, -4.18090774e-03]), + 'Velocity': array([ 5.52871799e+00, -5.58040202e-01, 6.66618325e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4745.27978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6477.25683594, 15351.625 , 120.55715179]), + 'frame': 28486, + 'frame_number': 28486, + 'framesequence': 114687, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.4663236513734, + 'timestamp_carla': 967464, + 'timestamp_device': 1838068, + 'timestamp_stream': 967.4663236513734, + 'transform': [array([-57.12865067, 93.13166046, 0.1224176 ]), + array([ 5.37128115e+00, -1.70757095e+02, -3.57723013e-02])]} +{'AngularVelocity': array([ 0.00116711, -0.00914082, 0.51244557]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2680983543395996, + 'FR_Wheel_Angle': 0.2687954902648926, + 'Location': array([-3.10288734e+01, 9.43591690e+01, 1.81482313e-03]), + 'Rotation': array([ 6.68675499e-03, -5.84756947e+00, -4.18090820e-03]), + 'Velocity': array([ 5.54437780e+00, -5.51434338e-01, 1.23023983e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16705.13671875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8394.3203125 , 27155.2421875 , 112.29029083]), + 'frame': 28487, + 'frame_number': 28487, + 'framesequence': 114690, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.4974951520562, + 'timestamp_carla': 967496, + 'timestamp_device': 1838093, + 'timestamp_stream': 967.4974951520562, + 'transform': [array([-57.11798096, 93.11788177, 0.12056056]), + array([ 5.35665083e+00, -1.70716400e+02, -2.85984576e-02])]} +{'AngularVelocity': array([-9.89114196e-05, -2.33308580e-02, 5.16167283e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2679598331451416, + 'FR_Wheel_Angle': 0.2686415910720825, + 'Location': array([-3.01062965e+01, 9.42675858e+01, 1.80707930e-03]), + 'Rotation': array([ 8.04596208e-03, -5.76416397e+00, -4.18090820e-03]), + 'Velocity': array([ 5.59792423e+00, -5.48525095e-01, 2.31742843e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16714.1328125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8406.96679688, 27160.79296875, 114.67497253]), + 'frame': 28488, + 'frame_number': 28488, + 'framesequence': 114695, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.5318155512214, + 'timestamp_carla': 967530, + 'timestamp_device': 1838135, + 'timestamp_stream': 967.5318155512214, + 'transform': [array([-57.10705948, 93.1026535 , 0.11897327]), + array([ 5.34341383e+00, -1.70675323e+02, -2.26520933e-02])]} +{'AngularVelocity': array([-0.00430799, -0.03312613, 0.50575078]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2675972580909729, + 'FR_Wheel_Angle': 0.2682090401649475, + 'Location': array([-2.91739101e+01, 9.41764069e+01, 1.79574965e-03]), + 'Rotation': array([ 9.98573564e-03, -5.67978287e+00, -4.21142532e-03]), + 'Velocity': array([ 5.67484140e+00, -5.48082530e-01, -7.39097572e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16722.759765625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8419.77539062, 27166.02734375, 116.79066467]), + 'frame': 28489, + 'frame_number': 28489, + 'framesequence': 114698, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.5645552501082, + 'timestamp_carla': 967563, + 'timestamp_device': 1838160, + 'timestamp_stream': 967.5645552501082, + 'transform': [array([-57.0957756 , 93.08848572, 0.1175806 ]), + array([ 5.33258104e+00, -1.70632507e+02, -1.73794199e-02])]} +{'AngularVelocity': array([-0.00139222, 0.00235412, 0.51904869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26718467473983765, + 'FR_Wheel_Angle': 0.2677738070487976, + 'Location': array([-2.80150108e+01, 9.40649948e+01, 1.76778785e-03]), + 'Rotation': array([ 1.47463772e-02, -5.57535124e+00, -4.36401367e-03]), + 'Velocity': array([ 5.86001062e+00, -5.55353403e-01, 1.96456904e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16730.513671875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8432.59765625, 27170.22070312, 118.54335022]), + 'frame': 28490, + 'frame_number': 28490, + 'framesequence': 114703, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.5980661511421, + 'timestamp_carla': 967596, + 'timestamp_device': 1838201, + 'timestamp_stream': 967.5980661511421, + 'transform': [array([-57.08448792, 93.07428741, 0.11640293]), + array([ 5.32351732e+00, -1.70589737e+02, -1.29655683e-02])]} +{'AngularVelocity': array([0.00070831, 0.02972126, 0.53110176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.266783207654953, + 'FR_Wheel_Angle': 0.26748496294021606, + 'Location': array([-2.69921703e+01, 9.39683990e+01, 1.76290504e-03]), + 'Rotation': array([ 1.56001514e-02, -5.48334122e+00, -4.45556641e-03]), + 'Velocity': array([ 6.00606918e+00, -5.59736729e-01, -1.03950504e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4784.14208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6499.88378906, 15379.76855469, 123.70422363]), + 'frame': 28491, + 'frame_number': 28491, + 'framesequence': 114707, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.6331490501761, + 'timestamp_carla': 967631, + 'timestamp_device': 1838235, + 'timestamp_stream': 967.6331490501761, + 'transform': [array([-57.07362366, 93.05918884, 0.11561912]), + array([ 5.31633902e+00, -1.70549240e+02, -1.01453848e-02])]} +{'AngularVelocity': array([-4.76015994e-04, -3.59523930e-02, 5.64146161e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2663419544696808, + 'FR_Wheel_Angle': 0.26692995429039, + 'Location': array([-2.60111542e+01, 9.38773041e+01, 1.75111764e-03]), + 'Rotation': array([ 1.75809059e-02, -5.39523602e+00, -4.60815476e-03]), + 'Velocity': array([ 6.20920229e+00, -5.68631709e-01, -9.25064057e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4780.7578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6502.70654297, 15374.41210938, 124.08982849]), + 'frame': 28492, + 'frame_number': 28492, + 'framesequence': 114711, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.6657420508564, + 'timestamp_carla': 967664, + 'timestamp_device': 1838268, + 'timestamp_stream': 967.6657420508564, + 'transform': [array([-57.06310272, 93.04588318, 0.11477119]), + array([ 5.31023979e+00, -1.70509567e+02, -6.92768954e-03])]} +{'AngularVelocity': array([ 0.00091238, -0.01905598, 0.58101028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2656885087490082, + 'FR_Wheel_Angle': 0.2662595808506012, + 'Location': array([-2.49574413e+01, 9.37811127e+01, 1.74051279e-03]), + 'Rotation': array([ 1.94182266e-02, -5.30087614e+00, -4.76074265e-03]), + 'Velocity': array([ 6.40942430e+00, -5.76542616e-01, 1.20162963e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4777.69677734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6505.39013672, 15369.31640625, 124.33772278]), + 'frame': 28493, + 'frame_number': 28493, + 'framesequence': 114715, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.7000756524503, + 'timestamp_carla': 967698, + 'timestamp_device': 1838301, + 'timestamp_stream': 967.7000756524503, + 'transform': [array([-57.05153656, 93.0318222 , 0.11413704]), + array([ 5.30514431e+00, -1.70465851e+02, -4.62863082e-03])]} +{'AngularVelocity': array([ 0.00106904, -0.01767238, 0.6008811 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26513856649398804, + 'FR_Wheel_Angle': 0.26571500301361084, + 'Location': array([-2.36566887e+01, 9.36647568e+01, 1.73463812e-03]), + 'Rotation': array([ 2.04086043e-02, -5.18475628e+00, -4.94384719e-03]), + 'Velocity': array([ 6.65869856e+00, -5.85627496e-01, -1.38282769e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4778.435546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6508.63623047, 15368.15625 , 124.61677551]), + 'frame': 28494, + 'frame_number': 28494, + 'framesequence': 114719, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.7324340492487, + 'timestamp_carla': 967731, + 'timestamp_device': 1838335, + 'timestamp_stream': 967.7324340492487, + 'transform': [array([-57.04145432, 93.01848602, 0.11380336]), + array([ 5.30142164e+00, -1.70428253e+02, -3.43330251e-03])]} +{'AngularVelocity': array([ 0.00133109, -0.01563975, 0.61717135]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26460400223731995, + 'FR_Wheel_Angle': 0.26516321301460266, + 'Location': array([-2.25218143e+01, 9.35653687e+01, 1.73494336e-03]), + 'Rotation': array([ 0.02034713, -5.08368158, -0.00509644]), + 'Velocity': array([ 6.85860968e+00, -5.91281295e-01, -1.62124635e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4782.708984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6512.80078125, 15370.34765625, 124.8157196 ]), + 'frame': 28495, + 'frame_number': 28495, + 'framesequence': 114723, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.7666040509939, + 'timestamp_carla': 967765, + 'timestamp_device': 1838368, + 'timestamp_stream': 967.7666040509939, + 'transform': [array([-57.03045273, 93.00471497, 0.11333691]), + array([ 5.29745340e+00, -1.70387085e+02, -1.80918979e-03])]} +{'AngularVelocity': array([2.44407915e-03, 3.42438259e-04, 6.34619117e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2639455497264862, + 'FR_Wheel_Angle': 0.26451829075813293, + 'Location': array([-2.13584328e+01, 9.34655533e+01, 1.73398969e-03]), + 'Rotation': array([ 0.02050423, -4.98034954, -0.00524902]), + 'Velocity': array([ 7.05863857e+00, -5.95967114e-01, -6.38961751e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4786.5302734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6516.40527344, 15372.24804688, 124.92316437]), + 'frame': 28496, + 'frame_number': 28496, + 'framesequence': 114727, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.7993258498609, + 'timestamp_carla': 967798, + 'timestamp_device': 1838401, + 'timestamp_stream': 967.7993258498609, + 'transform': [array([-57.01662064, 92.99068451, 0.1130376 ]), + array([ 5.29492617e+00, -1.70334305e+02, -7.05854385e-04])]} +{'AngularVelocity': array([ 0.00209829, -0.00497124, 0.65299708]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26342839002609253, + 'FR_Wheel_Angle': 0.2639886736869812, + 'Location': array([-1.99235477e+01, 9.33452835e+01, 1.73555373e-03]), + 'Rotation': array([ 0.02021736, -4.85321331, -0.00543213]), + 'Velocity': array([ 7.29733992e+00, -6.00104392e-01, -1.98364251e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4790.625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6520.34179688, 15374.3203125 , 125.06316376]), + 'frame': 28497, + 'frame_number': 28497, + 'framesequence': 114731, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.8326735496521, + 'timestamp_carla': 967831, + 'timestamp_device': 1838435, + 'timestamp_stream': 967.8326735496521, + 'transform': [array([-57.00657272, 92.97507477, 0.11324993]), + array([ 5.29254246e+00, -1.70298370e+02, -1.80904137e-03])]} +{'AngularVelocity': array([ 0.00145174, -0.01318017, 0.66711521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.262900173664093, + 'FR_Wheel_Angle': 0.2634828984737396, + 'Location': array([-1.87052174e+01, 9.32456436e+01, 1.73620216e-03]), + 'Rotation': array([ 0.02009442, -4.74557734, -0.00558472]), + 'Velocity': array([ 7.49467802e+00, -6.02374315e-01, -1.62124627e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4795.50390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6525.3671875 , 15376.96972656, 125.15991211]), + 'frame': 28498, + 'frame_number': 28498, + 'framesequence': 114735, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11651357263326645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.8648852519691, + 'timestamp_carla': 967863, + 'timestamp_device': 1838468, + 'timestamp_stream': 967.8648852519691, + 'transform': [array([-56.99499893, 92.95973206, 0.11324062]), + array([ 5.29092360e+00, -1.70255722e+02, -1.87066419e-03])]} +{'AngularVelocity': array([ 0.00169748, -0.0103654 , 0.68204027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2624160349369049, + 'FR_Wheel_Angle': 0.26298901438713074, + 'Location': array([-1.74345970e+01, 9.31441269e+01, 1.74005504e-03]), + 'Rotation': array([ 0.01944555, -4.63354778, -0.0057373 ]), + 'Velocity': array([ 7.67563343e+00, -6.02078378e-01, 1.23023983e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4799.47607421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6528.85693359, 15378.80761719, 125.072052 ]), + 'frame': 28499, + 'frame_number': 28499, + 'framesequence': 114739, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10246895253658295, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.8985401503742, + 'timestamp_carla': 967897, + 'timestamp_device': 1838501, + 'timestamp_stream': 967.8985401503742, + 'transform': [array([-56.9830513 , 92.94382477, 0.11288845]), + array([ 5.28842402e+00, -1.70212173e+02, -6.44782383e-04])]} +{'AngularVelocity': array([ 0.00157999, -0.01265543, 0.69553649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2618502974510193, + 'FR_Wheel_Angle': 0.26241886615753174, + 'Location': array([-1.61404667e+01, 9.30432816e+01, 1.74280163e-03]), + 'Rotation': array([ 0.01897427, -4.51968575, -0.00588989]), + 'Velocity': array([ 7.85409689e+00, -6.00627840e-01, -2.79903406e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4803.8603515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6532.97314453, 15380.97460938, 125.07087708]), + 'frame': 28500, + 'frame_number': 28500, + 'framesequence': 114743, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0793786495923996, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.931762252003, + 'timestamp_carla': 967930, + 'timestamp_device': 1838535, + 'timestamp_stream': 967.931762252003, + 'transform': [array([-56.97302628, 92.92843628, 0.11244678]), + array([ 5.28570557e+00, -1.70177322e+02, 9.52593226e-04])]} +{'AngularVelocity': array([2.29882146e-03, 4.66689002e-04, 7.12889791e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2613149881362915, + 'FR_Wheel_Angle': 0.2618650496006012, + 'Location': array([-1.45287495e+01, 9.29212189e+01, 1.74779887e-03]), + 'Rotation': array([ 0.01814781, -4.37820673, -0.006073 ]), + 'Velocity': array([ 8.05231857e+00, -5.96162617e-01, -1.63078300e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4808.3583984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6537.16064453, 15383.18164062, 125.17507172]), + 'frame': 28501, + 'frame_number': 28501, + 'framesequence': 114747, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05599536374211311, + 'throttle_input': 0.2222171425819397, + 'timestamp': 967.9666698500514, + 'timestamp_carla': 967965, + 'timestamp_device': 1838568, + 'timestamp_stream': 967.9666698500514, + 'transform': [array([-56.96505737, 92.91266632, 0.11202816]), + array([ 5.28310299e+00, -1.70152298e+02, 2.40660599e-03])]} +{'AngularVelocity': array([ 0.00202751, -0.00155261, 0.7281484 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26086321473121643, + 'FR_Wheel_Angle': 0.26142919063568115, + 'Location': array([-1.29082842e+01, 9.28024750e+01, 1.74848549e-03]), + 'Rotation': array([ 0.01801121, -4.23636055, -0.0062561 ]), + 'Velocity': array([ 8.25633621e+00, -5.90940952e-01, -2.47001640e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16782.2109375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8582.56640625, 27179.45117188, 125.50980377]), + 'frame': 28502, + 'frame_number': 28502, + 'framesequence': 114751, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03713492304086685, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.00120665133, + 'timestamp_carla': 967999, + 'timestamp_device': 1838601, + 'timestamp_stream': 968.00120665133, + 'transform': [array([-56.95967102, 92.89691925, 0.11189029]), + array([ 5.28112936e+00, -1.70139114e+02, 2.77062366e-03])]} +{'AngularVelocity': array([ 0.00152482, -0.01188516, 0.73916578]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2604232132434845, + 'FR_Wheel_Angle': 0.26100441813468933, + 'Location': array([-1.15346088e+01, 9.27049332e+01, 1.75027840e-03]), + 'Rotation': array([ 0.01769702, -4.11642599, -0.00640869]), + 'Velocity': array([ 8.42122555e+00, -5.85217416e-01, 1.97410577e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16785.73046875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8590.14355469, 27180.0859375 , 125.93535614]), + 'frame': 28503, + 'frame_number': 28503, + 'framesequence': 114755, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.036677148193120956, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.0345680490136, + 'timestamp_carla': 968033, + 'timestamp_device': 1838634, + 'timestamp_stream': 968.0345680490136, + 'transform': [array([-56.95410538, 92.88227081, 0.1116555 ]), + array([ 5.27996111e+00, -1.70124847e+02, 3.68247600e-03])]} +{'AngularVelocity': array([ 0.00168958, -0.00481831, 0.7519936 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2599342167377472, + 'FR_Wheel_Angle': 0.26050421595573425, + 'Location': array([-1.01126242e+01, 9.26069489e+01, 1.75249099e-03]), + 'Rotation': array([ 0.01732136, -3.99243283, -0.00656128]), + 'Velocity': array([ 8.57643986e+00, -5.77649057e-01, -2.32696539e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16788.07421875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8594.11328125, 27180.15625 , 126.04340363]), + 'frame': 28504, + 'frame_number': 28504, + 'framesequence': 114759, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.046382032334804535, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.0689073503017, + 'timestamp_carla': 968067, + 'timestamp_device': 1838668, + 'timestamp_stream': 968.0689073503017, + 'transform': [array([-56.9478302 , 92.86748505, 0.1115023 ]), + array([ 5.27962685e+00, -1.70107529e+02, 4.29305807e-03])]} +{'AngularVelocity': array([ 0.00148221, -0.01045927, 0.76468223]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.25943422317504883, + 'FR_Wheel_Angle': 0.2600073218345642, + 'Location': array([-8.38196278e+00, 9.24918518e+01, 1.75428391e-03]), + 'Rotation': array([ 0.01700717, -3.84188938, -0.00674439]), + 'Velocity': array([ 8.76238537e+00, -5.67303777e-01, 1.23977657e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16790.71875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8598.43945312, 27180.57421875, 126.31162262]), + 'frame': 28505, + 'frame_number': 28505, + 'framesequence': 114763, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059749141335487366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.1010365523398, + 'timestamp_carla': 968099, + 'timestamp_device': 1838701, + 'timestamp_stream': 968.1010365523398, + 'transform': [array([-56.9419899 , 92.85369873, 0.11153034]), + array([ 5.27996111e+00, -1.70091064e+02, 4.27912734e-03])]} +{'AngularVelocity': array([ 0.00155836, -0.01006819, 0.77825844]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.25904133915901184, + 'FR_Wheel_Angle': 0.25961488485336304, + 'Location': array([-6.61072636e+00, 9.23787308e+01, 1.75725936e-03]), + 'Rotation': array([ 0.0165154 , -3.68817306, -0.00692749]), + 'Velocity': array([ 8.93903160e+00, -5.54951668e-01, -1.90258027e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16793.38671875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8603.66601562, 27180.84570312, 126.49003601]), + 'frame': 28506, + 'frame_number': 28506, + 'framesequence': 114767, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06982024759054184, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.1332930512726, + 'timestamp_carla': 968131, + 'timestamp_device': 1838734, + 'timestamp_stream': 968.1332930512726, + 'transform': [array([-56.93530273, 92.84020233, 0.11148853]), + array([ 5.28015280e+00, -1.70070465e+02, 4.51245205e-03])]} +{'AngularVelocity': array([ 0.001594 , -0.00782251, 0.78931975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2586594820022583, + 'FR_Wheel_Angle': 0.2592361569404602, + 'Location': array([-5.11221743e+00, 9.22866974e+01, 1.75882340e-03]), + 'Rotation': array([ 0.01626268, -3.55838084, -0.00708008]), + 'Velocity': array([ 9.08207703e+00, -5.43389499e-01, -2.22206108e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16795.537109375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8608.59472656, 27180.75 , 126.48743439]), + 'frame': 28507, + 'frame_number': 28507, + 'framesequence': 114771, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0715964287519455, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.1652144491673, + 'timestamp_carla': 968163, + 'timestamp_device': 1838768, + 'timestamp_stream': 968.1652144491673, + 'transform': [array([-56.92910004, 92.82700348, 0.11153542]), + array([ 5.28039169e+00, -1.70051590e+02, 4.36862232e-03])]} +{'AngularVelocity': array([ 0.0016097 , -0.00153002, 0.80073881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.25822797417640686, + 'FR_Wheel_Angle': 0.2588050067424774, + 'Location': array([-3.57511687e+00, 9.21957626e+01, 1.76202774e-03]), + 'Rotation': array([ 0.01568211, -3.42547679, -0.00723267]), + 'Velocity': array([ 9.21526623e+00, -5.30208051e-01, 2.09808354e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4853.11279296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6555.12255859, 15414.80273438, 125.61932373]), + 'frame': 28508, + 'frame_number': 28508, + 'framesequence': 114775, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06776940822601318, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.1987713500857, + 'timestamp_carla': 968197, + 'timestamp_device': 1838801, + 'timestamp_stream': 968.1987713500857, + 'transform': [array([-56.92205811, 92.81317139, 0.11155426]), + array([ 5.28033018e+00, -1.70029556e+02, 4.24520811e-03])]} +{'AngularVelocity': array([ 0.00158365, -0.00605563, 0.81155765]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.25780877470970154, + 'FR_Wheel_Angle': 0.2583850622177124, + 'Location': array([-1.72077298e+00, 9.20908051e+01, 1.76458352e-03]), + 'Rotation': array([ 0.0152723 , -3.26547289, -0.00741577]), + 'Velocity': array([ 9.37451553e+00, -5.13333857e-01, -8.10623135e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4852.30859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6556.38525391, 15412.40625 , 125.60757446]), + 'frame': 28509, + 'frame_number': 28509, + 'framesequence': 114779, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06167180463671684, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.2311434522271, + 'timestamp_carla': 968229, + 'timestamp_device': 1838834, + 'timestamp_stream': 968.2311434522271, + 'transform': [array([-56.91500854, 92.79992676, 0.11149605]), + array([ 5.27996111e+00, -1.70007416e+02, 4.46459604e-03])]} +{'AngularVelocity': array([ 0.01604536, -0.00709158, 1.01055372]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.36429259181022644, + 'FR_Wheel_Angle': 0.4474436044692993, + 'Location': array([1.72966450e-01, 9.19890518e+01, 1.76729204e-03]), + 'Rotation': array([ 0.01480102, -3.09585619, -0.00820923]), + 'Velocity': array([ 9.52511787e+00, -4.89749104e-01, 1.95980078e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4851.2265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6557.85058594, 15409.625 , 125.59631348]), + 'frame': 28510, + 'frame_number': 28510, + 'framesequence': 114783, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.056031983345746994, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.2661649510264, + 'timestamp_carla': 968264, + 'timestamp_device': 1838868, + 'timestamp_stream': 968.2661649510264, + 'transform': [array([-56.90915298, 92.78587341, 0.11150562]), + array([ 5.27968836e+00, -1.69990921e+02, 4.31368966e-03])]} +{'AngularVelocity': array([1.63666019e-03, 1.19068730e-03, 1.33921361e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3990125060081482, + 'FR_Wheel_Angle': 0.37837183475494385, + 'Location': array([1.76859236e+00, 9.19096680e+01, 1.77045818e-03]), + 'Rotation': array([ 0.0142546 , -2.87930369, -0.01052856]), + 'Velocity': array([ 9.63806820e+00, -4.54220533e-01, -2.11715701e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4850.08740234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6559.31542969, 15406.84375 , 125.61533356]), + 'frame': 28511, + 'frame_number': 28511, + 'framesequence': 114787, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05478683114051819, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.2985419519246, + 'timestamp_carla': 968297, + 'timestamp_device': 1838901, + 'timestamp_stream': 968.2985419519246, + 'transform': [array([-56.90219498, 92.77274323, 0.11150238]), + array([ 5.27944899e+00, -1.69969391e+02, 4.34117857e-03])]} +{'AngularVelocity': array([-0.00900443, 0.00193711, 0.95640242]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26136600971221924, + 'FR_Wheel_Angle': 0.24099330604076385, + 'Location': array([3.37832522e+00, 9.18349304e+01, 1.78064348e-03]), + 'Rotation': array([ 0.0125334 , -2.68865991, -0.00930786]), + 'Velocity': array([ 9.71681881e+00, -4.33318764e-01, -2.54631027e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4849.63916015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6560.41992188, 15404.74609375, 125.6010437 ]), + 'frame': 28512, + 'frame_number': 28512, + 'framesequence': 114791, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05683767423033714, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.3335147500038, + 'timestamp_carla': 968332, + 'timestamp_device': 1838934, + 'timestamp_stream': 968.3335147500038, + 'transform': [array([-56.89647675, 92.75875854, 0.11150764]), + array([ 5.27938747e+00, -1.69953613e+02, 4.25184658e-03])]} +{'AngularVelocity': array([-0.00236775, 0.00316671, 0.77832663]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.23370838165283203, + 'FR_Wheel_Angle': 0.23420941829681396, + 'Location': array([5.01850796e+00, 9.17627487e+01, 1.78949349e-03]), + 'Rotation': array([ 0.01102392, -2.55020189, -0.00814819]), + 'Velocity': array([ 9.77938557e+00, -4.15291399e-01, -4.29153431e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4848.572265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6561.83789062, 15402.05664062, 125.6044693 ]), + 'frame': 28513, + 'frame_number': 28513, + 'framesequence': 114795, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06018860638141632, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.3662190511823, + 'timestamp_carla': 968364, + 'timestamp_device': 1838968, + 'timestamp_stream': 968.3662190511823, + 'transform': [array([-56.88949585, 92.74610138, 0.11139316]), + array([ 5.27920341e+00, -1.69931747e+02, 4.75970050e-03])]} +{'AngularVelocity': array([-4.10914916e-04, -4.94366419e-03, 7.71024644e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2335469126701355, + 'FR_Wheel_Angle': 0.2340567260980606, + 'Location': array([6.63695717e+00, 9.16951447e+01, 1.79262157e-03]), + 'Rotation': array([ 0.01049117, -2.4234314 , -0.00787353]), + 'Velocity': array([ 9.84548759e+00, -3.96162897e-01, -1.33514405e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4848.208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6562.88964844, 15400.06054688, 125.5956192 ]), + 'frame': 28514, + 'frame_number': 28514, + 'framesequence': 114799, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.062221139669418335, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.3989106491208, + 'timestamp_carla': 968397, + 'timestamp_device': 1839001, + 'timestamp_stream': 968.3989106491208, + 'transform': [array([-56.88323593, 92.73273468, 0.11173347]), + array([ 5.27975655e+00, -1.69913284e+02, 3.40156513e-03])]} +{'AngularVelocity': array([-0.02972223, -0.00359235, 0.37940654]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.01765255630016327, + 'FR_Wheel_Angle': -0.04962742701172829, + 'Location': array([8.29073048e+00, 9.16295013e+01, 1.79582590e-03]), + 'Rotation': array([ 0.00998574, -2.30841064, -0.00643921]), + 'Velocity': array([ 9.90300846e+00, -3.86611164e-01, 1.61170954e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4847.2421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6564.35693359, 15397.5078125 , 125.63929749]), + 'frame': 28515, + 'frame_number': 28515, + 'framesequence': 114803, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06161687523126602, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.4321770519018, + 'timestamp_carla': 968430, + 'timestamp_device': 1839034, + 'timestamp_stream': 968.4321770519018, + 'transform': [array([-56.87772751, 92.71887207, 0.11207748]), + array([ 5.28051472e+00, -1.69898209e+02, 2.02285009e-03])]} +{'AngularVelocity': array([-0.02835144, -0.00302148, -0.57273036]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22938790917396545, + 'FR_Wheel_Angle': -0.25080737471580505, + 'Location': array([9.93639183e+00, 9.15637894e+01, 1.79742812e-03]), + 'Rotation': array([ 9.70569812e-03, -2.33459473e+00, -1.19018543e-03]), + 'Velocity': array([ 9.95741081e+00, -4.09416467e-01, 9.58442683e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4849.8583984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6566.17431641, 15398.46484375, 125.52557373]), + 'frame': 28516, + 'frame_number': 28516, + 'framesequence': 114807, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06018860638141632, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.4654708504677, + 'timestamp_carla': 968464, + 'timestamp_device': 1839068, + 'timestamp_stream': 968.4654708504677, + 'transform': [array([-56.87092209, 92.70544434, 0.1120359 ]), + array([ 5.28076029e+00, -1.69877457e+02, 2.22134218e-03])]} +{'AngularVelocity': array([-0.03519955, -0.00211843, -1.3033433 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.4662650227546692, + 'FR_Wheel_Angle': -0.5525315999984741, + 'Location': array([1.16077929e+01, 9.14929657e+01, 1.80044165e-03]), + 'Rotation': array([ 0.00919343, -2.4883728 , 0.00350437]), + 'Velocity': array([ 1.00029936e+01, -4.49782580e-01, 1.83105465e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4852.30224609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6567.67578125, 15399.25585938, 125.40911102]), + 'frame': 28517, + 'frame_number': 28517, + 'framesequence': 114811, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059016697108745575, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.4978782497346, + 'timestamp_carla': 968496, + 'timestamp_device': 1839101, + 'timestamp_stream': 968.4978782497346, + 'transform': [array([-56.86194229, 92.69141388, 0.11220394]), + array([ 5.28097200e+00, -1.69848083e+02, 1.55615108e-03])]} +{'AngularVelocity': array([-4.45836037e-02, -1.81762478e-03, -2.58382988e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8636927604675293, + 'FR_Wheel_Angle': -0.8564542531967163, + 'Location': array([1.32775049e+01, 9.14132767e+01, 1.80181500e-03]), + 'Rotation': array([ 0.00895438, -2.82031298, 0.01118293]), + 'Velocity': array([ 1.00453806e+01, -5.31342447e-01, -4.67300396e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4855.0751953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6569.70019531, 15400.32421875, 125.42556 ]), + 'frame': 28518, + 'frame_number': 28518, + 'framesequence': 114815, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05949278548359871, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.531723652035, + 'timestamp_carla': 968530, + 'timestamp_device': 1839134, + 'timestamp_stream': 968.531723652035, + 'transform': [array([-56.85803604, 92.67557526, 0.11284794]), + array([ 5.28136826e+00, -1.69841309e+02, -1.16538582e-03])]} +{'AngularVelocity': array([-0.01410795, -0.00370244, -2.87200975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8501083850860596, + 'FR_Wheel_Angle': -0.8138533234596252, + 'Location': array([1.52767115e+01, 9.13003922e+01, 1.80448534e-03]), + 'Rotation': array([ 0.00853091, -3.37741137, 0.01568531]), + 'Velocity': array([ 1.00877399e+01, -6.33712053e-01, -2.61306764e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4858.486328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6572.55224609, 15401.82421875, 125.37008667]), + 'frame': 28519, + 'frame_number': 28519, + 'framesequence': 114819, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06035340577363968, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.5657512508333, + 'timestamp_carla': 968564, + 'timestamp_device': 1839168, + 'timestamp_stream': 968.5657512508333, + 'transform': [array([-56.85080338, 92.65999603, 0.11291184]), + array([ 5.28155279e+00, -1.69820221e+02, -1.44093763e-03])]} +{'AngularVelocity': array([ 0.02965646, -0.00577298, -2.0413096 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.4964572489261627, + 'FR_Wheel_Angle': -0.4012981057167053, + 'Location': array([1.69734688e+01, 9.11904755e+01, 1.80692668e-03]), + 'Rotation': array([ 0.00809377, -3.80395675, 0.01368726]), + 'Velocity': array([ 1.01174603e+01, -6.94638193e-01, -4.67300396e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4860.591796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6573.28417969, 15402.2109375 , 125.13996124]), + 'frame': 28520, + 'frame_number': 28520, + 'framesequence': 114823, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0603167861700058, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.5989458523691, + 'timestamp_carla': 968597, + 'timestamp_device': 1839201, + 'timestamp_stream': 968.5989458523691, + 'transform': [array([-56.84412384, 92.64517975, 0.11280414]), + array([ 5.28201723e+00, -1.69800797e+02, -9.20273713e-04])]} +{'AngularVelocity': array([ 0.04277582, -0.00821733, -0.5834831 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07702752947807312, + 'FR_Wheel_Angle': -0.034099139273166656, + 'Location': array([1.86672516e+01, 9.10739212e+01, 1.80818548e-03]), + 'Rotation': array([ 0.00799815, -4.01092625, 0.00635787]), + 'Velocity': array([ 1.01510124e+01, -7.09571898e-01, 1.21593475e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4863.615234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6575.35351562, 15403.30175781, 125.11603546]), + 'frame': 28521, + 'frame_number': 28521, + 'framesequence': 114826, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059859007596969604, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.6301430501044, + 'timestamp_carla': 968628, + 'timestamp_device': 1839226, + 'timestamp_stream': 968.6301430501044, + 'transform': [array([-56.83816147, 92.63152313, 0.11267658]), + array([ 5.28233814e+00, -1.69783569e+02, -2.76409148e-04])]} +{'AngularVelocity': array([ 0.017937 , 0.00893218, -0.05516662]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0022000635508447886, + 'FR_Wheel_Angle': 0.01759948581457138, + 'Location': array([2.03513432e+01, 9.09565201e+01, 1.81684492e-03]), + 'Rotation': array([ 7.15803774e-03, -4.04589939e+00, 1.35776703e-03]), + 'Velocity': array([ 1.01596518e+01, -7.10227132e-01, 1.00708003e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4866.44873046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6577.26318359, 15404.30664062, 125.15971375]), + 'frame': 28522, + 'frame_number': 28522, + 'framesequence': 114830, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.6644246503711, + 'timestamp_carla': 968663, + 'timestamp_device': 1839259, + 'timestamp_stream': 968.6644246503711, + 'transform': [array([-56.83041 , 92.61673737, 0.11239517]), + array([ 5.28237915e+00, -1.69759628e+02, 8.63470486e-04])]} +{'AngularVelocity': array([0.01477651, 0.00659799, 0.18744613]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07692094147205353, + 'FR_Wheel_Angle': 0.11766134202480316, + 'Location': array([2.24041710e+01, 9.08133011e+01, 1.81756972e-03]), + 'Rotation': array([ 7.39709428e-03, -4.03412008e+00, -1.70898426e-03]), + 'Velocity': array([ 1.01986065e+01, -7.07640350e-01, 2.71224962e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4869.01953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6578.96191406, 15405.20214844, 125.21517181]), + 'frame': 28523, + 'frame_number': 28523, + 'framesequence': 114834, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.6975097507238, + 'timestamp_carla': 968696, + 'timestamp_device': 1839293, + 'timestamp_stream': 968.6975097507238, + 'transform': [array([-56.82157516, 92.60224152, 0.11187255]), + array([ 5.28200340e+00, -1.69730911e+02, 3.04478593e-03])]} +{'AngularVelocity': array([0.01386116, 0.00784498, 0.59896708]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.19642242789268494, + 'FR_Wheel_Angle': 0.19788581132888794, + 'Location': array([2.41197033e+01, 9.06955185e+01, 1.82069780e-03]), + 'Rotation': array([ 0.00719219, -3.9620986 , -0.00466919]), + 'Velocity': array([ 1.02232170e+01, -6.89781427e-01, 2.79426558e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4872.15625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6581.30126953, 15406.43457031, 125.30975342]), + 'frame': 28524, + 'frame_number': 28524, + 'framesequence': 114839, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.7318612523377, + 'timestamp_carla': 968730, + 'timestamp_device': 1839334, + 'timestamp_stream': 968.7318612523377, + 'transform': [array([-56.81156158, 92.58776093, 0.11110088]), + array([ 5.28182602e+00, -1.69697372e+02, 6.26158901e-03])]} +{'AngularVelocity': array([-0.00070753, 0.00781839, 0.59546757]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.15584483742713928, + 'FR_Wheel_Angle': 0.1329912394285202, + 'Location': array([2.58192749e+01, 9.05819016e+01, 1.82188035e-03]), + 'Rotation': array([ 0.00707608, -3.85620213, -0.00582886]), + 'Velocity': array([ 1.02480774e+01, -6.73550785e-01, 1.94549557e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4875.576171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6584.08300781, 15407.8984375 , 125.49428558]), + 'frame': 28525, + 'frame_number': 28525, + 'framesequence': 114843, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.7649472504854, + 'timestamp_carla': 968763, + 'timestamp_device': 1839368, + 'timestamp_stream': 968.7649472504854, + 'transform': [array([-56.80442429, 92.57291412, 0.1112878 ]), + array([ 5.28198290e+00, -1.69676559e+02, 5.50717302e-03])]} +{'AngularVelocity': array([-0.01051992, 0.00856914, 0.16653803]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.01648055575788021, + 'FR_Wheel_Angle': 0.012086874805390835, + 'Location': array([2.75418663e+01, 9.04688187e+01, 1.82394020e-03]), + 'Rotation': array([ 0.00684385, -3.79269552, -0.00430298]), + 'Velocity': array([ 1.02672157e+01, -6.71019971e-01, 5.43594342e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4879.3193359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6587.31738281, 15409.60253906, 125.76538849]), + 'frame': 28526, + 'frame_number': 28526, + 'framesequence': 114847, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.7971938513219, + 'timestamp_carla': 968795, + 'timestamp_device': 1839401, + 'timestamp_stream': 968.7971938513219, + 'transform': [array([-56.79703903, 92.55792999, 0.11152199]), + array([ 5.28207207e+00, -1.69654694e+02, 4.56048083e-03])]} +{'AngularVelocity': array([-0.00704574, 0.00799355, -0.05187664]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.028563963249325752, + 'FR_Wheel_Angle': -0.034045085310935974, + 'Location': array([2.95789146e+01, 9.03356400e+01, 1.82416907e-03]), + 'Rotation': array([ 6.92581153e-03, -3.78344774e+00, -2.77709914e-03]), + 'Velocity': array([ 1.02942905e+01, -6.73913717e-01, 3.45230092e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4882.2646484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6589.37451172, 15410.68554688, 125.70233917]), + 'frame': 28527, + 'frame_number': 28527, + 'framesequence': 114850, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.8301083520055, + 'timestamp_carla': 968828, + 'timestamp_device': 1839426, + 'timestamp_stream': 968.8301083520055, + 'transform': [array([-56.78923035, 92.54264069, 0.11169288]), + array([ 5.28179884e+00, -1.69631256e+02, 3.80622223e-03])]} +{'AngularVelocity': array([-0.00376822, 0.00589224, -0.15943998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0505266934633255, + 'FR_Wheel_Angle': -0.05598614364862442, + 'Location': array([3.12938099e+01, 9.02230530e+01, 1.82550424e-03]), + 'Rotation': array([ 6.82335859e-03, -3.80328441e+00, -1.77001941e-03]), + 'Velocity': array([ 1.03129988e+01, -6.80123866e-01, 2.76565538e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4885.30078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6591.54003906, 15411.82714844, 125.6233902 ]), + 'frame': 28528, + 'frame_number': 28528, + 'framesequence': 114854, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.8643371500075, + 'timestamp_carla': 968863, + 'timestamp_device': 1839459, + 'timestamp_stream': 968.8643371500075, + 'transform': [array([-56.78190231, 92.52681732, 0.1118737 ]), + array([ 5.28216743e+00, -1.69610199e+02, 3.03760590e-03])]} +{'AngularVelocity': array([-0.00714159, 0.00704711, -0.31115106]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.12079727649688721, + 'FR_Wheel_Angle': -0.1228431984782219, + 'Location': array([3.30162582e+01, 9.01089630e+01, 1.82661053e-03]), + 'Rotation': array([ 6.78237760e-03, -3.84069920e+00, -7.62939453e-04]), + 'Velocity': array([ 1.03303919e+01, -6.90605700e-01, 4.49180607e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4888.4736328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6593.85351562, 15413.04589844, 125.56010437]), + 'frame': 28529, + 'frame_number': 28529, + 'framesequence': 114858, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.8964747525752, + 'timestamp_carla': 968895, + 'timestamp_device': 1839493, + 'timestamp_stream': 968.8964747525752, + 'transform': [array([-56.77516556, 92.51210022, 0.11190502]), + array([ 5.28244066e+00, -1.69590775e+02, 2.97608785e-03])]} +{'AngularVelocity': array([-0.00184965, 0.00804544, -0.42960998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1262647658586502, + 'FR_Wheel_Angle': -0.12610766291618347, + 'Location': array([3.50950470e+01, 8.99687653e+01, 1.82832719e-03]), + 'Rotation': array([ 6.65260386e-03, -3.92089987e+00, 3.64878273e-04]), + 'Velocity': array([ 1.03485937e+01, -7.07840264e-01, 5.37872302e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4891.54541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6595.94628906, 15414.1484375 , 125.49396515]), + 'frame': 28530, + 'frame_number': 28530, + 'framesequence': 114863, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.930658750236, + 'timestamp_carla': 968929, + 'timestamp_device': 1839534, + 'timestamp_stream': 968.930658750236, + 'transform': [array([-56.76854706, 92.49662781, 0.11190753]), + array([ 5.28259087e+00, -1.69572357e+02, 2.94189923e-03])]} +{'AngularVelocity': array([-0.00111332, 0.00266453, -0.43527338]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.12624211609363556, + 'FR_Wheel_Angle': -0.12608250975608826, + 'Location': array([3.67946129e+01, 8.98518066e+01, 1.82909006e-03]), + 'Rotation': array([ 6.68675499e-03, -3.99228001e+00, 6.96275907e-04]), + 'Velocity': array([ 1.03678856e+01, -7.22097635e-01, 6.76631907e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6269.00927734375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6846.23095703, 16767.16015625, 125.56067657]), + 'frame': 28531, + 'frame_number': 28531, + 'framesequence': 114867, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.9645260497928, + 'timestamp_carla': 968963, + 'timestamp_device': 1839568, + 'timestamp_stream': 968.9645260497928, + 'transform': [array([-56.76231766, 92.48175812, 0.11188854]), + array([ 5.28289843e+00, -1.69555191e+02, 3.04462970e-03])]} +{'AngularVelocity': array([ 0.00226854, 0.00975903, -0.40862322]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0998779833316803, + 'FR_Wheel_Angle': -0.07786542922258377, + 'Location': array([3.85519753e+01, 8.97286758e+01, 1.82992930e-03]), + 'Rotation': array([ 6.48184912e-03, -4.06497288e+00, 7.73667824e-04]), + 'Velocity': array([ 1.03789253e+01, -7.35491097e-01, -2.25257863e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6264.87109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6847.23583984, 16761.16796875, 125.55561829]), + 'frame': 28532, + 'frame_number': 28532, + 'framesequence': 114871, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 968.9982876516879, + 'timestamp_carla': 968996, + 'timestamp_device': 1839601, + 'timestamp_stream': 968.9982876516879, + 'transform': [array([-56.75288391, 92.46669006, 0.11181507]), + array([ 5.28271389e+00, -1.69524887e+02, 3.33223795e-03])]} +{'AngularVelocity': array([0.01147256, 0.01055202, 0.00108632]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.027426809072494507, + 'FR_Wheel_Angle': 0.030724484473466873, + 'Location': array([4.06484108e+01, 8.95799789e+01, 1.82661053e-03]), + 'Rotation': array([ 6.22913241e-03, -4.10894871e+00, -1.09863281e-03]), + 'Velocity': array([ 1.03952570e+01, -7.37530649e-01, -1.11961363e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6265.96875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6849.06103516, 16760.41015625, 125.56625366]), + 'frame': 28533, + 'frame_number': 28533, + 'framesequence': 114875, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.032014451921, + 'timestamp_carla': 969030, + 'timestamp_device': 1839634, + 'timestamp_stream': 969.032014451921, + 'transform': [array([-56.74604416, 92.45110321, 0.1120628 ]), + array([ 5.28216743e+00, -1.69505905e+02, 2.22129351e-03])]} +{'AngularVelocity': array([0.00868464, 0.00503522, 0.17284255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0668843537569046, + 'FR_Wheel_Angle': 0.0811883732676506, + 'Location': array([4.27126007e+01, 8.94338837e+01, 1.82088849e-03]), + 'Rotation': array([ 6.33841520e-03, -4.09094381e+00, -2.53295898e-03]), + 'Velocity': array([ 1.04161520e+01, -7.33599603e-01, -2.82573692e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6266.78955078125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6852.23583984, 16759.08984375, 125.59767151]), + 'frame': 28534, + 'frame_number': 28534, + 'framesequence': 114879, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.0665415488183, + 'timestamp_carla': 969065, + 'timestamp_device': 1839668, + 'timestamp_stream': 969.0665415488183, + 'transform': [array([-56.73948669, 92.43533325, 0.11217526]), + array([ 5.28179884e+00, -1.69488052e+02, 1.68021023e-03])]} +{'AngularVelocity': array([0.00879851, 0.01021092, 0.41326305]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1336653083562851, + 'FR_Wheel_Angle': 0.13493558764457703, + 'Location': array([4.44880295e+01, 8.93096466e+01, 1.81928626e-03]), + 'Rotation': array([ 0.00617449, -4.03888083, -0.00418091]), + 'Velocity': array([ 1.04258394e+01, -7.21027434e-01, -5.25474525e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6267.912109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6854.26269531, 16758.2421875 , 125.47769165]), + 'frame': 28535, + 'frame_number': 28535, + 'framesequence': 114883, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.1015491522849, + 'timestamp_carla': 969100, + 'timestamp_device': 1839701, + 'timestamp_stream': 969.1015491522849, + 'transform': [array([-56.73031998, 92.41992188, 0.11193226]), + array([ 5.28097200e+00, -1.69459091e+02, 2.59185233e-03])]} +{'AngularVelocity': array([0.00331968, 0.00080603, 0.46557412]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.13474245369434357, + 'FR_Wheel_Angle': 0.13491405546665192, + 'Location': array([4.62497482e+01, 8.91886520e+01, 1.81787484e-03]), + 'Rotation': array([ 0.00627694, -3.96237278, -0.0050354 ]), + 'Velocity': array([ 1.04422455e+01, -7.07793713e-01, -4.19616708e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4934.61572265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6612.71044922, 15445.37890625, 125.37974548]), + 'frame': 28536, + 'frame_number': 28536, + 'framesequence': 114887, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.1335273496807, + 'timestamp_carla': 969132, + 'timestamp_device': 1839734, + 'timestamp_stream': 969.1335273496807, + 'transform': [array([-56.7243042 , 92.40584564, 0.11198463]), + array([ 5.28130674e+00, -1.69442459e+02, 2.48912512e-03])]} +{'AngularVelocity': array([0.00147907, 0.00379056, 0.46904784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.13472065329551697, + 'FR_Wheel_Angle': 0.1348930299282074, + 'Location': array([4.79893456e+01, 8.90715103e+01, 1.81688310e-03]), + 'Rotation': array([ 0.00646819, -3.8842473 , -0.00540161]), + 'Velocity': array([ 1.04587679e+01, -6.94652796e-01, 4.45365913e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4932.978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6614.62158203, 15441.75 , 125.45774841]), + 'frame': 28537, + 'frame_number': 28537, + 'framesequence': 114891, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.1662563495338, + 'timestamp_carla': 969165, + 'timestamp_device': 1839768, + 'timestamp_stream': 969.1662563495338, + 'transform': [array([-56.71775436, 92.39025879, 0.11234466]), + array([ 5.28130674e+00, -1.69424896e+02, 9.86990053e-04])]} +{'AngularVelocity': array([0.00062879, 0.00738573, 0.46942112]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.13470174372196198, + 'FR_Wheel_Angle': 0.13487361371517181, + 'Location': array([4.97570648e+01, 8.89549179e+01, 1.81787484e-03]), + 'Rotation': array([ 0.00632476, -3.80474949, -0.0055542 ]), + 'Velocity': array([ 1.04697838e+01, -6.80865765e-01, 2.45094293e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4932.53369140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6615.73681641, 15439.6328125 , 125.45056152]), + 'frame': 28538, + 'frame_number': 28538, + 'framesequence': 114895, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.196949351579, + 'timestamp_carla': 969195, + 'timestamp_device': 1839801, + 'timestamp_stream': 969.196949351579, + 'transform': [array([-56.71120834, 92.37509918, 0.11276233]), + array([ 5.28140259e+00, -1.69407028e+02, -7.05651415e-04])]} +{'AngularVelocity': array([1.67508842e-05, 4.03153384e-03, 4.65084940e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.13249261677265167, + 'FR_Wheel_Angle': 0.1326577216386795, + 'Location': array([5.18512383e+01, 8.88199692e+01, 1.81810372e-03]), + 'Rotation': array([ 0.00630426, -3.71084714, -0.00564575]), + 'Velocity': array([ 1.04867640e+01, -6.64784789e-01, 1.73091883e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4932.1201171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6616.92431641, 15437.37890625, 125.32294464]), + 'frame': 28539, + 'frame_number': 28539, + 'framesequence': 114899, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.2299485504627, + 'timestamp_carla': 969228, + 'timestamp_device': 1839834, + 'timestamp_stream': 969.2299485504627, + 'transform': [array([-56.70376205, 92.35913849, 0.11283771]), + array([ 5.28149128e+00, -1.69385651e+02, -1.04288314e-03])]} +{'AngularVelocity': array([-0.00311564, 0.00582889, 0.42087153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1095103919506073, + 'FR_Wheel_Angle': 0.09646894782781601, + 'Location': array([5.39509315e+01, 8.86881027e+01, 1.81867590e-03]), + 'Rotation': array([ 0.00621547, -3.61932516, -0.00552368]), + 'Velocity': array([ 1.05007915e+01, -6.49712205e-01, 1.09672544e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4931.6337890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6618.12988281, 15435.08984375, 125.17990875]), + 'frame': 28540, + 'frame_number': 28540, + 'framesequence': 114902, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.2638829499483, + 'timestamp_carla': 969262, + 'timestamp_device': 1839859, + 'timestamp_stream': 969.2638829499483, + 'transform': [array([-56.69629288, 92.34320068, 0.11265586]), + array([ 5.28134108e+00, -1.69364151e+02, -3.37820937e-04])]} +{'AngularVelocity': array([-0.00837033, 0.00495956, 0.1853177 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03177843987941742, + 'FR_Wheel_Angle': 0.02630675956606865, + 'Location': array([5.57052879e+01, 8.85798416e+01, 1.81905739e-03]), + 'Rotation': array([ 0.00617449, -3.56817722, -0.00439453]), + 'Velocity': array([ 1.05119200e+01, -6.45022333e-01, 5.81741347e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4930.85986328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6619.55859375, 15432.37988281, 125.15048981]), + 'frame': 28541, + 'frame_number': 28541, + 'framesequence': 114906, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.2961930520833, + 'timestamp_carla': 969294, + 'timestamp_device': 1839893, + 'timestamp_stream': 969.2961930520833, + 'transform': [array([-56.68870163, 92.32835388, 0.11244735]), + array([ 5.28121805e+00, -1.69341385e+02, 5.54800034e-04])]} +{'AngularVelocity': array([-0.01080878, 0.00570038, -0.08702311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04932118579745293, + 'FR_Wheel_Angle': -0.10073354095220566, + 'Location': array([5.74613724e+01, 8.84719315e+01, 1.81936263e-03]), + 'Rotation': array([ 6.15400029e-03, -3.55972385e+00, -2.77709938e-03]), + 'Velocity': array([ 1.05219154e+01, -6.48311436e-01, 2.47955313e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4930.0830078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6620.98779297, 15429.66601562, 125.20975494]), + 'frame': 28542, + 'frame_number': 28542, + 'framesequence': 114911, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059840694069862366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.3311045505106, + 'timestamp_carla': 969329, + 'timestamp_device': 1839934, + 'timestamp_stream': 969.3311045505106, + 'transform': [array([-56.68176651, 92.3121109 , 0.11244644]), + array([ 5.28134108e+00, -1.69322372e+02, 4.99604153e-04])]} +{'AngularVelocity': array([-0.05402214, 0.0086819 , -1.33717978]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5304184556007385, + 'FR_Wheel_Angle': -0.6685166954994202, + 'Location': array([5.92128296e+01, 8.83618469e+01, 1.81924819e-03]), + 'Rotation': array([ 6.17449079e-03, -3.66375899e+00, 3.05712153e-03]), + 'Velocity': array([ 1.05297470e+01, -6.90016925e-01, 2.17437741e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4930.564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6622.76513672, 15428.27539062, 125.28646851]), + 'frame': 28543, + 'frame_number': 28543, + 'framesequence': 114915, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059236425906419754, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.3663460500538, + 'timestamp_carla': 969365, + 'timestamp_device': 1839968, + 'timestamp_stream': 969.3663460500538, + 'transform': [array([-56.67427444, 92.2963028 , 0.11220497]), + array([ 5.28109503e+00, -1.69300766e+02, 1.44613453e-03])]} +{'AngularVelocity': array([-0.06609386, 0.00635923, -3.39212632]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0979962348937988, + 'FR_Wheel_Angle': -1.1357423067092896, + 'Location': array([6.09609032e+01, 8.82407379e+01, 1.81959150e-03]), + 'Rotation': array([ 0.00611985, -4.07745504, 0.0150047 ]), + 'Velocity': array([ 1.05321875e+01, -7.99064696e-01, -1.48773188e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4933.5712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6624.68701172, 15429.2890625 , 125.27997589]), + 'frame': 28544, + 'frame_number': 28544, + 'framesequence': 114919, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04892727732658386, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.3999550491571, + 'timestamp_carla': 969398, + 'timestamp_device': 1840001, + 'timestamp_stream': 969.3999550491571, + 'transform': [array([-56.66718292, 92.28119659, 0.11221279]), + array([ 5.28069878e+00, -1.69280945e+02, 1.39811856e-03])]} +{'AngularVelocity': array([-0.05780293, 0.00476193, -4.55433989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.4068970680236816, + 'FR_Wheel_Angle': -1.4902143478393555, + 'Location': array([6.27053757e+01, 8.81006165e+01, 1.81997300e-03]), + 'Rotation': array([ 0.00607887, -4.7442646 , 0.02445229]), + 'Velocity': array([ 1.05298414e+01, -9.37912405e-01, 1.95503233e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4936.70458984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6626.84765625, 15430.42675781, 125.35990143]), + 'frame': 28545, + 'frame_number': 28545, + 'framesequence': 114923, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.028125859797000885, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.4332606494427, + 'timestamp_carla': 969432, + 'timestamp_device': 1840034, + 'timestamp_stream': 969.4332606494427, + 'transform': [array([-56.66000748, 92.26504517, 0.11237579]), + array([ 5.27981806e+00, -1.69262222e+02, 6.37217483e-04])]} +{'AngularVelocity': array([-0.07212434, 0.01962778, -6.76189089]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.1246776580810547, + 'FR_Wheel_Angle': -2.142832040786743, + 'Location': array([6.45745163e+01, 8.79205627e+01, 1.82397838e-03]), + 'Rotation': array([ 5.40950941e-03, -5.75406218e+00, 3.82294320e-02]), + 'Velocity': array([ 1.04992065e+01, -1.15414977e+00, -2.66075131e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4939.64599609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6628.83349609, 15431.47265625, 125.35697174]), + 'frame': 28546, + 'frame_number': 28546, + 'framesequence': 114927, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.004779198672622442, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.4644819498062, + 'timestamp_carla': 969463, + 'timestamp_device': 1840068, + 'timestamp_stream': 969.4644819498062, + 'transform': [array([-56.65527725, 92.24900055, 0.11240318]), + array([ 5.27916908e+00, -1.69254364e+02, 5.27093129e-04])]} +{'AngularVelocity': array([-3.77319418e-02, 2.71338224e-03, -7.59966850e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.2009801864624023, + 'FR_Wheel_Angle': -2.1550111770629883, + 'Location': array([6.62177505e+01, 8.77277145e+01, 1.81974412e-03]), + 'Rotation': array([ 6.14716997e-03, -6.90784311e+00, 4.82627824e-02]), + 'Velocity': array([ 1.04951448e+01, -1.38243675e+00, -4.81605525e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4942.61376953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.70410156, 15432.45898438, 125.29351044]), + 'frame': 28547, + 'frame_number': 28547, + 'framesequence': 114931, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.016827907413244247, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.498374748975, + 'timestamp_carla': 969497, + 'timestamp_device': 1840101, + 'timestamp_stream': 969.498374748975, + 'transform': [array([-56.65291977, 92.23177338, 0.11223 ]), + array([ 5.27849293e+00, -1.69258240e+02, 1.15171552e-03])]} +{'AngularVelocity': array([-0.03436984, 0.0110591 , -7.97752047]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.3685131072998047, + 'FR_Wheel_Angle': -2.4169135093688965, + 'Location': array([6.79556427e+01, 8.74856415e+01, 1.82176591e-03]), + 'Rotation': array([ 5.82615100e-03, -8.18869972e+00, 5.29906191e-02]), + 'Velocity': array([ 1.04620543e+01, -1.62066483e+00, 1.59263607e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4944.8046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6631.49316406, 15432.87304688, 125.28662872]), + 'frame': 28548, + 'frame_number': 28548, + 'framesequence': 114935, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.025946836918592453, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.5321661494672, + 'timestamp_carla': 969530, + 'timestamp_device': 1840134, + 'timestamp_stream': 969.5321661494672, + 'transform': [array([-56.65107727, 92.21487427, 0.11193058]), + array([ 5.27819920e+00, -1.69264633e+02, 2.37218337e-03])]} +{'AngularVelocity': array([-8.32294002e-02, 5.97111974e-03, -9.95196915e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.100964307785034, + 'FR_Wheel_Angle': -3.1323676109313965, + 'Location': array([7.01984329e+01, 8.71080475e+01, 1.82775490e-03]), + 'Rotation': array([ 4.82894341e-03, -1.01084127e+01, 6.47889078e-02]), + 'Velocity': array([ 1.03832541e+01, -1.99876463e+00, -1.84059138e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4946.2861328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6631.109375 , 15432.671875 , 125.33991241]), + 'frame': 28549, + 'frame_number': 28549, + 'framesequence': 114939, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.019373148679733276, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.5654566511512, + 'timestamp_carla': 969564, + 'timestamp_device': 1840167, + 'timestamp_stream': 969.5654566511512, + 'transform': [array([-56.64988708, 92.1985321 , 0.11172016]), + array([ 5.27862263e+00, -1.69273331e+02, 3.31892632e-03])]} +{'AngularVelocity': array([ -0.0917355 , 0.02075955, -12.39818573]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9636311531066895, + 'FR_Wheel_Angle': -4.007233142852783, + 'Location': array([7.21607666e+01, 8.67007217e+01, 1.82706828e-03]), + 'Rotation': array([ 4.93139634e-03, -1.22248716e+01, 8.06935579e-02]), + 'Velocity': array([ 1.02877350e+01, -2.42203188e+00, 8.24928293e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4947.54541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.45458984, 15432.32617188, 125.44438171]), + 'frame': 28550, + 'frame_number': 28550, + 'framesequence': 114943, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.006683554034680128, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.598989252001, + 'timestamp_carla': 969597, + 'timestamp_device': 1840201, + 'timestamp_stream': 969.598989252001, + 'transform': [array([-56.64757156, 92.18238831, 0.11160183]), + array([ 5.27968836e+00, -1.69276855e+02, 3.93626792e-03])]} +{'AngularVelocity': array([ -0.13242424, 0.04140633, -16.54154396]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.344378471374512, + 'FR_Wheel_Angle': -5.223050117492676, + 'Location': array([7.41781464e+01, 8.61831207e+01, 1.83565135e-03]), + 'Rotation': array([ 3.51071707e-03, -1.50767689e+01, 1.04461022e-01]), + 'Velocity': array([ 1.01044683e+01, -2.98162293e+00, -1.95503230e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4948.58837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.57519531, 15431.86328125, 125.52520752]), + 'frame': 28551, + 'frame_number': 28551, + 'framesequence': 114947, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0062990207225084305, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.6313191503286, + 'timestamp_carla': 969630, + 'timestamp_device': 1840234, + 'timestamp_stream': 969.6313191503286, + 'transform': [array([-56.64523697, 92.16717529, 0.11155735]), + array([ 5.28078794e+00, -1.69278961e+02, 4.27902583e-03])]} +{'AngularVelocity': array([ -0.11710121, 0.04043324, -19.98453903]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.054922580718994, + 'FR_Wheel_Angle': -5.836706161499023, + 'Location': array([7.61418915e+01, 8.55506363e+01, 1.84206001e-03]), + 'Rotation': array([ 2.41105654e-03, -1.87023964e+01, 1.30444631e-01]), + 'Velocity': array([ 9.83863163e+00, -3.65003920e+00, -2.14576721e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4949.974609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.2109375 , 15431.67089844, 125.57697296]), + 'frame': 28552, + 'frame_number': 28552, + 'framesequence': 114951, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.01268959604203701, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.6652001515031, + 'timestamp_carla': 969663, + 'timestamp_device': 1840267, + 'timestamp_stream': 969.6652001515031, + 'transform': [array([-56.64120483, 92.15155792, 0.11147483]), + array([ 5.28174400e+00, -1.69273941e+02, 4.70420253e-03])]} +{'AngularVelocity': array([ -0.05188692, 0.03814439, -21.90632439]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.725451469421387, + 'FR_Wheel_Angle': -6.432186603546143, + 'Location': array([7.77141113e+01, 8.49307098e+01, 1.84736250e-03]), + 'Rotation': array([ 1.53679249e-03, -2.20988007e+01, 1.47116616e-01]), + 'Velocity': array([ 9.54928684e+00, -4.22924232e+00, -2.05993638e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4951.37744140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.00341797, 15431.5625 , 125.60609436]), + 'frame': 28553, + 'frame_number': 28553, + 'framesequence': 114955, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.010547197423875332, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.6980649493635, + 'timestamp_carla': 969696, + 'timestamp_device': 1840301, + 'timestamp_stream': 969.6980649493635, + 'transform': [array([-56.6378746 , 92.13668823, 0.11142189]), + array([ 5.28219461e+00, -1.69271210e+02, 4.99288691e-03])]} +{'AngularVelocity': array([ -0.04192371, 0.03696551, -24.15994835]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.4595794677734375, + 'FR_Wheel_Angle': -7.1092000007629395, + 'Location': array([7.93065338e+01, 8.41801758e+01, 1.85728073e-03]), + 'Rotation': array([-1.57094342e-04, -2.60342216e+01, 1.62116259e-01]), + 'Velocity': array([ 9.16298866e+00, -4.85685968e+00, -2.09808354e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4953.31787109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.5 , 15431.82421875, 125.64100647]), + 'frame': 28554, + 'frame_number': 28554, + 'framesequence': 114959, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.004412976559251547, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.7308172509074, + 'timestamp_carla': 969729, + 'timestamp_device': 1840334, + 'timestamp_stream': 969.7308172509074, + 'transform': [array([-56.63411331, 92.12187958, 0.11136753]), + array([ 5.28225613e+00, -1.69266815e+02, 5.23955468e-03])]} +{'AngularVelocity': array([ -0.02960439, 0.03435754, -26.3693161 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.20536994934082, + 'FR_Wheel_Angle': -7.673534393310547, + 'Location': array([8.07745361e+01, 8.33522949e+01, 1.85903546e-03]), + 'Rotation': array([-4.23471705e-04, -3.01948643e+01, 1.78509325e-01]), + 'Velocity': array([ 8.72530079e+00, -5.51079893e+00, 2.57492047e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4955.02880859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.77832031, 15431.97070312, 125.66568756]), + 'frame': 28555, + 'frame_number': 28555, + 'framesequence': 114963, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0020691549871116877, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.7652331516147, + 'timestamp_carla': 969764, + 'timestamp_device': 1840367, + 'timestamp_stream': 969.7652331516147, + 'transform': [array([-56.63121796, 92.10606384, 0.11135132]), + array([ 5.28189421e+00, -1.69267044e+02, 5.21892030e-03])]} +{'AngularVelocity': array([ -0.04311996, 0.03318984, -28.11190414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.735074996948242, + 'FR_Wheel_Angle': -8.058874130249023, + 'Location': array([8.21892395e+01, 8.24007492e+01, 1.85461040e-03]), + 'Rotation': array([ 3.27849062e-04, -3.47392693e+01, 1.95348978e-01]), + 'Velocity': array([ 8.21266174e+00, -6.20968008e+00, -1.02043145e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4956.84521484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.21533203, 15432.20117188, 125.68719482]), + 'frame': 28556, + 'frame_number': 28556, + 'framesequence': 114966, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.005932798609137535, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.79666955024, + 'timestamp_carla': 969795, + 'timestamp_device': 1840392, + 'timestamp_stream': 969.79666955024, + 'transform': [array([-56.62911606, 92.09171295, 0.11134418]), + array([ 5.28161430e+00, -1.69269653e+02, 5.28102648e-03])]} +{'AngularVelocity': array([ 8.82085878e-03, 8.99847364e-05, -2.85428295e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.636870384216309, + 'FR_Wheel_Angle': -7.773036479949951, + 'Location': array([8.37603073e+01, 8.11216354e+01, 1.85560226e-03]), + 'Rotation': array([ 1.50264153e-04, -4.03751144e+01, 2.02354223e-01]), + 'Velocity': array([ 7.52416658e+00, -6.96494389e+00, -3.76701337e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4958.4404296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.19824219, 15432.19140625, 125.68479156]), + 'frame': 28557, + 'frame_number': 28557, + 'framesequence': 114970, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.004632710013538599, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.8302867524326, + 'timestamp_carla': 969829, + 'timestamp_device': 1840426, + 'timestamp_stream': 969.8302867524326, + 'transform': [array([-56.62651825, 92.07667542, 0.11131737]), + array([ 5.28157997e+00, -1.69270874e+02, 5.36333863e-03])]} +{'AngularVelocity': array([ 0.20164792, -0.21277778, -22.29185867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.850718975067139, + 'FR_Wheel_Angle': -4.711066722869873, + 'Location': array([8.52128754e+01, 7.96908875e+01, 1.85197825e-03]), + 'Rotation': array([ 7.37660390e-04, -4.56650314e+01, 1.78590462e-01]), + 'Velocity': array([ 6.91416359e+00, -7.53008461e+00, 8.21113554e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4959.7197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.94433594, 15432.05664062, 125.69197083]), + 'frame': 28558, + 'frame_number': 28558, + 'framesequence': 114975, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0018311106832697988, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.8653712496161, + 'timestamp_carla': 969864, + 'timestamp_device': 1840467, + 'timestamp_stream': 969.8653712496161, + 'transform': [array([-56.62143326, 92.06099701, 0.11121368]), + array([ 5.28174400e+00, -1.69262207e+02, 5.75421331e-03])]} +{'AngularVelocity': array([ 0.27759767, -0.31452581, -9.12460327]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.8355066776275635, + 'FR_Wheel_Angle': -1.5885839462280273, + 'Location': array([8.63501663e+01, 7.84383011e+01, 1.84095383e-03]), + 'Rotation': array([ 2.56815087e-03, -4.81779594e+01, 1.08714327e-01]), + 'Velocity': array([ 6.73600626e+00, -7.68117285e+00, 8.06808475e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4961.16259765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.81835938, 15431.99023438, 125.69852448]), + 'frame': 28559, + 'frame_number': 28559, + 'framesequence': 114979, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0016663107089698315, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.8980277515948, + 'timestamp_carla': 969896, + 'timestamp_device': 1840501, + 'timestamp_stream': 969.8980277515948, + 'transform': [array([-56.61896515, 92.04624176, 0.11133793]), + array([ 5.28170967e+00, -1.69263535e+02, 5.26698725e-03])]} +{'AngularVelocity': array([ 0.11625913, -0.13327122, -4.82043791]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.302282691001892, + 'FR_Wheel_Angle': -1.2023669481277466, + 'Location': array([8.74630661e+01, 7.71606674e+01, 1.83507917e-03]), + 'Rotation': array([ 3.59950960e-03, -4.92086143e+01, 6.35966435e-02]), + 'Velocity': array([ 6.62294912e+00, -7.76278496e+00, -2.40325926e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4963.3583984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.65771484, 15432.43359375, 125.73059845]), + 'frame': 28560, + 'frame_number': 28560, + 'framesequence': 114983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.002600177191197872, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.9339357502759, + 'timestamp_carla': 969932, + 'timestamp_device': 1840534, + 'timestamp_stream': 969.9339357502759, + 'transform': [array([-56.61672592, 92.03005981, 0.11150093]), + array([ 5.28140259e+00, -1.69267014e+02, 4.45747934e-03])]} +{'AngularVelocity': array([ 0.08739911, -0.10381605, -2.81585646]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6688414216041565, + 'FR_Wheel_Angle': -0.5721509456634521, + 'Location': array([8.85663147e+01, 7.58600693e+01, 1.83256145e-03]), + 'Rotation': array([ 4.02981136e-03, -4.98484268e+01, 3.76201980e-02]), + 'Velocity': array([ 6.54815292e+00, -7.80884075e+00, -1.88350668e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4964.76953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.53125 , 15432.3671875 , 125.68994904]), + 'frame': 28561, + 'frame_number': 28561, + 'framesequence': 114987, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00119022186845541, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.9665432497859, + 'timestamp_carla': 969965, + 'timestamp_device': 1840567, + 'timestamp_stream': 969.9665432497859, + 'transform': [array([-56.61327362, 92.01525116, 0.11160709]), + array([ 5.28109503e+00, -1.69264404e+02, 4.03916603e-03])]} +{'AngularVelocity': array([ 0.04489605, -0.04845849, -1.55681074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.4290654957294464, + 'FR_Wheel_Angle': -0.4305737316608429, + 'Location': array([8.96574860e+01, 7.45561905e+01, 1.82989112e-03]), + 'Rotation': array([ 4.47377376e-03, -5.01803703e+01, 2.04369780e-02]), + 'Velocity': array([ 6.50853634e+00, -7.82815218e+00, -8.48770128e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4966.18017578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.203125 , 15432.19335938, 125.6188736 ]), + 'frame': 28562, + 'frame_number': 28562, + 'framesequence': 114991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0005310220876708627, + 'throttle_input': 0.2222171425819397, + 'timestamp': 969.9998684488237, + 'timestamp_carla': 969998, + 'timestamp_device': 1840601, + 'timestamp_stream': 969.9998684488237, + 'transform': [array([-56.6107254 , 92.00003052, 0.11170208]), + array([ 5.28079462e+00, -1.69265945e+02, 3.62080056e-03])]} +{'AngularVelocity': array([ 0.00331507, 0.00670806, -2.09002948]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.8362544178962708, + 'FR_Wheel_Angle': -0.9550022482872009, + 'Location': array([9.07416611e+01, 7.32471542e+01, 1.82939530e-03]), + 'Rotation': array([ 4.54890588e-03, -5.04648895e+01, 1.59099251e-02]), + 'Velocity': array([ 6.45200729e+00, -7.85868263e+00, -1.59263607e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4967.87060546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.46142578, 15432.33007812, 125.58489227]), + 'frame': 28563, + 'frame_number': 28563, + 'framesequence': 114995, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0011352886212989688, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.0314722508192, + 'timestamp_carla': 970030, + 'timestamp_device': 1840634, + 'timestamp_stream': 970.0314722508192, + 'transform': [array([-56.6080513 , 91.98612976, 0.11161377]), + array([ 5.28051472e+00, -1.69265854e+02, 4.02549794e-03])]} +{'AngularVelocity': array([-0.03510553, 0.04802332, -4.48374462]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.6232060194015503, + 'FR_Wheel_Angle': -1.7345083951950073, + 'Location': array([9.20165634e+01, 7.16768112e+01, 1.82897563e-03]), + 'Rotation': array([ 4.63769818e-03, -5.11211472e+01, 2.48325802e-02]), + 'Velocity': array([ 6.32218027e+00, -7.94913673e+00, -8.05854768e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4969.314453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.31347656, 15432.25195312, 125.54976654]), + 'frame': 28564, + 'frame_number': 28564, + 'framesequence': 114999, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00021973327966406941, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.0650724507868, + 'timestamp_carla': 970063, + 'timestamp_device': 1840667, + 'timestamp_stream': 970.0650724507868, + 'transform': [array([-56.60462189, 91.97138214, 0.11152286]), + array([ 5.28036451e+00, -1.69263245e+02, 4.36862232e-03])]} +{'AngularVelocity': array([-0.0354944 , 0.05367509, -6.87855434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.1968653202056885, + 'FR_Wheel_Angle': -2.2471389770507812, + 'Location': array([9.32744446e+01, 7.00667343e+01, 1.82973861e-03]), + 'Rotation': array([ 4.52158507e-03, -5.22926407e+01, 3.92133370e-02]), + 'Velocity': array([ 6.11894655e+00, -8.08631706e+00, -2.81333928e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4970.7333984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.31738281, 15432.25390625, 125.58638 ]), + 'frame': 28565, + 'frame_number': 28565, + 'framesequence': 115003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0005859553930349648, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.0973965488374, + 'timestamp_carla': 970096, + 'timestamp_device': 1840701, + 'timestamp_stream': 970.0973965488374, + 'transform': [array([-56.60209656, 91.95755768, 0.11145004]), + array([ 5.28027534e+00, -1.69263626e+02, 4.69063362e-03])]} +{'AngularVelocity': array([-0.03381614, 0.05158384, -8.52499676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.6903135776519775, + 'FR_Wheel_Angle': -2.6743359565734863, + 'Location': array([9.42744522e+01, 6.87218857e+01, 1.82981486e-03]), + 'Rotation': array([ 4.50792443e-03, -5.35822830e+01, 5.08370213e-02]), + 'Velocity': array([ 5.90864849e+00, -8.22850132e+00, 5.67436189e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4972.4111328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.56445312, 15432.38476562, 125.61553955]), + 'frame': 28566, + 'frame_number': 28566, + 'framesequence': 115007, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00021973327966406941, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.1321982517838, + 'timestamp_carla': 970131, + 'timestamp_device': 1840734, + 'timestamp_stream': 970.1321982517838, + 'transform': [array([-56.59990692, 91.94252014, 0.11156711]), + array([ 5.28005695e+00, -1.69266449e+02, 4.10142913e-03])]} +{'AngularVelocity': array([-7.21747847e-03, 2.25324295e-02, -9.35254669e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.8480327129364014, + 'FR_Wheel_Angle': -2.7853198051452637, + 'Location': array([9.52476273e+01, 6.73395462e+01, 1.83015817e-03]), + 'Rotation': array([ 4.47377376e-03, -5.51017075e+01, 5.93339242e-02]), + 'Velocity': array([ 5.67225838e+00, -8.37800217e+00, -6.19888283e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4973.7900390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.52587891, 15432.36328125, 125.64403534]), + 'frame': 28567, + 'frame_number': 28567, + 'framesequence': 115011, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00042115544783882797, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.1655080504715, + 'timestamp_carla': 970164, + 'timestamp_device': 1840767, + 'timestamp_stream': 970.1655080504715, + 'transform': [array([-56.59916687, 91.92777252, 0.11183113]), + array([ 5.28045321e+00, -1.69274902e+02, 3.03786551e-03])]} +{'AngularVelocity': array([ -0.01466765, 0.03876521, -10.28420067]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.3605408668518066, + 'FR_Wheel_Angle': -3.3446197509765625, + 'Location': array([9.61818466e+01, 6.59302750e+01, 1.83065410e-03]), + 'Rotation': array([ 4.40547196e-03, -5.67331276e+01, 6.62136152e-02]), + 'Velocity': array([ 5.41077137e+00, -8.53367805e+00, -3.40461725e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4975.12890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.25585938, 15432.22167969, 125.59194946]), + 'frame': 28568, + 'frame_number': 28568, + 'framesequence': 115015, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00020142216817475855, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.1977785490453, + 'timestamp_carla': 970196, + 'timestamp_device': 1840801, + 'timestamp_stream': 970.1977785490453, + 'transform': [array([-56.5969429 , 91.9138031 , 0.11179554]), + array([ 5.28067160e+00, -1.69276505e+02, 3.25045129e-03])]} +{'AngularVelocity': array([ -0.01343576, 0.02751905, -11.79907703]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6274962425231934, + 'FR_Wheel_Angle': -3.513812780380249, + 'Location': array([9.72290726e+01, 6.42224121e+01, 1.83176040e-03]), + 'Rotation': array([ 4.24154708e-03, -5.89690514e+01, 7.67478868e-02]), + 'Velocity': array([ 5.04633808e+00, -8.73913288e+00, -1.62124635e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4976.04638671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.44238281, 15431.79296875, 125.50038147]), + 'frame': 28569, + 'frame_number': 28569, + 'framesequence': 115019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.2310422509909, + 'timestamp_carla': 970229, + 'timestamp_device': 1840834, + 'timestamp_stream': 970.2310422509909, + 'transform': [array([-56.59431458, 91.89941406, 0.11180054]), + array([ 5.28076029e+00, -1.69276932e+02, 3.22960573e-03])]} +{'AngularVelocity': array([-2.80247856e-04, 1.88739803e-02, -1.23157444e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.807425022125244, + 'FR_Wheel_Angle': -3.7143731117248535, + 'Location': array([9.80571747e+01, 6.27481918e+01, 1.83206552e-03]), + 'Rotation': array([ 4.19373577e-03, -6.09945145e+01, 8.18581954e-02]), + 'Velocity': array([ 4.72102880e+00, -8.90282345e+00, 3.03268416e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4977.357421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.28662109, 15431.71191406, 125.51942444]), + 'frame': 28570, + 'frame_number': 28570, + 'framesequence': 115023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.2643101513386, + 'timestamp_carla': 970263, + 'timestamp_device': 1840867, + 'timestamp_stream': 970.2643101513386, + 'transform': [array([-56.59171295, 91.88449097, 0.11205348]), + array([ 5.28054857e+00, -1.69278214e+02, 2.12525763e-03])]} +{'AngularVelocity': array([ 3.62050207e-03, 7.18507171e-03, -1.28653316e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.939063310623169, + 'FR_Wheel_Angle': -3.7946677207946777, + 'Location': array([9.88175735e+01, 6.12699699e+01, 1.83198927e-03]), + 'Rotation': array([ 4.20056609e-03, -6.30938416e+01, 8.66986215e-02]), + 'Velocity': array([ 4.37897253e+00, -9.06504154e+00, 1.33514405e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4978.79345703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.24414062, 15431.68945312, 125.51743317]), + 'frame': 28571, + 'frame_number': 28571, + 'framesequence': 115027, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.2983668521047, + 'timestamp_carla': 970297, + 'timestamp_device': 1840901, + 'timestamp_stream': 970.2983668521047, + 'transform': [array([-56.58728027, 91.8686676 , 0.11226501]), + array([ 5.28103352e+00, -1.69272324e+02, 1.25391316e-03])]} +{'AngularVelocity': array([ 4.64415504e-03, -6.27546106e-04, -1.29098988e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9395086765289307, + 'FR_Wheel_Angle': -3.795046329498291, + 'Location': array([9.96582565e+01, 5.94563599e+01, 1.83225633e-03]), + 'Rotation': array([ 4.18007560e-03, -6.56671906e+01, 8.86317417e-02]), + 'Velocity': array([ 3.96222854e+00, -9.24131775e+00, 1.23023983e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4980.22509765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.12353516, 15431.62597656, 125.42237091]), + 'frame': 28572, + 'frame_number': 28572, + 'framesequence': 115030, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.3299331516027, + 'timestamp_carla': 970328, + 'timestamp_device': 1840926, + 'timestamp_stream': 970.3299331516027, + 'transform': [array([-56.58446121, 91.85403442, 0.11237465]), + array([ 5.28093815e+00, -1.69272247e+02, 8.36031279e-04])]} +{'AngularVelocity': array([ 7.22680520e-03, -2.61482922e-03, -1.29135342e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9532713890075684, + 'FR_Wheel_Angle': -3.8405685424804688, + 'Location': array([1.00298477e+02, 5.79110718e+01, 1.83271407e-03]), + 'Rotation': array([ 4.07762267e-03, -6.78234634e+01, 8.91463533e-02]), + 'Velocity': array([ 3.60667896e+00, -9.37120152e+00, 3.52859502e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4982.24755859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.70654297, 15431.93261719, 125.34619141]), + 'frame': 28573, + 'frame_number': 28573, + 'framesequence': 115035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.3700133524835, + 'timestamp_carla': 970368, + 'timestamp_device': 1840967, + 'timestamp_stream': 970.3700133524835, + 'transform': [array([-56.58055496, 91.83544922, 0.11234272]), + array([ 5.28069878e+00, -1.69270767e+02, 9.66411259e-04])]} +{'AngularVelocity': array([-6.47010340e-04, 2.11812332e-02, -1.37224979e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.2890191078186035, + 'FR_Wheel_Angle': -4.142849922180176, + 'Location': array([1.00881874e+02, 5.63331223e+01, 1.83431618e-03]), + 'Rotation': array([ 3.81124532e-03, -7.00582809e+01, 9.28657055e-02]), + 'Velocity': array([ 3.21769524e+00, -9.49191475e+00, -3.74793990e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4983.74365234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.71484375, 15431.9375 , 125.3115921 ]), + 'frame': 28574, + 'frame_number': 28574, + 'framesequence': 115039, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.4033726491034, + 'timestamp_carla': 970402, + 'timestamp_device': 1841001, + 'timestamp_stream': 970.4033726491034, + 'transform': [array([-56.57735062, 91.81958008, 0.11232872]), + array([ 5.28057623e+00, -1.69270081e+02, 9.79861710e-04])]} +{'AngularVelocity': array([ 6.01732126e-03, 4.68765246e-03, -1.42498131e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.454176902770996, + 'FR_Wheel_Angle': -4.277623653411865, + 'Location': array([1.01392731e+02, 5.47555618e+01, 1.83500291e-03]), + 'Rotation': array([ 3.73611320e-03, -7.23926163e+01, 9.66549218e-02]), + 'Velocity': array([ 2.81548667e+00, -9.60179901e+00, -2.38418579e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4985.736328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.85644531, 15432.01171875, 125.32362366]), + 'frame': 28575, + 'frame_number': 28575, + 'framesequence': 115043, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.4378734491765, + 'timestamp_carla': 970436, + 'timestamp_device': 1841034, + 'timestamp_stream': 970.4378734491765, + 'transform': [array([-56.57371521, 91.80364227, 0.11210178]), + array([ 5.28039837e+00, -1.69267563e+02, 1.86492526e-03])]} +{'AngularVelocity': array([ 1.15980254e-02, -8.03713594e-03, -1.44659014e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.462847709655762, + 'FR_Wheel_Angle': -4.278537273406982, + 'Location': array([1.01923035e+02, 5.28163643e+01, 1.83671946e-03]), + 'Rotation': array([ 3.46290576e-03, -7.53065796e+01, 9.89544913e-02]), + 'Velocity': array([ 2.31540132e+00, -9.70815086e+00, 2.72750844e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4987.39599609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.91894531, 15432.04394531, 125.32420349]), + 'frame': 28576, + 'frame_number': 28576, + 'framesequence': 115047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.470575351268, + 'timestamp_carla': 970469, + 'timestamp_device': 1841067, + 'timestamp_stream': 970.470575351268, + 'transform': [array([-56.57144547, 91.7885437 , 0.11204342]), + array([ 5.28027534e+00, -1.69270081e+02, 2.12589954e-03])]} +{'AngularVelocity': array([ 9.45063308e-03, -9.37026180e-03, -1.44550953e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.4638447761535645, + 'FR_Wheel_Angle': -4.279476165771484, + 'Location': array([1.02281944e+02, 5.12152634e+01, 1.83732982e-03]), + 'Rotation': array([ 3.34679242e-03, -7.76965027e+01, 9.95800942e-02]), + 'Velocity': array([ 1.90311754e+00, -9.77727890e+00, -2.86102295e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4989.19091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.15722656, 15432.16992188, 125.39945984]), + 'frame': 28577, + 'frame_number': 28577, + 'framesequence': 115051, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.5039304494858, + 'timestamp_carla': 970502, + 'timestamp_device': 1841101, + 'timestamp_stream': 970.5039304494858, + 'transform': [array([-56.56916809, 91.77354431, 0.11195049]), + array([ 5.28015280e+00, -1.69272491e+02, 2.50241021e-03])]} +{'AngularVelocity': array([ 0.0162992 , -0.02116328, -14.40328312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.465125560760498, + 'FR_Wheel_Angle': -4.280810832977295, + 'Location': array([1.02576752e+02, 4.95808830e+01, 1.83931342e-03]), + 'Rotation': array([ 2.99845287e-03, -8.01168060e+01, 9.95211899e-02]), + 'Velocity': array([ 1.48400652e+00, -9.81888485e+00, 7.05719003e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4990.55029296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.90625 , 15432.03808594, 125.42276764]), + 'frame': 28578, + 'frame_number': 28578, + 'framesequence': 115055, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.5362362489104, + 'timestamp_carla': 970535, + 'timestamp_device': 1841134, + 'timestamp_stream': 970.5362362489104, + 'transform': [array([-56.5662384 , 91.75922394, 0.11183628]), + array([ 5.28009129e+00, -1.69271606e+02, 3.01058730e-03])]} +{'AngularVelocity': array([ 0.01525798, -0.01895958, -14.33452702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.390970230102539, + 'FR_Wheel_Angle': -4.084388732910156, + 'Location': array([1.02806847e+02, 4.78973656e+01, 1.84411998e-03]), + 'Rotation': array([ 2.18566041e-03, -8.25950851e+01, 9.85654667e-02]), + 'Velocity': array([ 1.05570483e+00, -9.82977390e+00, 6.10351549e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4991.90625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.66552734, 15431.91015625, 125.45542908]), + 'frame': 28579, + 'frame_number': 28579, + 'framesequence': 115059, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.5692934505641, + 'timestamp_carla': 970568, + 'timestamp_device': 1841167, + 'timestamp_stream': 970.5692934505641, + 'transform': [array([-56.56333542, 91.74463654, 0.11176392]), + array([ 5.28002977e+00, -1.69271118e+02, 3.30532249e-03])]} +{'AngularVelocity': array([ 9.38087609e-03, -1.55096903e-01, -1.04840355e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.761874198913574, + 'FR_Wheel_Angle': -2.359099864959717, + 'Location': array([1.02986908e+02, 4.59653244e+01, 1.84694282e-03]), + 'Rotation': array([ 1.69388682e-03, -8.51456299e+01, 8.21227655e-02]), + 'Velocity': array([ 6.82340443e-01, -9.81116581e+00, 1.84059138e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4993.419921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.74414062, 15431.95117188, 125.50013733]), + 'frame': 28580, + 'frame_number': 28580, + 'framesequence': 115063, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.601541351527, + 'timestamp_carla': 970600, + 'timestamp_device': 1841201, + 'timestamp_stream': 970.601541351527, + 'transform': [array([-56.55997086, 91.730896 , 0.11155609]), + array([ 5.27993393e+00, -1.69267960e+02, 4.19713696e-03])]} +{'AngularVelocity': array([ 5.55618526e-03, -1.39503717e-01, -6.03844929e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.3227859735488892, + 'FR_Wheel_Angle': -1.0448286533355713, + 'Location': array([1.03092369e+02, 4.43592911e+01, 1.84930803e-03]), + 'Rotation': array([ 1.28407544e-03, -8.64370804e+01, 5.57106249e-02]), + 'Velocity': array([ 5.25983393e-01, -9.76403046e+00, 1.00135799e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4994.9345703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.78320312, 15431.97265625, 125.52562714]), + 'frame': 28581, + 'frame_number': 28581, + 'framesequence': 115067, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.6325200498104, + 'timestamp_carla': 970631, + 'timestamp_device': 1841234, + 'timestamp_stream': 970.6325200498104, + 'transform': [array([-56.55749512, 91.71742249, 0.1115913 ]), + array([ 5.27987242e+00, -1.69268356e+02, 4.08695918e-03])]} +{'AngularVelocity': array([ 0.00236617, -0.1615743 , -1.08098614]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.13366222381591797, + 'FR_Wheel_Angle': 0.22014299035072327, + 'Location': array([1.03194412e+02, 4.24249268e+01, 1.85300817e-03]), + 'Rotation': array([ 6.42037718e-04, -8.71213913e+01, 2.29470860e-02]), + 'Velocity': array([ 4.85948890e-01, -9.68372250e+00, 1.40190116e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4996.55126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.08496094, 15432.1328125 , 125.6033783 ]), + 'frame': 28582, + 'frame_number': 28582, + 'framesequence': 115071, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.6657613515854, + 'timestamp_carla': 970664, + 'timestamp_device': 1841267, + 'timestamp_stream': 970.6657613515854, + 'transform': [array([-56.55479431, 91.70319366, 0.11154751]), + array([ 5.27981806e+00, -1.69268372e+02, 4.22446616e-03])]} +{'AngularVelocity': array([-0.00171242, -0.08746938, 1.35573149]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.543923556804657, + 'FR_Wheel_Angle': 0.6764017939567566, + 'Location': array([1.03295525e+02, 4.04934044e+01, 1.85483927e-03]), + 'Rotation': array([ 3.62000021e-04, -8.70402832e+01, 1.79965456e-04]), + 'Velocity': array([ 5.30118108e-01, -9.59447002e+00, 1.33514402e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4997.89306640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.04541016, 15432.11132812, 125.59514618]), + 'frame': 28583, + 'frame_number': 28583, + 'framesequence': 115075, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.6974977515638, + 'timestamp_carla': 970696, + 'timestamp_device': 1841301, + 'timestamp_stream': 970.6974977515638, + 'transform': [array([-56.55222702, 91.68994141, 0.1114859 ]), + array([ 5.27975655e+00, -1.69268204e+02, 4.49878350e-03])]} +{'AngularVelocity': array([-0.00333715, -0.04147941, 2.35045409]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7532607913017273, + 'FR_Wheel_Angle': 0.7588827610015869, + 'Location': array([1.03388573e+02, 3.88911362e+01, 1.85522076e-03]), + 'Rotation': array([ 2.73207552e-04, -8.66989670e+01, -1.11999493e-02]), + 'Velocity': array([ 5.97366393e-01, -9.51823044e+00, -1.10626218e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4999.3388671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.04150391, 15432.109375 , 125.60619354]), + 'frame': 28584, + 'frame_number': 28584, + 'framesequence': 115079, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.7310536503792, + 'timestamp_carla': 970729, + 'timestamp_device': 1841334, + 'timestamp_stream': 970.7310536503792, + 'transform': [array([-56.54900742, 91.67627716, 0.11138634]), + array([ 5.27968836e+00, -1.69265640e+02, 4.86907782e-03])]} +{'AngularVelocity': array([-0.00814484, -0.01115763, 2.30859804]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.6980352997779846, + 'FR_Wheel_Angle': 0.665164053440094, + 'Location': array([1.03490791e+02, 3.73153152e+01, 1.85457221e-03]), + 'Rotation': array([ 3.75660369e-04, -8.63068771e+01, -1.49841318e-02]), + 'Velocity': array([ 6.56168818e-01, -9.44794273e+00, 1.50680535e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5000.69482421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.05126953, 15432.11328125, 125.63056183]), + 'frame': 28585, + 'frame_number': 28585, + 'framesequence': 115082, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.7635666504502, + 'timestamp_carla': 970762, + 'timestamp_device': 1841359, + 'timestamp_stream': 970.7635666504502, + 'transform': [array([-56.54708862, 91.6631012 , 0.11140797]), + array([ 5.27972889e+00, -1.69268097e+02, 4.78730258e-03])]} +{'AngularVelocity': array([-0.01020765, 0.00768012, 1.82598197]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4869195222854614, + 'FR_Wheel_Angle': 0.4626602232456207, + 'Location': array([1.03601440e+02, 3.57548714e+01, 1.85281748e-03]), + 'Rotation': array([ 6.96679228e-04, -8.59671555e+01, -1.44348154e-02]), + 'Velocity': array([ 6.99332654e-01, -9.38358593e+00, 1.10626218e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5002.2646484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.30029297, 15432.24511719, 125.66174316]), + 'frame': 28586, + 'frame_number': 28586, + 'framesequence': 115086, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.7965943515301, + 'timestamp_carla': 970795, + 'timestamp_device': 1841392, + 'timestamp_stream': 970.7965943515301, + 'transform': [array([-56.5438652 , 91.64962769, 0.11133797]), + array([ 5.27999544e+00, -1.69265213e+02, 5.10213571e-03])]} +{'AngularVelocity': array([-0.01137671, 0.02515307, 0.99154586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1928224265575409, + 'FR_Wheel_Angle': 0.14101648330688477, + 'Location': array([1.03743240e+02, 3.38816338e+01, 1.85232155e-03]), + 'Rotation': array([ 7.78641552e-04, -8.56820602e+01, -1.07421856e-02]), + 'Velocity': array([ 7.25532115e-01, -9.30459595e+00, 2.11715701e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5003.43359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.05664062, 15432.1171875 , 125.6548233 ]), + 'frame': 28587, + 'frame_number': 28587, + 'framesequence': 115090, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.8301829509437, + 'timestamp_carla': 970829, + 'timestamp_device': 1841426, + 'timestamp_stream': 970.8301829509437, + 'transform': [array([-56.54166794, 91.6361084 , 0.11132206]), + array([ 5.28048706e+00, -1.69266632e+02, 5.19875903e-03])]} +{'AngularVelocity': array([-0.00530163, 0.02656117, -0.10327159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.08555234968662262, + 'FR_Wheel_Angle': -0.10102246701717377, + 'Location': array([1.03888023e+02, 3.20172462e+01, 1.85400003e-03]), + 'Rotation': array([ 5.05434000e-04, -8.56019058e+01, -4.39453125e-03]), + 'Velocity': array([ 7.13155091e-01, -9.21969032e+00, -8.39233394e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5005.0078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.34082031, 15432.26757812, 125.68172455]), + 'frame': 28588, + 'frame_number': 28588, + 'framesequence': 115095, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 3.66222120646853e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.8650850504637, + 'timestamp_carla': 970863, + 'timestamp_device': 1841467, + 'timestamp_stream': 970.8650850504637, + 'transform': [array([-56.54066467, 91.62046814, 0.11178333]), + array([ 5.28051472e+00, -1.69274872e+02, 3.18903849e-03])]} +{'AngularVelocity': array([ 0.03030189, 0.01046744, -0.30934843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.106796033680439, + 'FR_Wheel_Angle': -0.10672242939472198, + 'Location': array([1.04003799e+02, 3.05124817e+01, 1.87093730e-03]), + 'Rotation': array([-2.34958483e-03, -8.56439667e+01, -1.83105445e-03]), + 'Velocity': array([ 6.93235815e-01, -9.07879734e+00, 1.63078300e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5006.283203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6630.20166016, 15432.19335938, 125.6890564 ]), + 'frame': 28589, + 'frame_number': 28589, + 'framesequence': 115099, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00139164412394166, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.89799625054, + 'timestamp_carla': 970896, + 'timestamp_device': 1841501, + 'timestamp_stream': 970.89799625054, + 'transform': [array([-56.53856277, 91.60585785, 0.11187485]), + array([ 5.28067160e+00, -1.69277557e+02, 2.85255816e-03])]} +{'AngularVelocity': array([ 0.02736176, 0.00519109, -0.31550285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.10700393468141556, + 'FR_Wheel_Angle': -0.10693655908107758, + 'Location': array([1.04118446e+02, 2.90050354e+01, 1.89271918e-03]), + 'Rotation': array([-6.04471704e-03, -8.56972580e+01, -8.85010115e-04]), + 'Velocity': array([ 6.70415640e-01, -8.88992500e+00, 4.48226928e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5007.3056640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.40966797, 15431.77539062, 125.51366425]), + 'frame': 28590, + 'frame_number': 28590, + 'framesequence': 115102, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.013605152256786823, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.9301965497434, + 'timestamp_carla': 970929, + 'timestamp_device': 1841526, + 'timestamp_stream': 970.9301965497434, + 'transform': [array([-56.53604507, 91.59158325, 0.11178638]), + array([ 5.28085613e+00, -1.69278717e+02, 3.29128653e-03])]} +{'AngularVelocity': array([ 0.01597081, 0.00170345, -0.30950558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.10278677940368652, + 'FR_Wheel_Angle': -0.1004893109202385, + 'Location': array([1.04228668e+02, 2.75380363e+01, 1.90347666e-03]), + 'Rotation': array([-7.87520781e-03, -8.57497787e+01, -5.49316173e-04]), + 'Velocity': array([ 6.47785783e-01, -8.69765472e+00, -5.62667822e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5008.6103515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.15429688, 15431.640625 , 125.48527527]), + 'frame': 28591, + 'frame_number': 28591, + 'framesequence': 115107, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.03339945897459984, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.9641637504101, + 'timestamp_carla': 970963, + 'timestamp_device': 1841567, + 'timestamp_stream': 970.9641637504101, + 'transform': [array([-56.53571701, 91.57669067, 0.11172596]), + array([ 5.28085613e+00, -1.69290115e+02, 3.51796485e-03])]} +{'AngularVelocity': array([ 2.69509461e-02, -9.50459944e-05, -2.27363080e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07723791897296906, + 'FR_Wheel_Angle': -0.07385975867509842, + 'Location': array([1.04357498e+02, 2.58017254e+01, 1.90553663e-03]), + 'Rotation': array([-8.27135891e-03, -8.58049850e+01, -7.93457089e-04]), + 'Velocity': array([ 6.24121130e-01, -8.47192955e+00, 1.38282769e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5009.97216796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6629.02197266, 15431.57226562, 125.52423096]), + 'frame': 28592, + 'frame_number': 28592, + 'framesequence': 115110, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05839411914348602, + 'throttle_input': 0.2222171425819397, + 'timestamp': 970.9965555518866, + 'timestamp_carla': 970995, + 'timestamp_device': 1841592, + 'timestamp_stream': 970.9965555518866, + 'transform': [array([-56.53551483, 91.56272125, 0.11149932]), + array([ 5.28054857e+00, -1.69301910e+02, 4.47826553e-03])]} +{'AngularVelocity': array([ 0.03499384, 0.00140063, -0.20325682]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07404995709657669, + 'FR_Wheel_Angle': -0.05049295723438263, + 'Location': array([1.04458221e+02, 2.44316578e+01, 1.91675185e-03]), + 'Rotation': array([-1.01633212e-02, -8.58398972e+01, -9.76562733e-04]), + 'Velocity': array([ 6.02739155e-01, -8.24831867e+00, -1.14440911e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5010.67431640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6627.86914062, 15430.96582031, 125.54319763]), + 'frame': 28593, + 'frame_number': 28593, + 'framesequence': 115115, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08011108636856079, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.0330018512905, + 'timestamp_carla': 971031, + 'timestamp_device': 1841634, + 'timestamp_stream': 971.0330018512905, + 'transform': [array([-56.53906631, 91.54663849, 0.11146583]), + array([ 5.27966070e+00, -1.69332413e+02, 4.40302072e-03])]} +{'AngularVelocity': array([ 0.04162697, -0.01140747, 0.26803294]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.1505880504846573, + 'FR_Wheel_Angle': 0.21059606969356537, + 'Location': array([1.04558189e+02, 2.30717983e+01, 1.94036483e-03]), + 'Rotation': array([-1.41931325e-02, -8.58372192e+01, -3.02124070e-03]), + 'Velocity': array([ 5.90221286e-01, -7.94387960e+00, -4.76837158e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.240234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6626.65380859, 15430.32519531, 125.62757874]), + 'frame': 28594, + 'frame_number': 28594, + 'framesequence': 115119, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.08575091511011124, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.0648782514036, + 'timestamp_carla': 971063, + 'timestamp_device': 1841667, + 'timestamp_stream': 971.0648782514036, + 'transform': [array([-56.54224014, 91.5329361 , 0.11144554]), + array([ 5.27962685e+00, -1.69359390e+02, 4.57450328e-03])]} +{'AngularVelocity': array([ 0.03093306, -0.01394864, 0.93660831]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4329332411289215, + 'FR_Wheel_Angle': 0.5164059996604919, + 'Location': array([1.04656425e+02, 2.17732353e+01, 1.95856090e-03]), + 'Rotation': array([-1.73076987e-02, -8.57299500e+01, -6.43920898e-03]), + 'Velocity': array([ 5.93638778e-01, -7.61308432e+00, 2.41279599e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5010.697265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6623.56933594, 15428.70117188, 125.61909485]), + 'frame': 28595, + 'frame_number': 28595, + 'framesequence': 115123, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07782220840454102, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.0991324521601, + 'timestamp_carla': 971098, + 'timestamp_device': 1841700, + 'timestamp_stream': 971.0991324521601, + 'transform': [array([-56.54470444, 91.51815033, 0.11140777]), + array([ 5.28015280e+00, -1.69384537e+02, 4.77348035e-03])]} +{'AngularVelocity': array([ 0.0234651 , -0.02363498, 1.96738446]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.9241158962249756, + 'FR_Wheel_Angle': 1.0362581014633179, + 'Location': array([1.04756210e+02, 2.05322075e+01, 1.96558004e-03]), + 'Rotation': array([-1.84961520e-02, -8.54841537e+01, -1.14746094e-02]), + 'Velocity': array([ 6.21821702e-01, -7.28274155e+00, 7.62939436e-08]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.18798828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6621.20703125, 15429.25097656, 125.63620758]), + 'frame': 28596, + 'frame_number': 28596, + 'framesequence': 115127, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06449171900749207, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.1326878517866, + 'timestamp_carla': 971131, + 'timestamp_device': 1841734, + 'timestamp_stream': 971.1326878517866, + 'transform': [array([-56.54638672, 91.5039444 , 0.11138076]), + array([ 5.28109503e+00, -1.69405396e+02, 5.00643579e-03])]} +{'AngularVelocity': array([ 0.01080832, -0.00958863, 2.80141783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.2686229944229126, + 'FR_Wheel_Angle': 1.3455487489700317, + 'Location': array([1.04860786e+02, 1.93532925e+01, 1.96577073e-03]), + 'Rotation': array([-1.84961520e-02, -8.50690002e+01, -1.59606915e-02]), + 'Velocity': array([ 6.65663838e-01, -6.96656704e+00, -5.91278081e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5016.5546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6619.49951172, 15432.48925781, 125.65283966]), + 'frame': 28597, + 'frame_number': 28597, + 'framesequence': 115131, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.050447095185518265, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.1649328507483, + 'timestamp_carla': 971163, + 'timestamp_device': 1841767, + 'timestamp_stream': 971.1649328507483, + 'transform': [array([-56.54774475, 91.49044037, 0.11145054]), + array([ 5.28203773e+00, -1.69423767e+02, 4.86277323e-03])]} +{'AngularVelocity': array([ 0.01159609, -0.00690336, 3.47061157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.6569043397903442, + 'FR_Wheel_Angle': 1.790934681892395, + 'Location': array([1.04973366e+02, 1.82161407e+01, 1.96130737e-03]), + 'Rotation': array([-1.77038498e-02, -8.45375595e+01, -1.91345196e-02]), + 'Velocity': array([ 7.16741145e-01, -6.65785313e+00, -4.76837158e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5020.38623046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6618.08056641, 15435.18554688, 125.67276001]), + 'frame': 28598, + 'frame_number': 28598, + 'framesequence': 115135, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.046253856271505356, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.1973166503012, + 'timestamp_carla': 971196, + 'timestamp_device': 1841800, + 'timestamp_stream': 971.1973166503012, + 'transform': [array([-56.54737091, 91.47698212, 0.11135349]), + array([ 5.28259087e+00, -1.69434418e+02, 5.35638025e-03])]} +{'AngularVelocity': array([ 0.00794853, -0.00863243, 4.51456451]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.2325692176818848, + 'FR_Wheel_Angle': 2.445467233657837, + 'Location': array([1.05095757e+02, 1.71273670e+01, 1.95184699e-03]), + 'Rotation': array([-1.60850938e-02, -8.38548126e+01, -2.36206055e-02]), + 'Velocity': array([ 7.90841222e-01, -6.37809610e+00, 4.19616697e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5023.8447265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6616.83789062, 15437.54296875, 125.66069031]), + 'frame': 28599, + 'frame_number': 28599, + 'framesequence': 115138, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.04995269700884819, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.2301508523524, + 'timestamp_carla': 971229, + 'timestamp_device': 1841825, + 'timestamp_stream': 971.2301508523524, + 'transform': [array([-56.54779816, 91.46313477, 0.11138569]), + array([ 5.28274107e+00, -1.69448914e+02, 5.23280678e-03])]} +{'AngularVelocity': array([ 0.00928069, -0.02693726, 6.28751755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.2569022178649902, + 'FR_Wheel_Angle': 3.6308681964874268, + 'Location': array([1.05232018e+02, 1.60853920e+01, 1.94387429e-03]), + 'Rotation': array([-1.47122266e-02, -8.29380951e+01, -3.09753437e-02]), + 'Velocity': array([ 9.02197182e-01, -6.10914183e+00, 3.95774833e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5026.4541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6616.10205078, 15438.94140625, 125.70379639]), + 'frame': 28600, + 'frame_number': 28600, + 'framesequence': 115143, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.056782741099596024, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.264051951468, + 'timestamp_carla': 971262, + 'timestamp_device': 1841867, + 'timestamp_stream': 971.264051951468, + 'transform': [array([-56.54878616, 91.44821167, 0.11161549]), + array([ 5.28186035e+00, -1.69467209e+02, 4.12132218e-03])]} +{'AngularVelocity': array([ 0.03153271, -0.01061848, 8.57786179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.617043495178223, + 'FR_Wheel_Angle': 5.166734218597412, + 'Location': array([1.05391930e+02, 1.50701485e+01, 1.94875710e-03]), + 'Rotation': array([-1.55318491e-02, -8.16334152e+01, -4.06188890e-02]), + 'Velocity': array([ 1.05012429e+00, -5.78474760e+00, 1.13487238e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5029.5205078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6615.11523438, 15440.81445312, 125.69309235]), + 'frame': 28601, + 'frame_number': 28601, + 'framesequence': 115147, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06375927478075027, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.2992542497814, + 'timestamp_carla': 971298, + 'timestamp_device': 1841900, + 'timestamp_stream': 971.2992542497814, + 'transform': [array([-56.55112076, 91.43269348, 0.11182945]), + array([ 5.28136826e+00, -1.69491852e+02, 3.09247663e-03])]} +{'AngularVelocity': array([ 2.18316279e-02, -4.59021376e-03, 1.12630873e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.257791042327881, + 'FR_Wheel_Angle': 6.99799108505249, + 'Location': array([1.05570648e+02, 1.41492405e+01, 1.95711129e-03]), + 'Rotation': array([-1.69388689e-02, -7.99551010e+01, -5.15746959e-02]), + 'Velocity': array([ 1.23271000e+00, -5.44779873e+00, -1.57356254e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5033.115234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6613.87744141, 15443.16308594, 125.59664154]), + 'frame': 28602, + 'frame_number': 28602, + 'framesequence': 115151, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0667622983455658, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.3321973495185, + 'timestamp_carla': 971331, + 'timestamp_device': 1841934, + 'timestamp_stream': 971.3321973495185, + 'transform': [array([-56.55389023, 91.41841888, 0.11196731]), + array([ 5.28152561e+00, -1.69517029e+02, 2.56457832e-03])]} +{'AngularVelocity': array([ 0.01618742, 0.08333416, 13.52228832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.752570152282715, + 'FR_Wheel_Angle': 8.69509506225586, + 'Location': array([1.05788025e+02, 1.32470846e+01, 1.96020119e-03]), + 'Rotation': array([-1.74852833e-02, -7.77559586e+01, -5.92956506e-02]), + 'Velocity': array([ 1.42588711e+00, -5.08041239e+00, -2.59399417e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6371.28173828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6855.45458984, 16757.75 , 125.57791138]), + 'frame': 28603, + 'frame_number': 28603, + 'framesequence': 115155, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06458327174186707, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.3637974523008, + 'timestamp_carla': 971362, + 'timestamp_device': 1841967, + 'timestamp_stream': 971.3637974523008, + 'transform': [array([-56.55573273, 91.40506744, 0.11195053]), + array([ 5.28203773e+00, -1.69537430e+02, 2.75648059e-03])]} +{'AngularVelocity': array([-1.04926843e-02, -9.89749059e-02, 1.58436165e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.819931030273438, + 'FR_Wheel_Angle': 9.822996139526367, + 'Location': array([1.06023163e+02, 1.24481659e+01, 1.95241929e-03]), + 'Rotation': array([-1.61738880e-02, -7.53436661e+01, -6.37817308e-02]), + 'Velocity': array([ 1.63898635e+00, -4.78297949e+00, 2.31742843e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6373.33740234375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6852.76318359, 16758.86914062, 125.52050018]), + 'frame': 28604, + 'frame_number': 28604, + 'framesequence': 115159, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06088443100452423, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.3981586508453, + 'timestamp_carla': 971397, + 'timestamp_device': 1842000, + 'timestamp_stream': 971.3981586508453, + 'transform': [array([-56.5574646 , 91.39090729, 0.11186073]), + array([ 5.28265238e+00, -1.69557938e+02, 3.15443100e-03])]} +{'AngularVelocity': array([-0.0419103 , 0.02305374, 18.97901726]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.60990047454834, + 'FR_Wheel_Angle': 10.723152160644531, + 'Location': array([1.06309029e+02, 1.16472902e+01, 1.85850135e-03]), + 'Rotation': array([-6.40671700e-03, -7.25936356e+01, -7.06481934e-02]), + 'Velocity': array([ 1.90431333e+00, -4.62660456e+00, 1.23908999e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6375.189453125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6850.57080078, 16759.78125 , 125.54273987]), + 'frame': 28605, + 'frame_number': 28605, + 'framesequence': 115163, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.057387009263038635, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.4330324493349, + 'timestamp_carla': 971431, + 'timestamp_device': 1842034, + 'timestamp_stream': 971.4330324493349, + 'transform': [array([-56.55789566, 91.37619019, 0.1117503 ]), + array([ 5.28304863e+00, -1.69573349e+02, 3.62108182e-03])]} +{'AngularVelocity': array([-1.16533786e-02, 2.61161812e-02, 1.72298470e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.975712776184082, + 'FR_Wheel_Angle': 11.049497604370117, + 'Location': array([1.06701202e+02, 1.07349758e+01, 1.67676923e-03]), + 'Rotation': array([-2.86867935e-03, -6.91840515e+01, -6.85424730e-02]), + 'Velocity': array([ 2.17643166e+00, -4.42151880e+00, 2.76470179e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6377.12890625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6848.36181641, 16760.69921875, 125.58496857]), + 'frame': 28606, + 'frame_number': 28606, + 'framesequence': 115167, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05707572028040886, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.4664417505264, + 'timestamp_carla': 971465, + 'timestamp_device': 1842067, + 'timestamp_stream': 971.4664417505264, + 'transform': [array([-56.55967712, 91.3612442 , 0.1117437 ]), + array([ 5.28301430e+00, -1.69594406e+02, 3.66904330e-03])]} +{'AngularVelocity': array([-9.76277050e-03, 2.45417953e-02, 1.70609875e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.048850059509277, + 'FR_Wheel_Angle': 11.098868370056152, + 'Location': array([1.07067780e+02, 1.00026064e+01, 1.71602250e-03]), + 'Rotation': array([-3.02577368e-03, -6.62972183e+01, -6.39343187e-02]), + 'Velocity': array([ 2.35700226e+00, -4.22195435e+00, -1.89485552e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6379.95751953125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6846.85986328, 16762.33203125, 125.63517761]), + 'frame': 28607, + 'frame_number': 28607, + 'framesequence': 115171, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05887020751833916, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.4990445524454, + 'timestamp_carla': 971497, + 'timestamp_device': 1842100, + 'timestamp_stream': 971.4990445524454, + 'transform': [array([-56.56206512, 91.3458252 , 0.11192051]), + array([ 5.28256369e+00, -1.69618668e+02, 2.90770945e-03])]} +{'AngularVelocity': array([-0.15202075, 0.11258404, 16.53723907]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.878555297851562, + 'FR_Wheel_Angle': 10.883125305175781, + 'Location': array([1.07459969e+02, 9.30793285e+00, 1.85693742e-03]), + 'Rotation': array([ 3.40826414e-03, -6.34974251e+01, -4.59289514e-02]), + 'Velocity': array([ 2.51913810e+00, -4.04329538e+00, 1.76095963e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6388.91162109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6845.85253906, 16770.08007812, 125.64163208]), + 'frame': 28608, + 'frame_number': 28608, + 'framesequence': 115175, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.060664694756269455, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.5313229523599, + 'timestamp_carla': 971530, + 'timestamp_device': 1842134, + 'timestamp_stream': 971.5313229523599, + 'transform': [array([-56.56358719, 91.33075714, 0.11190777]), + array([ 5.28265238e+00, -1.69639008e+02, 3.00390110e-03])]} +{'AngularVelocity': array([-0.0408967 , -0.09803203, 16.71303749]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.828543663024902, + 'FR_Wheel_Angle': 10.842345237731934, + 'Location': array([1.07886139e+02, 8.63060665e+00, 1.94581982e-03]), + 'Rotation': array([ 1.36876982e-02, -6.07275352e+01, -4.35485840e-02]), + 'Velocity': array([ 2.75232029e+00, -3.98693156e+00, 5.33122977e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5010.7099609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6594.52587891, 15413.40039062, 125.48912048]), + 'frame': 28609, + 'frame_number': 28609, + 'framesequence': 115179, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.061360519379377365, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.5646643489599, + 'timestamp_carla': 971563, + 'timestamp_device': 1842167, + 'timestamp_stream': 971.5646643489599, + 'transform': [array([-56.56545639, 91.31537628, 0.11187183]), + array([ 5.28283691e+00, -1.69661133e+02, 3.16118402e-03])]} +{'AngularVelocity': array([ 1.20842839e-02, -2.93451458e-01, 1.74125614e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.790312767028809, + 'FR_Wheel_Angle': 10.792850494384766, + 'Location': array([1.08358673e+02, 7.95393229e+00, 2.21719733e-03]), + 'Rotation': array([ 3.30512822e-02, -5.78800087e+01, -6.73827976e-02]), + 'Velocity': array([ 3.07538104, -4.02467823, 0.00600664]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5010.7998046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6592.46289062, 15412.31445312, 125.49810028]), + 'frame': 28610, + 'frame_number': 28610, + 'framesequence': 115182, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06029847636818886, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.5965359508991, + 'timestamp_carla': 971595, + 'timestamp_device': 1842192, + 'timestamp_stream': 971.5965359508991, + 'transform': [array([-56.5664978 , 91.30085754, 0.11170364]), + array([ 5.28283691e+00, -1.69678848e+02, 3.90885072e-03])]} +{'AngularVelocity': array([ 0.06452911, -0.41740552, 17.28127289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.780328750610352, + 'FR_Wheel_Angle': 10.807456016540527, + 'Location': array([1.08879051e+02, 7.27831411e+00, 3.10289371e-03]), + 'Rotation': array([ 0.06341147, -54.94133377, -0.09197997]), + 'Velocity': array([ 3.26668215, -3.91285992, 0.00690012]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5010.79736328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6590.22314453, 15411.13476562, 125.51123047]), + 'frame': 28611, + 'frame_number': 28611, + 'framesequence': 115187, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059236425906419754, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.6308130510151, + 'timestamp_carla': 971629, + 'timestamp_device': 1842234, + 'timestamp_stream': 971.6308130510151, + 'transform': [array([-56.56833267, 91.28560638, 0.11157509]), + array([ 5.28308296e+00, -1.69700516e+02, 4.42356989e-03])]} +{'AngularVelocity': array([ 0.12046583, -0.75808108, 18.64462471]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.238041877746582, + 'FR_Wheel_Angle': 11.515360832214355, + 'Location': array([1.09551460e+02, 6.49553871e+00, 4.76762746e-03]), + 'Rotation': array([ 0.12210329, -51.34477234, -0.22122191]), + 'Velocity': array([ 3.66683698, -3.86636734, 0.01010225]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.0126953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6588.41601562, 15410.18261719, 125.57687378]), + 'frame': 28612, + 'frame_number': 28612, + 'framesequence': 115190, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05954771488904953, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.662528950721, + 'timestamp_carla': 971661, + 'timestamp_device': 1842259, + 'timestamp_stream': 971.662528950721, + 'transform': [array([-56.56932831, 91.27153778, 0.11152095]), + array([ 5.28320551e+00, -1.69717651e+02, 4.71155485e-03])]} +{'AngularVelocity': array([-0.57376713, 0.13667314, 21.66783142]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.189607620239258, + 'FR_Wheel_Angle': 12.697249412536621, + 'Location': array([1.10338715e+02, 5.69868755e+00, 6.65582623e-03]), + 'Rotation': array([ 0.19884728, -47.1920929 , -0.26358032]), + 'Velocity': array([ 4.2427125 , -3.81879139, 0.01427402]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.0283203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6586.22070312, 15409.02539062, 125.61987305]), + 'frame': 28613, + 'frame_number': 28613, + 'framesequence': 115195, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06028016284108162, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.6964453496039, + 'timestamp_carla': 971695, + 'timestamp_device': 1842300, + 'timestamp_stream': 971.6964453496039, + 'transform': [array([-56.57129288, 91.25655365, 0.11155079]), + array([ 5.28335571e+00, -1.69739792e+02, 4.56065079e-03])]} +{'AngularVelocity': array([ 0.70951021, -0.57494169, 25.77282715]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.764678001403809, + 'FR_Wheel_Angle': 13.35433292388916, + 'Location': array([1.11238914e+02, 4.92652035e+00, 1.05176354e-02]), + 'Rotation': array([ 0.23019102, -42.40361023, -0.2202148 ]), + 'Velocity': array([ 4.87922478, -3.65563369, 0.01902572]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.244140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6584.47851562, 15408.10742188, 125.64580536]), + 'frame': 28614, + 'frame_number': 28614, + 'framesequence': 115199, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06029847636818886, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.7311802506447, + 'timestamp_carla': 971730, + 'timestamp_device': 1842334, + 'timestamp_stream': 971.7311802506447, + 'transform': [array([-56.57354355, 91.24093628, 0.11174946]), + array([ 5.28362894e+00, -1.69763748e+02, 3.69637739e-03])]} +{'AngularVelocity': array([ 0.25431344, 0.46430236, 27.64776039]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.343053817749023, + 'FR_Wheel_Angle': 14.184347152709961, + 'Location': array([1.12104942e+02, 4.29974461e+00, 1.32979769e-02]), + 'Rotation': array([ 0.18372525, -37.83829498, -0.31887808]), + 'Velocity': array([ 5.42999363, -3.43246055, 0.01435861]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.20654296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6582.2421875, 15406.9296875, 125.6315918]), + 'frame': 28615, + 'frame_number': 28615, + 'framesequence': 115202, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.05980407074093819, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.7639101520181, + 'timestamp_carla': 971762, + 'timestamp_device': 1842359, + 'timestamp_stream': 971.7639101520181, + 'transform': [array([-56.57466507, 91.22566223, 0.11185508]), + array([ 5.28381348e+00, -1.69782715e+02, 3.30512808e-03])]} +{'AngularVelocity': array([-0.45983231, 0.87800747, 31.32682228]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.10754680633545, + 'FR_Wheel_Angle': 15.132719039916992, + 'Location': array([1.13057350e+02, 3.72850800e+00, 1.65021699e-02]), + 'Rotation': array([ 0.09140158, -32.79911804, -0.22824095]), + 'Velocity': array([ 6.064394 , -3.08141208, 0.01859551]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.10888671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6579.83056641, 15405.65917969, 125.55512238]), + 'frame': 28616, + 'frame_number': 28616, + 'framesequence': 115207, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059694208204746246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.7986213490367, + 'timestamp_carla': 971797, + 'timestamp_device': 1842400, + 'timestamp_stream': 971.7986213490367, + 'transform': [array([-56.57722473, 91.20986176, 0.11186771]), + array([ 5.28344488e+00, -1.69808121e+02, 3.16810026e-03])]} +{'AngularVelocity': array([-0.8739872 , 2.10646224, 34.48028946]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.462175369262695, + 'FR_Wheel_Angle': 15.326470375061035, + 'Location': array([1.14120514e+02, 3.22166657e+00, 1.96256451e-02]), + 'Rotation': array([ 0.07130034, -27.10588455, -0.210907 ]), + 'Velocity': array([ 6.65386009, -2.56718993, -0.03438747]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.3193359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6577.90625 , 15404.64453125, 125.52191925]), + 'frame': 28617, + 'frame_number': 28617, + 'framesequence': 115211, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.8322566524148, + 'timestamp_carla': 971831, + 'timestamp_device': 1842434, + 'timestamp_stream': 971.8322566524148, + 'transform': [array([-56.57674026, 91.19379425, 0.11170463]), + array([ 5.28368378e+00, -1.69821121e+02, 3.90199665e-03])]} +{'AngularVelocity': array([-0.28479156, 0.18929283, 31.12138367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.239636421203613, + 'FR_Wheel_Angle': 11.265701293945312, + 'Location': array([1.15342148e+02, 2.78272843e+00, 1.83044244e-02]), + 'Rotation': array([ 1.80795100e-02, -2.10412216e+01, -1.60095230e-01]), + 'Velocity': array([ 7.11285830e+00, -2.04859304e+00, 7.68613827e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.14208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6575.34521484, 15403.296875 , 125.50938416]), + 'frame': 28618, + 'frame_number': 28618, + 'framesequence': 115215, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.8648980520666, + 'timestamp_carla': 971863, + 'timestamp_device': 1842467, + 'timestamp_stream': 971.8648980520666, + 'transform': [array([-56.57788467, 91.17874908, 0.1115168 ]), + array([ 5.28368378e+00, -1.69839798e+02, 4.73878207e-03])]} +{'AngularVelocity': array([-0.3484281 , 0.10547604, 16.76502991]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.160372257232666, + 'FR_Wheel_Angle': 3.7292821407318115, + 'Location': array([1.16663406e+02, 2.40779591e+00, 1.86526682e-02]), + 'Rotation': array([ 9.41883028e-03, -1.66123199e+01, -9.02709886e-02]), + 'Velocity': array([ 7.34625959e+00, -1.84763741e+00, 1.20182034e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6573.98925781, 15402.58300781, 125.57316589]), + 'frame': 28619, + 'frame_number': 28619, + 'framesequence': 115218, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.8948706500232, + 'timestamp_carla': 971893, + 'timestamp_device': 1842492, + 'timestamp_stream': 971.8948706500232, + 'transform': [array([-56.57912064, 91.16460419, 0.11148082]), + array([ 5.28354025e+00, -1.69858032e+02, 4.66348883e-03])]} +{'AngularVelocity': array([-1.30518329, -0.56973207, 2.5464747 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22598108649253845, + 'FR_Wheel_Angle': -0.22099298238754272, + 'Location': array([1.18049339e+02, 2.03851295e+00, 1.96915995e-02]), + 'Rotation': array([-1.39472457e-02, -1.52445869e+01, -2.42614746e-02]), + 'Velocity': array([ 7.28740454, -1.95544076, -0.02226804]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.0419921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6572.08105469, 15401.57714844, 125.64669037]), + 'frame': 28620, + 'frame_number': 28620, + 'framesequence': 115222, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.9290491491556, + 'timestamp_carla': 971928, + 'timestamp_device': 1842525, + 'timestamp_stream': 971.9290491491556, + 'transform': [array([-56.58100128, 91.14819336, 0.11161655]), + array([ 5.28323317e+00, -1.69881195e+02, 4.12803050e-03])]} +{'AngularVelocity': array([0.04156177, 0.10393111, 1.34304774]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.22160865366458893, + 'FR_Wheel_Angle': -0.2121754139661789, + 'Location': array([1.19397537e+02, 1.67161453e+00, 1.84634198e-02]), + 'Rotation': array([ 8.11426435e-03, -1.51559925e+01, 5.40117791e-04]), + 'Velocity': array([ 7.20792389e+00, -1.96461082e+00, -1.64995188e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.1923828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6570.23144531, 15400.6015625 , 125.63535309]), + 'frame': 28621, + 'frame_number': 28621, + 'framesequence': 115226, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.9628134518862, + 'timestamp_carla': 971961, + 'timestamp_device': 1842559, + 'timestamp_stream': 971.9628134518862, + 'transform': [array([-56.58193588, 91.13215637, 0.11160392]), + array([ 5.28313732e+00, -1.69899887e+02, 4.23129462e-03])]} +{'AngularVelocity': array([0.03735797, 0.09336668, 1.48083556]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.19928765296936035, + 'FR_Wheel_Angle': -0.1899431347846985, + 'Location': array([1.20737320e+02, 1.30657959e+00, 1.85829736e-02]), + 'Rotation': array([ 1.22943398e-04, -1.50958748e+01, -2.07519485e-03]), + 'Velocity': array([ 7.06450891e+00, -1.91936719e+00, 4.05969622e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.23486328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6567.89501953, 15399.37109375, 125.59101868]), + 'frame': 28622, + 'frame_number': 28622, + 'framesequence': 115231, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 971.9972457513213, + 'timestamp_carla': 971996, + 'timestamp_device': 1842600, + 'timestamp_stream': 971.9972457513213, + 'transform': [array([-56.58388901, 91.11587524, 0.11161579]), + array([ 5.28301430e+00, -1.69923111e+02, 4.18333244e-03])]} +{'AngularVelocity': array([-0.71284908, -0.88132232, 0.09208738]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3654046356678009, + 'FR_Wheel_Angle': 0.7084561586380005, + 'Location': array([1.22081078e+02, 9.41896498e-01, 2.26373095e-02]), + 'Rotation': array([ 0.1943257 , -14.96336555, 0.42919755]), + 'Velocity': array([ 6.9693222 , -1.82318962, 0.04255756]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.54443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6565.98925781, 15398.3671875 , 125.60145569]), + 'frame': 28623, + 'frame_number': 28623, + 'framesequence': 115235, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.0303234495223, + 'timestamp_carla': 972029, + 'timestamp_device': 1842634, + 'timestamp_stream': 972.0303234495223, + 'transform': [array([-56.58586884, 91.10055542, 0.11157966]), + array([ 5.28301430e+00, -1.69945404e+02, 4.38921945e-03])]} +{'AngularVelocity': array([0.07012869, 0.00768685, 1.69527078]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.236250638961792, + 'FR_Wheel_Angle': 2.5931203365325928, + 'Location': array([1.23336586e+02, 6.20583236e-01, 1.86111238e-02]), + 'Rotation': array([ -0.01480102, -14.47114658, -0.03320312]), + 'Velocity': array([ 6.72304201e+00, -1.63755739e+00, -3.65509023e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5013.70556640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6563.84277344, 15398.25 , 125.59789276]), + 'frame': 28624, + 'frame_number': 28624, + 'framesequence': 115239, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.0632043518126, + 'timestamp_carla': 972062, + 'timestamp_device': 1842667, + 'timestamp_stream': 972.0632043518126, + 'transform': [array([-56.58791733, 91.08572388, 0.11154762]), + array([ 5.28283691e+00, -1.69967575e+02, 4.53980127e-03])]} +{'AngularVelocity': array([-8.75827599, 6.83941412, 2.61416674]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.1900103092193604, + 'FR_Wheel_Angle': 3.401010036468506, + 'Location': array([1.24609642e+02, 3.23630095e-01, 1.95573214e-02]), + 'Rotation': array([ -0.05938849, -13.31566429, 0.05998721]), + 'Velocity': array([ 6.47969151, -1.3690393 , 0.07241856]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5017.85009765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6562.31396484, 15401.15039062, 125.61727905]), + 'frame': 28625, + 'frame_number': 28625, + 'framesequence': 115243, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.0970272496343, + 'timestamp_carla': 972095, + 'timestamp_device': 1842700, + 'timestamp_stream': 972.0970272496343, + 'transform': [array([-56.59045792, 91.0699234 , 0.11177059]), + array([ 5.28286409e+00, -1.69992615e+02, 3.58630181e-03])]} +{'AngularVelocity': array([ 0.02717916, -0.23379819, 9.79753304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.393935441970825, + 'FR_Wheel_Angle': 3.510664701461792, + 'Location': array([1.25826439e+02, 7.70636424e-02, 1.89331975e-02]), + 'Rotation': array([-6.56381156e-03, -1.18519773e+01, -4.75463867e-02]), + 'Velocity': array([ 6.31824255, -1.16162026, -0.01187008]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5021.931640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6560.79492188, 15404.03613281, 125.63172913]), + 'frame': 28626, + 'frame_number': 28626, + 'framesequence': 115246, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.1287038512528, + 'timestamp_carla': 972127, + 'timestamp_device': 1842725, + 'timestamp_stream': 972.1287038512528, + 'transform': [array([-56.59437561, 91.0544281 , 0.11223385]), + array([ 5.28301430e+00, -1.70023010e+02, 1.69312838e-03])]} +{'AngularVelocity': array([-0.05326683, -0.02849936, 6.16195488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.1109330654144287, + 'FR_Wheel_Angle': 2.923696517944336, + 'Location': array([ 1.27004929e+02, -1.31164759e-01, 1.84729546e-02]), + 'Rotation': array([-2.44520768e-03, -1.03549051e+01, -4.18701135e-02]), + 'Velocity': array([ 6.22564363e+00, -9.77515519e-01, 6.64410589e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5026.42626953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6559.08886719, 15407.27539062, 125.54886627]), + 'frame': 28627, + 'frame_number': 28627, + 'framesequence': 115250, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.1619575507939, + 'timestamp_carla': 972160, + 'timestamp_device': 1842759, + 'timestamp_stream': 972.1619575507939, + 'transform': [array([-56.597332 , 91.03720856, 0.11276519]), + array([ 5.28271389e+00, -1.70051041e+02, -6.13855897e-04])]} +{'AngularVelocity': array([-0.09262335, -0.04038322, 2.94623709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.5567141771316528, + 'FR_Wheel_Angle': 1.3195501565933228, + 'Location': array([ 1.28123810e+02, -3.06820959e-01, 1.86120383e-02]), + 'Rotation': array([-5.43683022e-03, -9.24076557e+00, -2.47802734e-02]), + 'Velocity': array([ 6.04876709e+00, -8.93819153e-01, 4.61683259e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5031.47900390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6557.03076172, 15411.18164062, 125.38549805]), + 'frame': 28628, + 'frame_number': 28628, + 'framesequence': 115254, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.1958603523672, + 'timestamp_carla': 972194, + 'timestamp_device': 1842792, + 'timestamp_stream': 972.1958603523672, + 'transform': [array([-56.59991074, 91.01976013, 0.11295627]), + array([ 5.28231096e+00, -1.70077637e+02, -1.50272681e-03])]} +{'AngularVelocity': array([-0.04735095, -0.0654983 , 0.53840798]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5423932075500488, + 'FR_Wheel_Angle': 0.43267515301704407, + 'Location': array([ 1.29246277e+02, -4.75191981e-01, 1.86720435e-02]), + 'Rotation': array([-6.92581153e-03, -8.62107277e+00, -1.17797842e-02]), + 'Velocity': array([ 5.84839869e+00, -8.52916956e-01, 1.37567520e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5036.45361328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6555.12695312, 15414.79785156, 125.18405914]), + 'frame': 28629, + 'frame_number': 28629, + 'framesequence': 115258, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.2293682508171, + 'timestamp_carla': 972228, + 'timestamp_device': 1842825, + 'timestamp_stream': 972.2293682508171, + 'transform': [array([-56.60250473, 91.00286865, 0.11294754]), + array([ 5.28203773e+00, -1.70103729e+02, -1.50261901e-03])]} +{'AngularVelocity': array([-0.02190171, -0.07538531, -0.45941535]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.10936777293682098, + 'FR_Wheel_Angle': 0.04265289753675461, + 'Location': array([ 1.30320786e+02, -6.33022845e-01, 1.86838321e-02]), + 'Rotation': array([-6.59113238e-03, -8.29920387e+00, -6.86645508e-03]), + 'Velocity': array([ 5.66875219e+00, -8.17812681e-01, 3.56006603e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16978.46875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8610.26367188, 27176.8515625 , 124.79478455]), + 'frame': 28630, + 'frame_number': 28630, + 'framesequence': 115263, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.2644295506179, + 'timestamp_carla': 972263, + 'timestamp_device': 1842867, + 'timestamp_stream': 972.2644295506179, + 'transform': [array([-56.60472488, 90.98531342, 0.11279991]), + array([ 5.28189421e+00, -1.70128922e+02, -9.50979651e-04])]} +{'AngularVelocity': array([ 3.45994043, -2.83497524, 1.57364607]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.012690432369709015, + 'FR_Wheel_Angle': 0.011547663249075413, + 'Location': array([ 1.31354156e+02, -7.79886603e-01, 2.18762364e-02]), + 'Rotation': array([ 0.16671808, -8.08179665, -0.41558832]), + 'Velocity': array([ 5.47503042, -0.79602677, 0.06905445]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16978.96875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8602.37792969, 27176.99804688, 124.79489899]), + 'frame': 28631, + 'frame_number': 28631, + 'framesequence': 115267, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.2959306500852, + 'timestamp_carla': 972294, + 'timestamp_device': 1842900, + 'timestamp_stream': 972.2959306500852, + 'transform': [array([-56.6059494 , 90.96990967, 0.11253967]), + array([ 5.28206491e+00, -1.70147827e+02, 2.52990896e-04])]} +{'AngularVelocity': array([-0.96804124, 1.28714907, 0.04637234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011580582708120346, + 'FR_Wheel_Angle': 0.01159321516752243, + 'Location': array([ 1.32362869e+02, -9.26085889e-01, 2.00533830e-02]), + 'Rotation': array([ 8.03230237e-03, -8.03290653e+00, -2.83813453e-03]), + 'Velocity': array([ 5.27636051, -0.71774465, -0.04367942]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16980.08203125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8594.83105469, 27177.63085938, 124.9553833 ]), + 'frame': 28632, + 'frame_number': 28632, + 'framesequence': 115270, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.3293364495039, + 'timestamp_carla': 972328, + 'timestamp_device': 1842925, + 'timestamp_stream': 972.3293364495039, + 'transform': [array([-56.60922623, 90.9536438 , 0.11251106]), + array([ 5.28201723e+00, -1.70176041e+02, 3.56041361e-04])]} +{'AngularVelocity': array([ 0.04728561, -0.0326409 , 0.01126013]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011631508357822895, + 'FR_Wheel_Angle': 0.011643183417618275, + 'Location': array([ 1.33324219e+02, -1.05952799e+00, 1.82940066e-02]), + 'Rotation': array([-0.01794291, -8.02933407, 0.00861446]), + 'Velocity': array([ 5.05487633e+00, -7.07170784e-01, 8.95433419e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16981.74609375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8589.234375 , 27178.70117188, 125.31287384]), + 'frame': 28633, + 'frame_number': 28633, + 'framesequence': 115275, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.3634199500084, + 'timestamp_carla': 972362, + 'timestamp_device': 1842967, + 'timestamp_stream': 972.3634199500084, + 'transform': [array([-56.61044312, 90.93695068, 0.11221054]), + array([ 5.28198290e+00, -1.70195862e+02, 1.59747025e-03])]} +{'AngularVelocity': array([ 4.8325448 , 2.23661757, -0.77821022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02331641875207424, + 'FR_Wheel_Angle': -0.02796119824051857, + 'Location': array([ 1.34262482e+02, -1.18910623e+00, 2.17953660e-02]), + 'Rotation': array([-0.14926012, -8.03864288, -0.26165771]), + 'Velocity': array([ 4.99131536, -0.71194428, 0.06136959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.478515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6538.27783203, 15383.77050781, 125.2687912 ]), + 'frame': 28634, + 'frame_number': 28634, + 'framesequence': 115279, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.059785760939121246, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.3987770490348, + 'timestamp_carla': 972397, + 'timestamp_device': 1843000, + 'timestamp_stream': 972.3987770490348, + 'transform': [array([-56.60914993, 90.91863251, 0.11191113]), + array([ 5.28194904e+00, -1.70206802e+02, 2.80438806e-03])]} +{'AngularVelocity': array([-2.57285953, -1.69127131, 0.24600929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07352989912033081, + 'FR_Wheel_Angle': -0.2280718833208084, + 'Location': array([ 1.35192398e+02, -1.32291627e+00, 2.10448243e-02]), + 'Rotation': array([-0.05801562, -7.99338531, -0.04299926]), + 'Velocity': array([ 4.95121622, -0.67635751, -0.05045702]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.78564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6536.26171875, 15382.70703125, 125.37578583]), + 'frame': 28635, + 'frame_number': 28635, + 'framesequence': 115283, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.06187322735786438, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.4318433515728, + 'timestamp_carla': 972430, + 'timestamp_device': 1843034, + 'timestamp_stream': 972.4318433515728, + 'transform': [array([-56.61128235, 90.90119171, 0.1118811 ]), + array([ 5.28170967e+00, -1.70231476e+02, 2.94864690e-03])]} +{'AngularVelocity': array([ 0.02409818, 0.03442498, -1.62655485]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0545413494110107, + 'FR_Wheel_Angle': -1.1468257904052734, + 'Location': array([ 1.36141769e+02, -1.45899642e+00, 1.79643407e-02]), + 'Rotation': array([ 0.01497177, -8.17719555, 0.01620259]), + 'Velocity': array([ 4.93790627e+00, -7.47489631e-01, -1.38858787e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.85546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6535.10058594, 15382.09570312, 125.47914886]), + 'frame': 28636, + 'frame_number': 28636, + 'framesequence': 115287, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.07456282526254654, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.465110052377, + 'timestamp_carla': 972463, + 'timestamp_device': 1843067, + 'timestamp_stream': 972.465110052377, + 'transform': [array([-56.61295319, 90.88431549, 0.11158272]), + array([ 5.28192139e+00, -1.70253952e+02, 4.25880402e-03])]} +{'AngularVelocity': array([ 0.03571683, 0.02977532, -1.94263029]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1912665367126465, + 'FR_Wheel_Angle': -1.1780363321304321, + 'Location': array([ 1.37079376e+02, -1.60357630e+00, 1.82228629e-02]), + 'Rotation': array([ 6.62528304e-03, -8.54044628e+00, 1.02210101e-02]), + 'Velocity': array([ 4.86991405e+00, -7.79841721e-01, 1.69342034e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.91650390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6532.61523438, 15380.78710938, 125.49293518]), + 'frame': 28637, + 'frame_number': 28637, + 'framesequence': 115290, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.09714042395353317, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.4965253509581, + 'timestamp_carla': 972495, + 'timestamp_device': 1843092, + 'timestamp_stream': 972.4965253509581, + 'transform': [array([-56.61741257, 90.8683548 , 0.11163105]), + array([ 5.28170967e+00, -1.70287888e+02, 4.09396458e-03])]} +{'AngularVelocity': array([ 0.0139569 , 0.01023703, -1.91771722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1954740285873413, + 'FR_Wheel_Angle': -1.1959110498428345, + 'Location': array([ 1.38006805e+02, -1.75311303e+00, 1.84014682e-02]), + 'Rotation': array([ 2.45203776e-03, -8.91111374e+00, 6.34491211e-03]), + 'Velocity': array([ 4.78614712e+00, -7.98474967e-01, 5.42001741e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5013.05712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6530.32275391, 15379.57910156, 125.60684204]), + 'frame': 28638, + 'frame_number': 28638, + 'framesequence': 115294, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11931516975164413, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.5285299494863, + 'timestamp_carla': 972527, + 'timestamp_device': 1843125, + 'timestamp_stream': 972.5285299494863, + 'transform': [array([-56.62303162, 90.85191345, 0.11163093]), + array([ 5.28072643e+00, -1.70328171e+02, 4.00510849e-03])]} +{'AngularVelocity': array([-0.01076885, 0.00479531, -2.30370903]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.496033787727356, + 'FR_Wheel_Angle': -1.5717848539352417, + 'Location': array([ 1.38917725e+02, -1.90674615e+00, 1.84719246e-02]), + 'Rotation': array([ 1.18845282e-03, -9.30549335e+00, 6.48331409e-03]), + 'Velocity': array([ 4.70297432e+00, -8.28744709e-01, 1.13048554e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.3388671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6526.92382812, 15377.7890625 , 125.59425354]), + 'frame': 28639, + 'frame_number': 28639, + 'framesequence': 115299, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14081241190433502, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.5634885504842, + 'timestamp_carla': 972562, + 'timestamp_device': 1843167, + 'timestamp_stream': 972.5634885504842, + 'transform': [array([-56.63179016, 90.83406067, 0.11159309]), + array([ 5.27951050e+00, -1.70384064e+02, 3.94328730e-03])]} +{'AngularVelocity': array([-0.00685722, 0.00415766, -2.93093181]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.9182947874069214, + 'FR_Wheel_Angle': -1.9654104709625244, + 'Location': array([ 1.39807053e+02, -2.06655908e+00, 1.84795167e-02]), + 'Rotation': array([ 8.46943411e-04, -9.81437492e+00, 8.78985971e-03]), + 'Velocity': array([ 4.61719608e+00, -8.74434650e-01, -9.23538173e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5011.23046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6522.87890625, 15375.65722656, 125.58786774]), + 'frame': 28640, + 'frame_number': 28640, + 'framesequence': 115303, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.14560991525650024, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.5982623510063, + 'timestamp_carla': 972597, + 'timestamp_device': 1843200, + 'timestamp_stream': 972.5982623510063, + 'transform': [array([-56.64048386, 90.81663513, 0.11153667]), + array([ 5.27914190e+00, -1.70439667e+02, 4.10131598e-03])]} +{'AngularVelocity': array([-0.03430889, 0.02871598, -4.21419954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.9210147857666016, + 'FR_Wheel_Angle': -3.153787612915039, + 'Location': array([ 1.40676605e+02, -2.23542333e+00, 1.85146872e-02]), + 'Rotation': array([-1.70754723e-03, -1.04783783e+01, 1.33054815e-02]), + 'Velocity': array([ 4.46240950e+00, -9.35764015e-01, 1.36671064e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5009.205078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6517.28466797, 15372.7109375 , 125.58158875]), + 'frame': 28641, + 'frame_number': 28641, + 'framesequence': 115307, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1353190839290619, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.6312232501805, + 'timestamp_carla': 972630, + 'timestamp_device': 1843233, + 'timestamp_stream': 972.6312232501805, + 'transform': [array([-56.647686 , 90.80055237, 0.11148914]), + array([ 5.27968836e+00, -1.70487366e+02, 4.40267334e-03])]} +{'AngularVelocity': array([-0.02379569, 0.02094117, -6.56904888]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.728082180023193, + 'FR_Wheel_Angle': -4.6579413414001465, + 'Location': array([ 1.41525162e+02, -2.42273784e+00, 1.85300987e-02]), + 'Rotation': array([-5.61441528e-03, -1.15592232e+01, 2.30029523e-02]), + 'Velocity': array([ 4.22879648e+00, -1.04252541e+00, 2.39410394e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5007.15478515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6511.70751953, 15369.7734375 , 125.59453583]), + 'frame': 28642, + 'frame_number': 28642, + 'framesequence': 115311, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12268441170454025, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.6628787517548, + 'timestamp_carla': 972661, + 'timestamp_device': 1843267, + 'timestamp_stream': 972.6628787517548, + 'transform': [array([-56.65470505, 90.78450012, 0.11173885]), + array([ 5.28024149e+00, -1.70533859e+02, 3.46279237e-03])]} +{'AngularVelocity': array([-0.04055813, 0.01915522, -8.16355133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.29313325881958, + 'FR_Wheel_Angle': -6.558960914611816, + 'Location': array([ 1.42311066e+02, -2.62280273e+00, 1.85427256e-02]), + 'Rotation': array([-7.62932096e-03, -1.29368477e+01, 2.66765859e-02]), + 'Velocity': array([ 3.98307729e+00, -1.13943338e+00, 6.05773930e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5005.51220703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6506.91503906, 15367.25 , 125.62091827]), + 'frame': 28643, + 'frame_number': 28643, + 'framesequence': 115314, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11056245863437653, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.6952728517354, + 'timestamp_carla': 972694, + 'timestamp_device': 1843292, + 'timestamp_stream': 972.6952728517354, + 'transform': [array([-56.66031647, 90.76852417, 0.11177853]), + array([ 5.28121805e+00, -1.70573792e+02, 3.41515802e-03])]} +{'AngularVelocity': array([ 0.01288438, -0.0227546 , -11.44514561]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.218486785888672, + 'FR_Wheel_Angle': -8.797385215759277, + 'Location': array([ 1.43069550e+02, -2.85439873e+00, 1.86674278e-02]), + 'Rotation': array([-5.67588676e-03, -1.49451494e+01, 3.17935757e-02]), + 'Velocity': array([ 3.69944453e+00, -1.31033981e+00, 1.51716231e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5012.0009765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6503.59472656, 15372.72558594, 125.54072571]), + 'frame': 28644, + 'frame_number': 28644, + 'framesequence': 115318, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.10662557184696198, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.7290398515761, + 'timestamp_carla': 972727, + 'timestamp_device': 1843325, + 'timestamp_stream': 972.7290398515761, + 'transform': [array([-56.66672897, 90.75199127, 0.11185169]), + array([ 5.28182602e+00, -1.70617310e+02, 3.13403644e-03])]} +{'AngularVelocity': array([ 0.18755971, -0.19398639, -12.63481045]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.829937934875488, + 'FR_Wheel_Angle': -10.064863204956055, + 'Location': array([ 1.43777084e+02, -3.11370039e+00, 1.88515261e-02]), + 'Rotation': array([ 5.81249082e-03, -1.73585320e+01, 1.36121931e-02]), + 'Velocity': array([ 3.42689538, -1.4363035 , 0.00360455]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5018.38427734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6500.81152344, 15378.0078125 , 125.53623199]), + 'frame': 28645, + 'frame_number': 28645, + 'framesequence': 115323, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11080050468444824, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.7653838507831, + 'timestamp_carla': 972764, + 'timestamp_device': 1843367, + 'timestamp_stream': 972.7653838507831, + 'transform': [array([-56.67292404, 90.73491669, 0.11171962]), + array([ 5.28209925e+00, -1.70660400e+02, 3.60754482e-03])]} +{'AngularVelocity': array([ -0.13199592, -0.09851286, -13.20170879]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.7612943649292, + 'FR_Wheel_Angle': -10.720680236816406, + 'Location': array([ 1.44423233e+02, -3.39030743e+00, 1.95831470e-02]), + 'Rotation': array([ 3.57287191e-02, -1.98945274e+01, -5.82885696e-03]), + 'Velocity': array([ 3.17728233, -1.53695214, 0.00369667]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5025.24072265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6497.78515625, 15383.75292969, 125.51064301]), + 'frame': 28646, + 'frame_number': 28646, + 'framesequence': 115327, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11838129907846451, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.7986213490367, + 'timestamp_carla': 972797, + 'timestamp_device': 1843400, + 'timestamp_stream': 972.7986213490367, + 'transform': [array([-56.67855453, 90.71917725, 0.11163253]), + array([ 5.28219461e+00, -1.70699966e+02, 4.03266307e-03])]} +{'AngularVelocity': array([-1.01799900e-02, -7.59380758e-02, -1.29711971e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.130102157592773, + 'FR_Wheel_Angle': -10.878117561340332, + 'Location': array([ 1.45014145e+02, -3.67848849e+00, 2.00844742e-02]), + 'Rotation': array([ 5.56523800e-02, -2.24058037e+01, -1.73950195e-03]), + 'Velocity': array([ 2.94601226e+00, -1.60502863e+00, 2.38701818e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16988.994140625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8435.13964844, 27187.83984375, 126.29894257]), + 'frame': 28647, + 'frame_number': 28647, + 'framesequence': 115331, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12471694499254227, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.8309283517301, + 'timestamp_carla': 972829, + 'timestamp_device': 1843433, + 'timestamp_stream': 972.8309283517301, + 'transform': [array([-56.6840744 , 90.70425415, 0.11149471]), + array([ 5.28222895e+00, -1.70738541e+02, 4.67698323e-03])]} +{'AngularVelocity': array([-6.64993236e-03, -4.72663604e-02, -1.29554195e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.821489334106445, + 'FR_Wheel_Angle': -11.663328170776367, + 'Location': array([ 1.45586563e+02, -3.99170065e+00, 2.04448868e-02]), + 'Rotation': array([ 6.71339259e-02, -2.49601498e+01, -9.46044736e-03]), + 'Velocity': array([ 2.71495295e+00, -1.66229057e+00, 1.03796960e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16989.484375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8423.25097656, 27188.65820312, 126.425354 ]), + 'frame': 28648, + 'frame_number': 28648, + 'framesequence': 115335, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1261635273694992, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.8630472496152, + 'timestamp_carla': 972861, + 'timestamp_device': 1843467, + 'timestamp_stream': 972.8630472496152, + 'transform': [array([-56.69046783, 90.68980408, 0.11142185]), + array([ 5.28219461e+00, -1.70780228e+02, 5.02024358e-03])]} +{'AngularVelocity': array([ 0.01515324, -0.0550492 , -13.72604179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.577373504638672, + 'FR_Wheel_Angle': -13.17184829711914, + 'Location': array([ 1.46087708e+02, -4.30166960e+00, 2.08118595e-02]), + 'Rotation': array([ 7.52755105e-02, -2.75008373e+01, -1.31530743e-02]), + 'Velocity': array([ 2.48537445, -1.72986579, 0.00308988]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16990.087890625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8411.68554688, 27189.61328125, 126.61683655]), + 'frame': 28649, + 'frame_number': 28649, + 'framesequence': 115339, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12387463450431824, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.8970407508314, + 'timestamp_carla': 972895, + 'timestamp_device': 1843500, + 'timestamp_stream': 972.8970407508314, + 'transform': [array([-56.69716644, 90.67469788, 0.11140323]), + array([ 5.28213310e+00, -1.70823929e+02, 5.05440542e-03])]} +{'AngularVelocity': array([ 0.20084323, -0.03712825, -15.11768341]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.56419563293457, + 'FR_Wheel_Angle': -14.564996719360352, + 'Location': array([ 1.46535034e+02, -4.61665964e+00, 2.14373562e-02]), + 'Rotation': array([ 0.0700231 , -30.18772316, -0.03735351]), + 'Velocity': array([ 2.31846619, -1.84319651, 0.00473258]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4996.83447265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6477.64550781, 15351.83105469, 125.67234039]), + 'frame': 28650, + 'frame_number': 28650, + 'framesequence': 115342, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12015748023986816, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.9301289506257, + 'timestamp_carla': 972928, + 'timestamp_device': 1843525, + 'timestamp_stream': 972.9301289506257, + 'transform': [array([-56.70365524, 90.65994263, 0.11151554]), + array([ 5.28209925e+00, -1.70866257e+02, 4.58089821e-03])]} +{'AngularVelocity': array([ 1.35281226e-02, -2.64514349e-02, -1.67235012e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.192562103271484, + 'FR_Wheel_Angle': -15.831245422363281, + 'Location': array([ 1.46954163e+02, -4.95167685e+00, 2.20033433e-02]), + 'Rotation': array([ 0.07147793, -33.09889221, -0.04418945]), + 'Velocity': array([ 2.21706772, -2.00835109, 0.00270012]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4995.4228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6473.29931641, 15349.54101562, 125.67433929]), + 'frame': 28651, + 'frame_number': 28651, + 'framesequence': 115347, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11737419664859772, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.9637173488736, + 'timestamp_carla': 972962, + 'timestamp_device': 1843567, + 'timestamp_stream': 972.9637173488736, + 'transform': [array([-56.70982361, 90.6449585 , 0.11160316]), + array([ 5.28222895e+00, -1.70907303e+02, 4.21052286e-03])]} +{'AngularVelocity': array([ -0.40279701, 0.16567175, -18.77479362]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.282800674438477, + 'FR_Wheel_Angle': -17.276704788208008, + 'Location': array([ 1.47340332e+02, -5.30432415e+00, 2.29997803e-02]), + 'Rotation': array([ 8.23925659e-02, -3.62325745e+01, 9.65859275e-03]), + 'Velocity': array([ 2.0935564 , -2.18700409, 0.00846267]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4994.07421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6469.09667969, 15347.32714844, 125.6335144 ]), + 'frame': 28652, + 'frame_number': 28652, + 'framesequence': 115350, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11763054877519608, + 'throttle_input': 0.2222171425819397, + 'timestamp': 972.9965409524739, + 'timestamp_carla': 972995, + 'timestamp_device': 1843592, + 'timestamp_stream': 972.9965409524739, + 'transform': [array([-56.7159462 , 90.63059998, 0.11163773]), + array([ 5.28240633e+00, -1.70947403e+02, 4.10080189e-03])]} +{'AngularVelocity': array([ -0.53063798, 0.11552376, -19.83039284]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.06304168701172, + 'FR_Wheel_Angle': -17.632814407348633, + 'Location': array([ 1.47690323e+02, -5.67004585e+00, 2.43810434e-02]), + 'Rotation': array([ 0.11645472, -39.50614166, 0.08979805]), + 'Velocity': array([ 1.97143197, -2.34805799, 0.01006191]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4992.83935546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6465.02197266, 15345.1796875 , 125.60100555]), + 'frame': 28653, + 'frame_number': 28653, + 'framesequence': 115354, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11922361701726913, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.0289244502783, + 'timestamp_carla': 973027, + 'timestamp_device': 1843625, + 'timestamp_stream': 973.0289244502783, + 'transform': [array([-56.72163391, 90.61636353, 0.11170074]), + array([ 5.28246784e+00, -1.70985596e+02, 3.86096677e-03])]} +{'AngularVelocity': array([ -0.42596519, -0.0444855 , -21.06885719]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.647212982177734, + 'FR_Wheel_Angle': -18.968713760375977, + 'Location': array([ 1.48013809e+02, -6.05316591e+00, 2.58212052e-02]), + 'Rotation': array([ 0.15854917, -42.84892273, 0.16836549]), + 'Velocity': array([ 1.82980955, -2.50427198, 0.01187181]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4991.6103515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6461.04638672, 15343.08496094, 125.59162903]), + 'frame': 28654, + 'frame_number': 28654, + 'framesequence': 115358, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1209082379937172, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.0638974495232, + 'timestamp_carla': 973062, + 'timestamp_device': 1843658, + 'timestamp_stream': 973.0638974495232, + 'transform': [array([-56.72711945, 90.60083008, 0.11165871]), + array([ 5.28267956e+00, -1.71024261e+02, 3.99110792e-03])]} +{'AngularVelocity': array([ 0.21235709, -0.70508164, -22.99301147]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.05271339416504, + 'FR_Wheel_Angle': -19.802478790283203, + 'Location': array([ 1.48356689e+02, -6.52934742e+00, 2.78864447e-02]), + 'Rotation': array([ 0.22181039, -47.05854797, 0.11307558]), + 'Velocity': array([ 1.61687636, -2.70188594, 0.01251794]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4990.50146484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6457.2578125 , 15341.09082031, 125.57126617]), + 'frame': 28655, + 'frame_number': 28655, + 'framesequence': 115363, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12110965698957443, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.097131550312, + 'timestamp_carla': 973096, + 'timestamp_device': 1843700, + 'timestamp_stream': 973.097131550312, + 'transform': [array([-56.73338699, 90.58636475, 0.11164249]), + array([ 5.28259087e+00, -1.71065155e+02, 4.06698883e-03])]} +{'AngularVelocity': array([ 7.58299464e-03, -2.43098482e-01, -2.39164200e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.677400588989258, + 'FR_Wheel_Angle': -20.108659744262695, + 'Location': array([ 1.48618149e+02, -6.96072483e+00, 2.94510052e-02]), + 'Rotation': array([ 2.69246042e-01, -5.08591728e+01, 2.37632114e-02]), + 'Velocity': array([ 1.43711221, -2.84419632, 0.00788052]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4989.484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6453.40625 , 15339.06054688, 125.58052063]), + 'frame': 28656, + 'frame_number': 28656, + 'framesequence': 115366, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.1283469498158, + 'timestamp_carla': 973127, + 'timestamp_device': 1843725, + 'timestamp_stream': 973.1283469498158, + 'transform': [array([-56.73865128, 90.57262421, 0.11164883]), + array([ 5.28264570e+00, -1.71101044e+02, 4.11473634e-03])]} +{'AngularVelocity': array([ -0.03013795, 0.1299963 , -24.20318031]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.65361785888672, + 'FR_Wheel_Angle': -20.084901809692383, + 'Location': array([ 1.48859863e+02, -7.43103361e+00, 3.01896073e-02]), + 'Rotation': array([ 2.74450660e-01, -5.48863487e+01, 2.72782929e-02]), + 'Velocity': array([ 1.25430262, -2.97321653, 0.00440658]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4988.22607421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6449.35693359, 15336.92773438, 125.58745575]), + 'frame': 28657, + 'frame_number': 28657, + 'framesequence': 115371, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11909542977809906, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.1642801500857, + 'timestamp_carla': 973163, + 'timestamp_device': 1843767, + 'timestamp_stream': 973.1642801500857, + 'transform': [array([-56.74517441, 90.55698395, 0.11162277]), + array([ 5.28256369e+00, -1.71144043e+02, 4.10085637e-03])]} +{'AngularVelocity': array([-1.61733590e-02, 3.40267658e-01, -2.43678303e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.56139373779297, + 'FR_Wheel_Angle': -20.017532348632812, + 'Location': array([ 1.49074829e+02, -7.93378878e+00, 3.13966908e-02]), + 'Rotation': array([ 0.25600913, -59.04417419, 0.0694364 ]), + 'Velocity': array([ 1.05260611, -3.08961225, 0.0074827 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4993.07763671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6446.69970703, 15340.83203125, 125.59348297]), + 'frame': 28658, + 'frame_number': 28658, + 'framesequence': 115375, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11971801519393921, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.1955676488578, + 'timestamp_carla': 973194, + 'timestamp_device': 1843800, + 'timestamp_stream': 973.1955676488578, + 'transform': [array([-56.751091 , 90.54319763, 0.11170589]), + array([ 5.28237915e+00, -1.71182663e+02, 3.81295127e-03])]} +{'AngularVelocity': array([ 0.34582749, 0.20708133, -25.02283287]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.41486930847168, + 'FR_Wheel_Angle': -19.80529022216797, + 'Location': array([ 1.49247421e+02, -8.43109989e+00, 3.34139019e-02]), + 'Rotation': array([ 0.21112114, -63.03532028, 0.10338172]), + 'Velocity': array([ 0.84540182, -3.19694614, 0.01237841]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4993.8564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6442.75585938, 15340.61425781, 125.58973694]), + 'frame': 28659, + 'frame_number': 28659, + 'framesequence': 115378, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12028566002845764, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.2295290492475, + 'timestamp_carla': 973228, + 'timestamp_device': 1843825, + 'timestamp_stream': 973.2295290492475, + 'transform': [array([-56.75724792, 90.52799225, 0.11177315]), + array([ 5.28231096e+00, -1.71223679e+02, 3.49058956e-03])]} +{'AngularVelocity': array([ 7.97495484e-01, -5.58874849e-03, -2.26878757e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.846874237060547, + 'FR_Wheel_Angle': -16.854116439819336, + 'Location': array([ 1.49393738e+02, -8.95542336e+00, 3.74423377e-02]), + 'Rotation': array([ 1.02999248e-01, -6.69927368e+01, 3.09994891e-02]), + 'Velocity': array([ 0.69607979, -3.26722813, 0.02090584]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4992.22509765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6438.86669922, 15338.14257812, 125.56694031]), + 'frame': 28660, + 'frame_number': 28660, + 'framesequence': 115383, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12019409984350204, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.2641303502023, + 'timestamp_carla': 973263, + 'timestamp_device': 1843867, + 'timestamp_stream': 973.2641303502023, + 'transform': [array([-56.76321793, 90.51279449, 0.11169468]), + array([ 5.28267956e+00, -1.71263702e+02, 3.82718071e-03])]} +{'AngularVelocity': array([ 0.09296892, -0.03574146, -18.71602821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.524547576904297, + 'FR_Wheel_Angle': -14.281146049499512, + 'Location': array([ 1.49544785e+02, -9.61033535e+00, 3.85998711e-02]), + 'Rotation': array([ 7.70240426e-02, -7.10939865e+01, 2.33063269e-02]), + 'Velocity': array([ 5.88994801e-01, -3.35738468e+00, 9.44433210e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4990.552734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6434.72949219, 15335.51367188, 125.53834534]), + 'frame': 28661, + 'frame_number': 28661, + 'framesequence': 115387, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11995605379343033, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.2979535497725, + 'timestamp_carla': 973296, + 'timestamp_device': 1843900, + 'timestamp_stream': 973.2979535497725, + 'transform': [array([-56.77016449, 90.49765778, 0.11194301]), + array([ 5.28222895e+00, -1.71307800e+02, 2.72901729e-03])]} +{'AngularVelocity': array([ 0.12353389, -0.14509307, -12.37586117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.721759796142578, + 'FR_Wheel_Angle': -8.532537460327148, + 'Location': array([ 1.49658035e+02, -1.01673536e+01, 3.88289802e-02]), + 'Rotation': array([ 6.51736632e-02, -7.37076797e+01, 1.37773145e-03]), + 'Velocity': array([ 6.24351382e-01, -3.40516186e+00, 1.90742011e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4989.5107421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6430.77490234, 15333.4921875 , 125.56604004]), + 'frame': 28662, + 'frame_number': 28662, + 'framesequence': 115390, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.3292996510863, + 'timestamp_carla': 973328, + 'timestamp_device': 1843925, + 'timestamp_stream': 973.3292996510863, + 'transform': [array([-56.77656555, 90.48336029, 0.11223122]), + array([ 5.28167582e+00, -1.71348755e+02, 1.52188307e-03])]} +{'AngularVelocity': array([ 0.16420524, -0.15491901, -2.90243363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.9713228940963745, + 'FR_Wheel_Angle': -0.6375544667243958, + 'Location': array([ 1.49781067e+02, -1.07162819e+01, 3.91113833e-02]), + 'Rotation': array([ 4.99286801e-02, -7.49272156e+01, -3.19824144e-02]), + 'Velocity': array([ 8.11603785e-01, -3.38342428e+00, 1.65212632e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4995.56494140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6427.56298828, 15338.54296875, 125.47218323]), + 'frame': 28663, + 'frame_number': 28663, + 'framesequence': 115394, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.362672150135, + 'timestamp_carla': 973361, + 'timestamp_device': 1843958, + 'timestamp_stream': 973.362672150135, + 'transform': [array([-56.78318405, 90.4681778 , 0.1123611 ]), + array([ 5.28140259e+00, -1.71391449e+02, 9.25176137e-04])]} +{'AngularVelocity': array([-0.17754841, 0.46774617, 0.51632971]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2958645820617676, + 'FR_Wheel_Angle': 0.0288320854306221, + 'Location': array([ 1.49936829e+02, -1.12994394e+01, 4.01714109e-02]), + 'Rotation': array([ 1.79838873e-02, -7.49434662e+01, -6.40869723e-04]), + 'Velocity': array([ 0.92295986, -3.36163616, 0.00804257]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4979.921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6421.36767578, 15322.18261719, 125.36979675]), + 'frame': 28664, + 'frame_number': 28664, + 'framesequence': 115398, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.3959058523178, + 'timestamp_carla': 973394, + 'timestamp_device': 1843992, + 'timestamp_stream': 973.3959058523178, + 'transform': [array([-56.78988266, 90.45326233, 0.11238319]), + array([ 5.28136826e+00, -1.71434174e+02, 8.22366856e-04])]} +{'AngularVelocity': array([ 0.04795629, -0.02905772, -0.16697973]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.004806171637028456, + 'FR_Wheel_Angle': 0.004806387238204479, + 'Location': array([ 1.50082306e+02, -1.18363008e+01, 4.03453261e-02]), + 'Rotation': array([ 3.73611320e-03, -7.49284210e+01, -9.42993071e-03]), + 'Velocity': array([ 9.09372687e-01, -3.36593652e+00, 8.94947036e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4978.6640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6417.17285156, 15319.97460938, 125.31828308]), + 'frame': 28665, + 'frame_number': 28665, + 'framesequence': 115403, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.4304367490113, + 'timestamp_carla': 973429, + 'timestamp_device': 1844033, + 'timestamp_stream': 973.4304367490113, + 'transform': [array([-56.79603577, 90.43786621, 0.11228218]), + array([ 5.28161430e+00, -1.71474930e+02, 1.23349717e-03])]} +{'AngularVelocity': array([-0.02799238, 0.01453026, -0.19827056]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.012016343884170055, + 'FR_Wheel_Angle': 0.012014682404696941, + 'Location': array([ 1.50238892e+02, -1.24158030e+01, 4.03316692e-02]), + 'Rotation': array([ 3.41509446e-03, -7.49219818e+01, -6.53076172e-03]), + 'Velocity': array([ 9.09114838e-01, -3.36150074e+00, -6.22682564e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4966.2470703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6411.31689453, 15306.75195312, 125.30914307]), + 'frame': 28666, + 'frame_number': 28666, + 'framesequence': 115406, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.4622927494347, + 'timestamp_carla': 973461, + 'timestamp_device': 1844058, + 'timestamp_stream': 973.4622927494347, + 'transform': [array([-56.80084991, 90.42421722, 0.1120552 ]), + array([ 5.28206491e+00, -1.71508316e+02, 2.30379263e-03])]} +{'AngularVelocity': array([-0.01213694, 0.00329493, 0.02429748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.06723783910274506, + 'FR_Wheel_Angle': 0.0684843584895134, + 'Location': array([ 1.50385345e+02, -1.29572754e+01, 4.03680205e-02]), + 'Rotation': array([ 4.86309454e-03, -7.49138565e+01, -4.30297852e-03]), + 'Velocity': array([ 9.10215378e-01, -3.35920596e+00, 1.20453828e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4965.76611328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6407.40039062, 15305.2578125 , 125.34319305]), + 'frame': 28667, + 'frame_number': 28667, + 'framesequence': 115411, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.4981285519898, + 'timestamp_carla': 973497, + 'timestamp_device': 1844100, + 'timestamp_stream': 973.4981285519898, + 'transform': [array([-56.80697632, 90.40850067, 0.11199562]), + array([ 5.28209925e+00, -1.71549271e+02, 2.46203924e-03])]} +{'AngularVelocity': array([-0.01681403, -0.00093383, -0.03177784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07561613619327545, + 'FR_Wheel_Angle': 0.10447435081005096, + 'Location': array([ 1.50565353e+02, -1.36210299e+01, 4.03423123e-02]), + 'Rotation': array([ 6.21547177e-03, -7.48983612e+01, -3.29589844e-03]), + 'Velocity': array([ 9.17648613e-01, -3.37980485e+00, -4.60014329e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4968.2255859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6404.5859375 , 15306.74609375, 125.43610382]), + 'frame': 28668, + 'frame_number': 28668, + 'framesequence': 115415, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.5320312492549, + 'timestamp_carla': 973530, + 'timestamp_device': 1844133, + 'timestamp_stream': 973.5320312492549, + 'transform': [array([-56.81560516, 90.39257812, 0.11232761]), + array([ 5.28124523e+00, -1.71600906e+02, 9.72815906e-04])]} +{'AngularVelocity': array([0.01874357, 0.21759938, 0.21329235]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2079477459192276, + 'FR_Wheel_Angle': 0.21410143375396729, + 'Location': array([ 1.50723053e+02, -1.42006321e+01, 4.03751172e-02]), + 'Rotation': array([ 8.31917021e-03, -7.48672943e+01, 4.26380523e-03]), + 'Velocity': array([ 9.68827188e-01, -3.53770876e+00, 2.84664147e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4968.55029296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6400.765625 , 15306.01367188, 125.44731903]), + 'frame': 28669, + 'frame_number': 28669, + 'framesequence': 115419, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.5645844489336, + 'timestamp_carla': 973563, + 'timestamp_device': 1844167, + 'timestamp_stream': 973.5645844489336, + 'transform': [array([-56.8211937 , 90.37722778, 0.11221062]), + array([ 5.28161430e+00, -1.71639145e+02, 1.56349433e-03])]} +{'AngularVelocity': array([-0.0897984 , -0.02002318, 0.29050022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.21343185007572174, + 'FR_Wheel_Angle': 0.21342195570468903, + 'Location': array([ 1.50893585e+02, -1.48236799e+01, 4.01755311e-02]), + 'Rotation': array([ 2.67675091e-02, -7.48253021e+01, -4.36401321e-03]), + 'Velocity': array([ 1.08003533e+00, -3.93868470e+00, -5.23738854e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4966.833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6395.74804688, 15303.36914062, 125.32055664]), + 'frame': 28670, + 'frame_number': 28670, + 'framesequence': 115423, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.5972576513886, + 'timestamp_carla': 973596, + 'timestamp_device': 1844200, + 'timestamp_stream': 973.5972576513886, + 'transform': [array([-56.82763672, 90.36230469, 0.11207446]), + array([ 5.28179884e+00, -1.71680435e+02, 2.18737056e-03])]} +{'AngularVelocity': array([-0.08560708, -0.02187302, 0.33101878]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.21090878546237946, + 'FR_Wheel_Angle': 0.19314688444137573, + 'Location': array([ 1.51084473e+02, -1.55197096e+01, 4.01076302e-02]), + 'Rotation': array([ 4.18622270e-02, -7.47739258e+01, -3.90624884e-03]), + 'Velocity': array([ 1.24694169e+00, -4.53278685e+00, -6.21604922e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4965.90380859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6391.98535156, 15301.38867188, 125.3720932 ]), + 'frame': 28671, + 'frame_number': 28671, + 'framesequence': 115426, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.6291099488735, + 'timestamp_carla': 973628, + 'timestamp_device': 1844225, + 'timestamp_stream': 973.6291099488735, + 'transform': [array([-56.8335228 , 90.34784698, 0.11195751]), + array([ 5.28198290e+00, -1.71719025e+02, 2.74252053e-03])]} +{'AngularVelocity': array([ 0.08240843, 0.03421254, -0.03997172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.053340621292591095, + 'FR_Wheel_Angle': -0.07405757158994675, + 'Location': array([ 1.51311783e+02, -1.63484936e+01, 4.02671993e-02]), + 'Rotation': array([ 5.07278107e-02, -7.47451859e+01, -2.07519601e-03]), + 'Velocity': array([ 1.40472150e+00, -5.13580322e+00, 5.14678948e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4959.46533203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6387.17675781, 15294.03515625, 125.42592621]), + 'frame': 28672, + 'frame_number': 28672, + 'framesequence': 115430, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.6617705523968, + 'timestamp_carla': 973660, + 'timestamp_device': 1844258, + 'timestamp_stream': 973.6617705523968, + 'transform': [array([-56.83999252, 90.33318329, 0.11189815]), + array([ 5.28203773e+00, -1.71760162e+02, 2.99661024e-03])]} +{'AngularVelocity': array([-0.05680785, -0.01541625, -0.16913345]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07359082996845245, + 'FR_Wheel_Angle': -0.0734281837940216, + 'Location': array([ 1.51551666e+02, -1.72270718e+01, 4.02682684e-02]), + 'Rotation': array([ 4.46216241e-02, -7.47635345e+01, -1.55639462e-03]), + 'Velocity': array([ 1.52794838e+00, -5.60481453e+00, -3.62439139e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4958.4365234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6383.39746094, 15292.04492188, 125.47427368]), + 'frame': 28673, + 'frame_number': 28673, + 'framesequence': 115435, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.6968484520912, + 'timestamp_carla': 973695, + 'timestamp_device': 1844300, + 'timestamp_stream': 973.6968484520912, + 'transform': [array([-56.84606934, 90.31769562, 0.11175743]), + array([ 5.28219461e+00, -1.71800400e+02, 3.52493930e-03])]} +{'AngularVelocity': array([-0.06468778, -0.01697537, -0.19599126]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07293692231178284, + 'FR_Wheel_Angle': -0.0727655291557312, + 'Location': array([ 1.51881271e+02, -1.84367275e+01, 4.01617996e-02]), + 'Rotation': array([ 5.45049049e-02, -7.47941132e+01, -1.64794899e-03]), + 'Velocity': array([ 1.74919701e+00, -6.42944384e+00, -1.31435387e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4960.3564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6379.82324219, 15292.97851562, 125.49597168]), + 'frame': 28674, + 'frame_number': 28674, + 'framesequence': 115438, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.7294644489884, + 'timestamp_carla': 973728, + 'timestamp_device': 1844325, + 'timestamp_stream': 973.7294644489884, + 'transform': [array([-56.85161591, 90.30379486, 0.11161835]), + array([ 5.28237915e+00, -1.71836823e+02, 4.16952884e-03])]} +{'AngularVelocity': array([-0.06248113, -0.03098974, -0.18520701]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07232382893562317, + 'FR_Wheel_Angle': -0.0721452608704567, + 'Location': array([ 1.52256378e+02, -1.98162270e+01, 4.00525481e-02]), + 'Rotation': array([ 6.24757372e-02, -7.48277817e+01, 1.43811572e-03]), + 'Velocity': array([ 2.00518584e+00, -7.38627863e+00, 3.16619880e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4967.34326171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6377.02636719, 15298.83203125, 125.53956604]), + 'frame': 28675, + 'frame_number': 28675, + 'framesequence': 115443, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.7638193517923, + 'timestamp_carla': 973762, + 'timestamp_device': 1844367, + 'timestamp_stream': 973.7638193517923, + 'transform': [array([-56.85752869, 90.28916931, 0.11156429]), + array([ 5.28250217e+00, -1.71875488e+02, 4.37504100e-03])]} +{'AngularVelocity': array([-0.10148416, -0.0334338 , -0.20798688]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07155681401491165, + 'FR_Wheel_Angle': -0.07135584205389023, + 'Location': array([ 1.52617645e+02, -2.11477661e+01, 3.99982631e-02]), + 'Rotation': array([ 7.56306797e-02, -7.48606567e+01, -1.52588822e-04]), + 'Velocity': array([ 2.27567315e+00, -8.40098763e+00, 1.30605695e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4968.46826171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6373.74755859, 15298.99414062, 125.59566498]), + 'frame': 28676, + 'frame_number': 28676, + 'framesequence': 115447, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.796610750258, + 'timestamp_carla': 973795, + 'timestamp_device': 1844400, + 'timestamp_stream': 973.796610750258, + 'transform': [array([-56.86242676, 90.27438354, 0.11175018]), + array([ 5.28271389e+00, -1.71909958e+02, 3.64117557e-03])]} +{'AngularVelocity': array([-0.03919531, -0.01153846, -0.23578647]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.07073380798101425, + 'FR_Wheel_Angle': -0.07271578162908554, + 'Location': array([ 1.53013351e+02, -2.26095486e+01, 3.99437509e-02]), + 'Rotation': array([ 8.63472447e-02, -7.48966370e+01, 1.07182059e-04]), + 'Velocity': array([ 2.55829453e+00, -9.46496105e+00, -1.14994044e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4974.0166015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6370.89208984, 15303.48730469, 125.61279297]), + 'frame': 28677, + 'frame_number': 28677, + 'framesequence': 115451, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.8300737515092, + 'timestamp_carla': 973828, + 'timestamp_device': 1844433, + 'timestamp_stream': 973.8300737515092, + 'transform': [array([-56.86977386, 90.25861359, 0.11203552]), + array([ 5.28179884e+00, -1.71955780e+02, 2.32428894e-03])]} +{'AngularVelocity': array([-0.0188554 , 0.04605403, -1.16651332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.45550256967544556, + 'FR_Wheel_Angle': -0.6217765808105469, + 'Location': array([ 1.53470352e+02, -2.43055897e+01, 3.99292931e-02]), + 'Rotation': array([ 8.93457010e-02, -7.49841690e+01, 3.07038706e-03]), + 'Velocity': array([ 2.81844997e+00, -1.05544443e+01, 5.22136688e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4979.1552734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6368.33691406, 15307.5078125 , 125.55045319]), + 'frame': 28678, + 'frame_number': 28678, + 'framesequence': 115454, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.8621147498488, + 'timestamp_carla': 973860, + 'timestamp_device': 1844458, + 'timestamp_stream': 973.8621147498488, + 'transform': [array([-56.87775803, 90.24234009, 0.11256786]), + array([ 5.28088331e+00, -1.72004822e+02, 5.84112558e-06])]} +{'AngularVelocity': array([-0.02706234, 0.1142339 , -4.27806377]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.313020944595337, + 'FR_Wheel_Angle': -1.5063928365707397, + 'Location': array([ 1.53955383e+02, -2.61518574e+01, 3.99289876e-02]), + 'Rotation': array([ 8.92569050e-02, -7.54359207e+01, 1.75009184e-02]), + 'Velocity': array([ 2.96649861e+00, -1.16369562e+01, -9.11426541e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4985.5634765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6364.95947266, 15312.8203125 , 125.4380722 ]), + 'frame': 28679, + 'frame_number': 28679, + 'framesequence': 115459, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.8977509513497, + 'timestamp_carla': 973896, + 'timestamp_device': 1844500, + 'timestamp_stream': 973.8977509513497, + 'transform': [array([-56.885746 , 90.22467804, 0.11270206]), + array([ 5.28127289e+00, -1.72054779e+02, -6.14122429e-04])]} +{'AngularVelocity': array([-0.06252433, 0.13663775, -9.39217281]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.5178472995758057, + 'FR_Wheel_Angle': -2.6248550415039062, + 'Location': array([ 1.54458908e+02, -2.81959591e+01, 3.99501584e-02]), + 'Rotation': array([ 8.83894712e-02, -7.65780029e+01, 4.72624861e-02]), + 'Velocity': array([ 2.94076276e+00, -1.27548447e+01, -4.26902756e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5365.37548828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6413.23242188, 15687.89257812, 125.24002838]), + 'frame': 28680, + 'frame_number': 28680, + 'framesequence': 115464, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.11991943418979645, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.9374663494527, + 'timestamp_carla': 973936, + 'timestamp_device': 1844542, + 'timestamp_stream': 973.9374663494527, + 'transform': [array([-56.89504623, 90.20544434, 0.11264706]), + array([ 5.28198290e+00, -1.72111572e+02, -5.21817070e-04])]} +{'AngularVelocity': array([ -0.02918558, 0.16545555, -12.6511364 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.776031494140625, + 'FR_Wheel_Angle': -2.8039753437042236, + 'Location': array([ 1.54941544e+02, -3.04056606e+01, 3.99339870e-02]), + 'Rotation': array([ 0.08861487, -78.47531891, 0.07862806]), + 'Velocity': array([ 2.74742126e+00, -1.38786945e+01, 2.63500206e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5364.76416015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6408.14111328, 15686.15234375, 125.17944336]), + 'frame': 28681, + 'frame_number': 28681, + 'framesequence': 115468, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.12713401019573212, + 'throttle_input': 0.2222171425819397, + 'timestamp': 973.9749713502824, + 'timestamp_carla': 973973, + 'timestamp_device': 1844575, + 'timestamp_stream': 973.9749713502824, + 'transform': [array([-56.90348434, 90.18772888, 0.11239208]), + array([ 5.28256369e+00, -1.72163284e+02, 6.16695907e-04])]} +{'AngularVelocity': array([ -0.03127673, 0.22878918, -16.08552361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.441143274307251, + 'FR_Wheel_Angle': -3.394195079803467, + 'Location': array([ 1.55379562e+02, -3.27976761e+01, 3.99445891e-02]), + 'Rotation': array([ 0.08770645, -80.84407806, 0.1129967 ]), + 'Velocity': array([ 2.36504889e+00, -1.50054436e+01, 2.09617610e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4955.21923828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6346.25488281, 15279.26953125, 125.18618774]), + 'frame': 28682, + 'frame_number': 28682, + 'framesequence': 115472, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1470198780298233, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.0072157494724, + 'timestamp_carla': 974006, + 'timestamp_device': 1844608, + 'timestamp_stream': 974.0072157494724, + 'transform': [array([-56.91135788, 90.17259216, 0.11221298]), + array([ 5.28246784e+00, -1.72210861e+02, 1.54240930e-03])]} +{'AngularVelocity': array([-1.25660915e-02, 1.49275884e-01, -1.80153122e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.9434609413146973, + 'FR_Wheel_Angle': -2.524587631225586, + 'Location': array([ 1.55739014e+02, -3.53678360e+01, 3.99519913e-02]), + 'Rotation': array([ 0.08689366, -83.72492218, 0.14627579]), + 'Velocity': array([ 1.80470610e+00, -1.61170082e+01, 7.12394694e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4953.14013671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6341.15332031, 15276.02734375, 125.28302765]), + 'frame': 28683, + 'frame_number': 28683, + 'framesequence': 115476, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16981720924377441, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.0400455519557, + 'timestamp_carla': 974038, + 'timestamp_device': 1844642, + 'timestamp_stream': 974.0400455519557, + 'transform': [array([-56.92036057, 90.15753937, 0.11195232]), + array([ 5.28219461e+00, -1.72263626e+02, 2.70851958e-03])]} +{'AngularVelocity': array([ 0.02737074, -0.01908518, -12.79832649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.8169173002243042, + 'FR_Wheel_Angle': -1.782114028930664, + 'Location': array([ 1.56045761e+02, -3.86824226e+01, 3.99666391e-02]), + 'Rotation': array([ 8.45235884e-02, -8.67806015e+01, 1.50107339e-01]), + 'Velocity': array([ 1.15193105e+00, -1.73565025e+01, 1.25408167e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4951.11572265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6336.4609375 , 15273.04492188, 125.36656189]), + 'frame': 28684, + 'frame_number': 28684, + 'framesequence': 115480, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19157080352306366, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.0744908489287, + 'timestamp_carla': 974073, + 'timestamp_device': 1844675, + 'timestamp_stream': 974.0744908489287, + 'transform': [array([-56.93221664, 90.14183044, 0.11177567]), + array([ 5.28149128e+00, -1.72330170e+02, 3.38088977e-03])]} +{'AngularVelocity': array([ 0.09573526, 0.05214537, -11.31447697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.804250955581665, + 'FR_Wheel_Angle': -1.770329236984253, + 'Location': array([ 1.56199585e+02, -4.16804276e+01, 4.00489978e-02]), + 'Rotation': array([ 7.79051334e-02, -8.87737503e+01, 1.47619247e-01]), + 'Velocity': array([ 5.66778123e-01, -1.82313004e+01, -1.10786431e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4948.70458984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6331.26318359, 15269.74121094, 125.46876526]), + 'frame': 28685, + 'frame_number': 28685, + 'framesequence': 115484, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.2048463523387909, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.1084934510291, + 'timestamp_carla': 974107, + 'timestamp_device': 1844708, + 'timestamp_stream': 974.1084934510291, + 'transform': [array([-56.94485092, 90.12671661, 0.11165207]), + array([ 5.28103352e+00, -1.72399963e+02, 3.86771024e-03])]} +{'AngularVelocity': array([ 0.04714935, -0.07349795, -10.21298122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.2057195901870728, + 'FR_Wheel_Angle': -1.0183554887771606, + 'Location': array([ 1.56253769e+02, -4.47550583e+01, 4.00648676e-02]), + 'Rotation': array([ 6.72773570e-02, -9.05908279e+01, 1.42770752e-01]), + 'Velocity': array([ 1.66203594e-03, -1.89302273e+01, -3.05452326e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4945.35546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6324.73339844, 15265.58886719, 125.5268631 ]), + 'frame': 28686, + 'frame_number': 28686, + 'framesequence': 115488, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.19981078803539276, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.1417036503553, + 'timestamp_carla': 974140, + 'timestamp_device': 1844741, + 'timestamp_stream': 974.1417036503553, + 'transform': [array([-56.95606232, 90.11206818, 0.11150661]), + array([ 5.28203773e+00, -1.72463257e+02, 4.62918077e-03])]} +{'AngularVelocity': array([ 0.09467877, -0.12325559, -5.57794857]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5234885811805725, + 'FR_Wheel_Angle': -0.4042312800884247, + 'Location': array([ 1.56204437e+02, -4.86446114e+01, 4.01515774e-02]), + 'Rotation': array([ 5.61646409e-02, -9.21539307e+01, 1.18904546e-01]), + 'Velocity': array([-5.31939805e-01, -1.96221714e+01, -1.70530321e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4942.8974609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6318.05322266, 15262.40429688, 125.56915283]), + 'frame': 28687, + 'frame_number': 28687, + 'framesequence': 115492, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18904386460781097, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.1740897521377, + 'timestamp_carla': 974172, + 'timestamp_device': 1844775, + 'timestamp_stream': 974.1740897521377, + 'transform': [array([-56.96779251, 90.09770203, 0.11157379]), + array([ 5.28265238e+00, -1.72528122e+02, 4.45044134e-03])]} +{'AngularVelocity': array([-0.06583267, -0.05768377, -2.17477083]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.09691615402698517, + 'FR_Wheel_Angle': -0.056880369782447815, + 'Location': array([ 1.56093185e+02, -5.19552803e+01, 4.02091034e-02]), + 'Rotation': array([ 4.61925678e-02, -9.27752304e+01, 8.64631757e-02]), + 'Velocity': array([-8.13981354e-01, -2.00909195e+01, -1.66248321e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4951.16064453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6313.34179688, 15269.81738281, 125.63467407]), + 'frame': 28688, + 'frame_number': 28688, + 'framesequence': 115496, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17748954892158508, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.2065280489624, + 'timestamp_carla': 974205, + 'timestamp_device': 1844808, + 'timestamp_stream': 974.2065280489624, + 'transform': [array([-56.97817612, 90.0836792 , 0.11158253]), + array([ 5.28357458e+00, -1.72586624e+02, 4.53313533e-03])]} +{'AngularVelocity': array([ 0.03078562, -0.18151841, -0.56359226]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012948067858815193, + 'FR_Wheel_Angle': -0.01293929386883974, + 'Location': array([ 1.55944046e+02, -5.53338776e+01, 4.01741192e-02]), + 'Rotation': array([ 4.26408686e-02, -9.29691391e+01, 5.58322743e-02]), + 'Velocity': array([-9.70964968e-01, -2.04882832e+01, 1.28717424e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4959.55419921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6308.52099609, 15277.3984375 , 125.62033844]), + 'frame': 28689, + 'frame_number': 28689, + 'framesequence': 115500, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.16899318993091583, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.2393356524408, + 'timestamp_carla': 974238, + 'timestamp_device': 1844841, + 'timestamp_stream': 974.2393356524408, + 'transform': [array([-56.98700714, 90.06921387, 0.11150616]), + array([ 5.28442144e+00, -1.72638474e+02, 4.94483579e-03])]} +{'AngularVelocity': array([ 0.02184856, -0.12159916, -0.19296905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012906841933727264, + 'FR_Wheel_Angle': -0.012898685410618782, + 'Location': array([ 1.55776428e+02, -5.87469406e+01, 4.02300432e-02]), + 'Rotation': array([ 3.69103402e-02, -9.30225067e+01, 3.13678272e-02]), + 'Velocity': array([-1.05217934e+00, -2.08276463e+01, 1.02720260e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16994.376953125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7855.88964844, 27210.8515625 , 126.57518768]), + 'frame': 28690, + 'frame_number': 28690, + 'framesequence': 115504, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1695791482925415, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.2712391503155, + 'timestamp_carla': 974270, + 'timestamp_device': 1844875, + 'timestamp_stream': 974.2712391503155, + 'transform': [array([-56.99622345, 90.05549622, 0.11143501]), + array([ 5.28481770e+00, -1.72691071e+02, 5.30838454e-03])]} +{'AngularVelocity': array([ 0.01153116, -0.06369159, -0.10798904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012875097803771496, + 'FR_Wheel_Angle': -0.012867224402725697, + 'Location': array([ 1.55559875e+02, -6.29636154e+01, 4.02666666e-02]), + 'Rotation': array([ 3.27234343e-02, -9.30498581e+01, 1.33779580e-02]), + 'Velocity': array([-1.10310853e+00, -2.12080688e+01, 2.95352929e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16994.453125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7840.29492188, 27211.4296875 , 126.69554901]), + 'frame': 28691, + 'frame_number': 28691, + 'framesequence': 115507, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17454147338867188, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.3029513508081, + 'timestamp_carla': 974301, + 'timestamp_device': 1844900, + 'timestamp_stream': 974.3029513508081, + 'transform': [array([-57.00804138, 90.04026794, 0.11188228]), + array([ 5.28384781e+00, -1.72756241e+02, 3.31241614e-03])]} +{'AngularVelocity': array([ 0.00699324, -0.03238126, -0.09631421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012844763696193695, + 'FR_Wheel_Angle': -0.012837104499340057, + 'Location': array([ 1.55374054e+02, -6.65174942e+01, 4.02806662e-02]), + 'Rotation': array([ 3.08451317e-02, -9.30664597e+01, 5.82103431e-03]), + 'Velocity': array([-1.13064456e+00, -2.15096989e+01, 7.21454626e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4927.5673828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6289.45556641, 15243.1640625 , 125.68941498]), + 'frame': 28692, + 'frame_number': 28692, + 'framesequence': 115511, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1798883080482483, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.3347969502211, + 'timestamp_carla': 974333, + 'timestamp_device': 1844933, + 'timestamp_stream': 974.3347969502211, + 'transform': [array([-57.01927185, 90.02464294, 0.1120325 ]), + array([ 5.28335571e+00, -1.72819397e+02, 2.61924602e-03])]} +{'AngularVelocity': array([ 0.00480415, -0.01548238, -0.0945209 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012815304100513458, + 'FR_Wheel_Angle': -0.01280776783823967, + 'Location': array([ 1.55183792e+02, -7.01259995e+01, 4.02882174e-02]), + 'Rotation': array([ 2.96771694e-02, -9.30821762e+01, 2.09598942e-03]), + 'Velocity': array([-1.15385163e+00, -2.18028259e+01, 2.91347487e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4924.39892578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6283.16699219, 15239.16796875, 125.52029419]), + 'frame': 28693, + 'frame_number': 28693, + 'framesequence': 115515, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1849604845046997, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.3665738515556, + 'timestamp_carla': 974365, + 'timestamp_device': 1844966, + 'timestamp_stream': 974.3665738515556, + 'transform': [array([-57.03008652, 90.00935364, 0.11194953]), + array([ 5.28341055e+00, -1.72880569e+02, 2.97569041e-03])]} +{'AngularVelocity': array([ 0.00407 , -0.00703112, -0.09488388]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012786642648279667, + 'FR_Wheel_Angle': -0.012779485434293747, + 'Location': array([ 1.54989182e+02, -7.37939987e+01, 4.02931385e-02]), + 'Rotation': array([ 2.88712084e-02, -9.30978851e+01, 3.63747618e-04]), + 'Velocity': array([-1.17556322e+00, -2.20889053e+01, 2.10762028e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4921.40966796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6277.04980469, 15235.27832031, 125.461586 ]), + 'frame': 28694, + 'frame_number': 28694, + 'framesequence': 115519, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1849604845046997, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.4001265503466, + 'timestamp_carla': 974399, + 'timestamp_device': 1845000, + 'timestamp_stream': 974.4001265503466, + 'transform': [array([-57.04181671, 89.99317169, 0.11180847]), + array([ 5.28332186e+00, -1.72946411e+02, 3.50415334e-03])]} +{'AngularVelocity': array([ 0.00510067, -0.00316979, -0.09568214]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012758813798427582, + 'FR_Wheel_Angle': -0.012751886621117592, + 'Location': array([ 1.54787903e+02, -7.75668793e+01, 4.02984433e-02]), + 'Rotation': array([ 2.80242655e-02, -9.31140366e+01, -4.27247025e-04]), + 'Velocity': array([-1.19673634e+00, -2.23669796e+01, -8.20159869e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4918.53369140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6271.11523438, 15231.50488281, 125.49169922]), + 'frame': 28695, + 'frame_number': 28695, + 'framesequence': 115523, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18267160654067993, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.432833250612, + 'timestamp_carla': 974431, + 'timestamp_device': 1845033, + 'timestamp_stream': 974.432833250612, + 'transform': [array([-57.05303192, 89.97768402, 0.1116534 ]), + array([ 5.28347874e+00, -1.73009369e+02, 4.17012582e-03])]} +{'AngularVelocity': array([ 0.00587982, -0.00143342, -0.09650958]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012732738628983498, + 'FR_Wheel_Angle': -0.01272609643638134, + 'Location': array([ 1.54588028e+02, -8.12942505e+01, 4.03037071e-02]), + 'Rotation': array([ 2.71158498e-02, -9.31299438e+01, -7.32421118e-04]), + 'Velocity': array([-1.21680450e+00, -2.26256046e+01, -5.14984094e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4915.42919921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6264.74169922, 15227.45410156, 125.53514099]), + 'frame': 28696, + 'frame_number': 28696, + 'framesequence': 115527, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17957700788974762, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.4662526510656, + 'timestamp_carla': 974465, + 'timestamp_device': 1845066, + 'timestamp_stream': 974.4662526510656, + 'transform': [array([-57.06435776, 89.96202087, 0.11155052]), + array([ 5.28368378e+00, -1.73072800e+02, 4.60172910e-03])]} +{'AngularVelocity': array([ 0.00525923, -0.00067485, -0.09731097]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012703047133982182, + 'FR_Wheel_Angle': -0.01269669458270073, + 'Location': array([ 1.54385254e+02, -8.50562515e+01, 4.03091237e-02]), + 'Rotation': array([ 2.61664540e-02, -9.31459351e+01, -8.54491547e-04]), + 'Velocity': array([-1.23631883e+00, -2.28712234e+01, -2.35557559e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4919.28076171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6259.47998047, 15230.34082031, 125.59162903]), + 'frame': 28697, + 'frame_number': 28697, + 'framesequence': 115531, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17765435576438904, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.4984373487532, + 'timestamp_carla': 974497, + 'timestamp_device': 1845100, + 'timestamp_stream': 974.4984373487532, + 'transform': [array([-57.07466507, 89.947052 , 0.11144798]), + array([ 5.28390932e+00, -1.73131180e+02, 5.08191111e-03])]} +{'AngularVelocity': array([ 0.05116726, -0.14288381, -0.08319826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012679334729909897, + 'FR_Wheel_Angle': -0.012673299759626389, + 'Location': array([ 1.54133881e+02, -8.96946640e+01, 4.03494462e-02]), + 'Rotation': array([ 2.64123399e-02, -9.31642227e+01, 7.49884290e-04]), + 'Velocity': array([-1.25901914e+00, -2.31568069e+01, -1.03260996e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4927.77197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6254.73144531, 15237.81152344, 125.62821198]), + 'frame': 28698, + 'frame_number': 28698, + 'framesequence': 115535, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.178368479013443, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.5309587493539, + 'timestamp_carla': 974529, + 'timestamp_device': 1845133, + 'timestamp_stream': 974.5309587493539, + 'transform': [array([-57.08553696, 89.9323349 , 0.11138691]), + array([ 5.28408670e+00, -1.73191498e+02, 5.36341360e-03])]} +{'AngularVelocity': array([-0.00451693, -0.04642661, 0.02135797]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.042840369045734406, + 'FR_Wheel_Angle': -0.12734782695770264, + 'Location': array([ 1.53923035e+02, -9.35603333e+01, 4.03227024e-02]), + 'Rotation': array([ 2.37075854e-02, -9.31675491e+01, -2.01416062e-03]), + 'Velocity': array([-1.27798402e+00, -2.33747959e+01, -6.25820132e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12181.001953125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-7116.79931641, 22438.046875 , 126.31013489]), + 'frame': 28699, + 'frame_number': 28699, + 'framesequence': 115539, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1797967553138733, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.5644959509373, + 'timestamp_carla': 974563, + 'timestamp_device': 1845166, + 'timestamp_stream': 974.5644959509373, + 'transform': [array([-57.09647751, 89.91706848, 0.11136104]), + array([ 5.28412104e+00, -1.73252792e+02, 5.44524379e-03])]} +{'AngularVelocity': array([ 0.01691064, 0.21293852, -4.43909597]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1694583892822266, + 'FR_Wheel_Angle': -1.536629557609558, + 'Location': array([ 1.53697433e+02, -9.75740738e+01, 4.03117165e-02]), + 'Rotation': array([ 2.26284154e-02, -9.34557800e+01, 1.44187324e-02]), + 'Velocity': array([-1.42055869e+00, -2.35643406e+01, -8.87203205e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 13019.626953125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-7203.13916016, 23270.765625 , 126.44759369]), + 'frame': 28700, + 'frame_number': 28700, + 'framesequence': 115543, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18102359771728516, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.5982546508312, + 'timestamp_carla': 974597, + 'timestamp_device': 1845200, + 'timestamp_stream': 974.5982546508312, + 'transform': [array([-57.10732651, 89.90215302, 0.1112574 ]), + array([ 5.28427124e+00, -1.73313187e+02, 5.87770529e-03])]} +{'AngularVelocity': array([ 0.09561212, 0.58440661, -14.21973801]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.0142767429351807, + 'FR_Wheel_Angle': -3.1724965572357178, + 'Location': array([ 1.53430832e+02, -1.01485077e+02, 4.03790846e-02]), + 'Rotation': array([ 2.28538122e-02, -9.50358887e+01, 7.05514774e-02]), + 'Velocity': array([-1.95154035e+00, -2.36749001e+01, -1.95784567e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4901.26171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6235.20996094, 15208.68066406, 125.69700623]), + 'frame': 28701, + 'frame_number': 28701, + 'framesequence': 115547, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18062074482440948, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.6326846517622, + 'timestamp_carla': 974631, + 'timestamp_device': 1845233, + 'timestamp_stream': 974.6326846517622, + 'transform': [array([-57.11928177, 89.88707733, 0.1112915 ]), + array([ 5.28427124e+00, -1.73378540e+02, 5.69922803e-03])]} +{'AngularVelocity': array([ 0.14700186, 0.71032232, -26.65768814]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.029847621917725, + 'FR_Wheel_Angle': -5.160905838012695, + 'Location': array([ 1.52944534e+02, -1.06186043e+02, 4.03798856e-02]), + 'Rotation': array([ 1.70823019e-02, -9.91237869e+01, 1.95878372e-01]), + 'Velocity': array([-3.25914240e+00, -2.36055088e+01, -1.26147264e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4898.5009765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6229.41503906, 15204.99804688, 125.73264313]), + 'frame': 28702, + 'frame_number': 28702, + 'framesequence': 115551, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17941221594810486, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.6640030518174, + 'timestamp_carla': 974662, + 'timestamp_device': 1845266, + 'timestamp_stream': 974.6640030518174, + 'transform': [array([-57.12857437, 89.87369537, 0.11123001]), + array([ 5.28487921e+00, -1.73430908e+02, 6.10431051e-03])]} +{'AngularVelocity': array([ 0.26567531, 0.73669463, -39.99873734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.668452262878418, + 'FR_Wheel_Angle': -6.425823211669922, + 'Location': array([ 1.52123917e+02, -1.10842377e+02, 4.04908545e-02]), + 'Rotation': array([ 1.02179628e-02, -1.05876602e+02, 3.66011798e-01]), + 'Velocity': array([-5.38743210e+00, -2.29885082e+01, 4.24127560e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4895.43115234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6223.16992188, 15201.02832031, 125.71643066]), + 'frame': 28703, + 'frame_number': 28703, + 'framesequence': 115555, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17922911047935486, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.6960750520229, + 'timestamp_carla': 974694, + 'timestamp_device': 1845300, + 'timestamp_stream': 974.6960750520229, + 'transform': [array([-57.1387825 , 89.86011505, 0.11125652]), + array([ 5.28500223e+00, -1.73487244e+02, 6.02856418e-03])]} +{'AngularVelocity': array([ 0.35675484, 0.67677611, -47.90153503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.529312610626221, + 'FR_Wheel_Angle': -7.175119400024414, + 'Location': array([ 1.51079239e+02, -1.14590164e+02, 4.05480377e-02]), + 'Rotation': array([-2.19932082e-03, -1.13268394e+02, 4.98154044e-01]), + 'Velocity': array([-7.59989929e+00, -2.18994331e+01, -4.48083854e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4893.0966796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6218.14746094, 15197.8359375 , 125.75163269]), + 'frame': 28704, + 'frame_number': 28704, + 'framesequence': 115558, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.17981506884098053, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.7294086515903, + 'timestamp_carla': 974728, + 'timestamp_device': 1845325, + 'timestamp_stream': 974.7294086515903, + 'transform': [array([-57.14947128, 89.84584808, 0.11128532]), + array([ 5.28466749e+00, -1.73546158e+02, 5.84317092e-03])]} +{'AngularVelocity': array([ 0.38874587, 0.54070812, -52.99943542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.175653457641602, + 'FR_Wheel_Angle': -7.682995796203613, + 'Location': array([ 1.49706253e+02, -1.18002174e+02, 4.04867753e-02]), + 'Rotation': array([-1.41931325e-02, -1.21423187e+02, 6.04674518e-01]), + 'Velocity': array([-9.91213322e+00, -2.03108044e+01, -8.10680387e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4890.52685546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6212.77099609, 15194.41796875, 125.74539185]), + 'frame': 28705, + 'frame_number': 28705, + 'framesequence': 115562, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18025453388690948, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.7624522522092, + 'timestamp_carla': 974761, + 'timestamp_device': 1845358, + 'timestamp_stream': 974.7624522522092, + 'transform': [array([-57.15940475, 89.83203888, 0.11124836]), + array([ 5.28472185e+00, -1.73601501e+02, 6.00128481e-03])]} +{'AngularVelocity': array([ 0.38548616, 0.3441771 , -56.78969574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.819087028503418, + 'FR_Wheel_Angle': -8.162728309631348, + 'Location': array([ 1.47892487e+02, -1.21228004e+02, 4.06242535e-02]), + 'Rotation': array([-2.27650199e-02, -1.30564285e+02, 7.15173781e-01]), + 'Velocity': array([-1.22590160e+01, -1.81159306e+01, 1.74534321e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4887.85791015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6207.15869141, 15190.84960938, 125.72919464]), + 'frame': 28706, + 'frame_number': 28706, + 'framesequence': 115566, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.18014465272426605, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.7943034507334, + 'timestamp_carla': 974793, + 'timestamp_device': 1845391, + 'timestamp_stream': 974.7943034507334, + 'transform': [array([-57.16892624, 89.8189621 , 0.11125442]), + array([ 5.28502941e+00, -1.73654449e+02, 6.04188116e-03])]} +{'AngularVelocity': array([ 0.1057689 , 0.18515728, -57.99643707]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.906095504760742, + 'FR_Wheel_Angle': -8.214620590209961, + 'Location': array([ 1.45763977e+02, -1.23987282e+02, 4.07543369e-02]), + 'Rotation': array([-1.87693592e-02, -1.39923981e+02, 7.68406630e-01]), + 'Velocity': array([-1.43082762e+01, -1.54993563e+01, 1.82961463e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4893.3115234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6202.76220703, 15195.36035156, 125.74291229]), + 'frame': 28707, + 'frame_number': 28707, + 'framesequence': 115570, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.8272796496749, + 'timestamp_carla': 974826, + 'timestamp_device': 1845425, + 'timestamp_stream': 974.8272796496749, + 'transform': [array([-57.17414093, 89.80431366, 0.11085136]), + array([ 5.28497458e+00, -1.73690079e+02, 7.72944093e-03])]} +{'AngularVelocity': array([ 0.19843428, 0.1037225 , -57.89442062]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.718212127685547, + 'FR_Wheel_Angle': -7.639233112335205, + 'Location': array([ 1.43281128e+02, -1.26333183e+02, 4.07213792e-02]), + 'Rotation': array([-1.89469438e-02, -1.49506271e+02, 8.15861404e-01]), + 'Velocity': array([-1.59931202e+01, -1.24610720e+01, -7.71093357e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4900.498046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6198.76855469, 15201.64160156, 125.74759674]), + 'frame': 28708, + 'frame_number': 28708, + 'framesequence': 115574, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.8615081496537, + 'timestamp_carla': 974860, + 'timestamp_device': 1845458, + 'timestamp_stream': 974.8615081496537, + 'transform': [array([-57.18435287, 89.78910065, 0.11062142]), + array([ 5.28435993e+00, -1.73747940e+02, 8.58714618e-03])]} +{'AngularVelocity': array([ -0.30825824, -0.10382986, -47.03738785]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.0764150619506836, + 'FR_Wheel_Angle': -1.9032979011535645, + 'Location': array([ 1.39923691e+02, -1.28505981e+02, 4.07380871e-02]), + 'Rotation': array([-1.29090566e-02, -1.60446472e+02, 7.95436144e-01]), + 'Velocity': array([-1.73448429e+01, -8.72415066e+00, -7.60316849e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4906.0341796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6196.01269531, 15205.9765625 , 125.89110565]), + 'frame': 28709, + 'frame_number': 28709, + 'framesequence': 115579, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.8976361490786, + 'timestamp_carla': 974896, + 'timestamp_device': 1845500, + 'timestamp_stream': 974.8976361490786, + 'transform': [array([-57.19680023, 89.77301788, 0.11067951]), + array([ 5.28371811e+00, -1.73816376e+02, 8.17546993e-03])]} +{'AngularVelocity': array([ -0.92222756, -0.2113024 , -16.06258011]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3772594928741455, + 'FR_Wheel_Angle': 0.6192744374275208, + 'Location': array([ 1.36371094e+02, -1.29990402e+02, 4.07361016e-02]), + 'Rotation': array([-1.70891322e-02, -1.66686966e+02, 6.37457967e-01]), + 'Velocity': array([-1.78698978e+01, -5.95962858e+00, -4.40330507e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5131.5517578125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6215.29492188, 15429.11035156, 125.99698639]), + 'frame': 28710, + 'frame_number': 28710, + 'framesequence': 115583, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.9301355518401, + 'timestamp_carla': 974928, + 'timestamp_device': 1845533, + 'timestamp_stream': 974.9301355518401, + 'transform': [array([-57.20788956, 89.75828552, 0.11095688]), + array([ 5.28390932e+00, -1.73877548e+02, 7.09161628e-03])]} +{'AngularVelocity': array([-1.49236286, -0.34630048, 5.75547552]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.411621570587158, + 'FR_Wheel_Angle': 3.076350688934326, + 'Location': array([ 1.32786758e+02, -1.31023270e+02, 4.06554975e-02]), + 'Rotation': array([-1.67544540e-02, -1.67559311e+02, 3.91099721e-01]), + 'Velocity': array([-1.77631474e+01, -4.61930037e+00, -4.77466587e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5132.7216796875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-6208.96728516, 15429.25585938, 125.95904541]), + 'frame': 28711, + 'frame_number': 28711, + 'framesequence': 115586, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.9619558490813, + 'timestamp_carla': 974960, + 'timestamp_device': 1845558, + 'timestamp_stream': 974.9619558490813, + 'transform': [array([-57.21817398, 89.74417877, 0.11109871]), + array([ 5.28430557e+00, -1.73934509e+02, 6.59758737e-03])]} +{'AngularVelocity': array([-1.49355829, -0.41288218, 21.69128799]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.635415077209473, + 'FR_Wheel_Angle': 4.911728858947754, + 'Location': array([ 1.29873840e+02, -1.31784027e+02, 4.06120867e-02]), + 'Rotation': array([-1.96504537e-02, -1.65106735e+02, 1.21195681e-01]), + 'Velocity': array([-1.72811794e+01, -4.84071636e+00, -1.88694001e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4873.71728515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6175.578125 , 15170.77441406, 125.8323822 ]), + 'frame': 28712, + 'frame_number': 28712, + 'framesequence': 115590, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 974.9949493519962, + 'timestamp_carla': 974993, + 'timestamp_device': 1845591, + 'timestamp_stream': 974.9949493519962, + 'transform': [array([-57.22881699, 89.7298584 , 0.11116703]), + array([ 5.28472900e+00, -1.73993042e+02, 6.35772943e-03])]} +{'AngularVelocity': array([-0.78373218, -0.26698136, 24.18918037]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.4457716941833496, + 'FR_Wheel_Angle': 2.972229480743408, + 'Location': array([ 1.27067421e+02, -1.32625107e+02, 4.05717269e-02]), + 'Rotation': array([-2.09960006e-02, -1.61090775e+02, -7.39746168e-02]), + 'Velocity': array([-1.65847778e+01, -5.56576109e+00, -5.80377586e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4871.240234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6170.18945312, 15167.34960938, 125.79154968]), + 'frame': 28713, + 'frame_number': 28713, + 'framesequence': 115594, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.0293611511588, + 'timestamp_carla': 975028, + 'timestamp_device': 1845625, + 'timestamp_stream': 975.0293611511588, + 'transform': [array([-57.2396965 , 89.71498108, 0.11124428]), + array([ 5.28494740e+00, -1.74053070e+02, 6.00766391e-03])]} +{'AngularVelocity': array([ 5.89746935e-03, -2.08151266e-02, 1.11760616e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.827308714389801, + 'FR_Wheel_Angle': 0.2785341143608093, + 'Location': array([ 1.23835976e+02, -1.33795883e+02, 4.05911803e-02]), + 'Rotation': array([-2.53604911e-02, -1.57435654e+02, -1.48956299e-01]), + 'Velocity': array([-1.57325897e+01, -6.22874498e+00, 1.02558137e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4868.68798828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6164.66064453, 15163.83496094, 125.77064514]), + 'frame': 28714, + 'frame_number': 28714, + 'framesequence': 115598, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.0623541511595, + 'timestamp_carla': 975061, + 'timestamp_device': 1845658, + 'timestamp_stream': 975.0623541511595, + 'transform': [array([-57.25120163, 89.700737 , 0.11141948]), + array([ 5.28448296e+00, -1.74115097e+02, 5.23306290e-03])]} +{'AngularVelocity': array([ 0.47552773, 0.13977252, -4.09066772]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.9700582027435303, + 'FR_Wheel_Angle': -2.29949951171875, + 'Location': array([ 1.21280479e+02, -1.34830185e+02, 4.06902507e-02]), + 'Rotation': array([-2.67948303e-02, -1.56918503e+02, -9.41467136e-02]), + 'Velocity': array([-1.52272530e+01, -6.22196960e+00, -1.71761028e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4866.1005859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6158.99707031, 15160.234375 , 125.73961639]), + 'frame': 28715, + 'frame_number': 28715, + 'framesequence': 115603, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.0959986522794, + 'timestamp_carla': 975094, + 'timestamp_device': 1845700, + 'timestamp_stream': 975.0959986522794, + 'transform': [array([-57.26119614, 89.68659973, 0.11138786]), + array([ 5.28494740e+00, -1.74170609e+02, 5.41087333e-03])]} +{'AngularVelocity': array([ 0.40816456, 0.25055683, -13.32891464]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.018099784851074, + 'FR_Wheel_Angle': -3.1022868156433105, + 'Location': array([ 1.18746140e+02, -1.35849121e+02, 4.07213792e-02]), + 'Rotation': array([-3.14939991e-02, -1.58573959e+02, 5.15332585e-03]), + 'Velocity': array([-1.49006519e+01, -5.73021126e+00, -1.87972060e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4863.3408203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6153.17333984, 15156.53222656, 125.67503357]), + 'frame': 28716, + 'frame_number': 28716, + 'framesequence': 115606, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.128139551729, + 'timestamp_carla': 975127, + 'timestamp_device': 1845725, + 'timestamp_stream': 975.128139551729, + 'transform': [array([-57.27215195, 89.67298889, 0.11150326]), + array([ 5.28497458e+00, -1.74229721e+02, 4.96539148e-03])]} +{'AngularVelocity': array([ 0.43888763, 0.15170343, -17.71388245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.8296000957489014, + 'FR_Wheel_Angle': -3.7236318588256836, + 'Location': array([ 1.16313843e+02, -1.36744247e+02, 4.06174287e-02]), + 'Rotation': array([-2.88712084e-02, -1.61180008e+02, 9.04941335e-02]), + 'Velocity': array([-1.46781101e+01, -4.95974159e+00, -3.29208378e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4864.4970703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6148.29492188, 15156.6796875 , 125.68951416]), + 'frame': 28717, + 'frame_number': 28717, + 'framesequence': 115610, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.1613183505833, + 'timestamp_carla': 975160, + 'timestamp_device': 1845758, + 'timestamp_stream': 975.1613183505833, + 'transform': [array([-57.28238297, 89.65911865, 0.11151981]), + array([ 5.28530931e+00, -1.74285950e+02, 4.92423819e-03])]} +{'AngularVelocity': array([ 0.1989266 , 0.06132971, -18.34553146]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.6247663497924805, + 'FR_Wheel_Angle': -3.2873828411102295, + 'Location': array([ 1.13897377e+02, -1.37508881e+02, 4.06213924e-02]), + 'Rotation': array([-2.83862650e-02, -1.64244736e+02, 1.45800352e-01]), + 'Velocity': array([-1.44688082e+01, -4.08468103e+00, 4.36782830e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4872.51416015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6143.81542969, 15163.72851562, 125.65361023]), + 'frame': 28718, + 'frame_number': 28718, + 'framesequence': 115614, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.1949974521995, + 'timestamp_carla': 975193, + 'timestamp_device': 1845791, + 'timestamp_stream': 975.1949974521995, + 'transform': [array([-57.29383087, 89.64495087, 0.11167236]), + array([ 5.28478336e+00, -1.74347382e+02, 4.19698237e-03])]} +{'AngularVelocity': array([-5.48541471e-02, -4.16658167e-03, -1.36328182e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.4452362060546875, + 'FR_Wheel_Angle': -2.29958438873291, + 'Location': array([ 1.11498253e+02, -1.38140839e+02, 4.06198315e-02]), + 'Rotation': array([-2.71841511e-02, -1.66931854e+02, 1.52498499e-01]), + 'Velocity': array([-1.42133684e+01, -3.34281754e+00, 2.29549405e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4880.2744140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6139.52929688, 15170.46875 , 125.65027618]), + 'frame': 28719, + 'frame_number': 28719, + 'framesequence': 115618, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.22862175107, + 'timestamp_carla': 975227, + 'timestamp_device': 1845825, + 'timestamp_stream': 975.22862175107, + 'transform': [array([-57.30520248, 89.63104248, 0.11168361]), + array([ 5.28487921e+00, -1.74408203e+02, 4.14920831e-03])]} +{'AngularVelocity': array([-0.15721323, -0.02167402, -9.98012066]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.822940707206726, + 'FR_Wheel_Angle': -1.6051199436187744, + 'Location': array([ 1.09149139e+02, -1.38657318e+02, 4.06133085e-02]), + 'Rotation': array([-2.56883409e-02, -1.68885101e+02, 1.34858295e-01]), + 'Velocity': array([-1.39236326e+01, -2.75847197e+00, 7.71999385e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 17030.1953125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7330.671875 , 27260.33984375, 126.47528839]), + 'frame': 28720, + 'frame_number': 28720, + 'framesequence': 115622, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.2623475492001, + 'timestamp_carla': 975261, + 'timestamp_device': 1845858, + 'timestamp_stream': 975.2623475492001, + 'transform': [array([-57.31557465, 89.61641693, 0.1118037 ]), + array([ 5.28497458e+00, -1.74465454e+02, 3.64105473e-03])]} +{'AngularVelocity': array([-0.22479008, -0.02915393, -5.68338108]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7836537957191467, + 'FR_Wheel_Angle': -0.648760199546814, + 'Location': array([ 1.06861938e+02, -1.39088501e+02, 4.06044573e-02]), + 'Rotation': array([-2.40764152e-02, -1.70162689e+02, 9.98593122e-02]), + 'Velocity': array([-1.36065025e+01, -2.38461709e+00, 6.38008123e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 17031.8359375, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-7312.55322266, 27262.26953125, 126.46089172]), + 'frame': 28721, + 'frame_number': 28721, + 'framesequence': 115626, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.1800714135169983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 975.2946292497218, + 'timestamp_carla': 975293, + 'timestamp_device': 1845891, + 'timestamp_stream': 975.2946292497218, + 'transform': [array([-57.3261795 , 89.60176849, 0.11197906]), + array([ 5.28439426e+00, -1.74523682e+02, 2.87334085e-03])]} +{'AngularVelocity': array([-0.23676202, -0.08351979, -1.86516106]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.23388470709323883, + 'FR_Wheel_Angle': -0.12432703375816345, + 'Location': array([ 1.0417379e+02, -1.3954364e+02, 4.0670719e-02]), + 'Rotation': array([-2.11735852e-02, -1.70866531e+02, 5.54806776e-02]), + 'Velocity': array([-1.32086048e+01, -2.14667153e+00, -2.10868823e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4910.9765625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5926.02783203, 15161.01171875, 251.48974609]), + 'frame': 28752, + 'frame_number': 28752, + 'framesequence': 115750, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24015016853809357, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.327366951853, + 'timestamp_carla': 976326, + 'timestamp_device': 1846924, + 'timestamp_stream': 976.327366951853, + 'transform': [array([-57.78062439, 89.16741943, -0.34820646]), + array([ 2.9718492 , -176.81271362, 1.54990053])]} +{'AngularVelocity': array([-0.60281223, 0.18698584, -0.00098294]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.07885824888944626, + 'FR_Wheel_Angle': 0.08855848759412766, + 'Location': array([ 1.01997253e+02, -1.39895187e+02, 4.07962985e-02]), + 'Rotation': array([-2.63645295e-02, -1.70987473e+02, 3.30381654e-02]), + 'Velocity': array([-1.29323072e+01, -2.07449102e+00, -3.83468624e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4928.39208984375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5920.03808594, 15176.99804688, 255.59667969]), + 'frame': 28753, + 'frame_number': 28753, + 'framesequence': 115754, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.3598787523806, + 'timestamp_carla': 976358, + 'timestamp_device': 1846958, + 'timestamp_stream': 976.3598787523806, + 'transform': [array([-57.80044937, 89.15337372, -0.34757179]), + array([ 2.97245026, -176.91009521, 1.54603076])]} +{'AngularVelocity': array([-0.09582902, 0.04147955, 0.65868104]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.26747217774391174, + 'FR_Wheel_Angle': 0.3184025287628174, + 'Location': array([ 9.98632965e+01, -1.40237686e+02, 4.05092426e-02]), + 'Rotation': array([-1.08941514e-02, -1.70930206e+02, 7.43379025e-03]), + 'Velocity': array([-1.27847290e+01, -2.06183100e+00, -1.35602953e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4932.51904296875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5914.03808594, 15179.921875 , 256.69625854]), + 'frame': 28754, + 'frame_number': 28754, + 'framesequence': 115758, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.3924702517688, + 'timestamp_carla': 976391, + 'timestamp_device': 1846991, + 'timestamp_stream': 976.3924702517688, + 'transform': [array([-57.81851578, 89.13851166, -0.34497669]), + array([ 2.97818089, -177.00057983, 1.53580689])]} +{'AngularVelocity': array([-0.06545379, 0.04075089, 1.73495257]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4488547146320343, + 'FR_Wheel_Angle': 0.46357372403144836, + 'Location': array([ 9.73097534e+01, -1.40654541e+02, 4.04504575e-02]), + 'Rotation': array([ 3.00528307e-04, -1.70677261e+02, -7.78198056e-03]), + 'Velocity': array([-1.27780762e+01, -2.12892318e+00, 6.12831136e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4928.97265625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5905.20849609, 15175.21972656, 256.23950195]), + 'frame': 28755, + 'frame_number': 28755, + 'framesequence': 115762, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.4261717498302, + 'timestamp_carla': 976425, + 'timestamp_device': 1847024, + 'timestamp_stream': 976.4261717498302, + 'transform': [array([-57.83757782, 89.12200165, -0.34185743]), + array([ 2.98499751, -177.09716797, 1.52423716])]} +{'AngularVelocity': array([-0.04064074, 0.02171074, 1.9906801 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4643731713294983, + 'FR_Wheel_Angle': 0.46638160943984985, + 'Location': array([ 9.51790085e+01, -1.41013901e+02, 4.08169366e-02]), + 'Rotation': array([ 2.31133588e-02, -1.70358826e+02, 1.74143072e-02]), + 'Velocity': array([-1.28397436e+01, -2.21181154e+00, 3.01694876e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4923.1513671875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5896.86474609, 15168.1640625 , 255.20692444]), + 'frame': 28756, + 'frame_number': 28756, + 'framesequence': 115766, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.4605761505663, + 'timestamp_carla': 976459, + 'timestamp_device': 1847058, + 'timestamp_stream': 976.4605761505663, + 'transform': [array([-57.85700989, 89.10499573, -0.33890536]), + array([ 2.99193692, -177.19566345, 1.51376855])]} +{'AngularVelocity': array([ 0.00444779, -0.00677606, 1.84008825]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3920068144798279, + 'FR_Wheel_Angle': 0.3582383990287781, + 'Location': array([ 9.30318222e+01, -1.41388138e+02, 4.08154875e-02]), + 'Rotation': array([-6.04471704e-03, -1.70032883e+02, 5.57397539e-03]), + 'Velocity': array([-1.29170103e+01, -2.29574680e+00, 5.69601019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4735.63330078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5879.02880859, 14979.53125 , 249.25170898]), + 'frame': 28757, + 'frame_number': 28757, + 'framesequence': 115770, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.4944982491434, + 'timestamp_carla': 976493, + 'timestamp_device': 1847091, + 'timestamp_stream': 976.4944982491434, + 'transform': [array([-57.87602234, 89.08905029, -0.33640596]), + array([ 2.99740791, -177.2913208 , 1.5051651 ])]} +{'AngularVelocity': array([0.02111742, 0.0373438 , 0.89030451]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.060677215456962585, + 'FR_Wheel_Angle': 0.039402611553668976, + 'Location': array([ 9.08804550e+01, -1.41773315e+02, 4.03914452e-02]), + 'Rotation': array([ 1.19596608e-02, -1.69797821e+02, -1.58691406e-02]), + 'Velocity': array([-1.29995489e+01, -2.34999466e+00, -1.08231546e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4731.4892578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5870.37207031, 14973.90039062, 248.30535889]), + 'frame': 28758, + 'frame_number': 28758, + 'framesequence': 115775, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.5285689495504, + 'timestamp_carla': 976527, + 'timestamp_device': 1847133, + 'timestamp_stream': 976.5285689495504, + 'transform': [array([-57.89415741, 89.07348633, -0.33423245]), + array([ 3.00181341, -177.38267517, 1.49777758])]} +{'AngularVelocity': array([0.02217663, 0.00285077, 0.21412925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03935727849602699, + 'FR_Wheel_Angle': 0.03723696991801262, + 'Location': array([ 8.82698746e+01, -1.42246597e+02, 4.03599739e-02]), + 'Rotation': array([ 1.29022263e-02, -1.69716949e+02, -9.52148344e-03]), + 'Velocity': array([-1.31014471e+01, -2.38581347e+00, 1.33695605e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4727.46826171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5861.98828125, 14968.46679688, 247.52081299]), + 'frame': 28759, + 'frame_number': 28759, + 'framesequence': 115778, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.5624419488013, + 'timestamp_carla': 976561, + 'timestamp_device': 1847158, + 'timestamp_stream': 976.5624419488013, + 'transform': [array([-57.91183853, 89.05852509, -0.33253509]), + array([ 3.00615048, -177.47154236, 1.4922775 ])]} +{'AngularVelocity': array([0.01595815, 0.00150706, 0.08361513]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.009567243047058582, + 'FR_Wheel_Angle': -0.004251566249877214, + 'Location': array([ 8.60842743e+01, -1.42645126e+02, 4.03785892e-02]), + 'Rotation': array([ 1.26768304e-02, -1.69692169e+02, -6.31713821e-03]), + 'Velocity': array([-1.31842089e+01, -2.40722370e+00, 6.84642800e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4740.23193359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5854.72412109, 14979.8046875 , 247.27520752]), + 'frame': 28760, + 'frame_number': 28760, + 'framesequence': 115782, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.5933274514973, + 'timestamp_carla': 976592, + 'timestamp_device': 1847191, + 'timestamp_stream': 976.5933274514973, + 'transform': [array([-57.9275856 , 89.04541016, -0.33119452]), + array([ 3.00920367, -177.550354 , 1.48798656])]} +{'AngularVelocity': array([ 0.01207638, 0.00072836, -0.08284415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.02761666290462017, + 'FR_Wheel_Angle': -0.03291139751672745, + 'Location': array([ 8.38829880e+01, -1.43046967e+02, 4.03866395e-02]), + 'Rotation': array([ 1.24377739e-02, -1.69693832e+02, -3.84521415e-03]), + 'Velocity': array([-1.32653913e+01, -2.42031908e+00, 2.20489492e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4890.00732421875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5853.48730469, 15128.01660156, 250.74220276]), + 'frame': 28761, + 'frame_number': 28761, + 'framesequence': 115786, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.6271404512227, + 'timestamp_carla': 976626, + 'timestamp_device': 1847224, + 'timestamp_stream': 976.6271404512227, + 'transform': [array([-57.94392395, 89.03079987, -0.32994521]), + array([ 3.01269388, -177.63302612, 1.48394918])]} +{'AngularVelocity': array([ 8.32951162e-03, 1.23188453e-04, -1.72136679e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.05942075327038765, + 'FR_Wheel_Angle': -0.08056613802909851, + 'Location': array([ 8.16657486e+01, -1.43451172e+02, 4.03903760e-02]), + 'Rotation': array([ 1.21987173e-02, -1.69715622e+02, -2.28881813e-03]), + 'Velocity': array([-1.33443575e+01, -2.42915964e+00, 6.05583182e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4882.09619140625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5846.18457031, 15118.90527344, 250.19410706]), + 'frame': 28762, + 'frame_number': 28762, + 'framesequence': 115790, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.6613961495459, + 'timestamp_carla': 976660, + 'timestamp_device': 1847258, + 'timestamp_stream': 976.6613961495459, + 'transform': [array([-57.96227264, 89.01631927, -0.32883072]), + array([ 3.01434684, -177.7240448 , 1.48013473])]} +{'AngularVelocity': array([ 0.01738475, 0.00179781, -0.62666452]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.16645285487174988, + 'FR_Wheel_Angle': -0.16615866124629974, + 'Location': array([ 7.89888000e+01, -1.43936859e+02, 4.03926633e-02]), + 'Rotation': array([ 1.19460002e-02, -1.69791611e+02, 6.98339252e-04]), + 'Velocity': array([-1.34382954e+01, -2.42222381e+00, -6.19888283e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4874.0859375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5838.53759766, 15109.53515625, 249.66253662]), + 'frame': 28763, + 'frame_number': 28763, + 'framesequence': 115794, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.6943145506084, + 'timestamp_carla': 976693, + 'timestamp_device': 1847291, + 'timestamp_stream': 976.6943145506084, + 'transform': [array([-57.97824097, 89.00251007, -0.32804996]), + array([ 3.01688075, -177.804245 , 1.47773099])]} +{'AngularVelocity': array([ 8.97808839e-03, 3.07109585e-04, -7.46317804e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.16632027924060822, + 'FR_Wheel_Angle': -0.1660275161266327, + 'Location': array([ 7.67415009e+01, -1.44340225e+02, 4.03940752e-02]), + 'Rotation': array([ 1.17342640e-02, -1.69909912e+02, 2.68951058e-03]), + 'Velocity': array([-1.35149117e+01, -2.40842009e+00, 1.58309933e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4865.42626953125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5830.19775391, 15099.515625 , 249.13208008]), + 'frame': 28764, + 'frame_number': 28764, + 'framesequence': 115798, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.7278669513762, + 'timestamp_carla': 976726, + 'timestamp_device': 1847324, + 'timestamp_stream': 976.7278669513762, + 'transform': [array([-57.99562836, 88.98885345, -0.32738632]), + array([ 3.01797366, -177.89025879, 1.47552991])]} +{'AngularVelocity': array([ 0.00609061, -0.00522051, -0.75970542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.16618521511554718, + 'FR_Wheel_Angle': -0.16590654850006104, + 'Location': array([ 7.44930496e+01, -1.44739090e+02, 4.03963253e-02]), + 'Rotation': array([ 1.13859251e-02, -1.70034988e+02, 3.82515509e-03]), + 'Velocity': array([-1.35839348e+01, -2.39095759e+00, 2.84194948e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4858.302734375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5822.85839844, 15091.07421875, 248.75778198]), + 'frame': 28765, + 'frame_number': 28765, + 'framesequence': 115802, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.7605716511607, + 'timestamp_carla': 976759, + 'timestamp_device': 1847358, + 'timestamp_stream': 976.7605716511607, + 'transform': [array([-58.01109695, 88.97546387, -0.32688099]), + array([ 3.01977682, -177.96780396, 1.47399998])]} +{'AngularVelocity': array([ 0.00526656, -0.01342488, -0.77298337]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1703871488571167, + 'FR_Wheel_Angle': -0.17010633647441864, + 'Location': array([ 7.17760315e+01, -1.45214401e+02, 4.04105932e-02]), + 'Rotation': array([ 8.96803755e-03, -1.70187286e+02, 4.56256466e-03]), + 'Velocity': array([-1.36134090e+01, -2.35886216e+00, -1.52587882e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4850.7431640625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5815.04052734, 15082.19824219, 248.38833618]), + 'frame': 28766, + 'frame_number': 28766, + 'framesequence': 115806, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.7960592508316, + 'timestamp_carla': 976795, + 'timestamp_device': 1847391, + 'timestamp_stream': 976.7960592508316, + 'transform': [array([-58.02944183, 88.96103668, -0.32631683]), + array([ 3.02079439, -178.05848694, 1.47197688])]} +{'AngularVelocity': array([ 0.0027096 , -0.0084569 , -0.77961922]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.17039428651332855, + 'FR_Wheel_Angle': -0.1701166331768036, + 'Location': array([ 6.95095215e+01, -1.45605148e+02, 4.04218845e-02]), + 'Rotation': array([ 7.05558481e-03, -1.70316650e+02, 4.87432024e-03]), + 'Velocity': array([-1.36144371e+01, -2.32740164e+00, -6.86645478e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5308.5009765625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5823.82666016, 15538.22363281, 260.02612305]), + 'frame': 28767, + 'frame_number': 28767, + 'framesequence': 115810, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.8268821500242, + 'timestamp_carla': 976825, + 'timestamp_device': 1847424, + 'timestamp_stream': 976.8268821500242, + 'transform': [array([-58.04402161, 88.9478302 , -0.32576495]), + array([ 3.02170277, -178.13183594, 1.47006989])]} +{'AngularVelocity': array([ 0.04899383, -0.02505839, -0.78038901]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.1630021333694458, + 'FR_Wheel_Angle': -0.15747271478176117, + 'Location': array([ 6.72434082e+01, -1.45990433e+02, 4.04446609e-02]), + 'Rotation': array([ 6.27011340e-03, -1.70449188e+02, 5.55593939e-03]), + 'Velocity': array([-1.36106215e+01, -2.29465318e+00, -7.53140426e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5315.1728515625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5815.37402344, 15543.484375 , 260.01589966]), + 'frame': 28768, + 'frame_number': 28768, + 'framesequence': 115814, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.8596821501851, + 'timestamp_carla': 976858, + 'timestamp_device': 1847458, + 'timestamp_stream': 976.8596821501851, + 'transform': [array([-58.06211853, 88.93335724, -0.32510933]), + array([ 3.02146387, -178.22120667, 1.46746361])]} +{'AngularVelocity': array([ 0.21433343, 0.11392961, -0.53630114]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.013761673122644424, + 'FR_Wheel_Angle': 0.019055034965276718, + 'Location': array([ 6.49723434e+01, -1.46371765e+02, 4.04961966e-02]), + 'Rotation': array([ 1.98758487e-03, -1.70558823e+02, -1.49536121e-03]), + 'Velocity': array([-1.36045113e+01, -2.27255154e+00, -6.70566573e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5320.6953125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5808.50488281, 15547.70214844, 259.98834229]), + 'frame': 28769, + 'frame_number': 28769, + 'framesequence': 115818, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.8933952488005, + 'timestamp_carla': 976892, + 'timestamp_device': 1847491, + 'timestamp_stream': 976.8933952488005, + 'transform': [array([-58.0805397 , 88.91765594, -0.32445732]), + array([ 3.0219624 , -178.31282043, 1.46488559])]} +{'AngularVelocity': array([-0.01100432, -0.00312114, 0.01248215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.005293622147291899, + 'FR_Wheel_Angle': -0.005293460097163916, + 'Location': array([ 6.22610779e+01, -1.46824402e+02, 4.04169634e-02]), + 'Rotation': array([ 5.68271708e-03, -1.70584259e+02, 1.02426729e-03]), + 'Velocity': array([-1.35936737e+01, -2.26630926e+00, 3.54146941e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5327.1630859375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5800.14501953, 15552.72851562, 259.91812134]), + 'frame': 28770, + 'frame_number': 28770, + 'framesequence': 115822, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.9258677512407, + 'timestamp_carla': 976924, + 'timestamp_device': 1847524, + 'timestamp_stream': 976.9258677512407, + 'transform': [array([-58.09801102, 88.90328979, -0.32435679]), + array([ 3.02281618, -178.39933777, 1.46469498])]} +{'AngularVelocity': array([-0.00654651, -0.00191712, -0.02391818]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.012706303037703037, + 'FR_Wheel_Angle': -0.013763712719082832, + 'Location': array([ 5.95339622e+01, -1.47278702e+02, 4.04266529e-02]), + 'Rotation': array([ 5.48464153e-03, -1.70586655e+02, -8.54492071e-04]), + 'Velocity': array([-1.35829391e+01, -2.26135898e+00, 3.22055821e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5333.943359375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5791.54492188, 15557.92773438, 259.85559082]), + 'frame': 28771, + 'frame_number': 28771, + 'framesequence': 115826, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24004030227661133, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.9601783491671, + 'timestamp_carla': 976959, + 'timestamp_device': 1847558, + 'timestamp_stream': 976.9601783491671, + 'transform': [array([-58.11578369, 88.8885498 , -0.32450393]), + array([ 3.02403188, -178.48750305, 1.46550465])]} +{'AngularVelocity': array([-0.001706 , -0.00176874, -0.0604519 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.013767274096608162, + 'FR_Wheel_Angle': -0.013765904121100903, + 'Location': array([ 5.68250732e+01, -1.47729446e+02, 4.04317640e-02]), + 'Rotation': array([ 5.21826418e-03, -1.70596420e+02, -1.55639602e-03]), + 'Velocity': array([-1.35670748e+01, -2.25582027e+00, 8.87870738e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5340.98828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5783.40820312, 15563.5 , 260.0201416 ]), + 'frame': 28772, + 'frame_number': 28772, + 'framesequence': 115830, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.24229256808757782, + 'throttle_input': 0.2222171425819397, + 'timestamp': 976.9948572516441, + 'timestamp_carla': 976993, + 'timestamp_device': 1847591, + 'timestamp_stream': 976.9948572516441, + 'transform': [array([-58.13223648, 88.87380981, -0.32450143]), + array([ 3.02498126, -178.56987 , 1.4656353 ])]} +{'AngularVelocity': array([-0.00049725, -0.00101322, -0.06255671]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.01376962848007679, + 'FR_Wheel_Angle': -0.013768322765827179, + 'Location': array([ 5.45501060e+01, -1.48107559e+02, 4.04336341e-02]), + 'Rotation': array([ 5.04750945e-03, -1.70606674e+02, -1.77001941e-03]), + 'Velocity': array([-1.35518990e+01, -2.25086451e+00, 2.22206108e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5348.4970703125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5775.09521484, 15569.47851562, 260.28671265]), + 'frame': 28773, + 'frame_number': 28773, + 'framesequence': 115834, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.25703302025794983, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.0267424508929, + 'timestamp_carla': 977025, + 'timestamp_device': 1847624, + 'timestamp_stream': 977.0267424508929, + 'transform': [array([-58.15282059, 88.85941315, -0.32385078]), + array([ 3.02242684, -178.67016602, 1.46271133])]} +{'AngularVelocity': array([ 0.53141516, 0.30498949, -0.28888208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.08369646221399307, + 'FR_Wheel_Angle': -0.14389288425445557, + 'Location': array([ 5.23064041e+01, -1.48479782e+02, 4.04962711e-02]), + 'Rotation': array([ 8.57188739e-03, -1.70627411e+02, 9.74814687e-03]), + 'Velocity': array([-1.35318012e+01, -2.23928070e+00, 4.90264408e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5355.46923828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5767.29394531, 15574.91210938, 260.47613525]), + 'frame': 28774, + 'frame_number': 28774, + 'framesequence': 115838, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.27950072288513184, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.0602861493826, + 'timestamp_carla': 977059, + 'timestamp_device': 1847658, + 'timestamp_stream': 977.0602861493826, + 'transform': [array([-58.17479324, 88.8441391 , -0.32353386]), + array([ 3.02114272, -178.77787781, 1.4612596 ])]} +{'AngularVelocity': array([ 0.17756009, 0.02355601, -3.69590044]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.8263477087020874, + 'FR_Wheel_Angle': -2.334472894668579, + 'Location': array([ 5.00521584e+01, -1.48847641e+02, 4.04289439e-02]), + 'Rotation': array([ 3.40826414e-03, -1.70879364e+02, 1.21948412e-02]), + 'Velocity': array([-1.35129070e+01, -2.12240243e+00, -5.17272929e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5361.12158203125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5757.80078125, 15579.04589844, 260.35415649]), + 'frame': 28775, + 'frame_number': 28775, + 'framesequence': 115842, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30456864833831787, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.0930742509663, + 'timestamp_carla': 977092, + 'timestamp_device': 1847691, + 'timestamp_stream': 977.0930742509663, + 'transform': [array([-58.19581223, 88.82981873, -0.32360053]), + array([ 3.02226973, -178.8815155 , 1.46171951])]} +{'AngularVelocity': array([ 0.48844719, 0.04911161, -16.80258942]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.844238758087158, + 'FR_Wheel_Angle': -6.388179779052734, + 'Location': array([ 4.73435669e+01, -1.49228973e+02, 4.04305458e-02]), + 'Rotation': array([ 2.56132078e-03, -1.72881134e+02, 8.30676407e-02]), + 'Velocity': array([-1.35148554e+01, -1.49132824e+00, -4.85420205e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5364.041015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5747.49121094, 15580.32324219, 260.29632568]), + 'frame': 28776, + 'frame_number': 28776, + 'framesequence': 115846, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.32247689366340637, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.127812448889, + 'timestamp_carla': 977126, + 'timestamp_device': 1847724, + 'timestamp_stream': 977.127812448889, + 'transform': [array([-58.21966553, 88.81512451, -0.32375014]), + array([ 3.02321911, -178.99864197, 1.46243203])]} +{'AngularVelocity': array([ 0.37126201, -1.08706999, -34.42041016]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.429694175720215, + 'FR_Wheel_Angle': -9.033391952514648, + 'Location': array([ 4.46568489e+01, -1.49422729e+02, 3.91569696e-02]), + 'Rotation': array([-6.33909851e-02, -1.78187775e+02, 1.88568562e-01]), + 'Velocity': array([-13.41620827, -0.10409001, -0.02555545]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5367.33349609375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5737.53173828, 15582.04296875, 260.42297363]), + 'frame': 28777, + 'frame_number': 28777, + 'framesequence': 115850, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3247841000556946, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.1617639511824, + 'timestamp_carla': 977160, + 'timestamp_device': 1847758, + 'timestamp_stream': 977.1617639511824, + 'transform': [array([-58.24446487, 88.80030823, -0.32359308]), + array([ 3.02388859, -179.12028503, 1.46185815])]} +{'AngularVelocity': array([ 2.40855943e-02, -2.92139268e+00, -4.57785606e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.277247428894043, + 'FR_Wheel_Angle': -11.337328910827637, + 'Location': array([ 4.24328842e+01, -1.49348618e+02, 2.31927298e-02]), + 'Rotation': array([ -0.70586586, 175.18579102, 0.32009563]), + 'Velocity': array([-13.10173321, 1.47430849, -0.11763959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5370.97607421875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5726.27392578, 15584.02929688, 260.58050537]), + 'frame': 28778, + 'frame_number': 28778, + 'framesequence': 115854, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3145664930343628, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.1953738518059, + 'timestamp_carla': 977194, + 'timestamp_device': 1847791, + 'timestamp_stream': 977.1953738518059, + 'transform': [array([-58.26844406, 88.78672028, -0.32375762]), + array([ 3.02416182, -179.23703003, 1.46261132])]} +{'AngularVelocity': array([ 2.26734495, 5.28680706, -53.89575577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.3003568649292, + 'FR_Wheel_Angle': -11.997952461242676, + 'Location': array([ 4.02858772e+01, -1.48990784e+02, 9.30257794e-03]), + 'Rotation': array([ -0.35821608, 166.62918091, 0.49263456]), + 'Velocity': array([-12.46462631, 3.26807213, -0.10408848]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5845.2548828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5721.16308594, 16056.41015625, 272.60943604]), + 'frame': 28779, + 'frame_number': 28779, + 'framesequence': 115858, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30110782384872437, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.2270836494863, + 'timestamp_carla': 977226, + 'timestamp_device': 1847824, + 'timestamp_stream': 977.2270836494863, + 'transform': [array([-58.28913879, 88.77430725, -0.32397026]), + array([ 3.0251317 , -179.33795166, 1.4636929 ])]} +{'AngularVelocity': array([ 0.23228228, -0.15249498, -54.85492706]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.978445053100586, + 'FR_Wheel_Angle': -13.483214378356934, + 'Location': array([ 3.82322731e+01, -1.48312012e+02, -1.12653733e-03]), + 'Rotation': array([1.99851319e-02, 1.57510986e+02, 4.47759330e-01]), + 'Velocity': array([-1.14350481e+01, 5.18491268e+00, 2.89919856e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5852.474609375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5709.01708984, 16062.0390625 , 272.87011719]), + 'frame': 28780, + 'frame_number': 28780, + 'framesequence': 115862, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.2898098826408386, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.2613335512578, + 'timestamp_carla': 977260, + 'timestamp_device': 1847857, + 'timestamp_stream': 977.2613335512578, + 'transform': [array([-58.3119812 , 88.76084137, -0.32395771]), + array([ 3.02519298, -179.44859314, 1.46361113])]} +{'AngularVelocity': array([ 0.12910548, -0.23628879, -61.21259689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.210464477539062, + 'FR_Wheel_Angle': -14.991605758666992, + 'Location': array([ 3.64373512e+01, -1.47358566e+02, 5.06229408e-04]), + 'Rotation': array([-5.06799994e-03, 1.47904785e+02, 4.91067857e-01]), + 'Velocity': array([-1.00535965e+01, 6.88784027e+00, 8.52440856e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5861.8603515625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5698.51855469, 16069.95507812, 273.21932983]), + 'frame': 28781, + 'frame_number': 28781, + 'framesequence': 115866, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.28669700026512146, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.2931280508637, + 'timestamp_carla': 977292, + 'timestamp_device': 1847891, + 'timestamp_stream': 977.2931280508637, + 'transform': [array([-58.3288765 , 88.74768066, -0.32389128]), + array([ 3.0276041 , -179.5327301 , 1.46365547])]} +{'AngularVelocity': array([ 2.73285601e-02, -9.72178429e-02, -6.35668373e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.665756225585938, + 'FR_Wheel_Angle': -15.191169738769531, + 'Location': array([ 3.48504295e+01, -1.46103455e+02, 1.53242110e-03]), + 'Rotation': array([-1.98348686e-02, 1.37248093e+02, 5.18300533e-01]), + 'Velocity': array([-8.30058861e+00, 8.39686298e+00, 3.30710411e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5871.9248046875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5686.99853516, 16078.40429688, 273.46746826]), + 'frame': 28782, + 'frame_number': 28782, + 'framesequence': 115870, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.29129308462142944, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.3273771516979, + 'timestamp_carla': 977326, + 'timestamp_device': 1847924, + 'timestamp_stream': 977.3273771516979, + 'transform': [array([-58.34946823, 88.73455048, -0.32396671]), + array([ 3.02828026, -179.63287354, 1.46400511])]} +{'AngularVelocity': array([-1.47085814e-02, -1.30423121e-02, -6.32738991e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.064603805541992, + 'FR_Wheel_Angle': -15.523895263671875, + 'Location': array([ 3.35937576e+01, -1.44649277e+02, 1.88184739e-03]), + 'Rotation': array([-2.52716988e-02, 1.26724205e+02, 5.24691343e-01]), + 'Velocity': array([-6.37418890e+00, 9.52312088e+00, 1.04393961e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5879.2060546875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5678.14794922, 16084.1484375 , 273.65643311]), + 'frame': 28783, + 'frame_number': 28783, + 'framesequence': 115874, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.2985992133617401, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.3598549515009, + 'timestamp_carla': 977358, + 'timestamp_device': 1847957, + 'timestamp_stream': 977.3598549515009, + 'transform': [array([-58.37011719, 88.7220459 , -0.32360452]), + array([ 3.02715325, -179.73268127, 1.462376 ])]} +{'AngularVelocity': array([-3.42414379e-02, 5.88681363e-02, -6.29022903e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.421022415161133, + 'FR_Wheel_Angle': -15.710583686828613, + 'Location': array([ 3.26549950e+01, -1.43016647e+02, 1.99319841e-03]), + 'Rotation': array([-2.72183027e-02, 1.16149559e+02, 5.19685507e-01]), + 'Velocity': array([-4.30673742e+00, 1.02676458e+01, 3.19395069e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5887.88525390625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5667.64355469, 16091.2265625 , 273.91177368]), + 'frame': 28784, + 'frame_number': 28784, + 'framesequence': 115878, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3049531579017639, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.3926465511322, + 'timestamp_carla': 977391, + 'timestamp_device': 1847991, + 'timestamp_stream': 977.3926465511322, + 'transform': [array([-58.39291 , 88.70853424, -0.32301894]), + array([ 3.02605367, -179.84291077, 1.45978224])]} +{'AngularVelocity': array([-2.82311980e-02, 1.14015393e-01, -6.16761551e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.185211181640625, + 'FR_Wheel_Angle': -14.98990249633789, + 'Location': array([ 3.20653038e+01, -1.41310425e+02, 2.02165591e-03]), + 'Rotation': array([-2.70953588e-02, 1.05873123e+02, 5.03769994e-01]), + 'Velocity': array([-2.27179146e+00, 1.06097755e+01, 1.03816987e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5898.01904296875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5657.18798828, 16099.81445312, 274.00549316]), + 'frame': 28785, + 'frame_number': 28785, + 'framesequence': 115882, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30639973282814026, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.4265554510057, + 'timestamp_carla': 977425, + 'timestamp_device': 1848024, + 'timestamp_stream': 977.4265554510057, + 'transform': [array([-58.41487122, 88.69462585, -0.32302412]), + array([ 3.02636099, -179.95021057, 1.4598099 ])]} +{'AngularVelocity': array([-7.83211086e-03, 6.44241035e-01, -4.71124268e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.111448287963867, + 'FR_Wheel_Angle': -9.585670471191406, + 'Location': array([ 3.17688084e+01, -1.39199661e+02, 1.99834816e-03]), + 'Rotation': array([-2.16995105e-02, 9.46501236e+01, 4.28399235e-01]), + 'Velocity': array([-3.04919392e-01, 1.06262970e+01, 5.63621506e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5908.16015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5645.59765625, 16108.25585938, 273.99945068]), + 'frame': 28786, + 'frame_number': 28786, + 'framesequence': 115886, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30376294255256653, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.460158251226, + 'timestamp_carla': 977459, + 'timestamp_device': 1848057, + 'timestamp_stream': 977.460158251226, + 'transform': [array([-58.43631363, 88.68154907, -0.32328266]), + array([ 3.02715325, 179.94552612, 1.46098733])]} +{'AngularVelocity': array([ 0.05977891, 1.0390811 , -20.32058144]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.68227481842041, + 'FR_Wheel_Angle': -2.1021511554718018, + 'Location': array([ 3.17555771e+01, -1.37446945e+02, 1.95238111e-03]), + 'Rotation': array([-1.34896226e-02, 8.90894928e+01, 2.77203262e-01]), + 'Velocity': array([3.66853297e-01, 1.05188398e+01, 5.39302819e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5913.48291015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5634.23925781, 16111.81152344, 274.13671875]), + 'frame': 28787, + 'frame_number': 28787, + 'framesequence': 115890, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.2997894287109375, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.4945797510445, + 'timestamp_carla': 977493, + 'timestamp_device': 1848091, + 'timestamp_stream': 977.4945797510445, + 'transform': [array([-58.45846558, 88.66804504, -0.3229394 ]), + array([ 3.02727628, 179.83876038, 1.459517 ])]} +{'AngularVelocity': array([0.05066764, 0.66263777, 0.08123725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5340839624404907, + 'FR_Wheel_Angle': 0.5359023213386536, + 'Location': array([ 3.18067760e+01, -1.35712326e+02, 1.92068098e-03]), + 'Rotation': array([-7.80690601e-03, 8.78651581e+01, 1.12312146e-01]), + 'Velocity': array([3.32344592e-01, 1.03995008e+01, 1.95407865e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5918.9541015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5623.18017578, 16115.57617188, 274.39581299]), + 'frame': 28788, + 'frame_number': 28788, + 'framesequence': 115894, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.2969329059123993, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.5274154506624, + 'timestamp_carla': 977526, + 'timestamp_device': 1848124, + 'timestamp_stream': 977.5274154506624, + 'transform': [array([-58.4785347 , 88.65480042, -0.32286429]), + array([ 3.02761102, 179.74079895, 1.45927107])]} +{'AngularVelocity': array([0.01824766, 0.26330832, 2.1678493 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7477594614028931, + 'FR_Wheel_Angle': 0.8050855994224548, + 'Location': array([ 3.18712158e+01, -1.33641846e+02, 1.90275186e-03]), + 'Rotation': array([-4.76064160e-03, 8.81536636e+01, 3.14150117e-02]), + 'Velocity': array([ 2.86948979e-01, 1.02514915e+01, -3.25202927e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7782.0654296875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5604.15039062, 17976.30273438, 321.63235474]), + 'frame': 28789, + 'frame_number': 28789, + 'framesequence': 115900, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.29751884937286377, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.5706396512687, + 'timestamp_carla': 977569, + 'timestamp_device': 1848174, + 'timestamp_stream': 977.5706396512687, + 'transform': [array([-58.50647354, 88.63814545, -0.32320991]), + array([ 3.02810264, 179.60583496, 1.46074927])]} +{'AngularVelocity': array([0.00669947, 0.09933571, 2.88148999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7629515528678894, + 'FR_Wheel_Angle': 0.681800901889801, + 'Location': array([ 3.19205780e+01, -1.31611633e+02, 1.89466472e-03]), + 'Rotation': array([-3.51071707e-03, 8.86704102e+01, -3.69262672e-03]), + 'Velocity': array([ 1.84278965e-01, 1.01146603e+01, -3.58104694e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7782.76953125, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5590.58300781, 17975.2578125 , 321.61746216]), + 'frame': 28790, + 'frame_number': 28790, + 'framesequence': 115904, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.29977113008499146, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.6044111512601, + 'timestamp_carla': 977603, + 'timestamp_device': 1848207, + 'timestamp_stream': 977.6044111512601, + 'transform': [array([-58.52841187, 88.62501526, -0.32326853]), + array([ 3.02904534, 179.50009155, 1.4611131 ])]} +{'AngularVelocity': array([0.00221272, 0.02323589, 2.16720963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.6006278991699219, + 'FR_Wheel_Angle': 0.6108976006507874, + 'Location': array([ 3.19524193e+01, -1.29599365e+02, 1.89016340e-03]), + 'Rotation': array([-2.80720764e-03, 8.91445694e+01, -1.23901358e-02]), + 'Velocity': array([ 1.11313112e-01, 9.98328209e+00, -2.91824335e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7783.47705078125, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5571.89550781, 17973.65820312, 321.83380127]), + 'frame': 28791, + 'frame_number': 28791, + 'framesequence': 115907, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3014374375343323, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.6374886520207, + 'timestamp_carla': 977636, + 'timestamp_device': 1848232, + 'timestamp_stream': 977.6374886520207, + 'transform': [array([-58.54912949, 88.61238861, -0.32345936]), + array([ 3.02996063, 179.40005493, 1.46205163])]} +{'AngularVelocity': array([0.00727015, 0.00835049, 2.13408685]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.6077384352684021, + 'FR_Wheel_Angle': 0.6114314198493958, + 'Location': array([ 3.19676342e+01, -1.27936157e+02, 1.88379281e-03]), + 'Rotation': array([-1.76901894e-03, 8.94854431e+01, -1.50756845e-02]), + 'Velocity': array([ 5.04470430e-02, 9.89443016e+00, -8.77380330e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7784.14208984375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5557.26123047, 17972.47851562, 321.89907837]), + 'frame': 28792, + 'frame_number': 28792, + 'framesequence': 115912, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30110782384872437, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.6708563491702, + 'timestamp_carla': 977669, + 'timestamp_device': 1848274, + 'timestamp_stream': 977.6708563491702, + 'transform': [array([-58.57001495, 88.59963989, -0.32366711]), + array([ 3.03041124, 179.29898071, 1.46298885])]} +{'AngularVelocity': array([ 0.00893565, -0.00594873, 1.98459566]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5437314510345459, + 'FR_Wheel_Angle': 0.5024909973144531, + 'Location': array([ 3.19729404e+01, -1.26285072e+02, 1.87486643e-03]), + 'Rotation': array([-2.45886797e-04, 8.98184586e+01, -1.55639676e-02]), + 'Velocity': array([-5.26829390e-03, 9.83027840e+00, -7.62939408e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7784.76806640625, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5543.40820312, 17971.30664062, 322.04153442]), + 'frame': 28793, + 'frame_number': 28793, + 'framesequence': 115916, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.2999359369277954, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.7054728493094, + 'timestamp_carla': 977704, + 'timestamp_device': 1848307, + 'timestamp_stream': 977.7054728493094, + 'transform': [array([-58.59105301, 88.58640289, -0.32382467]), + array([ 3.03084159, 179.19708252, 1.4636668 ])]} +{'AngularVelocity': array([ 0.00500601, -0.02294842, 1.34267294]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.31499946117401123, + 'FR_Wheel_Angle': 0.24196244776248932, + 'Location': array([ 3.19704266e+01, -1.24657135e+02, 1.86540594e-03]), + 'Rotation': array([ 1.36603776e-03, 9.00769882e+01, -1.27563477e-02]), + 'Velocity': array([-3.80644649e-02, 9.78616524e+00, -2.95639040e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7785.4287109375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5529.40869141, 17970.12109375, 322.18475342]), + 'frame': 28794, + 'frame_number': 28794, + 'framesequence': 115920, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.2990936040878296, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.7380157522857, + 'timestamp_carla': 977737, + 'timestamp_device': 1848341, + 'timestamp_stream': 977.7380157522857, + 'transform': [array([-58.61265564, 88.5742569 , -0.32379851]), + array([ 3.02989221, 179.09370422, 1.46349442])]} +{'AngularVelocity': array([ 0.00455511, -0.02857926, 0.29535934]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.004420323297381401, + 'FR_Wheel_Angle': 0.004420881625264883, + 'Location': array([ 3.19644718e+01, -1.23040878e+02, 1.85827247e-03]), + 'Rotation': array([ 2.58864160e-03, 9.01834106e+01, -7.01904297e-03]), + 'Velocity': array([-3.86756323e-02, 9.75537872e+00, 1.50680535e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7786.181640625, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5515.28466797, 17968.94726562, 322.29425049]), + 'frame': 28795, + 'frame_number': 28795, + 'framesequence': 115924, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.29958799481391907, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.7710765488446, + 'timestamp_carla': 977770, + 'timestamp_device': 1848374, + 'timestamp_stream': 977.7710765488446, + 'transform': [array([-58.63237 , 88.56153107, -0.32384303]), + array([ 3.0307529 , 178.99810791, 1.46379006])]} +{'AngularVelocity': array([ 0.00027446, -0.00863363, 0.15588538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011054270900785923, + 'FR_Wheel_Angle': 0.009950236417353153, + 'Location': array([ 3.19579811e+01, -1.21406395e+02, 1.85510633e-03]), + 'Rotation': array([ 3.12822638e-03, 9.01957550e+01, -4.48608398e-03]), + 'Velocity': array([-4.00368161e-02, 9.72311974e+00, 2.86102289e-08]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7786.9208984375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5501.00537109, 17967.83984375, 322.29190063]), + 'frame': 28796, + 'frame_number': 28796, + 'framesequence': 115928, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30017396807670593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.8049505501986, + 'timestamp_carla': 977803, + 'timestamp_device': 1848407, + 'timestamp_stream': 977.8049505501986, + 'transform': [array([-58.65478897, 88.54841614, -0.32374176]), + array([ 3.02980351, 178.89067078, 1.46323466])]} +{'AngularVelocity': array([ 0.00197798, -0.00515221, 0.09673364]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.019906457513570786, + 'FR_Wheel_Angle': -0.021009042859077454, + 'Location': array([ 3.19499969e+01, -1.19482925e+02, 1.85270305e-03]), + 'Rotation': array([ 3.52437748e-03, 9.02010269e+01, -3.23486305e-03]), + 'Velocity': array([-4.04503904e-02, 9.69308662e+00, 9.87052886e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7787.740234375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5487.75390625, 17966.76953125, 322.35205078]), + 'frame': 28797, + 'frame_number': 28797, + 'framesequence': 115932, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30017396807670593, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.8380114510655, + 'timestamp_carla': 977837, + 'timestamp_device': 1848441, + 'timestamp_stream': 977.8380114510655, + 'transform': [array([-58.67589188, 88.53601074, -0.32378653]), + array([ 3.02968049, 178.78944397, 1.46342564])]} +{'AngularVelocity': array([0.02977003, 0.00422548, 0.14059904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02652784250676632, + 'FR_Wheel_Angle': 0.03205563500523567, + 'Location': array([ 3.19420815e+01, -1.17536133e+02, 1.83835975e-03]), + 'Rotation': array([ 5.96958492e-03, 9.01945114e+01, -2.68554641e-03]), + 'Velocity': array([-4.00748476e-02, 9.72025490e+00, 9.53674316e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7788.64794921875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5472.90429688, 17965.6484375 , 322.30065918]), + 'frame': 28798, + 'frame_number': 28798, + 'framesequence': 115936, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.8715053498745, + 'timestamp_carla': 977870, + 'timestamp_device': 1848474, + 'timestamp_stream': 977.8715053498745, + 'transform': [array([-58.70005798, 88.52375031, -0.32366481]), + array([ 3.02791142, 178.67497253, 1.46270537])]} +{'AngularVelocity': array([0.04698298, 0.00596331, 0.32420111]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.08382932841777802, + 'FR_Wheel_Angle': 0.11364751309156418, + 'Location': array([ 3.19349461e+01, -1.15913536e+02, 1.80109020e-03]), + 'Rotation': array([ 1.23284906e-02, 9.02163467e+01, -3.57055571e-03]), + 'Velocity': array([-4.79958579e-02, 9.87368298e+00, -9.82284519e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7789.47607421875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5458.89941406, 17964.52734375, 322.34820557]), + 'frame': 28799, + 'frame_number': 28799, + 'framesequence': 115940, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.9094800502062, + 'timestamp_carla': 977908, + 'timestamp_device': 1848507, + 'timestamp_stream': 977.9094800502062, + 'transform': [array([-58.72702408, 88.50899506, -0.32372978]), + array([ 3.02757692, 178.54612732, 1.46277332])]} +{'AngularVelocity': array([0.05096404, 0.02792513, 1.07330787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.34229570627212524, + 'FR_Wheel_Angle': 0.3981941342353821, + 'Location': array([ 3.19252377e+01, -1.14239777e+02, 1.75161357e-03]), + 'Rotation': array([ 2.07569432e-02, 9.03077087e+01, -6.92749023e-03]), + 'Velocity': array([-7.84157068e-02, 1.01530085e+01, 2.76565544e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7790.353515625, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5443.11083984, 17963.34765625, 322.27490234]), + 'frame': 28800, + 'frame_number': 28800, + 'framesequence': 115944, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.942882951349, + 'timestamp_carla': 977941, + 'timestamp_device': 1848541, + 'timestamp_stream': 977.942882951349, + 'transform': [array([-58.74967194, 88.49659729, -0.32366508]), + array([ 3.02761102, 178.43852234, 1.46258187])]} +{'AngularVelocity': array([0.03972547, 0.0501832 , 2.28070736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7089473605155945, + 'FR_Wheel_Angle': 0.8458143472671509, + 'Location': array([ 3.19082260e+01, -1.12507637e+02, 1.70675269e-03]), + 'Rotation': array([ 2.83930954e-02, 9.05598679e+01, -1.33056622e-02]), + 'Velocity': array([-1.46485656e-01, 1.05211630e+01, -8.86917121e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7791.4052734375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5425.29150391, 17961.93945312, 322.30731201]), + 'frame': 28801, + 'frame_number': 28801, + 'framesequence': 115948, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 977.9760792516172, + 'timestamp_carla': 977975, + 'timestamp_device': 1848574, + 'timestamp_stream': 977.9760792516172, + 'transform': [array([-58.77040482, 88.48400879, -0.3236402 ]), + array([ 3.02836919, 178.33917236, 1.46261704])]} +{'AngularVelocity': array([0.03313989, 0.09882936, 4.72252369]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.4433157444000244, + 'FR_Wheel_Angle': 1.5898746252059937, + 'Location': array([ 3.18752995e+01, -1.10726990e+02, 1.66997907e-03]), + 'Rotation': array([ 3.46632078e-02, 9.11155014e+01, -2.69775372e-02]), + 'Velocity': array([-2.97237456e-01, 1.09541693e+01, -2.95639040e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7792.3427734375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5410.421875 , 17960.78125 , 322.30712891]), + 'frame': 28802, + 'frame_number': 28802, + 'framesequence': 115952, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.0066254511476, + 'timestamp_carla': 978005, + 'timestamp_device': 1848607, + 'timestamp_stream': 978.0066254511476, + 'transform': [array([-58.79107285, 88.47226715, -0.32353476]), + array([ 3.02788424, 178.2406311 , 1.46221972])]} +{'AngularVelocity': array([0.02072396, 0.06471257, 6.48475552]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.7245426177978516, + 'FR_Wheel_Angle': 1.7606149911880493, + 'Location': array([ 3.18125992e+01, -1.08866219e+02, 1.64113997e-03]), + 'Rotation': array([ 3.95467915e-02, 9.20787430e+01, -4.17175218e-02]), + 'Velocity': array([-5.17263651e-01, 1.14320288e+01, -1.25885003e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7793.3310546875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5396.65966797, 17959.69140625, 322.3374939 ]), + 'frame': 28803, + 'frame_number': 28803, + 'framesequence': 115956, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.0385379493237, + 'timestamp_carla': 978037, + 'timestamp_device': 1848641, + 'timestamp_stream': 978.0385379493237, + 'transform': [array([-58.81278992, 88.46046448, -0.32355163]), + array([ 3.02709198, 178.13763428, 1.46222508])]} +{'AngularVelocity': array([3.13776638e-03, 1.29438311e-01, 8.50298691e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.4801137447357178, + 'FR_Wheel_Angle': 2.6816930770874023, + 'Location': array([ 3.17090740e+01, -1.06905121e+02, 1.62565231e-03]), + 'Rotation': array([ 4.21627536e-02, 9.32973328e+01, -5.65795824e-02]), + 'Velocity': array([-8.10342550e-01, 1.19178314e+01, -2.48908987e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7794.29833984375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5383.03417969, 17958.64648438, 322.31137085]), + 'frame': 28804, + 'frame_number': 28804, + 'framesequence': 115960, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.0706258490682, + 'timestamp_carla': 978069, + 'timestamp_device': 1848674, + 'timestamp_stream': 978.0706258490682, + 'transform': [array([-58.83384705, 88.4489212 , -0.32369497]), + array([ 3.02705765, 178.03781128, 1.462834 ])]} +{'AngularVelocity': array([-4.45000455e-03, 1.25911549e-01, 1.16225624e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.9128289222717285, + 'FR_Wheel_Angle': 3.382045030593872, + 'Location': array([ 3.15095177e+01, -1.04474815e+02, 1.61592476e-03]), + 'Rotation': array([ 4.38361503e-02, 9.53481827e+01, -8.13903809e-02]), + 'Velocity': array([-1.31299996e+00, 1.24861717e+01, -1.68800352e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7795.263671875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5368.80322266, 17957.52539062, 322.33728027]), + 'frame': 28805, + 'frame_number': 28805, + 'framesequence': 115963, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.1026848517358, + 'timestamp_carla': 978101, + 'timestamp_device': 1848699, + 'timestamp_stream': 978.1026848517358, + 'transform': [array([-58.85443115, 88.43772888, -0.32387775]), + array([ 3.02718067, 177.94026184, 1.46362042])]} +{'AngularVelocity': array([-0.06363557, 0.46363562, 21.80389595]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.942953586578369, + 'FR_Wheel_Angle': 7.071563720703125, + 'Location': array([ 3.12458973e+01, -1.02358795e+02, 1.61211006e-03]), + 'Rotation': array([ 4.44986783e-02, 9.80273743e+01, -1.35406494e-01]), + 'Velocity': array([-2.08924317e+00, 1.28997307e+01, -6.21795652e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7796.18505859375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5354.99365234, 17956.37890625, 322.44424438]), + 'frame': 28806, + 'frame_number': 28806, + 'framesequence': 115968, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.1390685513616, + 'timestamp_carla': 978138, + 'timestamp_device': 1848741, + 'timestamp_stream': 978.1390685513616, + 'transform': [array([-58.87734222, 88.42515564, -0.32409808]), + array([ 3.02748108, 177.83164978, 1.46443439])]} +{'AngularVelocity': array([-0.14385608, 0.57759094, 36.19984055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.434793472290039, + 'FR_Wheel_Angle': 11.372295379638672, + 'Location': array([ 3.08163471e+01, -1.00172295e+02, 1.61634444e-03]), + 'Rotation': array([ 4.34263386e-02, 1.02980064e+02, -2.29644760e-01]), + 'Velocity': array([-3.38691998e+00, 1.31232653e+01, -4.49466679e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7797.0859375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5341.50048828, 17955.2421875 , 322.5736084 ]), + 'frame': 28807, + 'frame_number': 28807, + 'framesequence': 115971, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.1701553501189, + 'timestamp_carla': 978169, + 'timestamp_device': 1848766, + 'timestamp_stream': 978.1701553501189, + 'transform': [array([-58.89608383, 88.41424561, -0.32414198]), + array([ 3.02806187, 177.74235535, 1.46477056])]} +{'AngularVelocity': array([-0.36065534, 0.70802802, 56.37822723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.576062202453613, + 'FR_Wheel_Angle': 16.18122100830078, + 'Location': array([ 2.99646835e+01, -9.75478516e+01, 1.65559771e-03]), + 'Rotation': array([ 3.62204909e-02, 1.12319748e+02, -3.79608095e-01]), + 'Velocity': array([-5.64616013e+00, 1.27630787e+01, -5.88226321e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7798.14013671875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5326.47070312, 17953.984375 , 322.70684814]), + 'frame': 28808, + 'frame_number': 28808, + 'framesequence': 115976, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.2071138508618, + 'timestamp_carla': 978206, + 'timestamp_device': 1848807, + 'timestamp_stream': 978.2071138508618, + 'transform': [array([-58.91899872, 88.40229034, -0.3243618 ]), + array([ 3.02763152, 177.63424683, 1.46550918])]} +{'AngularVelocity': array([-0.45815384, 0.47437 , 70.31427002]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.199565887451172, + 'FR_Wheel_Angle': 18.18616485595703, + 'Location': array([ 2.86372166e+01, -9.51041641e+01, 1.76668167e-03]), + 'Rotation': array([ 1.67544540e-02, 1.25182625e+02, -5.26397645e-01]), + 'Velocity': array([-8.20511627e+00, 1.12565374e+01, -5.27954107e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7799.1103515625, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5314.09960938, 17952.97460938, 322.77850342]), + 'frame': 28809, + 'frame_number': 28809, + 'framesequence': 115980, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.2404571510851, + 'timestamp_carla': 978239, + 'timestamp_device': 1848841, + 'timestamp_stream': 978.2404571510851, + 'transform': [array([-58.93717575, 88.39058685, -0.32427573]), + array([ 3.02873111, 177.5471344 , 1.46531868])]} +{'AngularVelocity': array([-0.4512217 , 0.29167455, 78.32068634]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.996885299682617, + 'FR_Wheel_Angle': 20.655776977539062, + 'Location': array([ 2.70218258e+01, -9.32379456e+01, 1.86429976e-03]), + 'Rotation': array([-1.84415097e-04, 1.38568390e+02, -6.33178711e-01]), + 'Velocity': array([-1.03053570e+01, 8.96257305e+00, -4.57382193e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7800.16552734375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5299.15234375, 17951.72851562, 322.90246582]), + 'frame': 28810, + 'frame_number': 28810, + 'framesequence': 115984, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.2710389494896, + 'timestamp_carla': 978270, + 'timestamp_device': 1848874, + 'timestamp_stream': 978.2710389494896, + 'transform': [array([-58.95583344, 88.38079834, -0.32422286]), + array([ 3.02763152, 177.45924377, 1.46507812])]} +{'AngularVelocity': array([-0.37881905, 0.13032736, 84.24329376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.82257652282715, + 'FR_Wheel_Angle': 23.296878814697266, + 'Location': array([ 2.52011452e+01, -9.19113388e+01, 1.93529122e-03]), + 'Rotation': array([-1.25470571e-02, 1.52264496e+02, -7.11700320e-01]), + 'Velocity': array([-1.17676525e+01, 6.12736416e+00, -4.14276110e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7801.30859375, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5287.06103516, 17950.78515625, 322.90588379]), + 'frame': 28811, + 'frame_number': 28811, + 'framesequence': 115988, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.3046115525067, + 'timestamp_carla': 978303, + 'timestamp_device': 1848907, + 'timestamp_stream': 978.3046115525067, + 'transform': [array([-58.97451019, 88.36956787, -0.32420081]), + array([ 3.02836919, 177.37033081, 1.46504462])]} +{'AngularVelocity': array([-1.88325956e-01, 2.97971000e-03, 8.87532654e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.97650718688965, + 'FR_Wheel_Angle': 22.344282150268555, + 'Location': array([ 2.28043289e+01, -9.09987106e+01, 1.99308386e-03]), + 'Rotation': array([-2.30450574e-02, 1.69542603e+02, -7.73834109e-01]), + 'Velocity': array([-1.25232296e+01, 2.23600149e+00, -4.97293477e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7802.2841796875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5274.91650391, 17949.84375 , 322.90188599]), + 'frame': 28812, + 'frame_number': 28812, + 'framesequence': 115991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.3381358496845, + 'timestamp_carla': 978337, + 'timestamp_device': 1848932, + 'timestamp_stream': 978.3381358496845, + 'transform': [array([-58.99570847, 88.35844421, -0.32397482]), + array([ 3.02718067, 177.27076721, 1.46394217])]} +{'AngularVelocity': array([3.29261541e-01, 7.67577738e-02, 7.86589355e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.247278213500977, + 'FR_Wheel_Angle': 16.477338790893555, + 'Location': array([ 2.03209095e+01, -9.08487549e+01, 1.98110566e-03]), + 'Rotation': array([-2.16107182e-02, -1.73436218e+02, -7.59582460e-01]), + 'Velocity': array([-1.22741766e+01, -1.46022987e+00, 3.37600704e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7803.4072265625, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5262.58691406, 17948.8671875 , 322.92468262]), + 'frame': 28813, + 'frame_number': 28813, + 'framesequence': 115995, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.3703393489122, + 'timestamp_carla': 978369, + 'timestamp_device': 1848966, + 'timestamp_stream': 978.3703393489122, + 'transform': [array([-59.01915359, 88.34690857, -0.32325274]), + array([ 3.02535701, 177.16107178, 1.46071136])]} +{'AngularVelocity': array([ 0.81858003, 0.32575586, 54.09189224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.364004135131836, + 'FR_Wheel_Angle': 8.736870765686035, + 'Location': array([ 1.83440056e+01, -9.12277145e+01, 1.92094804e-03]), + 'Rotation': array([-1.16249816e-02, -1.62529129e+02, -6.53076231e-01]), + 'Velocity': array([-1.17481060e+01, -3.68339753e+00, 7.91072816e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7804.64013671875, + 'focus_actor_name': 'Town05_WallNode_my0024_520', + 'focus_actor_pt': array([-5248.82617188, 17947.875 , 322.80773926]), + 'frame': 28814, + 'frame_number': 28814, + 'framesequence': 116000, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.4038578495383, + 'timestamp_carla': 978402, + 'timestamp_device': 1849007, + 'timestamp_stream': 978.4038578495383, + 'transform': [array([-59.04224396, 88.33385468, -0.32298815]), + array([ 3.02602625, 177.05189514, 1.45964551])]} +{'AngularVelocity': array([ 1.12702405, 0.55383062, 23.36249733]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.8076457977294922, + 'FR_Wheel_Angle': -0.18876227736473083, + 'Location': array([ 1.63902130e+01, -9.19358368e+01, 1.85899728e-03]), + 'Rotation': array([-7.03509431e-04, -1.56215881e+02, -4.59289581e-01]), + 'Velocity': array([-1.13622627e+01, -4.92616606e+00, 9.32598123e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4420.39990234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5405.87451172, 14566.72070312, 236.22357178]), + 'frame': 28815, + 'frame_number': 28815, + 'framesequence': 116004, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.4377963505685, + 'timestamp_carla': 978436, + 'timestamp_device': 1849041, + 'timestamp_stream': 978.4377963505685, + 'transform': [array([-59.0662384 , 88.32104492, -0.3229968 ]), + array([ 3.02629948, 176.93910217, 1.45968699])]} +{'AngularVelocity': array([ 1.09938204, 0.5312131 , -9.60117054]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.3548567295074463, + 'FR_Wheel_Angle': -3.333577871322632, + 'Location': array([ 1.41112976e+01, -9.29380951e+01, 1.81642524e-03]), + 'Rotation': array([ 7.20584905e-03, -1.55443466e+02, -1.63391128e-01]), + 'Velocity': array([-1.14389744e+01, -4.96473837e+00, 4.36306000e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4415.27587890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5397.53320312, 14559.34863281, 236.01034546]), + 'frame': 28816, + 'frame_number': 28816, + 'framesequence': 116008, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3000274896621704, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.4727230519056, + 'timestamp_carla': 978471, + 'timestamp_device': 1849074, + 'timestamp_stream': 978.4727230519056, + 'transform': [array([-59.09002686, 88.30807495, -0.3231948 ]), + array([ 3.02705765, 176.82713318, 1.4605633 ])]} +{'AngularVelocity': array([ 1.04159522, 0.4104825 , -22.92331886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.378683567047119, + 'FR_Wheel_Angle': -7.5899834632873535, + 'Location': array([ 1.21759434e+01, -9.37439270e+01, 1.80860516e-03]), + 'Rotation': array([ 8.74947198e-03, -1.58052628e+02, 2.12719198e-02]), + 'Velocity': array([-1.17050924e+01, -4.37297487e+00, -3.09944153e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4409.98388671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5388.95117188, 14551.77734375, 235.87802124]), + 'frame': 28817, + 'frame_number': 28817, + 'framesequence': 116012, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.300283819437027, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.50529704988, + 'timestamp_carla': 978504, + 'timestamp_device': 1849107, + 'timestamp_stream': 978.50529704988, + 'transform': [array([-59.11732101, 88.29597473, -0.32291111]), + array([ 3.02461934, 176.7003479 , 1.45913684])]} +{'AngularVelocity': array([ 0.55402458, 0.14568414, -33.05808258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.079922676086426, + 'FR_Wheel_Angle': -6.9672465324401855, + 'Location': array([ 1.02279329e+01, -9.43990326e+01, 1.83069229e-03]), + 'Rotation': array([ 4.97237733e-03, -1.62966125e+02, 1.64316460e-01]), + 'Velocity': array([-1.19864502e+01, -3.29339480e+00, -2.07042685e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4418.439453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5379.66601562, 14557.890625 , 236.15829468]), + 'frame': 28818, + 'frame_number': 28818, + 'framesequence': 116016, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.30782800912857056, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.5381632521749, + 'timestamp_carla': 978537, + 'timestamp_device': 1849141, + 'timestamp_stream': 978.5381632521749, + 'transform': [array([-59.1414299 , 88.28346252, -0.32305592]), + array([ 3.02565742, 176.58724976, 1.4598701 ])]} +{'AngularVelocity': array([-8.22772086e-02, -2.29956545e-02, -2.34622116e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.351090431213379, + 'FR_Wheel_Angle': -3.551050901412964, + 'Location': array([ 7.80277014e+00, -9.49764404e+01, 1.84488297e-03]), + 'Rotation': array([ 2.30177352e-03, -1.68816223e+02, 1.96385354e-01]), + 'Velocity': array([-1.21612167e+01, -2.23242497e+00, -9.34600791e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6745.7021484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5232.7109375 , 16877.9765625 , 295.23168945]), + 'frame': 28819, + 'frame_number': 28819, + 'framesequence': 116019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3272377848625183, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.5694818496704, + 'timestamp_carla': 978568, + 'timestamp_device': 1849166, + 'timestamp_stream': 978.5694818496704, + 'transform': [array([-59.16465378, 88.27205658, -0.32345131]), + array([ 3.02821875, 176.47836304, 1.46179569])]} +{'AngularVelocity': array([-0.3657957 , -0.05191588, -9.03591442]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.487627387046814, + 'FR_Wheel_Angle': -1.2025346755981445, + 'Location': array([ 5.38996935e+00, -9.53747406e+01, 1.84690475e-03]), + 'Rotation': array([ 1.91928307e-03, -1.71929260e+02, 1.36958629e-01]), + 'Velocity': array([-1.21910582e+01, -1.70765042e+00, 9.01222211e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6751.2041015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5218.890625 , 16880.85351562, 295.45648193]), + 'frame': 28820, + 'frame_number': 28820, + 'framesequence': 116024, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3497970402240753, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.6041621491313, + 'timestamp_carla': 978603, + 'timestamp_device': 1849207, + 'timestamp_stream': 978.6041621491313, + 'transform': [array([-59.19275284, 88.25999451, -0.32410106]), + array([ 3.03230333, 176.34672546, 1.46473563])]} +{'AngularVelocity': array([-0.21892665, -0.02658631, -4.7744813 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0858819484710693, + 'FR_Wheel_Angle': -1.0746934413909912, + 'Location': array([ 3.37293053e+00, -9.56438293e+01, 1.84648507e-03]), + 'Rotation': array([ 2.01490568e-03, -1.72933380e+02, 8.74153301e-02]), + 'Velocity': array([-1.21726646e+01, -1.48526120e+00, 5.02586363e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6754.55615234375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5205.67333984, 16881.70898438, 295.76391602]), + 'frame': 28821, + 'frame_number': 28821, + 'framesequence': 116028, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.37416914105415344, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.6375046521425, + 'timestamp_carla': 978636, + 'timestamp_device': 1849241, + 'timestamp_stream': 978.6375046521425, + 'transform': [array([-59.22053528, 88.24889374, -0.3251906 ]), + array([ 3.04029465, 176.21661377, 1.46985579])]} +{'AngularVelocity': array([-0.08446264, -0.00868716, -5.00961876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.3373134136199951, + 'FR_Wheel_Angle': -1.4105356931686401, + 'Location': array([ 1.34127617e+00, -9.58796921e+01, 1.84583664e-03]), + 'Rotation': array([ 2.13784911e-03, -1.73716644e+02, 6.21865205e-02]), + 'Velocity': array([-1.21477404e+01, -1.28707910e+00, 1.62124627e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5210.0615234375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5290.39941406, 15338.10742188, 256.67315674]), + 'frame': 28822, + 'frame_number': 28822, + 'framesequence': 116032, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3860347270965576, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.671261548996, + 'timestamp_carla': 978670, + 'timestamp_device': 1849274, + 'timestamp_stream': 978.671261548996, + 'transform': [array([-59.24986267, 88.23807526, -0.32619876]), + array([ 3.0463531 , 176.0789032 , 1.47439885])]} +{'AngularVelocity': array([ 6.32114038e-02, 4.36596898e-03, -7.67389631e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.2139134407043457, + 'FR_Wheel_Angle': -2.4581258296966553, + 'Location': array([-6.96756423e-01, -9.60800400e+01, 1.84637064e-03]), + 'Rotation': array([ 2.06271699e-03, -1.74754517e+02, 6.11423366e-02]), + 'Velocity': array([-1.21219225e+01, -1.01786613e+00, -1.64985659e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5224.35693359375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5277.36230469, 15349.78027344, 257.48425293]), + 'frame': 28823, + 'frame_number': 28823, + 'framesequence': 116036, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.38076114654541016, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.7056586518884, + 'timestamp_carla': 978704, + 'timestamp_device': 1849307, + 'timestamp_stream': 978.7056586518884, + 'transform': [array([-59.27855301, 88.22748566, -0.32668194]), + array([ 3.04851818, 175.9440918 , 1.47641265])]} +{'AngularVelocity': array([ 1.40763626e-01, 6.87791267e-03, -1.22726107e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.409672260284424, + 'FR_Wheel_Angle': -3.3335440158843994, + 'Location': array([-2.69698119e+00, -9.62230606e+01, 1.84820173e-03]), + 'Rotation': array([ 1.72803772e-03, -1.76440063e+02, 8.25076699e-02]), + 'Velocity': array([-1.20935230e+01, -5.97313821e-01, -3.18527213e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5239.28125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5263.515625 , 15361.98535156, 258.26330566]), + 'frame': 28824, + 'frame_number': 28824, + 'framesequence': 116040, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36832788586616516, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.7387342490256, + 'timestamp_carla': 978737, + 'timestamp_device': 1849340, + 'timestamp_stream': 978.7387342490256, + 'transform': [array([-59.30392456, 88.21781158, -0.32725987]), + array([ 3.0497067 , 175.82475281, 1.47885668])]} +{'AngularVelocity': array([ 1.59349646e-02, 9.94590111e-04, -1.27399607e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.1009902954101562, + 'FR_Wheel_Angle': -2.785768747329712, + 'Location': array([-4.70346165e+00, -9.62953949e+01, 1.84896460e-03]), + 'Rotation': array([ 1.63241511e-03, -1.78592941e+02, 9.55659747e-02]), + 'Velocity': array([-1.20539284e+01, -1.55141935e-01, -3.86238099e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5253.376953125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5249.96337891, 15373.39355469, 258.79949951]), + 'frame': 28825, + 'frame_number': 28825, + 'framesequence': 116044, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.35598623752593994, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.7715047523379, + 'timestamp_carla': 978770, + 'timestamp_device': 1849374, + 'timestamp_stream': 978.7715047523379, + 'transform': [array([-59.32666016, 88.20871735, -0.32777792]), + array([ 3.05131865, 175.7179718 , 1.48116314])]} +{'AngularVelocity': array([-8.60420167e-02, 2.48406525e-03, -9.27456474e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.944799542427063, + 'FR_Wheel_Angle': -1.7361382246017456, + 'Location': array([-6.72272635e+00, -9.63016968e+01, 1.84713362e-03]), + 'Rotation': array([1.90562266e-03, 1.79573990e+02, 8.55878368e-02]), + 'Velocity': array([-1.20066814e+01, 1.76375821e-01, 3.40461725e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5266.1552734375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5237.89208984, 15383.72460938, 259.34753418]), + 'frame': 28826, + 'frame_number': 28826, + 'framesequence': 116048, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.34802088141441345, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.8053580522537, + 'timestamp_carla': 978804, + 'timestamp_device': 1849407, + 'timestamp_stream': 978.8053580522537, + 'transform': [array([-59.34805679, 88.19991302, -0.32825789]), + array([ 3.05268455, 175.61766052, 1.48327255])]} +{'AngularVelocity': array([-0.10703858, 0.01877731, -5.74533987]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.2933450937271118, + 'FR_Wheel_Angle': -1.2214328050613403, + 'Location': array([-9.12402725e+00, -9.62452621e+01, 1.84179307e-03]), + 'Rotation': array([2.84818863e-03, 1.78114578e+02, 6.34512976e-02]), + 'Velocity': array([-1.19642391e+01, 4.43372518e-01, 6.48498542e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5277.73876953125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5227.03564453, 15393.04589844, 259.85391235]), + 'frame': 28827, + 'frame_number': 28827, + 'framesequence': 116052, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3493759036064148, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.8421815522015, + 'timestamp_carla': 978841, + 'timestamp_device': 1849440, + 'timestamp_stream': 978.8421815522015, + 'transform': [array([-59.37011719, 88.1907959 , -0.32856643]), + array([ 3.05351114, 175.514328 , 1.48451817])]} +{'AngularVelocity': array([-0.05238033, 0.05391359, -4.86416101]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.1981462240219116, + 'FR_Wheel_Angle': -1.183935284614563, + 'Location': array([-1.11576014e+01, -9.61590500e+01, 1.80616369e-03]), + 'Rotation': array([8.91339593e-03, 1.77248734e+02, 4.98102345e-02]), + 'Velocity': array([-1.20645990e+01, 6.26870036e-01, 7.34329205e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5288.69287109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5216.79882812, 15401.82421875, 260.32678223]), + 'frame': 28828, + 'frame_number': 28828, + 'framesequence': 116056, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3554551899433136, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.8740126490593, + 'timestamp_carla': 978873, + 'timestamp_device': 1849474, + 'timestamp_stream': 978.8740126490593, + 'transform': [array([-59.39012527, 88.18266296, -0.32822171]), + array([ 3.05189228, 175.42077637, 1.48296297])]} +{'AngularVelocity': array([-0.0316372 , 0.04989489, -4.66658211]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0708147287368774, + 'FR_Wheel_Angle': -1.0233906507492065, + 'Location': array([-1.31709633e+01, -9.60445404e+01, 1.75516121e-03]), + 'Rotation': array([1.76560376e-02, 1.76457413e+02, 4.29270566e-02]), + 'Velocity': array([-1.22929945e+01, 8.04822445e-01, 1.40190116e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5299.798828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5206.24023438, 15410.66699219, 260.72384644]), + 'frame': 28829, + 'frame_number': 28829, + 'framesequence': 116060, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3614429235458374, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.9060519523919, + 'timestamp_carla': 978905, + 'timestamp_device': 1849507, + 'timestamp_stream': 978.9060519523919, + 'transform': [array([-59.40945816, 88.17430115, -0.3277387 ]), + array([ 3.0520494 , 175.33024597, 1.48098016])]} +{'AngularVelocity': array([-0.01761673, 0.03269344, -4.14941406]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.9590320587158203, + 'FR_Wheel_Angle': -0.9116635918617249, + 'Location': array([-1.56480951e+01, -9.58688736e+01, 1.70969008e-03]), + 'Rotation': array([2.53741518e-02, 1.75591675e+02, 3.70054916e-02]), + 'Velocity': array([-1.26452875e+01, 1.00755501e+00, 5.43594354e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5309.20166015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5196.73339844, 15418.02929688, 260.82769775]), + 'frame': 28830, + 'frame_number': 28830, + 'framesequence': 116064, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3655446171760559, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.9390254504979, + 'timestamp_carla': 978938, + 'timestamp_device': 1849540, + 'timestamp_stream': 978.9390254504979, + 'transform': [array([-59.43321609, 88.16571808, -0.32727638]), + array([ 3.04787612, 175.21949768, 1.47855294])]} +{'AngularVelocity': array([-0.01733136, 0.0181216 , -3.60444975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.801792562007904, + 'FR_Wheel_Angle': -0.7897716164588928, + 'Location': array([-1.77811260e+01, -9.56908875e+01, 1.68680190e-03]), + 'Rotation': array([2.92605292e-02, 1.74952042e+02, 3.29233818e-02]), + 'Velocity': array([-1.29720955e+01, 1.16795075e+00, -1.65939332e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5318.27880859375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5187.49902344, 15425.06640625, 260.88024902]), + 'frame': 28831, + 'frame_number': 28831, + 'framesequence': 116068, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36455580592155457, + 'throttle_input': 0.2222171425819397, + 'timestamp': 978.9712947495282, + 'timestamp_carla': 978970, + 'timestamp_device': 1849574, + 'timestamp_stream': 978.9712947495282, + 'transform': [array([-59.4563942 , 88.15699005, -0.32709435]), + array([ 3.04674911, 175.11122131, 1.47767556])]} +{'AngularVelocity': array([-0.00560701, 0.00738201, -3.51819229]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7839220762252808, + 'FR_Wheel_Angle': -0.764859676361084, + 'Location': array([-1.99672203e+01, -9.54858780e+01, 1.67573930e-03]), + 'Rotation': array([3.11320014e-02, 1.74363586e+02, 3.11208609e-02]), + 'Velocity': array([-1.33020411e+01, 1.33223724e+00, 9.15527323e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4656.98974609375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5233.13574219, 14764.0625 , 243.62188721]), + 'frame': 28832, + 'frame_number': 28832, + 'framesequence': 116072, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36184579133987427, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.0060848519206, + 'timestamp_carla': 979005, + 'timestamp_device': 1849607, + 'timestamp_stream': 979.0060848519206, + 'transform': [array([-59.4787178 , 88.14781952, -0.32738131]), + array([ 3.04759598, 175.00640869, 1.47891486])]} +{'AngularVelocity': array([-1.16906990e-03, 1.44613506e-02, -3.42289138e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7416695356369019, + 'FR_Wheel_Angle': -0.7357288002967834, + 'Location': array([-2.22130489e+01, -9.52527390e+01, 1.66822434e-03]), + 'Rotation': array([3.24638858e-02, 1.73787277e+02, 3.01561505e-02]), + 'Velocity': array([-1.36475191e+01, 1.50019288e+00, 1.04904177e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4656.0927734375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5224.30419922, 14760.94824219, 243.52966309]), + 'frame': 28833, + 'frame_number': 28833, + 'framesequence': 116076, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.35834836959838867, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.0379147492349, + 'timestamp_carla': 979036, + 'timestamp_device': 1849640, + 'timestamp_stream': 979.0379147492349, + 'transform': [array([-59.50060272, 88.13969421, -0.32746753]), + array([ 3.0477531 , 174.90437317, 1.47934616])]} +{'AngularVelocity': array([-0.00346333, 0.02826813, -3.32463026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.667868971824646, + 'FR_Wheel_Angle': -0.6556063294410706, + 'Location': array([-2.45352306e+01, -9.49889221e+01, 1.64625165e-03]), + 'Rotation': array([3.61931697e-02, 1.73216156e+02, 2.98070665e-02]), + 'Velocity': array([-1.40669575e+01, 1.68128836e+00, -4.38213328e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4655.86328125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5215.67041016, 14758.46679688, 243.6211853 ]), + 'frame': 28834, + 'frame_number': 28834, + 'framesequence': 116079, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.35750603675842285, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.0706246495247, + 'timestamp_carla': 979069, + 'timestamp_device': 1849665, + 'timestamp_stream': 979.0706246495247, + 'transform': [array([-59.52257156, 88.13149261, -0.32754943]), + array([ 3.04791021, 174.80224609, 1.47970891])]} +{'AngularVelocity': array([-1.14649499e-03, 2.20428947e-02, -3.11056852e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6076070070266724, + 'FR_Wheel_Angle': -0.5723530054092407, + 'Location': array([-2.74160767e+01, -9.46319504e+01, 1.61485665e-03]), + 'Rotation': array([4.15002257e-02, 1.72571960e+02, 2.90462747e-02]), + 'Velocity': array([-1.46453695e+01, 1.90871727e+00, 1.26361840e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4655.38623046875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5207.31542969, 14755.86328125, 243.64460754]), + 'frame': 28835, + 'frame_number': 28835, + 'framesequence': 116084, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.35847651958465576, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.1037103496492, + 'timestamp_carla': 979102, + 'timestamp_device': 1849707, + 'timestamp_stream': 979.1037103496492, + 'transform': [array([-59.54501724, 88.12288666, -0.3273761 ]), + array([ 3.0478487 , 174.69779968, 1.47894955])]} +{'AngularVelocity': array([-0.04715119, 0.02284511, -1.95745182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.23746345937252045, + 'FR_Wheel_Angle': -0.1298651099205017, + 'Location': array([-2.98947601e+01, -9.43021240e+01, 1.59711833e-03]), + 'Rotation': array([4.45396602e-02, 1.72132538e+02, 2.44987141e-02]), + 'Velocity': array([-1.51579609e+01, 2.07380009e+00, -1.11579891e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4654.9189453125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5198.96337891, 14753.2421875 , 243.66166687]), + 'frame': 28836, + 'frame_number': 28836, + 'framesequence': 116088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.35990479588508606, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.1369717493653, + 'timestamp_carla': 979136, + 'timestamp_device': 1849740, + 'timestamp_stream': 979.1369717493653, + 'transform': [array([-59.56803894, 88.11421967, -0.32725349]), + array([ 3.04772592, 174.59082031, 1.47839546])]} +{'AngularVelocity': array([-0.06466259, 0.02267569, -0.04002617]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.09927142411470413, + 'FR_Wheel_Angle': 0.16436432301998138, + 'Location': array([-3.24742470e+01, -9.39470520e+01, 1.58262253e-03]), + 'Rotation': array([4.69985306e-02, 1.71990189e+02, 1.29368277e-02]), + 'Velocity': array([-1.57082806e+01, 2.17762494e+00, 9.05990589e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4648.38525390625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5190.99755859, 14744.5 , 243.43164062]), + 'frame': 28837, + 'frame_number': 28837, + 'framesequence': 116092, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3611316382884979, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.1707082502544, + 'timestamp_carla': 979169, + 'timestamp_device': 1849774, + 'timestamp_stream': 979.1707082502544, + 'transform': [array([-59.59087753, 88.10523987, -0.32733971]), + array([ 3.04860687, 174.48414612, 1.47882748])]} +{'AngularVelocity': array([-0.11576884, 0.02718721, 2.06130457]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5798261165618896, + 'FR_Wheel_Angle': 0.7178615927696228, + 'Location': array([-3.51452179e+01, -9.35787964e+01, 1.57045363e-03]), + 'Rotation': array([ 4.90339249e-02, 1.72148590e+02, -2.68554688e-03]), + 'Velocity': array([-1.62904530e+01, 2.20787430e+00, -3.52859502e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4641.5458984375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5182.88134766, 14735.39453125, 243.2104187 ]), + 'frame': 28838, + 'frame_number': 28838, + 'framesequence': 116096, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36063724756240845, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.2045921497047, + 'timestamp_carla': 979203, + 'timestamp_device': 1849807, + 'timestamp_stream': 979.2045921497047, + 'transform': [array([-59.61571121, 88.09650421, -0.32727697]), + array([ 3.04823804, 174.36891174, 1.47849154])]} +{'AngularVelocity': array([-0.14123571, 0.02542779, 4.92547798]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.0398889780044556, + 'FR_Wheel_Angle': 1.0995944738388062, + 'Location': array([-3.78988533e+01, -9.32158585e+01, 1.56156532e-03]), + 'Rotation': array([ 5.05638868e-02, 1.72753357e+02, -2.60925293e-02]), + 'Velocity': array([-1.68986282e+01, 2.11626363e+00, -1.10149381e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4635.27197265625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5174.74267578, 14726.80078125, 243.08175659]), + 'frame': 28839, + 'frame_number': 28839, + 'framesequence': 116100, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.35957521200180054, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.2366988509893, + 'timestamp_carla': 979235, + 'timestamp_device': 1849840, + 'timestamp_stream': 979.2366988509893, + 'transform': [array([-59.63858795, 88.08798981, -0.32736358]), + array([ 3.04844975, 174.2624054 , 1.47891617])]} +{'AngularVelocity': array([0.03530812, 0.14727725, 6.14144993]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.1569523811340332, + 'FR_Wheel_Angle': 1.169050693511963, + 'Location': array([-4.08137169e+01, -9.28675156e+01, 9.62678902e-03]), + 'Rotation': array([ 4.03957844e-01, 1.73732391e+02, -1.52282715e-02]), + 'Velocity': array([-17.51554489, 1.93049479, 0.02574508]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4628.0791015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5166.04785156, 14717.18554688, 242.86920166]), + 'frame': 28840, + 'frame_number': 28840, + 'framesequence': 116104, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3594287037849426, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.2708353511989, + 'timestamp_carla': 979269, + 'timestamp_device': 1849874, + 'timestamp_stream': 979.2708353511989, + 'transform': [array([-59.66430664, 88.079216 , -0.32734454]), + array([ 3.04821086, 174.14347839, 1.4787581 ])]} +{'AngularVelocity': array([-0.07849035, -0.92679685, 7.13059616]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.06258225440979, + 'FR_Wheel_Angle': 0.9805029630661011, + 'Location': array([-4.37618408e+01, -9.25623932e+01, 1.79372597e-02]), + 'Rotation': array([-4.22378890e-02, 1.74837952e+02, -9.61303432e-03]), + 'Velocity': array([-1.81276245e+01, 1.69036734e+00, 9.01317544e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4621.88330078125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5157.97998047, 14708.6796875 , 242.74414062]), + 'frame': 28841, + 'frame_number': 28841, + 'framesequence': 116108, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3601611256599426, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.3043149523437, + 'timestamp_carla': 979303, + 'timestamp_device': 1849907, + 'timestamp_stream': 979.3043149523437, + 'transform': [array([-59.69165421, 88.0694809 , -0.32714221]), + array([ 3.04692674, 174.01667786, 1.47774434])]} +{'AngularVelocity': array([-1.28344023, 0.93018311, 4.71638012]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3317306637763977, + 'FR_Wheel_Angle': 0.22167056798934937, + 'Location': array([-4.68247948e+01, -9.22979889e+01, 1.47206299e-02]), + 'Rotation': array([ 2.06135102e-02, 1.75847885e+02, -1.81884736e-01]), + 'Velocity': array([-1.87277145e+01, 1.46303773e+00, -1.41183902e-02]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4614.64111328125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5149.05664062, 14698.91796875, 242.54394531]), + 'frame': 28842, + 'frame_number': 28842, + 'framesequence': 116112, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.3602893054485321, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.3364018499851, + 'timestamp_carla': 979335, + 'timestamp_device': 1849940, + 'timestamp_stream': 979.3364018499851, + 'transform': [array([-59.71640015, 88.06040192, -0.32727256]), + array([ 3.04735017, 173.90177917, 1.47837412])]} +{'AngularVelocity': array([ 1.13311183, -0.52862847, 1.12004507]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0351015068590641, + 'FR_Wheel_Angle': 0.03508210554718971, + 'Location': array([-5.06299438e+01, -9.20215607e+01, 1.71183590e-02]), + 'Rotation': array([ 1.69197440e-01, 1.76362549e+02, -2.54333436e-01]), + 'Velocity': array([-19.41990089, 1.31435442, 0.03996977]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4606.62060546875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5139.61572266, 14688.15429688, 242.25733948]), + 'frame': 28843, + 'frame_number': 28843, + 'framesequence': 116115, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.3695821501315, + 'timestamp_carla': 979368, + 'timestamp_device': 1849965, + 'timestamp_stream': 979.3695821501315, + 'transform': [array([-59.74221039, 88.05142212, -0.32748795]), + array([ 3.04747987, 173.78224182, 1.47927725])]} +{'AngularVelocity': array([ 0.10889921, -0.0321793 , 0.37394094]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.03495071083307266, + 'FR_Wheel_Angle': 0.03094085492193699, + 'Location': array([-5.46255836e+01, -9.17622757e+01, 2.47167777e-02]), + 'Rotation': array([ 1.47320345e-01, 1.76488205e+02, -2.06817612e-01]), + 'Velocity': array([-20.10037231, 1.25825763, 0.03525465]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4563.83154296875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5134.89453125, 14643.0390625 , 241.20495605]), + 'frame': 28844, + 'frame_number': 28844, + 'framesequence': 116119, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.4026247523725, + 'timestamp_carla': 979401, + 'timestamp_device': 1849999, + 'timestamp_stream': 979.4026247523725, + 'transform': [array([-59.76694107, 88.04257965, -0.32773909]), + array([ 3.04796481, 173.66767883, 1.48037922])]} +{'AngularVelocity': array([ 0.06727519, -0.01567424, 0.24578074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02884000912308693, + 'FR_Wheel_Angle': 0.028823737055063248, + 'Location': array([-5.79979515e+01, -9.15542984e+01, 3.04968059e-02]), + 'Rotation': array([ 1.44581437e-01, 1.76536621e+02, -1.92352280e-01]), + 'Velocity': array([-20.64239883, 1.2552526 , 0.03473725]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4561.96923828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5125.50048828, 14638.52929688, 241.22824097]), + 'frame': 28845, + 'frame_number': 28845, + 'framesequence': 116124, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.4363152496517, + 'timestamp_carla': 979435, + 'timestamp_device': 1850040, + 'timestamp_stream': 979.4363152496517, + 'transform': [array([-59.79187012, 88.03462982, -0.32794932]), + array([ 3.04704976, 173.55290222, 1.48113012])]} +{'AngularVelocity': array([0.52219784, 2.85554624, 0.30358604]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.028695831075310707, + 'FR_Wheel_Angle': 0.028680697083473206, + 'Location': array([-6.14837685e+01, -9.13434525e+01, 1.73435397e-02]), + 'Rotation': array([-5.71659505e-01, 1.76577835e+02, -6.45141527e-02]), + 'Velocity': array([-21.18219948, 1.26320815, -0.09181804]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4557.93359375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5116.75097656, 14631.91992188, 241.21038818]), + 'frame': 28846, + 'frame_number': 28846, + 'framesequence': 116127, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.470401249826, + 'timestamp_carla': 979469, + 'timestamp_device': 1850065, + 'timestamp_stream': 979.470401249826, + 'transform': [array([-59.81709671, 88.02500153, -0.32744879]), + array([ 3.04661942, 173.43618774, 1.47892046])]} +{'AngularVelocity': array([-0.01645643, 0.02302667, 0.22958869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02857969142496586, + 'FR_Wheel_Angle': 0.028564192354679108, + 'Location': array([-6.57877426e+01, -9.10887299e+01, -1.49045943e-03]), + 'Rotation': array([ 7.24819601e-02, 1.76633698e+02, -3.08227516e-03]), + 'Velocity': array([-2.18097878e+01, 1.27621341e+00, 1.93361274e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4290.66845703125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5137.9375 , 14363.94042969, 234.37136841]), + 'frame': 28847, + 'frame_number': 28847, + 'framesequence': 116132, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.5035897493362, + 'timestamp_carla': 979502, + 'timestamp_device': 1850107, + 'timestamp_stream': 979.5035897493362, + 'transform': [array([-59.84366989, 88.01499176, -0.32693717]), + array([ 3.04564953, 173.31330872, 1.47664177])]} +{'AngularVelocity': array([-0.01082718, -0.07557032, 0.21787612]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02846428193151951, + 'FR_Wheel_Angle': 0.028449390083551407, + 'Location': array([-6.94864807e+01, -9.08734970e+01, 9.00840751e-05]), + 'Rotation': array([ 5.89445308e-02, 1.76670776e+02, -4.94384626e-03]), + 'Velocity': array([-2.23275757e+01, 1.29087782e+00, 8.66989139e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4300.09912109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5128.05712891, 14370.63085938, 234.44906616]), + 'frame': 28848, + 'frame_number': 28848, + 'framesequence': 116136, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.53746625036, + 'timestamp_carla': 979536, + 'timestamp_device': 1850140, + 'timestamp_stream': 979.53746625036, + 'transform': [array([-59.87214279, 88.00505829, -0.32179803]), + array([ 2.96024489, 173.17790222, 1.44201469])]} +{'AngularVelocity': array([-0.00420439, -0.03279711, 0.21820986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.028352616354823112, + 'FR_Wheel_Angle': 0.028337789699435234, + 'Location': array([-7.32096100e+01, -9.06592941e+01, 1.07748026e-03]), + 'Rotation': array([ 5.05912080e-02, 1.76706619e+02, -5.58471633e-03]), + 'Velocity': array([-2.28261909e+01, 1.30507982e+00, 3.41944210e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4305.72216796875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5118.12841797, 14373.38085938, 234.42547607]), + 'frame': 28849, + 'frame_number': 28849, + 'framesequence': 116140, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.5711801499128, + 'timestamp_carla': 979570, + 'timestamp_device': 1850174, + 'timestamp_stream': 979.5711801499128, + 'transform': [array([-59.89894867, 87.99568939, -0.31941134]), + array([ 2.93231606, 173.05387878, 1.42671335])]} +{'AngularVelocity': array([-0.0024357 , -0.0224763 , 0.22093639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.028221603482961655, + 'FR_Wheel_Angle': 0.028208693489432335, + 'Location': array([-7.70824814e+01, -9.04389725e+01, 1.44014356e-03]), + 'Rotation': array([ 4.64726053e-02, 1.76743408e+02, -5.85937547e-03]), + 'Velocity': array([-2.33145218e+01, 1.31813669e+00, 1.11251825e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4299.27783203125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5109.13330078, 14364.16210938, 231.69155884]), + 'frame': 28850, + 'frame_number': 28850, + 'framesequence': 116144, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.6080629490316, + 'timestamp_carla': 979607, + 'timestamp_device': 1850207, + 'timestamp_stream': 979.6080629490316, + 'transform': [array([-59.92822266, 87.98600769, -0.31931698]), + array([ 2.93698812, 172.92007446, 1.42601478])]} +{'AngularVelocity': array([-0.0018086 , -0.01896389, 0.22441977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.028126610442996025, + 'FR_Wheel_Angle': 0.028115715831518173, + 'Location': array([-8.18174973e+01, -9.01728897e+01, 1.57693855e-03]), + 'Rotation': array([ 4.21627536e-02, 1.76788071e+02, -6.04247907e-03]), + 'Velocity': array([-2.38377972e+01, 1.32950020e+00, 2.55689607e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4299.72314453125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5099.9140625 , 14361.8515625 , 230.54290771]), + 'frame': 28851, + 'frame_number': 28851, + 'framesequence': 116148, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.6377496495843, + 'timestamp_carla': 979636, + 'timestamp_device': 1850240, + 'timestamp_stream': 979.6377496495843, + 'transform': [array([-59.94997406, 87.97801208, -0.3202979 ]), + array([ 2.94899559, 172.82017517, 1.43146086])]} +{'AngularVelocity': array([-0.00146697, -0.01363824, 0.2272955 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02803591638803482, + 'FR_Wheel_Angle': 0.02802620269358158, + 'Location': array([-8.58263168e+01, -8.99504547e+01, 1.61645887e-03]), + 'Rotation': array([ 3.95126417e-02, 1.76825699e+02, -6.19506696e-03]), + 'Velocity': array([-2.42430553e+01, 1.33655238e+00, 7.61747360e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7738.5380859375, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4661.76660156, 17769.78710938, 315.93197632]), + 'frame': 28852, + 'frame_number': 28852, + 'framesequence': 116152, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.6726734489202, + 'timestamp_carla': 979671, + 'timestamp_device': 1850274, + 'timestamp_stream': 979.6726734489202, + 'transform': [array([-59.97856903, 87.96917725, -0.32103378]), + array([ 2.96251249, 172.69006348, 1.43664205])]} +{'AngularVelocity': array([-0.00107658, -0.00945748, 0.23041561]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.028889121487736702, + 'FR_Wheel_Angle': 0.03466016799211502, + 'Location': array([-9.04197540e+01, -8.96987076e+01, 1.63663866e-03]), + 'Rotation': array([ 3.73474732e-02, 1.76868607e+02, -6.34765485e-03]), + 'Velocity': array([-2.46764641e+01, 1.34239316e+00, 1.57070153e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7741.73828125, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4647.79199219, 17769.78125 , 316.73016357]), + 'frame': 28853, + 'frame_number': 28853, + 'framesequence': 116156, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.7080718502402, + 'timestamp_carla': 979707, + 'timestamp_device': 1850307, + 'timestamp_stream': 979.7080718502402, + 'transform': [array([-60.00740051, 87.96034241, -0.32184547]), + array([ 2.97518921, 172.55897522, 1.44220495])]} +{'AngularVelocity': array([-0.02265128, -0.00521111, 0.58534741]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.18399599194526672, + 'FR_Wheel_Angle': 0.23986002802848816, + 'Location': array([-9.49519119e+01, -8.94540100e+01, 1.64682383e-03]), + 'Rotation': array([ 3.59336250e-02, 1.76928787e+02, -7.78197963e-03]), + 'Velocity': array([-2.50825310e+01, 1.33650720e+00, 5.86509714e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4559.89794921875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5038.96728516, 14611.30273438, 237.75794983]), + 'frame': 28854, + 'frame_number': 28854, + 'framesequence': 116160, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.7420811504126, + 'timestamp_carla': 979741, + 'timestamp_device': 1850340, + 'timestamp_stream': 979.7420811504126, + 'transform': [array([-60.0344696 , 87.95158386, -0.32277453]), + array([ 2.98634982, 172.43527222, 1.44814277])]} +{'AngularVelocity': array([-7.43602812e-02, 3.35223922e-05, 2.42253470e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.41472452878952026, + 'FR_Wheel_Angle': 0.44006267189979553, + 'Location': array([-1.00008095e+02, -8.91923599e+01, 1.65369036e-03]), + 'Rotation': array([ 3.48612852e-02, 1.77225906e+02, -1.83105450e-02]), + 'Velocity': array([-2.55194874e+01, 1.25206137e+00, 3.22818755e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4540.07373046875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5031.05566406, 14588.5234375 , 237.70222473]), + 'frame': 28855, + 'frame_number': 28855, + 'framesequence': 116164, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.7757694497705, + 'timestamp_carla': 979774, + 'timestamp_device': 1850374, + 'timestamp_stream': 979.7757694497705, + 'transform': [array([-60.06049728, 87.94287109, -0.32374141]), + array([ 2.99674535, 172.31619263, 1.45410013])]} +{'AngularVelocity': array([-0.08429414, 0.02974687, 3.46152496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.444590300321579, + 'FR_Wheel_Angle': 0.44616830348968506, + 'Location': array([-1.04331696e+02, -8.89912796e+01, 1.64323801e-03]), + 'Rotation': array([ 3.66371311e-02, 1.77740280e+02, -3.22570689e-02]), + 'Velocity': array([-2.59445095e+01, 1.10419500e+00, 3.71932970e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4536.142578125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5021.70361328, 14581.60546875, 238.07632446]), + 'frame': 28856, + 'frame_number': 28856, + 'framesequence': 116168, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.8081430494785, + 'timestamp_carla': 979807, + 'timestamp_device': 1850407, + 'timestamp_stream': 979.8081430494785, + 'transform': [array([-60.08548355, 87.93451691, -0.32456523]), + array([ 3.00539923, 172.20185852, 1.45918679])]} +{'AngularVelocity': array([-0.07679182, 0.04675086, 3.82109785]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4422738254070282, + 'FR_Wheel_Angle': 0.4437296390533447, + 'Location': array([-1.08674858e+02, -8.88217239e+01, 1.60680769e-03]), + 'Rotation': array([ 4.28457744e-02, 1.78349243e+02, -4.58984300e-02]), + 'Velocity': array([-2.64858780e+01, 9.02367830e-01, -1.10626218e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4532.45947265625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5012.70214844, 14574.99316406, 238.45753479]), + 'frame': 28857, + 'frame_number': 28857, + 'framesequence': 116172, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.8402633517981, + 'timestamp_carla': 979839, + 'timestamp_device': 1850440, + 'timestamp_stream': 979.8402633517981, + 'transform': [array([-60.11103058, 87.92652893, -0.32524493]), + array([ 3.01201773, 172.08522034, 1.46333361])]} +{'AngularVelocity': array([-0.05679115, 0.04481017, 4.02940035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.439915269613266, + 'FR_Wheel_Angle': 0.4412729740142822, + 'Location': array([-1.14045532e+02, -8.86673050e+01, 1.55008317e-03]), + 'Rotation': array([ 5.20938486e-02, 1.79135910e+02, -5.94482236e-02]), + 'Velocity': array([-2.72806072e+01, 6.01930022e-01, -3.58200050e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4528.85205078125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-5004.09814453, 14568.55859375, 238.77108765]), + 'frame': 28858, + 'frame_number': 28858, + 'framesequence': 116176, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.8717177510262, + 'timestamp_carla': 979870, + 'timestamp_device': 1850474, + 'timestamp_stream': 979.8717177510262, + 'transform': [array([-60.13567352, 87.91886902, -0.32590544]), + array([ 3.01783705, 171.97268677, 1.46722627])]} +{'AngularVelocity': array([-0.04379177, 0.03063912, 4.15256882]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.43730756640434265, + 'FR_Wheel_Angle': 0.4386439919471741, + 'Location': array([-1.18689323e+02, -8.85874557e+01, 1.50583265e-03]), + 'Rotation': array([ 5.84527552e-02, 1.79823456e+02, -6.79015964e-02]), + 'Velocity': array([-2.80187130e+01, 3.11459005e-01, -3.95345669e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4524.990234375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4995.38427734, 14561.8515625 , 239.00358582]), + 'frame': 28859, + 'frame_number': 28859, + 'framesequence': 116179, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.9027810506523, + 'timestamp_carla': 979901, + 'timestamp_device': 1850499, + 'timestamp_stream': 979.9027810506523, + 'transform': [array([-60.15961838, 87.91132355, -0.3267647 ]), + array([ 3.02576685, 171.86347961, 1.47201777])]} +{'AngularVelocity': array([-0.0328954 , 0.0235707 , 4.22871923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.4164625406265259, + 'FR_Wheel_Angle': 0.4054815173149109, + 'Location': array([-1.23469643e+02, -8.85589142e+01, 1.47470471e-03]), + 'Rotation': array([ 6.27352819e-02, -1.79469955e+02, -7.43407980e-02]), + 'Velocity': array([-2.87910099e+01, -9.14164074e-03, -2.13241565e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4518.91748046875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4987.32763672, 14553.04296875, 239.15740967]), + 'frame': 28860, + 'frame_number': 28860, + 'framesequence': 116184, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.9372989498079, + 'timestamp_carla': 979936, + 'timestamp_device': 1850540, + 'timestamp_stream': 979.9372989498079, + 'transform': [array([-60.18855667, 87.90319824, -0.32830033]), + array([ 3.04088879, 171.73260498, 1.479918 ])]} +{'AngularVelocity': array([-0.01608788, 0.01799905, 4.02865601]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.36492976546287537, + 'FR_Wheel_Angle': 0.3537125885486603, + 'Location': array([-1.29546783e+02, -8.86010361e+01, 1.44750590e-03]), + 'Rotation': array([ 6.71680793e-02, -1.78609421e+02, -7.91625902e-02]), + 'Velocity': array([-2.97927971e+01, -4.31463093e-01, 2.36511232e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4517.8623046875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4978.83496094, 14549.24609375, 239.50404358]), + 'frame': 28861, + 'frame_number': 28861, + 'framesequence': 116188, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 979.97019245103, + 'timestamp_carla': 979969, + 'timestamp_device': 1850574, + 'timestamp_stream': 979.97019245103, + 'transform': [array([-60.21575165, 87.8945694 , -0.3301585 ]), + array([ 3.05667353, 171.60906982, 1.48911905])]} +{'AngularVelocity': array([0.01442007, 0.01698199, 3.44551754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2309047281742096, + 'FR_Wheel_Angle': 0.18248386681079865, + 'Location': array([-1.34562729e+02, -8.86989212e+01, 1.43209449e-03]), + 'Rotation': array([ 6.99206442e-02, -1.77980637e+02, -7.94982836e-02]), + 'Velocity': array([-3.06234055e+01, -7.72360384e-01, 6.00337989e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4392.115234375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4986.71777344, 14421.62109375, 236.85662842]), + 'frame': 28862, + 'frame_number': 28862, + 'framesequence': 116192, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36003297567367554, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.0040446519852, + 'timestamp_carla': 980003, + 'timestamp_device': 1850607, + 'timestamp_stream': 980.0040446519852, + 'transform': [array([-60.24420166, 87.88547516, -0.33230338]), + array([ 3.07341409, 171.47999573, 1.49938893])]} +{'AngularVelocity': array([0.07398369, 0.01942638, 1.6384902 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.03463984653353691, + 'FR_Wheel_Angle': -0.03639472275972366, + 'Location': array([-1.39739838e+02, -8.88514709e+01, 1.42259593e-03]), + 'Rotation': array([ 7.31171742e-02, -1.77552383e+02, -7.12280199e-02]), + 'Velocity': array([-3.14975548e+01, -1.06287658e+00, 1.04470251e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4402.67333984375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4975.62695312, 14428.89550781, 237.80386353]), + 'frame': 28863, + 'frame_number': 28863, + 'framesequence': 116196, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.36219367384910583, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.038670849055, + 'timestamp_carla': 980037, + 'timestamp_device': 1850640, + 'timestamp_stream': 980.038670849055, + 'transform': [array([-60.27365494, 87.87702942, -0.33472863]), + array([ 3.08959484, 171.34660339, 1.51067019])]} +{'AngularVelocity': array([0.09356736, 0.01657346, 0.40354675]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.040704887360334396, + 'FR_Wheel_Angle': -0.040625009685754776, + 'Location': array([-1.45080124e+02, -8.90484238e+01, 1.41561509e-03]), + 'Rotation': array([ 7.55350590e-02, -1.77402481e+02, -5.70068285e-02]), + 'Velocity': array([-3.24021225e+01, -1.28383172e+00, 4.72068768e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4414.02587890625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4963.94824219, 14436.76660156, 238.8500061 ]), + 'frame': 28864, + 'frame_number': 28864, + 'framesequence': 116200, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.37766656279563904, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.0713367499411, + 'timestamp_carla': 980070, + 'timestamp_device': 1850674, + 'timestamp_stream': 980.0713367499411, + 'transform': [array([-60.30065155, 87.86917877, -0.33686322]), + array([ 3.10376763, 171.22387695, 1.52062953])]} +{'AngularVelocity': array([ 0.09877194, 0.01121621, -0.09259016]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04037598893046379, + 'FR_Wheel_Angle': -0.040360208600759506, + 'Location': array([-1.50582062e+02, -8.92769241e+01, 1.40554423e-03]), + 'Rotation': array([ 7.71333203e-02, -1.77384506e+02, -4.03747484e-02]), + 'Velocity': array([-3.33199654e+01, -1.43110430e+00, -3.39508051e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4425.50390625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4951.87841797, 14444.703125 , 239.97891235]), + 'frame': 28865, + 'frame_number': 28865, + 'framesequence': 116203, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.39940187335014343, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.1046503521502, + 'timestamp_carla': 980103, + 'timestamp_device': 1850699, + 'timestamp_stream': 980.1046503521502, + 'transform': [array([-60.33022308, 87.86180115, -0.338844 ]), + array([ 3.11638284, 171.08901978, 1.52971101])]} +{'AngularVelocity': array([ 0.07834041, 0.00075356, -0.33377627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04037598893046379, + 'FR_Wheel_Angle': -0.040360208600759506, + 'Location': array([-1.57394211e+02, -8.95763321e+01, 1.40195841e-03]), + 'Rotation': array([ 7.75977746e-02, -1.77431992e+02, -2.23083496e-02]), + 'Velocity': array([-3.44169044e+01, -1.53120112e+00, -1.77860261e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4425.5380859375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4942.34326172, 14441.56640625, 240.71261597]), + 'frame': 28866, + 'frame_number': 28866, + 'framesequence': 116208, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4219428300857544, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.1387747488916, + 'timestamp_carla': 980137, + 'timestamp_device': 1850740, + 'timestamp_stream': 980.1387747488916, + 'transform': [array([-60.36157227, 87.85506439, -0.34085539]), + array([ 3.12893677, 170.94561768, 1.53886795])]} +{'AngularVelocity': array([ 0.05654726, -0.00850219, -0.42500737]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04037598893046379, + 'FR_Wheel_Angle': -0.040360208600759506, + 'Location': array([-1.63383194e+02, -8.98436203e+01, 1.40920631e-03]), + 'Rotation': array([ 7.63341933e-02, -1.77498245e+02, -1.08337393e-02]), + 'Velocity': array([-3.53213234e+01, -1.57266915e+00, 2.47955313e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4417.58935546875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4933.13525391, 14430.34472656, 241.16668701]), + 'frame': 28867, + 'frame_number': 28867, + 'framesequence': 116212, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.442854106426239, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.1738679520786, + 'timestamp_carla': 980172, + 'timestamp_device': 1850774, + 'timestamp_stream': 980.1738679520786, + 'transform': [array([-60.39403152, 87.84873962, -0.3428562 ]), + array([ 3.14168191, 170.7964325 , 1.54797077])]} +{'AngularVelocity': array([ 0.03762853, -0.01372254, -0.47528222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04037598893046379, + 'FR_Wheel_Angle': -0.040360208600759506, + 'Location': array([-1.69829239e+02, -9.01290588e+01, 1.42354961e-03]), + 'Rotation': array([ 7.38753229e-02, -1.77579956e+02, -2.62451172e-03]), + 'Velocity': array([-3.62265587e+01, -1.58858180e+00, -1.02043145e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4085.778564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4974.72509766, 14099.35644531, 232.93850708]), + 'frame': 28868, + 'frame_number': 28868, + 'framesequence': 116216, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4444105327129364, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.2070676498115, + 'timestamp_carla': 980206, + 'timestamp_device': 1850807, + 'timestamp_stream': 980.2070676498115, + 'transform': [array([-60.43436813, 87.84257507, -0.33372244]), + array([ 2.96888494, 170.59593201, 1.48209786])]} +{'AngularVelocity': array([ 0.02426348, -0.01349802, -0.50451112]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.04037598893046379, + 'FR_Wheel_Angle': -0.04125674441456795, + 'Location': array([-1.76379730e+02, -9.04132462e+01, 1.43911364e-03]), + 'Rotation': array([ 7.11774006e-02, -1.77667709e+02, 2.65034754e-03]), + 'Velocity': array([-3.70852127e+01, -1.58622766e+00, 3.91006466e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4078.775146484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4965.16992188, 14088.97265625, 233.36087036]), + 'frame': 28869, + 'frame_number': 28869, + 'framesequence': 116220, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4339732229709625, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.2392156496644, + 'timestamp_carla': 980238, + 'timestamp_device': 1850840, + 'timestamp_stream': 980.2392156496644, + 'transform': [array([-60.4764061 , 87.83563995, -0.31286424]), + array([ 2.63035345, 170.37815857, 1.33943093])]} +{'AngularVelocity': array([ 0.01420356, 0.53586948, -0.81607008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.11125827580690384, + 'FR_Wheel_Angle': -0.1227763220667839, + 'Location': array([-1.83281555e+02, -9.07036896e+01, 7.92680681e-03]), + 'Rotation': array([ 2.49923438e-01, -1.77781052e+02, 1.01312073e-02]), + 'Velocity': array([-37.93450928, -1.56119025, 0.10570325]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4094.786376953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4949.07519531, 14100.84863281, 229.11756897]), + 'frame': 28870, + 'frame_number': 28870, + 'framesequence': 116224, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42179635167121887, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.2735997512937, + 'timestamp_carla': 980272, + 'timestamp_device': 1850873, + 'timestamp_stream': 980.2735997512937, + 'transform': [array([-60.51500702, 87.82429504, -0.27024746]), + array([ 1.9691776 , 170.16442871, 1.05255902])]} +{'AngularVelocity': array([-1.69782913, -1.24094486, -1.26787436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.12292245775461197, + 'FR_Wheel_Angle': -0.1227763220667839, + 'Location': array([-1.90216873e+02, -9.09826279e+01, 3.01992595e-02]), + 'Rotation': array([ 2.16428190e-01, -1.77978912e+02, -6.41174093e-02]), + 'Velocity': array([-38.74112701, -1.50240135, 0.10281202]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4436.7666015625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4877.60595703, 14433.99023438, 226.93841553]), + 'frame': 28871, + 'frame_number': 28871, + 'framesequence': 116228, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.40994906425476074, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.306226849556, + 'timestamp_carla': 980305, + 'timestamp_device': 1850907, + 'timestamp_stream': 980.306226849556, + 'transform': [array([-60.54724503, 87.81176758, -0.21890365]), + array([ 1.2326647 , 169.98764038, 0.71302468])]} +{'AngularVelocity': array([-0.1144662 , -0.18200898, -1.55646706]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.12292245775461197, + 'FR_Wheel_Angle': -0.1227763220667839, + 'Location': array([-1.97522202e+02, -9.12559814e+01, 3.71343046e-02]), + 'Rotation': array([ 5.16362265e-02, -1.78248291e+02, -1.68457001e-01]), + 'Velocity': array([-3.95508156e+01, -1.40200508e+00, -9.57564358e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4345.439453125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4879.76269531, 14340.421875 , 203.0612793 ]), + 'frame': 28872, + 'frame_number': 28872, + 'framesequence': 116232, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4074404537677765, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.3400936499238, + 'timestamp_carla': 980339, + 'timestamp_device': 1850940, + 'timestamp_stream': 980.3400936499238, + 'transform': [array([-60.58662415, 87.80371094, -0.18479389]), + array([ 0.83777046, 169.80215454, 0.4928233 ])]} +{'AngularVelocity': array([ 0.0501103 , 1.38478661, -1.71519184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.12292245775461197, + 'FR_Wheel_Angle': -0.11651014536619186, + 'Location': array([-2.05092178e+02, -9.15110626e+01, -7.86018354e-05]), + 'Rotation': array([ 3.87681499e-02, -1.78551651e+02, 3.52907106e-02]), + 'Velocity': array([-40.31681442, -1.27167451, -0.06802195]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7996.73681640625, + 'focus_actor_name': 'Town05_WallNode_my0025_522', + 'focus_actor_pt': array([-4233.52587891, 17932.69335938, 222.60551453]), + 'frame': 28873, + 'frame_number': 28873, + 'framesequence': 116236, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4115237891674042, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.372577149421, + 'timestamp_carla': 980371, + 'timestamp_device': 1850973, + 'timestamp_stream': 980.372577149421, + 'transform': [array([-60.61962891, 87.79721832, -0.16774461]), + array([ 0.66242588, 169.65087891, 0.38064438])]} +{'AngularVelocity': array([ 0.03137717, -0.1156401 , -1.89112556]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.2099551409482956, + 'FR_Wheel_Angle': -0.35052600502967834, + 'Location': array([-2.12932755e+02, -9.17395477e+01, -9.94663220e-04]), + 'Rotation': array([ 6.56312853e-02, -1.78878235e+02, 3.90262716e-02]), + 'Velocity': array([-4.09528656e+01, -1.08150315e+00, 1.26752090e-02]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4019.918701171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4914.42382812, 14013.45117188, 157.35272217]), + 'frame': 28874, + 'frame_number': 28874, + 'framesequence': 116240, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4178594648838043, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.4039398506284, + 'timestamp_carla': 980402, + 'timestamp_device': 1851007, + 'timestamp_stream': 980.4039398506284, + 'transform': [array([-60.649189 , 87.79102325, -0.1589119 ]), + array([ 0.57021147, 169.51495361, 0.31959346])]} +{'AngularVelocity': array([ 0.14503931, -0.10132758, -5.42332506]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6262763738632202, + 'FR_Wheel_Angle': -0.5994486808776855, + 'Location': array([-2.21243118e+02, -9.19270401e+01, 8.94527417e-04]), + 'Rotation': array([ 4.28321138e-02, -1.79623795e+02, 6.02255501e-02]), + 'Velocity': array([-4.13089104e+01, -7.15310395e-01, 4.89569642e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4022.017578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4904.12304688, 14012.28027344, 149.20155334]), + 'frame': 28875, + 'frame_number': 28875, + 'framesequence': 116244, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4237556457519531, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.4380338490009, + 'timestamp_carla': 980437, + 'timestamp_device': 1851040, + 'timestamp_stream': 980.4380338490009, + 'transform': [array([-60.68011093, 87.7849884 , -0.15478154]), + array([ 0.50341225, 169.37255859, 0.28467947])]} +{'AngularVelocity': array([ 0.19713062, -0.08638079, -6.87973452]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5966673493385315, + 'FR_Wheel_Angle': -0.6420002579689026, + 'Location': array([-2.29101654e+02, -9.20192337e+01, 1.52227399e-03]), + 'Rotation': array([2.53126789e-02, 1.79179504e+02, 9.29713398e-02]), + 'Velocity': array([-4.14043312e+01, -1.75698757e-01, 1.38367654e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4014.2373046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4896.37158203, 14001.48144531, 144.65525818]), + 'frame': 28876, + 'frame_number': 28876, + 'framesequence': 116248, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42578813433647156, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.4705095514655, + 'timestamp_carla': 980469, + 'timestamp_device': 1851073, + 'timestamp_stream': 980.4705095514655, + 'transform': [array([-60.70909119, 87.77933502, -0.15359728]), + array([ 0.45446026, 169.23873901, 0.26780638])]} +{'AngularVelocity': array([ 0.35984036, -0.09761477, -10.95551682]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.4499465227127075, + 'FR_Wheel_Angle': -1.9593899250030518, + 'Location': array([-2.37018799e+02, -9.19844742e+01, 1.75622932e-03]), + 'Rotation': array([9.48030222e-03, 1.77566757e+02, 1.44821063e-01]), + 'Velocity': array([-4.12511406e+01, 6.61428452e-01, 3.48863599e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4006.084716796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4888.18701172, 13990.08105469, 142.00064087]), + 'frame': 28877, + 'frame_number': 28877, + 'framesequence': 116252, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4238838255405426, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.5048047490418, + 'timestamp_carla': 980503, + 'timestamp_device': 1851107, + 'timestamp_stream': 980.5048047490418, + 'transform': [array([-60.73859406, 87.77364349, -0.15316264]), + array([ 0.40789887, 169.10263062, 0.2563844 ])]} +{'AngularVelocity': array([ 1.1702528 , -0.2147802 , -34.69047928]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.681777000427246, + 'FR_Wheel_Angle': -7.208356857299805, + 'Location': array([-2.44812988e+02, -9.17278290e+01, 1.88520423e-03]), + 'Rotation': array([-6.19498128e-03, 1.73555405e+02, 2.93844104e-01]), + 'Velocity': array([-4.07225266e+01, 2.44600558e+00, 5.59473010e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3998.467041015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4880.47412109, 13979.3359375 , 140.68048096]), + 'frame': 28878, + 'frame_number': 28878, + 'framesequence': 116256, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.537222251296, + 'timestamp_carla': 980536, + 'timestamp_device': 1851140, + 'timestamp_stream': 980.537222251296, + 'transform': [array([-60.76544952, 87.76824951, -0.15309803]), + array([ 0.36892581, 168.97879028, 0.24921137])]} +{'AngularVelocity': array([ 1.49913836, -0.50243992, -65.17215729]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.051355361938477, + 'FR_Wheel_Angle': -10.55339241027832, + 'Location': array([-2.52451416e+02, -9.10102844e+01, 1.98751455e-03]), + 'Rotation': array([-2.15492453e-02, 1.63710876e+02, 5.74880838e-01]), + 'Velocity': array([-3.93447914e+01, 5.72731352e+00, -8.43429516e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4010.4208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4868.93798828, 13987.71777344, 139.87561035]), + 'frame': 28879, + 'frame_number': 28879, + 'framesequence': 116260, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4175298511981964, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.571136251092, + 'timestamp_carla': 980570, + 'timestamp_device': 1851173, + 'timestamp_stream': 980.571136251092, + 'transform': [array([-60.79358673, 87.7625885 , -0.15325819]), + array([ 0.33241847, 168.84907532, 0.24408762])]} +{'AngularVelocity': array([ 1.08467245, -0.68016839, -78.3289032 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.103780746459961, + 'FR_Wheel_Angle': -12.518263816833496, + 'Location': array([-2.59302917e+02, -8.97051086e+01, 2.06224434e-03]), + 'Rotation': array([-3.37821133e-02, 1.50560440e+02, 8.41978312e-01]), + 'Velocity': array([-3.68281593e+01, 9.45716190e+00, -1.43308629e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5294.40771484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4614.97314453, 15244.88867188, 144.93241882]), + 'frame': 28880, + 'frame_number': 28880, + 'framesequence': 116264, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4176214039325714, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.6060418523848, + 'timestamp_carla': 980605, + 'timestamp_device': 1851207, + 'timestamp_stream': 980.6060418523848, + 'transform': [array([-60.82141113, 87.75687408, -0.15369245]), + array([ 0.30052832, 168.72123718, 0.2412387 ])]} +{'AngularVelocity': array([11.23528194, 4.10497761, 55.88417053]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.909761428833008, + 'FR_Wheel_Angle': -15.74899959564209, + 'Location': array([-2.65047180e+02, -8.77706146e+01, 1.37050956e-01]), + 'Rotation': array([ 4.86514345e-02, 1.39330124e+02, -2.19113135e+00]), + 'Velocity': array([-5.1933713 , 9.53912926, 0.69211799]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3976.67578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4858.1171875 , 13948.1953125 , 138.83624268]), + 'frame': 28881, + 'frame_number': 28881, + 'framesequence': 116268, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.41897645592689514, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.6376515515149, + 'timestamp_carla': 980636, + 'timestamp_device': 1851240, + 'timestamp_stream': 980.6376515515149, + 'transform': [array([-60.8462944 , 87.75186157, -0.15420194]), + array([ 0.27477849, 168.6068573 , 0.23997454])]} +{'AngularVelocity': array([-25.29950142, 19.4569664 , -7.72068501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.872732162475586, + 'FR_Wheel_Angle': -19.581172943115234, + 'Location': array([-2.66003113e+02, -8.61780243e+01, 1.41077369e-01]), + 'Rotation': array([ 0.64807564, 142.73626709, -3.00238061]), + 'Velocity': array([-6.4223218 , 9.59399509, -0.44466633]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3969.65966796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4850.8203125 , 13938.02929688, 138.609375 ]), + 'frame': 28882, + 'frame_number': 28882, + 'framesequence': 116272, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.420477956533432, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.6711280494928, + 'timestamp_carla': 980670, + 'timestamp_device': 1851273, + 'timestamp_stream': 980.6711280494928, + 'transform': [array([-60.87335205, 87.74668121, -0.15484512]), + array([ 0.24999857, 168.4825592 , 0.23946863])]} +{'AngularVelocity': array([ 0.22059748, -1.36322963, -88.41261292]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.912700653076172, + 'FR_Wheel_Angle': -21.028837203979492, + 'Location': array([-2.67214630e+02, -8.45897064e+01, 8.69664252e-02]), + 'Rotation': array([ 0.13693845, 133.51234436, -5.16644526]), + 'Velocity': array([-7.0508666 , 10.31586742, -0.124254 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3963.416259765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4844.30664062, 13928.95703125, 138.50421143]), + 'frame': 28883, + 'frame_number': 28883, + 'framesequence': 116276, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4209723174571991, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.7046341523528, + 'timestamp_carla': 980703, + 'timestamp_device': 1851307, + 'timestamp_stream': 980.7046341523528, + 'transform': [array([-60.90065765, 87.74156952, -0.1555759 ]), + array([ 0.22836053, 168.3572998 , 0.23981661])]} +{'AngularVelocity': array([ 0.33305568, -1.56459975, -95.73461151]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.08582305908203, + 'FR_Wheel_Angle': -21.076404571533203, + 'Location': array([-2.68280396e+02, -8.28726807e+01, 7.92412832e-02]), + 'Rotation': array([ 4.97032851e-02, 1.18282776e+02, -4.90380955e+00]), + 'Velocity': array([-5.04040241, 11.32446957, -0.01624158]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3970.24072265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4834.53808594, 13932.43945312, 138.50717163]), + 'frame': 28884, + 'frame_number': 28884, + 'framesequence': 116280, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42013001441955566, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.7373052500188, + 'timestamp_carla': 980736, + 'timestamp_device': 1851340, + 'timestamp_stream': 980.7373052500188, + 'transform': [array([-60.92672348, 87.736763 , -0.15644842]), + array([ 0.21011026, 168.23780823, 0.24123701])]} +{'AngularVelocity': array([ -5.68615341, -27.20444298, -86.55625153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.68603515625, + 'FR_Wheel_Angle': -20.31208610534668, + 'Location': array([-2.69020660e+02, -8.07282791e+01, 6.13696165e-02]), + 'Rotation': array([ -0.78597713, 101.12978363, -2.77240014]), + 'Velocity': array([-2.24736619, 11.61089897, -0.3157776 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5256.78515625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4566.39794922, 15189.24511719, 143.9258728 ]), + 'frame': 28885, + 'frame_number': 28885, + 'framesequence': 116284, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.41943421959877014, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.7702871523798, + 'timestamp_carla': 980769, + 'timestamp_device': 1851373, + 'timestamp_stream': 980.7702871523798, + 'transform': [array([-60.95303726, 87.73197174, -0.15737262]), + array([ 0.19292551, 168.11698914, 0.24299896])]} +{'AngularVelocity': array([ 5.58798838, -10.43798828, -86.43904114]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.699602127075195, + 'FR_Wheel_Angle': -15.389966011047363, + 'Location': array([-2.69166199e+02, -7.85039597e+01, 2.58258339e-02]), + 'Rotation': array([-0.71923256, 82.62071228, -0.62518317]), + 'Velocity': array([ 1.34518182, 10.8085413 , -0.16794498]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3943.470458984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4823.41601562, 13899.85644531, 138.53546143]), + 'frame': 28886, + 'frame_number': 28886, + 'framesequence': 116287, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.41980043053627014, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.8032620511949, + 'timestamp_carla': 980802, + 'timestamp_device': 1851398, + 'timestamp_stream': 980.8032620511949, + 'transform': [array([-60.97880554, 87.72723389, -0.15839291]), + array([ 0.17798106, 167.99909973, 0.2454098 ])]} +{'AngularVelocity': array([ 0.73885858, -2.13145947, -47.52508545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.227507591247559, + 'FR_Wheel_Angle': -8.547080993652344, + 'Location': array([-2.68786987e+02, -7.67687378e+01, 8.43653642e-03]), + 'Rotation': array([-0.22619537, 71.85555267, 0.07964107]), + 'Velocity': array([ 3.47515678, 9.82133293, -0.04218204]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3937.020751953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4816.61572266, 13890.38378906, 138.63722229]), + 'frame': 28887, + 'frame_number': 28887, + 'framesequence': 116292, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.4202398955821991, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.8380054496229, + 'timestamp_carla': 980836, + 'timestamp_device': 1851440, + 'timestamp_stream': 980.8380054496229, + 'transform': [array([-61.00504684, 87.7221756 , -0.15954776]), + array([1.63118571e-01, 1.67878616e+02, 2.48319283e-01])]} +{'AngularVelocity': array([ 0.53129423, 0.18734138, -15.25126171]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.4912643432617188, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.68170593e+02, -7.51859665e+01, 3.92439822e-03]), + 'Rotation': array([-0.09883966, 66.84386444, 0.14255565]), + 'Velocity': array([ 4.00541258, 9.1325922 , -0.01160305]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3930.78662109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4810.00146484, 13881.171875 , 138.78182983]), + 'frame': 28888, + 'frame_number': 28888, + 'framesequence': 116296, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42025822401046753, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.8708742521703, + 'timestamp_carla': 980869, + 'timestamp_device': 1851473, + 'timestamp_stream': 980.8708742521703, + 'transform': [array([-61.03099442, 87.71777344, -0.16063686]), + array([1.49963632e-01, 1.67759705e+02, 2.51222074e-01])]} +{'AngularVelocity': array([ 0.23408023, 0.20973304, -0.75896478]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.67527893e+02, -7.37047882e+01, 2.64163013e-03]), + 'Rotation': array([-6.04539998e-02, 6.60498352e+01, 6.34374619e-02]), + 'Velocity': array([ 3.78307700e+00, 8.58345985e+00, -3.26870428e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3928.15576171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4802.47949219, 13875.37597656, 138.973526 ]), + 'frame': 28889, + 'frame_number': 28889, + 'framesequence': 116300, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.9035737514496, + 'timestamp_carla': 980902, + 'timestamp_device': 1851507, + 'timestamp_stream': 980.9035737514496, + 'transform': [array([-61.05635071, 87.7133255 , -0.16177101]), + array([1.38277173e-01, 1.67643753e+02, 2.54452527e-01])]} +{'AngularVelocity': array([0.09244879, 0.10403397, 0.17715648]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.66800964e+02, -7.20627060e+01, 2.22624769e-03]), + 'Rotation': array([-4.58373986e-02, 6.60006027e+01, 2.38500107e-02]), + 'Velocity': array([ 3.51560974e+00, 7.91436529e+00, -7.42845528e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3938.89453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4792.24511719, 13882.72460938, 139.22361755]), + 'frame': 28890, + 'frame_number': 28890, + 'framesequence': 116304, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.9390411488712, + 'timestamp_carla': 980938, + 'timestamp_device': 1851540, + 'timestamp_stream': 980.9390411488712, + 'transform': [array([-61.08420944, 87.70877075, -0.16304556]), + array([1.25702798e-01, 1.67516144e+02, 2.58038342e-01])]} +{'AngularVelocity': array([0.04043321, 0.03699587, 0.20934881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.66128967e+02, -7.05503235e+01, 2.11691856e-03]), + 'Rotation': array([-4.00385670e-02, 6.59992676e+01, 6.81988522e-03]), + 'Velocity': array([ 3.23885989e+00, 7.28637695e+00, -1.69429768e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5205.3955078125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-4513.44482422, 15116.76171875, 145.0723114 ]), + 'frame': 28891, + 'frame_number': 28891, + 'framesequence': 116308, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 980.971489649266, + 'timestamp_carla': 980970, + 'timestamp_device': 1851573, + 'timestamp_stream': 980.971489649266, + 'transform': [array([-61.11129761, 87.7038269 , -0.16428711]), + array([1.11967288e-01, 1.67392303e+02, 2.61419088e-01])]} +{'AngularVelocity': array([0.0213169 , 0.0131069 , 0.28996301]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.65605804e+02, -6.93732605e+01, 2.08312040e-03]), + 'Rotation': array([-3.69581506e-02, 6.59995575e+01, 1.17387890e-03]), + 'Velocity': array([ 3.01680684e+00, 6.78707552e+00, -5.06877877e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3905.620849609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4783.11132812, 13843.71386719, 139.54377747]), + 'frame': 28892, + 'frame_number': 28892, + 'framesequence': 116312, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.0050727501512, + 'timestamp_carla': 981004, + 'timestamp_device': 1851607, + 'timestamp_stream': 981.0050727501512, + 'transform': [array([-61.13900757, 87.69895172, -0.16572744]), + array([1.00772604e-01, 1.67265762e+02, 2.65851825e-01])]} +{'AngularVelocity': array([0.01720322, 0.00114459, 0.24573691]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.65125397e+02, -6.82924728e+01, 2.06439011e-03]), + 'Rotation': array([-3.45744155e-02, 6.59997559e+01, -1.12914911e-03]), + 'Velocity': array([ 2.80998158e+00, 6.32207394e+00, -1.23596192e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3899.313232421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4776.2734375 , 13834.1875 , 139.74729919]), + 'frame': 28893, + 'frame_number': 28893, + 'framesequence': 116315, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.0360022522509, + 'timestamp_carla': 981035, + 'timestamp_device': 1851632, + 'timestamp_stream': 981.0360022522509, + 'transform': [array([-61.16425705, 87.69458771, -0.1670552 ]), + array([9.13674384e-02, 1.67150436e+02, 2.70120591e-01])]} +{'AngularVelocity': array([ 0.01229259, -0.00241879, 0.28218427]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.64672546e+02, -6.72736130e+01, 2.05084798e-03]), + 'Rotation': array([-3.25321890e-02, 6.60000305e+01, -2.07519392e-03]), + 'Velocity': array([ 2.60948753e+00, 5.87114239e+00, -4.57763645e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3892.906982421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4769.30957031, 13824.48632812, 140.01698303]), + 'frame': 28894, + 'frame_number': 28894, + 'framesequence': 116320, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.0696108490229, + 'timestamp_carla': 981068, + 'timestamp_device': 1851673, + 'timestamp_stream': 981.0696108490229, + 'transform': [array([-61.19152832, 87.68995667, -0.16852939]), + array([8.17573592e-02, 1.67025986e+02, 2.74840146e-01])]} +{'AngularVelocity': array([ 0.00716493, -0.00279801, 0.33848372]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.64171997e+02, -6.61474152e+01, 2.03745835e-03]), + 'Rotation': array([-3.03055476e-02, 6.60004883e+01, -2.47192313e-03]), + 'Velocity': array([ 2.38127017e+00, 5.35776854e+00, -1.24931330e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3887.104736328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4762.97949219, 13815.67089844, 140.27862549]), + 'frame': 28895, + 'frame_number': 28895, + 'framesequence': 116324, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.1041390523314, + 'timestamp_carla': 981103, + 'timestamp_device': 1851707, + 'timestamp_stream': 981.1041390523314, + 'transform': [array([-61.2192421 , 87.68538666, -0.17005451]), + array([7.24478140e-02, 1.66899490e+02, 2.79785216e-01])]} +{'AngularVelocity': array([ 0.01027077, -0.00465552, 0.3096599 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.63795807e+02, -6.53009567e+01, 2.02681543e-03]), + 'Rotation': array([-2.85023786e-02, 6.60005341e+01, -2.62451055e-03]), + 'Velocity': array([ 2.20654011e+00, 4.96467352e+00, -2.03609466e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3880.885986328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4756.17236328, 13806.18847656, 140.56452942]), + 'frame': 28896, + 'frame_number': 28896, + 'framesequence': 116328, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.1361686512828, + 'timestamp_carla': 981135, + 'timestamp_device': 1851740, + 'timestamp_stream': 981.1361686512828, + 'transform': [array([-61.24493408, 87.68119049, -0.17139123]), + array([6.37188330e-02, 1.66782166e+02, 2.84129143e-01])]} +{'AngularVelocity': array([ 0.00967463, -0.00478164, 0.32694229]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.63443085e+02, -6.45074158e+01, 2.01716414e-03]), + 'Rotation': array([-2.68563032e-02, 6.60007858e+01, -2.62451218e-03]), + 'Velocity': array([ 2.03634191e+00, 4.58174467e+00, -2.43186946e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3874.60498046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4749.27832031, 13796.58496094, 140.86346436]), + 'frame': 28897, + 'frame_number': 28897, + 'framesequence': 116332, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.170840151608, + 'timestamp_carla': 981169, + 'timestamp_device': 1851773, + 'timestamp_stream': 981.170840151608, + 'transform': [array([-61.27312851, 87.67649841, -0.17286974]), + array([5.37399240e-02, 1.66653641e+02, 2.88773566e-01])]} +{'AngularVelocity': array([ 0.02149335, -0.00935959, 0.00016135]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.63111450e+02, -6.37612114e+01, 1.76959031e-03]), + 'Rotation': array([-2.02651694e-02, 6.59985275e+01, -2.62451265e-03]), + 'Velocity': array([1.92588806e+00, 4.33295965e+00, 3.90834786e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3868.819091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4742.90283203, 13787.70410156, 141.12602234]), + 'frame': 28898, + 'frame_number': 28898, + 'framesequence': 116336, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.203730750829, + 'timestamp_carla': 981202, + 'timestamp_device': 1851807, + 'timestamp_stream': 981.203730750829, + 'transform': [array([-61.30040359, 87.67253113, -0.17373949]), + array([4.92251702e-02, 1.66529709e+02, 2.91683316e-01])]} +{'AngularVelocity': array([ 3.48835754, 2.53504419, -0.74166471]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.62785065e+02, -6.30724258e+01, 2.23526098e-02]), + 'Rotation': array([ 0.97993404, 65.83624268, 2.24490762]), + 'Velocity': array([1.80180752, 3.88481855, 0.1429708 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3862.54150390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4735.94433594, 13778.01074219, 141.40260315]), + 'frame': 28899, + 'frame_number': 28899, + 'framesequence': 116340, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.2377682514489, + 'timestamp_carla': 981236, + 'timestamp_device': 1851840, + 'timestamp_stream': 981.2377682514489, + 'transform': [array([-61.32719421, 87.66841888, -0.17401433]), + array([4.84601893e-02, 1.66407928e+02, 2.92632669e-01])]} +{'AngularVelocity': array([ 0.058597 , -2.56613064, -0.07605837]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.62499695e+02, -6.24430351e+01, 3.36477757e-02]), + 'Rotation': array([ 1.25706208, 65.81482697, 2.59333301]), + 'Velocity': array([1.62147903, 3.64985061, 0.03716766]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3856.489013671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4729.26123047, 13768.70019531, 141.5642395 ]), + 'frame': 28900, + 'frame_number': 28900, + 'framesequence': 116344, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.2706078514457, + 'timestamp_carla': 981269, + 'timestamp_device': 1851873, + 'timestamp_stream': 981.2706078514457, + 'transform': [array([-61.35278702, 87.66460419, -0.17394415]), + array([4.85831313e-02, 1.66291473e+02, 2.92386740e-01])]} +{'AngularVelocity': array([-0.01681785, -1.07580996, -0.03920535]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.62238342e+02, -6.18610039e+01, 3.62257101e-02]), + 'Rotation': array([ 1.37217128, 65.81216431, 2.84815478]), + 'Velocity': array([1.52055597, 3.40141129, 0.00808328]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3850.5908203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4722.70214844, 13759.56542969, 141.59524536]), + 'frame': 28901, + 'frame_number': 28901, + 'framesequence': 116348, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.3040973506868, + 'timestamp_carla': 981303, + 'timestamp_device': 1851907, + 'timestamp_stream': 981.3040973506868, + 'transform': [array([-61.37905502, 87.66092682, -0.17370476]), + array([4.87129055e-02, 1.66171890e+02, 2.91457862e-01])]} +{'AngularVelocity': array([-0.01518321, -0.42143258, -0.02498684]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.61990570e+02, -6.13099899e+01, 3.68527323e-02]), + 'Rotation': array([ 1.41610301, 65.81105042, 2.95325184]), + 'Velocity': array([1.42145264e+00, 3.16743374e+00, 2.42018700e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3844.971923828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4716.44628906, 13750.84960938, 141.55091858]), + 'frame': 28902, + 'frame_number': 28902, + 'framesequence': 116352, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.3382002525032, + 'timestamp_carla': 981337, + 'timestamp_device': 1851940, + 'timestamp_stream': 981.3382002525032, + 'transform': [array([-61.40578079, 87.65740204, -0.17342587]), + array([4.94095869e-02, 1.66050522e+02, 2.90440112e-01])]} +{'AngularVelocity': array([5.77722502, 3.76390791, 0.53615159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-2.61771606e+02, -6.08040657e+01, 5.64998761e-02]), + 'Rotation': array([ 2.29962206, 66.0098877 , 1.1061939 ]), + 'Velocity': array([1.23371434, 2.66604757, 0.13759065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3839.228759765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4710.046875 , 13741.93554688, 141.46127319]), + 'frame': 28903, + 'frame_number': 28903, + 'framesequence': 116356, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.42016667127609253, + 'throttle_input': 0.2222171425819397, + 'timestamp': 981.3722586520016, + 'timestamp_carla': 981371, + 'timestamp_device': 1851973, + 'timestamp_stream': 981.3722586520016, + 'transform': [array([-61.43212128, 87.65354156, -0.17306413]), + array([4.97715846e-02, 1.65930756e+02, 2.89060444e-01])]} \ No newline at end of file diff --git a/PythonAPI/data/vehicle_logs/backward_2.txt b/PythonAPI/data/vehicle_logs/backward_2.txt new file mode 100644 index 0000000..559b2ec --- /dev/null +++ b/PythonAPI/data/vehicle_logs/backward_2.txt @@ -0,0 +1,21620 @@ +{'AngularVelocity': array([ 1.76853391e-05, -2.27151650e-05, 4.23225677e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30171776]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-1.51730593e-08, -1.17317827e-08, 3.45969194e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5487060546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 29.99996948]), + 'frame': 28859, + 'frame_number': 28859, + 'framesequence': 116748, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.6178986988962, + 'timestamp_carla': 985617, + 'timestamp_device': 2604176, + 'timestamp_stream': 985.6178986988962, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61329195e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.64709561e-05, -3.28308997e-05, -4.19949764e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30170339]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-2.98321723e-08, -2.43728433e-08, 1.30681990e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5479125976562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28860, + 'frame_number': 28860, + 'framesequence': 116752, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.6525316983461, + 'timestamp_carla': 985652, + 'timestamp_device': 2604209, + 'timestamp_stream': 985.6525316983461, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344454e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 1.29618320e-05, -1.94520180e-05, -4.93134145e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30171028]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-3.26333627e-09, -2.75805268e-10, 3.63306986e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5505981445312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30.00003052]), + 'frame': 28861, + 'frame_number': 28861, + 'framesequence': 116756, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.6845324970782, + 'timestamp_carla': 985684, + 'timestamp_device': 2604242, + 'timestamp_stream': 985.6845324970782, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61333531e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.04166718e-05, -2.72161160e-05, -4.14679091e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30171904]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-2.96801854e-08, -2.33437660e-08, 2.54087441e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5475463867188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30.00003052]), + 'frame': 28862, + 'frame_number': 28862, + 'framesequence': 116760, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.7188020981848, + 'timestamp_carla': 985718, + 'timestamp_device': 2604276, + 'timestamp_stream': 985.7188020981848, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344066e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.20831571e-05, -3.03139877e-05, 2.57948618e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30170289]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-1.90496081e-08, -1.35955434e-08, -2.33964922e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5497436523438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28863, + 'frame_number': 28863, + 'framesequence': 116764, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.752138197422, + 'timestamp_carla': 985751, + 'timestamp_device': 2604309, + 'timestamp_stream': 985.752138197422, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61342770e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.69666925e-05, -3.67243374e-05, -5.34543876e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30171478]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-1.25528414e-08, -7.65207187e-09, 5.90324402e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5476684570312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28864, + 'frame_number': 28864, + 'framesequence': 116768, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.7847080975771, + 'timestamp_carla': 985784, + 'timestamp_device': 2604342, + 'timestamp_stream': 985.7847080975771, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61336437e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-9.90758849e-07, -1.94140216e-06, 1.76773707e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30172232]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 9.64502367e-10, 2.70071210e-09, -1.02462764e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5479125976562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28865, + 'frame_number': 28865, + 'framesequence': 116772, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.8193624988198, + 'timestamp_carla': 985818, + 'timestamp_device': 2604376, + 'timestamp_stream': 985.8193624988198, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61348715e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.01123494e-05, -2.37367403e-05, -5.04925524e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30170617]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-8.76467254e-09, -7.55650920e-09, 2.21252435e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5491943359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28866, + 'frame_number': 28866, + 'framesequence': 116776, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.8524672985077, + 'timestamp_carla': 985851, + 'timestamp_device': 2604409, + 'timestamp_stream': 985.8524672985077, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61343530e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-8.36944018e-05, 3.52906354e-05, -6.17341867e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30171606]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([4.44087753e-08, 7.75260247e-08, 3.43146326e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5467529296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28867, + 'frame_number': 28867, + 'framesequence': 116780, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.8858123980463, + 'timestamp_carla': 985885, + 'timestamp_device': 2604442, + 'timestamp_stream': 985.8858123980463, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61342084e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-1.64524899e-05, 8.36198160e-05, -1.68937877e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30169821]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([7.99600244e-08, 2.73048020e-08, 2.63805385e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5477905273438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28868, + 'frame_number': 28868, + 'framesequence': 116784, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.9186705984175, + 'timestamp_carla': 985918, + 'timestamp_device': 2604476, + 'timestamp_stream': 985.9186705984175, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61337733e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-8.24258314e-06, 7.53766153e-06, 1.80862596e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30170691]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-3.71432911e-08, -2.79772880e-08, -1.22327809e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5480346679688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28869, + 'frame_number': 28869, + 'framesequence': 116788, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.9528536982834, + 'timestamp_carla': 985952, + 'timestamp_device': 2604509, + 'timestamp_stream': 985.9528536982834, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61345288e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 9.95386017e-07, -3.36707421e-06, -3.36664230e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30171189]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-7.01812253e-09, -4.58437599e-09, 4.38189483e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5489501953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28870, + 'frame_number': 28870, + 'framesequence': 116792, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 985.985981900245, + 'timestamp_carla': 985985, + 'timestamp_device': 2604542, + 'timestamp_stream': 985.985981900245, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341473e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 1.11930331e-05, -1.55387770e-05, 1.65114127e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30170569]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-4.09711021e-08, -3.11339896e-08, -3.19576247e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5474243164062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28871, + 'frame_number': 28871, + 'framesequence': 116796, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.0185553990304, + 'timestamp_carla': 986018, + 'timestamp_device': 2604576, + 'timestamp_stream': 986.0185553990304, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61335215e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.87754046e-05, -3.26548325e-05, -1.06129217e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30170807]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-2.36600872e-08, -2.07482369e-08, 4.98676272e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28872, + 'frame_number': 28872, + 'framesequence': 116801, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.0536185987294, + 'timestamp_carla': 986053, + 'timestamp_device': 2604617, + 'timestamp_stream': 986.0536185987294, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61351010e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-9.31399627e-05, 4.85515920e-05, 1.52680233e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30170843]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-6.68183020e-09, 3.51503857e-08, 2.25744239e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494384765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28873, + 'frame_number': 28873, + 'framesequence': 116804, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.0855941995978, + 'timestamp_carla': 986085, + 'timestamp_device': 2604642, + 'timestamp_stream': 986.0855941995978, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61336660e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.07542835e-05, -2.36079559e-05, -2.83633028e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25370789, 158.29377747, 0.30169982]), + 'Rotation': array([-1.52586419e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-5.05563325e-09, -4.80266760e-09, 6.10179908e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462646484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55566406, 30. ]), + 'frame': 28874, + 'frame_number': 28874, + 'framesequence': 116808, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.118549797684, + 'timestamp_carla': 986118, + 'timestamp_device': 2604675, + 'timestamp_stream': 986.118549797684, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61335140e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0055651 , -0.0048632 , -0.00043987]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02178196981549263, + 'FR_Wheel_Angle': 0.021786391735076904, + 'Location': array([237.25349426, 158.29400635, 0.30171746]), + 'Rotation': array([-1.52859623e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-0.00053292, 0.00063912, 0.00035692]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5491333007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28875, + 'frame_number': 28875, + 'framesequence': 116812, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.1513317972422, + 'timestamp_carla': 986150, + 'timestamp_device': 2604709, + 'timestamp_stream': 986.1513317972422, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61333308e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 1.68796834e-02, 1.43259307e-02, -8.71845623e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([237.25238037, 158.29537964, 0.30170378]), + 'Rotation': array([-1.47395479e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-1.77858323e-02, 2.09435485e-02, -8.78715509e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494384765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28876, + 'frame_number': 28876, + 'framesequence': 116816, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.1853397004306, + 'timestamp_carla': 986184, + 'timestamp_device': 2604742, + 'timestamp_stream': 986.1853397004306, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341622e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-6.80054352e-03, -5.75389480e-03, 2.75162449e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.021765710785984993, + 'Location': array([237.24305725, 158.30636597, 0.30169079]), + 'Rotation': array([-1.33393584e-02, 1.30399445e+02, -6.95800735e-03]), + 'Velocity': array([-0.04645143, 0.05469932, -0.00015043]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5498046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28877, + 'frame_number': 28877, + 'framesequence': 116820, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.2205081991851, + 'timestamp_carla': 986219, + 'timestamp_device': 2604775, + 'timestamp_stream': 986.2205081991851, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61355734e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00868891, -0.00758855, -0.00024198]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021770643070340157, + 'FR_Wheel_Angle': 0.021776597946882248, + 'Location': array([237.23629761, 158.31434631, 0.3017053 ]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-0.01818316, 0.02141429, -0.00022088]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28878, + 'frame_number': 28878, + 'framesequence': 116824, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.2528373971581, + 'timestamp_carla': 986252, + 'timestamp_device': 2604809, + 'timestamp_stream': 986.2528373971581, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341861e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00631871, -0.00542173, -0.0003544 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02177821472287178, + 'FR_Wheel_Angle': 0.021783573552966118, + 'Location': array([237.23287964, 158.31835938, 0.30171543]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([-5.95697993e-03, 7.02365255e-03, 5.30052166e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5453491210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77734375, 15942.55566406, 30. ]), + 'frame': 28879, + 'frame_number': 28879, + 'framesequence': 116828, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.2858047969639, + 'timestamp_carla': 986285, + 'timestamp_device': 2604842, + 'timestamp_stream': 986.2858047969639, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61338121e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00579302, -0.00497038, -0.00038253]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021784182637929916, + 'FR_Wheel_Angle': 0.02178940363228321, + 'Location': array([237.23200989, 158.31939697, 0.30171585]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 0.00368288, -0.00432308, 0.0002808 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 29.99996948]), + 'frame': 28880, + 'frame_number': 28880, + 'framesequence': 116832, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.3175786994398, + 'timestamp_carla': 986317, + 'timestamp_device': 2604875, + 'timestamp_stream': 986.3175786994398, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61327899e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00578948, -0.00502652, -0.00048664]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02178298868238926, + 'FR_Wheel_Angle': 0.02178693190217018, + 'Location': array([237.23309326, 158.31814575, 0.30169791]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 0.01066481, -0.01253951, -0.00030613]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5488891601562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28881, + 'frame_number': 28881, + 'framesequence': 116836, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.35152919963, + 'timestamp_carla': 986350, + 'timestamp_device': 2604909, + 'timestamp_stream': 986.35152919963, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61338046e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00609744, -0.00531335, -0.00064119]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021779285743832588, + 'FR_Wheel_Angle': 0.021783320233225822, + 'Location': array([237.2355957 , 158.31518555, 0.30170828]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 0.01652565, -0.0194388 , 0.00011045]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5509033203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28882, + 'frame_number': 28882, + 'framesequence': 116840, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.3847773000598, + 'timestamp_carla': 986384, + 'timestamp_device': 2604942, + 'timestamp_stream': 986.3847773000598, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61338046e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00622717, -0.00553737, -0.0004913 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02177531085908413, + 'FR_Wheel_Angle': 0.021779492497444153, + 'Location': array([237.23953247, 158.31056213, 0.30171746]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 2.30498649e-02, -2.71180551e-02, 1.00135799e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5488891601562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28883, + 'frame_number': 28883, + 'framesequence': 116844, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.4183830991387, + 'timestamp_carla': 986417, + 'timestamp_device': 2604975, + 'timestamp_stream': 986.4183830991387, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341086e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00578735, -0.00517006, -0.00066476]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021771837025880814, + 'FR_Wheel_Angle': 0.021776102483272552, + 'Location': array([237.24494934, 158.30419922, 0.30170256]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 0.02890779, -0.03401216, -0.00035223]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5488891601562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28884, + 'frame_number': 28884, + 'framesequence': 116848, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.4521626979113, + 'timestamp_carla': 986451, + 'timestamp_device': 2605009, + 'timestamp_stream': 986.4521626979113, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344141e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00577323, -0.00507604, -0.00075087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02176906354725361, + 'FR_Wheel_Angle': 0.0217733196914196, + 'Location': array([237.2515564 , 158.29644775, 0.30170837]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 3.32783945e-02, -3.91572639e-02, 1.10626215e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5482788085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28885, + 'frame_number': 28885, + 'framesequence': 116852, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.4846011996269, + 'timestamp_carla': 986484, + 'timestamp_device': 2605042, + 'timestamp_stream': 986.4846011996269, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61336049e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00600134, -0.00505587, -0.00078165]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021767182275652885, + 'FR_Wheel_Angle': 0.021771587431430817, + 'Location': array([237.25901794, 158.28765869, 0.30170715]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 0.03637505, -0.04280171, -0.0001042 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5476684570312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28886, + 'frame_number': 28886, + 'framesequence': 116856, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.5174282975495, + 'timestamp_carla': 986516, + 'timestamp_device': 2605075, + 'timestamp_stream': 986.5174282975495, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61334068e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00584174, -0.00507321, -0.00079855]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.021765710785984993, + 'FR_Wheel_Angle': 0.021770143881440163, + 'Location': array([237.26593018, 158.2795105 , 0.30170608]), + 'Rotation': array([-1.61465667e-02, 1.30399445e+02, -6.95800781e-03]), + 'Velocity': array([ 3.83773670e-02, -4.51592728e-02, 2.82573692e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5492553710938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28887, + 'frame_number': 28887, + 'framesequence': 116860, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.5516975000501, + 'timestamp_carla': 986551, + 'timestamp_device': 2605109, + 'timestamp_stream': 986.5516975000501, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344066e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0086842 , -0.00203203, 0.02847566]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7964950799942017, + 'FR_Wheel_Angle': -1.6395236253738403, + 'Location': array([237.2756958 , 158.26799011, 0.30170801]), + 'Rotation': array([-1.61465667e-02, 1.30399780e+02, -6.98852399e-03]), + 'Velocity': array([ 0.03996059, -0.04814208, 0.00024835]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5496826171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28888, + 'frame_number': 28888, + 'framesequence': 116865, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.5875591002405, + 'timestamp_carla': 986587, + 'timestamp_device': 2605150, + 'timestamp_stream': 986.5875591002405, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61362842e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0308735 , 0.00978792, 0.18566939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.202383041381836, + 'FR_Wheel_Angle': -8.490808486938477, + 'Location': array([237.28425598, 158.25714111, 0.30171439]), + 'Rotation': array([-1.62695106e-02, 1.30419479e+02, -7.56835844e-03]), + 'Velocity': array([ 0.04020152, -0.05928177, 0.00045452]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5476684570312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28889, + 'frame_number': 28889, + 'framesequence': 116869, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.6270073987544, + 'timestamp_carla': 986626, + 'timestamp_device': 2605184, + 'timestamp_stream': 986.6270073987544, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61406711e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00888569, 0.02170849, 1.82340217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.10346221923828, + 'FR_Wheel_Angle': -14.774733543395996, + 'Location': array([237.32598877, 158.1975708 , 0.301772 ]), + 'Rotation': array([-2.63918489e-02, 1.30714905e+02, -1.28784170e-02]), + 'Velocity': array([ 0.21172442, -0.3393822 , 0.00036602]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5438842773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77734375, 15942.5546875 , 30. ]), + 'frame': 28890, + 'frame_number': 28890, + 'framesequence': 116873, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.6550180986524, + 'timestamp_carla': 986654, + 'timestamp_device': 2605217, + 'timestamp_stream': 986.6550180986524, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61406711e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.06978746, -0.03207339, 3.27541447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.852466583251953, + 'FR_Wheel_Angle': -20.34466552734375, + 'Location': array([237.37495422, 158.12098694, 0.3017303 ]), + 'Rotation': array([-2.12692078e-02, 1.31281754e+02, -1.31835947e-02]), + 'Velocity': array([ 2.23386571e-01, -3.91368806e-01, -1.58615105e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5350952148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.78320312, 15942.54882812, 30.00006104]), + 'frame': 28891, + 'frame_number': 28891, + 'framesequence': 116877, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.6937447972596, + 'timestamp_carla': 986693, + 'timestamp_device': 2605250, + 'timestamp_stream': 986.6937447972596, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61416620e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.04999547, -0.04606703, 4.03153849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.51521873474121, + 'FR_Wheel_Angle': -25.33786964416504, + 'Location': array([237.42884827, 158.02746582, 0.30173305]), + 'Rotation': array([-1.95343401e-02, 1.32187027e+02, -1.38244601e-02]), + 'Velocity': array([ 2.26263180e-01, -4.51104611e-01, 4.37736480e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5350952148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.78320312, 15942.54882812, 30.00006104]), + 'frame': 28892, + 'frame_number': 28892, + 'framesequence': 116880, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.720607496798, + 'timestamp_carla': 986720, + 'timestamp_device': 2605275, + 'timestamp_stream': 986.720607496798, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61397785e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([0.01564207, 0.00667607, 6.32002926]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.5225944519043, + 'FR_Wheel_Angle': -28.75857162475586, + 'Location': array([237.48362732, 157.92277527, 0.30170771]), + 'Rotation': array([-1.85234714e-02, 1.33458344e+02, -1.40075684e-02]), + 'Velocity': array([ 2.07119286e-01, -4.94670004e-01, -3.56006611e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5331420898438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.78320312, 15942.54785156, 30. ]), + 'frame': 28893, + 'frame_number': 28893, + 'framesequence': 116884, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.7529150992632, + 'timestamp_carla': 986752, + 'timestamp_device': 2605309, + 'timestamp_stream': 986.7529150992632, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61356270e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.19975132e-02, -2.72980775e-03, 5.88960743e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.585670471191406, + 'FR_Wheel_Angle': -28.38453483581543, + 'Location': array([237.53894043, 157.81678772, 0.30169693]), + 'Rotation': array([-1.66588314e-02, 1.34861115e+02, -7.35473679e-03]), + 'Velocity': array([ 2.14431837e-01, -4.72426713e-01, -3.60412581e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5369262695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.78125 , 15942.54980469, 30. ]), + 'frame': 28894, + 'frame_number': 28894, + 'framesequence': 116888, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.7852580994368, + 'timestamp_carla': 986784, + 'timestamp_device': 2605342, + 'timestamp_stream': 986.7852580994368, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61332160e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-2.00464278e-02, 3.67166498e-03, 5.74455500e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.25132369995117, + 'FR_Wheel_Angle': -26.979612350463867, + 'Location': array([237.59361267, 157.71810913, 0.30170411]), + 'Rotation': array([-1.55318491e-02, 1.36179504e+02, -4.97436570e-03]), + 'Velocity': array([ 2.17988193e-01, -4.48486358e-01, 2.28328703e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452270507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77734375, 15942.55566406, 30. ]), + 'frame': 28895, + 'frame_number': 28895, + 'framesequence': 116892, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.817925799638, + 'timestamp_carla': 986817, + 'timestamp_device': 2605375, + 'timestamp_stream': 986.817925799638, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61321327e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.01266372, 0.01454081, 5.52871275]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.1823616027832, + 'FR_Wheel_Angle': -25.963756561279297, + 'Location': array([237.65550232, 157.61871338, 0.30172622]), + 'Rotation': array([-1.77926421e-02, 1.37413116e+02, -4.24194336e-03]), + 'Velocity': array([ 2.65675962e-01, -4.65342522e-01, 8.64744143e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.550048828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28896, + 'frame_number': 28896, + 'framesequence': 116896, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.8535369969904, + 'timestamp_carla': 986852, + 'timestamp_device': 2605409, + 'timestamp_stream': 986.8535369969904, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61339566e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([5.25544351e-03, 8.82954337e-03, 5.63040018e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.17252731323242, + 'FR_Wheel_Angle': -25.713212966918945, + 'Location': array([237.72279358, 157.51686096, 0.30171943]), + 'Rotation': array([-1.69661883e-02, 1.38678497e+02, -5.24902390e-03]), + 'Velocity': array([ 2.72761822e-01, -4.58606452e-01, 1.66606900e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5521850585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55957031, 30. ]), + 'frame': 28897, + 'frame_number': 28897, + 'framesequence': 116900, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.8855812996626, + 'timestamp_carla': 986884, + 'timestamp_device': 2605442, + 'timestamp_stream': 986.8855812996626, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61323547e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00882811, 0.01555643, 5.26100349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.335609436035156, + 'FR_Wheel_Angle': -25.729032516479492, + 'Location': array([237.79110718, 157.41825867, 0.3017008 ]), + 'Rotation': array([-1.49854338e-02, 1.39922394e+02, -4.02832078e-03]), + 'Velocity': array([ 2.63107896e-01, -4.27326620e-01, 1.79424285e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.548583984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28898, + 'frame_number': 28898, + 'framesequence': 116904, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.9198898971081, + 'timestamp_carla': 986919, + 'timestamp_device': 2605475, + 'timestamp_stream': 986.9198898971081, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61331788e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00807025, -0.01836862, 4.63399982]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.479671478271484, + 'FR_Wheel_Angle': -22.3432559967041, + 'Location': array([237.86485291, 157.31889343, 0.30170521]), + 'Rotation': array([-1.55660007e-02, 1.41147217e+02, -1.98364281e-03]), + 'Velocity': array([ 2.82982349e-01, -3.90669703e-01, 1.36528019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5517578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55957031, 30. ]), + 'frame': 28899, + 'frame_number': 28899, + 'framesequence': 116908, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.9515369981527, + 'timestamp_carla': 986950, + 'timestamp_device': 2605509, + 'timestamp_stream': 986.9515369981527, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61318362e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([0.02648473, 0.00696736, 4.34388542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.29623794555664, + 'FR_Wheel_Angle': -22.988252639770508, + 'Location': array([237.94256592, 157.22264099, 0.3017107 ]), + 'Rotation': array([-1.61465667e-02, 1.42258606e+02, -4.63867141e-03]), + 'Velocity': array([ 2.99882054e-01, -4.06700283e-01, 5.12409206e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.550048828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30.00003052]), + 'frame': 28900, + 'frame_number': 28900, + 'framesequence': 116912, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 986.9845348000526, + 'timestamp_carla': 986983, + 'timestamp_device': 2605542, + 'timestamp_stream': 986.9845348000526, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61320955e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0552585 , 0.04277252, 4.87859011]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.079809188842773, + 'FR_Wheel_Angle': -23.023601531982422, + 'Location': array([238.01591492, 157.13513184, 0.30171815]), + 'Rotation': array([-1.62353590e-02, 1.43292450e+02, -6.13403274e-03]), + 'Velocity': array([ 3.01607400e-01, -4.09327358e-01, 2.62274727e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5527954101562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77148438, 15942.56054688, 30. ]), + 'frame': 28901, + 'frame_number': 28901, + 'framesequence': 116916, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.0176838003099, + 'timestamp_carla': 987017, + 'timestamp_device': 2605575, + 'timestamp_stream': 987.0176838003099, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61324605e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.04486854, 0.03404023, 4.7439971 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.59283447265625, + 'FR_Wheel_Angle': -21.331226348876953, + 'Location': array([238.07958984, 157.06115723, 0.30169708]), + 'Rotation': array([-1.52244912e-02, 1.44185120e+02, -5.00488328e-03]), + 'Velocity': array([ 2.93317735e-01, -3.81968915e-01, 1.83362950e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5523071289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55957031, 30. ]), + 'frame': 28902, + 'frame_number': 28902, + 'framesequence': 116920, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.0513840988278, + 'timestamp_carla': 987050, + 'timestamp_device': 2605609, + 'timestamp_stream': 987.0513840988278, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61331788e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.01524674, -0.02845249, 3.63375258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.127674102783203, + 'FR_Wheel_Angle': -20.642887115478516, + 'Location': array([238.15231323, 156.98353577, 0.30170548]), + 'Rotation': array([-1.50469057e-02, 1.45035065e+02, -2.80761672e-03]), + 'Velocity': array([ 3.08899701e-01, -3.39802235e-01, 6.80446610e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5515747070312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55957031, 30. ]), + 'frame': 28903, + 'frame_number': 28903, + 'framesequence': 116924, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.0850197002292, + 'timestamp_carla': 987084, + 'timestamp_device': 2605642, + 'timestamp_stream': 987.0850197002292, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61335900e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([3.17814425e-02, 1.18001888e-03, 3.53554201e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.99388885498047, + 'FR_Wheel_Angle': -20.391403198242188, + 'Location': array([238.22869873, 156.90563965, 0.30171815]), + 'Rotation': array([-1.59553215e-02, 1.45889816e+02, -4.91333054e-03]), + 'Velocity': array([ 3.11437607e-01, -3.38630378e-01, 2.72145262e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.550048828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30.00003052]), + 'frame': 28904, + 'frame_number': 28904, + 'framesequence': 116928, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.1182252988219, + 'timestamp_carla': 987117, + 'timestamp_device': 2605675, + 'timestamp_stream': 987.1182252988219, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61335900e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.01772741, -0.01026512, 3.97514129]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.97723960876465, + 'FR_Wheel_Angle': -20.269145965576172, + 'Location': array([238.30584717, 156.82955933, 0.30171782]), + 'Rotation': array([-1.78882647e-02, 1.46738144e+02, -7.11059431e-03]), + 'Velocity': array([ 3.41884226e-01, -3.61396730e-01, 8.96263082e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54931640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28905, + 'frame_number': 28905, + 'framesequence': 116932, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.1514371968806, + 'timestamp_carla': 987150, + 'timestamp_device': 2605709, + 'timestamp_stream': 987.1514371968806, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61335900e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-3.00286282e-02, -3.01757292e-03, 4.08934021e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.762859344482422, + 'FR_Wheel_Angle': -16.727481842041016, + 'Location': array([238.38581848, 156.75437927, 0.30170727]), + 'Rotation': array([-1.66315101e-02, 1.47541183e+02, -3.96728609e-03]), + 'Velocity': array([ 3.50722700e-01, -3.39044571e-01, -6.28757480e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54931640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28906, + 'frame_number': 28906, + 'framesequence': 116936, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.1839928999543, + 'timestamp_carla': 987183, + 'timestamp_device': 2605742, + 'timestamp_stream': 987.1839928999543, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61331549e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([0.02584775, 0.00949598, 1.95069015]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.770000457763672, + 'FR_Wheel_Angle': -17.25727081298828, + 'Location': array([238.48738098, 156.66564941, 0.30170009]), + 'Rotation': array([-1.51083777e-02, 1.48405655e+02, -4.60815523e-03]), + 'Velocity': array([ 3.43330771e-01, -3.18912506e-01, -4.58049763e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54931640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28907, + 'frame_number': 28907, + 'framesequence': 116940, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.2180759981275, + 'timestamp_carla': 987217, + 'timestamp_device': 2605775, + 'timestamp_stream': 987.2180759981275, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61340788e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([2.94960830e-02, 3.67359025e-04, 2.95693493e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.7584171295166, + 'FR_Wheel_Angle': -17.42255401611328, + 'Location': array([238.57041931, 156.59509277, 0.30170393]), + 'Rotation': array([-1.56274717e-02, 1.49121155e+02, -5.46264648e-03]), + 'Velocity': array([ 3.42481405e-01, -3.08482498e-01, -1.22890473e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5501708984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28908, + 'frame_number': 28908, + 'framesequence': 116944, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.2514441981912, + 'timestamp_carla': 987250, + 'timestamp_device': 2605809, + 'timestamp_stream': 987.2514441981912, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61340788e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([0.03136958, 0.00721875, 1.3828603 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.918537139892578, + 'FR_Wheel_Angle': -15.264656066894531, + 'Location': array([238.64163208, 156.53633118, 0.30169597]), + 'Rotation': array([-1.44321891e-02, 1.49711349e+02, -4.60815430e-03]), + 'Velocity': array([ 3.23805928e-01, -2.82622159e-01, -1.32942194e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54833984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28909, + 'frame_number': 28909, + 'framesequence': 116948, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.2848690003157, + 'timestamp_carla': 987284, + 'timestamp_device': 2605842, + 'timestamp_stream': 987.2848690003157, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61340788e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-1.24324113e-04, -1.73357520e-02, 2.33566308e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.9820556640625, + 'FR_Wheel_Angle': -14.771783828735352, + 'Location': array([238.73953247, 156.4611969 , 0.30172595]), + 'Rotation': array([-1.91655103e-02, 1.50383606e+02, -6.71386719e-03]), + 'Velocity': array([ 4.08387303e-01, -3.24946165e-01, -4.99916059e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54833984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28910, + 'frame_number': 28910, + 'framesequence': 116952, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.3190151974559, + 'timestamp_carla': 987318, + 'timestamp_device': 2605875, + 'timestamp_stream': 987.3190151974559, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61346510e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.0229567 , -0.01134058, 2.45363927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.706567764282227, + 'FR_Wheel_Angle': -14.461454391479492, + 'Location': array([238.83251953, 156.39135742, 0.30169776]), + 'Rotation': array([-1.54157365e-02, 1.51010010e+02, -5.55420015e-03]), + 'Velocity': array([ 3.74522477e-01, -2.91516960e-01, -1.75666810e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54833984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28911, + 'frame_number': 28911, + 'framesequence': 116956, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.3514392971992, + 'timestamp_carla': 987350, + 'timestamp_device': 2605909, + 'timestamp_stream': 987.3514392971992, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61336973e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0035317 , 0.00379326, 1.86361825]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.635635375976562, + 'FR_Wheel_Angle': -14.255476951599121, + 'Location': array([238.92420959, 156.3243103 , 0.30171946]), + 'Rotation': array([-1.76082272e-02, 1.51614273e+02, -6.77490328e-03]), + 'Velocity': array([ 0.40491965, -0.31206533, 0.00054045]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5471801757812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28912, + 'frame_number': 28912, + 'framesequence': 116960, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.3845193982124, + 'timestamp_carla': 987383, + 'timestamp_device': 2605942, + 'timestamp_stream': 987.3845193982124, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61336973e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-4.03113721e-04, -3.84192704e-03, 6.63322866e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.43399715423584, + 'FR_Wheel_Angle': -10.431900024414062, + 'Location': array([239.01593018, 156.26098633, 0.30170849]), + 'Rotation': array([-1.53542645e-02, 1.52117615e+02, -3.38745071e-03]), + 'Velocity': array([ 3.89333218e-01, -2.67856449e-01, 7.65418954e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.549072265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28913, + 'frame_number': 28913, + 'framesequence': 116964, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.4191835001111, + 'timestamp_carla': 987418, + 'timestamp_device': 2605975, + 'timestamp_stream': 987.4191835001111, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61348954e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.03206453, -0.01127232, 2.96130061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.42719554901123, + 'FR_Wheel_Angle': -10.97704029083252, + 'Location': array([239.10877991, 156.20019531, 0.30170086]), + 'Rotation': array([-1.71847548e-02, 1.52571945e+02, -6.34765578e-03]), + 'Velocity': array([ 4.16896403e-01, -2.86010176e-01, -2.47840886e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.549072265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55761719, 30. ]), + 'frame': 28914, + 'frame_number': 28914, + 'framesequence': 116968, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.4524017982185, + 'timestamp_carla': 987451, + 'timestamp_device': 2606009, + 'timestamp_stream': 987.4524017982185, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344379e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([0.02558524, 0.00988012, 2.86274767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.45403003692627, + 'FR_Wheel_Angle': -11.171236991882324, + 'Location': array([239.20022583, 156.14117432, 0.30170372]), + 'Rotation': array([-1.48624908e-02, 1.53000580e+02, -5.85937547e-03]), + 'Velocity': array([ 3.67663115e-01, -2.46041954e-01, -1.28746033e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5466918945312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28915, + 'frame_number': 28915, + 'framesequence': 116972, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.4840446002781, + 'timestamp_carla': 987483, + 'timestamp_device': 2606042, + 'timestamp_stream': 987.4840446002781, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61330864e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([0.02077534, 0.00727233, 2.59901905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.20435619354248, + 'FR_Wheel_Angle': -8.482999801635742, + 'Location': array([239.29083252, 156.08398438, 0.30171084]), + 'Rotation': array([-1.55933211e-02, 1.53402771e+02, -5.15746931e-03]), + 'Velocity': array([ 3.76600862e-01, -2.39338353e-01, 6.77394855e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5475463867188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30.00003052]), + 'frame': 28916, + 'frame_number': 28916, + 'framesequence': 116976, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.5170184001327, + 'timestamp_carla': 987516, + 'timestamp_device': 2606075, + 'timestamp_stream': 987.5170184001327, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61332548e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00856354, 0.01679122, 2.42375159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.774230003356934, + 'FR_Wheel_Angle': -8.121463775634766, + 'Location': array([239.38218689, 156.03082275, 0.30171421]), + 'Rotation': array([-1.72120761e-02, 1.53679337e+02, -5.92040922e-03]), + 'Velocity': array([ 4.00141358e-01, -2.41349399e-01, -6.67381246e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55029296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28917, + 'frame_number': 28917, + 'framesequence': 116980, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.5510019995272, + 'timestamp_carla': 987550, + 'timestamp_device': 2606109, + 'timestamp_stream': 987.5510019995272, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341473e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.03164284, -0.00334526, 1.98320258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.413124084472656, + 'FR_Wheel_Angle': -7.793527126312256, + 'Location': array([239.46157837, 155.98490906, 0.30169794]), + 'Rotation': array([-1.52244912e-02, 1.53927277e+02, -6.34765625e-03]), + 'Velocity': array([ 3.85948569e-01, -2.32003778e-01, -5.51223729e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5499877929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28918, + 'frame_number': 28918, + 'framesequence': 116984, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.584044598043, + 'timestamp_carla': 987583, + 'timestamp_device': 2606142, + 'timestamp_stream': 987.584044598043, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61339492e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00435013, -0.00227318, 0.54296714]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.315412521362305, + 'FR_Wheel_Angle': -7.465745449066162, + 'Location': array([239.55935669, 155.92910767, 0.30172759]), + 'Rotation': array([-2.08457354e-02, 1.54232346e+02, -8.14819336e-03]), + 'Velocity': array([ 4.75004345e-01, -2.80929774e-01, -1.87110898e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28919, + 'frame_number': 28919, + 'framesequence': 116988, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.6177426986396, + 'timestamp_carla': 987616, + 'timestamp_device': 2606175, + 'timestamp_stream': 987.6177426986396, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61343306e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.02250345, 0.01289889, -0.6745379 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.0703179836273193, + 'FR_Wheel_Angle': -3.280639410018921, + 'Location': array([239.66093445, 155.87333679, 0.30170181]), + 'Rotation': array([-1.50195854e-02, 1.54474258e+02, -3.87573312e-03]), + 'Velocity': array([ 4.11804914e-01, -2.16876343e-01, -1.05657578e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.548583984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28920, + 'frame_number': 28920, + 'framesequence': 116992, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.6506382972002, + 'timestamp_carla': 987649, + 'timestamp_device': 2606208, + 'timestamp_stream': 987.6506382972002, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61339492e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00378127, -0.00813479, -0.66709602]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.988784074783325, + 'FR_Wheel_Angle': -3.787172317504883, + 'Location': array([239.75552368, 155.8243103 , 0.30169144]), + 'Rotation': array([-1.51630193e-02, 1.54617355e+02, -6.34765532e-03]), + 'Velocity': array([ 4.02926803e-01, -2.14179963e-01, -1.95016852e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5477905273438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28921, + 'frame_number': 28921, + 'framesequence': 116996, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.6863044984639, + 'timestamp_carla': 987685, + 'timestamp_device': 2606242, + 'timestamp_stream': 987.6863044984639, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61359251e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.00056375, 0.0029299 , -0.20216526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.111419677734375, + 'FR_Wheel_Angle': -4.0155229568481445, + 'Location': array([239.85871887, 155.77124023, 0.30171344]), + 'Rotation': array([-1.70276612e-02, 1.54787720e+02, -6.89697219e-03]), + 'Velocity': array([ 4.43004459e-01, -2.32342601e-01, 1.97601312e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.548583984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28922, + 'frame_number': 28922, + 'framesequence': 117000, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.7193029969931, + 'timestamp_carla': 987718, + 'timestamp_device': 2606275, + 'timestamp_stream': 987.7193029969931, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61348715e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([0.01689409, 0.00264914, 0.24083878]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.6872979402542114, + 'FR_Wheel_Angle': -0.6515756845474243, + 'Location': array([239.9586792 , 155.72026062, 0.30171236]), + 'Rotation': array([-1.66315101e-02, 1.54936554e+02, -6.16454938e-03]), + 'Velocity': array([ 4.35788602e-01, -2.19769210e-01, 5.90801210e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5446166992188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77734375, 15942.5546875 , 30. ]), + 'frame': 28923, + 'frame_number': 28923, + 'framesequence': 117004, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.7529673986137, + 'timestamp_carla': 987752, + 'timestamp_device': 2606308, + 'timestamp_stream': 987.7529673986137, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61347196e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0140795 , 0.01879015, -0.00608911]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5304034948348999, + 'FR_Wheel_Angle': -0.45452746748924255, + 'Location': array([240.05552673, 155.67474365, 0.30169979]), + 'Rotation': array([-1.40975099e-02, 1.54949371e+02, -5.34057617e-03]), + 'Velocity': array([ 3.89668643e-01, -1.82328418e-01, 2.27923389e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5467529296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28924, + 'frame_number': 28924, + 'framesequence': 117008, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.7859468981624, + 'timestamp_carla': 987785, + 'timestamp_device': 2606342, + 'timestamp_stream': 987.7859468981624, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341161e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00173184, 0.00298252, -1.13810885]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.123292937874794, + 'FR_Wheel_Angle': -0.09904658049345016, + 'Location': array([240.15335083, 155.62869263, 0.3017112 ]), + 'Rotation': array([-1.74852833e-02, 1.54940750e+02, -6.77490048e-03]), + 'Velocity': array([ 4.38541412e-01, -2.05714032e-01, -2.42671958e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5469970703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30.00003052]), + 'frame': 28925, + 'frame_number': 28925, + 'framesequence': 117012, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.8196582980454, + 'timestamp_carla': 987818, + 'timestamp_device': 2606375, + 'timestamp_stream': 987.8196582980454, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61343157e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00281543, -0.01550518, -0.74219769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0787474513053894, + 'FR_Wheel_Angle': 0.518575131893158, + 'Location': array([240.25334167, 155.58181763, 0.30169901]), + 'Rotation': array([-1.66315101e-02, 1.54949234e+02, -6.95800781e-03]), + 'Velocity': array([ 4.39793855e-01, -2.05025733e-01, 4.65583798e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5482788085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28926, + 'frame_number': 28926, + 'framesequence': 117016, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.8510659970343, + 'timestamp_carla': 987850, + 'timestamp_device': 2606408, + 'timestamp_stream': 987.8510659970343, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61328346e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.01467672, -0.04546419, 0.41979963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.940934658050537, + 'FR_Wheel_Angle': 4.73967981338501, + 'Location': array([240.3633728 , 155.53283691, 0.30171528]), + 'Rotation': array([-1.77926421e-02, 1.54858002e+02, -4.02832124e-03]), + 'Velocity': array([ 4.74281371e-01, -1.93955109e-01, -1.09596251e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5478515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28927, + 'frame_number': 28927, + 'framesequence': 117020, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.8839300982654, + 'timestamp_carla': 987883, + 'timestamp_device': 2606442, + 'timestamp_stream': 987.8839300982654, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61329955e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0002369 , 0.00177555, 0.15901694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.231836318969727, + 'FR_Wheel_Angle': 4.366661548614502, + 'Location': array([240.46618652, 155.48855591, 0.30169934]), + 'Rotation': array([-1.49239628e-02, 1.54703079e+02, -6.95800781e-03]), + 'Velocity': array([ 4.17297900e-01, -1.76427171e-01, 8.74805410e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5508422851562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28928, + 'frame_number': 28928, + 'framesequence': 117024, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.9172844998538, + 'timestamp_carla': 987916, + 'timestamp_device': 2606475, + 'timestamp_stream': 987.9172844998538, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61335066e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.0050165 , 0.00347645, -0.50353295]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.02288293838501, + 'FR_Wheel_Angle': 4.122958183288574, + 'Location': array([240.55496216, 155.44984436, 0.30167896]), + 'Rotation': array([-1.55045288e-02, 1.54566696e+02, -7.23266648e-03]), + 'Velocity': array([ 0.42629287, -0.18131857, -0.00048772]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5504760742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28929, + 'frame_number': 28929, + 'framesequence': 117028, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.9508886002004, + 'timestamp_carla': 987950, + 'timestamp_device': 2606508, + 'timestamp_stream': 987.9508886002004, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61340028e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.01455251, 0.02044934, -1.09628475]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.766875743865967, + 'FR_Wheel_Angle': 8.270918846130371, + 'Location': array([240.66691589, 155.40136719, 0.30170238]), + 'Rotation': array([-1.45892836e-02, 1.54372452e+02, -6.04247907e-03]), + 'Velocity': array([ 0.39845154, -0.15974276, 0.00043888]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494995117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28930, + 'frame_number': 28930, + 'framesequence': 117032, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 987.9848439991474, + 'timestamp_carla': 987984, + 'timestamp_device': 2606542, + 'timestamp_stream': 987.9848439991474, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61345676e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.03307899, -0.00664256, -1.37027335]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.291492938995361, + 'FR_Wheel_Angle': 8.046496391296387, + 'Location': array([240.76469421, 155.36164856, 0.30173171]), + 'Rotation': array([-1.84961520e-02, 1.54075333e+02, -6.28661970e-03]), + 'Velocity': array([ 4.69094604e-01, -1.88665688e-01, 7.96318054e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484619140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28931, + 'frame_number': 28931, + 'framesequence': 117036, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.0175300985575, + 'timestamp_carla': 988016, + 'timestamp_device': 2606575, + 'timestamp_stream': 988.0175300985575, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61339343e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.0053083 , 0.01214585, -0.65033984]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.6146111488342285, + 'FR_Wheel_Angle': 8.306654930114746, + 'Location': array([240.85386658, 155.32501221, 0.30172127]), + 'Rotation': array([-1.68773960e-02, 1.53816666e+02, -7.04956008e-03]), + 'Velocity': array([ 4.50720131e-01, -1.77869543e-01, 1.37591356e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54736328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28932, + 'frame_number': 28932, + 'framesequence': 117040, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.0510360002518, + 'timestamp_carla': 988050, + 'timestamp_device': 2606608, + 'timestamp_stream': 988.0510360002518, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341622e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.02400768, -0.01693776, -1.47107649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.855059623718262, + 'FR_Wheel_Angle': 9.139201164245605, + 'Location': array([240.96276855, 155.27973938, 0.30169013]), + 'Rotation': array([-1.58392079e-02, 1.53508774e+02, -7.29370024e-03]), + 'Velocity': array([ 4.58639324e-01, -1.79427922e-01, -3.37524398e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5487060546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 29.99996948]), + 'frame': 28933, + 'frame_number': 28933, + 'framesequence': 117044, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.0838177986443, + 'timestamp_carla': 988083, + 'timestamp_device': 2606642, + 'timestamp_stream': 988.0838177986443, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61337733e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-1.46086211e-03, 1.12340143e-02, -2.07921362e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.87426471710205, + 'FR_Wheel_Angle': 12.900764465332031, + 'Location': array([241.08638 , 155.23008728, 0.30171135]), + 'Rotation': array([-1.68159250e-02, 1.53031143e+02, -4.63867141e-03]), + 'Velocity': array([ 4.81123984e-01, -1.70972362e-01, -1.12371439e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28934, + 'frame_number': 28934, + 'framesequence': 117048, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.1170819997787, + 'timestamp_carla': 988116, + 'timestamp_device': 2606675, + 'timestamp_stream': 988.1170819997787, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61339104e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.00459762, -0.01972381, -1.74246645]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.356770515441895, + 'FR_Wheel_Angle': 12.643985748291016, + 'Location': array([241.18864441, 155.18948364, 0.30169657]), + 'Rotation': array([-1.41316606e-02, 1.52593063e+02, -7.78198196e-03]), + 'Velocity': array([ 4.29126471e-01, -1.59298286e-01, 6.48498535e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5489501953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28935, + 'frame_number': 28935, + 'framesequence': 117052, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.1518858969212, + 'timestamp_carla': 988151, + 'timestamp_device': 2606708, + 'timestamp_stream': 988.1518858969212, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61351919e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.03058677, -0.00595038, -2.132236 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.166434288024902, + 'FR_Wheel_Angle': 12.448431015014648, + 'Location': array([241.29394531, 155.14683533, 0.30170691]), + 'Rotation': array([-1.53542645e-02, 1.52137955e+02, -7.75146484e-03]), + 'Velocity': array([ 4.38621730e-01, -1.62932366e-01, 1.47819519e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5487060546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 29.99996948]), + 'frame': 28936, + 'frame_number': 28936, + 'framesequence': 117056, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.183389198035, + 'timestamp_carla': 988182, + 'timestamp_device': 2606742, + 'timestamp_stream': 988.183389198035, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61335066e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.01649314, -0.08720095, -2.2750597 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.658145904541016, + 'FR_Wheel_Angle': 16.700288772583008, + 'Location': array([241.39659119, 155.10498047, 0.30172566]), + 'Rotation': array([-1.88581515e-02, 1.51666794e+02, -4.76074312e-03]), + 'Velocity': array([ 5.24705470e-01, -1.89390928e-01, 8.81957967e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5460815429688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55566406, 30. ]), + 'frame': 28937, + 'frame_number': 28937, + 'framesequence': 117060, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.2176245003939, + 'timestamp_carla': 988216, + 'timestamp_device': 2606775, + 'timestamp_stream': 988.2176245003939, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344826e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00420994, 0.00180844, -1.46780705]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.044198989868164, + 'FR_Wheel_Angle': 16.414216995239258, + 'Location': array([241.5065918 , 155.06211853, 0.30170366]), + 'Rotation': array([-1.55933211e-02, 1.51031097e+02, -7.44628999e-03]), + 'Velocity': array([ 4.59844768e-01, -1.66802093e-01, 9.09805312e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494995117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28938, + 'frame_number': 28938, + 'framesequence': 117064, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.2508247978985, + 'timestamp_carla': 988250, + 'timestamp_device': 2606808, + 'timestamp_stream': 988.2508247978985, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61342382e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.0063888 , 0.01495461, -0.95626825]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.346220970153809, + 'FR_Wheel_Angle': 16.645870208740234, + 'Location': array([241.59176636, 155.02787781, 0.30167156]), + 'Rotation': array([-1.37286792e-02, 1.50556625e+02, -8.94165039e-03]), + 'Velocity': array([ 0.39832309, -0.14889291, -0.00054323]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5475463867188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28939, + 'frame_number': 28939, + 'framesequence': 117068, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.2844840995967, + 'timestamp_carla': 988283, + 'timestamp_device': 2606842, + 'timestamp_stream': 988.2844840995967, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344379e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.00390047, 0.0114135 , -2.4897759 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.636643409729004, + 'FR_Wheel_Angle': 17.6556339263916, + 'Location': array([241.70559692, 154.9806366 , 0.30170771]), + 'Rotation': array([-1.58938486e-02, 1.49892731e+02, -7.99560547e-03]), + 'Velocity': array([ 0.42498302, -0.16264217, 0.00044262]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5480346679688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28940, + 'frame_number': 28940, + 'framesequence': 117072, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.3170281983912, + 'timestamp_carla': 988316, + 'timestamp_device': 2606875, + 'timestamp_stream': 988.3170281983912, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61337271e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.0209284 , -0.02122282, -3.08666062]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.98020362854004, + 'FR_Wheel_Angle': 21.064895629882812, + 'Location': array([241.78468323, 154.94889832, 0.30169815]), + 'Rotation': array([-1.44936610e-02, 1.49366943e+02, -6.22558501e-03]), + 'Velocity': array([ 4.02176052e-01, -1.35121852e-01, -1.78804388e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5475463867188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30.00003052]), + 'frame': 28941, + 'frame_number': 28941, + 'framesequence': 117076, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.3508271984756, + 'timestamp_carla': 988350, + 'timestamp_device': 2606908, + 'timestamp_stream': 988.3508271984756, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61342546e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.00539262, -0.00348882, -2.26249146]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.58505630493164, + 'FR_Wheel_Angle': 20.91028594970703, + 'Location': array([241.89804077, 154.90318298, 0.30170822]), + 'Rotation': array([-1.68773960e-02, 1.48579193e+02, -7.08007859e-03]), + 'Velocity': array([ 4.38809603e-01, -1.60738021e-01, -1.74551009e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5490112304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28942, + 'frame_number': 28942, + 'framesequence': 117080, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.3838883973658, + 'timestamp_carla': 988383, + 'timestamp_device': 2606942, + 'timestamp_stream': 988.3838883973658, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61339954e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.00551659, -0.01136408, -1.95961869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.435415267944336, + 'FR_Wheel_Angle': 20.816865921020508, + 'Location': array([241.99324036, 154.86334229, 0.30170962]), + 'Rotation': array([-1.55045288e-02, 1.47912704e+02, -8.20922945e-03]), + 'Velocity': array([ 0.41406444, -0.15667996, 0.00042296]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5479125976562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30.00003052]), + 'frame': 28943, + 'frame_number': 28943, + 'framesequence': 117084, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.417313799262, + 'timestamp_carla': 988416, + 'timestamp_device': 2606975, + 'timestamp_stream': 988.417313799262, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341250e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.05900071, -0.03858312, -4.13964939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.981786727905273, + 'FR_Wheel_Angle': 25.44426727294922, + 'Location': array([242.09138489, 154.82170105, 0.30172893]), + 'Rotation': array([-1.87693592e-02, 1.47172684e+02, -4.05883836e-03]), + 'Velocity': array([ 4.74278033e-01, -1.63458675e-01, 2.38733293e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5485229492188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28944, + 'frame_number': 28944, + 'framesequence': 117088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.4538060985506, + 'timestamp_carla': 988453, + 'timestamp_device': 2607008, + 'timestamp_stream': 988.4538060985506, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61367416e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.01315779, -0.01005549, -3.63791347]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.0655574798584, + 'FR_Wheel_Angle': 24.84768295288086, + 'Location': array([242.20343018, 154.77558899, 0.30171767]), + 'Rotation': array([-1.80043783e-02, 1.46203598e+02, -6.80541852e-03]), + 'Velocity': array([ 5.02556086e-01, -1.90996170e-01, -1.09252927e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5482177734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28945, + 'frame_number': 28945, + 'framesequence': 117092, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.485011998564, + 'timestamp_carla': 988484, + 'timestamp_device': 2607042, + 'timestamp_stream': 988.485011998564, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61341399e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 1.23062963e-03, -2.55663339e-02, -3.25117636e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.28287124633789, + 'FR_Wheel_Angle': 24.991474151611328, + 'Location': array([242.31242371, 154.72822571, 0.3017107 ]), + 'Rotation': array([-1.64197739e-02, 1.45245041e+02, -8.11767671e-03]), + 'Velocity': array([ 4.87504572e-01, -1.89488918e-01, 2.99639709e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5430297851562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77734375, 15942.55371094, 30. ]), + 'frame': 28946, + 'frame_number': 28946, + 'framesequence': 117096, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.5180079974234, + 'timestamp_carla': 988517, + 'timestamp_device': 2607075, + 'timestamp_stream': 988.5180079974234, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61337882e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 2.36917846e-03, 1.74528304e-02, -2.46925378e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.69290542602539, + 'FR_Wheel_Angle': 26.3068904876709, + 'Location': array([242.41571045, 154.68162537, 0.30170348]), + 'Rotation': array([-1.45209813e-02, 1.44370026e+02, -9.67407320e-03]), + 'Velocity': array([ 4.24033761e-01, -1.71405077e-01, 2.08287238e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5482177734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28947, + 'frame_number': 28947, + 'framesequence': 117100, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.5507556982338, + 'timestamp_carla': 988550, + 'timestamp_device': 2607108, + 'timestamp_stream': 988.5507556982338, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61334231e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-6.54579559e-03, -8.68720061e-04, -3.45215464e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.425823211669922, + 'FR_Wheel_Angle': 29.17750358581543, + 'Location': array([242.49557495, 154.6464386 , 0.30169493]), + 'Rotation': array([-1.44048678e-02, 1.43604568e+02, -6.80542039e-03]), + 'Velocity': array([ 4.08416212e-01, -1.50775611e-01, -1.41839977e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5488891601562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28948, + 'frame_number': 28948, + 'framesequence': 117104, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.5855956971645, + 'timestamp_carla': 988584, + 'timestamp_device': 2607142, + 'timestamp_stream': 988.5855956971645, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61348566e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.00722989, 0.03583709, -3.0097692 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.17652702331543, + 'FR_Wheel_Angle': 29.18541717529297, + 'Location': array([242.61351013, 154.59307861, 0.30170646]), + 'Rotation': array([-1.62080377e-02, 1.42442917e+02, -8.36181641e-03]), + 'Velocity': array([ 4.30194348e-01, -1.73166573e-01, 1.50165550e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5496215820312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28949, + 'frame_number': 28949, + 'framesequence': 117108, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.6183849982917, + 'timestamp_carla': 988617, + 'timestamp_device': 2607175, + 'timestamp_stream': 988.6183849982917, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61340863e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-1.35316781e-03, 1.04166130e-02, -4.39636803e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.056554794311523, + 'FR_Wheel_Angle': 29.136533737182617, + 'Location': array([242.71305847, 154.54594421, 0.30171534]), + 'Rotation': array([-1.72120761e-02, 1.41432953e+02, -7.41577242e-03]), + 'Velocity': array([ 4.51216310e-01, -1.88128754e-01, 8.07380638e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5467529296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28950, + 'frame_number': 28950, + 'framesequence': 117112, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.6515036970377, + 'timestamp_carla': 988650, + 'timestamp_device': 2607208, + 'timestamp_stream': 988.6515036970377, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61338881e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.02764678, -0.02725781, -4.71033192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.675918579101562, + 'FR_Wheel_Angle': 34.170684814453125, + 'Location': array([242.79559326, 154.5057373 , 0.30170679]), + 'Rotation': array([-1.55933211e-02, 1.40573257e+02, -7.59887835e-03]), + 'Velocity': array([ 4.29103971e-01, -1.73884585e-01, 4.01315687e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5482788085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28951, + 'frame_number': 28951, + 'framesequence': 117116, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.6849268004298, + 'timestamp_carla': 988684, + 'timestamp_device': 2607242, + 'timestamp_stream': 988.6849268004298, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61340028e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.01183497, -0.01991841, -4.61675835]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.5526065826416, + 'FR_Wheel_Angle': 33.31586837768555, + 'Location': array([242.88685608, 154.46253967, 0.30169716]), + 'Rotation': array([-1.53201139e-02, 1.39517120e+02, -8.66699312e-03]), + 'Velocity': array([ 4.01238441e-01, -1.65798962e-01, -8.70704607e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5487060546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28952, + 'frame_number': 28952, + 'framesequence': 117120, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.7182267978787, + 'timestamp_carla': 988717, + 'timestamp_device': 2607275, + 'timestamp_stream': 988.7182267978787, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61340028e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.05873809, -0.03554953, -5.82072163]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.6765079498291, + 'FR_Wheel_Angle': 33.33194351196289, + 'Location': array([242.98501587, 154.41343689, 0.30172387]), + 'Rotation': array([-2.01763771e-02, 1.38368973e+02, -3.84521461e-03]), + 'Velocity': array([ 4.89622593e-01, -2.01365426e-01, -3.16524493e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484619140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28953, + 'frame_number': 28953, + 'framesequence': 117124, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.7504699975252, + 'timestamp_carla': 988749, + 'timestamp_device': 2607308, + 'timestamp_stream': 988.7504699975252, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61332548e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.01448637, 0.01304454, -5.30200148]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.213075637817383, + 'FR_Wheel_Angle': 34.99065017700195, + 'Location': array([243.09098816, 154.35778809, 0.30171153]), + 'Rotation': array([-1.63309816e-02, 1.37127777e+02, -9.12475586e-03]), + 'Velocity': array([ 4.50255722e-01, -2.07449943e-01, 2.54087441e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484619140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28954, + 'frame_number': 28954, + 'framesequence': 117128, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.7852410003543, + 'timestamp_carla': 988784, + 'timestamp_device': 2607342, + 'timestamp_stream': 988.7852410003543, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61347583e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.07663886, -0.12102474, -6.21007061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.487546920776367, + 'FR_Wheel_Angle': 37.275115966796875, + 'Location': array([243.18736267, 154.30705261, 0.3017002 ]), + 'Rotation': array([-1.58392079e-02, 1.35900452e+02, -7.17163226e-03]), + 'Velocity': array([ 4.60951746e-01, -1.96159095e-01, -7.97271696e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5499877929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28955, + 'frame_number': 28955, + 'framesequence': 117132, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.8185137994587, + 'timestamp_carla': 988817, + 'timestamp_device': 2607375, + 'timestamp_stream': 988.8185137994587, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61344290e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.02288834, 0.05404834, -5.32365131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.366121292114258, + 'FR_Wheel_Angle': 37.45437240600586, + 'Location': array([243.28588867, 154.25326538, 0.30170828]), + 'Rotation': array([-1.65085662e-02, 1.34626480e+02, -7.93457124e-03]), + 'Velocity': array([ 4.30545747e-01, -2.05675542e-01, 1.12819671e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5469360351562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28956, + 'frame_number': 28956, + 'framesequence': 117136, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.8524839989841, + 'timestamp_carla': 988851, + 'timestamp_device': 2607408, + 'timestamp_stream': 988.8524839989841, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61347494e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.02632443, 0.03064097, -5.04713726]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.26469612121582, + 'FR_Wheel_Angle': 37.47704315185547, + 'Location': array([243.37886047, 154.20062256, 0.30169886]), + 'Rotation': array([-1.58938486e-02, 1.33378754e+02, -9.36889835e-03]), + 'Velocity': array([ 4.11034435e-01, -2.09161848e-01, -1.61046977e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5475463867188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30.00003052]), + 'frame': 28957, + 'frame_number': 28957, + 'framesequence': 117140, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.8849900998175, + 'timestamp_carla': 988884, + 'timestamp_device': 2607442, + 'timestamp_stream': 988.8849900998175, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61338493e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.03510869, -0.03003627, -6.11214972]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.797761917114258, + 'FR_Wheel_Angle': 41.691497802734375, + 'Location': array([243.47175598, 154.14605713, 0.30170795]), + 'Rotation': array([-1.55933211e-02, 1.32088959e+02, -7.78198196e-03]), + 'Velocity': array([ 4.14691150e-01, -1.97883055e-01, 1.26910207e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5469970703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28958, + 'frame_number': 28958, + 'framesequence': 117144, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.9175694994628, + 'timestamp_carla': 988916, + 'timestamp_device': 2607475, + 'timestamp_stream': 988.9175694994628, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61333844e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.06015127, -0.05495524, -6.72113085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.783281326293945, + 'FR_Wheel_Angle': 41.66019821166992, + 'Location': array([243.56211853, 154.09326172, 0.3017168 ]), + 'Rotation': array([-1.76423769e-02, 1.30733032e+02, -5.49316453e-03]), + 'Velocity': array([ 4.38772649e-01, -2.06795618e-01, 2.63500206e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5487670898438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28959, + 'frame_number': 28959, + 'framesequence': 117148, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.952013798058, + 'timestamp_carla': 988951, + 'timestamp_device': 2607508, + 'timestamp_stream': 988.952013798058, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61345512e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.01092748, -0.07030144, -7.03054571]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76862335205078, + 'FR_Wheel_Angle': 41.64042663574219, + 'Location': array([243.67036438, 154.02745056, 0.30171746]), + 'Rotation': array([-1.77926421e-02, 1.29068619e+02, -6.86645601e-03]), + 'Velocity': array([ 4.65955645e-01, -2.47809038e-01, 1.02930069e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5497436523438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7734375 , 15942.55859375, 30. ]), + 'frame': 28960, + 'frame_number': 28960, + 'framesequence': 117153, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 988.9860238991678, + 'timestamp_carla': 988985, + 'timestamp_device': 2607550, + 'timestamp_stream': 988.9860238991678, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61348641e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 0.0250059 , -0.03036054, -6.46582079]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.791885375976562, + 'FR_Wheel_Angle': 41.68281555175781, + 'Location': array([243.75157166, 153.97453308, 0.30169258]), + 'Rotation': array([-1.58938486e-02, 1.27805359e+02, -1.01013184e-02]), + 'Velocity': array([ 4.16293055e-01, -2.32480496e-01, -2.80370703e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54736328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28961, + 'frame_number': 28961, + 'framesequence': 117156, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.0189778991044, + 'timestamp_carla': 989018, + 'timestamp_device': 2607575, + 'timestamp_stream': 989.0189778991044, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61342308e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([ 8.97850469e-03, -2.46667187e-04, -5.44613981e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80801773071289, + 'FR_Wheel_Angle': 41.7023811340332, + 'Location': array([243.83442688, 153.91784668, 0.30168837]), + 'Rotation': array([-1.45892836e-02, 1.26498131e+02, -1.16271982e-02]), + 'Velocity': array([ 3.59076649e-01, -2.14251831e-01, -2.18877787e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5467529296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30. ]), + 'frame': 28962, + 'frame_number': 28962, + 'framesequence': 117161, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.0558454990387, + 'timestamp_carla': 989055, + 'timestamp_device': 2607617, + 'timestamp_stream': 989.0558454990387, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61370844e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.08954181, 0.04791832, -5.60449886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77705955505371, + 'FR_Wheel_Angle': 41.651397705078125, + 'Location': array([243.9250946, 153.8522644, 0.3017157]), + 'Rotation': array([-1.82775855e-02, 1.25040359e+02, -6.98852446e-03]), + 'Velocity': array([ 3.99719238e-01, -2.76890934e-01, -1.87873829e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5480346679688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55761719, 30. ]), + 'frame': 28963, + 'frame_number': 28963, + 'framesequence': 117164, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.0877601988614, + 'timestamp_carla': 989087, + 'timestamp_device': 2607642, + 'timestamp_stream': 989.0877601988614, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61347121e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.05029051, 0.08438434, -5.59758139]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.785856246948242, + 'FR_Wheel_Angle': 41.66667556762695, + 'Location': array([244.0018158 , 153.79469299, 0.30171522]), + 'Rotation': array([-1.80658493e-02, 1.23773087e+02, -7.35473679e-03]), + 'Velocity': array([ 4.00482178e-01, -2.75645852e-01, -1.86700810e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5422973632812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77734375, 15942.55371094, 30. ]), + 'frame': 28964, + 'frame_number': 28964, + 'framesequence': 117169, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.1221276968718, + 'timestamp_carla': 989121, + 'timestamp_device': 2607683, + 'timestamp_stream': 989.1221276968718, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61350548e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.06071666, 0.06124814, -6.03831291]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7779483795166, + 'FR_Wheel_Angle': 41.659934997558594, + 'Location': array([244.10177612, 153.71582031, 0.30170512]), + 'Rotation': array([-1.68432463e-02, 1.22092781e+02, -9.30786040e-03]), + 'Velocity': array([ 3.96794349e-01, -2.94590920e-01, -6.07490529e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5469970703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55664062, 30.00003052]), + 'frame': 28965, + 'frame_number': 28965, + 'framesequence': 117173, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.156959798187, + 'timestamp_carla': 989156, + 'timestamp_device': 2607716, + 'timestamp_stream': 989.156959798187, + 'transform': [array([ 3.35143402e+02, 5.48899498e+01, -1.61355972e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52587835e-02])]} +{'AngularVelocity': array([-0.04506474, 0.08129752, -5.37219715]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79182243347168, + 'FR_Wheel_Angle': 41.677101135253906, + 'Location': array([244.18457031, 153.64686584, 0.30170971]), + 'Rotation': array([-1.62080377e-02, 1.20679214e+02, -1.04370108e-02]), + 'Velocity': array([ 0.3684777 , -0.28574902, 0.00043989]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54638671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77539062, 15942.55566406, 30. ]), + 'frame': 28966, + 'frame_number': 28966, + 'framesequence': 117176, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0317387655377388, + 'timestamp': 989.1857637986541, + 'timestamp_carla': 989185, + 'timestamp_device': 2607741, + 'timestamp_stream': 989.1857637986541, + 'transform': [array([ 3.35143463e+02, 5.48898430e+01, -1.61004603e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.54113723e-02])]} +{'AngularVelocity': array([-0.0526518, 0.104463 , -5.4484024]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79460906982422, + 'FR_Wheel_Angle': 41.683082580566406, + 'Location': array([244.26527405, 153.57627869, 0.30170882]), + 'Rotation': array([-1.61124151e-02, 1.19269577e+02, -1.05896015e-02]), + 'Velocity': array([ 3.51888329e-01, -2.89581150e-01, 2.54774088e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452880859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77734375, 15942.55566406, 30. ]), + 'frame': 28967, + 'frame_number': 28967, + 'framesequence': 117181, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0476234070956707, + 'timestamp': 989.2208082973957, + 'timestamp_carla': 989220, + 'timestamp_device': 2607783, + 'timestamp_stream': 989.2208082973957, + 'transform': [array([ 3.35143494e+02, 5.48898239e+01, -1.60995677e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.54113723e-02])]} +{'AngularVelocity': array([-0.05473916, 0.04750066, -5.71505594]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.780075073242188, + 'FR_Wheel_Angle': 41.66688919067383, + 'Location': array([244.34216309, 153.50570679, 0.30171555]), + 'Rotation': array([-1.73076987e-02, 1.17887352e+02, -8.48388951e-03]), + 'Velocity': array([ 3.68481904e-01, -3.16498220e-01, -7.96508757e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5393676757812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7890625 , 15942.54101562, 30. ]), + 'frame': 28968, + 'frame_number': 28968, + 'framesequence': 117185, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.255096398294, + 'timestamp_carla': 989254, + 'timestamp_device': 2607816, + 'timestamp_stream': 989.255096398294, + 'transform': [array([ 3.35143463e+02, 5.48898735e+01, -1.61286652e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([-0.03779103, 0.05343741, -5.49457788]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.789064407348633, + 'FR_Wheel_Angle': 41.66971969604492, + 'Location': array([244.42036438, 153.43028259, 0.30172005]), + 'Rotation': array([-1.67544540e-02, 1.16458076e+02, -9.15527344e-03]), + 'Velocity': array([ 0.35572696, -0.31707612, 0.00042405]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5411376953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.7890625 , 15942.54003906, 30. ]), + 'frame': 28969, + 'frame_number': 28969, + 'framesequence': 117188, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.2855507992208, + 'timestamp_carla': 989284, + 'timestamp_device': 2607841, + 'timestamp_stream': 989.2855507992208, + 'transform': [array([ 3.35143402e+02, 5.48899384e+01, -1.61254272e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 0.00730494, 0.00820455, -5.54077339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.796340942382812, + 'FR_Wheel_Angle': 41.687347412109375, + 'Location': array([244.4957428 , 153.35319519, 0.30170029]), + 'Rotation': array([-1.62353590e-02, 1.15047005e+02, -1.02233868e-02]), + 'Velocity': array([ 3.38148057e-01, -3.09322536e-01, -2.05001823e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5438842773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.78320312, 15942.546875 , 30. ]), + 'frame': 28970, + 'frame_number': 28970, + 'framesequence': 117193, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.3205659985542, + 'timestamp_carla': 989319, + 'timestamp_device': 2607883, + 'timestamp_stream': 989.3205659985542, + 'transform': [array([ 3.35143280e+02, 5.48900566e+01, -1.61267996e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([-0.0128904 , 0.05794393, -5.54524183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.793533325195312, + 'FR_Wheel_Angle': 41.68601989746094, + 'Location': array([244.56564331, 153.27761841, 0.30170527]), + 'Rotation': array([-1.68159250e-02, 1.13704987e+02, -8.91113281e-03]), + 'Velocity': array([ 3.25417966e-01, -3.16970795e-01, -8.07189936e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5503540039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.77148438, 15942.55761719, 30. ]), + 'frame': 28971, + 'frame_number': 28971, + 'framesequence': 117196, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.3525668978691, + 'timestamp_carla': 989351, + 'timestamp_device': 2607908, + 'timestamp_stream': 989.3525668978691, + 'transform': [array([ 3.35143188e+02, 5.48901825e+01, -1.61253735e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 0.0070712 , -0.08143178, -6.60755873]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81531524658203, + 'FR_Wheel_Angle': 41.70040512084961, + 'Location': array([244.63102722, 153.2023468 , 0.30170295]), + 'Rotation': array([-1.55660007e-02, 1.12409584e+02, -1.00402823e-02]), + 'Velocity': array([ 3.11162263e-01, -3.11825991e-01, 5.28049459e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.547607421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.76171875, 15942.56738281, 30. ]), + 'frame': 28972, + 'frame_number': 28972, + 'framesequence': 117200, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.3846273981035, + 'timestamp_carla': 989384, + 'timestamp_device': 2607941, + 'timestamp_stream': 989.3846273981035, + 'transform': [array([ 3.35143066e+02, 5.48903198e+01, -1.61246493e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 0.03762998, -0.09871519, -6.6470437 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.787254333496094, + 'FR_Wheel_Angle': 41.670833587646484, + 'Location': array([244.6975708 , 153.12362671, 0.30171448]), + 'Rotation': array([-1.80043783e-02, 1.11062431e+02, -5.61523438e-03]), + 'Velocity': array([ 3.43947262e-01, -3.37289304e-01, 2.48050692e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5504760742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.75195312, 15942.58203125, 30. ]), + 'frame': 28973, + 'frame_number': 28973, + 'framesequence': 117204, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.4172209985554, + 'timestamp_carla': 989416, + 'timestamp_device': 2607975, + 'timestamp_stream': 989.4172209985554, + 'transform': [array([ 3.35142975e+02, 5.48904572e+01, -1.61246866e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 0.01261308, -0.01376811, -6.54601383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77778434753418, + 'FR_Wheel_Angle': 41.66108322143555, + 'Location': array([244.76667786, 153.03781128, 0.3017177 ]), + 'Rotation': array([-1.81546416e-02, 1.09631836e+02, -7.53784226e-03]), + 'Velocity': array([ 3.35066229e-01, -3.68346006e-01, 6.34956377e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5518798828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.74023438, 15942.59667969, 30. ]), + 'frame': 28974, + 'frame_number': 28974, + 'framesequence': 117208, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.4513627998531, + 'timestamp_carla': 989450, + 'timestamp_device': 2608008, + 'timestamp_stream': 989.4513627998531, + 'transform': [array([ 3.35142853e+02, 5.48906136e+01, -1.61259681e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 0.00920846, 0.0153576 , -5.59529734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79610824584961, + 'FR_Wheel_Angle': 41.68217086791992, + 'Location': array([244.8314209 , 152.95314026, 0.30170009]), + 'Rotation': array([-1.54157365e-02, 1.08245132e+02, -1.06201172e-02]), + 'Velocity': array([ 2.90860564e-01, -3.35300028e-01, -3.70216367e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5518188476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.72851562, 15942.61035156, 29.99996948]), + 'frame': 28975, + 'frame_number': 28975, + 'framesequence': 117212, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.051590751856565475, + 'timestamp': 989.4856958985329, + 'timestamp_carla': 989485, + 'timestamp_device': 2608041, + 'timestamp_stream': 989.4856958985329, + 'transform': [array([ 3.35142731e+02, 5.48907700e+01, -1.61268726e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 0.03388207, -0.0576935 , -6.492661 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.789602279663086, + 'FR_Wheel_Angle': 41.67324447631836, + 'Location': array([244.89515686, 152.86637878, 0.30170923]), + 'Rotation': array([-1.65700372e-02, 1.06829193e+02, -8.54492188e-03]), + 'Velocity': array([ 0.30678418, -0.35279372, 0.00045878]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5492553710938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.71875 , 15942.62402344, 29.99996948]), + 'frame': 28976, + 'frame_number': 28976, + 'framesequence': 117216, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.027771420776844025, + 'timestamp': 989.517386097461, + 'timestamp_carla': 989516, + 'timestamp_device': 2608075, + 'timestamp_stream': 989.517386097461, + 'transform': [array([ 3.35142609e+02, 5.48909073e+01, -1.61254883e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([-0.0166135 , -0.09157513, -7.12943697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.788166046142578, + 'FR_Wheel_Angle': 41.649269104003906, + 'Location': array([244.95565796, 152.77987671, 0.30171555]), + 'Rotation': array([-1.70891322e-02, 1.05439568e+02, -7.99560454e-03]), + 'Velocity': array([ 3.10368985e-01, -3.89878482e-01, 1.54547684e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5474853515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.70703125, 15942.63867188, 29.99996948]), + 'frame': 28977, + 'frame_number': 28977, + 'framesequence': 117220, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0238040741533041, + 'timestamp': 989.5509678982198, + 'timestamp_carla': 989550, + 'timestamp_device': 2608108, + 'timestamp_stream': 989.5509678982198, + 'transform': [array([ 3.35142487e+02, 5.48910637e+01, -1.61260709e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 5.00439247e-03, 2.74385270e-02, -5.66579771e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.790616989135742, + 'FR_Wheel_Angle': 41.67835998535156, + 'Location': array([245.01541138, 152.68766785, 0.30170238]), + 'Rotation': array([-1.65700372e-02, 1.04037338e+02, -9.36889555e-03]), + 'Velocity': array([ 2.76668727e-01, -3.76505762e-01, -8.22830189e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5502319335938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.69335938, 15942.65429688, 29.99996948]), + 'frame': 28978, + 'frame_number': 28978, + 'framesequence': 117224, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0158693827688694, + 'timestamp': 989.5845361985266, + 'timestamp_carla': 989583, + 'timestamp_device': 2608141, + 'timestamp_stream': 989.5845361985266, + 'transform': [array([ 3.35142059e+02, 5.48915520e+01, -1.62630647e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.47399856e-02])]} +{'AngularVelocity': array([-0.00820284, 0.03417243, -5.3543787 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.797607421875, + 'FR_Wheel_Angle': 41.689056396484375, + 'Location': array([245.06925964, 152.60101318, 0.30170265]), + 'Rotation': array([-1.58392079e-02, 1.02710175e+02, -1.00708008e-02]), + 'Velocity': array([ 2.52290428e-01, -3.64934653e-01, -4.83894328e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.549072265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.68359375, 15942.66894531, 29.99996948]), + 'frame': 28979, + 'frame_number': 28979, + 'framesequence': 117228, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.6180520989001, + 'timestamp_carla': 989617, + 'timestamp_device': 2608175, + 'timestamp_stream': 989.6180520989001, + 'transform': [array([ 3.35141205e+02, 5.48925781e+01, -1.64757922e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.38854925e-02])]} +{'AngularVelocity': array([ 0.01001203, 0.05733874, -6.28163862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.771066665649414, + 'FR_Wheel_Angle': 41.64655303955078, + 'Location': array([245.12663269, 152.50292969, 0.30171728]), + 'Rotation': array([-1.88308302e-02, 1.01228935e+02, -6.43920945e-03]), + 'Velocity': array([ 2.82653570e-01, -4.27109569e-01, -8.30650333e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494995117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.64257812, 15942.71875 , 29.99996948]), + 'frame': 28980, + 'frame_number': 28980, + 'framesequence': 117232, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.6509299986064, + 'timestamp_carla': 989650, + 'timestamp_device': 2608208, + 'timestamp_stream': 989.6509299986064, + 'transform': [array([ 3.35140076e+02, 5.48939056e+01, -1.66348487e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.32446233e-02])]} +{'AngularVelocity': array([ 0.00780603, 0.05948527, -5.6752882 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78955841064453, + 'FR_Wheel_Angle': 41.67731857299805, + 'Location': array([245.18096924, 152.40454102, 0.30169827]), + 'Rotation': array([-1.55933211e-02, 9.97609940e+01, -1.09252930e-02]), + 'Velocity': array([ 2.44287640e-01, -3.94466579e-01, -5.77354404e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5509643554688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.55664062, 15942.8203125 , 29.99996948]), + 'frame': 28981, + 'frame_number': 28981, + 'framesequence': 117236, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.6842404976487, + 'timestamp_carla': 989683, + 'timestamp_device': 2608241, + 'timestamp_stream': 989.6842404976487, + 'transform': [array([ 3.35138794e+02, 5.48954468e+01, -1.67260706e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.28784114e-02])]} +{'AngularVelocity': array([ 3.71462689e-03, 5.64652123e-02, -6.68876505e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78912925720215, + 'FR_Wheel_Angle': 41.66960906982422, + 'Location': array([245.22958374, 152.31105042, 0.30171007]), + 'Rotation': array([-1.66041888e-02, 9.83854523e+01, -9.39941406e-03]), + 'Velocity': array([ 2.34098598e-01, -3.99860978e-01, 1.54199603e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5531616210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.44335938, 15942.95410156, 30.00006104]), + 'frame': 28982, + 'frame_number': 28982, + 'framesequence': 117240, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.7170151993632, + 'timestamp_carla': 989716, + 'timestamp_device': 2608275, + 'timestamp_stream': 989.7170151993632, + 'transform': [array([ 3.35137390e+02, 5.48971176e+01, -1.67485461e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.27868587e-02])]} +{'AngularVelocity': array([-0.00841362, -0.07617069, -6.70666647]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78150177001953, + 'FR_Wheel_Angle': 41.66707992553711, + 'Location': array([245.26876831, 152.23164368, 0.30169895]), + 'Rotation': array([-1.57162640e-02, 9.72361908e+01, -9.79614351e-03]), + 'Velocity': array([ 2.29735643e-01, -3.93557221e-01, 1.36661529e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5537109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.31054688, 15943.10839844, 30. ]), + 'frame': 28983, + 'frame_number': 28983, + 'framesequence': 117244, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.7522059977055, + 'timestamp_carla': 989751, + 'timestamp_device': 2608308, + 'timestamp_stream': 989.7522059977055, + 'transform': [array([ 3.35135773e+02, 5.48989639e+01, -1.67274967e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.28784114e-02])]} +{'AngularVelocity': array([-0.01464408, 0.06827576, -5.37139416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79038429260254, + 'FR_Wheel_Angle': 41.65467834472656, + 'Location': array([245.31446838, 152.134552 , 0.30170384]), + 'Rotation': array([-1.66861508e-02, 9.58364029e+01, -8.75854399e-03]), + 'Velocity': array([ 2.17681974e-01, -4.14975017e-01, -2.06174853e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.554443359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.171875 , 15943.27636719, 30. ]), + 'frame': 28984, + 'frame_number': 28984, + 'framesequence': 117248, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.784122698009, + 'timestamp_carla': 989783, + 'timestamp_device': 2608341, + 'timestamp_stream': 989.784122698009, + 'transform': [array([ 3.35134277e+02, 5.49006920e+01, -1.66804269e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.30615178e-02])]} +{'AngularVelocity': array([-0.01557599, -0.06381735, -5.93685007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.771465301513672, + 'FR_Wheel_Angle': 41.65170669555664, + 'Location': array([245.35774231, 152.03582764, 0.30169839]), + 'Rotation': array([-1.63583029e-02, 9.44188461e+01, -9.39941406e-03]), + 'Velocity': array([ 2.18263328e-01, -4.24275279e-01, -2.57120118e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.01367188, 15943.45800781, 30.00003052]), + 'frame': 28985, + 'frame_number': 28985, + 'framesequence': 117252, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.0, + 'timestamp': 989.8181429989636, + 'timestamp_carla': 989817, + 'timestamp_device': 2608375, + 'timestamp_stream': 989.8181429989636, + 'transform': [array([ 3.35132721e+02, 5.49025688e+01, -1.66127428e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.33361751e-02])]} +{'AngularVelocity': array([ 0.01033824, 0.0335884 , -6.72044134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79746437072754, + 'FR_Wheel_Angle': 41.68168640136719, + 'Location': array([245.39872742, 151.9339447 , 0.30170256]), + 'Rotation': array([-1.57162640e-02, 9.29859238e+01, -1.04675284e-02]), + 'Velocity': array([ 1.94064215e-01, -4.11870867e-01, -7.72952990e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5534057617188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.86328125, 15943.6328125 , 30. ]), + 'frame': 28986, + 'frame_number': 28986, + 'framesequence': 117256, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.035706110298633575, + 'timestamp': 989.850462500006, + 'timestamp_carla': 989849, + 'timestamp_device': 2608408, + 'timestamp_stream': 989.850462500006, + 'transform': [array([ 3.35131470e+02, 5.49040222e+01, -1.64296716e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.40685979e-02])]} +{'AngularVelocity': array([ 0.00805379, 0.04208746, -6.21691132]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.808225631713867, + 'FR_Wheel_Angle': 41.711647033691406, + 'Location': array([245.43429565, 151.84004211, 0.30169556]), + 'Rotation': array([-1.49854338e-02, 9.16869049e+01, -1.12915048e-02]), + 'Velocity': array([ 1.67427972e-01, -3.82397145e-01, -1.59740448e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5516357421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.70898438, 15943.81933594, 29.99996948]), + 'frame': 28987, + 'frame_number': 28987, + 'framesequence': 117260, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.07142747938632965, + 'timestamp': 989.8841209001839, + 'timestamp_carla': 989883, + 'timestamp_device': 2608441, + 'timestamp_stream': 989.8841209001839, + 'transform': [array([ 3.35130341e+02, 5.49053497e+01, -1.62631571e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.47399856e-02])]} +{'AngularVelocity': array([ 0.0140829 , 0.01738507, -5.22751808]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80516242980957, + 'FR_Wheel_Angle': 41.67238998413086, + 'Location': array([245.46612549, 151.74986267, 0.30170196]), + 'Rotation': array([-1.61124151e-02, 9.04467773e+01, -9.39941593e-03]), + 'Velocity': array([ 1.61666065e-01, -3.80493999e-01, 6.80637313e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5518188476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.58398438, 15943.96582031, 29.99996948]), + 'frame': 28988, + 'frame_number': 28988, + 'framesequence': 117264, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.10713358968496323, + 'timestamp': 989.9168413989246, + 'timestamp_carla': 989916, + 'timestamp_device': 2608475, + 'timestamp_stream': 989.9168413989246, + 'transform': [array([ 3.35129333e+02, 5.49065399e+01, -1.61412850e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.52282659e-02])]} +{'AngularVelocity': array([ 0.01522751, -0.08196314, -6.99038601]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.774328231811523, + 'FR_Wheel_Angle': 41.64644241333008, + 'Location': array([245.4997406 , 151.64724731, 0.30172434]), + 'Rotation': array([-1.95001885e-02, 8.90314941e+01, -4.66918899e-03]), + 'Velocity': array([ 1.98868200e-01, -4.66834605e-01, 3.58104699e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54931640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.47070312, 15944.09863281, 29.99996948]), + 'frame': 28989, + 'frame_number': 28989, + 'framesequence': 117268, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.13492026925086975, + 'timestamp': 989.9517583996058, + 'timestamp_carla': 989951, + 'timestamp_device': 2608508, + 'timestamp_stream': 989.9517583996058, + 'transform': [array([ 3.35128357e+02, 5.49077148e+01, -1.60516620e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.55944768e-02])]} +{'AngularVelocity': array([ 3.91492713e-03, -1.76866837e-02, -5.60705423e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.770877838134766, + 'FR_Wheel_Angle': 41.64624786376953, + 'Location': array([245.53347778, 151.53712463, 0.3017076 ]), + 'Rotation': array([-1.81204900e-02, 8.75272903e+01, -7.41577242e-03]), + 'Velocity': array([ 1.80543438e-01, -4.83989507e-01, -1.59111019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5490112304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.36914062, 15944.21679688, 30. ]), + 'frame': 28990, + 'frame_number': 28990, + 'framesequence': 117272, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1587243527173996, + 'timestamp': 989.9844319969416, + 'timestamp_carla': 989983, + 'timestamp_device': 2608541, + 'timestamp_stream': 989.9844319969416, + 'transform': [array([ 3.35127502e+02, 5.49087105e+01, -1.59900129e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.58386156e-02])]} +{'AngularVelocity': array([ 0.01341832, 0.01479178, -4.44715309]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.622299194335938, + 'FR_Wheel_Angle': 36.67842483520508, + 'Location': array([245.56188965, 151.42758179, 0.30170622]), + 'Rotation': array([-1.61738880e-02, 8.61207123e+01, -1.31225567e-02]), + 'Velocity': array([ 1.32614389e-01, -4.57221478e-01, -6.06632202e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54541015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.27148438, 15944.33105469, 30. ]), + 'frame': 28991, + 'frame_number': 28991, + 'framesequence': 117276, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.17062638700008392, + 'timestamp': 990.0170824974775, + 'timestamp_carla': 990016, + 'timestamp_device': 2608575, + 'timestamp_stream': 990.0170824974775, + 'transform': [array([ 3.35126709e+02, 5.49096260e+01, -1.59439236e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.60217211e-02])]} +{'AngularVelocity': array([-0.01781435, -0.03997465, -4.53723288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.173227310180664, + 'FR_Wheel_Angle': 37.231502532958984, + 'Location': array([245.58345032, 151.32473755, 0.30170053]), + 'Rotation': array([-1.53815849e-02, 8.49021606e+01, -1.09558105e-02]), + 'Velocity': array([ 1.20421238e-01, -4.40955758e-01, 2.09045411e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5466918945312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.18554688, 15944.43164062, 29.99996948]), + 'frame': 28992, + 'frame_number': 28992, + 'framesequence': 117280, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.0514236986637, + 'timestamp_carla': 990050, + 'timestamp_device': 2608608, + 'timestamp_stream': 990.0514236986637, + 'transform': [array([ 3.35126007e+02, 5.49105263e+01, -1.59145311e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.01697361, -0.04261725, -6.18944979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.25698471069336, + 'FR_Wheel_Angle': 37.519866943359375, + 'Location': array([245.60310364, 151.22015381, 0.30170351]), + 'Rotation': array([-1.58392079e-02, 8.36583481e+01, -9.76562500e-03]), + 'Velocity': array([ 1.11759052e-01, -4.45097774e-01, -1.22547144e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5474243164062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.109375 , 15944.52441406, 30. ]), + 'frame': 28993, + 'frame_number': 28993, + 'framesequence': 117284, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.0837011002004, + 'timestamp_carla': 990083, + 'timestamp_device': 2608641, + 'timestamp_stream': 990.0837011002004, + 'transform': [array([ 3.35125336e+02, 5.49112892e+01, -1.59135014e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.02188086, -0.02299964, -4.60543728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.461578369140625, + 'FR_Wheel_Angle': 33.462223052978516, + 'Location': array([245.61895752, 151.12457275, 0.30169925]), + 'Rotation': array([-1.52859623e-02, 8.25533524e+01, -1.05590830e-02]), + 'Velocity': array([ 8.83430913e-02, -4.11773890e-01, 4.96864322e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.545166015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.03710938, 15944.61328125, 30. ]), + 'frame': 28994, + 'frame_number': 28994, + 'framesequence': 117288, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.1170808970928, + 'timestamp_carla': 990116, + 'timestamp_device': 2608675, + 'timestamp_stream': 990.1170808970928, + 'transform': [array([ 3.35124756e+02, 5.49120026e+01, -1.59137219e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.0216597 , -0.03493085, -4.83967876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.05074691772461, + 'FR_Wheel_Angle': 33.64718246459961, + 'Location': array([245.63031006, 151.02549744, 0.30171889]), + 'Rotation': array([-1.87693592e-02, 8.15227966e+01, -7.50732562e-03]), + 'Velocity': array([ 7.89894238e-02, -4.71781641e-01, -1.20105738e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5472412109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.97265625, 15944.69042969, 30.00003052]), + 'frame': 28995, + 'frame_number': 28995, + 'framesequence': 117292, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.1507289968431, + 'timestamp_carla': 990150, + 'timestamp_device': 2608708, + 'timestamp_stream': 990.1507289968431, + 'transform': [array([ 3.35124207e+02, 5.49126434e+01, -1.59140274e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.017995 , 0.00571884, -3.94756222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.781038284301758, + 'FR_Wheel_Angle': 33.355010986328125, + 'Location': array([245.6424408 , 150.89904785, 0.30171108]), + 'Rotation': array([-1.76082272e-02, 8.02068481e+01, -8.20922945e-03]), + 'Velocity': array([ 6.84246346e-02, -4.76208448e-01, -1.97505942e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5467529296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.91210938, 15944.76171875, 30. ]), + 'frame': 28996, + 'frame_number': 28996, + 'framesequence': 117296, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.1834856979549, + 'timestamp_carla': 990182, + 'timestamp_device': 2608741, + 'timestamp_stream': 990.1834856979549, + 'transform': [array([ 3.35123718e+02, 5.49132118e+01, -1.59135699e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.0178341 , 0.01207277, -3.14552903]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.6390438079834, + 'FR_Wheel_Angle': 32.61723709106445, + 'Location': array([245.65000916, 150.79592896, 0.30169913]), + 'Rotation': array([-1.49239628e-02, 7.91453400e+01, -1.07727060e-02]), + 'Velocity': array([ 5.04248291e-02, -4.20240462e-01, 1.40562057e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.546142578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.85742188, 15944.82617188, 30. ]), + 'frame': 28997, + 'frame_number': 28997, + 'framesequence': 117300, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.2187141999602, + 'timestamp_carla': 990218, + 'timestamp_device': 2608775, + 'timestamp_stream': 990.2187141999602, + 'transform': [array([ 3.35123230e+02, 5.49137573e+01, -1.59152403e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01816188, 0.08228805, -3.69200015]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.538211822509766, + 'FR_Wheel_Angle': 28.8369140625, + 'Location': array([245.65324402, 150.70758057, 0.30171058]), + 'Rotation': array([-1.68773960e-02, 7.83109665e+01, -1.08337412e-02]), + 'Velocity': array([ 2.17467640e-02, -4.49802041e-01, 4.10270695e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.547119140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.80859375, 15944.8828125 , 30. ]), + 'frame': 28998, + 'frame_number': 28998, + 'framesequence': 117304, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.2507598996162, + 'timestamp_carla': 990250, + 'timestamp_device': 2608808, + 'timestamp_stream': 990.2507598996162, + 'transform': [array([ 3.35122894e+02, 5.49141693e+01, -1.59137532e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-1.20209320e-03, -1.16516184e-02, -3.39823484e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.93134880065918, + 'FR_Wheel_Angle': 29.034391403198242, + 'Location': array([245.65422058, 150.59991455, 0.3017025 ]), + 'Rotation': array([-1.77653208e-02, 7.73352432e+01, -8.30078032e-03]), + 'Velocity': array([ 2.54714601e-02, -4.77506965e-01, -2.33411789e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5437622070312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.76367188, 15944.93554688, 30. ]), + 'frame': 28999, + 'frame_number': 28999, + 'framesequence': 117308, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.2837368994951, + 'timestamp_carla': 990283, + 'timestamp_device': 2608841, + 'timestamp_stream': 990.2837368994951, + 'transform': [array([ 3.35122559e+02, 5.49145393e+01, -1.59135208e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 1.36199314e-02, -2.71193171e-03, -2.93223858e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.098695755004883, + 'FR_Wheel_Angle': 29.19733238220215, + 'Location': array([245.65324402, 150.49398804, 0.30170101]), + 'Rotation': array([-1.53201139e-02, 7.63863907e+01, -1.00708008e-02]), + 'Velocity': array([ 1.52150942e-02, -4.35130119e-01, -9.24110373e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5467529296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.7265625 , 15944.97851562, 30. ]), + 'frame': 29000, + 'frame_number': 29000, + 'framesequence': 117312, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.3181427977979, + 'timestamp_carla': 990317, + 'timestamp_device': 2608875, + 'timestamp_stream': 990.3181427977979, + 'transform': [array([ 3.35122284e+02, 5.49148636e+01, -1.59145087e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01541717, 0.01815104, -3.46903872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.762157440185547, + 'FR_Wheel_Angle': 24.62438201904297, + 'Location': array([245.65028381, 150.39093018, 0.30170757]), + 'Rotation': array([-1.63583029e-02, 7.54693298e+01, -1.01318359e-02]), + 'Velocity': array([-1.26117957e-03, -4.41664547e-01, -2.92396544e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5471801757812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.6953125, 15945.015625 , 30. ]), + 'frame': 29001, + 'frame_number': 29001, + 'framesequence': 117316, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.3503284975886, + 'timestamp_carla': 990349, + 'timestamp_device': 2608908, + 'timestamp_stream': 990.3503284975886, + 'transform': [array([ 3.35122101e+02, 5.49151154e+01, -1.59134254e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.02298966, -0.0318847 , -4.70214272]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.57676124572754, + 'FR_Wheel_Angle': 25.143762588500977, + 'Location': array([245.64163208, 150.27172852, 0.30171415]), + 'Rotation': array([-1.79770570e-02, 7.45271530e+01, -7.96508696e-03]), + 'Velocity': array([-1.44668054e-02, -4.82161522e-01, 1.40237811e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452270507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.66796875, 15945.046875 , 30. ]), + 'frame': 29002, + 'frame_number': 29002, + 'framesequence': 117320, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.384714499116, + 'timestamp_carla': 990384, + 'timestamp_device': 2608941, + 'timestamp_stream': 990.384714499116, + 'transform': [array([ 3.35121857e+02, 5.49153214e+01, -1.59144327e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.00788391, -0.01494245, -3.91918373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.36385726928711, + 'FR_Wheel_Angle': 24.948888778686523, + 'Location': array([245.6322937 , 150.16545105, 0.30171174]), + 'Rotation': array([-1.64812449e-02, 7.36981659e+01, -8.69750977e-03]), + 'Velocity': array([-2.22602263e-02, -4.60393786e-01, 1.80129995e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54736328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.64648438, 15945.07421875, 30. ]), + 'frame': 29003, + 'frame_number': 29003, + 'framesequence': 117324, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.4167997986078, + 'timestamp_carla': 990416, + 'timestamp_device': 2608975, + 'timestamp_stream': 990.4167997986078, + 'transform': [array([ 3.35121796e+02, 5.49154587e+01, -1.59133255e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01146885, 0.01757938, -3.57593131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.059946060180664, + 'FR_Wheel_Angle': 23.882381439208984, + 'Location': array([245.62098694, 150.05622864, 0.30170035]), + 'Rotation': array([-1.60167925e-02, 7.28465347e+01, -9.06371977e-03]), + 'Velocity': array([-3.18466686e-02, -4.55818504e-01, -1.10244746e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5453491210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.62695312, 15945.09277344, 30. ]), + 'frame': 29004, + 'frame_number': 29004, + 'framesequence': 117328, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.4500481002033, + 'timestamp_carla': 990449, + 'timestamp_device': 2609008, + 'timestamp_stream': 990.4500481002033, + 'transform': [array([ 3.35121704e+02, 5.49155464e+01, -1.59135208e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01779802, 0.04508553, -2.91602635]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.99747085571289, + 'FR_Wheel_Angle': 20.729406356811523, + 'Location': array([245.60627747, 149.95207214, 0.30170679]), + 'Rotation': array([-1.73896607e-02, 7.21297150e+01, -1.00708008e-02]), + 'Velocity': array([-6.16690107e-02, -4.63174403e-01, -9.17625439e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.547607421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.61523438, 15945.10839844, 30. ]), + 'frame': 29005, + 'frame_number': 29005, + 'framesequence': 117332, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.4844931997359, + 'timestamp_carla': 990483, + 'timestamp_device': 2609041, + 'timestamp_stream': 990.4844931997359, + 'transform': [array([ 3.35121674e+02, 5.49155960e+01, -1.59145921e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.00892186, 0.0093893 , -4.17326546]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.305150985717773, + 'FR_Wheel_Angle': 20.771644592285156, + 'Location': array([245.5894928 , 149.84674072, 0.30171284]), + 'Rotation': array([-1.75809059e-02, 7.14202271e+01, -8.54492188e-03]), + 'Velocity': array([-6.28171042e-02, -4.69637334e-01, 1.39360418e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.547119140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.609375 , 15945.11621094, 30. ]), + 'frame': 29006, + 'frame_number': 29006, + 'framesequence': 117336, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.5166276991367, + 'timestamp_carla': 990515, + 'timestamp_device': 2609075, + 'timestamp_stream': 990.5166276991367, + 'transform': [array([ 3.35121704e+02, 5.49155731e+01, -1.59134790e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.05473537, 0.018254 , -2.28721356]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.446075439453125, + 'FR_Wheel_Angle': 20.84724998474121, + 'Location': array([245.57145691, 149.74330139, 0.30170998]), + 'Rotation': array([-1.59280002e-02, 7.07453537e+01, -8.81958008e-03]), + 'Velocity': array([-7.28921518e-02, -4.72021788e-01, 2.16674798e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5450439453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.60546875, 15945.12011719, 30. ]), + 'frame': 29007, + 'frame_number': 29007, + 'framesequence': 117340, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.5498996973038, + 'timestamp_carla': 990549, + 'timestamp_device': 2609108, + 'timestamp_stream': 990.5498996973038, + 'transform': [array([ 3.35121704e+02, 5.49155159e+01, -1.59136727e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01686317, 0.01170877, -1.2393595 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.655688285827637, + 'FR_Wheel_Angle': 15.971714973449707, + 'Location': array([245.55050659, 149.63568115, 0.30169943]), + 'Rotation': array([-1.58938486e-02, 7.00689316e+01, -1.06201181e-02]), + 'Velocity': array([-8.17753300e-02, -4.41092938e-01, -1.12171168e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5472412109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.60742188, 15945.11914062, 30.00003052]), + 'frame': 29008, + 'frame_number': 29008, + 'framesequence': 117344, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.5831990987062, + 'timestamp_carla': 990582, + 'timestamp_device': 2609141, + 'timestamp_stream': 990.5831990987062, + 'transform': [array([ 3.35121826e+02, 5.49154205e+01, -1.59138218e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.02683096, -0.02337103, -1.59063089]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.682737350463867, + 'FR_Wheel_Angle': 16.771963119506836, + 'Location': array([245.52688599, 149.53361511, 0.30170158]), + 'Rotation': array([-1.58392079e-02, 6.95315781e+01, -8.72802641e-03]), + 'Velocity': array([-8.63790289e-02, -4.46090966e-01, 4.05693063e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5468139648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.61132812, 15945.11328125, 30.00003052]), + 'frame': 29009, + 'frame_number': 29009, + 'framesequence': 117348, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.6177573986351, + 'timestamp_carla': 990617, + 'timestamp_device': 2609175, + 'timestamp_stream': 990.6177573986351, + 'transform': [array([ 3.35121948e+02, 5.49152718e+01, -1.59148976e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.00594108, -0.00387181, -1.06830895]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.450517654418945, + 'FR_Wheel_Angle': 16.640901565551758, + 'Location': array([245.50213623, 149.43005371, 0.30170017]), + 'Rotation': array([-1.55933211e-02, 6.89760818e+01, -8.72802641e-03]), + 'Velocity': array([-9.04871151e-02, -4.31387156e-01, -2.88581850e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5465698242188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.62109375, 15945.10351562, 30. ]), + 'frame': 29010, + 'frame_number': 29010, + 'framesequence': 117352, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.6503442972898, + 'timestamp_carla': 990649, + 'timestamp_device': 2609208, + 'timestamp_stream': 990.6503442972898, + 'transform': [array([ 3.35122101e+02, 5.49150963e+01, -1.59140006e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01770928, 0.01115641, -2.36138153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.944974899291992, + 'FR_Wheel_Angle': 15.223109245300293, + 'Location': array([245.47540283, 149.32408142, 0.30171755]), + 'Rotation': array([-1.76082272e-02, 6.84002914e+01, -7.93457031e-03]), + 'Velocity': array([-1.06780782e-01, -4.67127413e-01, 9.55581636e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54443359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.6328125 , 15945.08789062, 30. ]), + 'frame': 29011, + 'frame_number': 29011, + 'framesequence': 117356, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.6838645972311, + 'timestamp_carla': 990683, + 'timestamp_device': 2609241, + 'timestamp_stream': 990.6838645972311, + 'transform': [array([ 3.35122284e+02, 5.49148712e+01, -1.59141645e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.02240475, -0.0213387 , -2.19557357]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.773965835571289, + 'FR_Wheel_Angle': 12.580257415771484, + 'Location': array([245.44593811, 149.22114563, 0.30170119]), + 'Rotation': array([-1.52586419e-02, 6.79508286e+01, -1.06811523e-02]), + 'Velocity': array([-1.19311072e-01, -4.32570577e-01, -1.00574493e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462036132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.6484375 , 15945.07128906, 30. ]), + 'frame': 29012, + 'frame_number': 29012, + 'framesequence': 117360, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.716884598136, + 'timestamp_carla': 990716, + 'timestamp_device': 2609274, + 'timestamp_stream': 990.716884598136, + 'transform': [array([ 3.35122498e+02, 5.49146194e+01, -1.59138903e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.02224586, 0.02324604, -2.11600018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.01638126373291, + 'FR_Wheel_Angle': 12.46178150177002, + 'Location': array([245.4130249 , 149.11183167, 0.30172867]), + 'Rotation': array([-1.91040374e-02, 6.75036850e+01, -7.72094820e-03]), + 'Velocity': array([-1.43858567e-01, -5.00524998e-01, 3.24249271e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5459594726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.66796875, 15945.04882812, 29.99996948]), + 'frame': 29013, + 'frame_number': 29013, + 'framesequence': 117364, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1745937317609787, + 'timestamp': 990.7518601976335, + 'timestamp_carla': 990751, + 'timestamp_device': 2609308, + 'timestamp_stream': 990.7518601976335, + 'transform': [array([ 3.35122803e+02, 5.49143143e+01, -1.59152716e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01182811, 0.02430802, -2.12482381]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.170716285705566, + 'FR_Wheel_Angle': 12.523245811462402, + 'Location': array([245.38417053, 149.01759338, 0.3016941 ]), + 'Rotation': array([-1.51083777e-02, 6.71122284e+01, -8.72802548e-03]), + 'Velocity': array([-1.31985351e-01, -4.50967908e-01, -1.83916083e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5465087890625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.68945312, 15945.0234375 , 29.99996948]), + 'frame': 29014, + 'frame_number': 29014, + 'framesequence': 117368, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.17856107652187347, + 'timestamp': 990.7852239981294, + 'timestamp_carla': 990784, + 'timestamp_device': 2609341, + 'timestamp_stream': 990.7852239981294, + 'transform': [array([ 3.35123047e+02, 5.49139938e+01, -1.59147635e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.03962719, 0.0205878 , -1.89310503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.714560031890869, + 'FR_Wheel_Angle': 7.45349645614624, + 'Location': array([245.34968567, 148.91067505, 0.30171397]), + 'Rotation': array([-1.71506032e-02, 6.66939240e+01, -9.85717680e-03]), + 'Velocity': array([-1.51258662e-01, -4.59712863e-01, 2.31170652e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.543701171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.71875 , 15944.99121094, 30.00003052]), + 'frame': 29015, + 'frame_number': 29015, + 'framesequence': 117372, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.17856107652187347, + 'timestamp': 990.81786589697, + 'timestamp_carla': 990817, + 'timestamp_device': 2609374, + 'timestamp_stream': 990.81786589697, + 'transform': [array([ 3.35123352e+02, 5.49136429e+01, -1.59139365e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.03692153, 0.01053053, -1.18604302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.938999176025391, + 'FR_Wheel_Angle': 8.274079322814941, + 'Location': array([245.31033325, 148.80200195, 0.30170047]), + 'Rotation': array([-1.53815849e-02, 6.63833160e+01, -9.00268368e-03]), + 'Velocity': array([-1.51138991e-01, -4.36471283e-01, 4.38594798e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.544677734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.74414062, 15944.95996094, 30.00003052]), + 'frame': 29016, + 'frame_number': 29016, + 'framesequence': 117376, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.1904631108045578, + 'timestamp': 990.8506684973836, + 'timestamp_carla': 990850, + 'timestamp_device': 2609408, + 'timestamp_stream': 990.8506684973836, + 'transform': [array([ 3.35123657e+02, 5.49132500e+01, -1.59135699e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 8.25308904e-04, -1.75538566e-03, -2.40751481e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.712856769561768, + 'FR_Wheel_Angle': 8.261760711669922, + 'Location': array([245.26594543, 148.68055725, 0.30170235]), + 'Rotation': array([-1.52859623e-02, 6.60330582e+01, -8.48388765e-03]), + 'Velocity': array([-1.56562775e-01, -4.43756223e-01, 7.39383686e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54638671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.7734375 , 15944.92578125, 30. ]), + 'frame': 29017, + 'frame_number': 29017, + 'framesequence': 117380, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.2222171425819397, + 'timestamp': 990.883877299726, + 'timestamp_carla': 990883, + 'timestamp_device': 2609441, + 'timestamp_stream': 990.883877299726, + 'transform': [array([ 3.35124054e+02, 5.49128227e+01, -1.59136847e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.00859541, 0.01042491, -2.20510554]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.060235500335693, + 'FR_Wheel_Angle': 6.7679123878479, + 'Location': array([245.22883606, 148.58157349, 0.30170602]), + 'Rotation': array([-1.62080377e-02, 6.57601547e+01, -8.42285249e-03]), + 'Velocity': array([-1.62207484e-01, -4.39979047e-01, 4.85992423e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.547119140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.80664062, 15944.88671875, 30. ]), + 'frame': 29018, + 'frame_number': 29018, + 'framesequence': 117384, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 990.9173193983734, + 'timestamp_carla': 990916, + 'timestamp_device': 2609474, + 'timestamp_stream': 990.9173193983734, + 'transform': [array([ 3.35124451e+02, 5.49123611e+01, -1.59139633e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-2.03288164e-05, -1.83809195e-02, -3.79772961e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.6813786029815674, + 'FR_Wheel_Angle': 4.317724704742432, + 'Location': array([245.18583679, 148.4763031 , 0.30170357]), + 'Rotation': array([-1.58938486e-02, 6.55896606e+01, -9.82666109e-03]), + 'Velocity': array([-1.76952094e-01, -4.30970937e-01, -1.06477732e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5468139648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.84179688, 15944.84375 , 30.00003052]), + 'frame': 29019, + 'frame_number': 29019, + 'framesequence': 117388, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 990.9514771997929, + 'timestamp_carla': 990950, + 'timestamp_device': 2609508, + 'timestamp_stream': 990.9514771997929, + 'transform': [array([ 3.35124847e+02, 5.49118652e+01, -1.59146681e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.03494463, -0.00209018, -0.89282733]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9033312797546387, + 'FR_Wheel_Angle': 4.189452171325684, + 'Location': array([245.14506531, 148.37826538, 0.30171454]), + 'Rotation': array([-1.83390565e-02, 6.54434204e+01, -7.81249953e-03]), + 'Velocity': array([-1.93070889e-01, -4.73919243e-01, -5.83076471e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462646484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.88085938, 15944.79785156, 30.00006104]), + 'frame': 29020, + 'frame_number': 29020, + 'framesequence': 117392, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 990.9845297969878, + 'timestamp_carla': 990983, + 'timestamp_device': 2609541, + 'timestamp_stream': 990.9845297969878, + 'transform': [array([ 3.35125305e+02, 5.49113579e+01, -1.59142345e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.00453552, -0.0113851 , -1.65592456]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.026253700256348, + 'FR_Wheel_Angle': 4.14762020111084, + 'Location': array([245.09733582, 148.26464844, 0.30170149]), + 'Rotation': array([-1.66315101e-02, 6.52623138e+01, -7.78198382e-03]), + 'Velocity': array([-1.92368001e-01, -4.69083935e-01, -2.92253477e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5448608398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.92382812, 15944.74707031, 30.00003052]), + 'frame': 29021, + 'frame_number': 29021, + 'framesequence': 117396, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.0175920985639, + 'timestamp_carla': 991016, + 'timestamp_device': 2609574, + 'timestamp_stream': 991.0175920985639, + 'transform': [array([ 3.35125763e+02, 5.49108086e+01, -1.59139782e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.00981685, 0.00779195, -1.28880382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0839054211974144, + 'FR_Wheel_Angle': -0.9061670303344727, + 'Location': array([245.0537262 , 148.16479492, 0.30169934]), + 'Rotation': array([-1.42819248e-02, 6.51669693e+01, -1.03759766e-02]), + 'Velocity': array([-1.88104048e-01, -4.05508995e-01, -7.64942160e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5457153320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23709.96679688, 15944.69628906, 30.00003052]), + 'frame': 29022, + 'frame_number': 29022, + 'framesequence': 117400, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.0526227988303, + 'timestamp_carla': 991052, + 'timestamp_device': 2609608, + 'timestamp_stream': 991.0526227988303, + 'transform': [array([ 3.35126251e+02, 5.49101944e+01, -1.59153938e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.00447329, -0.00845579, 0.0510513 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.2775719165802002, + 'FR_Wheel_Angle': -0.03050205297768116, + 'Location': array([245.00852966, 148.06771851, 0.30170691]), + 'Rotation': array([-1.72120761e-02, 6.51789856e+01, -8.11767578e-03]), + 'Velocity': array([-1.97959453e-01, -4.30730402e-01, -7.73334468e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462646484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.01367188, 15944.64257812, 30.00003052]), + 'frame': 29023, + 'frame_number': 29023, + 'framesequence': 117404, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.0857820995152, + 'timestamp_carla': 991085, + 'timestamp_device': 2609641, + 'timestamp_stream': 991.0857820995152, + 'transform': [array([ 3.35126801e+02, 5.49095688e+01, -1.59146681e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.06534763, 0.02166572, 0.61556524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.0139877675101161, + 'FR_Wheel_Angle': -0.05841438099741936, + 'Location': array([244.96446228, 147.97273254, 0.30170181]), + 'Rotation': array([-1.59894712e-02, 6.51855240e+01, -7.69042969e-03]), + 'Velocity': array([-2.02427059e-01, -4.38532859e-01, -1.51967994e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54345703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.06640625, 15944.57910156, 30. ]), + 'frame': 29024, + 'frame_number': 29024, + 'framesequence': 117409, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.1192055977881, + 'timestamp_carla': 991118, + 'timestamp_device': 2609683, + 'timestamp_stream': 991.1192055977881, + 'transform': [array([ 3.35127350e+02, 5.49089050e+01, -1.59144327e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.02212265, -0.00123882, 0.17117855]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.0289074182510376, + 'FR_Wheel_Angle': -1.837896466255188, + 'Location': array([244.91902161, 147.87509155, 0.30170262]), + 'Rotation': array([-1.51903396e-02, 6.51803818e+01, -7.96508789e-03]), + 'Velocity': array([-1.83897763e-01, -3.87899399e-01, 4.22477706e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5448608398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.1171875 , 15944.51757812, 30.00003052]), + 'frame': 29025, + 'frame_number': 29025, + 'framesequence': 117412, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.1517834998667, + 'timestamp_carla': 991151, + 'timestamp_device': 2609708, + 'timestamp_stream': 991.1517834998667, + 'transform': [array([ 3.35127960e+02, 5.49082222e+01, -1.59136921e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.01332689, -0.01456867, 0.94217759]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.347602367401123, + 'FR_Wheel_Angle': -3.6728553771972656, + 'Location': array([244.87489319, 147.78675842, 0.30169487]), + 'Rotation': array([-1.50742270e-02, 6.53101501e+01, -9.15527344e-03]), + 'Velocity': array([-1.91156551e-01, -3.70465606e-01, -2.21271504e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54541015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.17382812, 15944.45117188, 30. ]), + 'frame': 29026, + 'frame_number': 29026, + 'framesequence': 117416, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.1844443976879, + 'timestamp_carla': 991183, + 'timestamp_device': 2609741, + 'timestamp_stream': 991.1844443976879, + 'transform': [array([ 3.35128601e+02, 5.49074974e+01, -1.59133494e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 4.40539268e-04, -7.79446587e-03, -6.23547554e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.232412338256836, + 'FR_Wheel_Angle': -3.9342126846313477, + 'Location': array([244.83650208, 147.71011353, 0.30170897]), + 'Rotation': array([-1.67203024e-02, 6.54084473e+01, -7.84301758e-03]), + 'Velocity': array([-1.96241349e-01, -3.86666477e-01, -1.01633072e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5468139648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.23242188, 15944.38378906, 30.00003052]), + 'frame': 29027, + 'frame_number': 29027, + 'framesequence': 117420, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.2173019982874, + 'timestamp_carla': 991216, + 'timestamp_device': 2609774, + 'timestamp_stream': 991.2173019982874, + 'transform': [array([ 3.35129211e+02, 5.49067383e+01, -1.59133181e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01530084, -0.01565816, -0.53101176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.147455215454102, + 'FR_Wheel_Angle': -4.015269756317139, + 'Location': array([244.7906189 , 147.61769104, 0.30171084]), + 'Rotation': array([-1.68159250e-02, 6.55552750e+01, -7.47680617e-03]), + 'Velocity': array([-1.96794465e-01, -3.89749020e-01, 1.33085254e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.547607421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.29492188, 15944.3125 , 30. ]), + 'frame': 29028, + 'frame_number': 29028, + 'framesequence': 117424, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.2512196004391, + 'timestamp_carla': 991250, + 'timestamp_device': 2609808, + 'timestamp_stream': 991.2512196004391, + 'transform': [array([ 3.35129913e+02, 5.49059181e+01, -1.59141421e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.00042408, 0.02237713, 0.10769361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.569079399108887, + 'FR_Wheel_Angle': -8.535151481628418, + 'Location': array([244.74235535, 147.52175903, 0.30170441]), + 'Rotation': array([-1.64539255e-02, 6.57432938e+01, -9.36889835e-03]), + 'Velocity': array([-2.20398858e-01, -4.03925151e-01, 5.07068617e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.547607421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.359375 , 15944.23632812, 30. ]), + 'frame': 29029, + 'frame_number': 29029, + 'framesequence': 117428, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.2845618985593, + 'timestamp_carla': 991283, + 'timestamp_device': 2609841, + 'timestamp_stream': 991.2845618985593, + 'transform': [array([ 3.35130615e+02, 5.49050751e+01, -1.59141570e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01480088, -0.02238652, -0.01088967]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.136611938476562, + 'FR_Wheel_Angle': -7.755312919616699, + 'Location': array([244.69218445, 147.42723083, 0.3017084 ]), + 'Rotation': array([-1.70003399e-02, 6.60353470e+01, -7.78198196e-03]), + 'Velocity': array([-2.16636270e-01, -4.01554704e-01, 9.78851313e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5459594726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.4296875 , 15944.15332031, 30. ]), + 'frame': 29030, + 'frame_number': 29030, + 'framesequence': 117432, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.3182833977044, + 'timestamp_carla': 991317, + 'timestamp_device': 2609874, + 'timestamp_stream': 991.3182833977044, + 'transform': [array([ 3.35131409e+02, 5.49041977e+01, -1.59144819e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01162619, -0.01452672, -0.11083326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.368921279907227, + 'FR_Wheel_Angle': -7.750779628753662, + 'Location': array([244.64512634, 147.33721924, 0.30169576]), + 'Rotation': array([-1.48966415e-02, 6.63070602e+01, -7.04956101e-03]), + 'Velocity': array([-1.95289001e-01, -3.62226903e-01, -4.36973569e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5458984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.50195312, 15944.06835938, 29.99996948]), + 'frame': 29031, + 'frame_number': 29031, + 'framesequence': 117436, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.351101398468, + 'timestamp_carla': 991350, + 'timestamp_device': 2609908, + 'timestamp_stream': 991.351101398468, + 'transform': [array([ 3.35132141e+02, 5.49033012e+01, -1.59139901e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.00776446, 0.03159797, 2.0701561 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.529036521911621, + 'FR_Wheel_Angle': -9.573262214660645, + 'Location': array([244.59992981, 147.25003052, 0.30170876]), + 'Rotation': array([-1.69661883e-02, 6.65653229e+01, -7.56835938e-03]), + 'Velocity': array([-2.12997392e-01, -3.92485827e-01, 1.94196691e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452880859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.57617188, 15943.98046875, 30.00003052]), + 'frame': 29032, + 'frame_number': 29032, + 'framesequence': 117440, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.3822974972427, + 'timestamp_carla': 991381, + 'timestamp_device': 2609941, + 'timestamp_stream': 991.3822974972427, + 'transform': [array([ 3.35132874e+02, 5.49024124e+01, -1.59126133e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([1.04658306e-03, 1.33309476e-02, 2.53263402e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.49927043914795, + 'FR_Wheel_Angle': -10.814974784851074, + 'Location': array([244.55140686, 147.16073608, 0.30170378]), + 'Rotation': array([-1.64197739e-02, 6.69397278e+01, -9.42993071e-03]), + 'Velocity': array([-2.21329376e-01, -3.73439550e-01, -6.27803820e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462646484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.65234375, 15943.89160156, 30.00003052]), + 'frame': 29033, + 'frame_number': 29033, + 'framesequence': 117444, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.4155317991972, + 'timestamp_carla': 991414, + 'timestamp_device': 2609974, + 'timestamp_stream': 991.4155317991972, + 'transform': [array([ 3.35133728e+02, 5.49014359e+01, -1.59132421e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.00714218, 0.0178113 , 1.69374037]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.530701637268066, + 'FR_Wheel_Angle': -11.076848030090332, + 'Location': array([244.50245667, 147.07044983, 0.3017253 ]), + 'Rotation': array([-1.81819629e-02, 6.73351669e+01, -8.39233398e-03]), + 'Velocity': array([-2.36807451e-01, -4.13716078e-01, 2.66327843e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5490112304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.7265625 , 15943.8046875 , 30.00003052]), + 'frame': 29034, + 'frame_number': 29034, + 'framesequence': 117448, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.450204398483, + 'timestamp_carla': 991449, + 'timestamp_device': 2610008, + 'timestamp_stream': 991.450204398483, + 'transform': [array([ 3.35134644e+02, 5.49003792e+01, -1.59148067e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.0127635 , -0.02416189, 1.76887178]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.47008991241455, + 'FR_Wheel_Angle': -11.177494049072266, + 'Location': array([244.45155334, 146.97529602, 0.30170646]), + 'Rotation': array([-1.65427178e-02, 6.77621155e+01, -7.17163086e-03]), + 'Velocity': array([-2.19231695e-01, -3.92858028e-01, -9.93537906e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5477294921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.8125 , 15943.70605469, 30. ]), + 'frame': 29035, + 'frame_number': 29035, + 'framesequence': 117452, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.4846909977496, + 'timestamp_carla': 991484, + 'timestamp_device': 2610041, + 'timestamp_stream': 991.4846909977496, + 'transform': [array([ 3.35135529e+02, 5.48993149e+01, -1.59154847e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 5.24930656e-03, -8.33917511e-05, 1.00334191e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.3937931060791, + 'FR_Wheel_Angle': -15.140605926513672, + 'Location': array([244.40342712, 146.88548279, 0.30169722]), + 'Rotation': array([-1.55045288e-02, 6.82083893e+01, -8.81958008e-03]), + 'Velocity': array([-2.20146269e-01, -3.69498700e-01, 4.95910626e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5446166992188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.90234375, 15943.59863281, 30. ]), + 'frame': 29036, + 'frame_number': 29036, + 'framesequence': 117456, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.51663139835, + 'timestamp_carla': 991516, + 'timestamp_device': 2610074, + 'timestamp_stream': 991.51663139835, + 'transform': [array([ 3.35136414e+02, 5.48982887e+01, -1.59139976e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([0.00863166, 0.00336435, 2.53499198]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.609609603881836, + 'FR_Wheel_Angle': -14.521401405334473, + 'Location': array([244.35202026, 146.7928009 , 0.30171221]), + 'Rotation': array([-1.67544540e-02, 6.87715988e+01, -7.56835844e-03]), + 'Velocity': array([-2.32106835e-01, -3.94364506e-01, 2.43821138e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.543212890625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23710.99414062, 15943.49121094, 30.00003052]), + 'frame': 29037, + 'frame_number': 29037, + 'framesequence': 117460, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.5490501970053, + 'timestamp_carla': 991548, + 'timestamp_device': 2610108, + 'timestamp_stream': 991.5490501970053, + 'transform': [array([ 3.35137299e+02, 5.48972244e+01, -1.59134477e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.00731684, -0.01244616, 1.23178005]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.71381187438965, + 'FR_Wheel_Angle': -14.41225528717041, + 'Location': array([244.30143738, 146.69880676, 0.30170235]), + 'Rotation': array([-1.55933211e-02, 6.93318634e+01, -6.62231445e-03]), + 'Velocity': array([-2.18856484e-01, -3.81749749e-01, 2.54058832e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462646484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.078125 , 15943.390625 , 30.00003052]), + 'frame': 29038, + 'frame_number': 29038, + 'framesequence': 117464, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.582664899528, + 'timestamp_carla': 991582, + 'timestamp_device': 2610141, + 'timestamp_stream': 991.582664899528, + 'transform': [array([ 3.35138275e+02, 5.48960915e+01, -1.59140348e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01167108, -0.00376035, 3.49804902]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.24822998046875, + 'FR_Wheel_Angle': -16.318771362304688, + 'Location': array([244.25248718, 146.60604858, 0.3017092 ]), + 'Rotation': array([-1.70003399e-02, 6.98930588e+01, -7.17163086e-03]), + 'Velocity': array([-2.24322736e-01, -3.97772908e-01, 3.78417972e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54736328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.16796875, 15943.28515625, 30. ]), + 'frame': 29039, + 'frame_number': 29039, + 'framesequence': 117468, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.6170818991959, + 'timestamp_carla': 991616, + 'timestamp_device': 2610174, + 'timestamp_stream': 991.6170818991959, + 'transform': [array([ 3.35139252e+02, 5.48949203e+01, -1.59149975e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.01051477, 0.02447296, 3.3366487 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.629188537597656, + 'FR_Wheel_Angle': -17.102657318115234, + 'Location': array([244.20245361, 146.51460266, 0.30170351]), + 'Rotation': array([-1.59280002e-02, 7.05570145e+01, -8.81958008e-03]), + 'Velocity': array([-2.37145469e-01, -3.88351440e-01, -9.46044929e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462036132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.265625 , 15943.17089844, 30. ]), + 'frame': 29040, + 'frame_number': 29040, + 'framesequence': 117472, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.6497952975333, + 'timestamp_carla': 991649, + 'timestamp_device': 2610208, + 'timestamp_stream': 991.6497952975333, + 'transform': [array([ 3.35140228e+02, 5.48937874e+01, -1.59142599e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01161442, -0.01707771, 2.16487575]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.78166389465332, + 'FR_Wheel_Angle': -17.36504364013672, + 'Location': array([244.15138245, 146.41958618, 0.30171424]), + 'Rotation': array([-1.73691697e-02, 7.12474365e+01, -7.65991258e-03]), + 'Velocity': array([-2.35198647e-01, -4.04365301e-01, 2.76079169e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.544189453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.36328125, 15943.05175781, 30. ]), + 'frame': 29041, + 'frame_number': 29041, + 'framesequence': 117476, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.6830760985613, + 'timestamp_carla': 991682, + 'timestamp_device': 2610241, + 'timestamp_stream': 991.6830760985613, + 'transform': [array([ 3.35141235e+02, 5.48926163e+01, -1.59142256e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([0.01849159, 0.03978015, 3.63218808]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.823776245117188, + 'FR_Wheel_Angle': -17.484031677246094, + 'Location': array([244.10031128, 146.32197571, 0.30171534]), + 'Rotation': array([-1.81819629e-02, 7.19685898e+01, -8.27026553e-03]), + 'Velocity': array([-2.51534015e-01, -4.30876255e-01, 1.45893093e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5457153320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.4609375 , 15942.93945312, 30. ]), + 'frame': 29042, + 'frame_number': 29042, + 'framesequence': 117480, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.7161311991513, + 'timestamp_carla': 991715, + 'timestamp_device': 2610274, + 'timestamp_stream': 991.7161311991513, + 'transform': [array([ 3.35142273e+02, 5.48914146e+01, -1.59140512e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([0.01441529, 0.0131947 , 2.94009542]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.92131996154785, + 'FR_Wheel_Angle': -20.935314178466797, + 'Location': array([244.04690552, 146.21954346, 0.30171177]), + 'Rotation': array([-1.76696982e-02, 7.27729874e+01, -9.76562500e-03]), + 'Velocity': array([-2.62618512e-01, -4.37893361e-01, -5.98621373e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5457153320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.5625 , 15942.82226562, 30.00003052]), + 'frame': 29043, + 'frame_number': 29043, + 'framesequence': 117484, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.7494849972427, + 'timestamp_carla': 991748, + 'timestamp_device': 2610308, + 'timestamp_stream': 991.7494849972427, + 'transform': [array([ 3.35143311e+02, 5.48902054e+01, -1.59141839e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([5.17030363e-04, 1.55723551e-02, 2.47643042e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.029294967651367, + 'FR_Wheel_Angle': -20.465486526489258, + 'Location': array([243.99583435, 146.12284851, 0.30169463]), + 'Rotation': array([-1.48010189e-02, 7.36227112e+01, -5.73730422e-03]), + 'Velocity': array([-2.27470711e-01, -3.94098312e-01, -1.01861951e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.546142578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.6640625, 15942.703125 , 30. ]), + 'frame': 29044, + 'frame_number': 29044, + 'framesequence': 117488, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.7830335982144, + 'timestamp_carla': 991782, + 'timestamp_device': 2610341, + 'timestamp_stream': 991.7830335982144, + 'transform': [array([ 3.35144379e+02, 5.48889542e+01, -1.59143791e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.0168847 , 0.01727095, 3.79741335]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.996780395507812, + 'FR_Wheel_Angle': -20.35378074645996, + 'Location': array([243.9490509 , 146.03068542, 0.30170172]), + 'Rotation': array([-1.55933211e-02, 7.44394379e+01, -6.19506883e-03]), + 'Velocity': array([-2.19828397e-01, -3.95523071e-01, -3.24249254e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5458374023438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.76953125, 15942.58105469, 30. ]), + 'frame': 29045, + 'frame_number': 29045, + 'framesequence': 117492, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.8165069967508, + 'timestamp_carla': 991815, + 'timestamp_device': 2610374, + 'timestamp_stream': 991.8165069967508, + 'transform': [array([ 3.35145416e+02, 5.48877029e+01, -1.59144670e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([0.01019567, 0.02996074, 3.99369764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.268413543701172, + 'FR_Wheel_Angle': -21.845531463623047, + 'Location': array([243.89889526, 145.92857361, 0.3017092 ]), + 'Rotation': array([-1.65427178e-02, 7.53287964e+01, -7.23266695e-03]), + 'Velocity': array([-2.26756543e-01, -4.06561375e-01, -1.14917757e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5454711914062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.875 , 15942.45605469, 30.00003052]), + 'frame': 29046, + 'frame_number': 29046, + 'framesequence': 117496, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.8504542000592, + 'timestamp_carla': 991849, + 'timestamp_device': 2610408, + 'timestamp_stream': 991.8504542000592, + 'transform': [array([ 3.35146515e+02, 5.48864136e+01, -1.59148827e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 2.33239238e-03, -1.04146702e-02, 3.77894282e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.198606491088867, + 'FR_Wheel_Angle': -22.853538513183594, + 'Location': array([243.86048889, 145.85292053, 0.30169326]), + 'Rotation': array([-1.42819248e-02, 7.60849533e+01, -6.83593703e-03]), + 'Velocity': array([-2.03975290e-01, -3.51524144e-01, 2.32696539e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452880859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23711.98046875, 15942.33105469, 30.00003052]), + 'frame': 29047, + 'frame_number': 29047, + 'framesequence': 117500, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.8827855996788, + 'timestamp_carla': 991882, + 'timestamp_device': 2610441, + 'timestamp_stream': 991.8827855996788, + 'transform': [array([ 3.35147583e+02, 5.48851662e+01, -1.59138978e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.01299437, 0.05472213, 4.26331043]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.1945858001709, + 'FR_Wheel_Angle': -23.012990951538086, + 'Location': array([243.81797791, 145.76672363, 0.3017118 ]), + 'Rotation': array([-1.68159250e-02, 7.69521255e+01, -7.69042829e-03]), + 'Velocity': array([-2.16964379e-01, -3.86492223e-01, 9.07421127e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54443359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.08984375, 15942.20214844, 30. ]), + 'frame': 29048, + 'frame_number': 29048, + 'framesequence': 117504, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.9164688996971, + 'timestamp_carla': 991915, + 'timestamp_device': 2610474, + 'timestamp_stream': 991.9164688996971, + 'transform': [array([ 3.35148712e+02, 5.48838348e+01, -1.59143478e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.02079641, -0.02621355, 4.22534084]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.125171661376953, + 'FR_Wheel_Angle': -23.075706481933594, + 'Location': array([243.76565552, 145.65556335, 0.30172253]), + 'Rotation': array([-1.86464153e-02, 7.80618744e+01, -8.11767485e-03]), + 'Velocity': array([-2.22596183e-01, -4.23221350e-01, 1.57623290e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5465087890625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.1953125 , 15942.078125 , 29.99996948]), + 'frame': 29049, + 'frame_number': 29049, + 'framesequence': 117508, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.950186599046, + 'timestamp_carla': 991949, + 'timestamp_device': 2610508, + 'timestamp_stream': 991.950186599046, + 'transform': [array([ 3.35149841e+02, 5.48825073e+01, -1.59146070e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 1.60297416e-02, -4.08114772e-03, 4.50363016e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.09377670288086, + 'FR_Wheel_Angle': -26.362838745117188, + 'Location': array([243.72642517, 145.57089233, 0.3017036 ]), + 'Rotation': array([-1.59553215e-02, 7.89488144e+01, -8.05664062e-03]), + 'Velocity': array([-2.20289648e-01, -3.97745013e-01, 2.42233273e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5455322265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.30859375, 15941.94433594, 30. ]), + 'frame': 29050, + 'frame_number': 29050, + 'framesequence': 117512, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 991.9823562987149, + 'timestamp_carla': 991981, + 'timestamp_device': 2610541, + 'timestamp_stream': 991.9823562987149, + 'transform': [array([ 3.35150940e+02, 5.48812103e+01, -1.59136623e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01006623, -0.02084336, 4.40298176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.295928955078125, + 'FR_Wheel_Angle': -25.853862762451172, + 'Location': array([243.68191528, 145.47622681, 0.30170184]), + 'Rotation': array([-1.60167925e-02, 8.00433884e+01, -6.25610445e-03]), + 'Velocity': array([-2.07631007e-01, -3.92683357e-01, 1.10559464e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5450439453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.421875 , 15941.81152344, 30. ]), + 'frame': 29051, + 'frame_number': 29051, + 'framesequence': 117516, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.0160618983209, + 'timestamp_carla': 992015, + 'timestamp_device': 2610574, + 'timestamp_stream': 992.0160618983209, + 'transform': [array([ 3.35152100e+02, 5.48798409e+01, -1.59142420e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.01366854, -0.07304928, 4.56829166]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.35640335083008, + 'FR_Wheel_Angle': -25.736398696899414, + 'Location': array([243.6396637 , 145.3817749 , 0.30170906]), + 'Rotation': array([-1.77038498e-02, 8.11153336e+01, -7.47680804e-03]), + 'Velocity': array([-2.05963746e-01, -4.22491193e-01, 2.53486633e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5468139648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.53125 , 15941.68261719, 30.00003052]), + 'frame': 29052, + 'frame_number': 29052, + 'framesequence': 117520, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.0495106987655, + 'timestamp_carla': 992048, + 'timestamp_device': 2610608, + 'timestamp_stream': 992.0495106987655, + 'transform': [array([ 3.35153259e+02, 5.48784752e+01, -1.59143597e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.01134744, -0.00858359, 3.70698166]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.83592987060547, + 'FR_Wheel_Angle': -27.29215431213379, + 'Location': array([243.59761047, 145.28353882, 0.30170876]), + 'Rotation': array([-1.66041888e-02, 8.22133713e+01, -6.43920945e-03]), + 'Velocity': array([-2.01812893e-01, -4.11017478e-01, 5.72013851e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5457763671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.6484375 , 15941.54492188, 30.00003052]), + 'frame': 29053, + 'frame_number': 29053, + 'framesequence': 117524, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.0830763988197, + 'timestamp_carla': 992082, + 'timestamp_device': 2610641, + 'timestamp_stream': 992.0830763988197, + 'transform': [array([ 3.35154449e+02, 5.48770905e+01, -1.59145460e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-7.82170857e-04, 2.21912637e-02, 4.29891586e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.42755126953125, + 'FR_Wheel_Angle': -28.022018432617188, + 'Location': array([243.55728149, 145.19026184, 0.30170032]), + 'Rotation': array([-1.51630193e-02, 8.33785629e+01, -6.83593750e-03]), + 'Velocity': array([-1.99200347e-01, -3.82281601e-01, 2.79564847e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5455322265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.765625 , 15941.40820312, 30. ]), + 'frame': 29054, + 'frame_number': 29054, + 'framesequence': 117528, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.1163839995861, + 'timestamp_carla': 992115, + 'timestamp_device': 2610674, + 'timestamp_stream': 992.1163839995861, + 'transform': [array([ 3.35155609e+02, 5.48756905e+01, -1.59144551e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.05552625, 0.08007366, 5.46095514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.4536018371582, + 'FR_Wheel_Angle': -28.198423385620117, + 'Location': array([243.52078247, 145.10206604, 0.3017092 ]), + 'Rotation': array([-1.73896607e-02, 8.44985123e+01, -8.33129976e-03]), + 'Velocity': array([-2.05645874e-01, -4.29561108e-01, -3.40652441e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.545166015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23712.8828125 , 15941.26953125, 30. ]), + 'frame': 29055, + 'frame_number': 29055, + 'framesequence': 117532, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.1493680998683, + 'timestamp_carla': 992148, + 'timestamp_device': 2610708, + 'timestamp_stream': 992.1493680998683, + 'transform': [array([ 3.35156799e+02, 5.48743057e+01, -1.59141392e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([0.01807637, 0.0823345 , 6.4666872 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.4500617980957, + 'FR_Wheel_Angle': -28.296527862548828, + 'Location': array([243.47718811, 144.99168396, 0.30171129]), + 'Rotation': array([-1.87693592e-02, 8.59034042e+01, -8.94165132e-03]), + 'Velocity': array([-2.28626177e-01, -4.70183015e-01, -1.83305732e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452880859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713. , 15941.12988281, 30.00003052]), + 'frame': 29056, + 'frame_number': 29056, + 'framesequence': 117536, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.1825985983014, + 'timestamp_carla': 992181, + 'timestamp_device': 2610741, + 'timestamp_stream': 992.1825985983014, + 'transform': [array([ 3.35157990e+02, 5.48728981e+01, -1.59141809e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([0.01560239, 0.09724054, 6.69989157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.658390045166016, + 'FR_Wheel_Angle': -30.784067153930664, + 'Location': array([243.43701172, 144.887146 , 0.30170864]), + 'Rotation': array([-1.55933211e-02, 8.72661362e+01, -7.69042969e-03]), + 'Velocity': array([-2.17959568e-01, -4.27607000e-01, -1.39045718e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5459594726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.1171875, 15940.9921875, 30. ]), + 'frame': 29057, + 'frame_number': 29057, + 'framesequence': 117540, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.2152190990746, + 'timestamp_carla': 992214, + 'timestamp_device': 2610774, + 'timestamp_stream': 992.2152190990746, + 'transform': [array([ 3.35159180e+02, 5.48715019e+01, -1.59137607e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-1.09882408e-03, 2.77920309e-02, 6.51358700e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.670692443847656, + 'FR_Wheel_Angle': -30.7889404296875, + 'Location': array([243.39790344, 144.78421021, 0.30170891]), + 'Rotation': array([-1.67203024e-02, 8.87027512e+01, -6.77490281e-03]), + 'Velocity': array([-2.02757418e-01, -4.45695728e-01, -1.16119380e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5459594726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.23828125, 15940.8515625 , 29.99996948]), + 'frame': 29058, + 'frame_number': 29058, + 'framesequence': 117544, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.2501202002168, + 'timestamp_carla': 992249, + 'timestamp_device': 2610807, + 'timestamp_stream': 992.2501202002168, + 'transform': [array([ 3.35160461e+02, 5.48700180e+01, -1.59152836e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-6.18411228e-03, 4.08513248e-02, 6.26647663e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.65656280517578, + 'FR_Wheel_Angle': -30.78605842590332, + 'Location': array([243.36325073, 144.68450928, 0.30170003]), + 'Rotation': array([-1.55318491e-02, 9.00814743e+01, -4.48608398e-03]), + 'Velocity': array([-1.76100343e-01, -4.18499559e-01, -6.36386831e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5466918945312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.35546875, 15940.71191406, 30. ]), + 'frame': 29059, + 'frame_number': 29059, + 'framesequence': 117548, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.2820669971406, + 'timestamp_carla': 992281, + 'timestamp_device': 2610841, + 'timestamp_stream': 992.2820669971406, + 'transform': [array([ 3.35161621e+02, 5.48686333e+01, -1.59139395e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.00799174, -0.01077908, 4.74040222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.680049896240234, + 'FR_Wheel_Angle': -30.789207458496094, + 'Location': array([243.33078003, 144.58250427, 0.3017036 ]), + 'Rotation': array([-1.63309816e-02, 9.14673920e+01, -5.40160993e-03]), + 'Velocity': array([-1.65497676e-01, -4.28484440e-01, -1.70488347e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5436401367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.48632812, 15940.56152344, 30. ]), + 'frame': 29060, + 'frame_number': 29060, + 'framesequence': 117552, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00031128880800679326, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.3174024969339, + 'timestamp_carla': 992316, + 'timestamp_device': 2610874, + 'timestamp_stream': 992.3174024969339, + 'transform': [array([ 3.35162933e+02, 5.48670883e+01, -1.59157515e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 0.02124527, -0.02785035, 4.96409178]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66343307495117, + 'FR_Wheel_Angle': -30.78679656982422, + 'Location': array([243.3004303 , 144.47836304, 0.30171517]), + 'Rotation': array([-1.77038498e-02, 9.28770142e+01, -7.01904390e-03]), + 'Velocity': array([-1.62736505e-01, -4.53437060e-01, 7.73620559e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462646484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.6015625 , 15940.42480469, 30.00006104]), + 'frame': 29061, + 'frame_number': 29061, + 'framesequence': 117556, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.002288888208568096, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.3509274981916, + 'timestamp_carla': 992350, + 'timestamp_device': 2610907, + 'timestamp_stream': 992.3509274981916, + 'transform': [array([ 3.35164185e+02, 5.48656044e+01, -1.59152642e-01]), + array([-6.95996219e-03, 4.03995018e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.0082093 , 0.02509611, 5.01128626]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6883430480957, + 'FR_Wheel_Angle': -30.796716690063477, + 'Location': array([243.27305603, 144.37614441, 0.30170739]), + 'Rotation': array([-1.60509441e-02, 9.42493134e+01, -5.40161226e-03]), + 'Velocity': array([-1.48581043e-01, -4.39771801e-01, 1.45378115e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.542724609375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.73242188, 15940.26757812, 30.00003052]), + 'frame': 29062, + 'frame_number': 29062, + 'framesequence': 117560, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.011389507912099361, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.3834613002837, + 'timestamp_carla': 992382, + 'timestamp_device': 2610941, + 'timestamp_stream': 992.3834613002837, + 'transform': [array([ 3.35165955e+02, 5.48647346e+01, -1.59146607e-01]), + array([-6.98728301e-03, 4.03998375e+01, 1.61437914e-02])]} +{'AngularVelocity': array([ 9.60156042e-03, -2.58625532e-03, 4.34630442e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.70284652709961, + 'FR_Wheel_Angle': -30.807754516601562, + 'Location': array([243.24926758, 144.27774048, 0.30170187]), + 'Rotation': array([-1.55933211e-02, 9.55611954e+01, -4.73022461e-03]), + 'Velocity': array([-1.27883300e-01, -4.10936892e-01, -3.41701489e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.543701171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.85742188, 15940.12011719, 30.00003052]), + 'frame': 29063, + 'frame_number': 29063, + 'framesequence': 117564, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.02382274903357029, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.4157097004354, + 'timestamp_carla': 992414, + 'timestamp_device': 2610974, + 'timestamp_stream': 992.4157097004354, + 'transform': [array([ 3.35168640e+02, 5.48646660e+01, -1.59146532e-01]), + array([-7.04875495e-03, 4.04006424e+01, 1.61437877e-02])]} +{'AngularVelocity': array([0.0199246 , 0.06135027, 6.47206688]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.667816162109375, + 'FR_Wheel_Angle': -30.788387298583984, + 'Location': array([243.22636414, 144.17364502, 0.30171862]), + 'Rotation': array([-1.75467543e-02, 9.69619598e+01, -7.62939407e-03]), + 'Velocity': array([-1.40689969e-01, -4.49350119e-01, 2.69904122e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.545654296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23713.9765625 , 15939.9765625 , 30.00003052]), + 'frame': 29064, + 'frame_number': 29064, + 'framesequence': 117568, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0380321703851223, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.4493243992329, + 'timestamp_carla': 992448, + 'timestamp_device': 2611007, + 'timestamp_stream': 992.4493243992329, + 'transform': [array([ 3.35172546e+02, 5.48655930e+01, -1.59164235e-01]), + array([-7.14437757e-03, 4.04020958e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-0.0673376 , 0.10599882, 6.39103699]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.652099609375, + 'FR_Wheel_Angle': -30.777076721191406, + 'Location': array([243.20565796, 144.06814575, 0.30170986]), + 'Rotation': array([-1.68773960e-02, 9.83701401e+01, -6.43920898e-03]), + 'Velocity': array([-1.26519844e-01, -4.87075329e-01, 6.90269444e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5470581054688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23714.09179688, 15939.83203125, 30. ]), + 'frame': 29065, + 'frame_number': 29065, + 'framesequence': 117572, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05310220643877983, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.4827017001808, + 'timestamp_carla': 992481, + 'timestamp_device': 2611041, + 'timestamp_stream': 992.4827017001808, + 'transform': [array([ 3.35177521e+02, 5.48676567e+01, -1.59178078e-01]), + array([-7.23316986e-03, 4.04041786e+01, 1.61437895e-02])]} +{'AngularVelocity': array([ 1.60996933e-02, -3.70348315e-03, 6.13416290e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.673030853271484, + 'FR_Wheel_Angle': -30.788801193237305, + 'Location': array([243.18708801, 143.95730591, 0.30170843]), + 'Rotation': array([-1.65085662e-02, 9.98371811e+01, -5.61523391e-03]), + 'Velocity': array([-1.09009534e-01, -4.63778406e-01, -4.32109809e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.545654296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23714.21484375, 15939.67675781, 30.00003052]), + 'frame': 29066, + 'frame_number': 29066, + 'framesequence': 117576, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06917935609817505, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.515900798142, + 'timestamp_carla': 992515, + 'timestamp_device': 2611074, + 'timestamp_stream': 992.515900798142, + 'transform': [array([ 3.35183716e+02, 5.48708687e+01, -1.59190103e-01]), + array([-7.32879248e-03, 4.04069672e+01, 1.61437895e-02])]} +{'AngularVelocity': array([-2.10239156e-03, 1.85924047e-03, 5.64848518e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68621826171875, + 'FR_Wheel_Angle': -30.798601150512695, + 'Location': array([243.17253113, 143.85424805, 0.30169868]), + 'Rotation': array([-1.57162640e-02, 1.01197418e+02, -4.88281157e-03]), + 'Velocity': array([-9.05319974e-02, -4.40060079e-01, -1.08146669e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.545166015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23714.33398438, 15939.5234375 , 30. ]), + 'frame': 29067, + 'frame_number': 29067, + 'framesequence': 117580, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.08503677695989609, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.5491623990238, + 'timestamp_carla': 992548, + 'timestamp_device': 2611107, + 'timestamp_stream': 992.5491623990238, + 'transform': [array([ 3.35191254e+02, 5.48752823e+01, -1.59202501e-01]), + array([-7.41758524e-03, 4.04104576e+01, 1.61437914e-02])]} +{'AngularVelocity': array([-2.35903985e-03, 8.47510099e-02, 6.58514977e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.668697357177734, + 'FR_Wheel_Angle': -30.785696029663086, + 'Location': array([243.15815735, 143.73226929, 0.30171072]), + 'Rotation': array([-1.69115476e-02, 1.02805824e+02, -6.95800642e-03]), + 'Velocity': array([-9.64005366e-02, -4.64233726e-01, -7.69901235e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5450439453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23714.45117188, 15939.36914062, 30. ]), + 'frame': 29068, + 'frame_number': 29068, + 'framesequence': 117584, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10078433156013489, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.5839508995414, + 'timestamp_carla': 992583, + 'timestamp_device': 2611141, + 'timestamp_stream': 992.5839508995414, + 'transform': [array([ 3.35200256e+02, 5.48810234e+01, -1.59302518e-01]), + array([-7.50637753e-03, 4.04147644e+01, 1.61132719e-02])]} +{'AngularVelocity': array([0.01361057, 0.00788056, 6.20699596]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66512680053711, + 'FR_Wheel_Angle': -30.78700065612793, + 'Location': array([243.14816284, 143.6214447 , 0.30170509]), + 'Rotation': array([-1.66588314e-02, 1.04252403e+02, -5.58471633e-03]), + 'Velocity': array([-7.35314786e-02, -4.72525328e-01, -6.73580143e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5447998046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23714.56640625, 15939.21289062, 30. ]), + 'frame': 29069, + 'frame_number': 29069, + 'framesequence': 117588, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11730094254016876, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.6153917983174, + 'timestamp_carla': 992614, + 'timestamp_device': 2611174, + 'timestamp_stream': 992.6153917983174, + 'transform': [array([ 3.35210083e+02, 5.48875771e+01, -1.58913493e-01]), + array([-7.56784901e-03, 4.04195328e+01, 1.62658617e-02])]} +{'AngularVelocity': array([-0.01531918, 0.03661241, 6.01592827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6999397277832, + 'FR_Wheel_Angle': -30.796720504760742, + 'Location': array([243.14157104, 143.5186615 , 0.30168962]), + 'Rotation': array([-1.49854338e-02, 1.05599434e+02, -3.75366234e-03]), + 'Velocity': array([-5.58073670e-02, -4.32277530e-01, 8.04233568e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5421752929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23714.68359375, 15939.046875 , 30. ]), + 'frame': 29070, + 'frame_number': 29070, + 'framesequence': 117592, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1325540989637375, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.6500036977232, + 'timestamp_carla': 992649, + 'timestamp_device': 2611207, + 'timestamp_stream': 992.6500036977232, + 'transform': [array([ 3.35227020e+02, 5.48965302e+01, -1.50828123e-01]), + array([-8.33282992e-03, 4.04272232e+01, 1.95617564e-02])]} +{'AngularVelocity': array([-0.07387284, 0.08899676, 5.84226274]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68480682373047, + 'FR_Wheel_Angle': -30.802143096923828, + 'Location': array([243.13764954, 143.41802979, 0.30170357]), + 'Rotation': array([-1.69115476e-02, 1.06910690e+02, -6.65283296e-03]), + 'Velocity': array([-5.00309169e-02, -4.76099640e-01, -2.16341010e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452880859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23714.79101562, 15938.88769531, 29.99996948]), + 'frame': 29071, + 'frame_number': 29071, + 'framesequence': 117596, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14934538304805756, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.6832755990326, + 'timestamp_carla': 992682, + 'timestamp_device': 2611241, + 'timestamp_stream': 992.6832755990326, + 'transform': [array([ 3.35271332e+02, 5.49268265e+01, -1.40054017e-01]), + array([-1.01359999e-02, 4.04489975e+01, 2.39868034e-02])]} +{'AngularVelocity': array([-0.02268514, 0.05179371, 7.14187956]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67017364501953, + 'FR_Wheel_Angle': -30.79703140258789, + 'Location': array([243.13569641, 143.30726624, 0.30171654]), + 'Rotation': array([-1.77311692e-02, 1.08373352e+02, -7.56835844e-03]), + 'Velocity': array([-4.43405285e-02, -4.96915698e-01, 6.20651263e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5338134765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23715.09179688, 15938.46289062, 30. ]), + 'frame': 29072, + 'frame_number': 29072, + 'framesequence': 117600, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16522110998630524, + 'throttle_input': 0.23411917686462402, + 'timestamp': 992.7152114994824, + 'timestamp_carla': 992714, + 'timestamp_device': 2611274, + 'timestamp_stream': 992.7152114994824, + 'transform': [array([ 3.35339691e+02, 5.49777527e+01, -1.32124558e-01]), + array([-1.16932830e-02, 4.04836502e+01, 2.72521786e-02])]} +{'AngularVelocity': array([ 3.85767850e-03, -6.89491862e-03, 5.97350979e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.655269622802734, + 'FR_Wheel_Angle': -30.785993576049805, + 'Location': array([243.137146 , 143.20343018, 0.30169827]), + 'Rotation': array([-1.72120761e-02, 1.09677490e+02, -7.44628906e-03]), + 'Velocity': array([-2.45292522e-02, -4.69789416e-01, -2.33173370e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5210571289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23715.5546875 , 15937.76074219, 30. ]), + 'frame': 29073, + 'frame_number': 29073, + 'framesequence': 117604, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1814996898174286, + 'throttle_input': 0.2380865216255188, + 'timestamp': 992.7494139969349, + 'timestamp_carla': 992748, + 'timestamp_device': 2611307, + 'timestamp_stream': 992.7494139969349, + 'transform': [array([ 3.35437500e+02, 5.50541191e+01, -1.28794968e-01]), + array([-1.22670187e-02, 4.05340309e+01, 2.86254752e-02])]} +{'AngularVelocity': array([ 0.01420317, -0.01010554, 4.88012171]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66831588745117, + 'FR_Wheel_Angle': -30.785221099853516, + 'Location': array([243.14051819, 143.09831238, 0.30171683]), + 'Rotation': array([-1.72120761e-02, 1.11041603e+02, -6.62231445e-03]), + 'Velocity': array([-1.26510235e-02, -4.68199998e-01, 2.02751162e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5130004882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23716.078125 , 15936.9140625, 30. ]), + 'frame': 29074, + 'frame_number': 29074, + 'framesequence': 117608, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19829095900058746, + 'throttle_input': 0.24205386638641357, + 'timestamp': 992.7821733988822, + 'timestamp_carla': 992781, + 'timestamp_device': 2611341, + 'timestamp_stream': 992.7821733988822, + 'transform': [array([ 3.35553894e+02, 5.51484375e+01, -1.28977969e-01]), + array([-1.25470571e-02, 4.05948448e+01, 2.85644326e-02])]} +{'AngularVelocity': array([ 0.01123746, -0.0118114 , 4.48088884]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68608856201172, + 'FR_Wheel_Angle': -30.798858642578125, + 'Location': array([243.14634705, 142.99458313, 0.30170554]), + 'Rotation': array([-1.58938486e-02, 1.12389053e+02, -4.79125930e-03]), + 'Velocity': array([ 3.66211374e-04, -4.41070199e-01, 1.09052657e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.506591796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23716.6875 , 15935.91113281, 30.00003052]), + 'frame': 29075, + 'frame_number': 29075, + 'framesequence': 117612, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.214844211935997, + 'throttle_input': 0.24602121114730835, + 'timestamp': 992.8168917968869, + 'timestamp_carla': 992816, + 'timestamp_device': 2611374, + 'timestamp_stream': 992.8168917968869, + 'transform': [array([ 3.35660461e+02, 5.52332115e+01, -1.33149415e-01]), + array([-1.24241132e-02, 4.06502380e+01, 2.68859733e-02])]} +{'AngularVelocity': array([ 0.07523879, -0.11440119, 5.46382904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66646194458008, + 'FR_Wheel_Angle': -30.784040451049805, + 'Location': array([243.15426636, 142.8941803 , 0.30170402]), + 'Rotation': array([-1.63309816e-02, 1.13706375e+02, -5.34057617e-03]), + 'Velocity': array([ 1.76668111e-02, -4.25293088e-01, 1.74064626e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5072021484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23717.26367188, 15934.90429688, 30. ]), + 'frame': 29076, + 'frame_number': 29076, + 'framesequence': 117616, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23165379464626312, + 'throttle_input': 0.24602121114730835, + 'timestamp': 992.8487232998013, + 'timestamp_carla': 992847, + 'timestamp_device': 2611407, + 'timestamp_stream': 992.8487232998013, + 'transform': [array([ 3.35783539e+02, 5.53341866e+01, -1.34409711e-01]), + array([-1.28817363e-02, 4.07149620e+01, 2.63976902e-02])]} +{'AngularVelocity': array([-2.16834154e-03, 6.19906327e-03, 6.07537365e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.662044525146484, + 'FR_Wheel_Angle': -30.78435707092285, + 'Location': array([243.16566467, 142.78507996, 0.30171332]), + 'Rotation': array([-1.80658493e-02, 1.15129280e+02, -7.99560454e-03]), + 'Velocity': array([ 1.97824687e-02, -4.91932273e-01, 1.16519928e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5086059570312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23717.84765625, 15933.86914062, 29.99996948]), + 'frame': 29077, + 'frame_number': 29077, + 'framesequence': 117620, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24740135669708252, + 'throttle_input': 0.24602121114730835, + 'timestamp': 992.8816765993834, + 'timestamp_carla': 992880, + 'timestamp_device': 2611441, + 'timestamp_stream': 992.8816765993834, + 'transform': [array([ 3.35938507e+02, 5.54622459e+01, -1.31732523e-01]), + array([-1.38857737e-02, 4.07967033e+01, 2.75268387e-02])]} +{'AngularVelocity': array([-5.87496441e-03, -2.32772548e-02, 6.58107090e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.63487243652344, + 'FR_Wheel_Angle': -30.7729434967041, + 'Location': array([243.17976379, 142.67315674, 0.30171379]), + 'Rotation': array([-1.78541131e-02, 1.16612457e+02, -7.41577148e-03]), + 'Velocity': array([ 3.83254029e-02, -5.16686738e-01, 5.17845137e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5115356445312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23718.40234375, 15932.8359375 , 30. ]), + 'frame': 29078, + 'frame_number': 29078, + 'framesequence': 117624, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.26228830218315125, + 'throttle_input': 0.24602121114730835, + 'timestamp': 992.9157762974501, + 'timestamp_carla': 992915, + 'timestamp_device': 2611474, + 'timestamp_stream': 992.9157762974501, + 'transform': [array([ 3.36111816e+02, 5.56077118e+01, -1.33742750e-01]), + array([-1.35237742e-02, 4.08886566e+01, 2.67028697e-02])]} +{'AngularVelocity': array([-0.03647001, 0.03618252, 5.86194992]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67815017700195, + 'FR_Wheel_Angle': -30.791549682617188, + 'Location': array([243.19618225, 142.56521606, 0.30170739]), + 'Rotation': array([-1.54772075e-02, 1.18030090e+02, -4.27246094e-03]), + 'Velocity': array([ 4.24760059e-02, -4.70734537e-01, 9.31358300e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5070190429688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23719.07421875, 15931.56445312, 29.99996948]), + 'frame': 29079, + 'frame_number': 29079, + 'framesequence': 117628, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.27992188930511475, + 'throttle_input': 0.24602121114730835, + 'timestamp': 992.9496005997062, + 'timestamp_carla': 992948, + 'timestamp_device': 2611507, + 'timestamp_stream': 992.9496005997062, + 'transform': [array([ 3.36281403e+02, 5.57507019e+01, -1.37189373e-01]), + array([-1.31549435e-02, 4.09788780e+01, 2.52990555e-02])]} +{'AngularVelocity': array([-5.15821055e-02, 4.08905838e-03, 6.54972935e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.661537170410156, + 'FR_Wheel_Angle': -30.76792335510254, + 'Location': array([243.21574402, 142.45834351, 0.30172074]), + 'Rotation': array([-1.78541131e-02, 1.19449234e+02, -6.86645368e-03]), + 'Velocity': array([ 7.02743009e-02, -5.14003634e-01, 3.20363033e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23719.75 , 15930.25097656, 29.99996948]), + 'frame': 29080, + 'frame_number': 29080, + 'framesequence': 117632, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.295138418674469, + 'throttle_input': 0.24602121114730835, + 'timestamp': 992.9826573990285, + 'timestamp_carla': 992981, + 'timestamp_device': 2611541, + 'timestamp_stream': 992.9826573990285, + 'transform': [array([ 3.36457428e+02, 5.59004288e+01, -1.40293390e-01]), + array([-1.31207928e-02, 4.10728951e+01, 2.40478385e-02])]} +{'AngularVelocity': array([-3.88896535e-03, 1.21592069e-02, 6.08236456e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66086959838867, + 'FR_Wheel_Angle': -30.782339096069336, + 'Location': array([243.23878479, 142.3457489 , 0.30171141]), + 'Rotation': array([-1.65427178e-02, 1.20944527e+02, -5.52368117e-03]), + 'Velocity': array([ 7.00952038e-02, -4.88049358e-01, 1.54662135e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5113525390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23720.390625 , 15928.95996094, 29.99996948]), + 'frame': 29081, + 'frame_number': 29081, + 'framesequence': 117636, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3118015229701996, + 'throttle_input': 0.24602121114730835, + 'timestamp': 993.0158369988203, + 'timestamp_carla': 993015, + 'timestamp_device': 2611574, + 'timestamp_stream': 993.0158369988203, + 'transform': [array([ 3.36642609e+02, 5.60599709e+01, -1.43971711e-01]), + array([-1.34008303e-02, 4.11723785e+01, 2.25829929e-02])]} +{'AngularVelocity': array([ 0.03288458, -0.05589081, 4.93092775]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.70936584472656, + 'FR_Wheel_Angle': -30.791351318359375, + 'Location': array([243.26348877, 142.24255371, 0.30169612]), + 'Rotation': array([-1.36945285e-02, 1.22284897e+02, -1.83105469e-03]), + 'Velocity': array([ 8.12480077e-02, -4.13261205e-01, 1.81612966e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5147094726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23721.01757812, 15927.66308594, 30. ]), + 'frame': 29082, + 'frame_number': 29082, + 'framesequence': 117640, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3273293375968933, + 'throttle_input': 0.24602121114730835, + 'timestamp': 993.0500632971525, + 'timestamp_carla': 993049, + 'timestamp_device': 2611607, + 'timestamp_stream': 993.0500632971525, + 'transform': [array([ 3.36845306e+02, 5.62367096e+01, -1.47214994e-01]), + array([-1.31822648e-02, 4.12818146e+01, 2.12707371e-02])]} +{'AngularVelocity': array([-0.01797863, 0.03015084, 5.26322412]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67890167236328, + 'FR_Wheel_Angle': -30.796358108520508, + 'Location': array([243.29066467, 142.1375885 , 0.30170357]), + 'Rotation': array([-1.63924526e-02, 1.23690620e+02, -5.79833984e-03]), + 'Velocity': array([ 8.63338262e-02, -4.59447920e-01, -1.98841095e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5174560546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23721.59960938, 15926.37011719, 29.99996948]), + 'frame': 29083, + 'frame_number': 29083, + 'framesequence': 117644, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.343479722738266, + 'throttle_input': 0.24602121114730835, + 'timestamp': 993.0824852995574, + 'timestamp_carla': 993081, + 'timestamp_device': 2611641, + 'timestamp_stream': 993.0824852995574, + 'transform': [array([ 3.37047485e+02, 5.64147072e+01, -1.49378806e-01]), + array([-1.29636982e-02, 4.13914299e+01, 2.03857273e-02])]} +{'AngularVelocity': array([-4.98022325e-02, -5.07583003e-03, 5.19251776e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.7041130065918, + 'FR_Wheel_Angle': -30.795896530151367, + 'Location': array([243.31767273, 142.04188538, 0.3016994 ]), + 'Rotation': array([-1.57162640e-02, 1.24979584e+02, -5.06591843e-03]), + 'Velocity': array([ 1.02824926e-01, -4.42457348e-01, -9.11045063e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5194091796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23722.17578125, 15925.03613281, 29.99996948]), + 'frame': 29084, + 'frame_number': 29084, + 'framesequence': 117648, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3602893054485321, + 'throttle_input': 0.24602121114730835, + 'timestamp': 993.117306496948, + 'timestamp_carla': 993116, + 'timestamp_device': 2611674, + 'timestamp_stream': 993.117306496948, + 'transform': [array([ 3.37261719e+02, 5.66041489e+01, -1.52311772e-01]), + array([-1.20894341e-02, 4.15078201e+01, 1.91650242e-02])]} +{'AngularVelocity': array([5.26946085e-03, 1.20150959e-02, 6.50183535e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.657711029052734, + 'FR_Wheel_Angle': -30.7855281829834, + 'Location': array([243.35032654, 141.93547058, 0.30171347]), + 'Rotation': array([-1.78541131e-02, 1.26452652e+02, -7.41577055e-03]), + 'Velocity': array([ 1.12938859e-01, -4.77329671e-01, -8.95309422e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52392578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23722.70507812, 15923.75976562, 29.99996948]), + 'frame': 29085, + 'frame_number': 29085, + 'framesequence': 117652, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3763664662837982, + 'throttle_input': 0.24602121114730835, + 'timestamp': 993.1499074995518, + 'timestamp_carla': 993149, + 'timestamp_device': 2611707, + 'timestamp_stream': 993.1499074995518, + 'transform': [array([ 3.37472656e+02, 5.67929497e+01, -1.54631078e-01]), + array([-1.19050192e-02, 4.16230125e+01, 1.82189792e-02])]} +{'AngularVelocity': array([ 0.02830447, -0.00566629, 5.55167103]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.687400817871094, + 'FR_Wheel_Angle': -30.799598693847656, + 'Location': array([243.38375854, 141.83592224, 0.30170646]), + 'Rotation': array([-1.55318491e-02, 1.27823364e+02, -4.21142578e-03]), + 'Velocity': array([ 1.14097953e-01, -4.23605502e-01, 1.17926596e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5258178710938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23723.25976562, 15922.40722656, 29.99996948]), + 'frame': 29086, + 'frame_number': 29086, + 'framesequence': 117656, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3916013240814209, + 'throttle_input': 0.24602121114730835, + 'timestamp': 993.1827904991806, + 'timestamp_carla': 993182, + 'timestamp_device': 2611741, + 'timestamp_stream': 993.1827904991806, + 'transform': [array([ 3.37699829e+02, 5.69968452e+01, -1.53101802e-01]), + array([-1.29978489e-02, 4.17473068e+01, 1.88903678e-02])]} +{'AngularVelocity': array([ 0.04027325, -0.03083443, 6.56170321]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.683799743652344, + 'FR_Wheel_Angle': -30.79900550842285, + 'Location': array([243.41868591, 141.7403717 , 0.30169693]), + 'Rotation': array([-1.70003399e-02, 1.29154510e+02, -6.28661970e-03]), + 'Velocity': array([ 1.31048426e-01, -4.28232610e-01, -1.76324844e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5303344726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23723.73632812, 15921.15820312, 29.99996948]), + 'frame': 29087, + 'frame_number': 29087, + 'framesequence': 117660, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4078066647052765, + 'throttle_input': 0.24602121114730835, + 'timestamp': 993.216877900064, + 'timestamp_carla': 993216, + 'timestamp_device': 2611774, + 'timestamp_stream': 993.216877900064, + 'transform': [array([ 3.37951477e+02, 5.72255745e+01, -1.53692096e-01]), + array([-1.28202643e-02, 4.18856659e+01, 1.86462253e-02])]} +{'AngularVelocity': array([-0.03395903, 0.00745931, 5.25924015]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.65532302856445, + 'FR_Wheel_Angle': -30.782072067260742, + 'Location': array([243.45033264, 141.65867615, 0.30170932]), + 'Rotation': array([-1.77653208e-02, 1.30289825e+02, -7.41577335e-03]), + 'Velocity': array([ 1.48737058e-01, -4.58070010e-01, -2.09999082e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5269165039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23724.26757812, 15919.77929688, 30. ]), + 'frame': 29088, + 'frame_number': 29088, + 'framesequence': 117664, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4238838255405426, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.2491169981658, + 'timestamp_carla': 993248, + 'timestamp_device': 2611807, + 'timestamp_stream': 993.2491169981658, + 'transform': [array([ 3.38217804e+02, 5.74699097e+01, -1.51589543e-01]), + array([-1.36398869e-02, 4.20326881e+01, 1.95312351e-02])]} +{'AngularVelocity': array([-0.01999501, 0.02490467, 5.14726734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69015121459961, + 'FR_Wheel_Angle': -30.311487197875977, + 'Location': array([243.49177551, 141.55873108, 0.30169493]), + 'Rotation': array([-1.64812449e-02, 1.31695831e+02, -5.67626953e-03]), + 'Velocity': array([ 1.48737282e-01, -4.37750429e-01, -2.41918562e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5267944335938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23724.78125 , 15918.36230469, 30. ]), + 'frame': 29089, + 'frame_number': 29089, + 'framesequence': 117668, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4393566846847534, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.2820384986699, + 'timestamp_carla': 993281, + 'timestamp_device': 2611841, + 'timestamp_stream': 993.2820384986699, + 'transform': [array([ 3.38496399e+02, 5.77274971e+01, -1.51613384e-01]), + array([-1.38243018e-02, 4.21870880e+01, 1.95312276e-02])]} +{'AngularVelocity': array([ 0.01842569, -0.0040138 , 3.574157 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.672298431396484, + 'FR_Wheel_Angle': -28.146575927734375, + 'Location': array([243.53334045, 141.46910095, 0.3017047 ]), + 'Rotation': array([-1.61738880e-02, 1.32887085e+02, -2.44140625e-03]), + 'Velocity': array([ 1.67746171e-01, -3.92340958e-01, -8.75377664e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5247192382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23725.28515625, 15916.921875 , 29.99996948]), + 'frame': 29090, + 'frame_number': 29090, + 'framesequence': 117672, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45411545038223267, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.3160240985453, + 'timestamp_carla': 993315, + 'timestamp_device': 2611874, + 'timestamp_stream': 993.3160240985453, + 'transform': [array([ 3.38790527e+02, 5.80019112e+01, -1.53286889e-01]), + array([-1.32164154e-02, 4.23507652e+01, 1.88293289e-02])]} +{'AngularVelocity': array([ 0.03461857, -0.01444847, 4.56912661]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.2786750793457, + 'FR_Wheel_Angle': -28.212947845458984, + 'Location': array([243.57821655, 141.38108826, 0.30170485]), + 'Rotation': array([-1.60850938e-02, 1.34042679e+02, -4.66918992e-03]), + 'Velocity': array([ 1.70002490e-01, -3.79979968e-01, -6.76345808e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5245971679688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23725.77929688, 15915.43261719, 30. ]), + 'frame': 29091, + 'frame_number': 29091, + 'framesequence': 117676, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47118139266967773, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.3486190997064, + 'timestamp_carla': 993347, + 'timestamp_device': 2611907, + 'timestamp_stream': 993.3486190997064, + 'transform': [array([ 3.39071228e+02, 5.82658768e+01, -1.55406684e-01]), + array([-1.26358494e-02, 4.25075798e+01, 1.79443229e-02])]} +{'AngularVelocity': array([-0.02192057, 0.05815091, 6.27114725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.471683502197266, + 'FR_Wheel_Angle': -28.28339385986328, + 'Location': array([243.63240051, 141.27970886, 0.30172244]), + 'Rotation': array([-1.95001885e-02, 1.35376007e+02, -9.85718053e-03]), + 'Velocity': array([ 2.07889557e-01, -4.77741241e-01, 2.39925386e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5255737304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23726.25390625, 15913.91601562, 30.00003052]), + 'frame': 29092, + 'frame_number': 29092, + 'framesequence': 117680, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48674580454826355, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.3823463991284, + 'timestamp_carla': 993381, + 'timestamp_device': 2611941, + 'timestamp_stream': 993.3823463991284, + 'transform': [array([ 3.39369324e+02, 5.85488663e+01, -1.57488927e-01]), + array([-1.16932830e-02, 4.26748161e+01, 1.70593113e-02])]} +{'AngularVelocity': array([-0.02268953, 0.03728476, 6.14060783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.428428649902344, + 'FR_Wheel_Angle': -25.169862747192383, + 'Location': array([243.69046021, 141.17700195, 0.30172709]), + 'Rotation': array([-1.81204900e-02, 1.36735153e+02, -6.19506789e-03]), + 'Velocity': array([ 2.36336529e-01, -4.73868668e-01, 1.05948449e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5299072265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23726.68164062, 15912.48925781, 29.99996948]), + 'frame': 29093, + 'frame_number': 29093, + 'framesequence': 117684, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.502731442451477, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.4160787984729, + 'timestamp_carla': 993415, + 'timestamp_device': 2611974, + 'timestamp_stream': 993.4160787984729, + 'transform': [array([ 3.39679443e+02, 5.88457718e+01, -1.57999113e-01]), + array([-1.15020378e-02, 4.28494530e+01, 1.68456938e-02])]} +{'AngularVelocity': array([-0.05340499, 0.02100504, 5.51848745]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.6201171875, + 'FR_Wheel_Angle': -25.738319396972656, + 'Location': array([243.75386047, 141.07862854, 0.30170089]), + 'Rotation': array([-1.62353590e-02, 1.37914032e+02, -4.42504836e-03]), + 'Velocity': array([ 2.54964411e-01, -4.45149004e-01, -3.58104699e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5330200195312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23727.09179688, 15911.03027344, 30. ]), + 'frame': 29094, + 'frame_number': 29094, + 'framesequence': 117688, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5190283060073853, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.4503089003265, + 'timestamp_carla': 993449, + 'timestamp_device': 2612007, + 'timestamp_stream': 993.4503089003265, + 'transform': [array([ 3.40029480e+02, 5.91831818e+01, -1.54214174e-01]), + array([-1.44321891e-02, 4.30473213e+01, 1.85241587e-02])]} +{'AngularVelocity': array([-6.92416951e-02, 4.52416629e-04, 4.61051464e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.339107513427734, + 'FR_Wheel_Angle': -25.67374610900879, + 'Location': array([243.8160553, 140.9859314, 0.3017121]), + 'Rotation': array([-1.63309816e-02, 1.39060028e+02, -5.09643555e-03]), + 'Velocity': array([ 2.67098218e-01, -4.35181290e-01, 2.52013211e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23727.49609375, 15909.5546875 , 29.99996948]), + 'frame': 29095, + 'frame_number': 29095, + 'framesequence': 117692, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5343913435935974, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.4824693985283, + 'timestamp_carla': 993481, + 'timestamp_device': 2612041, + 'timestamp_stream': 993.4824693985283, + 'transform': [array([ 3.40373444e+02, 5.95181351e+01, -1.53231084e-01]), + array([-1.45551320e-02, 4.32426300e+01, 1.89208835e-02])]} +{'AngularVelocity': array([-0.03239923, 0.05262683, 5.17979765]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.53217697143555, + 'FR_Wheel_Angle': -24.615041732788086, + 'Location': array([243.88066101, 140.89299011, 0.30170006]), + 'Rotation': array([-1.57162640e-02, 1.40228088e+02, -5.61523438e-03]), + 'Velocity': array([ 2.41383493e-01, -4.04749602e-01, -2.77805320e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5221557617188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23727.94726562, 15907.8671875 , 29.99996948]), + 'frame': 29096, + 'frame_number': 29096, + 'framesequence': 117696, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5491501092910767, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.5176748000085, + 'timestamp_carla': 993517, + 'timestamp_device': 2612074, + 'timestamp_stream': 993.5176748000085, + 'transform': [array([ 3.40751648e+02, 5.98898506e+01, -1.54162064e-01]), + array([-1.40087176e-02, 4.34583893e+01, 1.85241513e-02])]} +{'AngularVelocity': array([-0.00717988, 0.00980756, 3.1516366 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.835956573486328, + 'FR_Wheel_Angle': -23.205778121948242, + 'Location': array([243.94699097, 140.80625916, 0.30171844]), + 'Rotation': array([-1.67817734e-02, 1.41238388e+02, -3.23486328e-03]), + 'Velocity': array([ 0.28155661, -0.3873983 , 0.00077226]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23728.34765625, 15906.27832031, 29.99996948]), + 'frame': 29097, + 'frame_number': 29097, + 'framesequence': 117700, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5552660226821899, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.5487274974585, + 'timestamp_carla': 993548, + 'timestamp_device': 2612107, + 'timestamp_stream': 993.5487274974585, + 'transform': [array([ 3.41088501e+02, 6.02238960e+01, -1.55658454e-01]), + array([-1.28475847e-02, 4.36513596e+01, 1.78527702e-02])]} +{'AngularVelocity': array([-0.02940649, 0.00723752, 3.35776782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.052778244018555, + 'FR_Wheel_Angle': -23.085084915161133, + 'Location': array([244.01347351, 140.72380066, 0.30169839]), + 'Rotation': array([-1.55933211e-02, 1.42198029e+02, -4.91333054e-03]), + 'Velocity': array([ 2.70068645e-01, -3.66151303e-01, -1.27487176e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5222778320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23728.76171875, 15904.55371094, 30.00003052]), + 'frame': 29098, + 'frame_number': 29098, + 'framesequence': 117704, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5515488386154175, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.5833709985018, + 'timestamp_carla': 993582, + 'timestamp_device': 2612141, + 'timestamp_stream': 993.5833709985018, + 'transform': [array([ 3.41451935e+02, 6.05867462e+01, -1.57517239e-01]), + array([-1.12903025e-02, 4.38602982e+01, 1.70287956e-02])]} +{'AngularVelocity': array([-0.02108465, -0.00437566, 3.95065641]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.186796188354492, + 'FR_Wheel_Angle': -23.082197189331055, + 'Location': array([244.0798645 , 140.64451599, 0.30170363]), + 'Rotation': array([-1.67817734e-02, 1.43138245e+02, -6.56127883e-03]), + 'Velocity': array([ 2.84374118e-01, -3.70604366e-01, -7.62939436e-08]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5305786132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23729.1015625 , 15903.06152344, 30. ]), + 'frame': 29099, + 'frame_number': 29099, + 'framesequence': 117708, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5441145300865173, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.6165114976466, + 'timestamp_carla': 993615, + 'timestamp_device': 2612174, + 'timestamp_stream': 993.6165114976466, + 'transform': [array([ 3.41793793e+02, 6.09303207e+01, -1.58515275e-01]), + array([-9.67837777e-03, 4.40574837e+01, 1.65405143e-02])]} +{'AngularVelocity': array([ 0.12905747, -0.02167244, 3.43444419]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.68125343322754, + 'FR_Wheel_Angle': -19.63565444946289, + 'Location': array([244.14756775, 140.5670929 , 0.30170166]), + 'Rotation': array([-1.56547930e-02, 1.44033188e+02, -3.17382812e-03]), + 'Velocity': array([ 2.63125569e-01, -3.02863687e-01, -7.12776164e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.532958984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23729.48046875, 15901.42871094, 30. ]), + 'frame': 29100, + 'frame_number': 29100, + 'framesequence': 117712, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5368999242782593, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.6511037983, + 'timestamp_carla': 993650, + 'timestamp_device': 2612207, + 'timestamp_stream': 993.6511037983, + 'transform': [array([ 3.42147491e+02, 6.12879677e+01, -1.58743054e-01]), + array([-8.45577382e-03, 4.42621117e+01, 1.63879320e-02])]} +{'AngularVelocity': array([ 0.04607801, -0.04625371, 2.82338548]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.20846176147461, + 'FR_Wheel_Angle': -20.26665687561035, + 'Location': array([244.21278381, 140.49873352, 0.30170479]), + 'Rotation': array([-1.61738880e-02, 1.44766312e+02, -6.07299712e-03]), + 'Velocity': array([ 2.82299906e-01, -3.13177645e-01, -4.40692893e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5383911132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23729.8515625 , 15899.88085938, 30. ]), + 'frame': 29101, + 'frame_number': 29101, + 'framesequence': 117716, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5329630970954895, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.6833847984672, + 'timestamp_carla': 993682, + 'timestamp_device': 2612241, + 'timestamp_stream': 993.6833847984672, + 'transform': [array([ 3.42483337e+02, 6.16297150e+01, -1.57463878e-01]), + array([-8.05962272e-03, 4.44570465e+01, 1.68762133e-02])]} +{'AngularVelocity': array([-2.89658713e-03, -3.60335479e-03, 3.43353105e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.961990356445312, + 'FR_Wheel_Angle': -20.280210494995117, + 'Location': array([244.28341675, 140.42601013, 0.3017104 ]), + 'Rotation': array([-1.66861508e-02, 1.45569717e+02, -6.68335101e-03]), + 'Velocity': array([ 2.93504089e-01, -3.24804902e-01, -1.26419065e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5397338867188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23730.2578125 , 15898.26367188, 30. ]), + 'frame': 29102, + 'frame_number': 29102, + 'framesequence': 117720, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5346477031707764, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.7165021970868, + 'timestamp_carla': 993715, + 'timestamp_device': 2612274, + 'timestamp_stream': 993.7165021970868, + 'transform': [array([ 3.42821564e+02, 6.19758682e+01, -1.57246590e-01]), + array([-7.56784901e-03, 4.46539764e+01, 1.69372484e-02])]} +{'AngularVelocity': array([3.67696281e-04, 7.66433077e-03, 3.57463145e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.918859481811523, + 'FR_Wheel_Angle': -18.9056396484375, + 'Location': array([244.35848999, 140.35093689, 0.30171633]), + 'Rotation': array([-1.68432463e-02, 1.46392349e+02, -6.80542039e-03]), + 'Velocity': array([ 3.10683519e-01, -3.36394638e-01, 1.85050958e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5418701171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23730.66601562, 15896.71191406, 30. ]), + 'frame': 29103, + 'frame_number': 29103, + 'framesequence': 117724, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538236677646637, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.7517542988062, + 'timestamp_carla': 993751, + 'timestamp_device': 2612307, + 'timestamp_stream': 993.7517542988062, + 'transform': [array([ 3.43175995e+02, 6.23414230e+01, -1.57918319e-01]), + array([-7.35611329e-03, 4.48611832e+01, 1.66625883e-02])]} +{'AngularVelocity': array([-0.0129885 , 0.01724519, 3.16292024]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.75171661376953, + 'FR_Wheel_Angle': -17.72929573059082, + 'Location': array([244.43803406, 140.27742004, 0.30170664]), + 'Rotation': array([-1.66315101e-02, 1.47125519e+02, -4.51660156e-03]), + 'Velocity': array([ 3.31858218e-01, -3.21050972e-01, 2.12526313e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.543212890625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23731.09179688, 15895.12207031, 30. ]), + 'frame': 29104, + 'frame_number': 29104, + 'framesequence': 117728, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5416058897972107, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.7831468991935, + 'timestamp_carla': 993782, + 'timestamp_device': 2612340, + 'timestamp_stream': 993.7831468991935, + 'transform': [array([ 3.43487183e+02, 6.26647339e+01, -1.59116820e-01]), + array([-6.22913241e-03, 4.50437622e+01, 1.61132757e-02])]} +{'AngularVelocity': array([ 0.03256187, -0.03183503, 3.34786034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.746356964111328, + 'FR_Wheel_Angle': -17.489046096801758, + 'Location': array([244.52987671, 140.19567871, 0.30171365]), + 'Rotation': array([-1.79429054e-02, 1.47929489e+02, -7.29370117e-03]), + 'Velocity': array([ 3.62696290e-01, -3.35619003e-01, -1.90162653e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5409545898438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23731.5390625 , 15893.45410156, 30.00003052]), + 'frame': 29105, + 'frame_number': 29105, + 'framesequence': 117732, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5425763726234436, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.8170899003744, + 'timestamp_carla': 993816, + 'timestamp_device': 2612374, + 'timestamp_stream': 993.8170899003744, + 'transform': [array([ 3.43817932e+02, 6.30108299e+01, -1.60266027e-01]), + array([-5.67588676e-03, 4.52385750e+01, 1.56249907e-02])]} +{'AngularVelocity': array([ 0.04225901, -0.02742667, 3.11740613]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.839845657348633, + 'FR_Wheel_Angle': -17.422245025634766, + 'Location': array([244.61328125, 140.12289429, 0.30171373]), + 'Rotation': array([-1.70618109e-02, 1.48651062e+02, -6.83593843e-03]), + 'Velocity': array([ 3.60174090e-01, -3.25958014e-01, 3.64685038e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484008789062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23731.92578125, 15892.00976562, 30. ]), + 'frame': 29106, + 'frame_number': 29106, + 'framesequence': 117736, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5411298274993896, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.8508708998561, + 'timestamp_carla': 993850, + 'timestamp_device': 2612407, + 'timestamp_stream': 993.8508708998561, + 'transform': [array([ 3.44143066e+02, 6.33533859e+01, -1.61027402e-01]), + array([-5.09532075e-03, 4.54307289e+01, 1.52892992e-02])]} +{'AngularVelocity': array([ 0.03125752, -0.02694454, 1.91477168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.02210235595703, + 'FR_Wheel_Angle': -13.5604248046875, + 'Location': array([244.69880676, 140.05207825, 0.30171672]), + 'Rotation': array([-1.73896607e-02, 1.49316116e+02, -4.51660249e-03]), + 'Velocity': array([ 3.82395804e-01, -3.13434541e-01, -7.71522537e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494384765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23732.34179688, 15890.46679688, 30. ]), + 'frame': 29107, + 'frame_number': 29107, + 'framesequence': 117740, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5392071604728699, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.8827590979636, + 'timestamp_carla': 993882, + 'timestamp_device': 2612440, + 'timestamp_stream': 993.8827590979636, + 'transform': [array([ 3.44444946e+02, 6.36733665e+01, -1.61367297e-01]), + array([-4.88358503e-03, 4.56097145e+01, 1.51367141e-02])]} +{'AngularVelocity': array([0.0208287 , 0.01105225, 3.82642555]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.724910736083984, + 'FR_Wheel_Angle': -14.24289608001709, + 'Location': array([244.79377747, 139.97854614, 0.30171633]), + 'Rotation': array([-1.81000009e-02, 1.49960342e+02, -6.86645508e-03]), + 'Velocity': array([ 4.04135734e-01, -3.31192404e-01, -2.90679927e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5509033203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23732.75585938, 15888.95605469, 30. ]), + 'frame': 29108, + 'frame_number': 29108, + 'framesequence': 117744, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538602888584137, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.9172939993441, + 'timestamp_carla': 993916, + 'timestamp_device': 2612474, + 'timestamp_stream': 993.9172939993441, + 'transform': [array([ 3.44768829e+02, 6.40187607e+01, -1.61380231e-01]), + array([-4.88358503e-03, 4.58023682e+01, 1.51367122e-02])]} +{'AngularVelocity': array([-7.12953974e-03, -6.02954882e-04, 3.50105214e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.59709930419922, + 'FR_Wheel_Angle': -14.3704252243042, + 'Location': array([244.88371277, 139.9102478 , 0.3016991 ]), + 'Rotation': array([-1.45551320e-02, 1.50546219e+02, -5.58471680e-03]), + 'Velocity': array([ 3.64638180e-01, -2.91380852e-01, 1.31034845e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5540161132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23733.14648438, 15887.54003906, 30. ]), + 'frame': 29109, + 'frame_number': 29109, + 'framesequence': 117749, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538602888584137, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.9514641985297, + 'timestamp_carla': 993950, + 'timestamp_device': 2612515, + 'timestamp_stream': 993.9514641985297, + 'transform': [array([ 3.45090820e+02, 6.43647766e+01, -1.61148876e-01]), + array([-4.81528323e-03, 4.59946556e+01, 1.52282659e-02])]} +{'AngularVelocity': array([ 2.31811209e-04, -5.75794093e-03, 2.24897885e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.371585845947266, + 'FR_Wheel_Angle': -12.666080474853516, + 'Location': array([244.97119141, 139.84559631, 0.301707 ]), + 'Rotation': array([-1.60509441e-02, 1.51102356e+02, -6.01196289e-03]), + 'Velocity': array([ 3.73969913e-01, -2.86902696e-01, -1.92737571e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.551513671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23733.58007812, 15886.00683594, 30. ]), + 'frame': 29110, + 'frame_number': 29110, + 'framesequence': 117752, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5324503183364868, + 'throttle_input': 0.24998855590820312, + 'timestamp': 993.9840990975499, + 'timestamp_carla': 993983, + 'timestamp_device': 2612540, + 'timestamp_stream': 993.9840990975499, + 'transform': [array([ 3.45399445e+02, 6.46985016e+01, -1.60400540e-01]), + array([-4.97920765e-03, 4.61795731e+01, 1.55334417e-02])]} +{'AngularVelocity': array([-0.08503196, -0.0489575 , 1.8442713 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.560867309570312, + 'FR_Wheel_Angle': -11.522665023803711, + 'Location': array([245.05915833, 139.7852478 , 0.30171224]), + 'Rotation': array([-1.79429054e-02, 1.51528046e+02, -6.31713821e-03]), + 'Velocity': array([ 4.33856070e-01, -3.07767868e-01, 6.40869112e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5504760742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23734.00976562, 15884.50195312, 30. ]), + 'frame': 29111, + 'frame_number': 29111, + 'framesequence': 117756, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5221961736679077, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.0161136984825, + 'timestamp_carla': 994015, + 'timestamp_device': 2612574, + 'timestamp_stream': 994.0161136984825, + 'transform': [array([ 3.45691406e+02, 6.50156784e+01, -1.60214916e-01]), + array([-4.21422627e-03, 4.63549614e+01, 1.55639611e-02])]} +{'AngularVelocity': array([-0.01341276, 0.00914718, 1.96800959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.48205280303955, + 'FR_Wheel_Angle': -11.243999481201172, + 'Location': array([245.1541748 , 139.72134399, 0.30169028]), + 'Rotation': array([-1.55933211e-02, 1.51988693e+02, -6.37817383e-03]), + 'Velocity': array([ 0.38303119, -0.26998541, -0.00038544]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5512084960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23734.43359375, 15883.04882812, 30. ]), + 'frame': 29112, + 'frame_number': 29112, + 'framesequence': 117760, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5093051195144653, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.0514093972743, + 'timestamp_carla': 994050, + 'timestamp_device': 2612607, + 'timestamp_stream': 994.0514093972743, + 'transform': [array([ 3.46008209e+02, 6.53612976e+01, -1.59375757e-01]), + array([-4.02981136e-03, 4.65457230e+01, 1.58996545e-02])]} +{'AngularVelocity': array([-0.06580887, -0.05830902, 2.63599896]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.492470741271973, + 'FR_Wheel_Angle': -11.127121925354004, + 'Location': array([245.24334717, 139.6625824 , 0.30170992]), + 'Rotation': array([-1.66861508e-02, 1.52423401e+02, -7.11059524e-03]), + 'Velocity': array([ 4.24671352e-01, -2.89820641e-01, -7.96127279e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5548095703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23734.86523438, 15881.64550781, 30. ]), + 'frame': 29113, + 'frame_number': 29113, + 'framesequence': 117765, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4941984713077545, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.0849762000144, + 'timestamp_carla': 994084, + 'timestamp_device': 2612649, + 'timestamp_stream': 994.0849762000144, + 'transform': [array([ 3.46300110e+02, 6.56811295e+01, -1.58837199e-01]), + array([-3.41509446e-03, 4.67219162e+01, 1.60827618e-02])]} +{'AngularVelocity': array([0.02623931, 0.01060896, 2.49207139]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.450984477996826, + 'FR_Wheel_Angle': -6.815516471862793, + 'Location': array([245.33084106, 139.60688782, 0.30171534]), + 'Rotation': array([-1.71506032e-02, 1.52777191e+02, -4.91333054e-03]), + 'Velocity': array([ 4.22653496e-01, -2.66168475e-01, -2.16560366e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5504150390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23735.375 , 15880.08105469, 30. ]), + 'frame': 29114, + 'frame_number': 29114, + 'framesequence': 117768, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4785790741443634, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.115749899298, + 'timestamp_carla': 994115, + 'timestamp_device': 2612674, + 'timestamp_stream': 994.115749899298, + 'transform': [array([ 3.46570007e+02, 6.59771652e+01, -1.55556828e-01]), + array([-4.02981136e-03, 4.68849373e+01, 1.74255315e-02])]} +{'AngularVelocity': array([-0.06323827, -0.02898138, 1.57445288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.326149940490723, + 'FR_Wheel_Angle': -7.537756443023682, + 'Location': array([245.42643738, 139.54985046, 0.30171302]), + 'Rotation': array([-1.68159250e-02, 1.53053421e+02, -6.56127930e-03]), + 'Velocity': array([ 4.44257319e-01, -2.76530325e-01, 1.25675200e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5521850585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23735.8828125 , 15878.60644531, 29.99993896]), + 'frame': 29115, + 'frame_number': 29115, + 'framesequence': 117772, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46671345829963684, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.1486845985055, + 'timestamp_carla': 994148, + 'timestamp_device': 2612707, + 'timestamp_stream': 994.1486845985055, + 'transform': [array([ 3.46869293e+02, 6.63075790e+01, -1.53402060e-01]), + array([-4.36449051e-03, 4.70663147e+01, 1.83105413e-02])]} +{'AngularVelocity': array([0.01522557, 0.01711304, 0.11786302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.270956993103027, + 'FR_Wheel_Angle': -7.692286491394043, + 'Location': array([245.53308105, 139.48666382, 0.30171406]), + 'Rotation': array([-1.69388689e-02, 1.53391922e+02, -7.11059524e-03]), + 'Velocity': array([ 4.40866053e-01, -2.69663721e-01, 3.78131845e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.552001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23736.421875 , 15877.17382812, 30. ]), + 'frame': 29116, + 'frame_number': 29116, + 'framesequence': 117776, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46409499645233154, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.1819943003356, + 'timestamp_carla': 994181, + 'timestamp_device': 2612740, + 'timestamp_stream': 994.1819943003356, + 'transform': [array([ 3.47159058e+02, 6.66289902e+01, -1.53746337e-01]), + array([-4.06396249e-03, 4.72424164e+01, 1.81579515e-02])]} +{'AngularVelocity': array([-0.00218362, -0.01975418, 0.37896428]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.288400650024414, + 'FR_Wheel_Angle': -5.046894550323486, + 'Location': array([245.62956238, 139.43041992, 0.30168945]), + 'Rotation': array([-1.41589809e-02, 1.53686554e+02, -6.10351609e-03]), + 'Velocity': array([ 3.99908692e-01, -2.35435650e-01, -2.12488172e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5486450195312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23737.03125 , 15875.59765625, 30.00003052]), + 'frame': 29117, + 'frame_number': 29117, + 'framesequence': 117780, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46971651911735535, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.2143980972469, + 'timestamp_carla': 994213, + 'timestamp_device': 2612774, + 'timestamp_stream': 994.2143980972469, + 'transform': [array([ 3.47438965e+02, 6.69416504e+01, -1.54677764e-01]), + array([-4.24154708e-03, 4.74131737e+01, 1.77917406e-02])]} +{'AngularVelocity': array([-0.01395786, 0.0181552 , 0.82359582]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.511399745941162, + 'FR_Wheel_Angle': -4.398667335510254, + 'Location': array([245.72790527, 139.37747192, 0.3017166 ]), + 'Rotation': array([-1.80043783e-02, 1.53841141e+02, -5.64575102e-03]), + 'Velocity': array([ 4.40964580e-01, -2.38923654e-01, 2.04849232e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5486450195312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23737.64648438, 15874.04101562, 30.00003052]), + 'frame': 29118, + 'frame_number': 29118, + 'framesequence': 117784, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4783593416213989, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.2490298002958, + 'timestamp_carla': 994248, + 'timestamp_device': 2612807, + 'timestamp_stream': 994.2490298002958, + 'transform': [array([ 3.47735687e+02, 6.72751465e+01, -1.55999526e-01]), + array([-4.36449051e-03, 4.75948296e+01, 1.72729436e-02])]} +{'AngularVelocity': array([0.00348566, 0.01242445, 0.47388521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.244003772735596, + 'FR_Wheel_Angle': -4.056982040405273, + 'Location': array([245.82536316, 139.32539368, 0.30169934]), + 'Rotation': array([-1.49581134e-02, 1.53993301e+02, -6.83593750e-03]), + 'Velocity': array([ 3.94732326e-01, -2.13901103e-01, -2.81429293e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.550048828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23738.23632812, 15872.54589844, 29.99996948]), + 'frame': 29119, + 'frame_number': 29119, + 'framesequence': 117788, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48592182993888855, + 'throttle_input': 0.24998855590820312, + 'timestamp': 994.2817825004458, + 'timestamp_carla': 994281, + 'timestamp_device': 2612840, + 'timestamp_stream': 994.2817825004458, + 'transform': [array([ 3.48018585e+02, 6.75958786e+01, -1.57380208e-01]), + array([-4.52158507e-03, 4.77688408e+01, 1.67236272e-02])]} +{'AngularVelocity': array([0.00883582, 0.0038751 , 1.94522941]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.185914516448975, + 'FR_Wheel_Angle': -3.841970920562744, + 'Location': array([245.91970825, 139.27548218, 0.30169773]), + 'Rotation': array([-1.61124151e-02, 1.54150009e+02, -7.44628906e-03]), + 'Velocity': array([ 4.01173592e-01, -2.15726674e-01, -3.66592394e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5477905273438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23738.86523438, 15870.95605469, 30. ]), + 'frame': 29120, + 'frame_number': 29120, + 'framesequence': 117792, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4875698387622833, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.3160529993474, + 'timestamp_carla': 994315, + 'timestamp_device': 2612874, + 'timestamp_stream': 994.3160529993474, + 'transform': [array([ 3.48316284e+02, 6.79357834e+01, -1.58187553e-01]), + array([-4.81528323e-03, 4.79526749e+01, 1.64184533e-02])]} +{'AngularVelocity': array([0.00992625, 0.0210017 , 1.06642282]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.060800313949585, + 'FR_Wheel_Angle': 0.8709436655044556, + 'Location': array([246.02682495, 139.22120667, 0.30170813]), + 'Rotation': array([-1.62695106e-02, 1.54229935e+02, -4.88281203e-03]), + 'Velocity': array([ 3.98955405e-01, -1.90254003e-01, 3.50570663e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494995117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23739.4375 , 15869.47167969, 30.00003052]), + 'frame': 29121, + 'frame_number': 29121, + 'framesequence': 117796, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4846949875354767, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.350508198142, + 'timestamp_carla': 994350, + 'timestamp_device': 2612907, + 'timestamp_stream': 994.350508198142, + 'transform': [array([ 3.48623352e+02, 6.82890091e+01, -1.57449946e-01]), + array([-5.52562252e-03, 4.81430702e+01, 1.67541448e-02])]} +{'AngularVelocity': array([-0.00914512, -0.01014046, 0.7634325 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.13717710971832275, + 'FR_Wheel_Angle': 0.2212911993265152, + 'Location': array([246.11906433, 139.17654419, 0.30170715]), + 'Rotation': array([-1.58118866e-02, 1.54223984e+02, -7.08007859e-03]), + 'Velocity': array([ 3.97256762e-01, -1.92855105e-01, 1.46942140e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5480346679688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23740.03125 , 15867.921875, 30. ]), + 'frame': 29122, + 'frame_number': 29122, + 'framesequence': 117800, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4802820086479187, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.3832242973149, + 'timestamp_carla': 994382, + 'timestamp_device': 2612940, + 'timestamp_stream': 994.3832242973149, + 'transform': [array([ 3.48911957e+02, 6.86219025e+01, -1.56109393e-01]), + array([-5.79883019e-03, 4.83223648e+01, 1.73034612e-02])]} +{'AngularVelocity': array([ 0.00278366, -0.01015957, -1.03804886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0521080382168293, + 'FR_Wheel_Angle': -0.01397370919585228, + 'Location': array([246.21011353, 139.13237 , 0.30170351]), + 'Rotation': array([-1.67817734e-02, 1.54219620e+02, -7.47680711e-03]), + 'Velocity': array([ 4.00449216e-01, -1.93041518e-01, -7.63130156e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.544677734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23740.65039062, 15866.3359375 , 30.00003052]), + 'frame': 29123, + 'frame_number': 29123, + 'framesequence': 117804, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47680291533470154, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.4162544980645, + 'timestamp_carla': 994415, + 'timestamp_device': 2612974, + 'timestamp_stream': 994.4162544980645, + 'transform': [array([ 3.49200226e+02, 6.89568253e+01, -1.56376988e-01]), + array([-5.55977365e-03, 4.85021935e+01, 1.71813890e-02])]} +{'AngularVelocity': array([ 0.02277922, 0.01764626, -0.50721991]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.315340757369995, + 'FR_Wheel_Angle': 3.369502305984497, + 'Location': array([246.31254578, 139.08314514, 0.30171156]), + 'Rotation': array([-1.77926421e-02, 1.54179459e+02, -6.46972563e-03]), + 'Velocity': array([ 4.36491132e-01, -2.00945601e-01, -8.79192303e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.544921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23741.28320312, 15864.78125 , 30. ]), + 'frame': 29124, + 'frame_number': 29124, + 'framesequence': 117808, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47658318281173706, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.448630400002, + 'timestamp_carla': 994448, + 'timestamp_device': 2613007, + 'timestamp_stream': 994.448630400002, + 'transform': [array([ 3.49481903e+02, 6.92862778e+01, -1.56861752e-01]), + array([-5.25241531e-03, 4.86785622e+01, 1.69677678e-02])]} +{'AngularVelocity': array([-0.01525388, 0.01938775, -0.72148979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.5449297428131104, + 'FR_Wheel_Angle': 3.6709542274475098, + 'Location': array([246.40893555, 139.04023743, 0.30170825]), + 'Rotation': array([-1.53815849e-02, 1.54038284e+02, -6.92748930e-03]), + 'Velocity': array([ 4.03515428e-01, -1.78987518e-01, 2.64987932e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5465087890625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23741.91210938, 15863.23535156, 30. ]), + 'frame': 29125, + 'frame_number': 29125, + 'framesequence': 117812, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4782494604587555, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.4816481992602, + 'timestamp_carla': 994481, + 'timestamp_device': 2613040, + 'timestamp_stream': 994.4816481992602, + 'transform': [array([ 3.49768036e+02, 6.96230469e+01, -1.57446012e-01]), + array([-5.06799994e-03, 4.88583488e+01, 1.67236291e-02])]} +{'AngularVelocity': array([ 0.00548664, 0.02556949, -1.75978422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.91225528717041, + 'FR_Wheel_Angle': 4.058323383331299, + 'Location': array([246.51364136, 138.99308777, 0.30170542]), + 'Rotation': array([-1.72120761e-02, 1.53872787e+02, -7.50732375e-03]), + 'Velocity': array([ 4.40455019e-01, -1.94374517e-01, 3.62777719e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5491333007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23742.52734375, 15861.72949219, 30. ]), + 'frame': 29126, + 'frame_number': 29126, + 'framesequence': 117816, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48030033707618713, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.5151192992926, + 'timestamp_carla': 994514, + 'timestamp_device': 2613074, + 'timestamp_stream': 994.5151192992926, + 'transform': [array([ 3.50065063e+02, 6.99754944e+01, -1.57322377e-01]), + array([-5.25241531e-03, 4.90458565e+01, 1.67846642e-02])]} +{'AngularVelocity': array([ 0.01087296, -0.01462134, -1.47028744]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.033890247344971, + 'FR_Wheel_Angle': 4.628816604614258, + 'Location': array([246.6125946 , 138.94827271, 0.301682 ]), + 'Rotation': array([-1.49581134e-02, 1.53722183e+02, -7.96508696e-03]), + 'Velocity': array([ 4.12366390e-01, -1.81382105e-01, -2.54049286e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5496215820312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23743.16210938, 15860.203125 , 30.00003052]), + 'frame': 29127, + 'frame_number': 29127, + 'framesequence': 117820, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48145392537117004, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.5500338971615, + 'timestamp_carla': 994549, + 'timestamp_device': 2613107, + 'timestamp_stream': 994.5500338971615, + 'transform': [array([ 3.50363831e+02, 7.03318558e+01, -1.58171073e-01]), + array([-5.25241531e-03, 4.92350769e+01, 1.64489653e-02])]} +{'AngularVelocity': array([ 2.05506198e-02, 9.56053031e-04, -1.82273257e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.609733581542969, + 'FR_Wheel_Angle': 8.947144508361816, + 'Location': array([246.71759033, 138.90296936, 0.301725 ]), + 'Rotation': array([-1.94387175e-02, 1.53457275e+02, -4.08935454e-03]), + 'Velocity': array([ 4.97608215e-01, -1.91187382e-01, 1.02863312e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54833984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23743.81054688, 15858.63476562, 30. ]), + 'frame': 29128, + 'frame_number': 29128, + 'framesequence': 117824, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4805017411708832, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.5815723985434, + 'timestamp_carla': 994581, + 'timestamp_device': 2613140, + 'timestamp_stream': 994.5815723985434, + 'transform': [array([ 3.50627411e+02, 7.06482620e+01, -1.59177050e-01]), + array([-4.94505651e-03, 4.94026566e+01, 1.60217211e-02])]} +{'AngularVelocity': array([ 0.02741163, 0.00421788, -1.45288908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.9380035400390625, + 'FR_Wheel_Angle': 8.553583145141602, + 'Location': array([246.82365417, 138.8581543 , 0.30169064]), + 'Rotation': array([-1.46507546e-02, 1.53144058e+02, -7.87353422e-03]), + 'Velocity': array([ 4.25553471e-01, -1.69567719e-01, -1.84288016e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5464477539062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23744.48046875, 15857.02539062, 30.00003052]), + 'frame': 29129, + 'frame_number': 29129, + 'framesequence': 117828, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4792199730873108, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.6148704998195, + 'timestamp_carla': 994614, + 'timestamp_device': 2613174, + 'timestamp_stream': 994.6148704998195, + 'transform': [array([ 3.50900787e+02, 7.09782639e+01, -1.59898341e-01]), + array([-4.63769818e-03, 4.95770454e+01, 1.57165471e-02])]} +{'AngularVelocity': array([-0.0177882 , 0.01003018, -1.69096184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.752470016479492, + 'FR_Wheel_Angle': 8.303744316101074, + 'Location': array([246.92216492, 138.81591797, 0.30169037]), + 'Rotation': array([-1.56547930e-02, 1.52855865e+02, -8.17871094e-03]), + 'Velocity': array([ 4.20888275e-01, -1.76046386e-01, -2.66141898e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5513916015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23745.08007812, 15855.60546875, 29.99996948]), + 'frame': 29130, + 'frame_number': 29130, + 'framesequence': 117832, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47898194193840027, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.6492369994521, + 'timestamp_carla': 994648, + 'timestamp_device': 2613207, + 'timestamp_stream': 994.6492369994521, + 'transform': [array([ 3.51181396e+02, 7.13193665e+01, -1.60702974e-01]), + array([-4.33716970e-03, 4.97567520e+01, 1.53808566e-02])]} +{'AngularVelocity': array([ 0.02154055, 0.01392634, -0.6151377 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.086030960083008, + 'FR_Wheel_Angle': 12.210783958435059, + 'Location': array([247.02799988, 138.7702179 , 0.30172428]), + 'Rotation': array([-1.76082272e-02, 1.52536469e+02, -6.31713774e-03]), + 'Velocity': array([ 4.65888321e-01, -1.82955056e-01, 1.19237899e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5523071289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23745.71484375, 15854.11816406, 29.99996948]), + 'frame': 29131, + 'frame_number': 29131, + 'framesequence': 117836, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47980591654777527, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.6819374971092, + 'timestamp_carla': 994681, + 'timestamp_device': 2613240, + 'timestamp_stream': 994.6819374971092, + 'transform': [array([ 3.51439209e+02, 7.16345520e+01, -1.61642715e-01]), + array([-4.02981136e-03, 4.99224586e+01, 1.49841253e-02])]} +{'AngularVelocity': array([-0.00957692, 0.01334779, -0.51599026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.750739097595215, + 'FR_Wheel_Angle': 12.168375015258789, + 'Location': array([247.13117981, 138.72819519, 0.30169365]), + 'Rotation': array([-1.47395479e-02, 1.52085785e+02, -7.96508789e-03]), + 'Velocity': array([ 4.22001630e-01, -1.63794041e-01, 2.43310918e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5517578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23746.36523438, 15852.60644531, 29.99996948]), + 'frame': 29132, + 'frame_number': 29132, + 'framesequence': 117840, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48026371002197266, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.7151964977384, + 'timestamp_carla': 994714, + 'timestamp_device': 2613274, + 'timestamp_stream': 994.7151964977384, + 'transform': [array([ 3.51697968e+02, 7.19528427e+01, -1.62441358e-01]), + array([-3.75660392e-03, 5.00893707e+01, 1.46484338e-02])]} +{'AngularVelocity': array([-0.00419087, -0.00112687, -0.72343194]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.070634841918945, + 'FR_Wheel_Angle': 12.454865455627441, + 'Location': array([247.22558594, 138.68885803, 0.30169928]), + 'Rotation': array([-1.51356980e-02, 1.51680374e+02, -8.48388672e-03]), + 'Velocity': array([ 4.0406689e-01, -1.5942876e-01, -3.0584335e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5545654296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23746.97265625, 15851.20019531, 30. ]), + 'frame': 29133, + 'frame_number': 29133, + 'framesequence': 117844, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48017215728759766, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.7490235976875, + 'timestamp_carla': 994748, + 'timestamp_device': 2613307, + 'timestamp_stream': 994.7490235976875, + 'transform': [array([ 3.51953308e+02, 7.22686081e+01, -1.63180768e-01]), + array([-3.57218878e-03, 5.02546349e+01, 1.43432617e-02])]} +{'AngularVelocity': array([ 1.11059938e-03, -3.29979062e-02, -2.36147714e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.259774208068848, + 'FR_Wheel_Angle': 13.122344970703125, + 'Location': array([247.3065033 , 138.65452576, 0.30169392]), + 'Rotation': array([-1.69661883e-02, 1.51327362e+02, -7.81249953e-03]), + 'Velocity': array([ 4.31022435e-01, -1.71938181e-01, -2.50129699e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5559692382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23747.5859375 , 15849.79394531, 30. ]), + 'frame': 29134, + 'frame_number': 29134, + 'framesequence': 117848, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4768212139606476, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.7819353975356, + 'timestamp_carla': 994781, + 'timestamp_device': 2613340, + 'timestamp_stream': 994.7819353975356, + 'transform': [array([ 3.52199493e+02, 7.25751953e+01, -1.63675502e-01]), + array([-3.32630193e-03, 5.04146118e+01, 1.41296331e-02])]} +{'AngularVelocity': array([ 0.01591484, -0.02403882, -2.88687778]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.073955535888672, + 'FR_Wheel_Angle': 17.030916213989258, + 'Location': array([247.4196167 , 138.60778809, 0.30170146]), + 'Rotation': array([-1.55045288e-02, 1.50732529e+02, -6.07299898e-03]), + 'Velocity': array([ 4.24301863e-01, -1.49573550e-01, -3.45230092e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5560913085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23748.20507812, 15848.38964844, 29.99993896]), + 'frame': 29135, + 'frame_number': 29135, + 'framesequence': 117852, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4666951596736908, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.8156640976667, + 'timestamp_carla': 994815, + 'timestamp_device': 2613374, + 'timestamp_stream': 994.8156640976667, + 'transform': [array([ 3.52439606e+02, 7.28751068e+01, -1.64050132e-01]), + array([-2.68426421e-03, 5.05709648e+01, 1.39465295e-02])]} +{'AngularVelocity': array([-0.0037236 , 0.03669859, -1.22342873]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.561095237731934, + 'FR_Wheel_Angle': 16.789155960083008, + 'Location': array([247.52101135, 138.56626892, 0.30171084]), + 'Rotation': array([-1.66861508e-02, 1.50169006e+02, -7.93457124e-03]), + 'Velocity': array([ 4.28751796e-01, -1.63202897e-01, -9.12666292e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55810546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23748.796875 , 15847.05078125, 30.00003052]), + 'frame': 29136, + 'frame_number': 29136, + 'framesequence': 117856, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45439010858535767, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.8479450978339, + 'timestamp_carla': 994847, + 'timestamp_device': 2613407, + 'timestamp_stream': 994.8479450978339, + 'transform': [array([ 3.52660187e+02, 7.31514511e+01, -1.64141461e-01]), + array([-2.28811335e-03, 5.07148781e+01, 1.38854962e-02])]} +{'AngularVelocity': array([-0.03794678, 0.02621997, -2.65937567]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.390538215637207, + 'FR_Wheel_Angle': 16.606586456298828, + 'Location': array([247.62109375, 138.52410889, 0.30172104]), + 'Rotation': array([-1.77653208e-02, 1.49579269e+02, -7.62939686e-03]), + 'Velocity': array([ 4.56445038e-01, -1.82390660e-01, -1.83763506e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5593872070312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23749.41015625, 15845.70800781, 30. ]), + 'frame': 29137, + 'frame_number': 29137, + 'framesequence': 117860, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4404553472995758, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.880538597703, + 'timestamp_carla': 994880, + 'timestamp_device': 2613440, + 'timestamp_stream': 994.880538597703, + 'transform': [array([ 3.52878662e+02, 7.34261398e+01, -1.63707197e-01]), + array([-1.89196225e-03, 5.08576736e+01, 1.40380859e-02])]} +{'AngularVelocity': array([ 0.03384664, -0.1273782 , -3.69277024]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.63604164123535, + 'FR_Wheel_Angle': 20.84300994873047, + 'Location': array([247.70858765, 138.48683167, 0.30171368]), + 'Rotation': array([-1.74511317e-02, 1.49055679e+02, -6.77490234e-03]), + 'Velocity': array([ 5.08710921e-01, -1.93646371e-01, 6.61373124e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5616455078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23750.00585938, 15844.44628906, 30.00006104]), + 'frame': 29138, + 'frame_number': 29138, + 'framesequence': 117864, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4249458611011505, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.9149595983326, + 'timestamp_carla': 994914, + 'timestamp_device': 2613474, + 'timestamp_stream': 994.9149595983326, + 'transform': [array([ 3.53102448e+02, 7.37082672e+01, -1.62776753e-01]), + array([-1.65290572e-03, 5.10042076e+01, 1.44042959e-02])]} +{'AngularVelocity': array([ 0.01492955, -0.027687 , -3.95100975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.10612678527832, + 'FR_Wheel_Angle': 20.568511962890625, + 'Location': array([247.81616211, 138.44273376, 0.30169746]), + 'Rotation': array([-1.53542645e-02, 1.48304657e+02, -7.96508789e-03]), + 'Velocity': array([ 4.55066025e-01, -1.67400762e-01, -2.16999048e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5628662109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23750.625 , 15843.18945312, 30. ]), + 'frame': 29139, + 'frame_number': 29139, + 'framesequence': 117868, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4104251265525818, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.9477107971907, + 'timestamp_carla': 994947, + 'timestamp_device': 2613507, + 'timestamp_stream': 994.9477107971907, + 'transform': [array([ 3.53320648e+02, 7.39840546e+01, -1.59930602e-01]), + array([-1.98758487e-03, 5.11472778e+01, 1.55639639e-02])]} +{'AngularVelocity': array([-0.00287147, -0.06901259, -2.20913267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.368913650512695, + 'FR_Wheel_Angle': 20.779966354370117, + 'Location': array([247.91358948, 138.40151978, 0.30170861]), + 'Rotation': array([-1.49239628e-02, 1.47626816e+02, -9.00268462e-03]), + 'Velocity': array([ 4.43613112e-01, -1.72893479e-01, 9.54341886e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5602416992188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23751.31054688, 15841.86425781, 29.99996948]), + 'frame': 29140, + 'frame_number': 29140, + 'framesequence': 117872, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.40432754158973694, + 'throttle_input': 0.22618448734283447, + 'timestamp': 994.9814963974059, + 'timestamp_carla': 994981, + 'timestamp_device': 2613540, + 'timestamp_stream': 994.9814963974059, + 'transform': [array([ 3.53568481e+02, 7.42978134e+01, -1.53183863e-01]), + array([-4.33716970e-03, 5.13099480e+01, 1.84020959e-02])]} +{'AngularVelocity': array([-9.69468907e-04, 1.25290174e-02, -3.00622559e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.603313446044922, + 'FR_Wheel_Angle': 21.703693389892578, + 'Location': array([248.01722717, 138.35601807, 0.30169567]), + 'Rotation': array([-1.58392079e-02, 1.46883759e+02, -9.06372070e-03]), + 'Velocity': array([ 4.30282921e-01, -1.72774330e-01, -2.61306763e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5581665039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23752.015625 , 15840.55371094, 29.99996948]), + 'frame': 29141, + 'frame_number': 29141, + 'framesequence': 117876, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.40755030512809753, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.0144558995962, + 'timestamp_carla': 995014, + 'timestamp_device': 2613574, + 'timestamp_stream': 995.0144558995962, + 'transform': [array([ 3.53804413e+02, 7.45981979e+01, -1.51774168e-01]), + array([-5.19094337e-03, 5.14654236e+01, 1.90124456e-02])]} +{'AngularVelocity': array([ 0.04236315, -0.01816726, -4.36122465]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.843059539794922, + 'FR_Wheel_Angle': 25.28885841369629, + 'Location': array([248.11601257, 138.31358337, 0.30171591]), + 'Rotation': array([-1.70618109e-02, 1.46089600e+02, -5.00488235e-03]), + 'Velocity': array([ 4.57933784e-01, -1.57596722e-01, 3.01790220e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5457763671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23752.87890625, 15839.01464844, 30. ]), + 'frame': 29142, + 'frame_number': 29142, + 'framesequence': 117880, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4146184027194977, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.0492778979242, + 'timestamp_carla': 995048, + 'timestamp_device': 2613607, + 'timestamp_stream': 995.0492778979242, + 'transform': [array([ 3.54056793e+02, 7.49217529e+01, -1.51711121e-01]), + array([-6.34524552e-03, 5.16324806e+01, 1.91039983e-02])]} +{'AngularVelocity': array([ 0.05305438, -0.02788214, -3.85366797]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.473037719726562, + 'FR_Wheel_Angle': 25.124324798583984, + 'Location': array([248.21463013, 138.2713623 , 0.3016983 ]), + 'Rotation': array([-1.51630193e-02, 1.45250732e+02, -9.03320312e-03]), + 'Velocity': array([ 4.17832822e-01, -1.52878553e-01, 1.11331938e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5435791015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23753.70117188, 15837.53320312, 29.99996948]), + 'frame': 29143, + 'frame_number': 29143, + 'framesequence': 117884, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42338940501213074, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.0814819000661, + 'timestamp_carla': 995081, + 'timestamp_device': 2613640, + 'timestamp_stream': 995.0814819000661, + 'transform': [array([ 3.54295624e+02, 7.52308273e+01, -1.52676955e-01]), + array([-6.29060389e-03, 5.17914314e+01, 1.87072642e-02])]} +{'AngularVelocity': array([-0.05451762, 0.08277311, -3.69904876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.314626693725586, + 'FR_Wheel_Angle': 24.96413230895996, + 'Location': array([248.32351685, 138.22183228, 0.30170554]), + 'Rotation': array([-1.70003399e-02, 1.44345215e+02, -8.72802641e-03]), + 'Velocity': array([ 4.12286013e-01, -1.76692203e-01, -3.51238232e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5382690429688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23754.5625 , 15835.95410156, 29.99990845]), + 'frame': 29144, + 'frame_number': 29144, + 'framesequence': 117888, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4271065294742584, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.11527909711, + 'timestamp_carla': 995114, + 'timestamp_device': 2613674, + 'timestamp_stream': 995.11527909711, + 'transform': [array([ 3.54537567e+02, 7.55454102e+01, -1.54830515e-01]), + array([-5.89445280e-03, 5.19529343e+01, 1.78222563e-02])]} +{'AngularVelocity': array([ 0.02310812, -0.04998586, -4.89103365]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.50653839111328, + 'FR_Wheel_Angle': 29.338945388793945, + 'Location': array([248.42706299, 138.17341614, 0.30172619]), + 'Rotation': array([-1.95616614e-02, 1.43443466e+02, -4.11987305e-03]), + 'Velocity': array([ 5.14653623e-01, -2.02303499e-01, -6.26087203e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5419921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23755.34765625, 15834.50683594, 29.99996948]), + 'frame': 29145, + 'frame_number': 29145, + 'framesequence': 117892, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42556843161582947, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.1482356004417, + 'timestamp_carla': 995147, + 'timestamp_device': 2613707, + 'timestamp_stream': 995.1482356004417, + 'transform': [array([ 3.54768890e+02, 7.58481064e+01, -1.56947672e-01]), + array([-5.27973613e-03, 5.21079712e+01, 1.69372521e-02])]} +{'AngularVelocity': array([ 1.02958139e-02, -3.66028748e-03, -4.68810892e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.772714614868164, + 'FR_Wheel_Angle': 28.892074584960938, + 'Location': array([248.53459167, 138.12475586, 0.30169526]), + 'Rotation': array([-1.56274717e-02, 1.42370529e+02, -9.03320312e-03]), + 'Velocity': array([ 4.53778803e-01, -1.82609141e-01, -2.09808354e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5437622070312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23756.15429688, 15833.02539062, 30. ]), + 'frame': 29146, + 'frame_number': 29146, + 'framesequence': 117896, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42219915986061096, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.1812028996646, + 'timestamp_carla': 995180, + 'timestamp_device': 2613740, + 'timestamp_stream': 995.1812028996646, + 'transform': [array([ 3.54993042e+02, 7.61428909e+01, -1.58835143e-01]), + array([-4.63769818e-03, 5.22586708e+01, 1.61437932e-02])]} +{'AngularVelocity': array([ 2.56253476e-03, 2.57739443e-02, -5.96482277e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.98719596862793, + 'FR_Wheel_Angle': 29.10258674621582, + 'Location': array([248.65202332, 138.06842041, 0.30171993]), + 'Rotation': array([-1.88308302e-02, 1.41212646e+02, -7.17163226e-03]), + 'Velocity': array([ 5.28527439e-01, -2.25227371e-01, -6.67572021e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5479125976562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23756.92773438, 15831.61328125, 30. ]), + 'frame': 29147, + 'frame_number': 29147, + 'framesequence': 117901, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41815242171287537, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.2192831970751, + 'timestamp_carla': 995218, + 'timestamp_device': 2613782, + 'timestamp_stream': 995.2192831970751, + 'transform': [array([ 3.55243439e+02, 7.64739304e+01, -1.60887673e-01]), + array([-3.75660392e-03, 5.24275856e+01, 1.52893011e-02])]} +{'AngularVelocity': array([ 9.07638483e-03, 2.44686520e-03, -5.69725370e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.249380111694336, + 'FR_Wheel_Angle': 30.09794807434082, + 'Location': array([248.76683044, 138.01081848, 0.30170768]), + 'Rotation': array([-1.59553215e-02, 1.40051498e+02, -9.85717773e-03]), + 'Velocity': array([ 4.96706367e-01, -2.22310603e-01, 3.72781738e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5514526367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23757.69140625, 15830.23632812, 30. ]), + 'frame': 29148, + 'frame_number': 29148, + 'framesequence': 117904, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41666924953460693, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.2479439005256, + 'timestamp_carla': 995247, + 'timestamp_device': 2613807, + 'timestamp_stream': 995.2479439005256, + 'transform': [array([ 3.55433258e+02, 7.67264557e+01, -1.61325678e-01]), + array([-4.06396249e-03, 5.25561447e+01, 1.51367141e-02])]} +{'AngularVelocity': array([-0.08586431, 0.17053157, -6.11012983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.138431549072266, + 'FR_Wheel_Angle': 33.47241973876953, + 'Location': array([248.88406372, 137.95219421, 0.30171454]), + 'Rotation': array([-1.84961520e-02, 1.38736847e+02, -5.67626907e-03]), + 'Velocity': array([ 5.14757812e-01, -2.28182256e-01, 1.77278518e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54638671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23758.56640625, 15828.68554688, 30.00006104]), + 'frame': 29149, + 'frame_number': 29149, + 'framesequence': 117908, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41767632961273193, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.2816275991499, + 'timestamp_carla': 995281, + 'timestamp_device': 2613840, + 'timestamp_stream': 995.2816275991499, + 'transform': [array([ 3.55644989e+02, 7.70089188e+01, -1.62238315e-01]), + array([-3.69513221e-03, 5.26998253e+01, 1.47399856e-02])]} +{'AngularVelocity': array([ 2.93844356e-03, 1.99250951e-02, -4.94482899e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.83131217956543, + 'FR_Wheel_Angle': 33.35871887207031, + 'Location': array([249.00665283, 137.88822937, 0.30170429]), + 'Rotation': array([-1.61124151e-02, 1.37318985e+02, -9.79614258e-03]), + 'Velocity': array([ 5.26822865e-01, -2.41915733e-01, -3.14140307e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5423583984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23759.22070312, 15827.515625 , 30.00003052]), + 'frame': 29150, + 'frame_number': 29150, + 'framesequence': 117912, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4199102818965912, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.3153153993189, + 'timestamp_carla': 995314, + 'timestamp_device': 2613873, + 'timestamp_stream': 995.3153153993189, + 'transform': [array([ 3.55852753e+02, 7.72878647e+01, -1.63453057e-01]), + array([-3.23750940e-03, 5.28413582e+01, 1.42211867e-02])]} +{'AngularVelocity': array([-0.0063446 , 0.01213268, -4.48409939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.68046760559082, + 'FR_Wheel_Angle': 33.2518196105957, + 'Location': array([249.12097168, 137.82531738, 0.30169958]), + 'Rotation': array([-1.51903396e-02, 1.35975708e+02, -1.11694327e-02]), + 'Velocity': array([ 4.95797992e-01, -2.44228303e-01, 1.15222931e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5492553710938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23759.97460938, 15826.18945312, 29.99996948]), + 'frame': 29151, + 'frame_number': 29151, + 'framesequence': 117916, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42126530408859253, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.3479188978672, + 'timestamp_carla': 995347, + 'timestamp_device': 2613907, + 'timestamp_stream': 995.3479188978672, + 'transform': [array([ 3.56066315e+02, 7.75757904e+01, -1.60407782e-01]), + array([-4.46011312e-03, 5.29872398e+01, 1.55029241e-02])]} +{'AngularVelocity': array([ 0.02483569, -0.0263351 , -5.17000008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.97663116455078, + 'FR_Wheel_Angle': 38.034400939941406, + 'Location': array([249.22930908, 137.76342773, 0.30170336]), + 'Rotation': array([-1.53201139e-02, 1.34648376e+02, -8.81957915e-03]), + 'Velocity': array([ 4.85873014e-01, -2.32244328e-01, 5.08499143e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5546264648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23760.71289062, 15824.89941406, 30.00003052]), + 'frame': 29152, + 'frame_number': 29152, + 'framesequence': 117920, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4207342863082886, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.3819972984493, + 'timestamp_carla': 995381, + 'timestamp_device': 2613940, + 'timestamp_stream': 995.3819972984493, + 'transform': [array([ 3.56294678e+02, 7.78860168e+01, -1.59059212e-01]), + array([-5.73735870e-03, 5.31439819e+01, 1.61132775e-02])]} +{'AngularVelocity': array([ 0.00738955, -0.02616434, -5.37581968]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.035865783691406, + 'FR_Wheel_Angle': 37.335243225097656, + 'Location': array([249.33573914, 137.70283508, 0.30171025]), + 'Rotation': array([-1.62968300e-02, 1.33206741e+02, -9.27734468e-03]), + 'Velocity': array([ 4.88177389e-01, -2.45416254e-01, 1.17063522e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5526733398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23761.49609375, 15823.56152344, 30. ]), + 'frame': 29153, + 'frame_number': 29153, + 'framesequence': 117924, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41912293434143066, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.4144409969449, + 'timestamp_carla': 995414, + 'timestamp_device': 2613973, + 'timestamp_stream': 995.4144409969449, + 'transform': [array([ 3.56510223e+02, 7.81805267e+01, -1.58796996e-01]), + array([-6.13350933e-03, 5.32925224e+01, 1.62353460e-02])]} +{'AngularVelocity': array([ 0.00892561, -0.02383754, -5.36474466]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.22776985168457, + 'FR_Wheel_Angle': 37.488861083984375, + 'Location': array([249.44116211, 137.63897705, 0.30170631]), + 'Rotation': array([-1.67817734e-02, 1.31764359e+02, -9.30786133e-03]), + 'Velocity': array([ 4.86057699e-01, -2.58441985e-01, -1.26237865e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54833984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23762.31640625, 15822.14746094, 30. ]), + 'frame': 29154, + 'frame_number': 29154, + 'framesequence': 117928, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4189581274986267, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.4480119980872, + 'timestamp_carla': 995447, + 'timestamp_device': 2614007, + 'timestamp_stream': 995.4480119980872, + 'transform': [array([ 3.56728180e+02, 7.84800644e+01, -1.59650266e-01]), + array([-5.67588676e-03, 5.34432640e+01, 1.58691332e-02])]} +{'AngularVelocity': array([ 0.06355453, -0.05549149, -7.26002645]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.62109375, + 'FR_Wheel_Angle': 38.91903305053711, + 'Location': array([249.54890442, 137.57034302, 0.30171788]), + 'Rotation': array([-1.81204900e-02, 1.30261108e+02, -6.95800688e-03]), + 'Velocity': array([ 5.12640476e-01, -2.71759301e-01, -1.04494095e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54931640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23763.08398438, 15820.80664062, 30.00003052]), + 'frame': 29155, + 'frame_number': 29155, + 'framesequence': 117932, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.4812530986965, + 'timestamp_carla': 995480, + 'timestamp_device': 2614040, + 'timestamp_stream': 995.4812530986965, + 'transform': [array([ 3.56947021e+02, 7.87827454e+01, -1.59829900e-01]), + array([-5.89445280e-03, 5.35952415e+01, 1.58080999e-02])]} +{'AngularVelocity': array([ 0.05247641, -0.05793868, -8.06992722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.500898361206055, + 'FR_Wheel_Angle': 41.07823944091797, + 'Location': array([249.66177368, 137.49897766, 0.30170584]), + 'Rotation': array([-1.70891322e-02, 1.28546173e+02, -6.62231352e-03]), + 'Velocity': array([ 5.25586247e-01, -2.73542672e-01, -2.40812296e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5505981445312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23763.8671875 , 15819.45507812, 30. ]), + 'frame': 29156, + 'frame_number': 29156, + 'framesequence': 117936, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.420294851064682, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.5140880979598, + 'timestamp_carla': 995513, + 'timestamp_device': 2614073, + 'timestamp_stream': 995.5140880979598, + 'transform': [array([ 3.57154358e+02, 7.90702896e+01, -1.60179019e-01]), + array([-5.67588676e-03, 5.37395439e+01, 1.56555139e-02])]} +{'AngularVelocity': array([ 0.05321264, -0.0521905 , -8.19085598]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.734193801879883, + 'FR_Wheel_Angle': 41.57905960083008, + 'Location': array([249.7747345 , 137.42404175, 0.30171469]), + 'Rotation': array([-1.71232838e-02, 1.26766525e+02, -8.78906343e-03]), + 'Velocity': array([ 5.24661243e-01, -2.94018656e-01, -5.08308403e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55029296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23764.64453125, 15818.10644531, 30. ]), + 'frame': 29157, + 'frame_number': 29157, + 'framesequence': 117940, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4201483428478241, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.5484234988689, + 'timestamp_carla': 995548, + 'timestamp_device': 2614107, + 'timestamp_stream': 995.5484234988689, + 'transform': [array([ 3.57370117e+02, 7.93718262e+01, -1.60988390e-01]), + array([-5.40267956e-03, 5.38904152e+01, 1.53198196e-02])]} +{'AngularVelocity': array([ 0.05790276, -0.06179771, -8.20579624]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.734264373779297, + 'FR_Wheel_Angle': 41.57865905761719, + 'Location': array([249.8861084 , 137.34513855, 0.30170691]), + 'Rotation': array([-1.67203024e-02, 1.24975800e+02, -1.01318369e-02]), + 'Velocity': array([ 5.14899373e-01, -3.09854686e-01, -2.01597213e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5515747070312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23765.4140625 , 15816.79101562, 30. ]), + 'frame': 29158, + 'frame_number': 29158, + 'framesequence': 117944, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4183904826641083, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.5835285969079, + 'timestamp_carla': 995583, + 'timestamp_device': 2614140, + 'timestamp_stream': 995.5835285969079, + 'transform': [array([ 3.57587341e+02, 7.96769791e+01, -1.61432028e-01]), + array([-5.21826418e-03, 5.40428658e+01, 1.51367122e-02])]} +{'AngularVelocity': array([ 0.05547739, -0.06359812, -8.21780682]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.733577728271484, + 'FR_Wheel_Angle': 41.577632904052734, + 'Location': array([249.99575806, 137.26220703, 0.30171034]), + 'Rotation': array([-1.66588314e-02, 1.23170952e+02, -1.04675265e-02]), + 'Velocity': array([ 5.05921781e-01, -3.27024251e-01, -2.26974487e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5506591796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23766.20117188, 15815.44824219, 29.99996948]), + 'frame': 29159, + 'frame_number': 29159, + 'framesequence': 117948, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4102420210838318, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.6168047972023, + 'timestamp_carla': 995616, + 'timestamp_device': 2614173, + 'timestamp_stream': 995.6168047972023, + 'transform': [array([ 3.57789612e+02, 7.99621887e+01, -1.61168903e-01]), + array([-5.00652846e-03, 5.41851730e+01, 1.52282659e-02])]} +{'AngularVelocity': array([ 0.05111978, -0.06562339, -8.2145586 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.733360290527344, + 'FR_Wheel_Angle': 41.57735061645508, + 'Location': array([250.10250854, 137.17596436, 0.30170688]), + 'Rotation': array([-1.66315101e-02, 1.21369789e+02, -1.04064951e-02]), + 'Velocity': array([ 4.96205688e-01, -3.43072236e-01, 8.33320591e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5491943359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23767.0078125 , 15814.08398438, 29.99996948]), + 'frame': 29160, + 'frame_number': 29160, + 'framesequence': 117953, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3974608778953552, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.6527859978378, + 'timestamp_carla': 995652, + 'timestamp_device': 2614215, + 'timestamp_stream': 995.6527859978378, + 'transform': [array([ 3.57999451e+02, 8.02587891e+01, -1.61337852e-01]), + array([-4.42596246e-03, 5.43330307e+01, 1.51367160e-02])]} +{'AngularVelocity': array([ 0.04846399, -0.06577661, -8.24011326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.732358932495117, + 'FR_Wheel_Angle': 41.57615661621094, + 'Location': array([250.20632935, 137.08660889, 0.30171067]), + 'Rotation': array([-1.67544540e-02, 1.19571884e+02, -1.04064951e-02]), + 'Velocity': array([ 4.87010270e-01, -3.60078841e-01, 7.41100303e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23767.78320312, 15812.796875 , 30. ]), + 'frame': 29161, + 'frame_number': 29161, + 'framesequence': 117956, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3816584050655365, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.681413397193, + 'timestamp_carla': 995681, + 'timestamp_device': 2614240, + 'timestamp_stream': 995.681413397193, + 'transform': [array([ 3.58157135e+02, 8.04814911e+01, -1.60717696e-01]), + array([-3.57218878e-03, 5.44441185e+01, 1.53503371e-02])]} +{'AngularVelocity': array([ 0.04896099, -0.07064886, -8.2604723 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731952667236328, + 'FR_Wheel_Angle': 41.57657241821289, + 'Location': array([250.29411316, 137.00643921, 0.30170166]), + 'Rotation': array([-1.66588314e-02, 1.18011963e+02, -1.05285654e-02]), + 'Velocity': array([ 4.76772338e-01, -3.72515619e-01, -3.28063943e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5488891601562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23768.63085938, 15811.43261719, 30. ]), + 'frame': 29162, + 'frame_number': 29162, + 'framesequence': 117960, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.369646281003952, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.7151462994516, + 'timestamp_carla': 995714, + 'timestamp_device': 2614273, + 'timestamp_stream': 995.7151462994516, + 'transform': [array([ 3.58336395e+02, 8.07352142e+01, -1.61027983e-01]), + array([-2.62279250e-03, 5.45705643e+01, 1.51672317e-02])]} +{'AngularVelocity': array([ 0.04818587, -0.07272819, -8.29477596]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731964111328125, + 'FR_Wheel_Angle': 41.57413864135742, + 'Location': array([250.4074707 , 136.89616394, 0.30169365]), + 'Rotation': array([-1.67544540e-02, 1.15936104e+02, -1.04370108e-02]), + 'Velocity': array([ 4.64195162e-01, -3.90052110e-01, -3.12156684e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5457153320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23769.3359375 , 15810.35839844, 29.99996948]), + 'frame': 29163, + 'frame_number': 29163, + 'framesequence': 117964, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35355085134506226, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.7490004971623, + 'timestamp_carla': 995748, + 'timestamp_device': 2614307, + 'timestamp_stream': 995.7490004971623, + 'transform': [array([ 3.58508820e+02, 8.09795303e+01, -1.61103964e-01]), + array([-2.13784911e-03, 5.46922874e+01, 1.51061984e-02])]} +{'AngularVelocity': array([ 0.03995484, -0.08144145, -8.34666157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72972297668457, + 'FR_Wheel_Angle': 41.57185363769531, + 'Location': array([250.50218201, 136.79753113, 0.30171242]), + 'Rotation': array([-1.68159250e-02, 1.14140068e+02, -1.02539062e-02]), + 'Velocity': array([ 4.56947416e-01, -4.09682900e-01, 1.44357677e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5521240234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23770.15625 , 15809.12792969, 29.99996948]), + 'frame': 29164, + 'frame_number': 29164, + 'framesequence': 117968, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3451460599899292, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.780880600214, + 'timestamp_carla': 995780, + 'timestamp_device': 2614340, + 'timestamp_stream': 995.780880600214, + 'transform': [array([ 3.58666229e+02, 8.12025833e+01, -1.60891414e-01]), + array([-1.83049054e-03, 5.48033943e+01, 1.51672345e-02])]} +{'AngularVelocity': array([ 0.04059139, -0.07967925, -8.34228325]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.72992515563965, + 'FR_Wheel_Angle': 41.57139587402344, + 'Location': array([250.59503174, 136.69451904, 0.30170909]), + 'Rotation': array([-1.67817734e-02, 1.12318665e+02, -1.04370117e-02]), + 'Velocity': array([ 4.42941666e-01, -4.23032403e-01, -4.25052640e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.555908203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23770.9921875, 15807.9140625, 30. ]), + 'frame': 29165, + 'frame_number': 29165, + 'framesequence': 117972, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3468855917453766, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.8151351995766, + 'timestamp_carla': 995814, + 'timestamp_device': 2614373, + 'timestamp_stream': 995.8151351995766, + 'transform': [array([ 3.58826172e+02, 8.14295425e+01, -1.61771923e-01]), + array([-1.55728310e-03, 5.49164314e+01, 1.48010226e-02])]} +{'AngularVelocity': array([ 0.03580675, -0.07955723, -8.33181 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730026245117188, + 'FR_Wheel_Angle': 41.573089599609375, + 'Location': array([250.68453979, 136.58862305, 0.30170837]), + 'Rotation': array([-1.66861508e-02, 1.10498550e+02, -1.04980459e-02]), + 'Velocity': array([ 4.28855270e-01, -4.36977118e-01, 1.63640972e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5601196289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23771.79492188, 15806.78222656, 30.00006104]), + 'frame': 29166, + 'frame_number': 29166, + 'framesequence': 117976, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35419172048568726, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.8485101982951, + 'timestamp_carla': 995848, + 'timestamp_device': 2614407, + 'timestamp_stream': 995.8485101982951, + 'transform': [array([ 3.58992828e+02, 8.16688766e+01, -1.61326140e-01]), + array([-2.80720764e-03, 5.50351257e+01, 1.50451604e-02])]} +{'AngularVelocity': array([ 0.0368778 , -0.07698589, -8.29216576]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731067657470703, + 'FR_Wheel_Angle': 41.57374954223633, + 'Location': array([250.77047729, 136.48010254, 0.30170739]), + 'Rotation': array([-1.66861508e-02, 1.08682411e+02, -1.06811523e-02]), + 'Velocity': array([ 4.12375987e-01, -4.47824806e-01, -9.75513467e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5606689453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23772.6484375 , 15805.60253906, 30. ]), + 'frame': 29167, + 'frame_number': 29167, + 'framesequence': 117980, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3618640899658203, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.8815231993794, + 'timestamp_carla': 995881, + 'timestamp_device': 2614440, + 'timestamp_stream': 995.8815231993794, + 'transform': [array([ 3.59160858e+02, 8.19110718e+01, -1.60076097e-01]), + array([-3.72245279e-03, 5.51550865e+01, 1.55944787e-02])]} +{'AngularVelocity': array([ 0.03439448, -0.07697424, -8.29099464]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7311954498291, + 'FR_Wheel_Angle': 41.573394775390625, + 'Location': array([250.85331726, 136.36846924, 0.30170181]), + 'Rotation': array([-1.66588314e-02, 1.06858574e+02, -1.06811542e-02]), + 'Velocity': array([ 3.97695184e-01, -4.60250765e-01, -1.67846683e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5582885742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23773.47460938, 15804.4296875 , 29.99996948]), + 'frame': 29168, + 'frame_number': 29168, + 'framesequence': 117984, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36689963936805725, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.9146516993642, + 'timestamp_carla': 995914, + 'timestamp_device': 2614473, + 'timestamp_stream': 995.9146516993642, + 'transform': [array([ 3.59335968e+02, 8.21652527e+01, -1.58909142e-01]), + array([-4.67184931e-03, 5.52806702e+01, 1.61132794e-02])]} +{'AngularVelocity': array([ 0.02769326, -0.07488502, -8.26728058]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73088836669922, + 'FR_Wheel_Angle': 41.575782775878906, + 'Location': array([250.93208313, 136.25494385, 0.30170882]), + 'Rotation': array([-1.66861508e-02, 1.05045692e+02, -1.06201172e-02]), + 'Velocity': array([ 3.83347541e-01, -4.74505574e-01, 4.22172539e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5555419921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23774.31054688, 15803.24414062, 30. ]), + 'frame': 29169, + 'frame_number': 29169, + 'framesequence': 117988, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36559954285621643, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.9490819983184, + 'timestamp_carla': 995948, + 'timestamp_device': 2614507, + 'timestamp_stream': 995.9490819983184, + 'transform': [array([ 3.59523987e+02, 8.24406433e+01, -1.58216506e-01]), + array([-5.09532075e-03, 5.54162521e+01, 1.64184514e-02])]} +{'AngularVelocity': array([ 0.027473 , -0.07747743, -8.27019787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731266021728516, + 'FR_Wheel_Angle': 41.574066162109375, + 'Location': array([251.00726318, 136.13887024, 0.30171111]), + 'Rotation': array([-1.66861508e-02, 1.03230766e+02, -1.06201163e-02]), + 'Velocity': array([ 3.67494613e-01, -4.84728128e-01, 1.20725628e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5525512695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23775.16796875, 15802.03320312, 29.99996948]), + 'frame': 29170, + 'frame_number': 29170, + 'framesequence': 117992, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3619922697544098, + 'throttle_input': 0.22618448734283447, + 'timestamp': 995.9810597002506, + 'timestamp_carla': 995980, + 'timestamp_device': 2614540, + 'timestamp_stream': 995.9810597002506, + 'transform': [array([ 3.59684174e+02, 8.26733398e+01, -1.57118261e-01]), + array([-5.49830217e-03, 5.55312958e+01, 1.68762151e-02])]} +{'AngularVelocity': array([ 0.02629677, -0.07869178, -8.28607655]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73107147216797, + 'FR_Wheel_Angle': 41.572994232177734, + 'Location': array([251.07914734, 136.0199585 , 0.30170551]), + 'Rotation': array([-1.67203024e-02, 1.01407463e+02, -1.05285635e-02]), + 'Velocity': array([ 3.52417827e-01, -4.96314734e-01, 3.72982031e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.549072265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23776.05664062, 15800.77539062, 29.99990845]), + 'frame': 29171, + 'frame_number': 29171, + 'framesequence': 117996, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35834836959838867, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.0146974995732, + 'timestamp_carla': 996014, + 'timestamp_device': 2614573, + 'timestamp_stream': 996.0146974995732, + 'transform': [array([ 3.59858459e+02, 8.29291763e+01, -1.57147706e-01]), + array([-5.67588676e-03, 5.56572762e+01, 1.68762151e-02])]} +{'AngularVelocity': array([ 0.02408004, -0.07997333, -8.29059982]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730802536010742, + 'FR_Wheel_Angle': 41.57318115234375, + 'Location': array([251.13717651, 135.91716003, 0.30170584]), + 'Rotation': array([-1.66861508e-02, 9.98588486e+01, -1.05590830e-02]), + 'Velocity': array([ 3.38863015e-01, -5.05773902e-01, -2.69889824e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5491943359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23776.92773438, 15799.58398438, 30.00006104]), + 'frame': 29172, + 'frame_number': 29172, + 'framesequence': 118000, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35657215118408203, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.0484438985586, + 'timestamp_carla': 996048, + 'timestamp_device': 2614607, + 'timestamp_stream': 996.0484438985586, + 'transform': [array([ 3.60021240e+02, 8.31678314e+01, -1.58250883e-01]), + array([-5.37535874e-03, 5.57749023e+01, 1.64184533e-02])]} +{'AngularVelocity': array([ 0.0214574 , -0.07998079, -8.2918272 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730716705322266, + 'FR_Wheel_Angle': 41.57408905029297, + 'Location': array([251.20152283, 135.7948761 , 0.30170703]), + 'Rotation': array([-1.66861508e-02, 9.80454102e+01, -1.06201172e-02]), + 'Velocity': array([ 3.22788954e-01, -5.16654551e-01, 6.29711139e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5478515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23777.82421875, 15798.34082031, 30. ]), + 'frame': 29173, + 'frame_number': 29173, + 'framesequence': 118004, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3579820990562439, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.0802680999041, + 'timestamp_carla': 996079, + 'timestamp_device': 2614640, + 'timestamp_stream': 996.0802680999041, + 'transform': [array([ 3.60179352e+02, 8.34019928e+01, -1.59318164e-01]), + array([-4.91090585e-03, 5.58898697e+01, 1.59606896e-02])]} +{'AngularVelocity': array([ 0.01785626, -0.08013979, -8.28540611]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730798721313477, + 'FR_Wheel_Angle': 41.5738410949707, + 'Location': array([251.27038574, 135.65257263, 0.30171072]), + 'Rotation': array([-1.67203024e-02, 9.59710541e+01, -1.05895987e-02]), + 'Velocity': array([ 3.03889364e-01, -5.28284252e-01, 7.48920429e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484619140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23778.71679688, 15797.12988281, 30.00003052]), + 'frame': 29174, + 'frame_number': 29174, + 'framesequence': 118008, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.1141585968435, + 'timestamp_carla': 996113, + 'timestamp_device': 2614673, + 'timestamp_stream': 996.1141585968435, + 'transform': [array([ 3.60343475e+02, 8.36460648e+01, -1.60446018e-01]), + array([-4.76064160e-03, 5.60095749e+01, 1.55029260e-02])]} +{'AngularVelocity': array([ 0.01460456, -0.07892123, -8.27395058]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730648040771484, + 'FR_Wheel_Angle': 41.57437515258789, + 'Location': array([251.32647705, 135.52577209, 0.30171102]), + 'Rotation': array([-1.67544540e-02, 9.41516037e+01, -1.06506338e-02]), + 'Velocity': array([ 2.86910564e-01, -5.38143039e-01, 2.43763920e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5529174804688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23779.53710938, 15796.00390625, 29.99996948]), + 'frame': 29175, + 'frame_number': 29175, + 'framesequence': 118012, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36127811670303345, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.1485660970211, + 'timestamp_carla': 996148, + 'timestamp_device': 2614707, + 'timestamp_stream': 996.1485660970211, + 'transform': [array([ 3.60504364e+02, 8.38861237e+01, -1.61526337e-01]), + array([-4.81528323e-03, 5.61272011e+01, 1.50756771e-02])]} +{'AngularVelocity': array([ 0.01427214, -0.08602851, -8.28857803]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731246948242188, + 'FR_Wheel_Angle': 41.573814392089844, + 'Location': array([251.3712616 , 135.41601562, 0.30170447]), + 'Rotation': array([-1.66861508e-02, 9.25976105e+01, -1.07421884e-02]), + 'Velocity': array([ 2.71795541e-01, -5.43318033e-01, -1.49288171e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5523681640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23780.40625 , 15794.82519531, 30. ]), + 'frame': 29176, + 'frame_number': 29176, + 'framesequence': 118016, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36050906777381897, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.1813519001007, + 'timestamp_carla': 996181, + 'timestamp_device': 2614740, + 'timestamp_stream': 996.1813519001007, + 'transform': [array([ 3.60657623e+02, 8.41159744e+01, -1.62078515e-01]), + array([-4.46011312e-03, 5.62396202e+01, 1.48315402e-02])]} +{'AngularVelocity': array([ 0.01125007, -0.08348161, -8.2973671 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730741500854492, + 'FR_Wheel_Angle': 41.573612213134766, + 'Location': array([251.41972351, 135.28645325, 0.30170766]), + 'Rotation': array([-1.67817734e-02, 9.07812195e+01, -1.06506348e-02]), + 'Velocity': array([ 2.54917473e-01, -5.53207099e-01, -2.85911556e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55126953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23781.265625 , 15793.65722656, 29.99996948]), + 'frame': 29177, + 'frame_number': 29177, + 'framesequence': 118020, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35920900106430054, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.2143319994211, + 'timestamp_carla': 996214, + 'timestamp_device': 2614773, + 'timestamp_stream': 996.2143319994211, + 'transform': [array([ 3.60812103e+02, 8.43490524e+01, -1.62032202e-01]), + array([-4.69916966e-03, 5.63534088e+01, 1.48620522e-02])]} +{'AngularVelocity': array([ 0.00857156, -0.08387036, -8.29758263]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73088836669922, + 'FR_Wheel_Angle': 41.572731018066406, + 'Location': array([251.46418762, 135.15498352, 0.30170891]), + 'Rotation': array([-1.67817734e-02, 8.89600372e+01, -1.06811523e-02]), + 'Velocity': array([ 2.37222552e-01, -5.61253786e-01, -2.46715535e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.553955078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23782.08203125, 15792.55664062, 29.99996948]), + 'frame': 29178, + 'frame_number': 29178, + 'framesequence': 118024, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35911738872528076, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.2480885982513, + 'timestamp_carla': 996247, + 'timestamp_device': 2614807, + 'timestamp_stream': 996.2480885982513, + 'transform': [array([ 3.60982483e+02, 8.46074982e+01, -1.59188151e-01]), + array([-5.55977365e-03, 5.64793282e+01, 1.60522424e-02])]} +{'AngularVelocity': array([ 6.28399150e-03, -8.41442049e-02, -8.30298805e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.730802536010742, + 'FR_Wheel_Angle': 41.57249069213867, + 'Location': array([251.50448608, 135.02203369, 0.30170101]), + 'Rotation': array([-1.68159250e-02, 8.71367493e+01, -1.06201172e-02]), + 'Velocity': array([ 2.19436795e-01, -5.68229139e-01, -4.82940668e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5540161132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23782.90039062, 15791.45117188, 30. ]), + 'frame': 29179, + 'frame_number': 29179, + 'framesequence': 118028, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.2817094996572, + 'timestamp_carla': 996281, + 'timestamp_device': 2614840, + 'timestamp_stream': 996.2817094996572, + 'transform': [array([ 3.61157654e+02, 8.48736877e+01, -1.55642390e-01]), + array([-6.87116990e-03, 5.66089973e+01, 1.75475962e-02])]} +{'AngularVelocity': array([ 3.11486283e-03, -8.38801637e-02, -8.29611397e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7305965423584, + 'FR_Wheel_Angle': 41.573787689208984, + 'Location': array([251.54039001, 134.88845825, 0.30170652]), + 'Rotation': array([-1.68432463e-02, 8.53220062e+01, -1.06506357e-02]), + 'Velocity': array([ 2.01161787e-01, -5.75004935e-01, -1.54495240e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484008789062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23783.80078125, 15790.25390625, 30.00003052]), + 'frame': 29180, + 'frame_number': 29180, + 'framesequence': 118032, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36030763387680054, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.3147285990417, + 'timestamp_carla': 996314, + 'timestamp_device': 2614873, + 'timestamp_stream': 996.3147285990417, + 'transform': [array([ 3.61331360e+02, 8.51395111e+01, -1.54835969e-01]), + array([-7.11022643e-03, 5.67381821e+01, 1.78832896e-02])]} +{'AngularVelocity': array([ 1.53095450e-03, -8.68458748e-02, -8.28767586e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731130599975586, + 'FR_Wheel_Angle': 41.57417297363281, + 'Location': array([251.57206726, 134.75352478, 0.30170169]), + 'Rotation': array([-1.68432463e-02, 8.35046005e+01, -1.07421856e-02]), + 'Velocity': array([ 1.82594374e-01, -5.79440355e-01, -2.19936366e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5421752929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23784.76953125, 15788.97851562, 29.99996948]), + 'frame': 29181, + 'frame_number': 29181, + 'framesequence': 118036, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.348698399961, + 'timestamp_carla': 996348, + 'timestamp_device': 2614907, + 'timestamp_stream': 996.348698399961, + 'transform': [array([ 3.61505157e+02, 8.54067001e+01, -1.55643806e-01]), + array([-6.87116990e-03, 5.68679008e+01, 1.75475962e-02])]} +{'AngularVelocity': array([-6.72119902e-04, -8.08821768e-02, -8.23498249e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.733015060424805, + 'FR_Wheel_Angle': 41.578369140625, + 'Location': array([251.59936523, 134.61836243, 0.30170849]), + 'Rotation': array([-1.67817734e-02, 8.16941757e+01, -1.07727041e-02]), + 'Velocity': array([ 1.63523063e-01, -5.83233535e-01, 1.10616682e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5416870117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23785.70507812, 15787.73828125, 30. ]), + 'frame': 29182, + 'frame_number': 29182, + 'framesequence': 118040, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35887935757637024, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.382671598345, + 'timestamp_carla': 996382, + 'timestamp_device': 2614940, + 'timestamp_stream': 996.382671598345, + 'transform': [array([ 3.61668427e+02, 8.56578674e+01, -1.57388568e-01]), + array([-6.25645276e-03, 5.69898682e+01, 1.68151800e-02])]} +{'AngularVelocity': array([-3.97642050e-03, -8.68073404e-02, -8.07552433e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.739835739135742, + 'FR_Wheel_Angle': 41.59006118774414, + 'Location': array([251.62223816, 134.48373413, 0.30169886]), + 'Rotation': array([-1.62968300e-02, 7.99023895e+01, -1.12915039e-02]), + 'Velocity': array([ 1.42864972e-01, -5.73510408e-01, -1.13630289e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5419311523438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23786.65039062, 15786.484375 , 29.99996948]), + 'frame': 29183, + 'frame_number': 29183, + 'framesequence': 118044, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35188451409339905, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.4146095998585, + 'timestamp_carla': 996414, + 'timestamp_device': 2614973, + 'timestamp_stream': 996.4146095998585, + 'transform': [array([ 3.61816254e+02, 8.58859482e+01, -1.59037173e-01]), + array([-5.61441528e-03, 5.71004982e+01, 1.61132757e-02])]} +{'AngularVelocity': array([-6.28458057e-03, -7.97657445e-02, -7.76059198e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74793815612793, + 'FR_Wheel_Angle': 41.604129791259766, + 'Location': array([251.6426239 , 134.33474731, 0.30170467]), + 'Rotation': array([-1.59553215e-02, 7.79291077e+01, -1.15966797e-02]), + 'Velocity': array([ 1.17929243e-01, -5.55743635e-01, 1.60675045e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.544189453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23787.58007812, 15785.27050781, 29.99996948]), + 'frame': 29184, + 'frame_number': 29184, + 'framesequence': 118048, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.34075137972831726, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.447905600071, + 'timestamp_carla': 996447, + 'timestamp_device': 2615007, + 'timestamp_stream': 996.447905600071, + 'transform': [array([ 3.61969666e+02, 8.61239853e+01, -1.60137594e-01]), + array([-4.73332079e-03, 5.72157326e+01, 1.56249944e-02])]} +{'AngularVelocity': array([-0.01553383, -0.09130321, -7.64514923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754926681518555, + 'FR_Wheel_Angle': 41.612831115722656, + 'Location': array([251.65423584, 134.22619629, 0.30169949]), + 'Rotation': array([-1.58938486e-02, 7.64950180e+01, -1.13220224e-02]), + 'Velocity': array([ 1.02869138e-01, -5.45097053e-01, -1.38072966e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5498046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23788.4375 , 15784.16210938, 30. ]), + 'frame': 29185, + 'frame_number': 29185, + 'framesequence': 118052, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3276589512825012, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.4813505969942, + 'timestamp_carla': 996481, + 'timestamp_device': 2615040, + 'timestamp_stream': 996.4813505969942, + 'transform': [array([ 3.62114441e+02, 8.63476257e+01, -1.60080224e-01]), + array([-4.27569821e-03, 5.73241882e+01, 1.56249944e-02])]} +{'AngularVelocity': array([-0.01950948, -0.08552937, -7.12932396]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75507354736328, + 'FR_Wheel_Angle': 41.62081527709961, + 'Location': array([251.66378784, 134.10192871, 0.30170906]), + 'Rotation': array([-1.67544540e-02, 7.48704834e+01, -1.17797842e-02]), + 'Velocity': array([ 7.66163468e-02, -5.47663391e-01, 1.52587891e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5520629882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23789.33203125, 15783.02539062, 30. ]), + 'frame': 29186, + 'frame_number': 29186, + 'framesequence': 118056, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3118015229701996, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.514740999788, + 'timestamp_carla': 996514, + 'timestamp_device': 2615073, + 'timestamp_stream': 996.514740999788, + 'transform': [array([ 3.62261230e+02, 8.65753098e+01, -1.59138069e-01]), + array([-4.02981136e-03, 5.74344101e+01, 1.59912053e-02])]} +{'AngularVelocity': array([-0.06857997, -0.05276075, -6.83090639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76826286315918, + 'FR_Wheel_Angle': 41.59516143798828, + 'Location': array([251.67030334, 133.96206665, 0.30171204]), + 'Rotation': array([-1.66588314e-02, 7.30434036e+01, -1.08337393e-02]), + 'Velocity': array([ 5.03754988e-02, -5.66833436e-01, 2.32024191e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5527954101562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23790.26171875, 15781.890625 , 30. ]), + 'frame': 29187, + 'frame_number': 29187, + 'framesequence': 118060, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2964751124382019, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.5483845993876, + 'timestamp_carla': 996548, + 'timestamp_device': 2615107, + 'timestamp_stream': 996.5483845993876, + 'transform': [array([ 3.62404053e+02, 8.67956314e+01, -1.57538563e-01]), + array([-3.96833988e-03, 5.75412521e+01, 1.66320782e-02])]} +{'AngularVelocity': array([-4.42550890e-03, -6.28957003e-02, -7.33717823e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.55225372314453, + 'FR_Wheel_Angle': 38.521202087402344, + 'Location': array([251.67216492, 133.85276794, 0.30171096]), + 'Rotation': array([-1.67203024e-02, 7.16246414e+01, -1.03454590e-02]), + 'Velocity': array([ 5.06325625e-02, -5.44797540e-01, 1.53636920e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55224609375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23791.21484375, 15780.75195312, 30. ]), + 'frame': 29188, + 'frame_number': 29188, + 'framesequence': 118064, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2851405441761017, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.5820498988032, + 'timestamp_carla': 996581, + 'timestamp_device': 2615140, + 'timestamp_stream': 996.5820498988032, + 'transform': [array([ 3.62551178e+02, 8.70210953e+01, -1.52338564e-01]), + array([-5.40267956e-03, 5.76508713e+01, 1.87988225e-02])]} +{'AngularVelocity': array([-0.06502693, -0.12005258, -7.25466299]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.514347076416016, + 'FR_Wheel_Angle': 37.939273834228516, + 'Location': array([251.66752625, 133.72808838, 0.30170169]), + 'Rotation': array([-1.65700372e-02, 7.01441422e+01, -1.23901367e-02]), + 'Velocity': array([ 1.44637357e-02, -5.53180873e-01, -6.07013681e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.550537109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23792.23046875, 15779.58496094, 30. ]), + 'frame': 29189, + 'frame_number': 29189, + 'framesequence': 118068, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.286037802696228, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.6146799996495, + 'timestamp_carla': 996614, + 'timestamp_device': 2615173, + 'timestamp_stream': 996.6146799996495, + 'transform': [array([ 3.62700775e+02, 8.72527847e+01, -1.50745615e-01]), + array([-5.46415104e-03, 5.77630692e+01, 1.94396861e-02])]} +{'AngularVelocity': array([-0.01906481, -0.07715149, -6.57198429]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.30416488647461, + 'FR_Wheel_Angle': 37.5601921081543, + 'Location': array([251.65950012, 133.60588074, 0.30170539]), + 'Rotation': array([-1.63583029e-02, 6.86917343e+01, -1.07421866e-02]), + 'Velocity': array([ 3.07493401e-03, -5.30521512e-01, 1.81198120e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5426025390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23793.390625 , 15778.296875 , 29.99996948]), + 'frame': 29190, + 'frame_number': 29190, + 'framesequence': 118072, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2926114797592163, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.6481886990368, + 'timestamp_carla': 996647, + 'timestamp_device': 2615207, + 'timestamp_stream': 996.6481886990368, + 'transform': [array([ 3.62848541e+02, 8.74825287e+01, -1.52090833e-01]), + array([-5.27973613e-03, 5.78742256e+01, 1.88903734e-02])]} +{'AngularVelocity': array([ 0.02217743, 0.01071913, -5.5768342 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.2231502532959, + 'FR_Wheel_Angle': 36.88407516479492, + 'Location': array([251.64831543, 133.48722839, 0.30168217]), + 'Rotation': array([-1.52586419e-02, 6.73008041e+01, -1.21765146e-02]), + 'Velocity': array([-2.12187674e-02, -4.89181370e-01, -4.23612597e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5424194335938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23794.51757812, 15777.04785156, 29.99993896]), + 'frame': 29191, + 'frame_number': 29191, + 'framesequence': 118076, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30044862627983093, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.6811370998621, + 'timestamp_carla': 996680, + 'timestamp_device': 2615240, + 'timestamp_stream': 996.6811370998621, + 'transform': [array([ 3.62992249e+02, 8.77073212e+01, -1.54361576e-01]), + array([-5.25241531e-03, 5.79827995e+01, 1.79748498e-02])]} +{'AngularVelocity': array([ 0.0344751 , 0.02590588, -4.29102898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.149805068969727, + 'FR_Wheel_Angle': 32.84999084472656, + 'Location': array([251.63392639, 133.38150024, 0.30168372]), + 'Rotation': array([-1.46780759e-02, 6.61365128e+01, -1.47399893e-02]), + 'Velocity': array([-4.84634005e-02, -4.30014372e-01, -2.65827170e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5431518554688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23795.63671875, 15775.80664062, 29.99996948]), + 'frame': 29192, + 'frame_number': 29192, + 'framesequence': 118080, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3067842721939087, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.7148266993463, + 'timestamp_carla': 996714, + 'timestamp_device': 2615273, + 'timestamp_stream': 996.7148266993463, + 'transform': [array([ 3.63135376e+02, 8.79325180e+01, -1.57154456e-01]), + array([-5.09532075e-03, 5.80913925e+01, 1.68456994e-02])]} +{'AngularVelocity': array([ 0.01683978, 0.08429892, -3.54405999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.576026916503906, + 'FR_Wheel_Angle': 33.154197692871094, + 'Location': array([251.61721802, 133.28529358, 0.30169147]), + 'Rotation': array([-1.49854338e-02, 6.51444244e+01, -1.20239258e-02]), + 'Velocity': array([-6.29198775e-02, -4.16054994e-01, -2.32772829e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.545654296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23796.70703125, 15774.61328125, 30. ]), + 'frame': 29193, + 'frame_number': 29193, + 'framesequence': 118084, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30654624104499817, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.7475674003363, + 'timestamp_carla': 996747, + 'timestamp_device': 2615307, + 'timestamp_stream': 996.7475674003363, + 'transform': [array([ 3.63273712e+02, 8.81512909e+01, -1.58624262e-01]), + array([-5.34120761e-03, 5.81967621e+01, 1.62658636e-02])]} +{'AngularVelocity': array([ 1.61615927e-02, 3.77155491e-03, -4.24752522e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.729110717773438, + 'FR_Wheel_Angle': 33.39640808105469, + 'Location': array([251.59851074, 133.18624878, 0.30169696]), + 'Rotation': array([-1.62080377e-02, 6.40892029e+01, -1.00097656e-02]), + 'Velocity': array([-5.87683059e-02, -4.20517713e-01, -7.73906722e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5477905273438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23797.765625 , 15773.42285156, 29.99996948]), + 'frame': 29194, + 'frame_number': 29194, + 'framesequence': 118088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.303158700466156, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.7809353992343, + 'timestamp_carla': 996780, + 'timestamp_device': 2615340, + 'timestamp_stream': 996.7809353992343, + 'transform': [array([ 3.63412506e+02, 8.83716812e+01, -1.59845203e-01]), + array([-5.37535874e-03, 5.83027649e+01, 1.57775842e-02])]} +{'AngularVelocity': array([ 0.01983827, 0.01764265, -3.97127962]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.746366500854492, + 'FR_Wheel_Angle': 29.227949142456055, + 'Location': array([251.57815552, 133.09115601, 0.30170637]), + 'Rotation': array([-1.62695106e-02, 6.30939713e+01, -1.04370127e-02]), + 'Velocity': array([-7.26944134e-02, -4.10799026e-01, 8.14914674e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494384765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23798.78710938, 15772.26757812, 30. ]), + 'frame': 29195, + 'frame_number': 29195, + 'framesequence': 118092, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299203485250473, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.8143867999315, + 'timestamp_carla': 996814, + 'timestamp_device': 2615373, + 'timestamp_stream': 996.8143867999315, + 'transform': [array([ 3.63546936e+02, 8.85859756e+01, -1.61416695e-01]), + array([-4.61037736e-03, 5.84057159e+01, 1.51061947e-02])]} +{'AngularVelocity': array([-0.02046384, -0.0738897 , -4.64459133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.374465942382812, + 'FR_Wheel_Angle': 29.46274757385254, + 'Location': array([251.55114746, 132.98800659, 0.30171883]), + 'Rotation': array([-1.81546416e-02, 6.21287498e+01, -8.45337007e-03]), + 'Velocity': array([-8.90863314e-02, -4.64290529e-01, 4.91428364e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5499877929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23799.8125 , 15771.11621094, 30. ]), + 'frame': 29196, + 'frame_number': 29196, + 'framesequence': 118096, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29636526107788086, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.847891997546, + 'timestamp_carla': 996847, + 'timestamp_device': 2615406, + 'timestamp_stream': 996.847891997546, + 'transform': [array([ 3.63677643e+02, 8.87941971e+01, -1.61945567e-01]), + array([-4.57622670e-03, 5.85057983e+01, 1.48925725e-02])]} +{'AngularVelocity': array([-0.02418271, -0.06573847, -4.62333822]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.13148307800293, + 'FR_Wheel_Angle': 29.17501449584961, + 'Location': array([251.52226257, 132.88308716, 0.30169937]), + 'Rotation': array([-1.62695106e-02, 6.11262970e+01, -9.46044829e-03]), + 'Velocity': array([-9.37883258e-02, -4.47067678e-01, -2.57987966e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5527954101562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23800.8203125 , 15770.00195312, 30. ]), + 'frame': 29197, + 'frame_number': 29197, + 'framesequence': 118100, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2974456250667572, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.8816863000393, + 'timestamp_carla': 996881, + 'timestamp_device': 2615440, + 'timestamp_stream': 996.8816863000393, + 'transform': [array([ 3.63809204e+02, 8.90052338e+01, -1.62196457e-01]), + array([-4.73332079e-03, 5.86070099e+01, 1.48010189e-02])]} +{'AngularVelocity': array([ 0.0200669 , -0.01222607, -4.74730682]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.936616897583008, + 'FR_Wheel_Angle': 28.29582405090332, + 'Location': array([251.49325562, 132.78485107, 0.30168363]), + 'Rotation': array([-1.55045288e-02, 6.01901932e+01, -1.00708017e-02]), + 'Velocity': array([-9.75105613e-02, -4.08212453e-01, -3.61137383e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5531616210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23801.8359375 , 15768.88476562, 29.99996948]), + 'frame': 29198, + 'frame_number': 29198, + 'framesequence': 118104, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29949644207954407, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.9139369986951, + 'timestamp_carla': 996913, + 'timestamp_device': 2615473, + 'timestamp_stream': 996.9139369986951, + 'transform': [array([ 3.63934601e+02, 8.92069473e+01, -1.62046999e-01]), + array([-4.81528323e-03, 5.87036705e+01, 1.48620568e-02])]} +{'AngularVelocity': array([ 0.02156667, -0.00697443, -4.73738575]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.759967803955078, + 'FR_Wheel_Angle': 24.69449806213379, + 'Location': array([251.4493866 , 132.65782166, 0.30172396]), + 'Rotation': array([-1.94387175e-02, 5.90567017e+01, -9.79614351e-03]), + 'Velocity': array([-1.61279306e-01, -5.02496958e-01, 5.48362732e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5523071289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23802.84375 , 15767.77636719, 29.99993896]), + 'frame': 29199, + 'frame_number': 29199, + 'framesequence': 118108, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3014008104801178, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.9492006003857, + 'timestamp_carla': 996949, + 'timestamp_device': 2615506, + 'timestamp_stream': 996.9492006003857, + 'transform': [array([ 3.64070801e+02, 8.94279251e+01, -1.62935525e-01]), + array([-4.52158507e-03, 5.88092651e+01, 1.44958450e-02])]} +{'AngularVelocity': array([ 0.01853548, -0.01014635, -4.58849287]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.155826568603516, + 'FR_Wheel_Angle': 24.858856201171875, + 'Location': array([251.40701294, 132.54528809, 0.30170241]), + 'Rotation': array([-1.65085662e-02, 5.80824966e+01, -9.88769531e-03]), + 'Velocity': array([-1.57410115e-01, -4.75722194e-01, 3.22246560e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5536499023438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23803.8125 , 15766.72363281, 30. ]), + 'frame': 29200, + 'frame_number': 29200, + 'framesequence': 118112, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3008881211280823, + 'throttle_input': 0.22618448734283447, + 'timestamp': 996.9820538982749, + 'timestamp_carla': 996981, + 'timestamp_device': 2615540, + 'timestamp_stream': 996.9820538982749, + 'transform': [array([ 3.64209137e+02, 8.96549759e+01, -1.61420703e-01]), + array([-5.19094337e-03, 5.89173737e+01, 1.51367122e-02])]} +{'AngularVelocity': array([ 0.02914815, -0.00834383, -4.64167643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.304567337036133, + 'FR_Wheel_Angle': 24.997591018676758, + 'Location': array([251.36244202, 132.43309021, 0.30170822]), + 'Rotation': array([-1.65427178e-02, 5.71074219e+01, -9.49096587e-03]), + 'Velocity': array([-1.66324303e-01, -4.77359354e-01, 1.51443483e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5516967773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23804.83789062, 15765.60644531, 30. ]), + 'frame': 29201, + 'frame_number': 29201, + 'framesequence': 118116, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29944151639938354, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.0143192000687, + 'timestamp_carla': 997014, + 'timestamp_device': 2615573, + 'timestamp_stream': 997.0143192000687, + 'transform': [array([ 3.64338806e+02, 8.98667526e+01, -1.60096660e-01]), + array([-5.58026414e-03, 5.90184250e+01, 1.56860296e-02])]} +{'AngularVelocity': array([ 0.02643414, 0.00819432, -4.40742683]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.044483184814453, + 'FR_Wheel_Angle': 20.631956100463867, + 'Location': array([251.31497192, 132.32106018, 0.30171251]), + 'Rotation': array([-1.75126046e-02, 5.61565208e+01, -1.05590820e-02]), + 'Velocity': array([-1.96755335e-01, -4.91457731e-01, -2.74391175e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5507202148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23805.8203125 , 15764.51855469, 30. ]), + 'frame': 29202, + 'frame_number': 29202, + 'framesequence': 118120, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29902034997940063, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.0480270981789, + 'timestamp_carla': 997047, + 'timestamp_device': 2615606, + 'timestamp_stream': 997.0480270981789, + 'transform': [array([ 3.64470367e+02, 9.00823822e+01, -1.60237655e-01]), + array([-5.46415104e-03, 5.91212120e+01, 1.56249972e-02])]} +{'AngularVelocity': array([ 0.02860875, 0.02622102, -3.37810349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.756330490112305, + 'FR_Wheel_Angle': 21.032493591308594, + 'Location': array([251.26127625, 132.20776367, 0.30171272]), + 'Rotation': array([-1.77311692e-02, 5.53129196e+01, -9.33837891e-03]), + 'Velocity': array([-2.19588563e-01, -5.01151145e-01, 2.94303882e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5504150390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23806.81445312, 15763.43945312, 30. ]), + 'frame': 29203, + 'frame_number': 29203, + 'framesequence': 118124, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299917608499527, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.0813611000776, + 'timestamp_carla': 997081, + 'timestamp_device': 2615640, + 'timestamp_stream': 997.0813611000776, + 'transform': [array([ 3.64601990e+02, 9.02986298e+01, -1.59067452e-01]), + array([-5.79883019e-03, 5.92242317e+01, 1.61132775e-02])]} +{'AngularVelocity': array([ 0.04446454, 0.04060343, -3.1626687 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.502744674682617, + 'FR_Wheel_Angle': 20.82929229736328, + 'Location': array([251.20814514, 132.09773254, 0.30169848]), + 'Rotation': array([-1.51903396e-02, 5.45093651e+01, -1.05285635e-02]), + 'Velocity': array([-2.07628652e-01, -4.50095206e-01, -1.08804699e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5496826171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23807.83789062, 15762.33789062, 30.00003052]), + 'frame': 29204, + 'frame_number': 29204, + 'framesequence': 118128, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3005218505859375, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.1147579997778, + 'timestamp_carla': 997114, + 'timestamp_device': 2615673, + 'timestamp_stream': 997.1147579997778, + 'transform': [array([ 3.64734528e+02, 9.05165634e+01, -1.57557711e-01]), + array([-5.86030213e-03, 5.93280296e+01, 1.67236254e-02])]} +{'AngularVelocity': array([-0.05403232, -0.00264483, -2.29744077]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.168310165405273, + 'FR_Wheel_Angle': 19.772239685058594, + 'Location': array([251.15847778, 131.99856567, 0.30170563]), + 'Rotation': array([-1.60509441e-02, 5.37917290e+01, -9.61303618e-03]), + 'Velocity': array([-2.14300975e-01, -4.57852244e-01, 4.09183500e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5480346679688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23808.875 , 15761.22460938, 30. ]), + 'frame': 29205, + 'frame_number': 29205, + 'framesequence': 118132, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30004578828811646, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.147887699306, + 'timestamp_carla': 997147, + 'timestamp_device': 2615706, + 'timestamp_stream': 997.147887699306, + 'transform': [array([ 3.64862061e+02, 9.07281265e+01, -1.59389988e-01]), + array([-5.37535874e-03, 5.94285011e+01, 1.59606878e-02])]} +{'AngularVelocity': array([ 0.00643641, -0.00861989, -1.18087935]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.85921573638916, + 'FR_Wheel_Angle': 16.48200798034668, + 'Location': array([251.10514832, 131.90145874, 0.3017047 ]), + 'Rotation': array([-1.53201139e-02, 5.31883392e+01, -1.23901367e-02]), + 'Velocity': array([-2.16018960e-01, -3.99224728e-01, -2.66265870e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54638671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23809.95703125, 15760.08789062, 30.00003052]), + 'frame': 29206, + 'frame_number': 29206, + 'framesequence': 118136, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29958799481391907, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.1812345981598, + 'timestamp_carla': 997181, + 'timestamp_device': 2615740, + 'timestamp_stream': 997.1812345981598, + 'transform': [array([ 3.64986176e+02, 9.09342346e+01, -1.60617173e-01]), + array([-5.46415104e-03, 5.95264359e+01, 1.54724037e-02])]} +{'AngularVelocity': array([ 0.01865327, 0.001081 , -0.98805487]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.249357223510742, + 'FR_Wheel_Angle': 16.572574615478516, + 'Location': array([251.05444336, 131.81268311, 0.3016969 ]), + 'Rotation': array([-1.46507546e-02, 5.26540375e+01, -1.03759775e-02]), + 'Velocity': array([-1.97621152e-01, -3.62820506e-01, 1.14364622e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494995117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23810.96484375, 15759.02929688, 30. ]), + 'frame': 29207, + 'frame_number': 29207, + 'framesequence': 118140, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2954680025577545, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.2138912975788, + 'timestamp_carla': 997213, + 'timestamp_device': 2615773, + 'timestamp_stream': 997.2138912975788, + 'transform': [array([ 3.65105804e+02, 9.11341553e+01, -1.61879033e-01]), + array([-5.27973613e-03, 5.96212311e+01, 1.49536077e-02])]} +{'AngularVelocity': array([-0.01473823, 0.00190685, -1.5786643 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.383885383605957, + 'FR_Wheel_Angle': 16.69266700744629, + 'Location': array([251.0018158 , 131.72277832, 0.30171087]), + 'Rotation': array([-1.75126046e-02, 5.21102371e+01, -8.27026367e-03]), + 'Velocity': array([-2.26716414e-01, -4.09449309e-01, 1.15680690e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55029296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23811.96679688, 15757.96582031, 29.99996948]), + 'frame': 29208, + 'frame_number': 29208, + 'framesequence': 118144, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2851405441761017, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.2476345971227, + 'timestamp_carla': 997247, + 'timestamp_device': 2615806, + 'timestamp_stream': 997.2476345971227, + 'transform': [array([ 3.65220001e+02, 9.13239822e+01, -1.63086966e-01]), + array([-4.61037736e-03, 5.97114105e+01, 1.44348107e-02])]} +{'AngularVelocity': array([ 0.0244459 , 0.01191763, -0.52049047]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.559759140014648, + 'FR_Wheel_Angle': 11.946065902709961, + 'Location': array([250.9488678 , 131.63566589, 0.30170485]), + 'Rotation': array([-1.55933211e-02, 5.16140251e+01, -1.08642578e-02]), + 'Velocity': array([-2.17680052e-01, -3.57646108e-01, 1.06763837e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.552734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23812.91601562, 15756.95996094, 30. ]), + 'frame': 29209, + 'frame_number': 29209, + 'framesequence': 118148, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.27237769961357117, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.2818564996123, + 'timestamp_carla': 997281, + 'timestamp_device': 2615840, + 'timestamp_stream': 997.2818564996123, + 'transform': [array([ 3.65334747e+02, 9.15151138e+01, -1.62977979e-01]), + array([-4.30301903e-03, 5.98021202e+01, 1.44653274e-02])]} +{'AngularVelocity': array([-0.0252029 , -0.00220064, -0.82736254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.435624122619629, + 'FR_Wheel_Angle': 12.586967468261719, + 'Location': array([250.89363098, 131.55111694, 0.30170837]), + 'Rotation': array([-1.66588314e-02, 5.12255898e+01, -8.57544038e-03]), + 'Velocity': array([-2.33436063e-01, -3.80450666e-01, 3.91960157e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5541381835938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23813.90039062, 15755.95019531, 30. ]), + 'frame': 29210, + 'frame_number': 29210, + 'framesequence': 118152, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25663015246391296, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.3136604987085, + 'timestamp_carla': 997313, + 'timestamp_device': 2615873, + 'timestamp_stream': 997.3136604987085, + 'transform': [array([ 3.65426941e+02, 9.16655960e+01, -1.63043782e-01]), + array([-3.75660392e-03, 5.98740082e+01, 1.44042931e-02])]} +{'AngularVelocity': array([ 0.05134555, -0.02368564, -2.81380653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.185123443603516, + 'FR_Wheel_Angle': 12.433297157287598, + 'Location': array([250.84104919, 131.47181702, 0.30171379]), + 'Rotation': array([-1.93226039e-02, 5.08170128e+01, -7.59887788e-03]), + 'Velocity': array([-2.53353953e-01, -4.04779196e-01, -1.91440573e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55322265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23814.90234375, 15754.93457031, 30. ]), + 'frame': 29211, + 'frame_number': 29211, + 'framesequence': 118156, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24280525743961334, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.3478390984237, + 'timestamp_carla': 997347, + 'timestamp_device': 2615906, + 'timestamp_stream': 997.3478390984237, + 'transform': [array([ 3.65530914e+02, 9.18365021e+01, -1.61395267e-01]), + array([-3.84539622e-03, 5.99554367e+01, 1.50756789e-02])]} +{'AngularVelocity': array([ 0.00871257, -0.00485323, -1.03223741]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.740397453308105, + 'FR_Wheel_Angle': 11.24756145477295, + 'Location': array([250.76544189, 131.35971069, 0.30171818]), + 'Rotation': array([-1.68159250e-02, 5.02699127e+01, -8.69750883e-03]), + 'Velocity': array([-0.27129561, -0.41807052, 0.0008017 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5574951171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23815.84375 , 15754.01855469, 30. ]), + 'frame': 29212, + 'frame_number': 29212, + 'framesequence': 118160, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22821131348609924, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.3808817975223, + 'timestamp_carla': 997380, + 'timestamp_device': 2615940, + 'timestamp_stream': 997.3808817975223, + 'transform': [array([ 3.65626892e+02, 9.19930420e+01, -1.60229340e-01]), + array([-3.66098108e-03, 6.00301895e+01, 1.55334454e-02])]} +{'AngularVelocity': array([ 0.00230864, -0.00427722, 0.20898393]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.2446608543396, + 'FR_Wheel_Angle': 8.336639404296875, + 'Location': array([250.71075439, 131.28369141, 0.30169475]), + 'Rotation': array([-1.46507546e-02, 4.99958267e+01, -1.17797842e-02]), + 'Velocity': array([-2.63750911e-01, -3.63458812e-01, 7.76195520e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.553955078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23816.89453125, 15753.01660156, 29.99996948]), + 'frame': 29213, + 'frame_number': 29213, + 'framesequence': 118164, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22434768080711365, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.4143146984279, + 'timestamp_carla': 997414, + 'timestamp_device': 2615973, + 'timestamp_stream': 997.4143146984279, + 'transform': [array([ 3.65736206e+02, 9.21757660e+01, -1.58975750e-01]), + array([-3.94101907e-03, 6.01166916e+01, 1.60522386e-02])]} +{'AngularVelocity': array([ 0.02264874, -0.01357876, -2.42710304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.571914196014404, + 'FR_Wheel_Angle': 8.31208610534668, + 'Location': array([250.64317322, 131.1927948 , 0.30172661]), + 'Rotation': array([-1.96777731e-02, 4.96934738e+01, -8.17871094e-03]), + 'Velocity': array([-3.04724097e-01, -4.22385842e-01, 1.52845372e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5541381835938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23817.93554688, 15752.04980469, 30. ]), + 'frame': 29214, + 'frame_number': 29214, + 'framesequence': 118168, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2288888394832611, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.4481741972268, + 'timestamp_carla': 997447, + 'timestamp_device': 2616006, + 'timestamp_stream': 997.4481741972268, + 'transform': [array([ 3.65837036e+02, 9.23404160e+01, -1.57581329e-01]), + array([-4.27569821e-03, 6.01952477e+01, 1.66320764e-02])]} +{'AngularVelocity': array([ 0.01358892, -0.01323489, -2.31308365]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.731472492218018, + 'FR_Wheel_Angle': 8.33973217010498, + 'Location': array([250.57450867, 131.10096741, 0.30169189]), + 'Rotation': array([-1.48966415e-02, 4.93922348e+01, -8.88061523e-03]), + 'Velocity': array([-2.66871035e-01, -3.67082119e-01, -2.91252127e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55224609375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23818.98828125, 15751.06835938, 30. ]), + 'frame': 29215, + 'frame_number': 29215, + 'framesequence': 118172, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23692740499973297, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.4806097000837, + 'timestamp_carla': 997480, + 'timestamp_device': 2616040, + 'timestamp_stream': 997.4806097000837, + 'transform': [array([ 3.65954956e+02, 9.25383377e+01, -1.53058738e-01]), + array([-5.73735870e-03, 6.02888947e+01, 1.85241625e-02])]} +{'AngularVelocity': array([ 0.00171166, 0.00896978, -0.51160252]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.222830772399902, + 'FR_Wheel_Angle': 3.4768128395080566, + 'Location': array([250.50874329, 131.01460266, 0.30170634]), + 'Rotation': array([-1.62695106e-02, 4.91359634e+01, -9.76562500e-03]), + 'Velocity': array([-2.87104309e-01, -3.72229874e-01, 1.53779984e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5493774414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23820.12109375, 15750.04394531, 30. ]), + 'frame': 29216, + 'frame_number': 29216, + 'framesequence': 118176, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2448561191558838, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.5139757990837, + 'timestamp_carla': 997513, + 'timestamp_device': 2616073, + 'timestamp_stream': 997.5139757990837, + 'transform': [array([ 3.66074341e+02, 9.27384186e+01, -1.51594803e-01]), + array([-6.71407580e-03, 6.03836517e+01, 1.91650335e-02])]} +{'AngularVelocity': array([-0.03648044, 0.007633 , -0.66331291]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.296082973480225, + 'FR_Wheel_Angle': 4.217608451843262, + 'Location': array([250.44230652, 130.93289185, 0.30170402]), + 'Rotation': array([-1.63309816e-02, 4.89935989e+01, -8.81958101e-03]), + 'Velocity': array([-2.94411093e-01, -3.71290922e-01, 3.79753110e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.543701171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23821.2890625 , 15748.96386719, 30. ]), + 'frame': 29217, + 'frame_number': 29217, + 'framesequence': 118180, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24747459590435028, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.5480232983828, + 'timestamp_carla': 997547, + 'timestamp_device': 2616106, + 'timestamp_stream': 997.5480232983828, + 'transform': [array([ 3.66201080e+02, 9.29534683e+01, -1.51877061e-01]), + array([-7.07607577e-03, 6.04851723e+01, 1.90734789e-02])]} +{'AngularVelocity': array([-0.00606 , 0.00139842, -0.59103334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.012887001037598, + 'FR_Wheel_Angle': 4.101802349090576, + 'Location': array([250.3722229 , 130.84707642, 0.30170688]), + 'Rotation': array([-1.68773960e-02, 4.88413773e+01, -8.33129976e-03]), + 'Velocity': array([-2.99834102e-01, -3.71665895e-01, -2.41641988e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5399780273438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23822.50390625, 15747.83496094, 30. ]), + 'frame': 29218, + 'frame_number': 29218, + 'framesequence': 118184, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2451307773590088, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.5817696005106, + 'timestamp_carla': 997581, + 'timestamp_device': 2616140, + 'timestamp_stream': 997.5817696005106, + 'transform': [array([ 3.66316559e+02, 9.31479187e+01, -1.53516382e-01]), + array([-6.83701877e-03, 6.05772171e+01, 1.84020903e-02])]} +{'AngularVelocity': array([ 0.01223649, -0.00398989, -0.31224951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.1555566787719727, + 'FR_Wheel_Angle': 2.3533337116241455, + 'Location': array([250.30210876, 130.76164246, 0.30170271]), + 'Rotation': array([-1.56889427e-02, 4.87012177e+01, -8.23974609e-03]), + 'Velocity': array([-2.84118563e-01, -3.49904001e-01, 1.84822085e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.537841796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23823.7265625 , 15746.67578125, 30. ]), + 'frame': 29219, + 'frame_number': 29219, + 'framesequence': 118188, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24077273905277252, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.6140782982111, + 'timestamp_carla': 997613, + 'timestamp_device': 2616173, + 'timestamp_stream': 997.6140782982111, + 'transform': [array([ 3.66428009e+02, 9.33368149e+01, -1.54625162e-01]), + array([-6.68675499e-03, 6.06664467e+01, 1.79443266e-02])]} +{'AngularVelocity': array([ 0.00635685, -0.02475 , 1.35429192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.2808590233325958, + 'FR_Wheel_Angle': 0.2287680208683014, + 'Location': array([250.22853088, 130.67675781, 0.30171371]), + 'Rotation': array([-1.74852833e-02, 4.86720772e+01, -1.07116709e-02]), + 'Velocity': array([-3.22899848e-01, -3.60519260e-01, 1.00727077e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5394897460938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23824.92773438, 15745.55859375, 30. ]), + 'frame': 29220, + 'frame_number': 29220, + 'framesequence': 118192, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23742179572582245, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.6477502994239, + 'timestamp_carla': 997647, + 'timestamp_device': 2616206, + 'timestamp_stream': 997.6477502994239, + 'transform': [array([ 3.66541565e+02, 9.35293655e+01, -1.55795977e-01]), + array([-6.31109439e-03, 6.07573929e+01, 1.74560454e-02])]} +{'AngularVelocity': array([ 0.01535752, -0.01789053, 0.1457774 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.08383441716432571, + 'FR_Wheel_Angle': 0.04574369266629219, + 'Location': array([250.14294434, 130.57983398, 0.30170929]), + 'Rotation': array([-1.76696982e-02, 4.86569901e+01, -8.42285249e-03]), + 'Velocity': array([-3.25393736e-01, -3.67729247e-01, 1.66893005e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5429077148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23826.0703125 , 15744.49511719, 30. ]), + 'frame': 29221, + 'frame_number': 29221, + 'framesequence': 118196, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23672598600387573, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.6806151978672, + 'timestamp_carla': 997680, + 'timestamp_device': 2616240, + 'timestamp_stream': 997.6806151978672, + 'transform': [array([ 3.66648163e+02, 9.37101898e+01, -1.57254592e-01]), + array([-5.89445280e-03, 6.08428154e+01, 1.68456938e-02])]} +{'AngularVelocity': array([-0.00703182, -0.00035716, -0.03766228]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.019052837044000626, + 'FR_Wheel_Angle': -0.008893498219549656, + 'Location': array([250.0789032 , 130.50732422, 0.30171779]), + 'Rotation': array([-1.72462258e-02, 4.86706734e+01, -7.93457124e-03]), + 'Velocity': array([-3.30473006e-01, -3.74777943e-01, 3.04265006e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5440063476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23827.26367188, 15743.3984375 , 30. ]), + 'frame': 29222, + 'frame_number': 29222, + 'framesequence': 118200, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23853878676891327, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.7146422974765, + 'timestamp_carla': 997714, + 'timestamp_device': 2616273, + 'timestamp_stream': 997.7146422974765, + 'transform': [array([ 3.66754761e+02, 9.38917389e+01, -1.59474865e-01]), + array([-5.40267956e-03, 6.09284668e+01, 1.59301683e-02])]} +{'AngularVelocity': array([0.02042316, 0.01231485, 0.62267518]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.514646053314209, + 'FR_Wheel_Angle': -4.928378105163574, + 'Location': array([250.00538635, 130.42512512, 0.30170745]), + 'Rotation': array([-1.56547930e-02, 4.87084084e+01, -9.76562593e-03]), + 'Velocity': array([-3.15700144e-01, -3.34412456e-01, 9.34982309e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5469970703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23828.41210938, 15742.3515625 , 30.00003052]), + 'frame': 29223, + 'frame_number': 29223, + 'framesequence': 118204, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24064455926418304, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.7482900992036, + 'timestamp_carla': 997748, + 'timestamp_device': 2616306, + 'timestamp_stream': 997.7482900992036, + 'transform': [array([ 3.66856354e+02, 9.40644913e+01, -1.60785973e-01]), + array([-5.55977365e-03, 6.10100594e+01, 1.54113704e-02])]} +{'AngularVelocity': array([ 0.00021305, -0.01994595, 0.20434436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.012199401855469, + 'FR_Wheel_Angle': -4.105929851531982, + 'Location': array([249.91325378, 130.32717896, 0.30170539]), + 'Rotation': array([-1.65085662e-02, 4.88958817e+01, -8.14819429e-03]), + 'Velocity': array([-3.35387409e-01, -3.55730057e-01, 7.51495327e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5486450195312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23829.5625 , 15741.30566406, 30. ]), + 'frame': 29224, + 'frame_number': 29224, + 'framesequence': 118208, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2413586974143982, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.780655298382, + 'timestamp_carla': 997780, + 'timestamp_device': 2616340, + 'timestamp_stream': 997.780655298382, + 'transform': [array([ 3.66959595e+02, 9.42425919e+01, -1.61013067e-01]), + array([-5.61441528e-03, 6.10938110e+01, 1.53198186e-02])]} +{'AngularVelocity': array([ 0.01813124, -0.02379204, 0.78878635]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.2054762840271, + 'FR_Wheel_Angle': -4.024985313415527, + 'Location': array([249.83512878, 130.24351501, 0.30170387]), + 'Rotation': array([-1.57162640e-02, 4.90488358e+01, -7.59887788e-03]), + 'Velocity': array([-3.18362325e-01, -3.36896747e-01, -6.40201542e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5493774414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23830.68554688, 15740.28515625, 29.99996948]), + 'frame': 29225, + 'frame_number': 29225, + 'framesequence': 118212, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24018678069114685, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.813690200448, + 'timestamp_carla': 997813, + 'timestamp_device': 2616373, + 'timestamp_stream': 997.813690200448, + 'transform': [array([ 3.67064758e+02, 9.44247894e+01, -1.61172718e-01]), + array([-5.67588676e-03, 6.11793938e+01, 1.52587853e-02])]} +{'AngularVelocity': array([4.50598600e-04, 1.18561760e-02, 9.64752316e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.262424468994141, + 'FR_Wheel_Angle': -5.786421775817871, + 'Location': array([249.76307678, 130.16595459, 0.3017028 ]), + 'Rotation': array([-1.58118866e-02, 4.91980476e+01, -7.99560547e-03]), + 'Velocity': array([-3.16460907e-01, -3.31018329e-01, 2.62823101e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5508422851562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23831.765625 , 15739.29785156, 30.00003052]), + 'frame': 29226, + 'frame_number': 29226, + 'framesequence': 118216, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23912473022937775, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.847875200212, + 'timestamp_carla': 997847, + 'timestamp_device': 2616406, + 'timestamp_stream': 997.847875200212, + 'transform': [array([ 3.67164764e+02, 9.45959167e+01, -1.61181331e-01]), + array([-5.67588676e-03, 6.12601051e+01, 1.52587797e-02])]} +{'AngularVelocity': array([-0.02458521, 0.04464542, 1.92585886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.42007064819336, + 'FR_Wheel_Angle': -7.390079021453857, + 'Location': array([249.69046021, 130.09152222, 0.30170959]), + 'Rotation': array([-1.70003399e-02, 4.94733276e+01, -9.67407320e-03]), + 'Velocity': array([-3.44582617e-01, -3.36133808e-01, 6.38294223e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5509643554688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23832.86328125, 15738.296875 , 30. ]), + 'frame': 29227, + 'frame_number': 29227, + 'framesequence': 118220, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23954589664936066, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.8804992996156, + 'timestamp_carla': 997880, + 'timestamp_device': 2616440, + 'timestamp_stream': 997.8804992996156, + 'transform': [array([ 3.67261292e+02, 9.47621460e+01, -1.61182851e-01]), + array([-5.73735870e-03, 6.13383484e+01, 1.52587816e-02])]} +{'AngularVelocity': array([-0.00629313, -0.01260203, 2.36135888]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.368613243103027, + 'FR_Wheel_Angle': -7.630619525909424, + 'Location': array([249.61579895, 130.01470947, 0.30171293]), + 'Rotation': array([-1.63924526e-02, 4.97607079e+01, -7.93457124e-03]), + 'Velocity': array([-0.31985641, -0.32007152, 0.00039201]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5494384765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23834.01171875, 15737.26757812, 29.99996948]), + 'frame': 29228, + 'frame_number': 29228, + 'framesequence': 118224, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24031496047973633, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.915681399405, + 'timestamp_carla': 997915, + 'timestamp_device': 2616473, + 'timestamp_stream': 997.915681399405, + 'transform': [array([ 3.67371857e+02, 9.49530411e+01, -1.57895088e-01]), + array([-6.59113238e-03, 6.14281502e+01, 1.66320708e-02])]} +{'AngularVelocity': array([-0.0068133 , 0.01927825, 2.10349536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.310791015625, + 'FR_Wheel_Angle': -7.7314934730529785, + 'Location': array([249.5464325 , 129.94284058, 0.30169478]), + 'Rotation': array([-1.49239628e-02, 5.00247040e+01, -7.04956008e-03]), + 'Velocity': array([-2.93980151e-01, -2.96560407e-01, 8.82911627e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5504760742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23835.09960938, 15736.29394531, 29.99996948]), + 'frame': 29229, + 'frame_number': 29229, + 'framesequence': 118228, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2402966469526291, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.9501543976367, + 'timestamp_carla': 997949, + 'timestamp_device': 2616506, + 'timestamp_stream': 997.9501543976367, + 'transform': [array([ 3.67489044e+02, 9.51575012e+01, -1.54968947e-01]), + array([-6.83701877e-03, 6.15239906e+01, 1.78222563e-02])]} +{'AngularVelocity': array([ 1.16137555e-03, -4.04983200e-02, 1.66629970e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.90146541595459, + 'FR_Wheel_Angle': -11.952320098876953, + 'Location': array([249.47865295, 129.87310791, 0.30174187]), + 'Rotation': array([-2.19044164e-02, 5.03232727e+01, -1.09252939e-02]), + 'Velocity': array([-3.85431677e-01, -3.74211222e-01, -1.28412241e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5425415039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23836.37109375, 15735.16894531, 29.99993896]), + 'frame': 29230, + 'frame_number': 29230, + 'framesequence': 118232, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.22618448734283447, + 'timestamp': 997.9815346002579, + 'timestamp_carla': 997981, + 'timestamp_device': 2616540, + 'timestamp_stream': 997.9815346002579, + 'transform': [array([ 3.67598267e+02, 9.53510590e+01, -1.55471802e-01]), + array([-6.77554728e-03, 6.16143417e+01, 1.76086351e-02])]} +{'AngularVelocity': array([-0.01663115, -0.02342931, 1.33110404]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.342733383178711, + 'FR_Wheel_Angle': -11.244410514831543, + 'Location': array([249.39678955, 129.792099 , 0.30169615]), + 'Rotation': array([-1.52859623e-02, 5.07915878e+01, -7.17163086e-03]), + 'Velocity': array([-3.32226872e-01, -3.23803365e-01, -1.80578223e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5389404296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23837.66992188, 15734.02734375, 29.99996948]), + 'frame': 29231, + 'frame_number': 29231, + 'framesequence': 118236, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23745842278003693, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.0135268978775, + 'timestamp_carla': 998013, + 'timestamp_device': 2616573, + 'timestamp_stream': 998.0135268978775, + 'transform': [array([ 3.67700104e+02, 9.55298615e+01, -1.56773910e-01]), + array([-6.34524552e-03, 6.16980247e+01, 1.70593187e-02])]} +{'AngularVelocity': array([ 0.00475356, -0.01728244, 2.11013651]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.509275436401367, + 'FR_Wheel_Angle': -11.20656681060791, + 'Location': array([249.31558228, 129.70979309, 0.30171356]), + 'Rotation': array([-1.79155860e-02, 5.12561493e+01, -7.59887695e-03]), + 'Velocity': array([-3.63027692e-01, -3.55342358e-01, 1.96170804e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5436401367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23838.796875 , 15733.01953125, 29.99993896]), + 'frame': 29232, + 'frame_number': 29232, + 'framesequence': 118240, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22951140999794006, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.0476235970855, + 'timestamp_carla': 998047, + 'timestamp_device': 2616606, + 'timestamp_stream': 998.0476235970855, + 'transform': [array([ 3.67800720e+02, 9.57053299e+01, -1.58674881e-01]), + array([-5.71003789e-03, 6.17803497e+01, 1.62658654e-02])]} +{'AngularVelocity': array([ 1.00620864e-02, -1.40020205e-03, 1.66239023e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.733464241027832, + 'FR_Wheel_Angle': -12.85914134979248, + 'Location': array([249.23922729, 129.63128662, 0.30169603]), + 'Rotation': array([-1.44595094e-02, 5.16921654e+01, -6.53076172e-03]), + 'Velocity': array([-3.13063622e-01, -3.07332158e-01, 3.07636248e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5474243164062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23839.9375 , 15732.01757812, 30. ]), + 'frame': 29233, + 'frame_number': 29233, + 'framesequence': 118244, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21702322363853455, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.081464998424, + 'timestamp_carla': 998081, + 'timestamp_device': 2616640, + 'timestamp_stream': 998.081464998424, + 'transform': [array([ 3.67899353e+02, 9.58771667e+01, -1.59166440e-01]), + array([-5.37535874e-03, 6.18609467e+01, 1.60522386e-02])]} +{'AngularVelocity': array([-0.04504148, 0.07979416, 2.31542706]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.68660545349121, + 'FR_Wheel_Angle': -14.081006050109863, + 'Location': array([249.15597534, 129.54878235, 0.30171204]), + 'Rotation': array([-1.81000009e-02, 5.22911797e+01, -9.88769438e-03]), + 'Velocity': array([-3.78508449e-01, -3.52014869e-01, -1.17340089e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23841.140625 , 15730.98144531, 30. ]), + 'frame': 29234, + 'frame_number': 29234, + 'framesequence': 118248, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.20120243728160858, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.1144292987883, + 'timestamp_carla': 998114, + 'timestamp_device': 2616673, + 'timestamp_stream': 998.1144292987883, + 'transform': [array([ 3.67987640e+02, 9.60292435e+01, -1.59629747e-01]), + array([-4.88358503e-03, 6.19324913e+01, 1.58386175e-02])]} +{'AngularVelocity': array([ 0.03281686, -0.02240215, 2.26514482]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.670188903808594, + 'FR_Wheel_Angle': -14.313502311706543, + 'Location': array([249.0799408 , 129.47218323, 0.30169886]), + 'Rotation': array([-1.59280002e-02, 5.28584442e+01, -7.32421922e-03]), + 'Velocity': array([-3.15457404e-01, -2.93305576e-01, -1.99460977e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484619140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23842.34375 , 15729.95898438, 29.99996948]), + 'frame': 29235, + 'frame_number': 29235, + 'framesequence': 118252, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18759728968143463, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.1482253968716, + 'timestamp_carla': 998147, + 'timestamp_device': 2616706, + 'timestamp_stream': 998.1482253968716, + 'transform': [array([ 3.68073792e+02, 9.61765213e+01, -1.60508230e-01]), + array([-4.02981136e-03, 6.20018806e+01, 1.54418880e-02])]} +{'AngularVelocity': array([ 0.00515217, -0.0081396 , 1.40002334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.661848068237305, + 'FR_Wheel_Angle': -14.402902603149414, + 'Location': array([249.01564026, 129.40649414, 0.30169678]), + 'Rotation': array([-1.59553215e-02, 5.33310890e+01, -6.59179688e-03]), + 'Velocity': array([-3.17475110e-01, -3.08831155e-01, -2.42567054e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5509033203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23843.515625 , 15728.99121094, 30. ]), + 'frame': 29236, + 'frame_number': 29236, + 'framesequence': 118256, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17287515103816986, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.1808461993933, + 'timestamp_carla': 998180, + 'timestamp_device': 2616740, + 'timestamp_stream': 998.1808461993933, + 'transform': [array([ 3.68149261e+02, 9.63025970e+01, -1.60445780e-01]), + array([-3.59950960e-03, 6.20616417e+01, 1.54418899e-02])]} +{'AngularVelocity': array([-4.77025984e-04, -2.52080690e-02, 4.09416580e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.37723159790039, + 'FR_Wheel_Angle': -18.160762786865234, + 'Location': array([248.93136597, 129.3203125 , 0.30170807]), + 'Rotation': array([-1.68432463e-02, 5.40327072e+01, -9.58251953e-03]), + 'Velocity': array([-3.34815890e-01, -3.08500707e-01, -9.76181036e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5527954101562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23844.71679688, 15728.02734375, 29.99996948]), + 'frame': 29237, + 'frame_number': 29237, + 'framesequence': 118260, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1647450178861618, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.2135201990604, + 'timestamp_carla': 998213, + 'timestamp_device': 2616773, + 'timestamp_stream': 998.2135201990604, + 'transform': [array([ 3.68220612e+02, 9.64204865e+01, -1.60642013e-01]), + array([-3.38777364e-03, 6.21176643e+01, 1.53503409e-02])]} +{'AngularVelocity': array([-8.46469833e-04, -2.76371948e-02, 3.70091677e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.771631240844727, + 'FR_Wheel_Angle': -17.564735412597656, + 'Location': array([248.8591156 , 129.24777222, 0.3017014 ]), + 'Rotation': array([-1.54430568e-02, 5.47002907e+01, -6.56127883e-03]), + 'Velocity': array([-3.02589297e-01, -2.88612247e-01, 1.87015525e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.554931640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23845.8984375 , 15727.11035156, 29.99996948]), + 'frame': 29238, + 'frame_number': 29238, + 'framesequence': 118264, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16688743233680725, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.2479355968535, + 'timestamp_carla': 998247, + 'timestamp_device': 2616806, + 'timestamp_stream': 998.2479355968535, + 'transform': [array([ 3.68295502e+02, 9.65455093e+01, -1.61908150e-01]), + array([-3.11456621e-03, 6.21768608e+01, 1.48315364e-02])]} +{'AngularVelocity': array([-0.00847282, 0.04560126, 4.05272293]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.8574161529541, + 'FR_Wheel_Angle': -17.463403701782227, + 'Location': array([248.79879761, 129.18566895, 0.30170897]), + 'Rotation': array([-1.78267919e-02, 5.52593880e+01, -8.02612305e-03]), + 'Velocity': array([-3.41596335e-01, -3.28900665e-01, -1.74036017e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5563354492188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23847.07617188, 15726.21582031, 29.99996948]), + 'frame': 29239, + 'frame_number': 29239, + 'framesequence': 118268, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1739555150270462, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.2807902991772, + 'timestamp_carla': 998280, + 'timestamp_device': 2616840, + 'timestamp_stream': 998.2807902991772, + 'transform': [array([ 3.68375854e+02, 9.66833801e+01, -1.61032215e-01]), + array([-4.00249055e-03, 6.22417068e+01, 1.52282678e-02])]} +{'AngularVelocity': array([ 4.85636876e-04, -2.89432313e-02, 4.36484385e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.254741668701172, + 'FR_Wheel_Angle': -19.15989112854004, + 'Location': array([248.7230072 , 129.10591125, 0.30169624]), + 'Rotation': array([-1.95889808e-02, 5.59747200e+01, -8.88061617e-03]), + 'Velocity': array([-0.36048397, -0.3557989 , 0.00079697]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5556640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23848.28710938, 15725.30761719, 30. ]), + 'frame': 29240, + 'frame_number': 29240, + 'framesequence': 118272, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18129825592041016, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.3137343004346, + 'timestamp_carla': 998313, + 'timestamp_device': 2616873, + 'timestamp_stream': 998.3137343004346, + 'transform': [array([ 3.68451996e+02, 9.68127518e+01, -1.60958141e-01]), + array([-4.61037736e-03, 6.23027267e+01, 1.52893029e-02])]} +{'AngularVelocity': array([-0.00683903, -0.01396903, 4.64009285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.96214485168457, + 'FR_Wheel_Angle': -20.02016258239746, + 'Location': array([248.64501953, 129.02592468, 0.30171004]), + 'Rotation': array([-1.57162640e-02, 5.68161964e+01, -8.23974703e-03]), + 'Velocity': array([-3.40280920e-01, -3.18505496e-01, 1.20172495e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5538330078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23849.46289062, 15724.40332031, 30.00006104]), + 'frame': 29241, + 'frame_number': 29241, + 'framesequence': 118276, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18677328526973724, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.3472118005157, + 'timestamp_carla': 998346, + 'timestamp_device': 2616906, + 'timestamp_stream': 998.3472118005157, + 'transform': [array([ 3.68530212e+02, 9.69467545e+01, -1.61032945e-01]), + array([-5.15679270e-03, 6.23658104e+01, 1.52893029e-02])]} +{'AngularVelocity': array([-0.00554306, -0.03779097, 4.36127424]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.997739791870117, + 'FR_Wheel_Angle': -20.26068878173828, + 'Location': array([248.56236267, 128.93939209, 0.30170515]), + 'Rotation': array([-1.58392079e-02, 5.77370415e+01, -6.43920898e-03]), + 'Velocity': array([-3.13139975e-01, -3.07586551e-01, 9.87052917e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5530395507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23850.6328125 , 15723.50390625, 29.99996948]), + 'frame': 29242, + 'frame_number': 29242, + 'framesequence': 118280, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18609577417373657, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.3798884004354, + 'timestamp_carla': 998379, + 'timestamp_device': 2616939, + 'timestamp_stream': 998.3798884004354, + 'transform': [array([ 3.68615845e+02, 9.70968552e+01, -1.58931419e-01]), + array([-5.95592475e-03, 6.24360123e+01, 1.61743071e-02])]} +{'AngularVelocity': array([0.03632133, 0.02951638, 4.2443471 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.973594665527344, + 'FR_Wheel_Angle': -20.346147537231445, + 'Location': array([248.48675537, 128.85784912, 0.30170721]), + 'Rotation': array([-1.74852833e-02, 5.85960655e+01, -8.11767578e-03]), + 'Velocity': array([-3.47793221e-01, -3.34767640e-01, -1.99890128e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5512084960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23851.81054688, 15722.59277344, 30. ]), + 'frame': 29243, + 'frame_number': 29243, + 'framesequence': 118284, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18272653222084045, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.4135775975883, + 'timestamp_carla': 998413, + 'timestamp_device': 2616973, + 'timestamp_stream': 998.4135775975883, + 'transform': [array([ 3.68697968e+02, 9.72380524e+01, -1.57854110e-01]), + array([-6.37939619e-03, 6.25024414e+01, 1.66320708e-02])]} +{'AngularVelocity': array([0.016385 , 0.06397546, 5.02664566]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.024065017700195, + 'FR_Wheel_Angle': -23.718751907348633, + 'Location': array([248.41612244, 128.78160095, 0.30170283]), + 'Rotation': array([-1.50469057e-02, 5.94680099e+01, -8.20922945e-03]), + 'Velocity': array([-3.26738209e-01, -3.04487169e-01, -1.65510181e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484619140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23853.00390625, 15721.66308594, 30.00003052]), + 'frame': 29244, + 'frame_number': 29244, + 'framesequence': 118288, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17911924421787262, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.4483019970357, + 'timestamp_carla': 998447, + 'timestamp_device': 2617006, + 'timestamp_stream': 998.4483019970357, + 'transform': [array([ 3.68783936e+02, 9.73861084e+01, -1.56494558e-01]), + array([-6.34524552e-03, 6.25720139e+01, 1.71813872e-02])]} +{'AngularVelocity': array([0.00646494, 0.02654718, 5.29084158]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.100732803344727, + 'FR_Wheel_Angle': -23.17975425720215, + 'Location': array([248.34078979, 128.70037842, 0.30172473]), + 'Rotation': array([-1.95616614e-02, 6.04689064e+01, -9.94873140e-03]), + 'Velocity': array([-3.76340210e-01, -3.68659288e-01, 3.70407106e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54541015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23854.25390625, 15720.70214844, 30. ]), + 'frame': 29245, + 'frame_number': 29245, + 'framesequence': 118292, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17673879861831665, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.4804184995592, + 'timestamp_carla': 998480, + 'timestamp_device': 2617039, + 'timestamp_stream': 998.4804184995592, + 'transform': [array([ 3.68861633e+02, 9.75198593e+01, -1.56744763e-01]), + array([-6.04471704e-03, 6.26348534e+01, 1.70593206e-02])]} +{'AngularVelocity': array([1.03690848e-02, 2.07819836e-03, 3.59665108e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.180889129638672, + 'FR_Wheel_Angle': -23.085405349731445, + 'Location': array([248.2625885 , 128.61282349, 0.30170813]), + 'Rotation': array([-1.63924526e-02, 6.14857216e+01, -6.40869187e-03]), + 'Velocity': array([-3.44448566e-01, -3.51544976e-01, 1.40376083e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5421752929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23855.58007812, 15719.69726562, 30. ]), + 'frame': 29246, + 'frame_number': 29246, + 'framesequence': 118296, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1778191477060318, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.5129437968135, + 'timestamp_carla': 998512, + 'timestamp_device': 2617073, + 'timestamp_stream': 998.5129437968135, + 'transform': [array([ 3.68934021e+02, 9.76428680e+01, -1.58106193e-01]), + array([-6.04471704e-03, 6.26928825e+01, 1.65100060e-02])]} +{'AngularVelocity': array([-4.12826892e-03, -3.57177034e-02, 4.21190119e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.925159454345703, + 'FR_Wheel_Angle': -24.828372955322266, + 'Location': array([248.19108582, 128.5302887 , 0.30170158]), + 'Rotation': array([-1.56547930e-02, 6.24879990e+01, -6.46972656e-03]), + 'Velocity': array([-3.17539245e-01, -3.31559569e-01, -6.15882891e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5458984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23856.79296875, 15718.78515625, 30. ]), + 'frame': 29247, + 'frame_number': 29247, + 'framesequence': 118300, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17983338236808777, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.5478920973837, + 'timestamp_carla': 998547, + 'timestamp_device': 2617106, + 'timestamp_stream': 998.5478920973837, + 'transform': [array([ 3.69017731e+02, 9.77887497e+01, -1.59196958e-01]), + array([-6.13350933e-03, 6.27612534e+01, 1.60827581e-02])]} +{'AngularVelocity': array([0.02236598, 0.06455405, 5.40258646]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.99913024902344, + 'FR_Wheel_Angle': -25.39535140991211, + 'Location': array([248.12043762, 128.45069885, 0.30171502]), + 'Rotation': array([-1.78882647e-02, 6.35925293e+01, -9.58251953e-03]), + 'Velocity': array([-3.55098635e-01, -3.48992229e-01, 9.31453687e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5479736328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23857.9921875 , 15717.88671875, 30.00003052]), + 'frame': 29248, + 'frame_number': 29248, + 'framesequence': 118304, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1813715100288391, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.5806405991316, + 'timestamp_carla': 998580, + 'timestamp_device': 2617139, + 'timestamp_stream': 998.5806405991316, + 'transform': [array([ 3.69094238e+02, 9.79219284e+01, -1.59672320e-01]), + array([-6.34524552e-03, 6.28237076e+01, 1.58996526e-02])]} +{'AngularVelocity': array([0.03199589, 0.03562309, 5.27078438]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.24222183227539, + 'FR_Wheel_Angle': -25.65528106689453, + 'Location': array([248.04821777, 128.36711121, 0.30170515]), + 'Rotation': array([-1.67544540e-02, 6.47412262e+01, -7.32421922e-03]), + 'Velocity': array([-3.33239406e-01, -3.37133944e-01, -9.03415639e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5455932617188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23859.2734375 , 15716.91699219, 29.99996948]), + 'frame': 29249, + 'frame_number': 29249, + 'framesequence': 118308, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1807672381401062, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.6150298975408, + 'timestamp_carla': 998614, + 'timestamp_device': 2617173, + 'timestamp_stream': 998.6150298975408, + 'transform': [array([ 3.69169342e+02, 9.80510559e+01, -1.60375282e-01]), + array([-6.44086814e-03, 6.28844681e+01, 1.56249925e-02])]} +{'AngularVelocity': array([ 0.01565937, -0.01099803, 4.74347639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.329917907714844, + 'FR_Wheel_Angle': -25.81243324279785, + 'Location': array([247.9778595 , 128.28160095, 0.30169678]), + 'Rotation': array([-1.60509441e-02, 6.58830185e+01, -5.12695359e-03]), + 'Velocity': array([-3.07596385e-01, -3.38296086e-01, -2.30045320e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5469360351562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23860.4609375 , 15716.015625 , 30.00003052]), + 'frame': 29250, + 'frame_number': 29250, + 'framesequence': 118312, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17948545515537262, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.6469611003995, + 'timestamp_carla': 998646, + 'timestamp_device': 2617206, + 'timestamp_stream': 998.6469611003995, + 'transform': [array([ 3.69237427e+02, 9.81682281e+01, -1.61388278e-01]), + array([-6.16766047e-03, 6.29395905e+01, 1.51977474e-02])]} +{'AngularVelocity': array([0.04525943, 0.0655087 , 6.193645 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.489349365234375, + 'FR_Wheel_Angle': -28.792705535888672, + 'Location': array([247.90837097, 128.19639587, 0.30169913]), + 'Rotation': array([-1.65085662e-02, 6.71102829e+01, -9.70458891e-03]), + 'Velocity': array([-3.40081871e-01, -3.37260693e-01, -1.56259528e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5458984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23861.69726562, 15715.08496094, 30. ]), + 'frame': 29251, + 'frame_number': 29251, + 'framesequence': 118316, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17935729026794434, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.6800666972995, + 'timestamp_carla': 998679, + 'timestamp_device': 2617239, + 'timestamp_stream': 998.6800666972995, + 'transform': [array([ 3.69311737e+02, 9.82988281e+01, -1.62183374e-01]), + array([-5.86030213e-03, 6.30006447e+01, 1.48620559e-02])]} +{'AngularVelocity': array([0.03747059, 0.06019593, 5.69874382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.607215881347656, + 'FR_Wheel_Angle': -28.429672241210938, + 'Location': array([247.84983826, 128.12498474, 0.3017031 ]), + 'Rotation': array([-1.62080377e-02, 6.82034683e+01, -6.65283296e-03]), + 'Velocity': array([-3.21497023e-01, -3.36767584e-01, 9.66072039e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5501708984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23862.82226562, 15714.24316406, 30. ]), + 'frame': 29252, + 'frame_number': 29252, + 'framesequence': 118320, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18008972704410553, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.7130124978721, + 'timestamp_carla': 998712, + 'timestamp_device': 2617273, + 'timestamp_stream': 998.7130124978721, + 'transform': [array([ 3.69382874e+02, 9.84235840e+01, -1.62714228e-01]), + array([-5.86030213e-03, 6.30590286e+01, 1.46484338e-02])]} +{'AngularVelocity': array([0.0411378 , 0.06286115, 5.42238379]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.5485725402832, + 'FR_Wheel_Angle': -28.31298828125, + 'Location': array([247.78631592, 128.04393005, 0.30170596]), + 'Rotation': array([-1.55660007e-02, 6.94163208e+01, -5.24902344e-03]), + 'Velocity': array([-2.94527173e-01, -3.20370376e-01, 2.39830013e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5513305664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23863.97265625, 15713.38085938, 30.00003052]), + 'frame': 29253, + 'frame_number': 29253, + 'framesequence': 118324, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18045595288276672, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.7467115968466, + 'timestamp_carla': 998746, + 'timestamp_device': 2617306, + 'timestamp_stream': 998.7467115968466, + 'transform': [array([ 3.69455383e+02, 9.85499878e+01, -1.61409453e-01]), + array([-6.29060389e-03, 6.31182785e+01, 1.51977483e-02])]} +{'AngularVelocity': array([9.83401318e-04, 2.71371994e-02, 5.99480200e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.56584930419922, + 'FR_Wheel_Angle': -30.149200439453125, + 'Location': array([247.71786499, 127.95028687, 0.30171591]), + 'Rotation': array([-1.80385280e-02, 7.07195587e+01, -9.64355376e-03]), + 'Velocity': array([-3.10613990e-01, -3.63466054e-01, -8.40187022e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5523681640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23865.09960938, 15712.5390625 , 29.99993896]), + 'frame': 29254, + 'frame_number': 29254, + 'framesequence': 118328, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18005309998989105, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.781441397965, + 'timestamp_carla': 998781, + 'timestamp_device': 2617339, + 'timestamp_stream': 998.781441397965, + 'transform': [array([ 3.69531555e+02, 9.86823120e+01, -1.59287378e-01]), + array([-6.80969842e-03, 6.31803932e+01, 1.60827562e-02])]} +{'AngularVelocity': array([5.14135789e-03, 7.61496127e-02, 5.56892776e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.264686584472656, + 'FR_Wheel_Angle': -30.707496643066406, + 'Location': array([247.65570068, 127.86737061, 0.30170429]), + 'Rotation': array([-1.65427178e-02, 7.20563354e+01, -7.59887835e-03]), + 'Velocity': array([-3.03640008e-01, -3.50178838e-01, -1.24073020e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5490112304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23866.2890625 , 15711.65527344, 30. ]), + 'frame': 29255, + 'frame_number': 29255, + 'framesequence': 118332, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17911924421787262, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.8146702982485, + 'timestamp_carla': 998814, + 'timestamp_device': 2617373, + 'timestamp_stream': 998.8146702982485, + 'transform': [array([ 3.69608856e+02, 9.88195496e+01, -1.58450618e-01]), + array([-6.83701877e-03, 6.32444115e+01, 1.64184496e-02])]} +{'AngularVelocity': array([-4.03291965e-03, -6.12273738e-02, 6.69685888e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.673179626464844, + 'FR_Wheel_Angle': -30.79416847229004, + 'Location': array([247.59532166, 127.78261566, 0.30170795]), + 'Rotation': array([-1.74852833e-02, 7.33706055e+01, -7.99560454e-03]), + 'Velocity': array([-2.89327234e-01, -3.59700203e-01, -6.43730164e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5433959960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23867.56835938, 15710.70605469, 30. ]), + 'frame': 29256, + 'frame_number': 29256, + 'framesequence': 118336, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17276528477668762, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.84875619784, + 'timestamp_carla': 998848, + 'timestamp_device': 2617406, + 'timestamp_stream': 998.84875619784, + 'transform': [array([ 3.69677948e+02, 9.89384537e+01, -1.59448385e-01]), + array([-6.31109439e-03, 6.33003464e+01, 1.59912053e-02])]} +{'AngularVelocity': array([-0.01936488, 0.01386011, 6.71749258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68311309814453, + 'FR_Wheel_Angle': -30.799644470214844, + 'Location': array([247.53811646, 127.69934082, 0.30170581]), + 'Rotation': array([-1.64539255e-02, 7.46819534e+01, -6.31713914e-03]), + 'Velocity': array([-2.77564257e-01, -3.61947358e-01, 7.31945038e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5438232421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23868.78125 , 15709.80273438, 30.00003052]), + 'frame': 29257, + 'frame_number': 29257, + 'framesequence': 118340, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16014893352985382, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.8807467967272, + 'timestamp_carla': 998880, + 'timestamp_device': 2617439, + 'timestamp_stream': 998.8807467967272, + 'transform': [array([ 3.69744049e+02, 9.90529556e+01, -1.59366757e-01]), + array([-5.79883019e-03, 6.33540573e+01, 1.59912035e-02])]} +{'AngularVelocity': array([0.0411365 , 0.06974659, 6.68300867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66287612915039, + 'FR_Wheel_Angle': -30.783035278320312, + 'Location': array([247.4798584 , 127.61031342, 0.30171341]), + 'Rotation': array([-1.82161126e-02, 7.60630875e+01, -8.81958008e-03]), + 'Velocity': array([-2.99131572e-01, -3.77740860e-01, -1.15232462e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452270507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23870.00585938, 15708.91308594, 30.00006104]), + 'frame': 29258, + 'frame_number': 29258, + 'framesequence': 118344, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1469649374485016, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.913444198668, + 'timestamp_carla': 998912, + 'timestamp_device': 2617473, + 'timestamp_stream': 998.913444198668, + 'transform': [array([ 3.69805115e+02, 9.91564026e+01, -1.60266370e-01]), + array([-5.1567927e-03, 6.3402832e+01, 1.5594475e-02])]} +{'AngularVelocity': array([ 1.23382062e-02, -4.04825434e-03, 6.25760603e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.669883728027344, + 'FR_Wheel_Angle': -30.79410171508789, + 'Location': array([247.42126465, 127.51634216, 0.30170473]), + 'Rotation': array([-1.67544540e-02, 7.75147629e+01, -5.70678571e-03]), + 'Velocity': array([-2.73379236e-01, -3.85084420e-01, -8.67080671e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5491333007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23871.16796875, 15708.08105469, 30. ]), + 'frame': 29259, + 'frame_number': 29259, + 'framesequence': 118348, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13301187753677368, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.9464272968471, + 'timestamp_carla': 998945, + 'timestamp_device': 2617506, + 'timestamp_stream': 998.9464272968471, + 'transform': [array([ 3.69863068e+02, 9.92528381e+01, -1.60598710e-01]), + array([-4.79479274e-03, 6.34484978e+01, 1.54418899e-02])]} +{'AngularVelocity': array([-0.02203771, 0.02980032, 6.34136534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6544303894043, + 'FR_Wheel_Angle': -30.77560043334961, + 'Location': array([247.36380005, 127.41706085, 0.30171263]), + 'Rotation': array([-1.79770570e-02, 7.90042648e+01, -7.08007859e-03]), + 'Velocity': array([-2.89098918e-01, -4.43745762e-01, -1.64403915e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5521850585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23872.33789062, 15707.26660156, 30. ]), + 'frame': 29260, + 'frame_number': 29260, + 'framesequence': 118352, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11755730211734772, + 'throttle_input': 0.22618448734283447, + 'timestamp': 998.9819088988006, + 'timestamp_carla': 998981, + 'timestamp_device': 2617539, + 'timestamp_stream': 998.9819088988006, + 'transform': [array([ 3.69916626e+02, 9.93366776e+01, -1.60750732e-01]), + array([-4.06396249e-03, 6.34887962e+01, 1.53503390e-02])]} +{'AngularVelocity': array([-0.02014254, 0.01844552, 6.21500397]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.650455474853516, + 'FR_Wheel_Angle': -30.775819778442383, + 'Location': array([247.31538391, 127.32865906, 0.30170649]), + 'Rotation': array([-1.72735471e-02, 8.03311920e+01, -6.13403413e-03]), + 'Velocity': array([-2.78469324e-01, -4.49315965e-01, -9.29641683e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.552978515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23873.51953125, 15706.46484375, 30. ]), + 'frame': 29261, + 'frame_number': 29261, + 'framesequence': 118356, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10545366257429123, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.0129391998053, + 'timestamp_carla': 999012, + 'timestamp_device': 2617573, + 'timestamp_stream': 999.0129391998053, + 'transform': [array([ 3.69963013e+02, 9.94095230e+01, -1.60857305e-01]), + array([-3.87954712e-03, 6.35237541e+01, 1.52893029e-02])]} +{'AngularVelocity': array([-0.01594839, 0.02921059, 6.31203461]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66970443725586, + 'FR_Wheel_Angle': -30.785539627075195, + 'Location': array([247.25720215, 127.21652222, 0.30169964]), + 'Rotation': array([-1.53201139e-02, 8.20018692e+01, -4.11987305e-03]), + 'Velocity': array([-2.43238628e-01, -4.10984308e-01, -3.64589687e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23874.81054688, 15705.62402344, 29.99996948]), + 'frame': 29262, + 'frame_number': 29262, + 'framesequence': 118360, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10517899692058563, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.0472605004907, + 'timestamp_carla': 999046, + 'timestamp_device': 2617606, + 'timestamp_stream': 999.0472605004907, + 'transform': [array([ 3.70009766e+02, 9.94797897e+01, -1.60668865e-01]), + array([-4.08445299e-03, 6.35578728e+01, 1.53808529e-02])]} +{'AngularVelocity': array([-0.0178841 , 0.07510929, 5.83550167]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67295837402344, + 'FR_Wheel_Angle': -30.787595748901367, + 'Location': array([247.2116394 , 127.12217712, 0.3017092 ]), + 'Rotation': array([-1.63583029e-02, 8.33599167e+01, -5.40161133e-03]), + 'Velocity': array([-2.33991027e-01, -4.16428417e-01, 1.32684698e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.555419921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23875.92773438, 15704.90625 , 30.00003052]), + 'frame': 29263, + 'frame_number': 29263, + 'framesequence': 118364, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11191748082637787, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.0808302983642, + 'timestamp_carla': 999080, + 'timestamp_device': 2617639, + 'timestamp_stream': 999.0808302983642, + 'transform': [array([ 3.70059875e+02, 9.95584030e+01, -1.60257608e-01]), + array([-4.42596246e-03, 6.35955811e+01, 1.55639611e-02])]} +{'AngularVelocity': array([ 3.68413678e-03, -4.92356569e-02, 7.01599169e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66048049926758, + 'FR_Wheel_Angle': -30.789518356323242, + 'Location': array([247.16595459, 127.02149963, 0.30170971]), + 'Rotation': array([-1.70003399e-02, 8.48042679e+01, -6.34765672e-03]), + 'Velocity': array([-2.21271068e-01, -4.25673008e-01, -1.74827568e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5526123046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23877.17578125, 15704.11523438, 30.00003052]), + 'frame': 29264, + 'frame_number': 29264, + 'framesequence': 118368, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.1132906973362, + 'timestamp_carla': 999112, + 'timestamp_device': 2617673, + 'timestamp_stream': 999.1132906973362, + 'transform': [array([ 3.70113037e+02, 9.96421890e+01, -1.56794161e-01]), + array([-5.27973613e-03, 6.36357231e+01, 1.69982836e-02])]} +{'AngularVelocity': array([-1.77535065e-03, -3.53396051e-02, 6.85724640e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67967224121094, + 'FR_Wheel_Angle': -30.795696258544922, + 'Location': array([247.13018799, 126.93754578, 0.30170903]), + 'Rotation': array([-1.66041888e-02, 8.59858551e+01, -5.76782180e-03]), + 'Velocity': array([-2.07768172e-01, -4.22633708e-01, -6.10351549e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.551513671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23878.40234375, 15703.33984375, 29.99996948]), + 'frame': 29265, + 'frame_number': 29265, + 'framesequence': 118372, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12641988694667816, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.1467273980379, + 'timestamp_carla': 999146, + 'timestamp_device': 2617706, + 'timestamp_stream': 999.1467273980379, + 'transform': [array([ 3.70169769e+02, 9.97338715e+01, -1.56349331e-01]), + array([-5.92177361e-03, 6.36794090e+01, 1.72119047e-02])]} +{'AngularVelocity': array([1.85021508, 1.8707689 , 4.36429596]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68415451049805, + 'FR_Wheel_Angle': -30.801143646240234, + 'Location': array([247.09196472, 126.84242249, 0.29528385]), + 'Rotation': array([ 0.23787498, 87.32840729, -0.42074588]), + 'Velocity': array([-0.15458012, -0.41566738, -0.04554216]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23879.6953125 , 15702.51855469, 30. ]), + 'frame': 29266, + 'frame_number': 29266, + 'framesequence': 118376, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12693259119987488, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.1802808977664, + 'timestamp_carla': 999179, + 'timestamp_device': 2617739, + 'timestamp_stream': 999.1802808977664, + 'transform': [array([ 3.70227295e+02, 9.98273392e+01, -1.56272501e-01]), + array([-6.46818895e-03, 6.37238922e+01, 1.72729436e-02])]} +{'AngularVelocity': array([ 0.45598656, -0.50919664, 6.3742466 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68944549560547, + 'FR_Wheel_Angle': -30.805316925048828, + 'Location': array([247.05841064, 126.75157928, 0.28526336]), + 'Rotation': array([5.68865955e-01, 8.85874710e+01, 7.15964474e-03]), + 'Velocity': array([-0.183577 , -0.40356761, -0.01953585]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5457763671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23881.00195312, 15701.67382812, 30. ]), + 'frame': 29267, + 'frame_number': 29267, + 'framesequence': 118380, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12381970137357712, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.2126583978534, + 'timestamp_carla': 999212, + 'timestamp_device': 2617773, + 'timestamp_stream': 999.2126583978534, + 'transform': [array([ 3.70281952e+02, 9.99168320e+01, -1.57400236e-01]), + array([-6.44086814e-03, 6.37663841e+01, 1.68151762e-02])]} +{'AngularVelocity': array([-0.10940008, 0.10471739, 6.07201242]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6999626159668, + 'FR_Wheel_Angle': -30.788232803344727, + 'Location': array([247.02487183, 126.65646362, 0.28536624]), + 'Rotation': array([5.52275419e-01, 8.98977737e+01, 4.72078705e-03]), + 'Velocity': array([-0.17042688, -0.40101904, 0.00396726]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5435791015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23882.3046875 , 15700.82128906, 30. ]), + 'frame': 29268, + 'frame_number': 29268, + 'framesequence': 118384, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11980956792831421, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.2470241971314, + 'timestamp_carla': 999246, + 'timestamp_device': 2617806, + 'timestamp_stream': 999.2470241971314, + 'transform': [array([ 3.70336212e+02, 1.00003311e+02, -1.58170432e-01]), + array([-6.44086814e-03, 6.38077469e+01, 1.65100042e-02])]} +{'AngularVelocity': array([-0.03476569, -0.10945161, 5.51655245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68303680419922, + 'FR_Wheel_Angle': -30.786113739013672, + 'Location': array([246.99179077, 126.55406189, 0.28603664]), + 'Rotation': array([ 5.36606967e-01, 9.12991104e+01, -3.44848959e-03]), + 'Velocity': array([-0.15970077, -0.43825784, 0.00111533]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5462036132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23883.53515625, 15700.02246094, 30. ]), + 'frame': 29269, + 'frame_number': 29269, + 'framesequence': 118388, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11673329770565033, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.2805118001997, + 'timestamp_carla': 999279, + 'timestamp_device': 2617839, + 'timestamp_stream': 999.2805118001997, + 'transform': [array([ 3.70389221e+02, 1.00089340e+02, -1.59727782e-01]), + array([-6.16766047e-03, 6.38486748e+01, 1.58691313e-02])]} +{'AngularVelocity': array([ 2.06672912e-03, -8.61639380e-02, 5.05796289e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66716766357422, + 'FR_Wheel_Angle': -30.776514053344727, + 'Location': array([246.96089172, 126.45066071, 0.28618285]), + 'Rotation': array([ 5.33068895e-01, 9.27101059e+01, -4.76076733e-03]), + 'Velocity': array([-1.53394699e-01, -4.43140239e-01, 9.90009285e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5445556640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23884.84375 , 15699.18066406, 29.99996948]), + 'frame': 29270, + 'frame_number': 29270, + 'framesequence': 118392, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.117319256067276, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.313840597868, + 'timestamp_carla': 999313, + 'timestamp_device': 2617873, + 'timestamp_stream': 999.313840597868, + 'transform': [array([ 3.70443512e+02, 1.00178818e+02, -1.60484999e-01]), + array([-6.16766047e-03, 6.38910599e+01, 1.55639593e-02])]} +{'AngularVelocity': array([ 8.98168131e-04, -1.53304555e-03, 6.05889177e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66317367553711, + 'FR_Wheel_Angle': -30.788076400756836, + 'Location': array([246.93209839, 126.34410095, 0.28621703]), + 'Rotation': array([ 5.31935096e-01, 9.41405640e+01, -5.85938059e-03]), + 'Velocity': array([-1.57407120e-01, -4.70721573e-01, 3.16333753e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23886.08203125, 15698.38769531, 29.99996948]), + 'frame': 29271, + 'frame_number': 29271, + 'framesequence': 118396, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11924192309379578, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.3473601974547, + 'timestamp_carla': 999346, + 'timestamp_device': 2617906, + 'timestamp_stream': 999.3473601974547, + 'transform': [array([ 3.70491547e+02, 1.00254425e+02, -1.61344528e-01]), + array([-6.34524552e-03, 6.39273376e+01, 1.52282659e-02])]} +{'AngularVelocity': array([ 0.01374556, -0.04643226, 5.51723862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68659973144531, + 'FR_Wheel_Angle': -30.802268981933594, + 'Location': array([246.90653992, 126.23976898, 0.28619492]), + 'Rotation': array([ 5.33697307e-01, 9.55431290e+01, -3.87573987e-03]), + 'Velocity': array([-0.12833606, -0.43275201, -0.00046696]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5479736328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23887.30664062, 15697.60253906, 29.99996948]), + 'frame': 29272, + 'frame_number': 29272, + 'framesequence': 118400, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12114628404378891, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.3793164975941, + 'timestamp_carla': 999378, + 'timestamp_device': 2617939, + 'timestamp_stream': 999.3793164975941, + 'transform': [array([ 3.70541931e+02, 1.00337502e+02, -1.61329642e-01]), + array([-6.31109439e-03, 6.39666862e+01, 1.52282640e-02])]} +{'AngularVelocity': array([0.02264765, 0.0864461 , 6.44810724]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66712188720703, + 'FR_Wheel_Angle': -30.78801918029785, + 'Location': array([246.884552 , 126.13803101, 0.2862277 ]), + 'Rotation': array([ 5.31525314e-01, 9.69091339e+01, -7.65993260e-03]), + 'Velocity': array([-1.39147833e-01, -4.50485289e-01, 2.12016108e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5481567382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23888.51171875, 15696.83398438, 30. ]), + 'frame': 29273, + 'frame_number': 29273, + 'framesequence': 118404, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12131107598543167, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.4134837985039, + 'timestamp_carla': 999412, + 'timestamp_device': 2617973, + 'timestamp_stream': 999.4134837985039, + 'transform': [array([ 3.70591400e+02, 1.00415932e+02, -1.61339790e-01]), + array([-6.31109439e-03, 6.40042267e+01, 1.52282631e-02])]} +{'AngularVelocity': array([0.02383761, 0.08131429, 6.25927067]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67839050292969, + 'FR_Wheel_Angle': -30.79656219482422, + 'Location': array([246.86357117, 126.03340912, 0.28620929]), + 'Rotation': array([ 5.33615351e-01, 9.83113174e+01, -5.40163275e-03]), + 'Velocity': array([-1.27149209e-01, -4.37715292e-01, -5.55515289e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5502319335938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23889.66210938, 15696.09960938, 30. ]), + 'frame': 29274, + 'frame_number': 29274, + 'framesequence': 118408, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12021241337060928, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.4465254992247, + 'timestamp_carla': 999446, + 'timestamp_device': 2618006, + 'timestamp_stream': 999.4465254992247, + 'transform': [array([ 3.70638885e+02, 1.00491638e+02, -1.61293253e-01]), + array([-6.56381156e-03, 6.40404358e+01, 1.52587853e-02])]} +{'AngularVelocity': array([0.0189164 , 0.10409152, 6.76861334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66267013549805, + 'FR_Wheel_Angle': -30.785255432128906, + 'Location': array([246.84327698, 125.91390991, 0.28621525]), + 'Rotation': array([ 5.31620920e-01, 9.98818207e+01, -6.62234006e-03]), + 'Velocity': array([-1.22602992e-01, -4.67514664e-01, 9.33647152e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5482177734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23890.8984375 , 15695.31640625, 30.00003052]), + 'frame': 29275, + 'frame_number': 29275, + 'framesequence': 118412, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11922361701726913, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.4796781986952, + 'timestamp_carla': 999479, + 'timestamp_device': 2618039, + 'timestamp_stream': 999.4796781986952, + 'transform': [array([ 3.70691132e+02, 1.00575935e+02, -1.58515662e-01]), + array([-6.80969842e-03, 6.40805893e+01, 1.63879320e-02])]} +{'AngularVelocity': array([ 0.01371373, -0.00817889, 6.0124445 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66051483154297, + 'FR_Wheel_Angle': -30.78751564025879, + 'Location': array([246.82980347, 125.82084656, 0.28621283]), + 'Rotation': array([ 5.33150852e-01, 1.01110565e+02, -4.85225907e-03]), + 'Velocity': array([-9.59982947e-02, -4.62078303e-01, 7.88784018e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.548095703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23892.078125 , 15694.56542969, 30.00003052]), + 'frame': 29276, + 'frame_number': 29276, + 'framesequence': 118416, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11958983540534973, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.5133932977915, + 'timestamp_carla': 999512, + 'timestamp_device': 2618073, + 'timestamp_stream': 999.5133932977915, + 'transform': [array([ 3.70760864e+02, 1.00699089e+02, -1.54668227e-01]), + array([-7.54052866e-03, 6.41379395e+01, 1.79748423e-02])]} +{'AngularVelocity': array([-0.01998252, -0.03909483, 5.21532345]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.6099853515625, + 'FR_Wheel_Angle': -24.58917236328125, + 'Location': array([246.81845093, 125.7127533 , 0.28623283]), + 'Rotation': array([ 5.32898188e-01, 1.02476227e+02, -1.89207087e-03]), + 'Velocity': array([-5.36685400e-02, -4.78505939e-01, 2.32501028e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5454711914062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23893.34765625, 15693.76171875, 29.99996948]), + 'frame': 29277, + 'frame_number': 29277, + 'framesequence': 118420, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12030397355556488, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.5462290979922, + 'timestamp_carla': 999545, + 'timestamp_device': 2618106, + 'timestamp_stream': 999.5462290979922, + 'transform': [array([ 3.70820374e+02, 1.00792885e+02, -1.47823870e-01]), + array([-8.05962272e-03, 6.41828995e+01, 2.07519419e-02])]} +{'AngularVelocity': array([6.15082495e-03, 1.04790041e-03, 2.97607207e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.35518455505371, + 'FR_Wheel_Angle': -14.881572723388672, + 'Location': array([246.820755 , 125.58141327, 0.28621399]), + 'Rotation': array([5.30459762e-01, 1.03575630e+02, 1.66098098e-03]), + 'Velocity': array([ 2.26788539e-02, -5.20509601e-01, 3.03497305e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.539794921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23894.6953125 , 15692.88476562, 29.99996948]), + 'frame': 29278, + 'frame_number': 29278, + 'framesequence': 118424, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12030397355556488, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.580453298986, + 'timestamp_carla': 999579, + 'timestamp_device': 2618139, + 'timestamp_stream': 999.580453298986, + 'transform': [array([ 3.70884216e+02, 1.00897018e+02, -1.47616237e-01]), + array([-8.14841501e-03, 6.42323914e+01, 2.08434947e-02])]} +{'AngularVelocity': array([1.23951246e-03, 1.13994563e-02, 1.28161943e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.203983306884766, + 'FR_Wheel_Angle': -3.138777494430542, + 'Location': array([246.83363342, 125.4863739 , 0.28621623]), + 'Rotation': array([5.33758759e-01, 1.03972824e+02, 4.15595016e-03]), + 'Velocity': array([ 7.86443055e-02, -4.62849140e-01, 6.82830796e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5335083007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23896.23828125, 15691.91894531, 30. ]), + 'frame': 29279, + 'frame_number': 29279, + 'framesequence': 118428, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11993774026632309, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.6133098974824, + 'timestamp_carla': 999612, + 'timestamp_device': 2618173, + 'timestamp_stream': 999.6133098974824, + 'transform': [array([ 3.70943573e+02, 1.00993767e+02, -1.49771452e-01]), + array([-7.84105714e-03, 6.42783737e+01, 1.99584812e-02])]} +{'AngularVelocity': array([-0.00651386, 0.03920444, -0.08452335]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.08893326669931412, + 'FR_Wheel_Angle': -0.03178183734416962, + 'Location': array([246.85778809, 125.38317108, 0.28621262]), + 'Rotation': array([5.33321619e-01, 1.04018547e+02, 4.99532558e-04]), + 'Velocity': array([ 1.11819081e-01, -4.40809816e-01, -3.45134722e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5315551757812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23897.78125 , 15690.93945312, 30. ]), + 'frame': 29280, + 'frame_number': 29280, + 'framesequence': 118432, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1159825474023819, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.6467918977141, + 'timestamp_carla': 999646, + 'timestamp_device': 2618206, + 'timestamp_stream': 999.6467918977141, + 'transform': [array([ 3.71002441e+02, 1.01090027e+02, -1.52669176e-01]), + array([-7.35611329e-03, 6.43240814e+01, 1.87683012e-02])]} +{'AngularVelocity': array([-0.00470953, 0.00938294, 0.18822348]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00381483300589025, + 'FR_Wheel_Angle': 0.003815640229731798, + 'Location': array([246.88267517, 125.28331757, 0.28620049]), + 'Rotation': array([ 5.33130407e-01, 1.04023415e+02, -5.27953729e-03]), + 'Velocity': array([ 1.07766971e-01, -4.28180724e-01, -8.29219789e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5353393554688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23899.22265625, 15690.02734375, 29.99996948]), + 'frame': 29281, + 'frame_number': 29281, + 'framesequence': 118436, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10592975467443466, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.6799300983548, + 'timestamp_carla': 999679, + 'timestamp_device': 2618239, + 'timestamp_stream': 999.6799300983548, + 'transform': [array([ 3.71055420e+02, 1.01173836e+02, -1.55683517e-01]), + array([-6.62528304e-03, 6.43641815e+01, 1.75170787e-02])]} +{'AngularVelocity': array([-0.00576373, 0.05367316, 1.23534322]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003813931718468666, + 'FR_Wheel_Angle': 0.0038152041379362345, + 'Location': array([246.91026306, 125.17175293, 0.28622809]), + 'Rotation': array([ 5.32126367e-01, 1.04020416e+02, -7.20215822e-03]), + 'Velocity': array([ 1.06836945e-01, -4.32186544e-01, 9.49048990e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5386352539062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23900.65625 , 15689.12695312, 29.99996948]), + 'frame': 29282, + 'frame_number': 29282, + 'framesequence': 118440, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09355144202709198, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.7136300988495, + 'timestamp_carla': 999713, + 'timestamp_device': 2618273, + 'timestamp_stream': 999.7136300988495, + 'transform': [array([ 3.71104889e+02, 1.01249390e+02, -1.57943606e-01]), + array([-5.89445280e-03, 6.44006348e+01, 1.65710412e-02])]} +{'AngularVelocity': array([-0.01448206, 0.04385009, 1.25644732]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038130758330225945, + 'FR_Wheel_Angle': 0.003813328919932246, + 'Location': array([246.93185425, 125.08473969, 0.28621238]), + 'Rotation': array([ 5.31955600e-01, 1.04015808e+02, -7.20215729e-03]), + 'Velocity': array([ 1.10724226e-01, -4.44378227e-01, -1.97429647e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5432739257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23902.04492188, 15688.26855469, 30. ]), + 'frame': 29283, + 'frame_number': 29283, + 'framesequence': 118444, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07866451144218445, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.7466164976358, + 'timestamp_carla': 999746, + 'timestamp_device': 2618306, + 'timestamp_stream': 999.7466164976358, + 'transform': [array([ 3.71146545e+02, 1.01308357e+02, -1.59521908e-01]), + array([-5.21826418e-03, 6.44296417e+01, 1.58996545e-02])]} +{'AngularVelocity': array([ 0.02369344, -0.04304949, -1.18082416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038097533397376537, + 'FR_Wheel_Angle': 0.0038112010806798935, + 'Location': array([246.95985413, 124.97084808, 0.28623185]), + 'Rotation': array([ 5.29886067e-01, 1.04005806e+02, -7.17163133e-03]), + 'Velocity': array([ 1.21683255e-01, -4.90174085e-01, 8.16345164e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54638671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23903.44335938, 15687.42480469, 30. ]), + 'frame': 29284, + 'frame_number': 29284, + 'framesequence': 118448, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06286203116178513, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.7790833003819, + 'timestamp_carla': 999778, + 'timestamp_device': 2618339, + 'timestamp_stream': 999.7790833003819, + 'transform': [array([ 3.71185699e+02, 1.01362442e+02, -1.60710633e-01]), + array([-4.48743394e-03, 6.44563599e+01, 1.53808510e-02])]} +{'AngularVelocity': array([ 0.0185912 , -0.04161675, -1.17141008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003813098883256316, + 'FR_Wheel_Angle': 0.003813538234680891, + 'Location': array([246.98648071, 124.86325073, 0.28620613]), + 'Rotation': array([ 5.34195900e-01, 1.04001221e+02, -6.95799664e-03]), + 'Velocity': array([ 1.08044401e-01, -4.34710771e-01, -1.48105619e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5499267578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23904.79882812, 15686.63378906, 30. ]), + 'frame': 29285, + 'frame_number': 29285, + 'framesequence': 118452, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.049549851566553116, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.8125796988606, + 'timestamp_carla': 999812, + 'timestamp_device': 2618373, + 'timestamp_stream': 999.8125796988606, + 'transform': [array([ 3.71216949e+02, 1.01396255e+02, -1.61545902e-01]), + array([-3.87954712e-03, 6.44743042e+01, 1.50146447e-02])]} +{'AngularVelocity': array([ 0.00592607, -0.0440654 , -1.23415077]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038134311325848103, + 'FR_Wheel_Angle': 0.003813508665189147, + 'Location': array([247.01176453, 124.76178741, 0.28621939]), + 'Rotation': array([ 5.33294320e-01, 1.03994698e+02, -6.43919921e-03]), + 'Velocity': array([ 1.08705841e-01, -4.38218027e-01, 1.95417393e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.553955078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23906.125 , 15685.87792969, 29.99996948]), + 'frame': 29286, + 'frame_number': 29286, + 'framesequence': 118456, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04423963278532028, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.8461653999984, + 'timestamp_carla': 999845, + 'timestamp_device': 2618406, + 'timestamp_stream': 999.8461653999984, + 'transform': [array([ 3.71245575e+02, 1.01424606e+02, -1.62128553e-01]), + array([-3.66098108e-03, 6.44897842e+01, 1.47705050e-02])]} +{'AngularVelocity': array([-0.00373021, 0.00380083, 0.02510872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812195034697652, + 'FR_Wheel_Angle': 0.0038101363461464643, + 'Location': array([247.03778076, 124.6577301 , 0.28622806]), + 'Rotation': array([ 5.31525314e-01, 1.04001633e+02, -7.32419873e-03]), + 'Velocity': array([ 1.14161707e-01, -4.57679093e-01, 1.01881022e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5547485351562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23907.50585938, 15685.125 , 30. ]), + 'frame': 29287, + 'frame_number': 29287, + 'framesequence': 118460, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.048799097537994385, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.8797819986939, + 'timestamp_carla': 999879, + 'timestamp_device': 2618439, + 'timestamp_stream': 999.8797819986939, + 'transform': [array([ 3.71276245e+02, 1.01458916e+02, -1.63281202e-01]), + array([-3.75660392e-03, 6.45077286e+01, 1.43127404e-02])]} +{'AngularVelocity': array([-0.00259613, 0.01695123, 0.40032402]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038135198410600424, + 'FR_Wheel_Angle': 0.0038135999348014593, + 'Location': array([247.06118774, 124.56349945, 0.28621215]), + 'Rotation': array([ 5.32433689e-01, 1.04006729e+02, -7.35475030e-03]), + 'Velocity': array([ 1.15675434e-01, -4.66776937e-01, -1.77602764e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5552978515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23908.86914062, 15684.39355469, 30. ]), + 'frame': 29288, + 'frame_number': 29288, + 'framesequence': 118464, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05661793798208237, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.9128840975463, + 'timestamp_carla': 999912, + 'timestamp_device': 2618472, + 'timestamp_stream': 999.9128840975463, + 'transform': [array([ 3.71308533e+02, 1.01497528e+02, -1.63155138e-01]), + array([-4.54890588e-03, 6.45275650e+01, 1.44042931e-02])]} +{'AngularVelocity': array([-0.09689422, -0.03452304, -0.63402063]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003811440896242857, + 'FR_Wheel_Angle': 0.003810185706242919, + 'Location': array([247.0901947 , 124.44625092, 0.28622726]), + 'Rotation': array([ 5.31101823e-01, 1.04001656e+02, -6.74438057e-03]), + 'Velocity': array([ 1.26365617e-01, -5.15799701e-01, -1.03492734e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5556640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23910.20117188, 15683.68164062, 30.00003052]), + 'frame': 29289, + 'frame_number': 29289, + 'framesequence': 118468, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06441847234964371, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.9462129995227, + 'timestamp_carla': 999945, + 'timestamp_device': 2618506, + 'timestamp_stream': 999.9462129995227, + 'transform': [array([ 3.71343628e+02, 1.01543434e+02, -1.63183436e-01]), + array([-5.34120761e-03, 6.45505676e+01, 1.44348089e-02])]} +{'AngularVelocity': array([ 0.00850362, -0.03853904, -0.87157553]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812857437878847, + 'FR_Wheel_Angle': 0.0038145591970533133, + 'Location': array([247.11360168, 124.35158539, 0.28620812]), + 'Rotation': array([ 5.33219159e-01, 1.04002625e+02, -6.71385974e-03]), + 'Velocity': array([ 1.15343727e-01, -4.61355895e-01, -2.08415979e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55419921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23911.515625 , 15682.96582031, 30. ]), + 'frame': 29290, + 'frame_number': 29290, + 'framesequence': 118472, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0676412284374237, + 'throttle_input': 0.22618448734283447, + 'timestamp': 999.9786790981889, + 'timestamp_carla': 999978, + 'timestamp_device': 2618539, + 'timestamp_stream': 999.9786790981889, + 'transform': [array([ 3.71376678e+02, 1.01585350e+02, -1.62730172e-01]), + array([-5.98324556e-03, 6.45717697e+01, 1.46484300e-02])]} +{'AngularVelocity': array([ 0.00803066, -0.04770311, -1.19986486]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038126897998154163, + 'FR_Wheel_Angle': 0.003812829963862896, + 'Location': array([247.13967896, 124.2466507 , 0.28621528]), + 'Rotation': array([ 5.31941950e-01, 1.04004257e+02, -7.08008930e-03]), + 'Velocity': array([ 1.15992211e-01, -4.65638876e-01, -1.02844235e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5526123046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23912.80664062, 15682.25 , 29.99993896]), + 'frame': 29291, + 'frame_number': 29291, + 'framesequence': 118476, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06559038162231445, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.0124458000064, + 'timestamp_carla': 1000011, + 'timestamp_device': 2618572, + 'timestamp_stream': 1000.0124458000064, + 'transform': [array([ 3.71413208e+02, 1.01634483e+02, -1.62988245e-01]), + array([-6.16766047e-03, 6.45961914e+01, 1.45568782e-02])]} +{'AngularVelocity': array([-0.01331619, -0.0371624 , -1.15335679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812341718003154, + 'FR_Wheel_Angle': 0.003812389215454459, + 'Location': array([247.16897583, 124.12837982, 0.28621358]), + 'Rotation': array([ 5.33068895e-01, 1.04001274e+02, -7.23265531e-03]), + 'Velocity': array([ 1.10200182e-01, -4.49261338e-01, -1.12962720e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5518188476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23914.0703125, 15681.546875 , 30. ]), + 'frame': 29292, + 'frame_number': 29292, + 'framesequence': 118480, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0617450512945652, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.0468542985618, + 'timestamp_carla': 1000046, + 'timestamp_device': 2618606, + 'timestamp_stream': 1000.0468542985618, + 'transform': [array([ 3.71447174e+02, 1.01675995e+02, -1.61502495e-01]), + array([-6.34524552e-03, 6.46174164e+01, 1.51672298e-02])]} +{'AngularVelocity': array([-1.05129015, -3.11801624, 0.04861699]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003814966417849064, + 'FR_Wheel_Angle': 0.0038139817770570517, + 'Location': array([247.19165039, 124.038414 , 0.2811273 ]), + 'Rotation': array([ 0.28212777, 104.02797699, 0.5500986 ]), + 'Velocity': array([ 0.0658003 , -0.42492676, -0.06189239]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.55029296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23915.36523438, 15680.82421875, 30. ]), + 'frame': 29293, + 'frame_number': 29293, + 'framesequence': 118484, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.057460252195596695, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.0801277980208, + 'timestamp_carla': 1000079, + 'timestamp_device': 2618639, + 'timestamp_stream': 1000.0801277980208, + 'transform': [array([ 3.71483673e+02, 1.01723961e+02, -1.59972146e-01]), + array([-6.29060389e-03, 6.46414032e+01, 1.57775842e-02])]} +{'AngularVelocity': array([0.05028632, 0.15915051, 0.14807536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003815317526459694, + 'FR_Wheel_Angle': 0.0038145750295370817, + 'Location': array([247.215271 , 123.94006348, 0.2787661 ]), + 'Rotation': array([ 0.23902246, 104.01309967, 0.58765435]), + 'Velocity': array([ 0.10604707, -0.42178121, 0.00365614]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23916.72851562, 15680.07128906, 30. ]), + 'frame': 29294, + 'frame_number': 29294, + 'framesequence': 118488, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.056636255234479904, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.1133858002722, + 'timestamp_carla': 1000112, + 'timestamp_device': 2618672, + 'timestamp_stream': 1000.1133858002722, + 'transform': [array([ 3.71518616e+02, 1.01767868e+02, -1.58502996e-01]), + array([-6.10618899e-03, 6.46636200e+01, 1.63574126e-02])]} +{'AngularVelocity': array([ 0.02611679, 0.04015388, -0.32486963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038136232178658247, + 'FR_Wheel_Angle': 0.003813753370195627, + 'Location': array([247.24128723, 123.83515167, 0.27939132]), + 'Rotation': array([ 0.25138509, 104.00680542, 0.56975698]), + 'Velocity': array([ 0.11349668, -0.45622024, 0.00173913]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54638671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23918.0625 , 15679.3359375 , 29.99996948]), + 'frame': 29295, + 'frame_number': 29295, + 'framesequence': 118492, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05817438289523125, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.1477016992867, + 'timestamp_carla': 1000147, + 'timestamp_device': 2618706, + 'timestamp_stream': 1000.1477016992867, + 'transform': [array([ 3.71559692e+02, 1.01822037e+02, -1.54521868e-01]), + array([-6.37939619e-03, 6.46906204e+01, 1.79748442e-02])]} +{'AngularVelocity': array([-0.02736965, 0.00134317, -0.12697604]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003811934497207403, + 'FR_Wheel_Angle': 0.003811658127233386, + 'Location': array([247.26681519, 123.73221588, 0.27956146]), + 'Rotation': array([ 0.25419915, 104.00367737, 0.56476682]), + 'Velocity': array([ 1.21398889e-01, -4.84744877e-01, 1.70326224e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.54638671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23919.42773438, 15678.59375 , 30. ]), + 'frame': 29296, + 'frame_number': 29296, + 'framesequence': 118496, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06033509597182274, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.1794390976429, + 'timestamp_carla': 1000178, + 'timestamp_device': 2618739, + 'timestamp_stream': 1000.1794390976429, + 'transform': [array([ 3.71599182e+02, 1.01874565e+02, -1.52737081e-01]), + array([-6.77554728e-03, 6.47167969e+01, 1.87072642e-02])]} +{'AngularVelocity': array([-1.17181635, 0.88791901, 0.76378834]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038181913550943136, + 'FR_Wheel_Angle': 0.003810345195233822, + 'Location': array([247.2938385 , 123.62389374, 0.2734524 ]), + 'Rotation': array([-2.28264909e-02, 1.04006538e+02, -3.64990197e-02]), + 'Velocity': array([ 0.12624444, -0.42210391, -0.04012764]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5411987304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23920.94726562, 15677.76953125, 29.99993896]), + 'frame': 29297, + 'frame_number': 29297, + 'framesequence': 118500, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.061561938375234604, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.2139091975987, + 'timestamp_carla': 1000213, + 'timestamp_device': 2618772, + 'timestamp_stream': 1000.2139091975987, + 'transform': [array([ 3.71639313e+02, 1.01926094e+02, -1.53447643e-01]), + array([-6.89849071e-03, 6.47427292e+01, 1.84326079e-02])]} +{'AngularVelocity': array([ 0.15133686, -0.08797648, -0.11491 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038119645323604345, + 'FR_Wheel_Angle': 0.003812733106315136, + 'Location': array([247.32167053, 123.51293945, 0.27223536]), + 'Rotation': array([-3.36864926e-02, 1.03991196e+02, -2.97851562e-02]), + 'Velocity': array([ 0.11392973, -0.46404961, 0.00382788]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5416259765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23922.38671875, 15676.97949219, 30. ]), + 'frame': 29298, + 'frame_number': 29298, + 'framesequence': 118504, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06082949414849281, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.2467385977507, + 'timestamp_carla': 1000246, + 'timestamp_device': 2618806, + 'timestamp_stream': 1000.2467385977507, + 'transform': [array([ 3.71675385e+02, 1.01970840e+02, -1.55115694e-01]), + array([-6.92581153e-03, 6.47654648e+01, 1.77612193e-02])]} +{'AngularVelocity': array([ 0.01067602, -0.03023219, -0.97042382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038118534721434116, + 'FR_Wheel_Angle': 0.0038131342735141516, + 'Location': array([247.34806824, 123.40672302, 0.2727977 ]), + 'Rotation': array([-2.12077368e-02, 1.03991867e+02, -1.37939481e-02]), + 'Velocity': array([ 0.11757572, -0.47557181, 0.00163642]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5396728515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23923.921875 , 15676.13867188, 29.99996948]), + 'frame': 29299, + 'frame_number': 29299, + 'framesequence': 118508, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05949278548359871, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.279918897897, + 'timestamp_carla': 1000279, + 'timestamp_device': 2618839, + 'timestamp_stream': 1000.279918897897, + 'transform': [array([ 3.71710846e+02, 1.02014725e+02, -1.56932861e-01]), + array([-6.89849071e-03, 6.47877808e+01, 1.70288011e-02])]} +{'AngularVelocity': array([-4.06966108e-04, -7.35794939e-03, -1.18859375e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038148555904626846, + 'FR_Wheel_Angle': 0.0038169773761183023, + 'Location': array([247.37646484, 123.29158783, 0.27293116]), + 'Rotation': array([-1.58938486e-02, 1.03989342e+02, -9.21630859e-03]), + 'Velocity': array([ 1.02780767e-01, -4.17304188e-01, 2.69584649e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.542236328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23925.34960938, 15675.35839844, 30. ]), + 'frame': 29300, + 'frame_number': 29300, + 'framesequence': 118512, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05925473943352699, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.3144312985241, + 'timestamp_carla': 1000313, + 'timestamp_device': 2618872, + 'timestamp_stream': 1000.3144312985241, + 'transform': [array([ 3.71745117e+02, 1.02054565e+02, -1.58528775e-01]), + array([-6.83701877e-03, 6.48084183e+01, 1.63879320e-02])]} +{'AngularVelocity': array([ 0.01621307, 0.00906524, -1.11769414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038125193677842617, + 'FR_Wheel_Angle': 0.0038130541797727346, + 'Location': array([247.40206909, 123.18827057, 0.27296084]), + 'Rotation': array([-1.83117352e-02, 1.03998627e+02, -8.30078125e-03]), + 'Velocity': array([ 1.11097962e-01, -4.54309314e-01, -7.95841188e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5440063476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23926.75976562, 15674.58984375, 30. ]), + 'frame': 29301, + 'frame_number': 29301, + 'framesequence': 118516, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06018860638141632, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.3458708003163, + 'timestamp_carla': 1000345, + 'timestamp_device': 2618906, + 'timestamp_stream': 1000.3458708003163, + 'transform': [array([ 3.71777649e+02, 1.02095291e+02, -1.60554036e-01]), + array([-6.77554728e-03, 6.48290634e+01, 1.55639574e-02])]} +{'AngularVelocity': array([ 1.05012581e-02, -4.07461775e-04, -9.90120471e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812643466517329, + 'FR_Wheel_Angle': 0.0038133193738758564, + 'Location': array([247.42892456, 123.07946777, 0.2729516 ]), + 'Rotation': array([-1.72120761e-02, 1.04000977e+02, -7.62939500e-03]), + 'Velocity': array([ 1.15228668e-01, -4.59470659e-01, -7.85636876e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5435791015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23928.22070312, 15673.79980469, 30.00003052]), + 'frame': 29302, + 'frame_number': 29302, + 'framesequence': 118520, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06033509597182274, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.3789695985615, + 'timestamp_carla': 1000378, + 'timestamp_device': 2618939, + 'timestamp_stream': 1000.3789695985615, + 'transform': [array([ 3.71814575e+02, 1.02144432e+02, -1.60875469e-01]), + array([-6.89849071e-03, 6.48535461e+01, 1.54418843e-02])]} +{'AngularVelocity': array([-0.01562711, -0.00481244, -0.87928385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038147533778101206, + 'FR_Wheel_Angle': 0.0038139112293720245, + 'Location': array([247.454422 , 122.97694397, 0.27295485]), + 'Rotation': array([-1.54772075e-02, 1.03996635e+02, -7.87353516e-03]), + 'Velocity': array([ 1.07724600e-01, -4.34988290e-01, 2.56052008e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.548828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23929.49804688, 15673.10253906, 29.99996948]), + 'frame': 29303, + 'frame_number': 29303, + 'framesequence': 118524, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0600421167910099, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.4138115979731, + 'timestamp_carla': 1000413, + 'timestamp_device': 2618972, + 'timestamp_stream': 1000.4138115979731, + 'transform': [array([ 3.71850159e+02, 1.02189468e+02, -1.62161067e-01]), + array([-6.74822647e-03, 6.48762894e+01, 1.49230873e-02])]} +{'AngularVelocity': array([ 0.02002514, 0.00490698, -0.05978203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812717739492655, + 'FR_Wheel_Angle': 0.0038124180864542723, + 'Location': array([247.48110962, 122.86932373, 0.27295649]), + 'Rotation': array([-1.69661883e-02, 1.04006790e+02, -7.75146624e-03]), + 'Velocity': array([ 1.11431919e-01, -4.48484302e-01, -1.45311351e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5484008789062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23930.85742188, 15672.35644531, 30.00003052]), + 'frame': 29304, + 'frame_number': 29304, + 'framesequence': 118528, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0585222989320755, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.4470205977559, + 'timestamp_carla': 1000446, + 'timestamp_device': 2619006, + 'timestamp_stream': 1000.4470205977559, + 'transform': [array([ 3.71888245e+02, 1.02240669e+02, -1.60047024e-01]), + array([-6.87116990e-03, 6.49017029e+01, 1.57775823e-02])]} +{'AngularVelocity': array([0.00693353, 0.00188013, 0.00301795]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038135508075356483, + 'FR_Wheel_Angle': 0.003814361058175564, + 'Location': array([247.50750732, 122.76298523, 0.27295318]), + 'Rotation': array([-1.62968300e-02, 1.04009636e+02, -7.84301851e-03]), + 'Velocity': array([ 1.10142477e-01, -4.45200175e-01, -4.50038897e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5469970703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23932.25390625, 15671.59863281, 29.99996948]), + 'frame': 29305, + 'frame_number': 29305, + 'framesequence': 118532, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.050263985991477966, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.479904897511, + 'timestamp_carla': 1000479, + 'timestamp_device': 2619039, + 'timestamp_stream': 1000.479904897511, + 'transform': [array([ 3.71920532e+02, 1.02276772e+02, -1.58040464e-01]), + array([-6.65260386e-03, 6.49206009e+01, 1.65710393e-02])]} +{'AngularVelocity': array([ 0.00706853, 0.003478 , -0.10050329]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812754061073065, + 'FR_Wheel_Angle': 0.003814197378233075, + 'Location': array([247.53329468, 122.65914917, 0.27296311]), + 'Rotation': array([-1.73896607e-02, 1.04015671e+02, -7.75146484e-03]), + 'Velocity': array([ 1.13079078e-01, -4.56020147e-01, -9.26971406e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5455322265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23933.64453125, 15670.84179688, 30. ]), + 'frame': 29306, + 'frame_number': 29306, + 'framesequence': 118536, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03869136795401573, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.5128557980061, + 'timestamp_carla': 1000512, + 'timestamp_device': 2619072, + 'timestamp_stream': 1000.5128557980061, + 'transform': [array([ 3.71949982e+02, 1.02306427e+02, -1.57822222e-01]), + array([-6.16766047e-03, 6.49366226e+01, 1.66320708e-02])]} +{'AngularVelocity': array([-0.01492872, -0.0062268 , 0.08361278]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038126311264932156, + 'FR_Wheel_Angle': 0.003809908404946327, + 'Location': array([247.55509949, 122.57136536, 0.27295753]), + 'Rotation': array([-1.69388689e-02, 1.04015671e+02, -7.84301758e-03]), + 'Velocity': array([ 1.12007529e-01, -4.51765418e-01, 1.42850869e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5452880859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23935.07617188, 15670.08007812, 30.00003052]), + 'frame': 29307, + 'frame_number': 29307, + 'framesequence': 118540, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.024317149072885513, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.54568669945, + 'timestamp_carla': 1000545, + 'timestamp_device': 2619106, + 'timestamp_stream': 1000.54568669945, + 'transform': [array([ 3.71975525e+02, 1.02327286e+02, -1.58347279e-01]), + array([-5.55977365e-03, 6.49487152e+01, 1.63879339e-02])]} +{'AngularVelocity': array([ 0.00597089, -0.00453151, -0.82180482]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038126090075820684, + 'FR_Wheel_Angle': 0.0038124355487525463, + 'Location': array([247.58319092, 122.45830536, 0.27295753]), + 'Rotation': array([-1.73350200e-02, 1.04012085e+02, -7.81249953e-03]), + 'Velocity': array([ 1.18505448e-01, -4.75167960e-01, 5.91278076e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5467529296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23936.5 , 15669.33789062, 29.99996948]), + 'frame': 29308, + 'frame_number': 29308, + 'framesequence': 118544, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.009448531083762646, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.5788509994745, + 'timestamp_carla': 1000578, + 'timestamp_device': 2619139, + 'timestamp_stream': 1000.5788509994745, + 'transform': [array([ 3.71995880e+02, 1.02335358e+02, -1.59327045e-01]), + array([-4.91090585e-03, 6.49552002e+01, 1.59606878e-02])]} +{'AngularVelocity': array([-0.01974996, -0.00889438, -1.09305155]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038111857138574123, + 'FR_Wheel_Angle': 0.003812351729720831, + 'Location': array([247.60946655, 122.35237885, 0.27296087]), + 'Rotation': array([-1.73350200e-02, 1.04009445e+02, -7.96508789e-03]), + 'Velocity': array([ 1.18705660e-01, -4.81689751e-01, 9.64450810e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.549072265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23937.90625 , 15668.62597656, 30. ]), + 'frame': 29309, + 'frame_number': 29309, + 'framesequence': 118548, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.006280709523707628, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.6131314001977, + 'timestamp_carla': 1000612, + 'timestamp_device': 2619172, + 'timestamp_stream': 1000.6131314001977, + 'transform': [array([ 3.72012360e+02, 1.02333435e+02, -1.60319090e-01]), + array([-4.30301903e-03, 6.49573135e+01, 1.55334435e-02])]} +{'AngularVelocity': array([ 1.51327150e-02, 8.55645412e-05, -1.25585163e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038146167062222958, + 'FR_Wheel_Angle': 0.003814409486949444, + 'Location': array([247.63574219, 122.24680328, 0.27294582]), + 'Rotation': array([-1.55933211e-02, 1.04008621e+02, -7.56835844e-03]), + 'Velocity': array([ 1.07717380e-01, -4.28148597e-01, -1.54113768e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.551025390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23939.32421875, 15667.93261719, 30. ]), + 'frame': 29310, + 'frame_number': 29310, + 'framesequence': 118552, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.015655996277928352, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.6481199003756, + 'timestamp_carla': 1000647, + 'timestamp_device': 2619206, + 'timestamp_stream': 1000.6481199003756, + 'transform': [array([ 3.72027527e+02, 1.02328308e+02, -1.61564440e-01]), + array([-3.87954712e-03, 6.49579773e+01, 1.50146447e-02])]} +{'AngularVelocity': array([0.03282991, 0.00849963, 0.01337656]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038127077277749777, + 'FR_Wheel_Angle': 0.0038127629086375237, + 'Location': array([247.66220093, 122.14009857, 0.27295619]), + 'Rotation': array([-1.77038498e-02, 1.04011429e+02, -7.81250093e-03]), + 'Velocity': array([ 1.12210624e-01, -4.52967763e-01, -3.08036797e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5514526367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23940.76953125, 15667.25 , 29.99996948]), + 'frame': 29311, + 'frame_number': 29311, + 'framesequence': 118556, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0135135967284441, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.6786791980267, + 'timestamp_carla': 1000678, + 'timestamp_device': 2619239, + 'timestamp_stream': 1000.6786791980267, + 'transform': [array([ 3.72035156e+02, 1.02310524e+02, -1.62622139e-01]), + array([-4.02981136e-03, 6.49527512e+01, 1.45873986e-02])]} +{'AngularVelocity': array([ 0.02956118, 0.00655667, -0.12348258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038098562508821487, + 'FR_Wheel_Angle': 0.0038106117863208055, + 'Location': array([247.69009399, 122.02754974, 0.27296719]), + 'Rotation': array([-1.95889808e-02, 1.04013199e+02, -7.81250093e-03]), + 'Velocity': array([ 1.25697494e-01, -5.05613327e-01, -4.41455813e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5512084960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23942.22460938, 15666.58203125, 30. ]), + 'frame': 29312, + 'frame_number': 29312, + 'framesequence': 118560, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.006665242835879326, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.7131503000855, + 'timestamp_carla': 1000712, + 'timestamp_device': 2619272, + 'timestamp_stream': 1000.7131503000855, + 'transform': [array([ 3.72044830e+02, 1.02293388e+02, -1.62942380e-01]), + array([-4.63769818e-03, 6.49481354e+01, 1.44958450e-02])]} +{'AngularVelocity': array([-0.01212641, -0.00730494, -0.77335387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003812529379501939, + 'FR_Wheel_Angle': 0.0038132164627313614, + 'Location': array([247.72213745, 121.89850616, 0.27294478]), + 'Rotation': array([-1.56274717e-02, 1.04009079e+02, -7.72094727e-03]), + 'Velocity': array([ 1.17887296e-01, -4.71042097e-01, -8.52298690e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5567016601562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23943.4765625, 15666.015625 , 30. ]), + 'frame': 29313, + 'frame_number': 29313, + 'framesequence': 118564, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0022522660437971354, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.7454230971634, + 'timestamp_carla': 1000744, + 'timestamp_device': 2619306, + 'timestamp_stream': 1000.7454230971634, + 'transform': [array([ 3.72058777e+02, 1.02290443e+02, -1.64012492e-01]), + array([-5.34120761e-03, 6.49494400e+01, 1.40991174e-02])]} +{'AngularVelocity': array([ 0.01540719, -0.00231923, -0.99740916]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038134464994072914, + 'FR_Wheel_Angle': 0.003814482130110264, + 'Location': array([247.74499512, 121.80647278, 0.2729547 ]), + 'Rotation': array([-1.58938486e-02, 1.04007202e+02, -7.93457124e-03]), + 'Velocity': array([ 1.11530289e-01, -4.49001491e-01, 2.08473197e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5532836914062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23944.88867188, 15665.36914062, 30. ]), + 'frame': 29314, + 'frame_number': 29314, + 'framesequence': 118568, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.007635731250047684, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.7791258990765, + 'timestamp_carla': 1000778, + 'timestamp_device': 2619339, + 'timestamp_stream': 1000.7791258990765, + 'transform': [array([ 3.72071838e+02, 1.02284279e+02, -1.64641261e-01]), + array([-6.04471704e-03, 6.49494400e+01, 1.38854925e-02])]} +{'AngularVelocity': array([ 0.00399067, -0.00763332, -0.89782488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003815972711890936, + 'FR_Wheel_Angle': 0.0038157422095537186, + 'Location': array([247.77362061, 121.69112396, 0.27294436]), + 'Rotation': array([-1.51903396e-02, 1.04008560e+02, -7.93457124e-03]), + 'Velocity': array([ 1.02877080e-01, -4.14076120e-01, 5.73921207e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.554443359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23946.15625 , 15664.77539062, 30. ]), + 'frame': 29315, + 'frame_number': 29315, + 'framesequence': 118572, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.006573687307536602, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.813523799181, + 'timestamp_carla': 1000813, + 'timestamp_device': 2619372, + 'timestamp_stream': 1000.813523799181, + 'transform': [array([ 3.72090393e+02, 1.02291588e+02, -1.64701879e-01]), + array([-6.44086814e-03, 6.49552841e+01, 1.38854887e-02])]} +{'AngularVelocity': array([ 0.26322192, 0.0648722 , -0.22025022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([247.78894043, 121.629776 , 0.27284667]), + 'Rotation': array([ 1.40018866e-03, 1.04015495e+02, -7.78198289e-03]), + 'Velocity': array([-1.53329438e-02, 6.20580129e-02, 1.00708003e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5521240234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23947.46484375, 15664.15722656, 30.00003052]), + 'frame': 29316, + 'frame_number': 29316, + 'framesequence': 118576, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0026184881571680307, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.8458689972758, + 'timestamp_carla': 1000845, + 'timestamp_device': 2619406, + 'timestamp_stream': 1000.8458689972758, + 'transform': [array([ 3.72100494e+02, 1.02276993e+02, -1.60975218e-01]), + array([-6.46818895e-03, 6.49517059e+01, 1.53808529e-02])]} +{'AngularVelocity': array([-0.09245245, -0.02331025, -0.25665748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([247.77116394, 121.70137787, 0.27283028]), + 'Rotation': array([ 4.48743394e-03, 1.04017555e+02, -7.75146484e-03]), + 'Velocity': array([-9.61943641e-02, 3.87741685e-01, -2.21137991e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5498657226562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23948.76757812, 15663.53222656, 30. ]), + 'frame': 29317, + 'frame_number': 29317, + 'framesequence': 118580, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0014648885698989034, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.8809500001371, + 'timestamp_carla': 1000880, + 'timestamp_device': 2619439, + 'timestamp_stream': 1000.8809500001371, + 'transform': [array([ 3.72114868e+02, 1.02269119e+02, -1.59176245e-01]), + array([-6.52966043e-03, 6.49513092e+01, 1.61132775e-02])]} +{'AngularVelocity': array([-0.03333893, -0.00831143, -0.04056977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([247.74598694, 121.80274963, 0.27293837]), + 'Rotation': array([-1.29432082e-02, 1.04018654e+02, -7.75146531e-03]), + 'Velocity': array([-9.08535570e-02, 3.66226256e-01, 1.78713788e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.548583984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23950.12109375, 15662.90039062, 30.00003052]), + 'frame': 29318, + 'frame_number': 29318, + 'framesequence': 118584, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0037537768948823214, + 'throttle_input': 0.22618448734283447, + 'timestamp': 1000.9127558991313, + 'timestamp_carla': 1000912, + 'timestamp_device': 2619472, + 'timestamp_stream': 1000.9127558991313, + 'transform': [array([ 3.72126160e+02, 1.02255623e+02, -1.56175375e-01]), + array([-6.34524552e-03, 6.49483032e+01, 1.73034612e-02])]} \ No newline at end of file diff --git a/PythonAPI/data/vehicle_logs/forward_0.txt b/PythonAPI/data/vehicle_logs/forward_0.txt new file mode 100644 index 0000000..ba4b17b --- /dev/null +++ b/PythonAPI/data/vehicle_logs/forward_0.txt @@ -0,0 +1,30221 @@ +{'AngularVelocity': array([-5.72848003e-05, 1.59741230e-05, 5.52085730e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57937424e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.96382984e-06, 3.09073357e-06, -2.15010179e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25282288]), + 'frame': 18563, + 'frame_number': 18563, + 'framesequence': 74943, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.3401084505022, + 'timestamp_carla': 636340, + 'timestamp_device': 1506940, + 'timestamp_stream': 636.3401084505022, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288829]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-5.86462047e-05, -3.10458017e-05, 5.46869487e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58410443e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.32488514e-06, 3.27694215e-06, 1.74837478e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25248718]), + 'frame': 18564, + 'frame_number': 18564, + 'framesequence': 74947, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.3727264516056, + 'timestamp_carla': 636372, + 'timestamp_device': 1506973, + 'timestamp_stream': 636.3727264516056, + 'transform': [array([-22.4464798, 84.5209198, -0.1628812]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 6.37955818e-05, -2.64514006e-06, 5.42277558e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58421898e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.72255988e-06, 3.39994676e-06, 2.46038922e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2515564 ]), + 'frame': 18565, + 'frame_number': 18565, + 'framesequence': 74951, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.4062410518527, + 'timestamp_carla': 636406, + 'timestamp_device': 1507006, + 'timestamp_stream': 636.4062410518527, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288356]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-4.20935794e-06, -1.33216608e-05, 5.59973123e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57491111e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.59771775e-06, 2.87935131e-06, -4.16217896e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2522583 ]), + 'frame': 18566, + 'frame_number': 18566, + 'framesequence': 74955, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.4394779503345, + 'timestamp_carla': 636439, + 'timestamp_device': 1507040, + 'timestamp_stream': 636.4394779503345, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288356]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-2.25735148e-05, 1.65121605e-06, 5.48663120e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58494378e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.19937078e-06, 3.22356823e-06, -7.50075487e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25202942]), + 'frame': 18567, + 'frame_number': 18567, + 'framesequence': 74959, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.4731791503727, + 'timestamp_carla': 636473, + 'timestamp_device': 1507073, + 'timestamp_stream': 636.4731791503727, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288657]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 3.90680107e-05, -3.06611219e-05, 5.48654789e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.59562489e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.78890706e-06, 3.44564660e-06, 2.62609450e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25202942]), + 'frame': 18568, + 'frame_number': 18568, + 'framesequence': 74963, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.5053910501301, + 'timestamp_carla': 636505, + 'timestamp_device': 1507106, + 'timestamp_stream': 636.5053910501301, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287757]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-4.34855756e-05, 1.22731517e-05, 5.56634950e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57376675e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.72190948e-06, 2.96246253e-06, -3.50206072e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25172424]), + 'frame': 18569, + 'frame_number': 18569, + 'framesequence': 74967, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.5403413511813, + 'timestamp_carla': 636540, + 'timestamp_device': 1507140, + 'timestamp_stream': 636.5403413511813, + 'transform': [array([-22.4464798, 84.5209198, -0.1628933]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-1.93672781e-06, 2.74581689e-05, 5.52762140e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.56049144e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.62206242e-06, 2.90869730e-06, -3.69263464e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25262451]), + 'frame': 18570, + 'frame_number': 18570, + 'framesequence': 74971, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.5728692524135, + 'timestamp_carla': 636573, + 'timestamp_device': 1507173, + 'timestamp_stream': 636.5728692524135, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288345]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 4.54857473e-05, -3.36756711e-05, 5.33845086e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.54691113e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.83406859e-06, 3.02266312e-06, -1.45193102e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25105286]), + 'frame': 18571, + 'frame_number': 18571, + 'framesequence': 74975, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.607316352427, + 'timestamp_carla': 636607, + 'timestamp_device': 1507206, + 'timestamp_stream': 636.607316352427, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289203]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 1.14865172e-04, -1.62616670e-05, 5.60139888e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.62072566e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([5.30605212e-06, 3.61716366e-06, 5.13418170e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25204468]), + 'frame': 18572, + 'frame_number': 18572, + 'framesequence': 74979, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.6408309489489, + 'timestamp_carla': 636641, + 'timestamp_device': 1507240, + 'timestamp_stream': 636.6408309489489, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288941]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 9.34370109e-05, -5.47513591e-05, 5.39387511e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58872029e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.78198763e-06, 3.42105977e-06, 3.19286657e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25117493]), + 'frame': 18573, + 'frame_number': 18573, + 'framesequence': 74983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.6723785512149, + 'timestamp_carla': 636672, + 'timestamp_device': 1507273, + 'timestamp_stream': 636.6723785512149, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287422]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([2.65152885e-05, 1.85765057e-05, 5.48621465e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58898735e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.23089614e-06, 3.14120666e-06, -6.43954481e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25144958]), + 'frame': 18574, + 'frame_number': 18574, + 'framesequence': 74987, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.7075571492314, + 'timestamp_carla': 636707, + 'timestamp_device': 1507306, + 'timestamp_stream': 636.7075571492314, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289276]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-3.53420546e-05, 4.28689827e-06, 5.46891388e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58929236e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.47712819e-06, 3.35640266e-06, 7.95269807e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25296021]), + 'frame': 18575, + 'frame_number': 18575, + 'framesequence': 74991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.7400892488658, + 'timestamp_carla': 636740, + 'timestamp_device': 1507340, + 'timestamp_stream': 636.7400892488658, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288269]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 6.01995343e-05, -3.99079763e-05, 5.49447905e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57803919e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.98524116e-06, 3.06562515e-06, -1.67876118e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25111389]), + 'frame': 18576, + 'frame_number': 18576, + 'framesequence': 74995, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.7738045491278, + 'timestamp_carla': 636774, + 'timestamp_device': 1507373, + 'timestamp_stream': 636.7738045491278, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288543]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-9.29552261e-05, 3.27485541e-05, 5.63561443e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57815351e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.58470697e-06, 2.94920051e-06, -4.64917859e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25212097]), + 'frame': 18577, + 'frame_number': 18577, + 'framesequence': 74999, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.8065100498497, + 'timestamp_carla': 636806, + 'timestamp_device': 1507406, + 'timestamp_stream': 636.8065100498497, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287968]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-6.73232580e-06, -1.36374756e-05, 5.45845032e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57304194e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.07063408e-06, 3.14290628e-06, -1.14390299e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25184631]), + 'frame': 18578, + 'frame_number': 18578, + 'framesequence': 75003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.8400751501322, + 'timestamp_carla': 636840, + 'timestamp_device': 1507440, + 'timestamp_stream': 636.8400751501322, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288273]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([1.18625758e-05, 2.33642095e-05, 5.69488475e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.53668777e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.12034035e-06, 2.64057417e-06, -6.53169525e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25241089]), + 'frame': 18579, + 'frame_number': 18579, + 'framesequence': 75007, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.8734329491854, + 'timestamp_carla': 636873, + 'timestamp_device': 1507473, + 'timestamp_stream': 636.8734329491854, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288273]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-4.52248314e-05, -2.52359296e-05, 5.43292663e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.59272568e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.62845901e-06, 3.41715759e-06, 1.99597489e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25210571]), + 'frame': 18580, + 'frame_number': 18580, + 'framesequence': 75011, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.9063603505492, + 'timestamp_carla': 636906, + 'timestamp_device': 1507506, + 'timestamp_stream': 636.9063603505492, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287987]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-1.38264786e-05, 3.94519338e-05, 5.48712123e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.59108539e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.29130159e-06, 3.25448809e-06, -4.66422862e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25210571]), + 'frame': 18581, + 'frame_number': 18581, + 'framesequence': 75015, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.9398603513837, + 'timestamp_carla': 636940, + 'timestamp_device': 1507540, + 'timestamp_stream': 636.9398603513837, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288249]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-4.51262131e-05, 1.12544758e-05, 5.49844990e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58456217e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.12945610e-06, 3.19709534e-06, -1.20633158e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25239563]), + 'frame': 18582, + 'frame_number': 18582, + 'framesequence': 75019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 636.9716356508434, + 'timestamp_carla': 636971, + 'timestamp_device': 1507573, + 'timestamp_stream': 636.9716356508434, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287205]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 1.39194435e-05, -1.69252125e-05, 5.45060248e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58723251e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.54102610e-06, 3.38685231e-06, 1.32801477e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25213623]), + 'frame': 18583, + 'frame_number': 18583, + 'framesequence': 75023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.0061345510185, + 'timestamp_carla': 637006, + 'timestamp_device': 1507606, + 'timestamp_stream': 637.0061345510185, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288638]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 4.00737918e-06, -1.64735466e-05, 5.50747536e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58269301e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.03626791e-06, 3.14992849e-06, -1.63340563e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25317383]), + 'frame': 18584, + 'frame_number': 18584, + 'framesequence': 75027, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.0392294488847, + 'timestamp_carla': 637039, + 'timestamp_device': 1507640, + 'timestamp_stream': 637.0392294488847, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288364]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-1.73119479e-05, -7.07896288e-06, 5.55640690e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.56579393e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.64305447e-06, 2.96357553e-06, -3.71054019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2517395 ]), + 'frame': 18585, + 'frame_number': 18585, + 'framesequence': 75031, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.0717930495739, + 'timestamp_carla': 637072, + 'timestamp_device': 1507673, + 'timestamp_stream': 637.0717930495739, + 'transform': [array([-22.4464798, 84.5209198, -0.1628783]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-1.83169723e-05, 2.73351907e-06, 5.51247795e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58528697e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.07872722e-06, 3.10312953e-06, -1.48962979e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25201416]), + 'frame': 18586, + 'frame_number': 18586, + 'framesequence': 75035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.1067743487656, + 'timestamp_carla': 637107, + 'timestamp_device': 1507706, + 'timestamp_stream': 637.1067743487656, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289391]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-1.78418559e-05, 4.32931574e-06, 5.44304639e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58364668e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.51373853e-06, 3.34815104e-06, 1.16097253e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25254822]), + 'frame': 18587, + 'frame_number': 18587, + 'framesequence': 75040, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.1528061516583, + 'timestamp_carla': 637153, + 'timestamp_device': 1507748, + 'timestamp_stream': 637.1528061516583, + 'transform': [array([-22.4464798, 84.5209198, -0.1629221]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 5.02994008e-05, -2.88344781e-05, 5.45404182e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.59207725e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.86194131e-06, 3.50663890e-06, 3.21235391e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25099182]), + 'frame': 18588, + 'frame_number': 18588, + 'framesequence': 75044, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.1792255491018, + 'timestamp_carla': 637179, + 'timestamp_device': 1507781, + 'timestamp_stream': 637.1792255491018, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16291881]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 3.15047109e-05, -2.10887392e-05, 5.54211838e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58799549e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.98546445e-06, 3.04235141e-06, -2.05461110e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24816895]), + 'frame': 18589, + 'frame_number': 18589, + 'framesequence': 75047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.2097816504538, + 'timestamp_carla': 637210, + 'timestamp_device': 1507806, + 'timestamp_stream': 637.2097816504538, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288352]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-1.87435194e-06, 3.85391431e-05, 5.67805291e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.56018643e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 3.31713818e-06, 2.77243089e-06, -5.91045362e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24850464]), + 'frame': 18590, + 'frame_number': 18590, + 'framesequence': 75053, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.255027551204, + 'timestamp_carla': 637255, + 'timestamp_device': 1507856, + 'timestamp_stream': 637.255027551204, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290718]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([3.10804280e-05, 1.73657263e-05, 5.30159850e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57742871e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([5.01059003e-06, 3.62119158e-06, 4.59194649e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25202942]), + 'frame': 18591, + 'frame_number': 18591, + 'framesequence': 75057, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.2899497523904, + 'timestamp_carla': 637290, + 'timestamp_device': 1507890, + 'timestamp_stream': 637.2899497523904, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290519]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 2.62838671e-06, -4.99844718e-05, 5.44063878e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.59650219e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.95037966e-06, 3.56487931e-06, 3.93919676e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24966431]), + 'frame': 18592, + 'frame_number': 18592, + 'framesequence': 75061, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.3199341520667, + 'timestamp_carla': 637320, + 'timestamp_device': 1507923, + 'timestamp_stream': 637.3199341520667, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16294277]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-1.16987667e-05, 3.69107256e-05, 5.50220175e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.59726518e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([4.43308591e-06, 3.28663259e-06, 2.30988571e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24986267]), + 'frame': 18593, + 'frame_number': 18593, + 'framesequence': 75063, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.3446545489132, + 'timestamp_carla': 637344, + 'timestamp_device': 1507940, + 'timestamp_stream': 637.3446545489132, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16291568]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([7.64844935e-06, 2.39394794e-05, 5.48670432e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58212094e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.14728174e-06, 3.15807279e-06, -1.11039648e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24610901]), + 'frame': 18594, + 'frame_number': 18594, + 'framesequence': 75067, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.3722085505724, + 'timestamp_carla': 637372, + 'timestamp_device': 1507973, + 'timestamp_stream': 637.3722085505724, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16292076]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-5.83475367e-06, -1.41925011e-05, 5.46272313e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.57796282e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.15825298e-06, 3.17521381e-06, -7.36972142e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24880981]), + 'frame': 18595, + 'frame_number': 18595, + 'framesequence': 75070, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.4039099514484, + 'timestamp_carla': 637404, + 'timestamp_device': 1507998, + 'timestamp_stream': 637.4039099514484, + 'transform': [array([-22.4464798, 84.5209198, -0.1628865]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 1.05536974e-05, -2.23876650e-05, 5.49255092e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58589745e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.18650916e-06, 3.18209163e-06, -7.60192343e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24830627]), + 'frame': 18596, + 'frame_number': 18596, + 'framesequence': 75074, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.4358961507678, + 'timestamp_carla': 637436, + 'timestamp_device': 1508031, + 'timestamp_stream': 637.4358961507678, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16286846]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 1.34381798e-05, -2.39754099e-05, 5.48001335e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.003842528909444809, + 'Location': array([-3.55098534e+01, 8.70480042e+01, 2.58738501e-03]), + 'Rotation': array([ 4.51748669e-02, 1.75398163e+02, -6.98242038e-02]), + 'Velocity': array([ 4.31047738e-06, 3.25513997e-06, -3.24729763e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2517395 ]), + 'frame': 18597, + 'frame_number': 18597, + 'framesequence': 75078, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.4689844511449, + 'timestamp_carla': 637469, + 'timestamp_device': 1508065, + 'timestamp_stream': 637.4689844511449, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16286652]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.00334399, 0.07167349, 0.00419912]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038421780336648226, + 'FR_Wheel_Angle': 0.003842088393867016, + 'Location': array([-3.55096703e+01, 8.70479736e+01, 2.59356503e-03]), + 'Rotation': array([ 4.53114733e-02, 1.75396286e+02, -6.98852539e-02]), + 'Velocity': array([-0.03622264, 0.00302751, 0.00052456]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25354004]), + 'frame': 18598, + 'frame_number': 18598, + 'framesequence': 75082, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.4990274496377, + 'timestamp_carla': 637499, + 'timestamp_device': 1508098, + 'timestamp_stream': 637.4990274496377, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16284694]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.00367315, 0.07640605, 0.00398797]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038425889797508717, + 'FR_Wheel_Angle': 0.003842797828838229, + 'Location': array([-3.55093575e+01, 8.70479889e+01, 2.58292188e-03]), + 'Rotation': array([ 4.53114733e-02, 1.75396286e+02, -6.98852539e-02]), + 'Velocity': array([-0.03963757, 0.00330638, 0.00029217]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2537384 ]), + 'frame': 18599, + 'frame_number': 18599, + 'framesequence': 75085, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.5280645489693, + 'timestamp_carla': 637528, + 'timestamp_device': 1508123, + 'timestamp_stream': 637.5280645489693, + 'transform': [array([-22.4464798, 84.5209198, -0.1628965]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.00509699, 0.08234646, 0.0042058 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038437126204371452, + 'FR_Wheel_Angle': 0.003844568273052573, + 'Location': array([-3.55101051e+01, 8.70480804e+01, 2.57937424e-03]), + 'Rotation': array([ 4.58510555e-02, 1.75396744e+02, -7.00073242e-02]), + 'Velocity': array([-5.27447909e-02, 4.36125742e-03, -7.61413539e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25569153]), + 'frame': 18600, + 'frame_number': 18600, + 'framesequence': 75090, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.5625724494457, + 'timestamp_carla': 637562, + 'timestamp_device': 1508165, + 'timestamp_stream': 637.5625724494457, + 'transform': [array([-22.4464798, 84.5209198, -0.1628965]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.02170902, 0.04942587, -0.27307996]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038334571290761232, + 'FR_Wheel_Angle': 0.0038348466623574495, + 'Location': array([-3.55166969e+01, 8.70485229e+01, 2.57552136e-03]), + 'Rotation': array([ 4.94778864e-02, 1.75384232e+02, -7.12280124e-02]), + 'Velocity': array([-0.10383395, 0.00806587, 0.00118445]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25073242]), + 'frame': 18601, + 'frame_number': 18601, + 'framesequence': 75094, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.5965791493654, + 'timestamp_carla': 637596, + 'timestamp_device': 1508198, + 'timestamp_stream': 637.5965791493654, + 'transform': [array([-22.4464798, 84.5209198, -0.162892 ]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.00105692, 0.05916434, -0.03237168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038257224950939417, + 'FR_Wheel_Angle': 0.0038253592792898417, + 'Location': array([-3.55399513e+01, 8.70502548e+01, 2.58166296e-03]), + 'Rotation': array([ 5.51810935e-02, 1.75382660e+02, -7.26013109e-02]), + 'Velocity': array([-0.22796169, 0.01732901, 0.00053427]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25073242]), + 'frame': 18602, + 'frame_number': 18602, + 'framesequence': 75098, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.6291312500834, + 'timestamp_carla': 637629, + 'timestamp_device': 1508231, + 'timestamp_stream': 637.6291312500834, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287895]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.00777623, -0.0068288 , 0.21438031]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038185815792530775, + 'FR_Wheel_Angle': 0.0038158127572387457, + 'Location': array([-3.55784302e+01, 8.70532684e+01, 2.67668720e-03]), + 'Rotation': array([ 6.11643419e-02, 1.75380173e+02, -7.20214769e-02]), + 'Velocity': array([-0.31855154, 0.02524889, 0.0010251 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25119019]), + 'frame': 18603, + 'frame_number': 18603, + 'framesequence': 75102, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.6629421524704, + 'timestamp_carla': 637663, + 'timestamp_device': 1508265, + 'timestamp_stream': 637.6629421524704, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288097]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 1.33718961e-04, 6.66203350e-02, -8.77886117e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00381400715559721, + 'FR_Wheel_Angle': 0.003812666516751051, + 'Location': array([-3.56337166e+01, 8.70576477e+01, 2.80413614e-03]), + 'Rotation': array([ 6.83770180e-02, 1.75371689e+02, -7.17468113e-02]), + 'Velocity': array([-0.46573496, 0.03734357, 0.00148281]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25248718]), + 'frame': 18604, + 'frame_number': 18604, + 'framesequence': 75105, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.6943991519511, + 'timestamp_carla': 637694, + 'timestamp_device': 1508290, + 'timestamp_stream': 637.6943991519511, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16286618]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([0.011308 , 0.11616407, 0.15884754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003806614549830556, + 'FR_Wheel_Angle': 0.0038044035900384188, + 'Location': array([-3.57020912e+01, 8.70632019e+01, 2.98647885e-03]), + 'Rotation': array([ 7.52755105e-02, 1.75383621e+02, -7.15331957e-02]), + 'Velocity': array([-0.58622617, 0.04715183, 0.00175921]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25228882]), + 'frame': 18605, + 'frame_number': 18605, + 'framesequence': 75109, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.728376749903, + 'timestamp_carla': 637728, + 'timestamp_device': 1508323, + 'timestamp_stream': 637.728376749903, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287628]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.00961492, 0.12726031, -0.06622843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037985029630362988, + 'FR_Wheel_Angle': 0.0037976291496306658, + 'Location': array([-3.57849503e+01, 8.70698929e+01, 3.22146411e-03]), + 'Rotation': array([ 8.51861164e-02, 1.75384354e+02, -7.14721531e-02]), + 'Velocity': array([-0.70765102, 0.05685727, 0.00245396]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25376892]), + 'frame': 18606, + 'frame_number': 18606, + 'framesequence': 75113, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.7618475519121, + 'timestamp_carla': 637761, + 'timestamp_device': 1508356, + 'timestamp_stream': 637.7618475519121, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287868]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([0.00527745, 0.11271921, 0.52833593]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003789745969697833, + 'FR_Wheel_Angle': 0.0037872004322707653, + 'Location': array([-3.58813629e+01, 8.70776520e+01, 3.47296707e-03]), + 'Rotation': array([ 9.48508307e-02, 1.75383606e+02, -7.17162862e-02]), + 'Velocity': array([-0.79036087, 0.06426985, 0.00245415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25276184]), + 'frame': 18607, + 'frame_number': 18607, + 'framesequence': 75117, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.7952893488109, + 'timestamp_carla': 637795, + 'timestamp_device': 1508389, + 'timestamp_stream': 637.7952893488109, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288024]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.01014482, 0.11699313, -0.00564377]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037785267923027277, + 'FR_Wheel_Angle': 0.0037765062879770994, + 'Location': array([-3.59958725e+01, 8.70868530e+01, 3.75498761e-03]), + 'Rotation': array([ 1.09378643e-01, 1.75384354e+02, -7.17773363e-02]), + 'Velocity': array([-0.9307611 , 0.07466947, 0.00301417]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2525177 ]), + 'frame': 18608, + 'frame_number': 18608, + 'framesequence': 75121, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.827349551022, + 'timestamp_carla': 637827, + 'timestamp_device': 1508423, + 'timestamp_stream': 637.827349551022, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287166]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.01013606, 0.10552341, -0.25204495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003771335119381547, + 'FR_Wheel_Angle': 0.003769886214286089, + 'Location': array([-3.61285896e+01, 8.70974197e+01, 4.11128020e-03]), + 'Rotation': array([ 1.24104530e-01, 1.75375732e+02, -7.16552511e-02]), + 'Velocity': array([-1.05356812, 0.08450358, 0.00368338]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25236511]), + 'frame': 18609, + 'frame_number': 18609, + 'framesequence': 75125, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.8614062517881, + 'timestamp_carla': 637861, + 'timestamp_device': 1508456, + 'timestamp_stream': 637.8614062517881, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288178]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.00930062, 0.12431958, -0.244054 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037641453091055155, + 'FR_Wheel_Angle': 0.0037623250391334295, + 'Location': array([-3.62758942e+01, 8.71092072e+01, 4.49992158e-03]), + 'Rotation': array([ 1.38495743e-01, 1.75370941e+02, -7.16247559e-02]), + 'Velocity': array([-1.15134752, 0.09235492, 0.00381332]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2532196 ]), + 'frame': 18610, + 'frame_number': 18610, + 'framesequence': 75129, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.8942126519978, + 'timestamp_carla': 637894, + 'timestamp_device': 1508489, + 'timestamp_stream': 637.8942126519978, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287838]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0098829 , 0.13532604, -0.02301961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037571783177554607, + 'FR_Wheel_Angle': 0.003755602054297924, + 'Location': array([-3.64362259e+01, 8.71220474e+01, 4.93201241e-03]), + 'Rotation': array([ 1.55578047e-01, 1.75369263e+02, -7.17162937e-02]), + 'Velocity': array([-1.25655162, 0.10094748, 0.00449844]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25221252]), + 'frame': 18611, + 'frame_number': 18611, + 'framesequence': 75134, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.9295022524893, + 'timestamp_carla': 637929, + 'timestamp_device': 1508531, + 'timestamp_stream': 637.9295022524893, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289611]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.01241393, 0.15320933, -0.01646668]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003749854164198041, + 'FR_Wheel_Angle': 0.0037482657935470343, + 'Location': array([-3.66104584e+01, 8.71360626e+01, 5.39484946e-03]), + 'Rotation': array([ 1.74026385e-01, 1.75367508e+02, -7.17162862e-02]), + 'Velocity': array([-1.35796928, 0.10925958, 0.0045506 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25254822]), + 'frame': 18612, + 'frame_number': 18612, + 'framesequence': 75137, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.9608975499868, + 'timestamp_carla': 637960, + 'timestamp_device': 1508556, + 'timestamp_stream': 637.9608975499868, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287728]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0126025 , 0.15640722, -0.01654312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003743384964764118, + 'FR_Wheel_Angle': 0.0037426925264298916, + 'Location': array([-3.67991562e+01, 8.71512451e+01, 5.88057516e-03]), + 'Rotation': array([ 1.94516942e-01, 1.75365967e+02, -7.17162937e-02]), + 'Velocity': array([-1.45834243, 0.11735859, 0.00467189]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2507782 ]), + 'frame': 18613, + 'frame_number': 18613, + 'framesequence': 75141, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 637.9945854507387, + 'timestamp_carla': 637994, + 'timestamp_device': 1508589, + 'timestamp_stream': 637.9945854507387, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288234]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.01917195, 0.12370287, -0.11949193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.2501546144485474, + 'FR_Wheel_Angle': -2.6578586101531982, + 'Location': array([-3.69989166e+01, 8.71673737e+01, 6.42291037e-03]), + 'Rotation': array([ 2.12937966e-01, 1.75361954e+02, -7.14416504e-02]), + 'Velocity': array([-1.47934234, 0.12182665, 0.00532499]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25265503]), + 'frame': 18614, + 'frame_number': 18614, + 'framesequence': 75146, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.0288195498288, + 'timestamp_carla': 638028, + 'timestamp_device': 1508631, + 'timestamp_stream': 638.0288195498288, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288963]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.09520657, 0.0986022 , -2.83008051]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.102471351623535, + 'FR_Wheel_Angle': -9.189422607421875, + 'Location': array([-3.71892891e+01, 8.71869965e+01, 6.95780758e-03]), + 'Rotation': array([ 2.27561399e-01, 1.75171066e+02, -6.18286096e-02]), + 'Velocity': array([-1.42017484, 0.1964696 , 0.00461846]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25215149]), + 'frame': 18615, + 'frame_number': 18615, + 'framesequence': 75150, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.0624467507005, + 'timestamp_carla': 638062, + 'timestamp_device': 1508664, + 'timestamp_stream': 638.0624467507005, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288963]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0661451 , 0.09278888, -6.03260994]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.896232604980469, + 'FR_Wheel_Angle': -15.279125213623047, + 'Location': array([-3.73722343e+01, 8.72165909e+01, 7.43712392e-03]), + 'Rotation': array([ 2.41064683e-01, 1.74568649e+02, -5.32226525e-02]), + 'Velocity': array([-1.31982505, 0.29411229, 0.00394124]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25141907]), + 'frame': 18616, + 'frame_number': 18616, + 'framesequence': 75153, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.0942919515073, + 'timestamp_carla': 638094, + 'timestamp_device': 1508689, + 'timestamp_stream': 638.0942919515073, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287658]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.04006388, 0.08836399, -8.6673317 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.802370071411133, + 'FR_Wheel_Angle': -20.72089958190918, + 'Location': array([-3.75424538e+01, 8.72566299e+01, 7.84834847e-03]), + 'Rotation': array([ 2.53939599e-01, 1.73584244e+02, -5.17578050e-02]), + 'Velocity': array([-1.20291793, 0.38352272, 0.00360946]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25141907]), + 'frame': 18617, + 'frame_number': 18617, + 'framesequence': 75157, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.1261117495596, + 'timestamp_carla': 638126, + 'timestamp_device': 1508723, + 'timestamp_stream': 638.1261117495596, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16286911]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.08548246, 0.10396328, -9.99657154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.423124313354492, + 'FR_Wheel_Angle': -25.75922966003418, + 'Location': array([-3.76933975e+01, 8.73044968e+01, 8.13677814e-03]), + 'Rotation': array([ 2.65516758e-01, 1.72328430e+02, -5.55724986e-02]), + 'Velocity': array([-1.08441436, 0.44400829, 0.00200333]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25273132]), + 'frame': 18618, + 'frame_number': 18618, + 'framesequence': 75161, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.1611206494272, + 'timestamp_carla': 638161, + 'timestamp_device': 1508756, + 'timestamp_stream': 638.1611206494272, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288951]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ -0.20729096, 0.06889361, -11.87892246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.26673126220703, + 'FR_Wheel_Angle': -30.53394317626953, + 'Location': array([-3.78316231e+01, 8.73613281e+01, 8.49593151e-03]), + 'Rotation': array([ 2.74778485e-01, 1.70786057e+02, -6.33239746e-02]), + 'Velocity': array([-0.97484195, 0.51508409, 0.00314275]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.253479 ]), + 'frame': 18619, + 'frame_number': 18619, + 'framesequence': 75165, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.1933976523578, + 'timestamp_carla': 638193, + 'timestamp_device': 1508789, + 'timestamp_stream': 638.1933976523578, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288021]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ -0.29161149, 0.07357275, -12.5782795 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.04907989501953, + 'FR_Wheel_Angle': -29.806455612182617, + 'Location': array([-3.79552155e+01, 8.74247131e+01, 8.93954281e-03]), + 'Rotation': array([ 2.75823504e-01, 1.69055634e+02, -8.56628120e-02]), + 'Velocity': array([-0.88839066, 0.55714399, 0.00343789]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25143433]), + 'frame': 18620, + 'frame_number': 18620, + 'framesequence': 75170, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.2294918522239, + 'timestamp_carla': 638229, + 'timestamp_device': 1508831, + 'timestamp_stream': 638.2294918522239, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290508]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ -0.23186116, 0.06670211, -12.14245129]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.296165466308594, + 'FR_Wheel_Angle': -30.57103729248047, + 'Location': array([-3.80722160e+01, 8.74903412e+01, 9.37491376e-03]), + 'Rotation': array([ 2.77462751e-01, 1.67369019e+02, -1.12426735e-01]), + 'Velocity': array([-0.84207058, 0.56359959, 0.00329138]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25236511]), + 'frame': 18621, + 'frame_number': 18621, + 'framesequence': 75174, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.2619009502232, + 'timestamp_carla': 638261, + 'timestamp_device': 1508864, + 'timestamp_stream': 638.2619009502232, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288948]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ -0.16852321, 0.02083386, -11.71202183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.25676345825195, + 'FR_Wheel_Angle': -30.51057243347168, + 'Location': array([-3.81832428e+01, 8.75579758e+01, 9.72422585e-03]), + 'Rotation': array([ 2.76527017e-01, 1.65697189e+02, -1.30096436e-01]), + 'Velocity': array([-0.79312867, 0.56749618, 0.00148461]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24987793]), + 'frame': 18622, + 'frame_number': 18622, + 'framesequence': 75178, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.2962719500065, + 'timestamp_carla': 638296, + 'timestamp_device': 1508898, + 'timestamp_stream': 638.2962719500065, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289462]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ -1.08677852, 0.8237626 , -11.10204697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.36299514770508, + 'FR_Wheel_Angle': -30.612871170043945, + 'Location': array([-3.82862015e+01, 8.76249466e+01, 1.06799603e-02]), + 'Rotation': array([ 0.30641592, 164.11817932, -0.22131346]), + 'Velocity': array([-0.73021942, 0.56960171, 0.01646904]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25143433]), + 'frame': 18623, + 'frame_number': 18623, + 'framesequence': 75182, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.3297147490084, + 'timestamp_carla': 638329, + 'timestamp_device': 1508931, + 'timestamp_stream': 638.3297147490084, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289012]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ -0.82324767, 0.69905621, -10.58903599]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.390071868896484, + 'FR_Wheel_Angle': -30.626976013183594, + 'Location': array([-3.83825455e+01, 8.76922379e+01, 1.26469703e-02]), + 'Rotation': array([ 0.37175351, 162.60150146, -0.37246707]), + 'Velocity': array([-0.6813522 , 0.56115979, 0.01598543]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25091553]), + 'frame': 18624, + 'frame_number': 18624, + 'framesequence': 75186, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.3622860498726, + 'timestamp_carla': 638362, + 'timestamp_device': 1508964, + 'timestamp_stream': 638.3622860498726, + 'transform': [array([-22.4464798, 84.5209198, -0.1628812]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ -0.1343644 , 0.0842262 , -10.39006901]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.39621353149414, + 'FR_Wheel_Angle': -30.30135726928711, + 'Location': array([-3.84742546e+01, 8.77598419e+01, 1.39581580e-02]), + 'Rotation': array([ 0.40661481, 161.12974548, -0.45040876]), + 'Velocity': array([-0.66063178, 0.56057686, 0.00429641]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25137329]), + 'frame': 18625, + 'frame_number': 18625, + 'framesequence': 75190, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.3988499492407, + 'timestamp_carla': 638398, + 'timestamp_device': 1508998, + 'timestamp_stream': 638.3988499492407, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290848]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.27861878, 0.16630442, -9.48113346]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.281925201416016, + 'FR_Wheel_Angle': -27.023258209228516, + 'Location': array([-3.85644875e+01, 8.78282700e+01, 1.42322062e-02]), + 'Rotation': array([ 0.40683335, 159.70921326, -0.46606439]), + 'Velocity': array([-0.65712714, 0.55528647, 0.00221479]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2522583 ]), + 'frame': 18626, + 'frame_number': 18626, + 'framesequence': 75193, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.4273710511625, + 'timestamp_carla': 638427, + 'timestamp_device': 1509023, + 'timestamp_stream': 638.4273710511625, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16293098]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-8.16826522e-03, -5.88090271e-02, -9.01023483e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.43576431274414, + 'FR_Wheel_Angle': -28.666810989379883, + 'Location': array([-3.86540146e+01, 8.78949280e+01, 1.45178884e-02]), + 'Rotation': array([ 0.40862972, 158.45680237, -0.48281845]), + 'Velocity': array([-6.55438602e-01, 5.51912308e-01, 1.50012973e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24954224]), + 'frame': 18627, + 'frame_number': 18627, + 'framesequence': 75197, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.460922151804, + 'timestamp_carla': 638461, + 'timestamp_device': 1509056, + 'timestamp_stream': 638.460922151804, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290924]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.05623669, -0.04116211, -9.26962376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.251853942871094, + 'FR_Wheel_Angle': -27.89957618713379, + 'Location': array([-3.87412720e+01, 8.79641495e+01, 1.45636648e-02]), + 'Rotation': array([ 0.39914942, 157.15245056, -0.47500613]), + 'Velocity': array([-6.30345166e-01, 5.71196258e-01, 2.46143347e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24728394]), + 'frame': 18628, + 'frame_number': 18628, + 'framesequence': 75201, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.494875151664, + 'timestamp_carla': 638494, + 'timestamp_device': 1509089, + 'timestamp_stream': 638.494875151664, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289894]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.05772316, -0.07370576, -8.95862103]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.31449890136719, + 'FR_Wheel_Angle': -28.26017189025879, + 'Location': array([-3.88282738e+01, 8.80360947e+01, 1.46883298e-02]), + 'Rotation': array([ 0.38621303, 155.85063171, -0.4673461 ]), + 'Velocity': array([-6.09561801e-01, 5.70757449e-01, 1.27763749e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24946594]), + 'frame': 18629, + 'frame_number': 18629, + 'framesequence': 75205, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.5274945497513, + 'timestamp_carla': 638527, + 'timestamp_device': 1509123, + 'timestamp_stream': 638.5274945497513, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288325]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.09583759, -0.06188707, -8.64215946]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.201576232910156, + 'FR_Wheel_Angle': -28.124162673950195, + 'Location': array([-3.89076958e+01, 8.81049881e+01, 1.48526663e-02]), + 'Rotation': array([ 0.37143248, 154.63240051, -0.46392807]), + 'Velocity': array([-5.74533641e-01, 5.64131081e-01, 3.08752060e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25048828]), + 'frame': 18630, + 'frame_number': 18630, + 'framesequence': 75209, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.5601843520999, + 'timestamp_carla': 638560, + 'timestamp_device': 1509156, + 'timestamp_stream': 638.5601843520999, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287494]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.09516326, -0.05205051, -8.17207336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.33422088623047, + 'FR_Wheel_Angle': -28.19377899169922, + 'Location': array([-3.89828453e+01, 8.81730423e+01, 1.49825951e-02]), + 'Rotation': array([ 0.35710275, 153.45568848, -0.46246323]), + 'Velocity': array([-0.53127068, 0.5443235 , 0.00060371]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25205994]), + 'frame': 18631, + 'frame_number': 18631, + 'framesequence': 75213, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.5934493504465, + 'timestamp_carla': 638593, + 'timestamp_device': 1509189, + 'timestamp_stream': 638.5934493504465, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287494]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.15019737, -0.06081185, -7.61394453]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.37548828125, + 'FR_Wheel_Angle': -28.22080421447754, + 'Location': array([-3.90531235e+01, 8.82397232e+01, 1.51218316e-02]), + 'Rotation': array([ 0.34629056, 152.31655884, -0.45431519]), + 'Velocity': array([-0.47671536, 0.51221937, 0.00229557]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25288391]), + 'frame': 18632, + 'frame_number': 18632, + 'framesequence': 75217, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.6280798502266, + 'timestamp_carla': 638628, + 'timestamp_device': 1509223, + 'timestamp_stream': 638.6280798502266, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288623]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.25645801, -0.0301601 , -6.89567423]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.417213439941406, + 'FR_Wheel_Angle': -28.245012283325195, + 'Location': array([-3.91144905e+01, 8.83009567e+01, 1.57031920e-02]), + 'Rotation': array([ 0.35553181, 151.26985168, -0.40911859]), + 'Velocity': array([-0.42206329, 0.47154501, 0.00523358]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25288391]), + 'frame': 18633, + 'frame_number': 18633, + 'framesequence': 75221, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.6602833494544, + 'timestamp_carla': 638660, + 'timestamp_device': 1509256, + 'timestamp_stream': 638.6602833494544, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287491]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.23425682, -0.02734232, -6.35325813]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.44736862182617, + 'FR_Wheel_Angle': -28.261089324951172, + 'Location': array([-3.91693687e+01, 8.83578415e+01, 1.63177382e-02]), + 'Rotation': array([ 0.36661038, 150.30885315, -0.3664245 ]), + 'Velocity': array([-0.38118443, 0.44160333, 0.00460227]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25175476]), + 'frame': 18634, + 'frame_number': 18634, + 'framesequence': 75225, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.6935843490064, + 'timestamp_carla': 638693, + 'timestamp_device': 1509289, + 'timestamp_stream': 638.6935843490064, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287658]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.15091071, -0.01819425, -6.19820023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.471038818359375, + 'FR_Wheel_Angle': -28.276309967041016, + 'Location': array([-3.92192574e+01, 8.84113388e+01, 1.68323796e-02]), + 'Rotation': array([ 0.37573552, 149.41444397, -0.32931519]), + 'Velocity': array([-0.34926498, 0.4156858 , 0.00340829]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25289917]), + 'frame': 18635, + 'frame_number': 18635, + 'framesequence': 75229, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.7271567508578, + 'timestamp_carla': 638727, + 'timestamp_device': 1509323, + 'timestamp_stream': 638.7271567508578, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288009]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 5.36518544e-02, -5.04466798e-03, -5.56407738e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.494747161865234, + 'FR_Wheel_Angle': -28.29274559020996, + 'Location': array([-3.92648964e+01, 8.84618073e+01, 1.72172822e-02]), + 'Rotation': array([ 0.38048932, 148.58998108, -0.30239868]), + 'Velocity': array([-0.31657645, 0.38550165, 0.00266064]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25273132]), + 'frame': 18636, + 'frame_number': 18636, + 'framesequence': 75233, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.7604478523135, + 'timestamp_carla': 638760, + 'timestamp_device': 1509356, + 'timestamp_stream': 638.7604478523135, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288009]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 6.53050467e-02, -5.06399153e-03, -5.53510761e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.110939025878906, + 'FR_Wheel_Angle': -25.8660945892334, + 'Location': array([-3.93076668e+01, 8.85104599e+01, 1.75232217e-02]), + 'Rotation': array([ 0.38429374, 147.80238342, -0.27786264]), + 'Velocity': array([-0.30158657, 0.37408644, 0.00235757]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25238037]), + 'frame': 18637, + 'frame_number': 18637, + 'framesequence': 75237, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.7933866493404, + 'timestamp_carla': 638793, + 'timestamp_device': 1509389, + 'timestamp_stream': 638.7933866493404, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287796]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 7.20210969e-02, 2.86389026e-03, -4.37634230e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.05838394165039, + 'FR_Wheel_Angle': -25.486873626708984, + 'Location': array([-3.93487129e+01, 8.85555191e+01, 1.78510193e-02]), + 'Rotation': array([ 0.39035895, 147.14537048, -0.25378418]), + 'Velocity': array([-0.30634323, 0.35004914, 0.00255444]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25238037]), + 'frame': 18638, + 'frame_number': 18638, + 'framesequence': 75241, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.8271342515945, + 'timestamp_carla': 638827, + 'timestamp_device': 1509423, + 'timestamp_stream': 638.8271342515945, + 'transform': [array([-22.4464798, 84.5209198, -0.1628831]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.15786731, -0.0645067 , -5.79995203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.05770492553711, + 'FR_Wheel_Angle': -25.911771774291992, + 'Location': array([-3.93902473e+01, 8.86013641e+01, 1.81323141e-02]), + 'Rotation': array([ 0.39358279, 146.48803711, -0.22988887]), + 'Velocity': array([-0.32380825, 0.41086927, 0.00067371]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25259399]), + 'frame': 18639, + 'frame_number': 18639, + 'framesequence': 75245, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.8610229492188, + 'timestamp_carla': 638861, + 'timestamp_device': 1509456, + 'timestamp_stream': 638.8610229492188, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288719]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.04707103, -0.01020664, -5.13158035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.994022369384766, + 'FR_Wheel_Angle': -25.675203323364258, + 'Location': array([-3.94317513e+01, 8.86482468e+01, 1.81816760e-02]), + 'Rotation': array([ 0.38574174, 145.84927368, -0.23095702]), + 'Velocity': array([-3.08126837e-01, 3.76077563e-01, -2.98547733e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2520752 ]), + 'frame': 18640, + 'frame_number': 18640, + 'framesequence': 75249, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.8936523497105, + 'timestamp_carla': 638893, + 'timestamp_device': 1509489, + 'timestamp_stream': 638.8936523497105, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288032]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.01559419, -0.03376118, -4.66881275]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.407508850097656, + 'FR_Wheel_Angle': -25.70513916015625, + 'Location': array([-3.94731712e+01, 8.86956329e+01, 1.81920137e-02]), + 'Rotation': array([ 0.37767529, 145.20677185, -0.23001102]), + 'Velocity': array([-0.30568916, 0.39247325, -0.00058471]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25166321]), + 'frame': 18641, + 'frame_number': 18641, + 'framesequence': 75253, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.927545350045, + 'timestamp_carla': 638927, + 'timestamp_device': 1509523, + 'timestamp_stream': 638.927545350045, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288581]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-7.33327195e-02, -4.31138324e-03, -4.84141445e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.338226318359375, + 'FR_Wheel_Angle': -25.73749351501465, + 'Location': array([-3.95133896e+01, 8.87431641e+01, 1.82215776e-02]), + 'Rotation': array([ 0.3693971 , 144.55592346, -0.22937004]), + 'Velocity': array([-2.91409016e-01, 3.75782400e-01, -1.89809798e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25234985]), + 'frame': 18642, + 'frame_number': 18642, + 'framesequence': 75257, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.9602812491357, + 'timestamp_carla': 638960, + 'timestamp_device': 1509556, + 'timestamp_stream': 638.9602812491357, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288044]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.05330062, -0.03965794, -5.20867872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.316707611083984, + 'FR_Wheel_Angle': -25.7187557220459, + 'Location': array([-3.95531693e+01, 8.87912064e+01, 1.82482433e-02]), + 'Rotation': array([ 0.36218444, 143.90496826, -0.22805782]), + 'Velocity': array([-3.05548400e-01, 4.12619323e-01, -3.56235483e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25180054]), + 'frame': 18643, + 'frame_number': 18643, + 'framesequence': 75262, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 638.9958327524364, + 'timestamp_carla': 638995, + 'timestamp_device': 1509598, + 'timestamp_stream': 638.9958327524364, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289966]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0580234 , -0.05375112, -5.18419695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.31356430053711, + 'FR_Wheel_Angle': -25.722627639770508, + 'Location': array([-3.95938263e+01, 8.88411179e+01, 1.82818882e-02]), + 'Rotation': array([ 0.35467121, 143.24824524, -0.227478 ]), + 'Velocity': array([-3.02489012e-01, 4.20418411e-01, -5.03635383e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25233459]), + 'frame': 18644, + 'frame_number': 18644, + 'framesequence': 75265, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.0275020487607, + 'timestamp_carla': 639027, + 'timestamp_device': 1509623, + 'timestamp_stream': 639.0275020487607, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288109]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.06119967, -0.08347229, -4.87227392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.32331466674805, + 'FR_Wheel_Angle': -25.722244262695312, + 'Location': array([-3.96332970e+01, 8.88906937e+01, 1.83320139e-02]), + 'Rotation': array([ 0.34714434, 142.59092712, -0.22604369]), + 'Velocity': array([-2.85209388e-01, 4.13521290e-01, 3.61957529e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25041199]), + 'frame': 18645, + 'frame_number': 18645, + 'framesequence': 75269, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.0603225491941, + 'timestamp_carla': 639060, + 'timestamp_device': 1509656, + 'timestamp_stream': 639.0603225491941, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287807]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.08293426, -0.08640421, -4.92939281]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.310176849365234, + 'FR_Wheel_Angle': -25.70751190185547, + 'Location': array([-3.96731300e+01, 8.89419479e+01, 1.84176918e-02]), + 'Rotation': array([ 0.34190559, 141.90315247, -0.21911617]), + 'Velocity': array([-0.28140467, 0.41994068, 0.00059662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25227356]), + 'frame': 18646, + 'frame_number': 18646, + 'framesequence': 75273, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.0942658521235, + 'timestamp_carla': 639094, + 'timestamp_device': 1509689, + 'timestamp_stream': 639.0942658521235, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288498]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.07028278, -0.04994043, -4.23582315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.295570373535156, + 'FR_Wheel_Angle': -25.70203971862793, + 'Location': array([-3.97120018e+01, 8.89933929e+01, 1.85294617e-02]), + 'Rotation': array([ 0.3367283 , 141.23832703, -0.21343991]), + 'Velocity': array([-0.25355017, 0.38593164, 0.00103315]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25257874]), + 'frame': 18647, + 'frame_number': 18647, + 'framesequence': 75277, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.1269560493529, + 'timestamp_carla': 639127, + 'timestamp_device': 1509723, + 'timestamp_stream': 639.1269560493529, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287971]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.04219531, -0.03747577, -4.25849581]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.03501892089844, + 'FR_Wheel_Angle': -24.838895797729492, + 'Location': array([-3.97503548e+01, 8.90456696e+01, 1.86198708e-02]), + 'Rotation': array([ 0.331633 , 140.5737915, -0.2074585]), + 'Velocity': array([-2.58715779e-01, 3.98582727e-01, 3.79323959e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25189209]), + 'frame': 18648, + 'frame_number': 18648, + 'framesequence': 75281, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.160722348839, + 'timestamp_carla': 639160, + 'timestamp_device': 1509756, + 'timestamp_stream': 639.160722348839, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288482]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.02717512, -0.02258596, -3.56333899]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.524173736572266, + 'FR_Wheel_Angle': -22.002185821533203, + 'Location': array([-3.97885132e+01, 8.90973740e+01, 1.86933409e-02]), + 'Rotation': array([ 0.32655814, 139.95558167, -0.20477295]), + 'Velocity': array([-2.76552826e-01, 4.03049797e-01, 4.01878351e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25241089]), + 'frame': 18649, + 'frame_number': 18649, + 'framesequence': 75285, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.1941301487386, + 'timestamp_carla': 639194, + 'timestamp_device': 1509789, + 'timestamp_stream': 639.1941301487386, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288482]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.07424344, -0.03531907, -3.86484194]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.763383865356445, + 'FR_Wheel_Angle': -23.59662628173828, + 'Location': array([-3.98268585e+01, 8.91474762e+01, 1.87090207e-02]), + 'Rotation': array([ 0.31894931, 139.42294312, -0.20571896]), + 'Velocity': array([-0.27132282, 0.39441961, -0.00048783]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25190735]), + 'frame': 18650, + 'frame_number': 18650, + 'framesequence': 75290, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.2296582497656, + 'timestamp_carla': 639229, + 'timestamp_device': 1509831, + 'timestamp_stream': 639.2296582497656, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290188]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.1150703 , -0.00837825, -3.3232069 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.91407012939453, + 'FR_Wheel_Angle': -22.82488441467285, + 'Location': array([-3.98648758e+01, 8.91994781e+01, 1.86904799e-02]), + 'Rotation': array([ 0.31032279, 138.84603882, -0.20581053]), + 'Velocity': array([-2.63864279e-01, 4.00185317e-01, -3.86447908e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25190735]), + 'frame': 18651, + 'frame_number': 18651, + 'framesequence': 75294, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.2624524496496, + 'timestamp_carla': 639262, + 'timestamp_device': 1509864, + 'timestamp_stream': 639.2624524496496, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288967]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.07542728, -0.02514347, -3.4239676 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.24954605102539, + 'FR_Wheel_Angle': -23.15325164794922, + 'Location': array([-3.99029274e+01, 8.92521973e+01, 1.86869707e-02]), + 'Rotation': array([ 0.30213341, 138.26850891, -0.20608519]), + 'Velocity': array([-2.61108875e-01, 4.02791470e-01, -1.54914858e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25019836]), + 'frame': 18652, + 'frame_number': 18652, + 'framesequence': 75297, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.2945778518915, + 'timestamp_carla': 639294, + 'timestamp_device': 1509889, + 'timestamp_stream': 639.2945778518915, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287789]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.02211425, -0.07616744, -5.31187534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.081680297851562, + 'FR_Wheel_Angle': -23.064817428588867, + 'Location': array([-3.99413185e+01, 8.93063812e+01, 1.87556352e-02]), + 'Rotation': array([ 0.29682633, 137.66444397, -0.20046996]), + 'Velocity': array([-0.27212375, 0.43870166, 0.00045421]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25141907]), + 'frame': 18653, + 'frame_number': 18653, + 'framesequence': 75301, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.3274036496878, + 'timestamp_carla': 639327, + 'timestamp_device': 1509922, + 'timestamp_stream': 639.3274036496878, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287613]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.0259612 , -0.05906647, -5.31264639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.145238876342773, + 'FR_Wheel_Angle': -23.070491790771484, + 'Location': array([-3.99785309e+01, 8.93601761e+01, 1.87785998e-02]), + 'Rotation': array([ 0.28890333, 137.08247375, -0.20062253]), + 'Velocity': array([-2.63322085e-01, 4.29536849e-01, -2.18353263e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25259399]), + 'frame': 18654, + 'frame_number': 18654, + 'framesequence': 75305, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.3611591495574, + 'timestamp_carla': 639361, + 'timestamp_device': 1509956, + 'timestamp_stream': 639.3611591495574, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288239]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.0403871 , -0.0383196 , -4.44944954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.13155174255371, + 'FR_Wheel_Angle': -23.06147003173828, + 'Location': array([-4.00155296e+01, 8.94147949e+01, 1.87710468e-02]), + 'Rotation': array([ 0.2808437 , 136.5007019 , -0.20101929]), + 'Velocity': array([-2.58754432e-01, 4.32138592e-01, -7.51924526e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2527771 ]), + 'frame': 18655, + 'frame_number': 18655, + 'framesequence': 75310, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.3947836495936, + 'timestamp_carla': 639394, + 'timestamp_device': 1509997, + 'timestamp_stream': 639.3947836495936, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288508]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.07559855, -0.03189718, -4.68436193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.118539810180664, + 'FR_Wheel_Angle': -23.052730560302734, + 'Location': array([-4.00516930e+01, 8.94690781e+01, 1.87742524e-02]), + 'Rotation': array([ 0.27298215, 135.90795898, -0.20111082]), + 'Velocity': array([-2.48700663e-01, 4.19320822e-01, -1.70569416e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25215149]), + 'frame': 18656, + 'frame_number': 18656, + 'framesequence': 75313, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.4266866520047, + 'timestamp_carla': 639426, + 'timestamp_device': 1510022, + 'timestamp_stream': 639.4266866520047, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287445]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.06056354, -0.03611444, -3.64276123]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.12446403503418, + 'FR_Wheel_Angle': -23.052757263183594, + 'Location': array([-4.00888481e+01, 8.95261688e+01, 1.87674612e-02]), + 'Rotation': array([ 0.26591974, 135.29653931, -0.19979858]), + 'Velocity': array([-2.54456222e-01, 4.46374297e-01, -2.33783721e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25187683]), + 'frame': 18657, + 'frame_number': 18657, + 'framesequence': 75318, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.4612871520221, + 'timestamp_carla': 639461, + 'timestamp_device': 1510064, + 'timestamp_stream': 639.4612871520221, + 'transform': [array([-22.4464798, 84.5209198, -0.1628886]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.10403495, -0.00947206, -3.27023458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.12648582458496, + 'FR_Wheel_Angle': -23.058483123779297, + 'Location': array([-4.01255379e+01, 8.95841980e+01, 1.87621582e-02]), + 'Rotation': array([ 0.2573615 , 134.68389893, -0.20043944]), + 'Velocity': array([-2.44317979e-01, 4.35247838e-01, -3.65180953e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25294495]), + 'frame': 18658, + 'frame_number': 18658, + 'framesequence': 75321, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.4942360520363, + 'timestamp_carla': 639494, + 'timestamp_device': 1510089, + 'timestamp_stream': 639.4942360520363, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288403]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.05358833, -0.01719826, -3.91612577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.12714195251465, + 'FR_Wheel_Angle': -23.046459197998047, + 'Location': array([-4.01601715e+01, 8.96404572e+01, 1.87662784e-02]), + 'Rotation': array([ 0.24918577, 134.10267639, -0.20141599]), + 'Velocity': array([-2.42181733e-01, 4.34654117e-01, -2.69422511e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25152588]), + 'frame': 18659, + 'frame_number': 18659, + 'framesequence': 75326, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.5299118496478, + 'timestamp_carla': 639529, + 'timestamp_device': 1510131, + 'timestamp_stream': 639.5299118496478, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290291]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.01934077, -0.0432044 , -4.20498228]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.884384155273438, + 'FR_Wheel_Angle': -19.81743621826172, + 'Location': array([-4.01947441e+01, 8.96973801e+01, 1.87660493e-02]), + 'Rotation': array([ 0.24258098, 133.51350403, -0.20111078]), + 'Velocity': array([-2.49738708e-01, 4.57182497e-01, 1.35965340e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25198364]), + 'frame': 18660, + 'frame_number': 18660, + 'framesequence': 75330, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.5631850510836, + 'timestamp_carla': 639563, + 'timestamp_device': 1510164, + 'timestamp_stream': 639.5631850510836, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289374]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0231302 , -0.06960681, -3.35805631]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.196664810180664, + 'FR_Wheel_Angle': -20.35736656188965, + 'Location': array([-4.02322807e+01, 8.97562408e+01, 1.87235549e-02]), + 'Rotation': array([ 0.23493801, 132.97938538, -0.20358276]), + 'Velocity': array([-0.26762864, 0.4615753 , -0.00100841]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25009155]), + 'frame': 18661, + 'frame_number': 18661, + 'framesequence': 75334, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.5964990518987, + 'timestamp_carla': 639596, + 'timestamp_device': 1510197, + 'timestamp_stream': 639.5964990518987, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288841]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.05298123, -0.08838753, -4.95277166]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.46998405456543, + 'FR_Wheel_Angle': -20.35790252685547, + 'Location': array([-4.02678604e+01, 8.98132782e+01, 1.87276360e-02]), + 'Rotation': array([ 0.22795072, 132.46382141, -0.19949341]), + 'Velocity': array([-0.25597316, 0.47359169, -0.00081714]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25100708]), + 'frame': 18662, + 'frame_number': 18662, + 'framesequence': 75338, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.6284152492881, + 'timestamp_carla': 639628, + 'timestamp_device': 1510231, + 'timestamp_stream': 639.6284152492881, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287559]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0470753 , -0.05955071, -4.23999929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.759212493896484, + 'FR_Wheel_Angle': -20.318769454956055, + 'Location': array([-4.03030434e+01, 8.98713150e+01, 1.86630916e-02]), + 'Rotation': array([ 0.22215872, 131.94845581, -0.1968994 ]), + 'Velocity': array([-0.25283217, 0.46288738, -0.0006653 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25154114]), + 'frame': 18663, + 'frame_number': 18663, + 'framesequence': 75342, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.6616771519184, + 'timestamp_carla': 639661, + 'timestamp_device': 1510264, + 'timestamp_stream': 639.6616771519184, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287792]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.15968616, 0.03639085, -4.1348815 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.9980411529541, + 'FR_Wheel_Angle': -20.26348304748535, + 'Location': array([-4.03378792e+01, 8.99298248e+01, 1.85998809e-02]), + 'Rotation': array([ 0.21662627, 131.43087769, -0.19415282]), + 'Velocity': array([-0.2539399 , 0.4816328 , 0.00059362]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25282288]), + 'frame': 18664, + 'frame_number': 18664, + 'framesequence': 75346, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.6960713490844, + 'timestamp_carla': 639696, + 'timestamp_device': 1510297, + 'timestamp_stream': 639.6960713490844, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288833]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.44487903, 0.06738475, -4.23861122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.00746726989746, + 'FR_Wheel_Angle': -20.324857711791992, + 'Location': array([-4.03707962e+01, 8.99874268e+01, 1.92857254e-02]), + 'Rotation': array([ 0.18227042, 130.95196533, -0.23693845]), + 'Velocity': array([-0.23011135, 0.46388084, 0.00530239]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25259399]), + 'frame': 18665, + 'frame_number': 18665, + 'framesequence': 75349, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.7272047512233, + 'timestamp_carla': 639727, + 'timestamp_device': 1510322, + 'timestamp_stream': 639.7272047512233, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287129]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.50895792, 0.14203268, -4.23854685]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.982885360717773, + 'FR_Wheel_Angle': -20.325889587402344, + 'Location': array([-4.04030380e+01, 9.00450821e+01, 2.01587956e-02]), + 'Rotation': array([ 0.14413065, 130.47976685, -0.28436276]), + 'Velocity': array([-0.23336418, 0.45186567, 0.00504443]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2515564 ]), + 'frame': 18666, + 'frame_number': 18666, + 'framesequence': 75353, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.7609248496592, + 'timestamp_carla': 639761, + 'timestamp_device': 1510356, + 'timestamp_stream': 639.7609248496592, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287968]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.31738451, 0.03773627, -4.34736013]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.975034713745117, + 'FR_Wheel_Angle': -20.31017303466797, + 'Location': array([-4.04340096e+01, 9.01011429e+01, 2.09091082e-02]), + 'Rotation': array([ 1.11209132e-01, 1.30004700e+02, -3.22265625e-01]), + 'Velocity': array([-0.2138069 , 0.44506687, 0.00352055]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25325012]), + 'frame': 18667, + 'frame_number': 18667, + 'framesequence': 75357, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.7943488508463, + 'timestamp_carla': 639794, + 'timestamp_device': 1510389, + 'timestamp_stream': 639.7943488508463, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288246]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.43446404, 0.1072114 , -3.72728705]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.975854873657227, + 'FR_Wheel_Angle': -20.314523696899414, + 'Location': array([-4.04646072e+01, 9.01572647e+01, 2.15365887e-02]), + 'Rotation': array([ 8.20920393e-02, 1.29524506e+02, -3.57299745e-01]), + 'Velocity': array([-0.20073625, 0.4089275 , 0.00379621]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25241089]), + 'frame': 18668, + 'frame_number': 18668, + 'framesequence': 75362, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.8301315493882, + 'timestamp_carla': 639830, + 'timestamp_device': 1510431, + 'timestamp_stream': 639.8301315493882, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290325]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.03569549, -0.07259957, -4.34566259]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.989364624023438, + 'FR_Wheel_Angle': -20.31563377380371, + 'Location': array([-4.04943619e+01, 9.02127838e+01, 2.19095126e-02]), + 'Rotation': array([ 6.37939647e-02, 1.29048706e+02, -3.73992860e-01]), + 'Velocity': array([-2.15694904e-01, 4.56735015e-01, -1.59192088e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25213623]), + 'frame': 18669, + 'frame_number': 18669, + 'framesequence': 75366, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.861192651093, + 'timestamp_carla': 639861, + 'timestamp_device': 1510464, + 'timestamp_stream': 639.861192651093, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287975]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.05253713, -0.07257184, -4.75064754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.983417510986328, + 'FR_Wheel_Angle': -20.320083618164062, + 'Location': array([-4.05248146e+01, 9.02705383e+01, 2.17627622e-02]), + 'Rotation': array([ 6.09047934e-02, 1.28546997e+02, -3.67950320e-01]), + 'Velocity': array([-0.20884147, 0.45411968, -0.00179776]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25006104]), + 'frame': 18670, + 'frame_number': 18670, + 'framesequence': 75370, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.8976831510663, + 'timestamp_carla': 639897, + 'timestamp_device': 1510497, + 'timestamp_stream': 639.8976831510663, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290748]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0116252 , -0.05125454, -4.5099926 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.665449142456055, + 'FR_Wheel_Angle': -18.339122772216797, + 'Location': array([-4.05546761e+01, 9.03280029e+01, 2.16320325e-02]), + 'Rotation': array([ 5.80156222e-02, 1.28055222e+02, -3.63677979e-01]), + 'Velocity': array([-0.21152091, 0.46243468, -0.00081334]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25241089]), + 'frame': 18671, + 'frame_number': 18671, + 'framesequence': 75374, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.9326122514904, + 'timestamp_carla': 639932, + 'timestamp_device': 1510531, + 'timestamp_stream': 639.9326122514904, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290748]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.08099785, -0.04718833, -3.31268501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.046886444091797, + 'FR_Wheel_Angle': -16.60873794555664, + 'Location': array([-4.05857010e+01, 9.03859482e+01, 2.16543488e-02]), + 'Rotation': array([ 4.87812087e-02, 1.27609100e+02, -3.71581972e-01]), + 'Velocity': array([-2.18256503e-01, 4.42079574e-01, -2.42862690e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24963379]), + 'frame': 18672, + 'frame_number': 18672, + 'framesequence': 75377, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.9610924497247, + 'timestamp_carla': 639961, + 'timestamp_device': 1510556, + 'timestamp_stream': 639.9610924497247, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16292915]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.13274913, -0.04533456, -3.74744034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.72657012939453, + 'FR_Wheel_Angle': -17.88457679748535, + 'Location': array([-4.06175194e+01, 9.04444962e+01, 2.17508208e-02]), + 'Rotation': array([ 3.77572849e-02, 1.27188293e+02, -3.75823975e-01]), + 'Velocity': array([-2.07877114e-01, 4.38325912e-01, -9.36412762e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24963379]), + 'frame': 18673, + 'frame_number': 18673, + 'framesequence': 75382, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 639.9948459491134, + 'timestamp_carla': 639994, + 'timestamp_device': 1510597, + 'timestamp_stream': 639.9948459491134, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16290882]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.0062699 , -0.07456025, -3.64789677]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.357900619506836, + 'FR_Wheel_Angle': -17.203577041625977, + 'Location': array([-4.06494370e+01, 9.05055542e+01, 2.16433611e-02]), + 'Rotation': array([ 3.42943780e-02, 1.26728455e+02, -3.69079560e-01]), + 'Velocity': array([-0.21349029, 0.45658383, -0.00156809]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24746704]), + 'frame': 18674, + 'frame_number': 18674, + 'framesequence': 75385, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.0277257524431, + 'timestamp_carla': 640027, + 'timestamp_device': 1510622, + 'timestamp_stream': 640.0277257524431, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289024]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.09451927, -0.03307849, -2.74275398]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.95151710510254, + 'FR_Wheel_Angle': -17.454980850219727, + 'Location': array([-4.06814041e+01, 9.05670471e+01, 2.14900114e-02]), + 'Rotation': array([ 3.11661512e-02, 1.26289833e+02, -3.63403291e-01]), + 'Velocity': array([-0.2074156 , 0.4504081 , -0.00079362]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.24949646]), + 'frame': 18675, + 'frame_number': 18675, + 'framesequence': 75389, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.0608860515058, + 'timestamp_carla': 640061, + 'timestamp_device': 1510656, + 'timestamp_stream': 640.0608860515058, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288143]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.07739827, -0.03795659, -2.84878826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.77557945251465, + 'FR_Wheel_Angle': -17.437517166137695, + 'Location': array([-4.07122078e+01, 9.06278381e+01, 2.14042179e-02]), + 'Rotation': array([ 2.64260005e-02, 1.25865120e+02, -3.59710634e-01]), + 'Velocity': array([-0.20085713, 0.4396815 , -0.00113137]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25135803]), + 'frame': 18676, + 'frame_number': 18676, + 'framesequence': 75394, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.096049848944, + 'timestamp_carla': 640096, + 'timestamp_device': 1510697, + 'timestamp_stream': 640.096049848944, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16289234]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.0320402 , -0.0591042 , -2.97196913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.77927589416504, + 'FR_Wheel_Angle': -17.39963150024414, + 'Location': array([-4.07429428e+01, 9.06897049e+01, 2.12685671e-02]), + 'Rotation': array([ 2.31748298e-02, 1.25437241e+02, -3.54187012e-01]), + 'Velocity': array([-0.20174432, 0.45663977, -0.00141792]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25224304]), + 'frame': 18677, + 'frame_number': 18677, + 'framesequence': 75398, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.12975025177, + 'timestamp_carla': 640129, + 'timestamp_device': 1510731, + 'timestamp_stream': 640.12975025177, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288692]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.01195387, -0.07690311, -3.79245305]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.771223068237305, + 'FR_Wheel_Angle': -17.412309646606445, + 'Location': array([-4.07735901e+01, 9.07516556e+01, 2.11473741e-02]), + 'Rotation': array([ 1.99509822e-02, 1.24981171e+02, -3.48602325e-01]), + 'Velocity': array([-0.20327125, 0.47001991, -0.00129475]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25114441]), + 'frame': 18678, + 'frame_number': 18678, + 'framesequence': 75402, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.1616048514843, + 'timestamp_carla': 640161, + 'timestamp_device': 1510764, + 'timestamp_stream': 640.1616048514843, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287117]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.04233266, -0.07134312, -3.15842628]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.78293800354004, + 'FR_Wheel_Angle': -17.40130043029785, + 'Location': array([-4.08044930e+01, 9.08155289e+01, 2.10114196e-02]), + 'Rotation': array([ 1.66520011e-02, 1.24514954e+02, -3.42987031e-01]), + 'Velocity': array([-0.21436569, 0.4989152 , -0.00118523]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25169373]), + 'frame': 18679, + 'frame_number': 18679, + 'framesequence': 75405, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.1941549517214, + 'timestamp_carla': 640194, + 'timestamp_device': 1510789, + 'timestamp_stream': 640.1941549517214, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16286731]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.04478044, -0.02308889, -2.44021893]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.773435592651367, + 'FR_Wheel_Angle': -17.401086807250977, + 'Location': array([-4.08348007e+01, 9.08795395e+01, 2.08886229e-02]), + 'Rotation': array([ 1.34008303e-02, 1.24057236e+02, -3.37280273e-01]), + 'Velocity': array([-0.20575097, 0.48140272, -0.00119034]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25326538]), + 'frame': 18680, + 'frame_number': 18680, + 'framesequence': 75409, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.2276502512395, + 'timestamp_carla': 640227, + 'timestamp_device': 1510822, + 'timestamp_stream': 640.2276502512395, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287288]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.02735279, -0.03160213, -3.16020656]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.774194717407227, + 'FR_Wheel_Angle': -17.392553329467773, + 'Location': array([-4.08650665e+01, 9.09455719e+01, 2.07252782e-02]), + 'Rotation': array([ 9.28905699e-03, 1.23598183e+02, -3.32092226e-01]), + 'Velocity': array([-0.20141806, 0.48172733, -0.0015568 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25364685]), + 'frame': 18681, + 'frame_number': 18681, + 'framesequence': 75413, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.2604619525373, + 'timestamp_carla': 640260, + 'timestamp_device': 1510856, + 'timestamp_stream': 640.2604619525373, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287166]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.03316386, -0.03718376, -2.93462038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.639820098876953, + 'FR_Wheel_Angle': -16.52671241760254, + 'Location': array([-4.08957787e+01, 9.10135345e+01, 2.05363370e-02]), + 'Rotation': array([ 6.10618899e-03, 1.23113441e+02, -3.26263398e-01]), + 'Velocity': array([-0.20928961, 0.51278514, -0.00127802]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25309753]), + 'frame': 18682, + 'frame_number': 18682, + 'framesequence': 75417, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.2931076511741, + 'timestamp_carla': 640293, + 'timestamp_device': 1510889, + 'timestamp_stream': 640.2931076511741, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287041]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.01933665, -0.00864446, -2.27427959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.06949520111084, + 'FR_Wheel_Angle': -13.081616401672363, + 'Location': array([-4.09260330e+01, 9.10797119e+01, 2.04851814e-02]), + 'Rotation': array([ 3.28532071e-03, 1.22661774e+02, -3.23242158e-01]), + 'Velocity': array([-0.23032358, 0.52227437, -0.00109905]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2532196 ]), + 'frame': 18683, + 'frame_number': 18683, + 'framesequence': 75421, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.3265334516764, + 'timestamp_carla': 640326, + 'timestamp_device': 1510922, + 'timestamp_stream': 640.3265334516764, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287598]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.02855572, -0.04408456, -2.16496944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.1818904876709, + 'FR_Wheel_Angle': -14.976423263549805, + 'Location': array([-4.09579430e+01, 9.11462708e+01, 2.03394592e-02]), + 'Rotation': array([-1.84415097e-04, 1.22292984e+02, -3.17840517e-01]), + 'Velocity': array([-0.23163295, 0.52513254, -0.00156857]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25334167]), + 'frame': 18684, + 'frame_number': 18684, + 'framesequence': 75425, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.3603432513773, + 'timestamp_carla': 640360, + 'timestamp_device': 1510956, + 'timestamp_stream': 640.3603432513773, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288246]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0471876 , -0.04534092, -2.83443117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.45159149169922, + 'FR_Wheel_Angle': -14.10098648071289, + 'Location': array([-4.09887619e+01, 9.12136307e+01, 2.02078149e-02]), + 'Rotation': array([-3.94101907e-03, 1.21889488e+02, -3.10607880e-01]), + 'Velocity': array([-0.22665673, 0.54011387, -0.00116868]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25279236]), + 'frame': 18685, + 'frame_number': 18685, + 'framesequence': 75429, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.393435548991, + 'timestamp_carla': 640393, + 'timestamp_device': 1510989, + 'timestamp_stream': 640.393435548991, + 'transform': [array([-22.4464798, 84.5209198, -0.1628809]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.04997084, -0.07794188, -3.62929511]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.74904441833496, + 'FR_Wheel_Angle': -14.475319862365723, + 'Location': array([-4.10202980e+01, 9.12830353e+01, 2.00476740e-02]), + 'Rotation': array([-7.66347162e-03, 1.21493324e+02, -3.05358857e-01]), + 'Velocity': array([-0.22037834, 0.5395425 , -0.00151139]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25213623]), + 'frame': 18686, + 'frame_number': 18686, + 'framesequence': 75433, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.4272583499551, + 'timestamp_carla': 640427, + 'timestamp_device': 1511022, + 'timestamp_stream': 640.4272583499551, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288555]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.04754581, -0.06977353, -3.55964971]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.576082229614258, + 'FR_Wheel_Angle': -14.375181198120117, + 'Location': array([-4.10497055e+01, 9.13494034e+01, 1.99362841e-02]), + 'Rotation': array([-1.09897740e-02, 1.21123451e+02, -2.99804717e-01]), + 'Velocity': array([-0.21655461, 0.54029602, -0.00117898]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25228882]), + 'frame': 18687, + 'frame_number': 18687, + 'framesequence': 75437, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.4603758491576, + 'timestamp_carla': 640460, + 'timestamp_device': 1511056, + 'timestamp_stream': 640.4603758491576, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288291]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.0407504 , -0.07040717, -3.42414784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.627878189086914, + 'FR_Wheel_Angle': -14.370881080627441, + 'Location': array([-4.10794754e+01, 9.14177017e+01, 1.97884645e-02]), + 'Rotation': array([-1.46166040e-02, 1.20746674e+02, -2.94586182e-01]), + 'Velocity': array([-0.20881626, 0.5324598 , -0.00115676]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25183105]), + 'frame': 18688, + 'frame_number': 18688, + 'framesequence': 75441, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.4929316490889, + 'timestamp_carla': 640493, + 'timestamp_device': 1511089, + 'timestamp_stream': 640.4929316490889, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287746]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.04430898, -0.07111545, -3.59617639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.629276275634766, + 'FR_Wheel_Angle': -14.374412536621094, + 'Location': array([-4.11080360e+01, 9.14844513e+01, 1.96454898e-02]), + 'Rotation': array([-1.82775855e-02, 1.20379738e+02, -2.89794892e-01]), + 'Velocity': array([-0.20128299, 0.52204639, -0.00138259]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25209045]), + 'frame': 18689, + 'frame_number': 18689, + 'framesequence': 75445, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.5270971506834, + 'timestamp_carla': 640527, + 'timestamp_device': 1511122, + 'timestamp_stream': 640.5270971506834, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288647]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.06594297, -0.05620342, -3.04916239]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.62635612487793, + 'FR_Wheel_Angle': -14.367403030395508, + 'Location': array([-4.11363907e+01, 9.15518417e+01, 1.94940083e-02]), + 'Rotation': array([-2.10847929e-02, 1.20013687e+02, -2.84545839e-01]), + 'Velocity': array([-0.20483726, 0.53276509, -0.00158603]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25263977]), + 'frame': 18690, + 'frame_number': 18690, + 'framesequence': 75449, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.5610406510532, + 'timestamp_carla': 640561, + 'timestamp_device': 1511156, + 'timestamp_stream': 640.5610406510532, + 'transform': [array([-22.4464798, 84.5209198, -0.1628897]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.04457615, -0.0724301 , -3.66247177]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.62668228149414, + 'FR_Wheel_Angle': -14.371220588684082, + 'Location': array([-4.11641502e+01, 9.16190720e+01, 1.93605330e-02]), + 'Rotation': array([-2.33729053e-02, 1.19644196e+02, -2.78808594e-01]), + 'Velocity': array([-0.2001857 , 0.5414238 , -0.00176488]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2517395 ]), + 'frame': 18691, + 'frame_number': 18691, + 'framesequence': 75454, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.5944731496274, + 'timestamp_carla': 640594, + 'timestamp_device': 1511197, + 'timestamp_stream': 640.5944731496274, + 'transform': [array([-22.4464798, 84.5209198, -0.1628875]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.04547686, -0.0593894 , -3.23497558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.631074905395508, + 'FR_Wheel_Angle': -14.369455337524414, + 'Location': array([-4.11915207e+01, 9.16866989e+01, 1.92285441e-02]), + 'Rotation': array([-2.72797737e-02, 1.19277634e+02, -2.74383575e-01]), + 'Velocity': array([-0.19546707, 0.53168011, -0.00107252]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25141907]), + 'frame': 18692, + 'frame_number': 18692, + 'framesequence': 75457, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.6266629509628, + 'timestamp_carla': 640626, + 'timestamp_device': 1511222, + 'timestamp_stream': 640.6266629509628, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287735]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([ 0.06744838, -0.05303433, -3.01903343]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.631929397583008, + 'FR_Wheel_Angle': -14.36609172821045, + 'Location': array([-4.12186165e+01, 9.17548676e+01, 1.90786645e-02]), + 'Rotation': array([-2.97318120e-02, 1.18905388e+02, -2.68920869e-01]), + 'Velocity': array([-0.20142747, 0.55571067, -0.00108259]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25163269]), + 'frame': 18693, + 'frame_number': 18693, + 'framesequence': 75461, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.6598490513861, + 'timestamp_carla': 640660, + 'timestamp_device': 1511256, + 'timestamp_stream': 640.6598490513861, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16287868]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.0593411 , -0.01118427, -2.8214891 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.756620407104492, + 'FR_Wheel_Angle': -10.886320114135742, + 'Location': array([-4.12459793e+01, 9.18238449e+01, 1.89247802e-02]), + 'Rotation': array([-3.36864926e-02, 1.18515602e+02, -2.65258700e-01]), + 'Velocity': array([-0.18495166, 0.49697745, -0.00112221]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25265503]), + 'frame': 18694, + 'frame_number': 18694, + 'framesequence': 75465, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.6933171488345, + 'timestamp_carla': 640693, + 'timestamp_device': 1511289, + 'timestamp_stream': 640.6933171488345, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288178]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.05986763, -0.05450637, -2.48830533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.39272403717041, + 'FR_Wheel_Angle': -11.018950462341309, + 'Location': array([-4.12753563e+01, 9.18933487e+01, 1.87617783e-02]), + 'Rotation': array([-3.60702276e-02, 1.18220093e+02, -2.63030976e-01]), + 'Velocity': array([-0.20258135, 0.49833125, -0.0014093 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2525177 ]), + 'frame': 18695, + 'frame_number': 18695, + 'framesequence': 75469, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.7269530519843, + 'timestamp_carla': 640727, + 'timestamp_device': 1511322, + 'timestamp_stream': 640.7269530519843, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288486]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.03003533, -0.06285065, -3.17358613]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.07731819152832, + 'FR_Wheel_Angle': -11.251582145690918, + 'Location': array([-4.13044662e+01, 9.19630661e+01, 1.86219681e-02]), + 'Rotation': array([-3.91847938e-02, 1.17911873e+02, -2.54577637e-01]), + 'Velocity': array([-0.19666319, 0.52384633, -0.00118076]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25221252]), + 'frame': 18696, + 'frame_number': 18696, + 'framesequence': 75473, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.7605629488826, + 'timestamp_carla': 640760, + 'timestamp_device': 1511356, + 'timestamp_stream': 640.7605629488826, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288635]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.05966919, -0.04711062, -2.77303839]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.190918922424316, + 'FR_Wheel_Angle': -11.114240646362305, + 'Location': array([-4.13335152e+01, 9.20345840e+01, 1.84645746e-02]), + 'Rotation': array([-4.23198491e-02, 1.17597084e+02, -2.49908477e-01]), + 'Velocity': array([-0.19744663, 0.52010578, -0.00135931]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25189209]), + 'frame': 18697, + 'frame_number': 18697, + 'framesequence': 75477, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.7932338491082, + 'timestamp_carla': 640793, + 'timestamp_device': 1511389, + 'timestamp_stream': 640.7932338491082, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288029]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.03737222, -0.05271002, -2.99247646]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.49327278137207, + 'FR_Wheel_Angle': -11.081681251525879, + 'Location': array([-4.13625832e+01, 9.21067657e+01, 1.83170605e-02]), + 'Rotation': array([-4.56256606e-02, 1.17274094e+02, -2.44110122e-01]), + 'Velocity': array([-0.19763558, 0.53609377, -0.00145574]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25175476]), + 'frame': 18698, + 'frame_number': 18698, + 'framesequence': 75481, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.8263842500746, + 'timestamp_carla': 640826, + 'timestamp_device': 1511422, + 'timestamp_stream': 640.8263842500746, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288029]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.04027739, -0.00945446, -1.6010741 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.499682426452637, + 'FR_Wheel_Angle': -11.149666786193848, + 'Location': array([-4.13911972e+01, 9.21792297e+01, 1.81450937e-02]), + 'Rotation': array([-4.80025671e-02, 1.16969719e+02, -2.40325883e-01]), + 'Velocity': array([-0.20132911, 0.5439406 , -0.00128227]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25234985]), + 'frame': 18699, + 'frame_number': 18699, + 'framesequence': 75485, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 640.8605772517622, + 'timestamp_carla': 640860, + 'timestamp_device': 1511455, + 'timestamp_stream': 640.8605772517622, + 'transform': [array([-22.4464798 , 84.5209198 , -0.16288833]), + array([ 6.98250234e-02, -9.46017685e+01, 4.51748781e-02])]} +{'AngularVelocity': array([-0.03315513, -0.00967829, -1.35982883]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.454752922058105, + 'FR_Wheel_Angle': -11.131438255310059, + 'Location': array([-4.14193687e+01, 9.22517624e+01, 1.79494377e-02]), + 'Rotation': array([-5.07483035e-02, 1.16672028e+02, -2.37853989e-01]), + 'Velocity': array([-0.1908308 , 0.52661663, -0.00151997]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.25234985]), + 'frame': 18700, + 'frame_number': 18700, + 'framesequence': 75489, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.051590751856565475, + 'timestamp': 640.8930197507143, + 'timestamp_carla': 640893, + 'timestamp_device': 1511489, + 'timestamp_stream': 640.8930197507143, + 'transform': [array([-22.44652939, 84.52045441, -0.16291019]), + array([ 6.98864907e-02, -9.46036606e+01, 4.53114957e-02])]} +{'AngularVelocity': array([-0.02829284, -0.0088314 , -1.4795866 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.453476905822754, + 'FR_Wheel_Angle': -11.130145072937012, + 'Location': array([-4.14468880e+01, 9.23236694e+01, 1.77399721e-02]), + 'Rotation': array([-5.18138111e-02, 1.16376610e+02, -2.34924287e-01]), + 'Velocity': array([-0.19030114, 0.53256267, -0.0018829 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.88671875, 10083.18945312, 130.2515564 ]), + 'frame': 18701, + 'frame_number': 18701, + 'framesequence': 75493, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0793621763586998, + 'timestamp': 640.9276304505765, + 'timestamp_carla': 640927, + 'timestamp_device': 1511522, + 'timestamp_stream': 640.9276304505765, + 'transform': [array([-22.44640732, 84.52045441, -0.16292159]), + array([ 6.98864907e-02, -9.46036606e+01, 4.53114957e-02])]} +{'AngularVelocity': array([ 0.01163909, -0.0520406 , -2.28783798]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.457263946533203, + 'FR_Wheel_Angle': -11.132410049438477, + 'Location': array([-4.14736481e+01, 9.23947449e+01, 1.75567903e-02]), + 'Rotation': array([-5.31935096e-02, 1.16085945e+02, -2.31964067e-01]), + 'Velocity': array([-0.18792979, 0.54978514, -0.00157474]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.373046875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.81445312, 10083.72753906, 130.29177856]), + 'frame': 18702, + 'frame_number': 18702, + 'framesequence': 75497, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.08332952111959457, + 'timestamp': 640.958849452436, + 'timestamp_carla': 640958, + 'timestamp_device': 1511555, + 'timestamp_stream': 640.958849452436, + 'transform': [array([-22.44637489, 84.52045441, -0.16290405]), + array([ 6.98864907e-02, -9.46036606e+01, 4.53114957e-02])]} +{'AngularVelocity': array([ 0.01362208, -0.05407986, -2.54136586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.45643424987793, + 'FR_Wheel_Angle': -11.133234977722168, + 'Location': array([-4.15006943e+01, 9.24672928e+01, 1.73449982e-02]), + 'Rotation': array([-5.47234714e-02, 1.15771751e+02, -2.28942826e-01]), + 'Velocity': array([-0.1865748 , 0.5555684 , -0.00206196]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.384765625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.81445312, 10083.72851562, 130.29063416]), + 'frame': 18703, + 'frame_number': 18703, + 'framesequence': 75501, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.08729686588048935, + 'timestamp': 640.9923603497446, + 'timestamp_carla': 640992, + 'timestamp_device': 1511589, + 'timestamp_stream': 640.9923603497446, + 'transform': [array([-22.4462738 , 84.52045441, -0.16290961]), + array([ 6.98864907e-02, -9.46036606e+01, 4.53114957e-02])]} +{'AngularVelocity': array([-0.00996538, -0.22571616, -2.26273632]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.460394859313965, + 'FR_Wheel_Angle': -11.13488483428955, + 'Location': array([-4.15269127e+01, 9.25395203e+01, 1.72508135e-02]), + 'Rotation': array([-6.02764152e-02, 1.15471962e+02, -2.19116196e-01]), + 'Velocity': array([-1.77581474e-01, 5.48739016e-01, 8.47721094e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.388671875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.81445312, 10083.72851562, 130.29238892]), + 'frame': 18704, + 'frame_number': 18704, + 'framesequence': 75505, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1111009418964386, + 'timestamp': 641.0276408493519, + 'timestamp_carla': 641027, + 'timestamp_device': 1511622, + 'timestamp_stream': 641.0276408493519, + 'transform': [array([-22.44613266, 84.52045441, -0.16292748]), + array([ 6.98864907e-02, -9.46036606e+01, 4.53114957e-02])]} +{'AngularVelocity': array([-0.04198553, -0.27567258, -2.27518702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.727716445922852, + 'FR_Wheel_Angle': -9.38685417175293, + 'Location': array([-4.15523338e+01, 9.26123047e+01, 1.75564103e-02]), + 'Rotation': array([-8.08147937e-02, 1.15182938e+02, -1.86737075e-01]), + 'Velocity': array([-0.17405616, 0.54604554, 0.00134917]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.3984375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.8125 , 10083.72949219, 130.2918396 ]), + 'frame': 18705, + 'frame_number': 18705, + 'framesequence': 75509, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.13888761401176453, + 'timestamp': 641.0612023510039, + 'timestamp_carla': 641061, + 'timestamp_device': 1511655, + 'timestamp_stream': 641.0612023510039, + 'transform': [array([-22.446064 , 84.52045441, -0.1629235 ]), + array([ 6.98864907e-02, -9.46036606e+01, 4.53114957e-02])]} +{'AngularVelocity': array([-0.05992972, -0.2419216 , -1.32598734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.53232479095459, + 'FR_Wheel_Angle': -6.498745441436768, + 'Location': array([-4.15782661e+01, 9.26837006e+01, 1.79598518e-02]), + 'Rotation': array([-1.02111325e-01, 1.14961342e+02, -1.57653779e-01]), + 'Velocity': array([-0.19861509, 0.54014945, 0.00188035]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.412109375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.8125 , 10083.73046875, 130.29006958]), + 'frame': 18706, + 'frame_number': 18706, + 'framesequence': 75513, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.15475699305534363, + 'timestamp': 641.0938747487962, + 'timestamp_carla': 641093, + 'timestamp_device': 1511689, + 'timestamp_stream': 641.0938747487962, + 'transform': [array([-22.44605827, 84.52046967, -0.16291469]), + array([ 6.98864907e-02, -9.46036606e+01, 4.53114957e-02])]} +{'AngularVelocity': array([-0.02661906, -0.24595593, -1.5460453 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.093485832214355, + 'FR_Wheel_Angle': -8.325325012207031, + 'Location': array([-4.16062546e+01, 9.27561493e+01, 1.82598010e-02]), + 'Rotation': array([ -0.12108558, 114.79420471, -0.12811278]), + 'Velocity': array([-0.19341192, 0.53957754, 0.00082734]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.419921875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.81445312, 10083.73144531, 130.29046631]), + 'frame': 18707, + 'frame_number': 18707, + 'framesequence': 75517, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.16665904223918915, + 'timestamp': 641.1265878491104, + 'timestamp_carla': 641126, + 'timestamp_device': 1511722, + 'timestamp_stream': 641.1265878491104, + 'transform': [array([-22.44610214, 84.52051544, -0.1629322 ]), + array([ 6.98864907e-02, -9.46035385e+01, 4.54071201e-02])]} +{'AngularVelocity': array([-0.03818012, -0.20836081, -1.53770351]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.986968994140625, + 'FR_Wheel_Angle': -7.41680908203125, + 'Location': array([-4.16332207e+01, 9.28289948e+01, 1.84973814e-02]), + 'Rotation': array([-1.38215706e-01, 1.14590218e+02, -1.00250222e-01]), + 'Velocity': array([-0.19043916, 0.54042405, 0.00058708]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.421875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.81640625, 10083.73242188, 130.29136658]), + 'frame': 18708, + 'frame_number': 18708, + 'framesequence': 75521, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17062638700008392, + 'timestamp': 641.1600630506873, + 'timestamp_carla': 641160, + 'timestamp_device': 1511755, + 'timestamp_stream': 641.1600630506873, + 'transform': [array([-22.44621468, 84.52055359, -0.16295978]), + array([ 6.99206442e-02, -9.46034393e+01, 4.55163941e-02])]} +{'AngularVelocity': array([ 0.00220619, -0.04282352, -1.64552748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.45832633972168, + 'FR_Wheel_Angle': -7.773174285888672, + 'Location': array([-4.16605721e+01, 9.29012604e+01, 1.85001660e-02]), + 'Rotation': array([-1.45168826e-01, 1.14390320e+02, -9.05151442e-02]), + 'Velocity': array([-0.19487593, 0.54788011, -0.00090308]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.416015625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.8203125 , 10083.69824219, 130.31945801]), + 'frame': 18709, + 'frame_number': 18709, + 'framesequence': 75525, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17062638700008392, + 'timestamp': 641.1928961500525, + 'timestamp_carla': 641192, + 'timestamp_device': 1511789, + 'timestamp_stream': 641.1928961500525, + 'transform': [array([-22.44643974, 84.52060699, -0.16299304]), + array([ 6.99479654e-02, -9.46033096e+01, 4.56734933e-02])]} +{'AngularVelocity': array([-1.12106814e-03, -3.45610641e-02, -1.66953993e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.279348373413086, + 'FR_Wheel_Angle': -7.71492862701416, + 'Location': array([-4.16881981e+01, 9.29750977e+01, 1.82480905e-02]), + 'Rotation': array([-1.45933807e-01, 1.14176308e+02, -8.82263035e-02]), + 'Velocity': array([-0.19080995, 0.54492825, -0.00207182]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.40625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.82226562, 10083.671875 , 130.35067749]), + 'frame': 18710, + 'frame_number': 18710, + 'framesequence': 75530, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1745937317609787, + 'timestamp': 641.2268445491791, + 'timestamp_carla': 641226, + 'timestamp_device': 1511830, + 'timestamp_stream': 641.2268445491791, + 'transform': [array([-22.44678879, 84.52067566, -0.16303965]), + array([ 7.00026080e-02, -9.46031952e+01, 4.58510779e-02])]} +{'AngularVelocity': array([ 0.00197604, -0.03215583, -1.70462275]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.317134857177734, + 'FR_Wheel_Angle': -7.701247215270996, + 'Location': array([-4.17148247e+01, 9.30469131e+01, 1.80443097e-02]), + 'Rotation': array([-1.46398261e-01, 1.13968010e+02, -8.63036811e-02]), + 'Velocity': array([-0.19191162, 0.55348164, -0.00133877]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.384765625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.828125 , 10083.6328125 , 130.39624023]), + 'frame': 18711, + 'frame_number': 18711, + 'framesequence': 75533, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1745937317609787, + 'timestamp': 641.2599649503827, + 'timestamp_carla': 641260, + 'timestamp_device': 1511855, + 'timestamp_stream': 641.2599649503827, + 'transform': [array([-22.44734764, 84.52075195, -0.16309848]), + array([ 7.00982288e-02, -9.46030655e+01, 4.61242832e-02])]} +{'AngularVelocity': array([ 0.00256868, -0.03743099, -1.59379864]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.315528869628906, + 'FR_Wheel_Angle': -7.700334548950195, + 'Location': array([-4.17418823e+01, 9.31208496e+01, 1.77981090e-02]), + 'Rotation': array([-1.47614047e-01, 1.13758377e+02, -8.44726488e-02]), + 'Velocity': array([-0.186505 , 0.54771483, -0.00190925]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.35546875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.8359375 , 10083.60351562, 130.44677734]), + 'frame': 18712, + 'frame_number': 18712, + 'framesequence': 75538, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1745937317609787, + 'timestamp': 641.2939546518028, + 'timestamp_carla': 641294, + 'timestamp_device': 1511897, + 'timestamp_stream': 641.2939546518028, + 'transform': [array([-22.44823456, 84.52085876, -0.16320339]), + array([ 7.02553242e-02, -9.46029129e+01, 4.65682521e-02])]} +{'AngularVelocity': array([-0.07019006, -0.01694947, -1.32213843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.312187194824219, + 'FR_Wheel_Angle': -7.696076393127441, + 'Location': array([-4.17683868e+01, 9.31939316e+01, 1.75770856e-02]), + 'Rotation': array([-1.48863971e-01, 1.13545837e+02, -8.29467699e-02]), + 'Velocity': array([-0.17557427, 0.51221502, -0.00161547]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.298828125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.8359375 , 10083.56738281, 130.52578735]), + 'frame': 18713, + 'frame_number': 18713, + 'framesequence': 75542, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 641.3308507502079, + 'timestamp_carla': 641330, + 'timestamp_device': 1511930, + 'timestamp_stream': 641.3308507502079, + 'transform': [array([-22.45074844, 84.51959991, -0.16355793]), + array([ 7.07675889e-02, -9.46090164e+01, 4.80299108e-02])]} +{'AngularVelocity': array([-0.06852309, -0.05706661, -1.19205356]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.31074333190918, + 'FR_Wheel_Angle': -7.695398807525635, + 'Location': array([-4.17942238e+01, 9.32664261e+01, 1.73897836e-02]), + 'Rotation': array([-1.50079742e-01, 1.13361794e+02, -7.94982985e-02]), + 'Velocity': array([-0.17711607, 0.52441603, -0.00123362]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16545.212890625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.84375 , 10083.52246094, 130.65324402]), + 'frame': 18714, + 'frame_number': 18714, + 'framesequence': 75545, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 641.3611138500273, + 'timestamp_carla': 641361, + 'timestamp_device': 1511955, + 'timestamp_stream': 641.3611138500273, + 'transform': [array([-22.45394897, 84.51825714, -0.16384925]), + array([ 7.12320358e-02, -9.46156921e+01, 4.94779050e-02])]} +{'AngularVelocity': array([-0.08204874, -0.06750976, -1.24149466]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.310510635375977, + 'FR_Wheel_Angle': -7.695690631866455, + 'Location': array([-4.18203316e+01, 9.33407822e+01, 1.72844213e-02]), + 'Rotation': array([-1.55052111e-01, 1.13176613e+02, -7.13500828e-02]), + 'Velocity': array([-0.1757628 , 0.52595949, -0.00107757]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16544.91015625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.61523438, 10085.2734375 , 131.0718689 ]), + 'frame': 18715, + 'frame_number': 18715, + 'framesequence': 75549, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 641.3935902491212, + 'timestamp_carla': 641393, + 'timestamp_device': 1511989, + 'timestamp_stream': 641.3935902491212, + 'transform': [array([-22.45863724, 84.5177002 , -0.16427884]), + array([ 7.19013959e-02, -9.46193695e+01, 5.14244996e-02])]} +{'AngularVelocity': array([-0.04304184, -0.01020479, -1.21774673]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.310150146484375, + 'FR_Wheel_Angle': -7.383148193359375, + 'Location': array([-4.18461761e+01, 9.34148941e+01, 1.71703231e-02]), + 'Rotation': array([-1.59266338e-01, 1.12990479e+02, -6.50634840e-02]), + 'Velocity': array([-0.18156961, 0.54436368, -0.00156739]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16544.529296875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.359375 , 10087.18554688, 131.49269104]), + 'frame': 18716, + 'frame_number': 18716, + 'framesequence': 75553, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 641.4256160520017, + 'timestamp_carla': 641425, + 'timestamp_device': 1512022, + 'timestamp_stream': 641.4256160520017, + 'transform': [array([-22.46377945, 84.52031708, -0.16465172]), + array([ 7.23863393e-02, -9.46099548e+01, 5.31115606e-02])]} +{'AngularVelocity': array([-0.0390841 , 0.0242993 , -1.63297689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.560410499572754, + 'FR_Wheel_Angle': -2.3896825313568115, + 'Location': array([-4.18729286e+01, 9.34898605e+01, 1.69166457e-02]), + 'Rotation': array([-1.58207670e-01, 1.12808617e+02, -6.81762695e-02]), + 'Velocity': array([-0.19428293, 0.54691708, -0.00172168]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16544.03125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.22265625, 10088.23339844, 132.05439758]), + 'frame': 18717, + 'frame_number': 18717, + 'framesequence': 75557, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.17856107652187347, + 'timestamp': 641.4595322497189, + 'timestamp_carla': 641459, + 'timestamp_device': 1512055, + 'timestamp_stream': 641.4595322497189, + 'transform': [array([-22.47002602, 84.51931763, -0.1647816 ]), + array([ 7.25092813e-02, -9.46162415e+01, 5.36784753e-02])]} +{'AngularVelocity': array([-0.01731851, -0.05614528, -1.27843142]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.081676006317139, + 'FR_Wheel_Angle': -4.6823577880859375, + 'Location': array([-4.19021721e+01, 9.35650482e+01, 1.66711323e-02]), + 'Rotation': array([-1.58562839e-01, 1.12715851e+02, -6.85425028e-02]), + 'Velocity': array([-0.21175689, 0.55472314, -0.00141653]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16543.60546875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.578125 , 10085.53710938, 132.54144287]), + 'frame': 18718, + 'frame_number': 18718, + 'framesequence': 75561, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18252842128276825, + 'timestamp': 641.4939694516361, + 'timestamp_carla': 641494, + 'timestamp_device': 1512089, + 'timestamp_stream': 641.4939694516361, + 'transform': [array([-22.47728539, 84.51963043, -0.16512416]), + array([ 7.26049095e-02, -9.46172638e+01, 5.51811121e-02])]} +{'AngularVelocity': array([-0.03519664, -0.01456753, -1.63285923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.297976016998291, + 'FR_Wheel_Angle': -3.7113256454467773, + 'Location': array([-4.19304810e+01, 9.36404648e+01, 1.64909642e-02]), + 'Rotation': array([-1.60823628e-01, 1.12588913e+02, -6.18590973e-02]), + 'Velocity': array([-0.2010951 , 0.55830568, -0.00163034]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16542.92578125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.34179688, 10087.33496094, 132.70428467]), + 'frame': 18719, + 'frame_number': 18719, + 'framesequence': 75565, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18252842128276825, + 'timestamp': 641.5262381508946, + 'timestamp_carla': 641526, + 'timestamp_device': 1512122, + 'timestamp_stream': 641.5262381508946, + 'transform': [array([-22.48570061, 84.5186615 , -0.16551746]), + array([ 7.24136606e-02, -9.46240845e+01, 5.69706112e-02])]} +{'AngularVelocity': array([-0.06850677, -0.01934512, -0.80780452]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.129870414733887, + 'FR_Wheel_Angle': -4.136326789855957, + 'Location': array([-4.19604759e+01, 9.37200089e+01, 1.62063502e-02]), + 'Rotation': array([-1.60946563e-01, 1.12467552e+02, -6.24084212e-02]), + 'Velocity': array([-0.20147114, 0.54491967, -0.00203851]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16542.189453125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.30078125, 10087.625 , 133.13786316]), + 'frame': 18720, + 'frame_number': 18720, + 'framesequence': 75569, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18252842128276825, + 'timestamp': 641.5595318488777, + 'timestamp_carla': 641559, + 'timestamp_device': 1512155, + 'timestamp_stream': 641.5595318488777, + 'transform': [array([-22.49498749, 84.51994324, -0.1659262 ]), + array([ 7.22907186e-02, -9.46217880e+01, 5.88079467e-02])]} +{'AngularVelocity': array([-0.05148082, -0.01213685, -0.68509096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.098602294921875, + 'FR_Wheel_Angle': -3.9423515796661377, + 'Location': array([-4.19885864e+01, 9.37951431e+01, 1.60101987e-02]), + 'Rotation': array([-1.61677405e-01, 1.12365700e+02, -6.16149791e-02]), + 'Velocity': array([-0.19879749, 0.54549962, -0.00109539]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16541.2890625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.04492188, 10089.57324219, 133.65658569]), + 'frame': 18721, + 'frame_number': 18721, + 'framesequence': 75573, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18252842128276825, + 'timestamp': 641.5930183492601, + 'timestamp_carla': 641593, + 'timestamp_device': 1512189, + 'timestamp_stream': 641.5930183492601, + 'transform': [array([-22.50496864, 84.52078247, -0.16614608]), + array([ 7.22633973e-02, -9.46215057e+01, 5.98597936e-02])]} +{'AngularVelocity': array([-0.02773996, -0.02631641, -1.25426745]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.164227485656738, + 'FR_Wheel_Angle': -3.9993996620178223, + 'Location': array([-4.20167389e+01, 9.38705826e+01, 1.57439318e-02]), + 'Rotation': array([-1.61711544e-01, 1.12254311e+02, -6.11572228e-02]), + 'Velocity': array([-0.19836044, 0.55322385, -0.00215475]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16540.3828125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.13476562, 10088.9140625 , 134.18843079]), + 'frame': 18722, + 'frame_number': 18722, + 'framesequence': 75577, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.6263134516776, + 'timestamp_carla': 641626, + 'timestamp_device': 1512222, + 'timestamp_stream': 641.6263134516776, + 'transform': [array([-22.51589394, 84.52207947, -0.16642497]), + array([ 7.20243379e-02, -9.46197357e+01, 6.11643754e-02])]} +{'AngularVelocity': array([-0.03328879, -0.01237738, -1.56885254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.1599016189575195, + 'FR_Wheel_Angle': -3.9988603591918945, + 'Location': array([-4.20451050e+01, 9.39470291e+01, 1.55004403e-02]), + 'Rotation': array([-1.61315396e-01, 1.12126167e+02, -6.06384017e-02]), + 'Velocity': array([-0.20254108, 0.56449693, -0.00189975]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16539.388671875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.14453125, 10088.83300781, 134.49365234]), + 'frame': 18723, + 'frame_number': 18723, + 'framesequence': 75581, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.659485951066, + 'timestamp_carla': 641659, + 'timestamp_device': 1512255, + 'timestamp_stream': 641.659485951066, + 'transform': [array([-22.52794456, 84.52459717, -0.16688675]), + array([ 7.18672499e-02, -9.46132202e+01, 6.32748976e-02])]} +{'AngularVelocity': array([-0.04579038, -0.01764745, -1.44376159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.159717082977295, + 'FR_Wheel_Angle': -3.99918532371521, + 'Location': array([-4.20735817e+01, 9.40245743e+01, 1.52501957e-02]), + 'Rotation': array([-1.61499813e-01, 1.12001663e+02, -6.02416918e-02]), + 'Velocity': array([-0.19953802, 0.56184614, -0.00178118]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16538.3125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.2109375 , 10088.328125 , 134.87243652]), + 'frame': 18724, + 'frame_number': 18724, + 'framesequence': 75585, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.6923119500279, + 'timestamp_carla': 641692, + 'timestamp_device': 1512289, + 'timestamp_stream': 641.6923119500279, + 'transform': [array([-22.54090118, 84.5245285 , -0.1671273 ]), + array([ 7.18399286e-02, -9.46178055e+01, 6.44770116e-02])]} +{'AngularVelocity': array([-0.04680246, -0.01937631, -1.47288275]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.159714221954346, + 'FR_Wheel_Angle': -3.997960090637207, + 'Location': array([-4.21023445e+01, 9.41033859e+01, 1.49920937e-02]), + 'Rotation': array([-1.61738873e-01, 1.11879318e+02, -5.99060059e-02]), + 'Velocity': array([-0.19864072, 0.56330526, -0.00194019]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16537.16796875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.45703125, 10086.46289062, 135.4838562 ]), + 'frame': 18725, + 'frame_number': 18725, + 'framesequence': 75589, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.7268113493919, + 'timestamp_carla': 641726, + 'timestamp_device': 1512322, + 'timestamp_stream': 641.7268113493919, + 'transform': [array([-22.55526543, 84.52613068, -0.16747399]), + array([ 7.16828331e-02, -9.46159439e+01, 6.60821050e-02])]} +{'AngularVelocity': array([-0.02117883, -0.01222589, -1.41980481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.158383846282959, + 'FR_Wheel_Angle': -3.9984335899353027, + 'Location': array([-4.21305466e+01, 9.41811829e+01, 1.47508141e-02]), + 'Rotation': array([-1.61650077e-01, 1.11755409e+02, -5.94176985e-02]), + 'Velocity': array([-0.20380403, 0.58202618, -0.00161156]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16535.828125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.28320312, 10087.76953125, 135.83335876]), + 'frame': 18726, + 'frame_number': 18726, + 'framesequence': 75593, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.7613707520068, + 'timestamp_carla': 641761, + 'timestamp_device': 1512355, + 'timestamp_stream': 641.7613707520068, + 'transform': [array([-22.57157135, 84.52452087, -0.16796929]), + array([ 7.17511326e-02, -9.46282196e+01, 6.83770403e-02])]} +{'AngularVelocity': array([-0.01111637, 0.20009789, -1.33631158]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.1595377922058105, + 'FR_Wheel_Angle': -3.998485565185547, + 'Location': array([-4.21592178e+01, 9.42607803e+01, 1.45360846e-02]), + 'Rotation': array([-1.59580529e-01, 1.11630859e+02, -6.51245192e-02]), + 'Velocity': array([-2.02583611e-01, 5.85575461e-01, 2.53238686e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16534.41015625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.35351562, 10087.24023438, 136.29820251]), + 'frame': 18727, + 'frame_number': 18727, + 'framesequence': 75597, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.7922252491117, + 'timestamp_carla': 641792, + 'timestamp_device': 1512389, + 'timestamp_stream': 641.7922252491117, + 'transform': [array([-22.58612061, 84.52739716, -0.16831729]), + array([ 7.16828331e-02, -9.46209335e+01, 7.01392442e-02])]} +{'AngularVelocity': array([-0.00630095, 0.25455546, -1.26044071]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.37447190284729, + 'FR_Wheel_Angle': -0.730910062789917, + 'Location': array([-4.21873474e+01, 9.43393860e+01, 1.45947933e-02]), + 'Rotation': array([-1.46760270e-01, 1.11510399e+02, -9.33837742e-02]), + 'Velocity': array([-0.19879873, 0.57352936, 0.00202748]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16532.66796875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.89257812, 10090.75 , 136.96209717]), + 'frame': 18728, + 'frame_number': 18728, + 'framesequence': 75601, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.8254211507738, + 'timestamp_carla': 641825, + 'timestamp_device': 1512422, + 'timestamp_stream': 641.8254211507738, + 'transform': [array([-22.6025486 , 84.52934265, -0.16864124]), + array([ 7.15598911e-02, -9.46183243e+01, 7.17101917e-02])]} +{'AngularVelocity': array([-0.00590171, 0.27346057, -0.12701797]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.5252019166946411, + 'FR_Wheel_Angle': 0.800944447517395, + 'Location': array([-4.22167168e+01, 9.44158707e+01, 1.47089288e-02]), + 'Rotation': array([ -0.13253298, 111.48542023, -0.12606812]), + 'Velocity': array([-0.2310407 , 0.56945217, 0.00184453]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16531.279296875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.16796875, 10088.66015625, 137.47531128]), + 'frame': 18729, + 'frame_number': 18729, + 'framesequence': 75605, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.8600751496851, + 'timestamp_carla': 641860, + 'timestamp_device': 1512455, + 'timestamp_stream': 641.8600751496851, + 'transform': [array([-22.62049675, 84.53138733, -0.16899818]), + array([ 7.14642629e-02, -9.46157990e+01, 7.34040588e-02])]} +{'AngularVelocity': array([-0.02946228, 0.03217071, 0.11169852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.7714720368385315, + 'FR_Wheel_Angle': -0.49420225620269775, + 'Location': array([-4.22472267e+01, 9.44924698e+01, 1.47807980e-02]), + 'Rotation': array([ -0.12079189, 111.50224304, -0.14767453]), + 'Velocity': array([-2.09773988e-01, 5.42683423e-01, -5.73348989e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16529.66015625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.265625 , 10087.91308594, 137.93115234]), + 'frame': 18730, + 'frame_number': 18730, + 'framesequence': 75610, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.18649576604366302, + 'timestamp': 641.8947704508901, + 'timestamp_carla': 641894, + 'timestamp_device': 1512497, + 'timestamp_stream': 641.8947704508901, + 'transform': [array([-22.63944817, 84.53279877, -0.16938461]), + array([ 7.15257376e-02, -9.46162720e+01, 7.52755404e-02])]} +{'AngularVelocity': array([-0.05350753, 0.00969938, 0.2553696 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.34466519951820374, + 'FR_Wheel_Angle': 0.22040671110153198, + 'Location': array([-4.22769966e+01, 9.45690689e+01, 1.46164224e-02]), + 'Rotation': array([ -0.11816227, 111.51380157, -0.15158083]), + 'Velocity': array([-0.21524915, 0.54430574, -0.00136103]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16527.88671875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.36132812, 10087.19726562, 138.42163086]), + 'frame': 18731, + 'frame_number': 18731, + 'framesequence': 75614, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 641.9281955510378, + 'timestamp_carla': 641928, + 'timestamp_device': 1512530, + 'timestamp_stream': 641.9281955510378, + 'transform': [array([-22.65863228, 84.53527832, -0.16987148]), + array([ 7.13823065e-02, -9.46124039e+01, 7.76114762e-02])]} +{'AngularVelocity': array([-5.62031083e-02, 7.80302362e-05, 1.29672689e-02]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.12289781123399734, + 'FR_Wheel_Angle': -0.037992361932992935, + 'Location': array([-4.23073730e+01, 9.46460800e+01, 1.43917371e-02]), + 'Rotation': array([ -0.1167894 , 111.53462982, -0.15512088]), + 'Velocity': array([-0.21020727, 0.53469765, -0.00127559]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16525.986328125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.34179688, 10087.33398438, 138.96372986]), + 'frame': 18732, + 'frame_number': 18732, + 'framesequence': 75618, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 641.961473852396, + 'timestamp_carla': 641961, + 'timestamp_device': 1512564, + 'timestamp_stream': 641.961473852396, + 'transform': [array([-22.67910194, 84.53681183, -0.17041233]), + array([ 7.13823065e-02, -9.46129532e+01, 8.02001208e-02])]} +{'AngularVelocity': array([-0.04471689, 0.01663191, 0.10271055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.021536698564887047, + 'FR_Wheel_Angle': -0.025341574102640152, + 'Location': array([-4.23368073e+01, 9.47207336e+01, 1.41944019e-02]), + 'Rotation': array([ -0.1146174 , 111.53697205, -0.15948485]), + 'Velocity': array([-0.21301319, 0.53925556, -0.00118513]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16524.103515625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.48828125, 10086.2265625 , 139.64117432]), + 'frame': 18733, + 'frame_number': 18733, + 'framesequence': 75622, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.19839780032634735, + 'timestamp': 641.9945400506258, + 'timestamp_carla': 641994, + 'timestamp_device': 1512597, + 'timestamp_stream': 641.9945400506258, + 'transform': [array([-22.7003746 , 84.53843689, -0.17092854]), + array([ 7.14369416e-02, -9.46132889e+01, 8.26999620e-02])]} +{'AngularVelocity': array([-0.05158383, 0.01459996, 0.24620584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0139329694211483, + 'FR_Wheel_Angle': 0.013934717513620853, + 'Location': array([-4.23669243e+01, 9.47972794e+01, 1.39914220e-02]), + 'Rotation': array([ -0.11196729, 111.56075287, -0.16433714]), + 'Velocity': array([-0.21300916, 0.53951836, -0.00133736]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16522.05078125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.46679688, 10086.38378906, 140.39103699]), + 'frame': 18734, + 'frame_number': 18734, + 'framesequence': 75625, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.20236514508724213, + 'timestamp': 642.0270432494581, + 'timestamp_carla': 642027, + 'timestamp_device': 1512622, + 'timestamp_stream': 642.0270432494581, + 'transform': [array([-22.72229958, 84.53965759, -0.17143856]), + array([ 7.14642629e-02, -9.46155319e+01, 8.51861611e-02])]} +{'AngularVelocity': array([-0.0587806 , 0.01268845, -0.0060453 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.013934615068137646, + 'FR_Wheel_Angle': 0.01393910963088274, + 'Location': array([-4.23970795e+01, 9.48737946e+01, 1.38031673e-02]), + 'Rotation': array([-1.09535739e-01, 1.11576622e+02, -1.69433564e-01]), + 'Velocity': array([-0.21196012, 0.53661615, -0.00116105]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16519.921875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.45507812, 10086.48339844, 141.11521912]), + 'frame': 18735, + 'frame_number': 18735, + 'framesequence': 75629, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2063324898481369, + 'timestamp': 642.0589199513197, + 'timestamp_carla': 642059, + 'timestamp_device': 1512655, + 'timestamp_stream': 642.0589199513197, + 'transform': [array([-22.7445755 , 84.54124451, -0.17193137]), + array([ 7.14984164e-02, -9.46163483e+01, 8.76108706e-02])]} +{'AngularVelocity': array([ 0.08443765, -0.11297736, -0.12541379]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.013933337293565273, + 'FR_Wheel_Angle': 0.013936989940702915, + 'Location': array([-4.24269028e+01, 9.49492493e+01, 1.37234777e-02]), + 'Rotation': array([-1.02329887e-01, 1.11568665e+02, -1.63482636e-01]), + 'Velocity': array([-0.21364616, 0.5385955 , 0.0013626 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16517.70703125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.36914062, 10087.12207031, 141.83555603]), + 'frame': 18736, + 'frame_number': 18736, + 'framesequence': 75633, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21031509339809418, + 'timestamp': 642.0934538505971, + 'timestamp_carla': 642093, + 'timestamp_device': 1512689, + 'timestamp_stream': 642.0934538505971, + 'transform': [array([-22.76976204, 84.54143524, -0.17243691]), + array([ 7.16555119e-02, -9.46240845e+01, 9.00356099e-02])]} +{'AngularVelocity': array([ 0.11160384, -0.12877037, 0.21466248]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.013935120776295662, + 'FR_Wheel_Angle': 0.013936428353190422, + 'Location': array([-4.24570045e+01, 9.50257111e+01, 1.38613414e-02]), + 'Rotation': array([-8.61491710e-02, 1.11580681e+02, -1.39862075e-01]), + 'Velocity': array([-0.21089263, 0.53088742, 0.00185804]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16515.47265625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.33789062, 10087.35546875, 142.53822327]), + 'frame': 18737, + 'frame_number': 18737, + 'framesequence': 75637, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21824978291988373, + 'timestamp': 642.1255720518529, + 'timestamp_carla': 642125, + 'timestamp_device': 1512722, + 'timestamp_stream': 642.1255720518529, + 'transform': [array([-22.79350853, 84.54344177, -0.17286861]), + array([ 7.16828331e-02, -9.46236801e+01, 9.22280997e-02])]} +{'AngularVelocity': array([ 0.12431293, -0.11791571, -0.01148507]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.013934832066297531, + 'FR_Wheel_Angle': 0.013942485675215721, + 'Location': array([-4.24862251e+01, 9.50998688e+01, 1.40367029e-02]), + 'Rotation': array([-7.01938495e-02, 1.11590927e+02, -1.17767304e-01]), + 'Velocity': array([-0.21328382, 0.53669447, 0.00227559]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16512.8828125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.05078125, 10089.56445312, 143.23846436]), + 'frame': 18738, + 'frame_number': 18738, + 'framesequence': 75641, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 642.1589974500239, + 'timestamp_carla': 642159, + 'timestamp_device': 1512755, + 'timestamp_stream': 642.1589974500239, + 'transform': [array([-22.81877327, 84.54725647, -0.1734114 ]), + array([ 7.17169791e-02, -9.46162720e+01, 9.48508680e-02])]} +{'AngularVelocity': array([ 0.05155727, -0.03104497, 0.5750165 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.027877431362867355, + 'FR_Wheel_Angle': 0.5499663352966309, + 'Location': array([-4.25161514e+01, 9.51756973e+01, 1.41664790e-02]), + 'Rotation': array([-5.45322262e-02, 1.11602341e+02, -9.74731371e-02]), + 'Velocity': array([-0.21555635, 0.5437724 , 0.00081126]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16510.509765625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.0625 , 10089.45410156, 143.8742981 ]), + 'frame': 18739, + 'frame_number': 18739, + 'framesequence': 75645, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 642.193120252341, + 'timestamp_carla': 642193, + 'timestamp_device': 1512789, + 'timestamp_stream': 642.193120252341, + 'transform': [array([-22.8457489 , 84.55005646, -0.17402431]), + array([ 7.17511326e-02, -9.46135788e+01, 9.77810323e-02])]} +{'AngularVelocity': array([-0.04495698, 0.02140232, 0.42817095]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.7354960441589355, + 'FR_Wheel_Angle': 5.94218635559082, + 'Location': array([-4.25457954e+01, 9.52488632e+01, 1.40889259e-02]), + 'Rotation': array([-4.97442633e-02, 1.11632011e+02, -1.00158669e-01]), + 'Velocity': array([-0.22294216, 0.51659089, -0.00088392]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16508.05078125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.34179688, 10087.3359375 , 144.63272095]), + 'frame': 18740, + 'frame_number': 18740, + 'framesequence': 75649, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.225243549794, + 'timestamp_carla': 642225, + 'timestamp_device': 1512822, + 'timestamp_stream': 642.225243549794, + 'transform': [array([-22.87248039, 84.55233002, -0.17472546]), + array([ 7.17784539e-02, -9.46130447e+01, 1.01161979e-01])]} +{'AngularVelocity': array([-0.00654981, -0.03593681, 0.72883743]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.896367073059082, + 'FR_Wheel_Angle': 3.2856576442718506, + 'Location': array([-4.25782890e+01, 9.53214645e+01, 1.39488121e-02]), + 'Rotation': array([-4.53114733e-02, 1.11748230e+02, -1.02874741e-01]), + 'Velocity': array([-2.35960379e-01, 5.14162600e-01, -3.16810590e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16505.376953125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.4453125 , 10086.56640625, 145.47921753]), + 'frame': 18741, + 'frame_number': 18741, + 'framesequence': 75653, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.2589516490698, + 'timestamp_carla': 642259, + 'timestamp_device': 1512855, + 'timestamp_stream': 642.2589516490698, + 'transform': [array([-22.90213394, 84.55430603, -0.17559898]), + array([ 7.17784539e-02, -9.46147461e+01, 1.05239592e-01])]} +{'AngularVelocity': array([0.01480406, 0.01702603, 0.29344678]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9676127433776855, + 'FR_Wheel_Angle': 4.528238773345947, + 'Location': array([-4.26104813e+01, 9.53954239e+01, 1.38003062e-02]), + 'Rotation': array([-3.99156250e-02, 1.11829071e+02, -1.00341797e-01]), + 'Velocity': array([-0.2404445 , 0.54320139, -0.00085259]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16502.708984375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.46289062, 10086.41308594, 146.45697021]), + 'frame': 18742, + 'frame_number': 18742, + 'framesequence': 75657, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.2928124517202, + 'timestamp_carla': 642293, + 'timestamp_device': 1512889, + 'timestamp_stream': 642.2928124517202, + 'transform': [array([-22.93330002, 84.55662537, -0.17648083]), + array([ 7.17784539e-02, -9.46155014e+01, 1.09378695e-01])]} +{'AngularVelocity': array([-0.00136863, -0.02071038, 0.20967777]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9644930362701416, + 'FR_Wheel_Angle': 3.951462745666504, + 'Location': array([-4.26432381e+01, 9.54697647e+01, 1.36663336e-02]), + 'Rotation': array([-3.52164544e-02, 1.11934677e+02, -1.01135232e-01]), + 'Velocity': array([-0.2361774 , 0.52266133, -0.00080744]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16499.73046875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.3984375 , 10086.90039062, 147.63356018]), + 'frame': 18743, + 'frame_number': 18743, + 'framesequence': 75661, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.3261136524379, + 'timestamp_carla': 642326, + 'timestamp_device': 1512922, + 'timestamp_stream': 642.3261136524379, + 'transform': [array([-22.96512604, 84.55923462, -0.17730671]), + array([ 7.17511326e-02, -9.46152267e+01, 1.13312885e-01])]} +{'AngularVelocity': array([ 0.02776559, -0.00191813, 0.28202078]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.064577579498291, + 'FR_Wheel_Angle': 4.215007781982422, + 'Location': array([-4.26756325e+01, 9.55425568e+01, 1.35767264e-02]), + 'Rotation': array([-3.05855852e-02, 1.12027275e+02, -1.00677460e-01]), + 'Velocity': array([-2.38511935e-01, 5.25913358e-01, 1.39427184e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16496.607421875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.36914062, 10087.1171875 , 148.82775879]), + 'frame': 18744, + 'frame_number': 18744, + 'framesequence': 75665, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.3593459501863, + 'timestamp_carla': 642359, + 'timestamp_device': 1512955, + 'timestamp_stream': 642.3593459501863, + 'transform': [array([-22.99802589, 84.56164551, -0.17808941]), + array([ 7.17169791e-02, -9.46161652e+01, 1.17076322e-01])]} +{'AngularVelocity': array([ 0.00225942, -0.02125473, 0.30331475]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9957735538482666, + 'FR_Wheel_Angle': 4.180169582366943, + 'Location': array([-4.27071686e+01, 9.56129150e+01, 1.34547325e-02]), + 'Rotation': array([-2.51760762e-02, 1.12111343e+02, -1.00585938e-01]), + 'Velocity': array([-0.2349209 , 0.51526308, -0.00107346]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16493.4296875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.37890625, 10087.03613281, 149.96331787]), + 'frame': 18745, + 'frame_number': 18745, + 'framesequence': 75669, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.3928782492876, + 'timestamp_carla': 642393, + 'timestamp_device': 1512988, + 'timestamp_stream': 642.3928782492876, + 'transform': [array([-23.0324173 , 84.56352997, -0.17886086]), + array([ 7.16828331e-02, -9.46198044e+01, 1.20798796e-01])]} +{'AngularVelocity': array([ 0.01219046, -0.01507061, 0.26972315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.989140510559082, + 'FR_Wheel_Angle': 4.148853778839111, + 'Location': array([-4.27388535e+01, 9.56834030e+01, 1.33435726e-02]), + 'Rotation': array([-2.05725282e-02, 1.12202171e+02, -1.00433350e-01]), + 'Velocity': array([-0.23332219, 0.51032919, -0.00062338]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16490.130859375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.34375 , 10087.30371094, 151.04940796]), + 'frame': 18746, + 'frame_number': 18746, + 'framesequence': 75673, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.4253021515906, + 'timestamp_carla': 642425, + 'timestamp_device': 1513022, + 'timestamp_stream': 642.4253021515906, + 'transform': [array([-23.06644058, 84.56523132, -0.1795264 ]), + array([ 7.16555119e-02, -9.46241074e+01, 1.24104582e-01])]} +{'AngularVelocity': array([ 0.01123156, -0.01480038, -0.00086082]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9883925914764404, + 'FR_Wheel_Angle': 4.148705005645752, + 'Location': array([-4.27704735e+01, 9.57534637e+01, 1.32388966e-02]), + 'Rotation': array([-1.52244912e-02, 1.12292221e+02, -1.00524887e-01]), + 'Velocity': array([-0.23437227, 0.51059365, -0.00058403]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16486.66015625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.20898438, 10088.34082031, 152.12307739]), + 'frame': 18747, + 'frame_number': 18747, + 'framesequence': 75677, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.4586946517229, + 'timestamp_carla': 642458, + 'timestamp_device': 1513055, + 'timestamp_stream': 642.4586946517229, + 'transform': [array([-23.10214806, 84.56723785, -0.18019816]), + array([ 7.16213584e-02, -9.46277542e+01, 1.27417266e-01])]} +{'AngularVelocity': array([ 0.00368032, -0.01935452, -0.13835615]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.98881196975708, + 'FR_Wheel_Angle': 4.149293899536133, + 'Location': array([-4.28024025e+01, 9.58239441e+01, 1.31314751e-02]), + 'Rotation': array([-1.01633212e-02, 1.12384285e+02, -1.00585938e-01]), + 'Velocity': array([-0.23353365, 0.50643361, -0.00068776]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16483.21875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20050.04882812, 10089.56445312, 153.07737732]), + 'frame': 18748, + 'frame_number': 18748, + 'framesequence': 75681, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.4916851520538, + 'timestamp_carla': 642491, + 'timestamp_device': 1513088, + 'timestamp_stream': 642.4916851520538, + 'transform': [array([-23.13795853, 84.5701828 , -0.18086876]), + array([ 7.16213584e-02, -9.46274490e+01, 1.30750388e-01])]} +{'AngularVelocity': array([ 0.01119769, -0.0148113 , 0.2188368 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9890859127044678, + 'FR_Wheel_Angle': 4.1489973068237305, + 'Location': array([-4.28347092e+01, 9.58948746e+01, 1.30152795e-02]), + 'Rotation': array([-4.94505651e-03, 1.12479431e+02, -1.00738518e-01]), + 'Velocity': array([-0.2364594 , 0.51013315, -0.00078192]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16479.61328125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.91210938, 10090.60253906, 154.03242493]), + 'frame': 18749, + 'frame_number': 18749, + 'framesequence': 75685, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.525525148958, + 'timestamp_carla': 642525, + 'timestamp_device': 1513122, + 'timestamp_stream': 642.525525148958, + 'transform': [array([-23.17566299, 84.57311249, -0.18165535]), + array([ 7.15872124e-02, -9.46278229e+01, 1.34568438e-01])]} +{'AngularVelocity': array([-0.00019569, -0.02258514, -0.00123957]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9890966415405273, + 'FR_Wheel_Angle': 4.1492815017700195, + 'Location': array([-4.28664474e+01, 9.59642181e+01, 1.29238414e-02]), + 'Rotation': array([-3.41509440e-05, 1.12567802e+02, -1.00799561e-01]), + 'Velocity': array([-2.34140977e-01, 5.03367901e-01, -4.45446960e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16476.033203125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.92382812, 10090.51953125, 154.9934845 ]), + 'frame': 18750, + 'frame_number': 18750, + 'framesequence': 75689, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.55911995098, + 'timestamp_carla': 642559, + 'timestamp_device': 1513155, + 'timestamp_stream': 642.55911995098, + 'transform': [array([-23.21399879, 84.57592773, -0.18245998]), + array([ 7.16213584e-02, -9.46288986e+01, 1.38495833e-01])]} +{'AngularVelocity': array([ 0.00213313, -0.00639689, 0.59272647]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.3536834716796875, + 'FR_Wheel_Angle': 8.581467628479004, + 'Location': array([-4.28989067e+01, 9.60346451e+01, 1.28113842e-02]), + 'Rotation': array([ 5.05433977e-03, 1.12668762e+02, -1.01531960e-01]), + 'Velocity': array([-2.40357757e-01, 5.02453268e-01, -4.14829236e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16472.259765625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.91015625, 10090.625 , 156.09289551]), + 'frame': 18751, + 'frame_number': 18751, + 'framesequence': 75693, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.5926363505423, + 'timestamp_carla': 642592, + 'timestamp_device': 1513188, + 'timestamp_stream': 642.5926363505423, + 'transform': [array([-23.25312042, 84.5789566 , -0.18330516]), + array([ 7.16213584e-02, -9.46293182e+01, 1.42607599e-01])]} +{'AngularVelocity': array([0.05943465, 0.04990562, 1.31545472]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.710792541503906, + 'FR_Wheel_Angle': 8.609067916870117, + 'Location': array([-4.29334335e+01, 9.61036682e+01, 1.26986597e-02]), + 'Rotation': array([ 1.07165659e-02, 1.12860085e+02, -1.05743386e-01]), + 'Velocity': array([-0.28624943, 0.52505529, -0.00086044]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16468.4140625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.87109375, 10090.921875 , 157.22357178]), + 'frame': 18752, + 'frame_number': 18752, + 'framesequence': 75697, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.6253150515258, + 'timestamp_carla': 642625, + 'timestamp_device': 1513222, + 'timestamp_stream': 642.6253150515258, + 'transform': [array([-23.29220009, 84.58204651, -0.18416935]), + array([ 7.16555119e-02, -9.46295013e+01, 1.46828666e-01])]} +{'AngularVelocity': array([0.06910585, 0.02632836, 0.91308534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.147972583770752, + 'FR_Wheel_Angle': 8.126266479492188, + 'Location': array([-4.29685287e+01, 9.61735840e+01, 1.25829978e-02]), + 'Rotation': array([ 1.59553215e-02, 1.13091232e+02, -1.02508552e-01]), + 'Velocity': array([-2.72258282e-01, 5.28985798e-01, -3.34844575e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16464.49609375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.8515625 , 10091.03808594, 158.40689087]), + 'frame': 18753, + 'frame_number': 18753, + 'framesequence': 75701, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.659885250032, + 'timestamp_carla': 642659, + 'timestamp_device': 1513255, + 'timestamp_stream': 642.659885250032, + 'transform': [array([-23.33446312, 84.58515167, -0.18510185]), + array([ 7.16828331e-02, -9.46306915e+01, 1.51309326e-01])]} +{'AngularVelocity': array([0.05499069, 0.04868688, 1.17920208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.967607498168945, + 'FR_Wheel_Angle': 8.380058288574219, + 'Location': array([-4.30021324e+01, 9.62405853e+01, 1.25107095e-02]), + 'Rotation': array([ 2.12009065e-02, 1.13300049e+02, -1.03546157e-01]), + 'Velocity': array([-0.27976608, 0.52403146, -0.0007103 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16460.587890625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.84375 , 10091.08984375, 159.62158203]), + 'frame': 18754, + 'frame_number': 18754, + 'framesequence': 75705, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.691946849227, + 'timestamp_carla': 642691, + 'timestamp_device': 1513288, + 'timestamp_stream': 642.691946849227, + 'transform': [array([-23.37446404, 84.58838654, -0.18596809]), + array([ 7.17169791e-02, -9.46305618e+01, 1.55578136e-01])]} +{'AngularVelocity': array([0.06449144, 0.04136274, 1.14721298]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.6333184242248535, + 'FR_Wheel_Angle': 8.35845947265625, + 'Location': array([-4.30367622e+01, 9.63086777e+01, 1.24024488e-02]), + 'Rotation': array([ 2.63303779e-02, 1.13519951e+02, -1.03271477e-01]), + 'Velocity': array([-0.27822125, 0.52315193, -0.00092358]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16456.353515625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.80273438, 10091.4296875 , 160.90859985]), + 'frame': 18755, + 'frame_number': 18755, + 'framesequence': 75710, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.7273267507553, + 'timestamp_carla': 642727, + 'timestamp_device': 1513330, + 'timestamp_stream': 642.7273267507553, + 'transform': [array([-23.41939926, 84.5918045 , -0.18692565]), + array([ 7.17169791e-02, -9.46313858e+01, 1.60168052e-01])]} +{'AngularVelocity': array([ 0.03208205, -0.00093689, 0.37518612]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.6534552574157715, + 'FR_Wheel_Angle': 8.274757385253906, + 'Location': array([-4.30717392e+01, 9.63766098e+01, 1.23087596e-02]), + 'Rotation': array([ 3.18764895e-02, 1.13731239e+02, -1.03729233e-01]), + 'Velocity': array([-0.27269873, 0.5058434 , -0.00070057]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16452.35546875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.80859375, 10091.38671875, 162.13652039]), + 'frame': 18756, + 'frame_number': 18756, + 'framesequence': 75713, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.7597882524133, + 'timestamp_carla': 642759, + 'timestamp_device': 1513355, + 'timestamp_stream': 642.7597882524133, + 'transform': [array([-23.46139145, 84.59512329, -0.1878123 ]), + array([ 7.17169791e-02, -9.46315994e+01, 1.64546192e-01])]} +{'AngularVelocity': array([0.04622166, 0.01584923, 0.82210267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7061381340026855, + 'FR_Wheel_Angle': 8.322694778442383, + 'Location': array([-4.31087265e+01, 9.64472504e+01, 1.21765798e-02]), + 'Rotation': array([ 3.67805660e-02, 1.13942726e+02, -1.03301987e-01]), + 'Velocity': array([-0.27574909, 0.50515395, -0.00078505]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16447.85546875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.77929688, 10091.62109375, 163.45301819]), + 'frame': 18757, + 'frame_number': 18757, + 'framesequence': 75717, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.7924677506089, + 'timestamp_carla': 642792, + 'timestamp_device': 1513388, + 'timestamp_stream': 642.7924677506089, + 'transform': [array([-23.5045414 , 84.598526 , -0.18876335]), + array([ 7.17169791e-02, -9.46319504e+01, 1.69183880e-01])]} +{'AngularVelocity': array([0.04285146, 0.01735132, 1.2969209 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7059502601623535, + 'FR_Wheel_Angle': 8.322125434875488, + 'Location': array([-4.31427345e+01, 9.65118179e+01, 1.21478559e-02]), + 'Rotation': array([ 4.20329832e-02, 1.14135658e+02, -1.03393547e-01]), + 'Velocity': array([-2.78147072e-01, 5.06282926e-01, -2.37364759e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16443.654296875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.76953125, 10091.68066406, 164.71105957]), + 'frame': 18758, + 'frame_number': 18758, + 'framesequence': 75721, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.825343452394, + 'timestamp_carla': 642825, + 'timestamp_device': 1513422, + 'timestamp_stream': 642.825343452394, + 'transform': [array([-23.54883766, 84.60201263, -0.18976307]), + array([ 7.17169791e-02, -9.46322632e+01, 1.74026489e-01])]} +{'AngularVelocity': array([0.04161243, 0.02015614, 1.26202285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7053632736206055, + 'FR_Wheel_Angle': 8.321797370910645, + 'Location': array([-4.31783447e+01, 9.65790024e+01, 1.20289130e-02]), + 'Rotation': array([ 4.74629812e-02, 1.14340233e+02, -1.03637680e-01]), + 'Velocity': array([-2.81844229e-01, 5.08943081e-01, -4.21028119e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16439.3359375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.7578125 , 10091.78417969, 166.04217529]), + 'frame': 18759, + 'frame_number': 18759, + 'framesequence': 75725, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.858153950423, + 'timestamp_carla': 642858, + 'timestamp_device': 1513455, + 'timestamp_stream': 642.858153950423, + 'transform': [array([-23.59392548, 84.60555267, -0.19078837]), + array([ 7.17169791e-02, -9.46326523e+01, 1.78985238e-01])]} +{'AngularVelocity': array([0.04788704, 0.02834859, 1.3180244 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.705347061157227, + 'FR_Wheel_Angle': 8.324268341064453, + 'Location': array([-4.32146149e+01, 9.66468811e+01, 1.19300364e-02]), + 'Rotation': array([ 5.28178513e-02, 1.14549171e+02, -1.03942864e-01]), + 'Velocity': array([-2.87530690e-01, 5.14757574e-01, -4.53720073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16434.90625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.74609375, 10091.87597656, 167.43093872]), + 'frame': 18760, + 'frame_number': 18760, + 'framesequence': 75729, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.22618448734283447, + 'timestamp': 642.8925486505032, + 'timestamp_carla': 642892, + 'timestamp_device': 1513488, + 'timestamp_stream': 642.8925486505032, + 'transform': [array([-23.64206886, 84.60933685, -0.19187321]), + array([ 7.17169791e-02, -9.46330414e+01, 1.84182957e-01])]} +{'AngularVelocity': array([ 0.44582126, -0.32092977, 1.19725096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.709536552429199, + 'FR_Wheel_Angle': 8.329011917114258, + 'Location': array([-4.32515755e+01, 9.67152405e+01, 1.20060630e-02]), + 'Rotation': array([ 6.75095841e-02, 1.14756447e+02, -8.10241625e-02]), + 'Velocity': array([-0.28868794, 0.50280291, 0.00482837]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16430.396484375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.73046875, 10091.98242188, 168.85015869]), + 'frame': 18761, + 'frame_number': 18761, + 'framesequence': 75733, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 642.9249519519508, + 'timestamp_carla': 642925, + 'timestamp_device': 1513522, + 'timestamp_stream': 642.9249519519508, + 'transform': [array([-23.68830299, 84.61296844, -0.19291523]), + array([ 7.17169791e-02, -9.46334076e+01, 1.89257815e-01])]} +{'AngularVelocity': array([ 0.36527824, -0.23266438, 0.29105762]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.927220344543457, + 'FR_Wheel_Angle': 9.741219520568848, + 'Location': array([-4.32870064e+01, 9.67801666e+01, 1.25818150e-02]), + 'Rotation': array([ 1.00506231e-01, 1.14955849e+02, -2.40173284e-02]), + 'Velocity': array([-0.28106529, 0.48832342, 0.00516977]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16425.578125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.71484375, 10092.09277344, 170.33970642]), + 'frame': 18762, + 'frame_number': 18762, + 'framesequence': 75737, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1587243527173996, + 'timestamp': 642.958992049098, + 'timestamp_carla': 642959, + 'timestamp_device': 1513555, + 'timestamp_stream': 642.958992049098, + 'transform': [array([-23.73766708, 84.61685181, -0.19400646]), + array([ 7.17169791e-02, -9.46337814e+01, 1.94517046e-01])]} +{'AngularVelocity': array([ 0.32027301, -0.25089222, 1.32783806]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.418890953063965, + 'FR_Wheel_Angle': 14.195038795471191, + 'Location': array([-4.33238869e+01, 9.68445892e+01, 1.32181831e-02]), + 'Rotation': array([1.33072570e-01, 1.15194443e+02, 2.94856988e-02]), + 'Velocity': array([-0.28392333, 0.44702616, 0.00546981]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16420.953125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.70117188, 10092.19824219, 171.79322815]), + 'frame': 18763, + 'frame_number': 18763, + 'framesequence': 75741, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.09919890016317368, + 'timestamp': 642.9926989488304, + 'timestamp_carla': 642992, + 'timestamp_device': 1513588, + 'timestamp_stream': 642.9926989488304, + 'transform': [array([-23.78717041, 84.6207428 , -0.19503944]), + array([ 7.17169791e-02, -9.46341705e+01, 1.99557811e-01])]} +{'AngularVelocity': array([ 0.46574509, -0.35328549, 2.04761147]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.584606170654297, + 'FR_Wheel_Angle': 11.591228485107422, + 'Location': array([-4.33615799e+01, 9.69059372e+01, 1.37763498e-02]), + 'Rotation': array([1.64484605e-01, 1.15500717e+02, 8.32959861e-02]), + 'Velocity': array([-0.29691055, 0.45554644, 0.00619597]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16416.015625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.6875 , 10092.3046875 , 173.29707336]), + 'frame': 18764, + 'frame_number': 18764, + 'framesequence': 75745, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0634927898645401, + 'timestamp': 643.0258079506457, + 'timestamp_carla': 643025, + 'timestamp_device': 1513622, + 'timestamp_stream': 643.0258079506457, + 'transform': [array([-23.83622169, 84.62458801, -0.19599731]), + array([ 7.17169791e-02, -9.46345291e+01, 2.04297870e-01])]} +{'AngularVelocity': array([ 0.49482667, -0.31465971, 1.71518552]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.365485191345215, + 'FR_Wheel_Angle': 12.897964477539062, + 'Location': array([-4.33983841e+01, 9.69668655e+01, 1.44069958e-02]), + 'Rotation': array([ 0.19913416, 115.76840973, 0.14685468]), + 'Velocity': array([-0.2956017 , 0.45404682, 0.00684606]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16411.05859375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.66992188, 10092.40917969, 174.73809814]), + 'frame': 18765, + 'frame_number': 18765, + 'framesequence': 75750, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.043656062334775925, + 'timestamp': 643.0617568492889, + 'timestamp_carla': 643061, + 'timestamp_device': 1513663, + 'timestamp_stream': 643.0617568492889, + 'transform': [array([-23.88951111, 84.62878418, -0.1969416 ]), + array([ 7.17169791e-02, -9.46349335e+01, 2.08935603e-01])]} +{'AngularVelocity': array([ 0.3757861 , -0.20127235, 2.15698695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.035563468933105, + 'FR_Wheel_Angle': 12.349055290222168, + 'Location': array([-4.34349251e+01, 9.70262985e+01, 1.50976079e-02]), + 'Rotation': array([ 0.23049839, 116.06040192, 0.20104043]), + 'Velocity': array([-0.29489449, 0.44781426, 0.00753061]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16406.154296875, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.66015625, 10092.51464844, 176.09286499]), + 'frame': 18766, + 'frame_number': 18766, + 'framesequence': 75753, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0035889768041670322, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.0942207500339, + 'timestamp_carla': 643094, + 'timestamp_device': 1513688, + 'timestamp_stream': 643.0942207500339, + 'transform': [array([-23.93767548, 84.63206482, -0.19772263]), + array([ 7.14369416e-02, -9.46377792e+01, 2.12938100e-01])]} +{'AngularVelocity': array([ 0.33174196, -0.19864887, 1.92611706]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.201006889343262, + 'FR_Wheel_Angle': 12.4854097366333, + 'Location': array([-4.34703102e+01, 9.70835114e+01, 1.60058495e-02]), + 'Rotation': array([ 0.25336584, 116.33457947, 0.24315175]), + 'Velocity': array([-0.28879738, 0.43381438, 0.0080932 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16400.8203125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.64257812, 10092.62890625, 177.41491699]), + 'frame': 18767, + 'frame_number': 18767, + 'framesequence': 75757, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.01834772899746895, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.1246638521552, + 'timestamp_carla': 643124, + 'timestamp_device': 1513722, + 'timestamp_stream': 643.1246638521552, + 'transform': [array([-23.98322296, 84.63300323, -0.1984711 ]), + array([ 7.02211708e-02, -9.46507111e+01, 2.16681018e-01])]} +{'AngularVelocity': array([ 0.32836714, -0.17349109, 2.04191279]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.160380363464355, + 'FR_Wheel_Angle': 12.492280006408691, + 'Location': array([-4.35049210e+01, 9.71388092e+01, 1.68894865e-02]), + 'Rotation': array([ 0.27471703, 116.60626984, 0.28284806]), + 'Velocity': array([-0.28779194, 0.42876574, 0.00801531]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16395.97265625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.53515625, 10093.43847656, 178.55862427]), + 'frame': 18768, + 'frame_number': 18768, + 'framesequence': 75761, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.040028076618909836, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.1584970504045, + 'timestamp_carla': 643158, + 'timestamp_device': 1513755, + 'timestamp_stream': 643.1584970504045, + 'transform': [array([-24.0343399 , 84.62978363, -0.19929637]), + array([ 6.77486435e-02, -9.46856842e+01, 2.20533222e-01])]} +{'AngularVelocity': array([ 0.32539552, -0.15008326, 2.20044446]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.167851448059082, + 'FR_Wheel_Angle': 12.495162963867188, + 'Location': array([-4.35396576e+01, 9.71934357e+01, 1.77231506e-02]), + 'Rotation': array([ 0.29485241, 116.87030792, 0.31942731]), + 'Velocity': array([-0.29119429, 0.4302364 , 0.00752361]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16391.30078125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20049.05078125, 10097.13671875, 179.62854004]), + 'frame': 18769, + 'frame_number': 18769, + 'framesequence': 75765, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06546220928430557, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.1922026500106, + 'timestamp_carla': 643192, + 'timestamp_device': 1513788, + 'timestamp_stream': 643.1922026500106, + 'transform': [array([-24.08575058, 84.62154388, -0.20007019]), + array([ 6.47911727e-02, -9.47450256e+01, 2.24119097e-01])]} +{'AngularVelocity': array([ 0.33828852, -0.1974481 , 2.62950277]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.168785095214844, + 'FR_Wheel_Angle': 12.50535774230957, + 'Location': array([-4.35747566e+01, 9.72479935e+01, 1.85015388e-02]), + 'Rotation': array([ 0.31639484, 117.1384201 , 0.36060324]), + 'Velocity': array([-0.27469593, 0.39502928, 0.00576799]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16385.869140625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20047.73632812, 10107.13574219, 180.7253418 ]), + 'frame': 18770, + 'frame_number': 18770, + 'framesequence': 75769, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09126255661249161, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.2252028509974, + 'timestamp_carla': 643225, + 'timestamp_device': 1513822, + 'timestamp_stream': 643.2252028509974, + 'transform': [array([-24.13661385, 84.60822296, -0.20080951]), + array([ 6.18268698e-02, -9.48287048e+01, 2.27561474e-01])]} +{'AngularVelocity': array([ 0.39125952, -0.19279492, 2.21571898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.166595458984375, + 'FR_Wheel_Angle': 12.495288848876953, + 'Location': array([-4.36085052e+01, 9.72995911e+01, 1.90376174e-02]), + 'Rotation': array([ 0.34257495, 117.37286377, 0.4057768 ]), + 'Velocity': array([-0.27585503, 0.39615637, 0.00552797]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16380.1953125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20045.5 , 10124.09960938, 181.74493408]), + 'frame': 18771, + 'frame_number': 18771, + 'framesequence': 75773, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11876583099365234, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.259410250932, + 'timestamp_carla': 643259, + 'timestamp_device': 1513855, + 'timestamp_stream': 643.259410250932, + 'transform': [array([-24.18987274, 84.58866119, -0.20155624]), + array([ 5.90538122e-02, -9.49435272e+01, 2.31017560e-01])]} +{'AngularVelocity': array([ 0.34437466, -0.2446817 , 2.76200294]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.17153549194336, + 'FR_Wheel_Angle': 12.504800796508789, + 'Location': array([-4.36429787e+01, 9.73523331e+01, 1.95505042e-02]), + 'Rotation': array([ 0.37064019, 117.62708282, 0.45296249]), + 'Velocity': array([-0.26137161, 0.37847206, 0.00525244]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16374.3955078125, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20042.34960938, 10148.02539062, 182.72244263]), + 'frame': 18772, + 'frame_number': 18772, + 'framesequence': 75777, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1476607620716095, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.2923233509064, + 'timestamp_carla': 643292, + 'timestamp_device': 1513888, + 'timestamp_stream': 643.2923233509064, + 'transform': [array([-24.24159431, 84.56462097, -0.20226508]), + array([ 5.66700771e-02, -9.50798035e+01, 2.34371156e-01])]} +{'AngularVelocity': array([0.07806822, 0.05665566, 1.98645413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.16823959350586, + 'FR_Wheel_Angle': 12.51585578918457, + 'Location': array([-4.36769180e+01, 9.74034424e+01, 1.99369323e-02]), + 'Rotation': array([ 0.38919783, 117.86580658, 0.48073143]), + 'Velocity': array([-0.27410057, 0.39462543, 0.00113043]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16368.1552734375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20038.02929688, 10180.85058594, 183.70030212]), + 'frame': 18773, + 'frame_number': 18773, + 'framesequence': 75781, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17503586411476135, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.3251337520778, + 'timestamp_carla': 643325, + 'timestamp_device': 1513922, + 'timestamp_stream': 643.3251337520778, + 'transform': [array([-24.29363632, 84.53556824, -0.20296603]), + array([ 5.47234714e-02, -9.52408676e+01, 2.37711161e-01])]} +{'AngularVelocity': array([-0.03192385, 0.01675075, 1.40056288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.898316383361816, + 'FR_Wheel_Angle': 17.648345947265625, + 'Location': array([-4.37110291e+01, 9.74543533e+01, 1.99550912e-02]), + 'Rotation': array([ 0.39214846, 118.11967468, 0.47687179]), + 'Velocity': array([-2.65246153e-01, 3.64496559e-01, 2.15930937e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16361.9853515625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20032.8984375 , 10219.79101562, 184.64848328]), + 'frame': 18774, + 'frame_number': 18774, + 'framesequence': 75785, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.20336315035820007, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.3587813489139, + 'timestamp_carla': 643358, + 'timestamp_device': 1513955, + 'timestamp_stream': 643.3587813489139, + 'transform': [array([-24.34744263, 84.50074768, -0.20366757]), + array([ 5.32276630e-02, -9.54311295e+01, 2.41064787e-01])]} +{'AngularVelocity': array([ 0.13419357, -0.26029018, 1.88420022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.897075653076172, + 'FR_Wheel_Angle': 16.496742248535156, + 'Location': array([-4.37471199e+01, 9.75045090e+01, 2.02459991e-02]), + 'Rotation': array([ 0.39063898, 118.43741608, 0.50048941]), + 'Velocity': array([-0.27282694, 0.33778584, 0.00409815]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16355.7333984375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20026.84179688, 10265.79882812, 185.59074402]), + 'frame': 18775, + 'frame_number': 18775, + 'framesequence': 75789, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23260597884655, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.3931252509356, + 'timestamp_carla': 643393, + 'timestamp_device': 1513988, + 'timestamp_stream': 643.3931252509356, + 'transform': [array([-24.40260124, 84.46067047, -0.20434634]), + array([ 5.22714332e-02, -9.56482620e+01, 2.44356915e-01])]} +{'AngularVelocity': array([ 0.15497319, -0.26421767, 1.77685285]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.058598518371582, + 'FR_Wheel_Angle': 16.64419937133789, + 'Location': array([-4.37824249e+01, 9.75532074e+01, 2.08969787e-02]), + 'Rotation': array([ 0.39744869, 118.74510193, 0.54931659]), + 'Velocity': array([-0.26247135, 0.3354021 , 0.00529071]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16349.2978515625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-20019.6875 , 10320.12890625, 186.5340271 ]), + 'frame': 18776, + 'frame_number': 18776, + 'framesequence': 75793, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.26104313135147095, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.4257190488279, + 'timestamp_carla': 643425, + 'timestamp_device': 1514022, + 'timestamp_stream': 643.4257190488279, + 'transform': [array([-24.45536995, 84.41822815, -0.20498699]), + array([ 5.16703799e-02, -9.58765945e+01, 2.47546539e-01])]} +{'AngularVelocity': array([ 0.16999821, -0.07951824, 2.91077709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.528158187866211, + 'FR_Wheel_Angle': 16.63981056213379, + 'Location': array([-4.38174171e+01, 9.76005478e+01, 2.18040738e-02]), + 'Rotation': array([ 0.41542575, 119.07632446, 0.57115275]), + 'Velocity': array([-0.25646788, 0.31548712, 0.00856127]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12968.421875, + 'focus_actor_name': 'SM_BusStop6_468', + 'focus_actor_pt': array([-16653.54882812, 10049.98632812, 173.06665039]), + 'frame': 18777, + 'frame_number': 18777, + 'framesequence': 75797, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2885464131832123, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.4605393521488, + 'timestamp_carla': 643460, + 'timestamp_device': 1514055, + 'timestamp_stream': 643.4605393521488, + 'transform': [array([-24.51204109, 84.36855316, -0.20565432]), + array([ 5.15747555e-02, -9.61426163e+01, 2.50831902e-01])]} +{'AngularVelocity': array([0.11680667, 0.05216989, 1.89862299]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.390149116516113, + 'FR_Wheel_Angle': 16.718952178955078, + 'Location': array([-4.38524742e+01, 9.76473236e+01, 2.29121689e-02]), + 'Rotation': array([ 0.44023299, 119.40092468, 0.58071226]), + 'Velocity': array([-0.2588492 , 0.31860888, 0.0090856 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12975.6650390625, + 'focus_actor_name': 'SM_BusStop6_468', + 'focus_actor_pt': array([-16659.51367188, 10103.11523438, 173.83218384]), + 'frame': 18778, + 'frame_number': 18778, + 'framesequence': 75802, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3185217082500458, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.4936779513955, + 'timestamp_carla': 643493, + 'timestamp_device': 1514097, + 'timestamp_stream': 643.4936779513955, + 'transform': [array([-24.56629372, 84.31742859, -0.20626533]), + array([ 5.17591722e-02, -9.64155121e+01, 2.53939629e-01])]} +{'AngularVelocity': array([0.10850929, 0.1663833 , 1.89027059]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.375481605529785, + 'FR_Wheel_Angle': 16.658103942871094, + 'Location': array([-4.38861847e+01, 9.76920776e+01, 2.37841308e-02]), + 'Rotation': array([ 0.46815479, 119.72079468, 0.58008087]), + 'Velocity': array([-0.25040454, 0.30218247, 0.0070028 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12974.8642578125, + 'focus_actor_name': 'SM_BusStop6_468', + 'focus_actor_pt': array([-16656.50976562, 10164.03320312, 174.58276367]), + 'frame': 18779, + 'frame_number': 18779, + 'framesequence': 75805, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3476729989051819, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.5253534503281, + 'timestamp_carla': 643525, + 'timestamp_device': 1514122, + 'timestamp_stream': 643.5253534503281, + 'transform': [array([-24.61865425, 84.26477051, -0.20685489]), + array([ 5.19709066e-02, -9.66959152e+01, 2.56951809e-01])]} +{'AngularVelocity': array([0.15434906, 0.15953599, 2.54744482]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.413331031799316, + 'FR_Wheel_Angle': 16.67784309387207, + 'Location': array([-4.39196053e+01, 9.77357712e+01, 2.44973656e-02]), + 'Rotation': array([ 0.49782515, 120.03144073, 0.57756454]), + 'Velocity': array([-0.25948951, 0.30664676, 0.00676071]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16322.005859375, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-19979.68164062, 10600.57910156, 190.13189697]), + 'frame': 18780, + 'frame_number': 18780, + 'framesequence': 75810, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.37349164485931396, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.5608017519116, + 'timestamp_carla': 643560, + 'timestamp_device': 1514163, + 'timestamp_stream': 643.5608017519116, + 'transform': [array([-24.67749405, 84.20249176, -0.20749778]), + array([ 5.27632087e-02, -9.70275345e+01, 2.60134727e-01])]} +{'AngularVelocity': array([-0.00930409, 0.17561017, 1.75286484]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.405803680419922, + 'FR_Wheel_Angle': 16.676828384399414, + 'Location': array([-4.39526100e+01, 9.77782516e+01, 2.50268076e-02]), + 'Rotation': array([ 0.51885527, 120.32978821, 0.55884361]), + 'Velocity': array([-0.24454711, 0.2922602 , 0.0042149 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 16336.5322265625, + 'focus_actor_name': 'BP_RepSpline108_11', + 'focus_actor_pt': array([-19988.51171875, 10682.73339844, 191.06552124]), + 'frame': 18781, + 'frame_number': 18781, + 'framesequence': 75814, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4034852087497711, + 'throttle_input': 0.035706110298633575, + 'timestamp': 643.5965097509325, + 'timestamp_carla': 643596, + 'timestamp_device': 1514197, + 'timestamp_stream': 643.5965097509325, + 'transform': [array([-24.73694992, 84.13645935, -0.20808242]), + array([ 5.40131330e-02, -9.73789444e+01, 2.63133109e-01])]} +{'AngularVelocity': array([-0.01604853, 0.20300826, 2.04121876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.409453392028809, + 'FR_Wheel_Angle': 16.684534072875977, + 'Location': array([-4.39860115e+01, 9.78210983e+01, 2.54791547e-02]), + 'Rotation': array([ 0.53661376, 120.63353729, 0.53779221]), + 'Velocity': array([-0.24406113, 0.28799745, 0.00402957]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 11582.474609375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-15262.73925781, 10196.25097656, 170.39578247]), + 'frame': 18782, + 'frame_number': 18782, + 'framesequence': 75817, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.43408307433128357, + 'throttle_input': 0.05555810034275055, + 'timestamp': 643.6252456493676, + 'timestamp_carla': 643625, + 'timestamp_device': 1514222, + 'timestamp_stream': 643.6252456493676, + 'transform': [array([-24.78481865, 84.08161163, -0.20855087]), + array([ 5.55704162e-02, -9.76713181e+01, 2.65516847e-01])]} +{'AngularVelocity': array([-0.01598336, 0.27760437, 1.51300228]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.410414695739746, + 'FR_Wheel_Angle': 16.682348251342773, + 'Location': array([-4.40187454e+01, 9.78624649e+01, 2.59274952e-02]), + 'Rotation': array([ 0.55522603, 120.92745209, 0.51431495]), + 'Velocity': array([-0.24314561, 0.28484282, 0.00512021]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 11587.71875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-15262.74121094, 10268.77148438, 171.03302002]), + 'frame': 18783, + 'frame_number': 18783, + 'framesequence': 75821, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45807063579559326, + 'throttle_input': 0.05555810034275055, + 'timestamp': 643.6591148488224, + 'timestamp_carla': 643659, + 'timestamp_device': 1514255, + 'timestamp_stream': 643.6591148488224, + 'transform': [array([-24.84205437, 84.01250458, -0.20906211]), + array([ 5.66086061e-02, -9.80387497e+01, 2.68262625e-01])]} +{'AngularVelocity': array([0.03247452, 0.28389513, 1.04732299]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.409860610961914, + 'FR_Wheel_Angle': 16.67984962463379, + 'Location': array([-4.40512009e+01, 9.79032669e+01, 2.64379010e-02]), + 'Rotation': array([ 0.57554585, 121.23064423, 0.48953307]), + 'Velocity': array([-0.25552708, 0.30013946, 0.00507676]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10886.2890625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14562.7421875 , 10234.88867188, 168.26789856]), + 'frame': 18784, + 'frame_number': 18784, + 'framesequence': 75825, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.486416220664978, + 'throttle_input': 0.05555810034275055, + 'timestamp': 643.6933534517884, + 'timestamp_carla': 643693, + 'timestamp_device': 1514288, + 'timestamp_stream': 643.6933534517884, + 'transform': [array([-24.90039062, 83.94002533, -0.2095935 ]), + array([ 5.79814725e-02, -9.84247589e+01, 2.71069795e-01])]} +{'AngularVelocity': array([0.05973601, 0.11482307, 2.34481215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.119806289672852, + 'FR_Wheel_Angle': 19.088647842407227, + 'Location': array([-4.40851517e+01, 9.79453659e+01, 2.69192029e-02]), + 'Rotation': array([ 0.59551048, 121.53701782, 0.46545652]), + 'Velocity': array([-0.25292632, 0.29467779, 0.00350195]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10892.5986328125, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14562.74121094, 10306.32226562, 168.82835388]), + 'frame': 18785, + 'frame_number': 18785, + 'framesequence': 75829, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5157872438430786, + 'throttle_input': 0.05555810034275055, + 'timestamp': 643.7254657521844, + 'timestamp_carla': 643725, + 'timestamp_device': 1514322, + 'timestamp_stream': 643.7254657521844, + 'transform': [array([-24.95577621, 83.86920929, -0.21002166]), + array([ 5.96002266e-02, -9.88022919e+01, 2.73487657e-01])]} +{'AngularVelocity': array([0.03385323, 0.31133196, 3.07233953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.707895278930664, + 'FR_Wheel_Angle': 22.26645851135254, + 'Location': array([-4.41180687e+01, 9.79840775e+01, 2.74049658e-02]), + 'Rotation': array([ 0.61331677, 121.8662796 , 0.44115245]), + 'Velocity': array([-0.28885984, 0.30129296, 0.00520554]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10899.96484375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14562.74023438, 10381.49023438, 169.40435791]), + 'frame': 18786, + 'frame_number': 18786, + 'framesequence': 75833, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5432722568511963, + 'throttle_input': 0.05555810034275055, + 'timestamp': 643.7591356523335, + 'timestamp_carla': 643759, + 'timestamp_device': 1514355, + 'timestamp_stream': 643.7591356523335, + 'transform': [array([-25.01449966, 83.79213715, -0.21013027]), + array([ 6.33295104e-02, -9.92136536e+01, 2.74778605e-01])]} +{'AngularVelocity': array([2.79597519e-03, 3.25048566e-01, 2.81928992e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.895814895629883, + 'FR_Wheel_Angle': 20.017370223999023, + 'Location': array([-4.41505013e+01, 9.80201950e+01, 2.78737154e-02]), + 'Rotation': array([ 0.62875301, 122.22145844, 0.4205088 ]), + 'Velocity': array([-0.28601134, 0.30081141, 0.0041255 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10545.6103515625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14204.73632812, 10399.68945312, 168.18083191]), + 'frame': 18787, + 'frame_number': 18787, + 'framesequence': 75837, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5714713335037231, + 'throttle_input': 0.05555810034275055, + 'timestamp': 643.7925511524081, + 'timestamp_carla': 643792, + 'timestamp_device': 1514388, + 'timestamp_stream': 643.7925511524081, + 'transform': [array([-25.07349586, 83.71290588, -0.21002166]), + array([ 6.79330602e-02, -9.96371155e+01, 2.75290906e-01])]} +{'AngularVelocity': array([-0.05070112, 0.2219274 , 2.65373182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.679927825927734, + 'FR_Wheel_Angle': 21.249183654785156, + 'Location': array([-4.41851311e+01, 9.80596085e+01, 2.81901453e-02]), + 'Rotation': array([ 0.64304179, 122.59807587, 0.39000738]), + 'Velocity': array([-0.26168999, 0.27521163, 0.00265618]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10419.560546875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14071.42773438, 10455.82421875, 167.82029724]), + 'frame': 18788, + 'frame_number': 18788, + 'framesequence': 75841, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.05555810034275055, + 'timestamp': 643.8241548500955, + 'timestamp_carla': 643824, + 'timestamp_device': 1514422, + 'timestamp_stream': 643.8241548500955, + 'transform': [array([-25.13010216, 83.63537598, -0.20982303]), + array([ 7.24478140e-02, -1.00052200e+02, 2.75447965e-01])]} +{'AngularVelocity': array([-0.06663989, 0.3307696 , 3.71455884]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.346200942993164, + 'FR_Wheel_Angle': 20.708791732788086, + 'Location': array([-4.42199631e+01, 9.80981903e+01, 2.85219476e-02]), + 'Rotation': array([ 0.65563667, 122.97716522, 0.36126062]), + 'Velocity': array([-0.2886821 , 0.29127857, 0.00325625]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10429.4697265625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14071.4296875 , 10535.02929688, 167.96798706]), + 'frame': 18789, + 'frame_number': 18789, + 'framesequence': 75845, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.059525445103645325, + 'timestamp': 643.8586097508669, + 'timestamp_carla': 643858, + 'timestamp_device': 1514455, + 'timestamp_stream': 643.8586097508669, + 'transform': [array([-25.19210625, 83.5504837 , -0.20958889]), + array([ 7.86701143e-02, -1.00508774e+02, 2.75571018e-01])]} +{'AngularVelocity': array([-0.07780505, 0.26044494, 3.61642623]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.49785804748535, + 'FR_Wheel_Angle': 20.856569290161133, + 'Location': array([-4.42544975e+01, 9.81361313e+01, 2.88572218e-02]), + 'Rotation': array([ 0.66765779, 123.33394623, 0.33490524]), + 'Velocity': array([-0.27283138, 0.27425992, 0.00271054]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7538.6826171875, + 'focus_actor_name': 'AmericanLights_Town04_34_TrafficLight', + 'focus_actor_pt': array([-11214.73242188, 10106.42773438, 154.10722351]), + 'frame': 18790, + 'frame_number': 18790, + 'framesequence': 75849, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5970519185066223, + 'throttle_input': 0.059525445103645325, + 'timestamp': 643.891755849123, + 'timestamp_carla': 643891, + 'timestamp_device': 1514488, + 'timestamp_stream': 643.891755849123, + 'transform': [array([-25.25173569, 83.47005463, -0.20935436]), + array([ 8.56642276e-02, -1.00943954e+02, 2.75823712e-01])]} +{'AngularVelocity': array([-0.07901512, 0.19547082, 2.70412517]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.452594757080078, + 'FR_Wheel_Angle': 20.848350524902344, + 'Location': array([-4.42889252e+01, 9.81733704e+01, 2.91871168e-02]), + 'Rotation': array([ 0.67925543, 123.69908905, 0.30712381]), + 'Velocity': array([-0.263809 , 0.25732461, 0.00305911]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10443.416015625, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14062.74023438, 10697.04101562, 168.09886169]), + 'frame': 18791, + 'frame_number': 18791, + 'framesequence': 75853, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.582274854183197, + 'throttle_input': 0.059525445103645325, + 'timestamp': 643.9260471500456, + 'timestamp_carla': 643926, + 'timestamp_device': 1514521, + 'timestamp_stream': 643.9260471500456, + 'transform': [array([-25.3130703 , 83.38961029, -0.20916305]), + array([ 9.35394391e-02, -1.01382881e+02, 2.76329249e-01])]} +{'AngularVelocity': array([-0.06437767, 0.16562618, 2.18104291]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.458219528198242, + 'FR_Wheel_Angle': 20.85987091064453, + 'Location': array([-4.43256226e+01, 9.82124405e+01, 2.95448583e-02]), + 'Rotation': array([ 0.6923421 , 124.08940887, 0.27724522]), + 'Velocity': array([-0.27130911, 0.26301023, 0.00348481]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10455.8046875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14062.74023438, 10778.9765625 , 168.20980835]), + 'frame': 18792, + 'frame_number': 18792, + 'framesequence': 75857, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5817804336547852, + 'throttle_input': 0.059525445103645325, + 'timestamp': 643.959908451885, + 'timestamp_carla': 643960, + 'timestamp_device': 1514555, + 'timestamp_stream': 643.959908451885, + 'transform': [array([-25.37354851, 83.31193542, -0.20898555]), + array([ 1.00922868e-01, -1.01809494e+02, 2.76855141e-01])]} +{'AngularVelocity': array([-0.06454777, 0.14882866, 2.65573359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.45107650756836, + 'FR_Wheel_Angle': 20.855173110961914, + 'Location': array([-4.43618736e+01, 9.82508163e+01, 2.98911948e-02]), + 'Rotation': array([ 0.70469105, 124.45571136, 0.25144738]), + 'Velocity': array([-0.26776084, 0.25866145, 0.00289757]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10560.5224609375, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14152.5546875 , 10879.94140625, 168.81088257]), + 'frame': 18793, + 'frame_number': 18793, + 'framesequence': 75861, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5897274613380432, + 'throttle_input': 0.059525445103645325, + 'timestamp': 643.9926623515785, + 'timestamp_carla': 643992, + 'timestamp_device': 1514588, + 'timestamp_stream': 643.9926623515785, + 'transform': [array([-25.43226433, 83.23726654, -0.20880233]), + array([ 0.10711785, -102.22141266, 0.27723777])]} +{'AngularVelocity': array([-0.07577458, 0.11326645, 3.33847523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.453107833862305, + 'FR_Wheel_Angle': 20.856632232666016, + 'Location': array([-4.43989944e+01, 9.82892532e+01, 3.02406978e-02]), + 'Rotation': array([ 0.71673954, 124.82987976, 0.22394156]), + 'Velocity': array([-0.27007797, 0.25555387, 0.00249995]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 10593.2919921875, + 'focus_actor_name': 'MultipleFloorBuilding_2', + 'focus_actor_pt': array([-14171.4296875 , 10965.36328125, 169.07073975]), + 'frame': 18794, + 'frame_number': 18794, + 'framesequence': 75865, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.598828136920929, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.0250519514084, + 'timestamp_carla': 644025, + 'timestamp_device': 1514621, + 'timestamp_stream': 644.0250519514084, + 'transform': [array([-25.49064827, 83.16343689, -0.20861022]), + array([ 0.11241808, -102.63043976, 0.27746326])]} +{'AngularVelocity': array([-0.06861597, 0.17237225, 2.07588673]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.455480575561523, + 'FR_Wheel_Angle': 20.85115623474121, + 'Location': array([-4.44359016e+01, 9.83272476e+01, 3.05556767e-02]), + 'Rotation': array([ 0.72839183, 125.2036972 , 0.19863214]), + 'Velocity': array([-0.2669284 , 0.25052243, 0.00291719]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6773.42626953125, + 'focus_actor_name': 'BP_Block05_33', + 'focus_actor_pt': array([-10424.8125 , 10232.83496094, 150.66421509]), + 'frame': 18795, + 'frame_number': 18795, + 'framesequence': 75869, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.0583777502179, + 'timestamp_carla': 644058, + 'timestamp_device': 1514655, + 'timestamp_stream': 644.0583777502179, + 'transform': [array([-25.55087662, 83.0880127 , -0.20841259]), + array([ 0.11770464, -103.05032349, 0.27762038])]} +{'AngularVelocity': array([-0.06914758, 0.13912378, 2.3444829 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.456239700317383, + 'FR_Wheel_Angle': 20.910625457763672, + 'Location': array([-4.44735336e+01, 9.83653412e+01, 3.08841225e-02]), + 'Rotation': array([ 0.74161506, 125.56972504, 0.17135747]), + 'Velocity': array([-0.27524707, 0.25307155, 0.0028297 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6553.416015625, + 'focus_actor_name': 'BP_Block05_33', + 'focus_actor_pt': array([-10202.13476562, 10233.57324219, 149.6315918 ]), + 'frame': 18796, + 'frame_number': 18796, + 'framesequence': 75873, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.0928147509694, + 'timestamp_carla': 644092, + 'timestamp_device': 1514688, + 'timestamp_stream': 644.0928147509694, + 'transform': [array([-25.61310959, 83.01110077, -0.20820217]), + array([ 0.12319612, -103.48108673, 0.27771604])]} +{'AngularVelocity': array([-0.02693792, 0.10806761, 3.56214333]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.150983810424805, + 'FR_Wheel_Angle': 26.245437622070312, + 'Location': array([-4.45118561e+01, 9.84034195e+01, 3.12176794e-02]), + 'Rotation': array([ 0.75313759, 125.96928406, 0.14477377]), + 'Velocity': array([-0.29058373, 0.26611471, 0.00226893]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6335.3427734375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9981.45898438, 10232.83691406, 148.59815979]), + 'frame': 18797, + 'frame_number': 18797, + 'framesequence': 75877, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.1239948496222, + 'timestamp_carla': 644124, + 'timestamp_device': 1514721, + 'timestamp_stream': 644.1239948496222, + 'transform': [array([-25.66953468, 82.94232941, -0.20794722]), + array([ 0.12722592, -103.86841583, 0.27749759])]} +{'AngularVelocity': array([-0.03079928, 0.05577743, 4.16525936]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.66446304321289, + 'FR_Wheel_Angle': 24.566740036010742, + 'Location': array([-4.45519829e+01, 9.84405899e+01, 3.12988162e-02]), + 'Rotation': array([ 0.75386161, 126.42015839, 0.14100234]), + 'Velocity': array([-3.27708006e-01, 2.65886426e-01, -1.02510450e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6188.029296875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9829.75195312, 10246.59570312, 147.89904785]), + 'frame': 18798, + 'frame_number': 18798, + 'framesequence': 75881, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.1592732518911, + 'timestamp_carla': 644159, + 'timestamp_device': 1514755, + 'timestamp_stream': 644.1592732518911, + 'transform': [array([-25.73327637, 82.86579895, -0.20759128]), + array([ 0.1300946 , -104.30218506, 0.2765277 ])]} +{'AngularVelocity': array([0.02280618, 0.05992427, 3.18627238]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.089683532714844, + 'FR_Wheel_Angle': 25.121009826660156, + 'Location': array([-4.45911522e+01, 9.84765320e+01, 3.13082412e-02]), + 'Rotation': array([ 0.75261849, 126.82701874, 0.14431806]), + 'Velocity': array([-3.33602756e-01, 2.83368230e-01, 2.78129563e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6162.9306640625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9797.70800781, 10282.80273438, 147.76040649]), + 'frame': 18799, + 'frame_number': 18799, + 'framesequence': 75885, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5990661382675171, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.1912685520947, + 'timestamp_carla': 644191, + 'timestamp_device': 1514788, + 'timestamp_stream': 644.1912685520947, + 'transform': [array([-25.79110718, 82.79734039, -0.20720397]), + array([ 0.13217099, -104.69243622, 0.27540755])]} +{'AngularVelocity': array([-0.04073119, 0.01387287, 4.23401976]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.45232582092285, + 'FR_Wheel_Angle': 24.908552169799805, + 'Location': array([-4.46312828e+01, 9.85129089e+01, 3.13159451e-02]), + 'Rotation': array([ 0.75217456, 127.24362946, 0.14408205]), + 'Velocity': array([-3.12172055e-01, 2.55607128e-01, -2.54058832e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6176.3857421875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9801.85839844, 10333.16699219, 147.72415161]), + 'frame': 18800, + 'frame_number': 18800, + 'framesequence': 75889, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5981139540672302, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.2261939495802, + 'timestamp_carla': 644226, + 'timestamp_device': 1514821, + 'timestamp_stream': 644.2261939495802, + 'transform': [array([-25.85383034, 82.72438049, -0.20745906]), + array([ 0.14736815, -105.11100769, 0.27876812])]} +{'AngularVelocity': array([-0.05536257, 0.01053709, 3.758533 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.32123374938965, + 'FR_Wheel_Angle': 25.0875244140625, + 'Location': array([-4.46723366e+01, 9.85493317e+01, 3.13467681e-02]), + 'Rotation': array([ 0.75135493, 127.67874146, 0.14286239]), + 'Velocity': array([-0.32799 , 0.25717777, 0.00040703]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6156.78369140625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9774.57519531, 10370.54492188, 147.51542664]), + 'frame': 18801, + 'frame_number': 18801, + 'framesequence': 75893, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5989745855331421, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.2591528519988, + 'timestamp_carla': 644259, + 'timestamp_device': 1514855, + 'timestamp_stream': 644.2591528519988, + 'transform': [array([-25.912714 , 82.65671539, -0.20902893]), + array([ 0.18166253, -105.50102234, 0.29078975])]} +{'AngularVelocity': array([-0.01503765, -0.05653748, 2.45154119]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.30216407775879, + 'FR_Wheel_Angle': 25.00116539001465, + 'Location': array([-4.47140694e+01, 9.85858154e+01, 3.13806422e-02]), + 'Rotation': array([ 0.75055581, 128.10964966, 0.14298086]), + 'Velocity': array([-0.32064599, 0.24952209, 0.00035742]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6136.17529296875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9745.46386719, 10410.42578125, 147.77589417]), + 'frame': 18802, + 'frame_number': 18802, + 'framesequence': 75897, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.059525445103645325, + 'timestamp': 644.2916478514671, + 'timestamp_carla': 644291, + 'timestamp_device': 1514888, + 'timestamp_stream': 644.2916478514671, + 'transform': [array([-25.97042465, 82.59128571, -0.21119148]), + array([ 0.22130495, -105.88064575, 0.30641809])]} +{'AngularVelocity': array([-0.01606382, -0.03407829, 3.75790596]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.33820152282715, + 'FR_Wheel_Angle': 25.01374053955078, + 'Location': array([-4.47576370e+01, 9.86237869e+01, 3.14178728e-02]), + 'Rotation': array([ 0.75048065, 128.56842041, 0.14205007]), + 'Velocity': array([-0.32066157, 0.25655872, 0.00067121]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6117.3818359375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9718.45898438, 10447.421875 , 148.97253418]), + 'frame': 18803, + 'frame_number': 18803, + 'framesequence': 75901, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0634927898645401, + 'timestamp': 644.3245216496289, + 'timestamp_carla': 644324, + 'timestamp_device': 1514921, + 'timestamp_stream': 644.3245216496289, + 'transform': [array([-26.02846336, 82.52632904, -0.21364158]), + array([ 0.26290762, -106.25984192, 0.32377476])]} +{'AngularVelocity': array([-0.03765327, 0.07639917, 4.17255878]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.34507942199707, + 'FR_Wheel_Angle': 25.019229888916016, + 'Location': array([-4.48006401e+01, 9.86604385e+01, 3.14659029e-02]), + 'Rotation': array([ 0.75028259, 129.01292419, 0.14020681]), + 'Velocity': array([-0.36063796, 0.27422324, 0.00074591]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6070.564453125, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9664.51074219, 10475.34570312, 150.40151978]), + 'frame': 18804, + 'frame_number': 18804, + 'framesequence': 75905, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.07539482414722443, + 'timestamp': 644.3596442490816, + 'timestamp_carla': 644359, + 'timestamp_device': 1514955, + 'timestamp_stream': 644.3596442490816, + 'transform': [array([-26.09000015, 82.4582901 , -0.21625607]), + array([ 0.30553484, -106.65943909, 0.3421289 ])]} +{'AngularVelocity': array([-0.03678126, 0.07114232, 4.18777752]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.34201431274414, + 'FR_Wheel_Angle': 25.01970100402832, + 'Location': array([-4.48457451e+01, 9.86980820e+01, 3.14958841e-02]), + 'Rotation': array([ 0.75012547, 129.47271729, 0.13959128]), + 'Velocity': array([-3.71434480e-01, 2.76831210e-01, 3.56063829e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6052.5556640625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9638.11621094, 10510.65136719, 152.15406799]), + 'frame': 18805, + 'frame_number': 18805, + 'framesequence': 75909, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0793621763586998, + 'timestamp': 644.3931295499206, + 'timestamp_carla': 644393, + 'timestamp_device': 1514988, + 'timestamp_stream': 644.3931295499206, + 'transform': [array([-26.14838791, 82.39459991, -0.21845691]), + array([ 0.34087422, -107.03601837, 0.35774428])]} +{'AngularVelocity': array([-0.04748625, 0.05822469, 4.3245697 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.329477310180664, + 'FR_Wheel_Angle': 25.00058937072754, + 'Location': array([-4.48915176e+01, 9.87355957e+01, 3.15592848e-02]), + 'Rotation': array([ 0.75132078, 129.93917847, 0.13494608]), + 'Velocity': array([-0.34303045, 0.25781155, 0.000791 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6062.84619140625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9638.11523438, 10555.92675781, 154.17282104]), + 'frame': 18806, + 'frame_number': 18806, + 'framesequence': 75913, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.4254438504577, + 'timestamp_carla': 644425, + 'timestamp_device': 1515021, + 'timestamp_stream': 644.4254438504577, + 'transform': [array([-26.20465088, 82.33405304, -0.22042163]), + array([ 0.37245703, -107.39608765, 0.37176138])]} +{'AngularVelocity': array([-0.0374409 , 0.10989144, 3.71855283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.330181121826172, + 'FR_Wheel_Angle': 25.002243041992188, + 'Location': array([-4.49378242e+01, 9.87730942e+01, 3.17700095e-02]), + 'Rotation': array([7.57577240e-01, 1.30432388e+02, 1.18582606e-01]), + 'Velocity': array([-0.35450661, 0.2622917 , 0.00196745]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6119.609375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9682.80859375, 10612.4375 , 156.20072937]), + 'frame': 18807, + 'frame_number': 18807, + 'framesequence': 75917, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.4585531502962, + 'timestamp_carla': 644458, + 'timestamp_device': 1515055, + 'timestamp_stream': 644.4585531502962, + 'transform': [array([-26.26222992, 82.27288055, -0.22232555]), + array([ 0.40330899, -107.76207733, 0.38533446])]} +{'AngularVelocity': array([-0.04208119, 0.09228897, 3.91086578]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.001075744628906, + 'FR_Wheel_Angle': 27.578447341918945, + 'Location': array([-4.49834480e+01, 9.88094025e+01, 3.20125856e-02]), + 'Rotation': array([7.63881505e-01, 1.30906067e+02, 1.03320941e-01]), + 'Velocity': array([-0.35811928, 0.25945044, 0.00238077]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6130.45263671875, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9683.65625 , 10654.0859375 , 157.78866577]), + 'frame': 18808, + 'frame_number': 18808, + 'framesequence': 75922, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.4939253516495, + 'timestamp_carla': 644494, + 'timestamp_device': 1515096, + 'timestamp_stream': 644.4939253516495, + 'transform': [array([-26.32361794, 82.20836639, -0.2242052 ]), + array([ 0.43406534, -108.15013885, 0.39871678])]} +{'AngularVelocity': array([-0.063719 , 0.07680102, 4.76205826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.21904945373535, + 'FR_Wheel_Angle': 30.325590133666992, + 'Location': array([-4.50323486e+01, 9.88461304e+01, 3.21911909e-02]), + 'Rotation': array([7.68901646e-01, 1.31466812e+02, 8.69985893e-02]), + 'Velocity': array([-0.37933573, 0.23798725, 0.00148907]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6141.7822265625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9684.52148438, 10696.5859375 , 159.33581543]), + 'frame': 18809, + 'frame_number': 18809, + 'framesequence': 75925, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.5266244523227, + 'timestamp_carla': 644526, + 'timestamp_device': 1515121, + 'timestamp_stream': 644.5266244523227, + 'transform': [array([-26.38053703, 82.14942932, -0.22501579]), + array([ 0.44648945, -108.50746918, 0.40485793])]} +{'AngularVelocity': array([-0.07924563, 0.05892297, 4.38282585]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.467992782592773, + 'FR_Wheel_Angle': 28.477994918823242, + 'Location': array([-4.50817528e+01, 9.88808365e+01, 3.23689543e-02]), + 'Rotation': array([7.72207499e-01, 1.32051666e+02, 7.82491341e-02]), + 'Velocity': array([-0.37192249, 0.22761194, 0.00150249]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6154.13916015625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9685.44042969, 10741.82421875, 160.87319946]), + 'frame': 18810, + 'frame_number': 18810, + 'framesequence': 75929, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.5595576502383, + 'timestamp_carla': 644559, + 'timestamp_device': 1515155, + 'timestamp_stream': 644.5595576502383, + 'transform': [array([-26.43819427, 82.09050751, -0.22515373]), + array([ 0.4503963 , -108.8670578 , 0.40662721])]} +{'AngularVelocity': array([-0.0388222 , 0.19836463, 4.68678379]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.363780975341797, + 'FR_Wheel_Angle': 29.45497703552246, + 'Location': array([-4.51305542e+01, 9.89151611e+01, 3.24851871e-02]), + 'Rotation': array([7.77644336e-01, 1.32590637e+02, 6.75365031e-02]), + 'Velocity': array([-0.42411876, 0.26206875, 0.0012517 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6165.79541015625, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9686.29101562, 10783.609375 , 161.63397217]), + 'frame': 18811, + 'frame_number': 18811, + 'framesequence': 75934, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.5931718498468, + 'timestamp_carla': 644593, + 'timestamp_device': 1515196, + 'timestamp_stream': 644.5931718498468, + 'transform': [array([-26.49730682, 82.03077698, -0.22493629]), + array([ 0.45125008, -109.23340607, 0.40617648])]} +{'AngularVelocity': array([-0.05795979, 0.14815067, 4.85062742]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.97899627685547, + 'FR_Wheel_Angle': 29.090255737304688, + 'Location': array([-4.51809807e+01, 9.89493637e+01, 3.26975137e-02]), + 'Rotation': array([7.81195998e-01, 1.33162201e+02, 5.80578186e-02]), + 'Velocity': array([-0.40913227, 0.24475424, 0.00158242]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6177.80224609375, + 'focus_actor_name': 'BP_Block05_34', + 'focus_actor_pt': array([-9687.14746094, 10825.79199219, 161.92341614]), + 'frame': 18812, + 'frame_number': 18812, + 'framesequence': 75937, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5920895934104919, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.6268164515495, + 'timestamp_carla': 644626, + 'timestamp_device': 1515221, + 'timestamp_stream': 644.6268164515495, + 'transform': [array([-26.55646515, 81.97209167, -0.22458571]), + array([ 0.45196041, -109.59621429, 0.40495396])]} +{'AngularVelocity': array([-0.01243155, -0.18287471, 4.92342806]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.10605239868164, + 'FR_Wheel_Angle': 29.151655197143555, + 'Location': array([-4.52300873e+01, 9.89818039e+01, 3.31971645e-02]), + 'Rotation': array([7.70861924e-01, 1.33698166e+02, 7.17761144e-02]), + 'Velocity': array([-0.40338603, 0.2296489 , 0.00506355]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4259.61181640625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7865.13916016, 10232.8359375 , 148.28536987]), + 'frame': 18813, + 'frame_number': 18813, + 'framesequence': 75941, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5727531313896179, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.6585842519999, + 'timestamp_carla': 644658, + 'timestamp_device': 1515255, + 'timestamp_stream': 644.6585842519999, + 'transform': [array([-26.61200142, 81.91863251, -0.22447956]), + array([ 0.4573836 , -109.93039703, 0.40540496])]} +{'AngularVelocity': array([ 0.08064916, -0.24120955, 4.26495075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.088184356689453, + 'FR_Wheel_Angle': 29.195228576660156, + 'Location': array([-4.52803459e+01, 9.90140610e+01, 3.39139849e-02]), + 'Rotation': array([7.53704488e-01, 1.34223541e+02, 9.45544094e-02]), + 'Velocity': array([-0.38327068, 0.22654323, 0.00460169]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4178.77099609375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7781.94677734, 10232.83496094, 147.62731934]), + 'frame': 18814, + 'frame_number': 18814, + 'framesequence': 75946, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5503402948379517, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.6938224509358, + 'timestamp_carla': 644693, + 'timestamp_device': 1515296, + 'timestamp_stream': 644.6938224509358, + 'transform': [array([-26.6726799 , 81.86225128, -0.22452797]), + array([ 0.46605793, -110.28749084, 0.40684667])]} +{'AngularVelocity': array([-3.13741458e-03, -2.30159536e-01, 3.77548766e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.079299926757812, + 'FR_Wheel_Angle': 29.165603637695312, + 'Location': array([-4.53263092e+01, 9.90431442e+01, 3.45874317e-02]), + 'Rotation': array([7.38500476e-01, 1.34727966e+02, 1.11785263e-01]), + 'Velocity': array([-0.34885681, 0.19158122, 0.00387224]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4106.80419921875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7707.87939453, 10232.83496094, 147.15332031]), + 'frame': 18815, + 'frame_number': 18815, + 'framesequence': 75949, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5259865522384644, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.7253418490291, + 'timestamp_carla': 644725, + 'timestamp_device': 1515321, + 'timestamp_stream': 644.7253418490291, + 'transform': [array([-26.72611809, 81.81473541, -0.22465584]), + array([ 0.4746913 , -110.59340668, 0.40880066])]} +{'AngularVelocity': array([ 0.01133249, -0.1909616 , 2.88653302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.080841064453125, + 'FR_Wheel_Angle': 29.180496215820312, + 'Location': array([-4.53750610e+01, 9.90732803e+01, 3.52690034e-02]), + 'Rotation': array([7.23856568e-01, 1.35243912e+02, 1.29963338e-01]), + 'Velocity': array([-0.36224094, 0.19242151, 0.0040171 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4032.41455078125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7631.34472656, 10232.83496094, 146.72714233]), + 'frame': 18816, + 'frame_number': 18816, + 'framesequence': 75953, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5135349631309509, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.7596860490739, + 'timestamp_carla': 644759, + 'timestamp_device': 1515355, + 'timestamp_stream': 644.7596860490739, + 'transform': [array([-26.78363228, 81.7652359 , -0.22484584]), + array([ 0.48396668, -110.9160614 , 0.41105518])]} +{'AngularVelocity': array([ 0.07778404, -0.24282554, 2.80423594]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.087453842163086, + 'FR_Wheel_Angle': 29.176340103149414, + 'Location': array([-4.54224434e+01, 9.91021042e+01, 3.58980857e-02]), + 'Rotation': array([ 0.70976591, 135.73381042, 0.14945015]), + 'Velocity': array([-0.35544166, 0.19437063, 0.00342022]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3972.93701171875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7570.00097656, 10233.66015625, 146.44308472]), + 'frame': 18817, + 'frame_number': 18817, + 'framesequence': 75957, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5175817608833313, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.7925938516855, + 'timestamp_carla': 644792, + 'timestamp_device': 1515388, + 'timestamp_stream': 644.7925938516855, + 'transform': [array([-26.83876801, 81.7184906 , -0.22466709]), + array([ 0.48539421, -111.22309113, 0.41072744])]} +{'AngularVelocity': array([ 0.06710362, -0.22596514, 2.37562466]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.092607498168945, + 'FR_Wheel_Angle': 29.186466217041016, + 'Location': array([-4.54696655e+01, 9.91300430e+01, 3.65510471e-02]), + 'Rotation': array([ 0.69329834, 136.21942139, 0.17182526]), + 'Velocity': array([-0.35533717, 0.18732183, 0.00419848]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3907.271484375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7502.76513672, 10232.8359375 , 146.12966919]), + 'frame': 18818, + 'frame_number': 18818, + 'framesequence': 75961, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.530161440372467, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.8260595500469, + 'timestamp_carla': 644826, + 'timestamp_device': 1515421, + 'timestamp_stream': 644.8260595500469, + 'transform': [array([-26.89546585, 81.67037964, -0.22422642]), + array([ 0.48280555, -111.53974915, 0.40864402])]} +{'AngularVelocity': array([ 0.12030212, -0.3168664 , 2.59434605]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.10796546936035, + 'FR_Wheel_Angle': 29.763418197631836, + 'Location': array([-4.55174904e+01, 9.91578293e+01, 3.72076705e-02]), + 'Rotation': array([ 0.675533 , 136.71469116, 0.19622272]), + 'Velocity': array([-0.34514609, 0.18286994, 0.00334078]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3848.8447265625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7442.72900391, 10232.8359375 , 145.69377136]), + 'frame': 18819, + 'frame_number': 18819, + 'framesequence': 75965, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5426679253578186, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.8583724498749, + 'timestamp_carla': 644858, + 'timestamp_device': 1515455, + 'timestamp_stream': 644.8583724498749, + 'transform': [array([-26.95103455, 81.62300873, -0.22367321]), + array([ 0.47884405, -111.85192108, 0.40586388])]} +{'AngularVelocity': array([ 0.04384193, -0.17441276, 4.21244383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.12483787536621, + 'FR_Wheel_Angle': 35.000972747802734, + 'Location': array([-4.55637970e+01, 9.91838913e+01, 3.78254578e-02]), + 'Rotation': array([ 0.65591669, 137.20736694, 0.22202486]), + 'Velocity': array([-0.38697109, 0.18300521, 0.00326767]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3790.425048828125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7382.60742188, 10232.8359375 , 145.14175415]), + 'frame': 18820, + 'frame_number': 18820, + 'framesequence': 75970, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5525376200675964, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.8934979513288, + 'timestamp_carla': 644893, + 'timestamp_device': 1515496, + 'timestamp_stream': 644.8934979513288, + 'transform': [array([-27.01223373, 81.57054138, -0.22310252]), + array([ 0.47618029, -112.19772339, 0.4030427 ])]} +{'AngularVelocity': array([ 0.10600687, -0.28560606, 3.05202889]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.823699951171875, + 'FR_Wheel_Angle': 32.747467041015625, + 'Location': array([-4.56098976e+01, 9.92073212e+01, 3.84083465e-02]), + 'Rotation': array([ 0.63764596, 137.73550415, 0.24793985]), + 'Velocity': array([-0.35274523, 0.15573412, 0.00286193]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3734.5771484375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7325.02148438, 10232.8359375 , 144.56660461]), + 'frame': 18821, + 'frame_number': 18821, + 'framesequence': 75973, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5520432591438293, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.9257963523269, + 'timestamp_carla': 644925, + 'timestamp_device': 1515521, + 'timestamp_stream': 644.9257963523269, + 'transform': [array([-27.06876564, 81.52256012, -0.22268489]), + array([ 0.47590706, -112.5161438 , 0.40132841])]} +{'AngularVelocity': array([ 0.02476744, -0.26183853, 3.72079539]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.640148162841797, + 'FR_Wheel_Angle': 33.59707260131836, + 'Location': array([-4.56564293e+01, 9.92309189e+01, 3.89736816e-02]), + 'Rotation': array([ 0.6191088 , 138.25878906, 0.27527195]), + 'Velocity': array([-0.33891818, 0.14312199, 0.00245342]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3674.617919921875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7263.05761719, 10232.8359375 , 143.96157837]), + 'frame': 18822, + 'frame_number': 18822, + 'framesequence': 75977, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5468612313270569, + 'throttle_input': 0.08729686588048935, + 'timestamp': 644.9592748507857, + 'timestamp_carla': 644959, + 'timestamp_device': 1515555, + 'timestamp_stream': 644.9592748507857, + 'transform': [array([-27.12741661, 81.47354889, -0.22219352]), + array([ 0.47499183, -112.84423828, 0.39916313])]} +{'AngularVelocity': array([ 0.02783714, -0.23456368, 4.87059641]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.773834228515625, + 'FR_Wheel_Angle': 33.2281494140625, + 'Location': array([-4.57053833e+01, 9.92551270e+01, 3.95278446e-02]), + 'Rotation': array([ 0.59984767, 138.82855225, 0.30221477]), + 'Velocity': array([-0.38186789, 0.15516274, 0.00314678]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3622.867919921875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7209.30761719, 10233.53808594, 143.49198914]), + 'frame': 18823, + 'frame_number': 18823, + 'framesequence': 75981, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5399029850959778, + 'throttle_input': 0.0634927898645401, + 'timestamp': 644.9931578524411, + 'timestamp_carla': 644993, + 'timestamp_device': 1515588, + 'timestamp_stream': 644.9931578524411, + 'transform': [array([-27.18654633, 81.42508698, -0.22155857]), + array([ 0.4733116 , -113.17195129, 0.39632827])]} +{'AngularVelocity': array([ 0.09408925, -0.20493688, 4.23609161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.78006362915039, + 'FR_Wheel_Angle': 33.44182205200195, + 'Location': array([-4.57502708e+01, 9.92768021e+01, 4.00839522e-02]), + 'Rotation': array([ 0.5828405 , 139.32778931, 0.32740858]), + 'Velocity': array([-0.38238895, 0.16210273, 0.00322782]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3613.12353515625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7194.20849609, 10250.60058594, 143.28912354]), + 'frame': 18824, + 'frame_number': 18824, + 'framesequence': 75985, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5341715812683105, + 'throttle_input': 0.0634927898645401, + 'timestamp': 645.0263425521553, + 'timestamp_carla': 645026, + 'timestamp_device': 1515621, + 'timestamp_stream': 645.0263425521553, + 'transform': [array([-27.24419403, 81.37873077, -0.22086345]), + array([ 0.47145379, -113.48838043, 0.39327496])]} +{'AngularVelocity': array([ 0.07047125, -0.17181788, 4.07105303]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.76187515258789, + 'FR_Wheel_Angle': 33.38340759277344, + 'Location': array([-4.57963028e+01, 9.92986603e+01, 4.05670814e-02]), + 'Rotation': array([ 0.56584698, 139.84973145, 0.35192016]), + 'Velocity': array([-0.38077453, 0.15532526, 0.00323044]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3603.5126953125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7179.19238281, 10267.56738281, 143.04679871]), + 'frame': 18825, + 'frame_number': 18825, + 'framesequence': 75989, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5340617299079895, + 'throttle_input': 0.0634927898645401, + 'timestamp': 645.0595854520798, + 'timestamp_carla': 645059, + 'timestamp_device': 1515655, + 'timestamp_stream': 645.0595854520798, + 'transform': [array([-27.3018055 , 81.33304596, -0.22013012]), + array([ 0.46940473, -113.80268097, 0.39005089])]} +{'AngularVelocity': array([ 0.05563378, -0.20038106, 3.26790762]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.750699996948242, + 'FR_Wheel_Angle': 33.368011474609375, + 'Location': array([-4.58434868e+01, 9.93204117e+01, 4.10775281e-02]), + 'Rotation': array([ 0.5492633 , 140.3800354 , 0.37532154]), + 'Velocity': array([-0.36763111, 0.14137834, 0.00315604]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3594.347412109375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7164.75878906, 10283.87695312, 142.79719543]), + 'frame': 18826, + 'frame_number': 18826, + 'framesequence': 75994, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5368816256523132, + 'throttle_input': 0.05555810034275055, + 'timestamp': 645.0958940498531, + 'timestamp_carla': 645095, + 'timestamp_device': 1515696, + 'timestamp_stream': 645.0958940498531, + 'transform': [array([-27.36482811, 81.28330994, -0.21928008]), + array([ 0.46734202, -114.14620972, 0.3862257 ])]} +{'AngularVelocity': array([ 0.0543788 , -0.18904346, 2.93754435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.750566482543945, + 'FR_Wheel_Angle': 33.368011474609375, + 'Location': array([-4.58920784e+01, 9.93425369e+01, 4.15783599e-02]), + 'Rotation': array([ 0.53218782, 140.90979004, 0.40081742]), + 'Velocity': array([-0.37536892, 0.1405488 , 0.00225015]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3621.4052734375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7183.44921875, 10314.55078125, 142.78453064]), + 'frame': 18827, + 'frame_number': 18827, + 'framesequence': 75998, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5406537055969238, + 'throttle_input': 0.051590751856565475, + 'timestamp': 645.127430152148, + 'timestamp_carla': 645127, + 'timestamp_device': 1515730, + 'timestamp_stream': 645.127430152148, + 'transform': [array([-27.41942787, 81.24077606, -0.21844177]), + array([ 0.46614674, -114.44247437, 0.38271484])]} +{'AngularVelocity': array([ 0.07007369, -0.21404628, 3.27167034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.75457191467285, + 'FR_Wheel_Angle': 33.4002685546875, + 'Location': array([-4.59385910e+01, 9.93629456e+01, 4.21033762e-02]), + 'Rotation': array([ 0.51498258, 141.42977905, 0.42497233]), + 'Velocity': array([-0.36011097, 0.13323611, 0.00314462]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3613.985595703125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7169.8359375 , 10333.19921875, 142.49591064]), + 'frame': 18828, + 'frame_number': 18828, + 'framesequence': 76002, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5425397753715515, + 'throttle_input': 0.0476234070956707, + 'timestamp': 645.1609747521579, + 'timestamp_carla': 645161, + 'timestamp_device': 1515763, + 'timestamp_stream': 645.1609747521579, + 'transform': [array([-27.47743988, 81.1958847 , -0.21754703]), + array([ 0.46517 , -114.75674438, 0.37888291])]} +{'AngularVelocity': array([ 0.16594282, -0.3043707 , 2.8007679 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.78269386291504, + 'FR_Wheel_Angle': 33.39982986450195, + 'Location': array([-4.59838905e+01, 9.93822632e+01, 4.24826704e-02]), + 'Rotation': array([ 0.49820763, 141.92323303, 0.44898343]), + 'Velocity': array([-0.32497561, 0.12491507, 0.00271875]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3607.7021484375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7158.12744141, 10349.23925781, 142.23873901]), + 'frame': 18829, + 'frame_number': 18829, + 'framesequence': 76005, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5416058897972107, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.1931618489325, + 'timestamp_carla': 645193, + 'timestamp_device': 1515788, + 'timestamp_stream': 645.1931618489325, + 'transform': [array([-27.53285599, 81.15349579, -0.21668182]), + array([ 0.46443236, -115.05569458, 0.37523538])]} +{'AngularVelocity': array([ 0.03365233, -0.01685296, 4.28311443]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.77488136291504, + 'FR_Wheel_Angle': 33.39351272583008, + 'Location': array([-4.60292015e+01, 9.94012680e+01, 4.29421514e-02]), + 'Rotation': array([ 0.4869788 , 142.43830872, 0.46380782]), + 'Velocity': array([-0.3633824 , 0.13833548, 0.00188736]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3601.17529296875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7145.74316406, 10366.20605469, 141.95800781]), + 'frame': 18830, + 'frame_number': 18830, + 'framesequence': 76010, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401226878166199, + 'throttle_input': 0.03967345505952835, + 'timestamp': 645.2267938517034, + 'timestamp_carla': 645226, + 'timestamp_device': 1515830, + 'timestamp_stream': 645.2267938517034, + 'transform': [array([-27.59034538, 81.10999298, -0.21579249]), + array([ 0.46391326, -115.36459351, 0.37144452])]} +{'AngularVelocity': array([ 0.01292917, -0.03602552, 4.72738647]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.95374298095703, + 'FR_Wheel_Angle': 36.859405517578125, + 'Location': array([-4.60786819e+01, 9.94218597e+01, 4.29329947e-02]), + 'Rotation': array([ 0.48695832, 143.00294495, 0.46151814]), + 'Velocity': array([-3.57699335e-01, 1.26659796e-01, -3.53670126e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3595.08154296875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7133.99414062, 10382.30175781, 141.69302368]), + 'frame': 18831, + 'frame_number': 18831, + 'framesequence': 76013, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538694441318512, + 'throttle_input': 0.0317387655377388, + 'timestamp': 645.2599791511893, + 'timestamp_carla': 645260, + 'timestamp_device': 1515855, + 'timestamp_stream': 645.2599791511893, + 'transform': [array([-27.64655685, 81.06799316, -0.21491997]), + array([ 0.46355125, -115.66517639, 0.36776298])]} +{'AngularVelocity': array([-0.0459075 , 0.09526622, 5.47673941]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.26705551147461, + 'FR_Wheel_Angle': 38.296268463134766, + 'Location': array([-4.61273689e+01, 9.94403000e+01, 4.29607667e-02]), + 'Rotation': array([ 0.48691732, 143.6131897 , 0.45796639]), + 'Velocity': array([-4.22733724e-01, 1.19093388e-01, -2.91175849e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3588.900390625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7121.88476562, 10398.88964844, 141.41760254]), + 'frame': 18832, + 'frame_number': 18832, + 'framesequence': 76018, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5389508008956909, + 'throttle_input': 0.0238040741533041, + 'timestamp': 645.2934955507517, + 'timestamp_carla': 645293, + 'timestamp_device': 1515896, + 'timestamp_stream': 645.2934955507517, + 'transform': [array([-27.70281982, 81.02638245, -0.21405169]), + array([ 0.46318924, -115.96492767, 0.36408806])]} +{'AngularVelocity': array([-1.95491803e-03, 5.51023930e-02, 4.99431515e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.823091506958008, + 'FR_Wheel_Angle': 37.12091064453125, + 'Location': array([-4.61785622e+01, 9.94581223e+01, 4.29571047e-02]), + 'Rotation': array([ 0.48567423, 144.25535583, 0.46010137]), + 'Velocity': array([-4.20518607e-01, 1.22676663e-01, -2.50034325e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3582.995361328125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7110.1328125 , 10414.98925781, 141.15193176]), + 'frame': 18833, + 'frame_number': 18833, + 'framesequence': 76021, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5397748351097107, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.3269000500441, + 'timestamp_carla': 645326, + 'timestamp_device': 1515921, + 'timestamp_stream': 645.3269000500441, + 'transform': [array([-27.7583828 , 80.98562622, -0.21320373]), + array([ 0.46278626, -116.26022339, 0.36050215])]} +{'AngularVelocity': array([ 0.03651131, -0.07996248, 5.43848848]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.5602970123291, + 'FR_Wheel_Angle': 37.77224349975586, + 'Location': array([-4.62289886e+01, 9.94752502e+01, 4.31049988e-02]), + 'Rotation': array([ 0.47781268, 144.89253235, 0.47050172]), + 'Velocity': array([-0.44778216, 0.11673312, 0.00268439]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3577.22119140625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7098.44335938, 10431.00390625, 140.88801575]), + 'frame': 18834, + 'frame_number': 18834, + 'framesequence': 76025, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.3591918498278, + 'timestamp_carla': 645359, + 'timestamp_device': 1515955, + 'timestamp_stream': 645.3591918498278, + 'transform': [array([-27.81148338, 80.94709015, -0.21239311]), + array([ 0.46245161, -116.54141998, 0.35711426])]} +{'AngularVelocity': array([-3.70376324e-03, -1.13195732e-01, 5.71238327e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.21381187438965, + 'FR_Wheel_Angle': 37.48185729980469, + 'Location': array([-4.62814941e+01, 9.94920425e+01, 4.35035974e-02]), + 'Rotation': array([ 0.46397471, 145.53538513, 0.48971334]), + 'Velocity': array([-0.42402732, 0.09940581, 0.00223972]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3571.6494140625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7086.95605469, 10446.74121094, 140.63180542]), + 'frame': 18835, + 'frame_number': 18835, + 'framesequence': 76030, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.3940098509192, + 'timestamp_carla': 645394, + 'timestamp_device': 1515996, + 'timestamp_stream': 645.3940098509192, + 'transform': [array([-27.86828613, 80.90605927, -0.21156906]), + array([ 0.46199396, -116.84204865, 0.35356247])]} +{'AngularVelocity': array([ 0.13179751, -0.183183 , 5.07217836]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.32353401184082, + 'FR_Wheel_Angle': 37.47764205932617, + 'Location': array([-4.63330231e+01, 9.95081406e+01, 4.38317396e-02]), + 'Rotation': array([ 0.45139351, 146.14962769, 0.50890076]), + 'Velocity': array([-0.40969542, 0.1089121 , 0.00174769]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3566.444091796875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7076.04345703, 10461.69140625, 140.39154053]), + 'frame': 18836, + 'frame_number': 18836, + 'framesequence': 76033, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.4254858493805, + 'timestamp_carla': 645425, + 'timestamp_device': 1516021, + 'timestamp_stream': 645.4254858493805, + 'transform': [array([-27.91876411, 80.87015533, -0.21081042]), + array([ 0.46172076, -117.10774231, 0.35043404])]} +{'AngularVelocity': array([ 0.1138519 , -0.20304593, 3.96687794]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.31612205505371, + 'FR_Wheel_Angle': 37.54021072387695, + 'Location': array([-4.63849640e+01, 9.95237885e+01, 4.41682711e-02]), + 'Rotation': array([ 0.43879864, 146.78466797, 0.52574575]), + 'Velocity': array([-0.38599327, 0.0904903 , 0.00164833]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3533.722412109375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7040.06152344, 10465.31542969, 139.96987915]), + 'frame': 18837, + 'frame_number': 18837, + 'framesequence': 76037, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.4588903523982, + 'timestamp_carla': 645458, + 'timestamp_device': 1516054, + 'timestamp_stream': 645.4588903523982, + 'transform': [array([-27.97170639, 80.83271027, -0.21004741]), + array([ 0.46144757, -117.38597107, 0.3472034 ])]} +{'AngularVelocity': array([-5.54884784e-03, -1.13208681e-01, 5.97046852e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.31160545349121, + 'FR_Wheel_Angle': 37.530277252197266, + 'Location': array([-4.64374466e+01, 9.95391312e+01, 4.44453694e-02]), + 'Rotation': array([ 0.42736492, 147.420578 , 0.54182845]), + 'Velocity': array([-0.43807828, 0.08863403, 0.00133457]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3528.7548828125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7029.63867188, 10479.16113281, 139.75015259]), + 'frame': 18838, + 'frame_number': 18838, + 'framesequence': 76042, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.4945204518735, + 'timestamp_carla': 645494, + 'timestamp_device': 1516096, + 'timestamp_stream': 645.4945204518735, + 'transform': [array([-28.02757072, 80.79310608, -0.20996791]), + array([ 0.45430318, -117.68068695, 0.34630144])]} +{'AngularVelocity': array([ 0.03431632, -0.09995678, 5.51188946]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.29947853088379, + 'FR_Wheel_Angle': 37.49955368041992, + 'Location': array([-4.64891281e+01, 9.95532684e+01, 4.47804928e-02]), + 'Rotation': array([ 0.41579458, 148.03070068, 0.5583837 ]), + 'Velocity': array([-0.44329917, 0.08919601, 0.0018858 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3523.658935546875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7018.75097656, 10493.625 , 139.52278137]), + 'frame': 18839, + 'frame_number': 18839, + 'framesequence': 76046, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.5267424508929, + 'timestamp_carla': 645526, + 'timestamp_device': 1516129, + 'timestamp_stream': 645.5267424508929, + 'transform': [array([-28.07707024, 80.75828552, -0.21038848]), + array([ 0.44417402, -117.94147491, 0.34754398])]} +{'AngularVelocity': array([-0.03736245, -0.09808206, 5.48367167]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.306638717651367, + 'FR_Wheel_Angle': 37.51395797729492, + 'Location': array([-4.65442696e+01, 9.95680847e+01, 4.50678542e-02]), + 'Rotation': array([ 0.40383491, 148.69874573, 0.57488751]), + 'Velocity': array([-0.43511826, 0.07284017, 0.00159563]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3518.419189453125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7007.25585938, 10508.89648438, 139.44732666]), + 'frame': 18840, + 'frame_number': 18840, + 'framesequence': 76049, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.01190203707665205, + 'timestamp': 645.5597407519817, + 'timestamp_carla': 645559, + 'timestamp_device': 1516154, + 'timestamp_stream': 645.5597407519817, + 'transform': [array([-28.12704277, 80.72325134, -0.21106525]), + array([ 0.43270612, -118.20458221, 0.34981802])]} +{'AngularVelocity': array([ 0.05548217, -0.16968188, 5.33043385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.30501937866211, + 'FR_Wheel_Angle': 37.52857971191406, + 'Location': array([-4.65997505e+01, 9.95819092e+01, 4.53245454e-02]), + 'Rotation': array([ 0.39182061, 149.36619568, 0.59123546]), + 'Velocity': array([-0.40737113, 0.06927974, 0.00063318]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3524.081298828125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7006.11621094, 10527.15234375, 139.57991028]), + 'frame': 18841, + 'frame_number': 18841, + 'framesequence': 76054, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.0317387655377388, + 'timestamp': 645.5937498509884, + 'timestamp_carla': 645593, + 'timestamp_device': 1516196, + 'timestamp_stream': 645.5937498509884, + 'transform': [array([-28.17741585, 80.68828583, -0.21186215]), + array([ 0.4208011 , -118.46907806, 0.35260427])]} +{'AngularVelocity': array([-0.0219127 , -0.06453936, 5.53871393]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.29775047302246, + 'FR_Wheel_Angle': 37.9095573425293, + 'Location': array([-4.66554337e+01, 9.95950851e+01, 4.53765765e-02]), + 'Rotation': array([ 0.38420495, 150.04681396, 0.60168374]), + 'Velocity': array([-4.37475324e-01, 6.10540174e-02, -3.34777811e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3531.224853515625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7006.11621094, 10546.24902344, 139.78834534]), + 'frame': 18842, + 'frame_number': 18842, + 'framesequence': 76058, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.035706110298633575, + 'timestamp': 645.627797652036, + 'timestamp_carla': 645627, + 'timestamp_device': 1516229, + 'timestamp_stream': 645.627797652036, + 'transform': [array([-28.22679138, 80.65429688, -0.21268028]), + array([ 0.4091078 , -118.7276001 , 0.35554078])]} +{'AngularVelocity': array([ 0.05227682, -0.08773312, 4.46783924]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.792936325073242, + 'FR_Wheel_Angle': 41.66731262207031, + 'Location': array([-4.67117043e+01, 9.96073685e+01, 4.53736372e-02]), + 'Rotation': array([ 0.37649366, 150.73991394, 0.61324728]), + 'Velocity': array([-0.44147 , 0.05575135, -0.00059623]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3538.52685546875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7006.11572266, 10565.53222656, 140.03134155]), + 'frame': 18843, + 'frame_number': 18843, + 'framesequence': 76061, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.6600532494485, + 'timestamp_carla': 645660, + 'timestamp_device': 1516254, + 'timestamp_stream': 645.6600532494485, + 'transform': [array([-28.27257729, 80.62307739, -0.21342833]), + array([ 0.39839125, -118.96662903, 0.35830668])]} +{'AngularVelocity': array([ 0.15624052, -0.17907685, 4.5874896 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.295644760131836, + 'FR_Wheel_Angle': 41.32792663574219, + 'Location': array([-4.67688179e+01, 9.96179962e+01, 4.53537628e-02]), + 'Rotation': array([ 0.36749148, 151.49946594, 0.62853718]), + 'Velocity': array([-4.25425112e-01, 5.19573279e-02, -3.19204322e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2559.684814453125, + 'focus_actor_name': 'AmericanLights_Town04_33_TrafficLight', + 'focus_actor_pt': array([-6141.42871094, 10110.46972656, 134.16578674]), + 'frame': 18844, + 'frame_number': 18844, + 'framesequence': 76066, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.6950729489326, + 'timestamp_carla': 645695, + 'timestamp_device': 1516296, + 'timestamp_stream': 645.6950729489326, + 'transform': [array([-28.32153511, 80.58989716, -0.21426372]), + array([ 0.38695753, -119.22195435, 0.36129785])]} +{'AngularVelocity': array([ 0.15358441, -0.17607009, 4.66504478]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79059410095215, + 'FR_Wheel_Angle': 41.67823791503906, + 'Location': array([-4.68262978e+01, 9.96276855e+01, 4.53189760e-02]), + 'Rotation': array([ 0.35813412, 152.26496887, 0.6439243 ]), + 'Velocity': array([-0.43045306, 0.04267516, -0.00075003]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2544.399658203125, + 'focus_actor_name': 'AmericanLights_Town04_33_TrafficLight', + 'focus_actor_pt': array([-6124.08105469, 10113.74609375, 134.22038269]), + 'frame': 18845, + 'frame_number': 18845, + 'framesequence': 76070, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.7270598523319, + 'timestamp_carla': 645727, + 'timestamp_device': 1516329, + 'timestamp_stream': 645.7270598523319, + 'transform': [array([-28.36542511, 80.56044006, -0.21496181]), + array([ 0.37691712, -119.45007324, 0.36389285])]} +{'AngularVelocity': array([ 0.09088582, -0.09169064, 5.14524508]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.796232223510742, + 'FR_Wheel_Angle': 41.68693161010742, + 'Location': array([-4.68848763e+01, 9.96365204e+01, 4.52749133e-02]), + 'Rotation': array([ 0.34849674, 153.04692078, 0.65963048]), + 'Velocity': array([-0.46639636, 0.03751403, -0.0010487 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2543.37841796875, + 'focus_actor_name': 'AmericanLights_Town04_33_TrafficLight', + 'focus_actor_pt': array([-6118.91992188, 10124.56933594, 134.37242126]), + 'frame': 18846, + 'frame_number': 18846, + 'framesequence': 76074, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.7610824517906, + 'timestamp_carla': 645761, + 'timestamp_device': 1516363, + 'timestamp_stream': 645.7610824517906, + 'transform': [array([-28.4114418 , 80.5297699 , -0.21571906]), + array([ 0.36641914, -119.688797 , 0.36661777])]} +{'AngularVelocity': array([ 0.03035039, -0.04562616, 6.51902246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.798704147338867, + 'FR_Wheel_Angle': 41.6904411315918, + 'Location': array([-4.69443283e+01, 9.96447906e+01, 4.52398583e-02]), + 'Rotation': array([ 0.338873 , 153.83914185, 0.67531246]), + 'Velocity': array([-0.49596149, 0.03043433, -0.00127423]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3619.221923828125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7051.8515625 , 10663.64941406, 141.34555054]), + 'frame': 18847, + 'frame_number': 18847, + 'framesequence': 76077, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.7934669516981, + 'timestamp_carla': 645793, + 'timestamp_device': 1516388, + 'timestamp_stream': 645.7934669516981, + 'transform': [array([-28.45454979, 80.50127411, -0.21639125]), + array([ 0.35677493, -119.91190338, 0.36907625])]} +{'AngularVelocity': array([ 0.01811681, -0.09048571, 7.03655243]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8013858795166, + 'FR_Wheel_Angle': 41.6834602355957, + 'Location': array([-4.70033646e+01, 9.96521454e+01, 4.51972485e-02]), + 'Rotation': array([ 0.32834765, 154.62057495, 0.69278997]), + 'Velocity': array([-0.48096892, 0.01679055, -0.00121595]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3626.892822265625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7052.22265625, 10681.89453125, 141.59074402]), + 'frame': 18848, + 'frame_number': 18848, + 'framesequence': 76082, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.8274391517043, + 'timestamp_carla': 645827, + 'timestamp_device': 1516429, + 'timestamp_stream': 645.8274391517043, + 'transform': [array([-28.49934006, 80.47187805, -0.21711113]), + array([ 0.34676185, -120.14334869, 0.37163725])]} +{'AngularVelocity': array([ 0.07928681, -0.11383446, 6.68697262]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.799497604370117, + 'FR_Wheel_Angle': 41.695716857910156, + 'Location': array([-4.70626640e+01, 9.96587219e+01, 4.51430008e-02]), + 'Rotation': array([ 0.31789064, 155.40176392, 0.71060044]), + 'Velocity': array([-0.45847747, 0.01795696, -0.00074315]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3634.161376953125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7052.57128906, 10699.0234375 , 141.81652832]), + 'frame': 18849, + 'frame_number': 18849, + 'framesequence': 76085, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.8598698489368, + 'timestamp_carla': 645859, + 'timestamp_device': 1516454, + 'timestamp_stream': 645.8598698489368, + 'transform': [array([-28.54123878, 80.44458771, -0.21768428]), + array([ 0.33809435, -120.35920715, 0.3737202 ])]} +{'AngularVelocity': array([-0.01262065, -0.03610054, 7.03172016]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.798656463623047, + 'FR_Wheel_Angle': 41.69634246826172, + 'Location': array([-4.71221237e+01, 9.96645660e+01, 4.50010970e-02]), + 'Rotation': array([ 0.31047305, 156.18707275, 0.72315603]), + 'Velocity': array([-0.48417434, 0.00591816, -0.00168356]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3641.805908203125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7052.93408203, 10716.86523438, 142.05075073]), + 'frame': 18850, + 'frame_number': 18850, + 'framesequence': 76090, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.8941136524081, + 'timestamp_carla': 645894, + 'timestamp_device': 1516496, + 'timestamp_stream': 645.8941136524081, + 'transform': [array([-28.5848217 , 80.41640472, -0.21826346]), + array([ 0.32931072, -120.58337402, 0.37574172])]} +{'AngularVelocity': array([-0.11491866, 0.07356246, 6.90823412]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.798582077026367, + 'FR_Wheel_Angle': 41.69658660888672, + 'Location': array([-4.71816978e+01, 9.96697845e+01, 4.49060351e-02]), + 'Rotation': array([ 0.30635446, 156.97129822, 0.72869515]), + 'Velocity': array([-4.85261559e-01, 7.41415366e-04, 2.11625098e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3649.02734375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7053.27441406, 10733.57910156, 142.25137329]), + 'frame': 18851, + 'frame_number': 18851, + 'framesequence': 76094, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.9268346503377, + 'timestamp_carla': 645926, + 'timestamp_device': 1516529, + 'timestamp_stream': 645.9268346503377, + 'transform': [array([-28.6252346 , 80.39093018, -0.21871071]), + array([ 0.32192045, -120.78949738, 0.3773464 ])]} +{'AngularVelocity': array([-0.10555907, 0.06241938, 6.87250376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.800579071044922, + 'FR_Wheel_Angle': 41.696842193603516, + 'Location': array([-4.72413559e+01, 9.96743240e+01, 4.49519232e-02]), + 'Rotation': array([ 0.30701014, 157.74679565, 0.72523838]), + 'Velocity': array([-0.47810584, -0.00466337, 0.00079106]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3656.6279296875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7053.62890625, 10751.01367188, 142.44944763]), + 'frame': 18852, + 'frame_number': 18852, + 'framesequence': 76097, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.9600276499987, + 'timestamp_carla': 645960, + 'timestamp_device': 1516554, + 'timestamp_stream': 645.9600276499987, + 'transform': [array([-28.66609001, 80.36506653, -0.21910381]), + array([ 0.31472144, -120.99829865, 0.37867129])]} +{'AngularVelocity': array([-0.13169858, 0.07506541, 6.9361515 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.800622940063477, + 'FR_Wheel_Angle': 41.6937255859375, + 'Location': array([-4.73014183e+01, 9.96781387e+01, 4.49944958e-02]), + 'Rotation': array([ 0.30713993, 158.52401733, 0.72263896]), + 'Velocity': array([-4.75787520e-01, -1.20201157e-02, 2.80084612e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3663.67529296875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7053.95654297, 10767.12792969, 142.61642456]), + 'frame': 18853, + 'frame_number': 18853, + 'framesequence': 76102, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 645.9944626502693, + 'timestamp_carla': 645994, + 'timestamp_device': 1516596, + 'timestamp_stream': 645.9944626502693, + 'transform': [array([-28.70788956, 80.33867645, -0.21940319]), + array([ 0.30840352, -121.21168518, 0.37962726])]} +{'AngularVelocity': array([-0.1008909 , 0.04318036, 6.84433556]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.809154510498047, + 'FR_Wheel_Angle': 41.69622802734375, + 'Location': array([-4.73594666e+01, 9.96809540e+01, 4.50531654e-02]), + 'Rotation': array([ 0.30698967, 159.27462769, 0.7200464 ]), + 'Velocity': array([-4.65242654e-01, -1.81288719e-02, 1.47514336e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3670.919921875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7054.29003906, 10783.50976562, 142.76542664]), + 'frame': 18854, + 'frame_number': 18854, + 'framesequence': 76106, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.043656062334775925, + 'timestamp': 646.0273607522249, + 'timestamp_carla': 646027, + 'timestamp_device': 1516629, + 'timestamp_stream': 646.0273607522249, + 'transform': [array([-28.74658203, 80.31475067, -0.21966697]), + array([ 0.30238611, -121.40802765, 0.38049453])]} +{'AngularVelocity': array([-0.10200524, 0.05196086, 6.58100796]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.800050735473633, + 'FR_Wheel_Angle': 41.69285202026367, + 'Location': array([-4.74176292e+01, 9.96829758e+01, 4.50860485e-02]), + 'Rotation': array([ 0.30635446, 160.02804565, 0.71811306]), + 'Velocity': array([-4.61579859e-01, -2.36446131e-02, 3.80153651e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3678.421630859375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7054.63183594, 10800.31933594, 142.89051819]), + 'frame': 18855, + 'frame_number': 18855, + 'framesequence': 76109, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.0476234070956707, + 'timestamp': 646.0597794502974, + 'timestamp_carla': 646059, + 'timestamp_device': 1516654, + 'timestamp_stream': 646.0597794502974, + 'transform': [array([-28.78453827, 80.29132843, -0.21996562]), + array([ 0.29607502, -121.60062408, 0.38145736])]} +{'AngularVelocity': array([-0.0926555 , 0.0646408 , 6.61492443]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80082893371582, + 'FR_Wheel_Angle': 41.690250396728516, + 'Location': array([-4.74763908e+01, 9.96843109e+01, 4.51179408e-02]), + 'Rotation': array([ 0.30653206, 160.78979492, 0.71513087]), + 'Velocity': array([-4.79076803e-01, -2.89127398e-02, 3.59373080e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3685.384521484375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7054.94775391, 10815.85839844, 143.00700378]), + 'frame': 18856, + 'frame_number': 18856, + 'framesequence': 76114, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.051590751856565475, + 'timestamp': 646.0956950522959, + 'timestamp_carla': 646095, + 'timestamp_device': 1516696, + 'timestamp_stream': 646.0956950522959, + 'transform': [array([-28.82631302, 80.26546478, -0.22026092]), + array([ 0.28981858, -121.81283569, 0.38229045])]} +{'AngularVelocity': array([-0.1001771 , 0.03795718, 6.78903627]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80883026123047, + 'FR_Wheel_Angle': 41.712913513183594, + 'Location': array([-4.75351601e+01, 9.96848679e+01, 4.51521948e-02]), + 'Rotation': array([ 0.30571926, 161.5559082 , 0.713467 ]), + 'Velocity': array([-4.66853738e-01, -3.74300778e-02, 2.96974176e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3692.3037109375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7055.25878906, 10831.16210938, 143.12936401]), + 'frame': 18857, + 'frame_number': 18857, + 'framesequence': 76118, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538456380367279, + 'throttle_input': 0.05555810034275055, + 'timestamp': 646.1293146498501, + 'timestamp_carla': 646129, + 'timestamp_device': 1516729, + 'timestamp_stream': 646.1293146498501, + 'transform': [array([-28.86484337, 80.24206543, -0.22058231]), + array([ 0.28343233, -122.00760651, 0.38332844])]} +{'AngularVelocity': array([ 0.08337858, -0.07501173, 5.52839088]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.787038803100586, + 'FR_Wheel_Angle': 41.66849899291992, + 'Location': array([-4.75940552e+01, 9.96847839e+01, 4.51725647e-02]), + 'Rotation': array([ 0.30479717, 162.3165741 , 0.71316528]), + 'Velocity': array([-4.24763441e-01, -2.79351398e-02, -1.45921702e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3700.031982421875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7055.60351562, 10848.08496094, 143.24609375]), + 'frame': 18858, + 'frame_number': 18858, + 'framesequence': 76122, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5258767008781433, + 'throttle_input': 0.07142747938632965, + 'timestamp': 646.16251154989, + 'timestamp_carla': 646162, + 'timestamp_device': 1516763, + 'timestamp_stream': 646.16251154989, + 'transform': [array([-28.90230942, 80.21965027, -0.22086914]), + array([ 0.27785209, -122.19576263, 0.38429829])]} +{'AngularVelocity': array([ 0.06022505, -0.04487881, 6.40450716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.785505294799805, + 'FR_Wheel_Angle': 41.66618347167969, + 'Location': array([-4.76527863e+01, 9.96840134e+01, 4.52096052e-02]), + 'Rotation': array([ 0.30455127, 163.09303284, 0.71028006]), + 'Velocity': array([-4.50294018e-01, -3.31396125e-02, 1.77612295e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3707.194091796875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7055.92089844, 10863.6953125 , 143.37507629]), + 'frame': 18859, + 'frame_number': 18859, + 'framesequence': 76126, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5056062340736389, + 'throttle_input': 0.07142747938632965, + 'timestamp': 646.1935739517212, + 'timestamp_carla': 646193, + 'timestamp_device': 1516796, + 'timestamp_stream': 646.1935739517212, + 'transform': [array([-28.93598747, 80.20033264, -0.22114208]), + array([ 0.27281824, -122.36182404, 0.38530874])]} +{'AngularVelocity': array([-0.10806456, 0.03861284, 7.09869385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.785755157470703, + 'FR_Wheel_Angle': 41.65751266479492, + 'Location': array([-4.77148514e+01, 9.96824493e+01, 4.52286415e-02]), + 'Rotation': array([ 0.30437371, 163.91467285, 0.70689666]), + 'Velocity': array([-4.89486545e-01, -5.61537929e-02, 2.58493412e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3714.16748046875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7056.22949219, 10878.83007812, 143.49777222]), + 'frame': 18860, + 'frame_number': 18860, + 'framesequence': 76130, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4831385314464569, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.2276714518666, + 'timestamp_carla': 646227, + 'timestamp_device': 1516829, + 'timestamp_stream': 646.2276714518666, + 'transform': [array([-28.97200775, 80.1802597 , -0.22152351]), + array([ 0.26696476, -122.53722382, 0.38661322])]} +{'AngularVelocity': array([ 0.08677275, -0.07369854, 5.86642361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.778295516967773, + 'FR_Wheel_Angle': 41.65092086791992, + 'Location': array([-4.77765465e+01, 9.96797714e+01, 4.52782325e-02]), + 'Rotation': array([ 0.30323988, 164.71287537, 0.70578778]), + 'Velocity': array([-4.53321666e-01, -5.05141020e-02, 3.27243790e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3720.32470703125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7056.50146484, 10892.24414062, 143.61831665]), + 'frame': 18861, + 'frame_number': 18861, + 'framesequence': 76134, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4604876935482025, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.2604321502149, + 'timestamp_carla': 646260, + 'timestamp_device': 1516863, + 'timestamp_stream': 646.2604321502149, + 'transform': [array([-29.00562859, 80.16241455, -0.2219891 ]), + array([ 0.26064682, -122.69766235, 0.38830024])]} +{'AngularVelocity': array([ 0.01196049, -0.02742318, 6.17365026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77692985534668, + 'FR_Wheel_Angle': 41.65166091918945, + 'Location': array([-4.78393288e+01, 9.96761703e+01, 4.53033708e-02]), + 'Rotation': array([ 0.30207193, 165.53915405, 0.70396394]), + 'Velocity': array([-4.64944571e-01, -6.12150095e-02, 3.85627733e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3726.83837890625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7056.79101562, 10906.453125 , 143.75939941]), + 'frame': 18862, + 'frame_number': 18862, + 'framesequence': 76138, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4538956880569458, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.2942092493176, + 'timestamp_carla': 646294, + 'timestamp_device': 1516896, + 'timestamp_stream': 646.2942092493176, + 'transform': [array([-29.03910637, 80.14601135, -0.22255939]), + array([ 0.25378248, -122.8529129 , 0.39036268])]} +{'AngularVelocity': array([ 0.15898845, -0.12542415, 6.4058876 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.776782989501953, + 'FR_Wheel_Angle': 41.64902114868164, + 'Location': array([-4.79026222e+01, 9.96717758e+01, 4.53073792e-02]), + 'Rotation': array([ 0.30024144, 166.38223267, 0.70452636]), + 'Velocity': array([-0.45912245, -0.06600457, -0.00104442]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3732.783203125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7057.05664062, 10919.49804688, 143.92391968]), + 'frame': 18863, + 'frame_number': 18863, + 'framesequence': 76142, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4616779386997223, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.3277365490794, + 'timestamp_carla': 646327, + 'timestamp_device': 1516929, + 'timestamp_stream': 646.3277365490794, + 'transform': [array([-29.07372093, 80.12806702, -0.22307301]), + array([ 0.24572287, -123.01659393, 0.3920632 ])]} +{'AngularVelocity': array([ 0.27113467, -0.2219933 , 6.27848291]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77090835571289, + 'FR_Wheel_Angle': 41.632137298583984, + 'Location': array([-4.79651489e+01, 9.96661911e+01, 4.50318418e-02]), + 'Rotation': array([ 0.28509891, 167.22880554, 0.73296809]), + 'Velocity': array([-0.46621844, -0.07508681, -0.0036311 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3738.48095703125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7057.31396484, 10932.18164062, 144.11178589]), + 'frame': 18864, + 'frame_number': 18864, + 'framesequence': 76146, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4743858277797699, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.3614782504737, + 'timestamp_carla': 646361, + 'timestamp_device': 1516963, + 'timestamp_stream': 646.3614782504737, + 'transform': [array([-29.10833931, 80.11009216, -0.22348171]), + array([ 0.23827797, -123.18071747, 0.39336756])]} +{'AngularVelocity': array([ 0.26170734, -0.21150076, 6.76401377]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.764034271240234, + 'FR_Wheel_Angle': 41.618927001953125, + 'Location': array([-4.80298042e+01, 9.96593628e+01, 4.46335860e-02]), + 'Rotation': array([ 0.26749751, 168.10160828, 0.76482821]), + 'Velocity': array([-0.48221087, -0.08634197, -0.00359351]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3744.62890625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7057.58642578, 10945.56933594, 144.28082275]), + 'frame': 18865, + 'frame_number': 18865, + 'framesequence': 76150, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4872402250766754, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.3936940506101, + 'timestamp_carla': 646393, + 'timestamp_device': 1516996, + 'timestamp_stream': 646.3936940506101, + 'transform': [array([-29.14110374, 80.09334564, -0.22364147]), + array([ 0.2329914 , -123.33589172, 0.39381137])]} +{'AngularVelocity': array([ 0.24904995, -0.19481388, 7.40304089]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.759870529174805, + 'FR_Wheel_Angle': 41.6232795715332, + 'Location': array([-4.80966301e+01, 9.96513824e+01, 4.42370102e-02]), + 'Rotation': array([ 0.24969804, 169.01127625, 0.79754305]), + 'Velocity': array([-0.50737339, -0.09830195, -0.00354615]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3750.86865234375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7057.85986328, 10959.04394531, 144.42410278]), + 'frame': 18866, + 'frame_number': 18866, + 'framesequence': 76154, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49315473437309265, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.4275099523365, + 'timestamp_carla': 646427, + 'timestamp_device': 1517029, + 'timestamp_stream': 646.4275099523365, + 'transform': [array([-29.17777824, 80.07420349, -0.2236357 ]), + array([ 0.22988367, -123.51037598, 0.39358586])]} +{'AngularVelocity': array([ 0.28534713, -0.2223406 , 6.66415215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.756206512451172, + 'FR_Wheel_Angle': 41.61882400512695, + 'Location': array([-4.81641197e+01, 9.96421585e+01, 4.38495912e-02]), + 'Rotation': array([ 0.2308877 , 169.92427063, 0.83195186]), + 'Velocity': array([-0.49777773, -0.10870542, -0.00365934]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3756.82470703125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7058.12109375, 10971.84960938, 144.50666809]), + 'frame': 18867, + 'frame_number': 18867, + 'framesequence': 76158, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4903531074523926, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.4616544507444, + 'timestamp_carla': 646461, + 'timestamp_device': 1517063, + 'timestamp_stream': 646.4616544507444, + 'transform': [array([-29.21343613, 80.05612183, -0.22319824]), + array([ 0.23004076, -123.67857361, 0.39179635])]} +{'AngularVelocity': array([ 0.30667058, -0.22971584, 6.76234198]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.754037857055664, + 'FR_Wheel_Angle': 41.61270523071289, + 'Location': array([-4.82323265e+01, 9.96317062e+01, 4.34253588e-02]), + 'Rotation': array([ 0.21065669, 170.85089111, 0.86980444]), + 'Velocity': array([-0.50073349, -0.11787888, -0.00384829]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3763.6162109375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7058.41455078, 10986.28320312, 144.5446167 ]), + 'frame': 18868, + 'frame_number': 18868, + 'framesequence': 76162, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4839991629123688, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.495250351727, + 'timestamp_carla': 646495, + 'timestamp_device': 1517096, + 'timestamp_stream': 646.495250351727, + 'transform': [array([-29.24809074, 80.03913116, -0.22274952]), + array([ 0.22988367, -123.84075165, 0.38989753])]} +{'AngularVelocity': array([ 0.32387948, -0.23149246, 6.87391376]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.752180099487305, + 'FR_Wheel_Angle': 41.6082878112793, + 'Location': array([-4.83022995e+01, 9.96198196e+01, 4.29592803e-02]), + 'Rotation': array([ 0.18960604, 171.80639648, 0.90937483]), + 'Velocity': array([-0.50731272, -0.1269539 , -0.00424702]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3770.19775390625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7058.69921875, 11000.27148438, 144.47363281]), + 'frame': 18869, + 'frame_number': 18869, + 'framesequence': 76166, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47726067900657654, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.5279493518174, + 'timestamp_carla': 646527, + 'timestamp_device': 1517129, + 'timestamp_stream': 646.5279493518174, + 'transform': [array([-29.28086853, 80.02368927, -0.2222507 ]), + array([ 0.23036861, -123.99214935, 0.38785523])]} +{'AngularVelocity': array([ 0.32526124, -0.22515248, 7.18400383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.746845245361328, + 'FR_Wheel_Angle': 41.600074768066406, + 'Location': array([-4.83716316e+01, 9.96069107e+01, 4.25153263e-02]), + 'Rotation': array([1.68603212e-01, 1.72755371e+02, 9.48912799e-01]), + 'Velocity': array([-0.52372408, -0.14060058, -0.00441266]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3776.576416015625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7058.97460938, 11013.82421875, 144.39331055]), + 'frame': 18870, + 'frame_number': 18870, + 'framesequence': 76170, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47376325726509094, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.5619448497891, + 'timestamp_carla': 646561, + 'timestamp_device': 1517163, + 'timestamp_stream': 646.5619448497891, + 'transform': [array([-29.31496048, 80.00774384, -0.22174934]), + array([ 0.230956 , -124.14916992, 0.38574478])]} +{'AngularVelocity': array([ 0.30330631, -0.20114228, 7.05598545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.745336532592773, + 'FR_Wheel_Angle': 41.58909606933594, + 'Location': array([-4.84429626e+01, 9.95923920e+01, 4.20983396e-02]), + 'Rotation': array([1.49342075e-01, 1.73728455e+02, 9.84296799e-01]), + 'Velocity': array([-0.51726723, -0.14680113, -0.0036537 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3782.541259765625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7059.23339844, 11026.53320312, 144.29974365]), + 'frame': 18871, + 'frame_number': 18871, + 'framesequence': 76174, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4751182496547699, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.5971724502742, + 'timestamp_carla': 646597, + 'timestamp_device': 1517196, + 'timestamp_stream': 646.5971724502742, + 'transform': [array([-29.35160637, 79.99012756, -0.22128925]), + array([ 0.23092185, -124.31920624, 0.38370252])]} +{'AngularVelocity': array([ 0.3025924 , -0.19663756, 7.40215158]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.740596771240234, + 'FR_Wheel_Angle': 41.5892448425293, + 'Location': array([-4.85155525e+01, 9.95763931e+01, 4.17035557e-02]), + 'Rotation': array([1.30415618e-01, 1.74723358e+02, 1.01958930e+00]), + 'Velocity': array([-0.53136218, -0.16141321, -0.00355959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3788.773193359375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7059.50195312, 11039.75097656, 144.20140076]), + 'frame': 18872, + 'frame_number': 18872, + 'framesequence': 76178, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4786339998245239, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.6290363520384, + 'timestamp_carla': 646629, + 'timestamp_device': 1517229, + 'timestamp_stream': 646.6290363520384, + 'transform': [array([-29.38447189, 79.97486115, -0.22087428]), + array([ 0.23034129, -124.47057343, 0.38192669])]} +{'AngularVelocity': array([ 0.35244748, -0.21582292, 7.42071247]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73057746887207, + 'FR_Wheel_Angle': 41.57062530517578, + 'Location': array([-4.85873756e+01, 9.95592270e+01, 4.12707813e-02]), + 'Rotation': array([1.09795287e-01, 1.75713654e+02, 1.05827153e+00]), + 'Velocity': array([-0.53058457, -0.17034055, -0.00469272]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3783.49609375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7049.77734375, 11047.25390625, 144.02960205]), + 'frame': 18873, + 'frame_number': 18873, + 'framesequence': 76181, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4814905524253845, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.6608783490956, + 'timestamp_carla': 646660, + 'timestamp_device': 1517254, + 'timestamp_stream': 646.6608783490956, + 'transform': [array([-29.41706467, 79.95992279, -0.22041798]), + array([ 0.23012272, -124.62031555, 0.37998685])]} +{'AngularVelocity': array([ 0.36900753, -0.23490039, 6.85125589]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.728769302368164, + 'FR_Wheel_Angle': 41.56577682495117, + 'Location': array([-4.86599045e+01, 9.95402298e+01, 4.07977961e-02]), + 'Rotation': array([8.76859650e-02, 1.76691177e+02, 1.09974337e+00]), + 'Velocity': array([-0.51684064, -0.18554802, -0.00453859]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3772.6396484375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7036.05224609, 11050.44433594, 143.84213257]), + 'frame': 18874, + 'frame_number': 18874, + 'framesequence': 76186, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48246103525161743, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.6959545500576, + 'timestamp_carla': 646696, + 'timestamp_device': 1517296, + 'timestamp_stream': 646.6959545500576, + 'transform': [array([-29.45387459, 79.94220734, -0.21990173]), + array([ 0.23000661, -124.79173279, 0.3776783 ])]} +{'AngularVelocity': array([ 0.12173098, -0.09757619, 6.78156471]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.726638793945312, + 'FR_Wheel_Angle': 41.568180084228516, + 'Location': array([-4.87326469e+01, 9.95196381e+01, 4.03637588e-02]), + 'Rotation': array([6.83633611e-02, 1.77665344e+02, 1.13525438e+00]), + 'Velocity': array([-0.5236004 , -0.19362451, -0.00136291]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3757.0615234375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7018.50292969, 11050.80078125, 143.61230469]), + 'frame': 18875, + 'frame_number': 18875, + 'framesequence': 76190, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48123419284820557, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.7277070507407, + 'timestamp_carla': 646727, + 'timestamp_device': 1517329, + 'timestamp_stream': 646.7277070507407, + 'transform': [array([-29.48750687, 79.92645264, -0.21946056]), + array([ 0.22988367, -124.94741821, 0.37583405])]} +{'AngularVelocity': array([ 0.03189034, -0.03600122, 6.67779493]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.731351852416992, + 'FR_Wheel_Angle': 41.57585525512695, + 'Location': array([-4.88056297e+01, 9.94980164e+01, 4.04057987e-02]), + 'Rotation': array([6.95996210e-02, 1.78636765e+02, 1.12875748e+00]), + 'Velocity': array([-0.50694788, -0.19629528, 0.00105043]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3759.72412109375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7015.22216797, 11062.73242188, 143.47680664]), + 'frame': 18876, + 'frame_number': 18876, + 'framesequence': 76194, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4795861840248108, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.7619504518807, + 'timestamp_carla': 646761, + 'timestamp_device': 1517363, + 'timestamp_stream': 646.7619504518807, + 'transform': [array([-29.52417183, 79.90914917, -0.21900222]), + array([ 0.22921431, -125.11791229, 0.37375078])]} +{'AngularVelocity': array([ 0.03868612, -0.0408454 , 6.52193451]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7341251373291, + 'FR_Wheel_Angle': 41.5781364440918, + 'Location': array([-4.88768578e+01, 9.94756393e+01, 4.05659750e-02]), + 'Rotation': array([7.21336231e-02, 1.79588898e+02, 1.12094164e+00]), + 'Velocity': array([-0.49701819, -0.20201805, 0.00090858]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3756.978271484375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7007.98632812, 11070.63378906, 143.33940125]), + 'frame': 18877, + 'frame_number': 18877, + 'framesequence': 76198, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4786156713962555, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.7944032512605, + 'timestamp_carla': 646794, + 'timestamp_device': 1517396, + 'timestamp_stream': 646.7944032512605, + 'transform': [array([-29.55839348, 79.89308167, -0.21847518]), + array([ 0.22933725, -125.27689362, 0.37154469])]} +{'AngularVelocity': array([ 0.0357279 , -0.03739117, 6.50525856]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.734760284423828, + 'FR_Wheel_Angle': 41.599327087402344, + 'Location': array([-4.89470596e+01, 9.94521866e+01, 4.06943411e-02]), + 'Rotation': array([ 7.39094764e-02, -1.79474930e+02, 1.11392736e+00]), + 'Velocity': array([-0.49466619, -0.21078944, 0.00112847]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3746.616455078125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-6994.00390625, 11075.01171875, 143.13487244]), + 'frame': 18878, + 'frame_number': 18878, + 'framesequence': 76202, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4792199730873108, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.8282632492483, + 'timestamp_carla': 646828, + 'timestamp_device': 1517429, + 'timestamp_stream': 646.8282632492483, + 'transform': [array([-29.59414482, 79.87646484, -0.21797813]), + array([ 0.2293714 , -125.44258881, 0.36939994])]} +{'AngularVelocity': array([ 0.04608422, -0.02103619, 6.02089167]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74641227722168, + 'FR_Wheel_Angle': 41.59295654296875, + 'Location': array([-4.90173378e+01, 9.94276123e+01, 4.07817364e-02]), + 'Rotation': array([ 7.47700781e-02, -1.78524750e+02, 1.10831261e+00]), + 'Velocity': array([-0.49987146, -0.21634918, 0.00076511]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3752.011962890625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-6993.26464844, 11087.7265625 , 143.02653503]), + 'frame': 18879, + 'frame_number': 18879, + 'framesequence': 76206, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4801538288593292, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.8615575507283, + 'timestamp_carla': 646861, + 'timestamp_device': 1517463, + 'timestamp_stream': 646.8615575507283, + 'transform': [array([-29.62861252, 79.86096954, -0.21750805]), + array([ 0.22948751, -125.60101318, 0.36741236])]} +{'AngularVelocity': array([1.92005951e-02, 6.49649359e-04, 6.15584612e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74687385559082, + 'FR_Wheel_Angle': 41.598365783691406, + 'Location': array([-4.90851631e+01, 9.94027634e+01, 4.08687107e-02]), + 'Rotation': array([ 7.47427568e-02, -1.77596786e+02, 1.10400784e+00]), + 'Velocity': array([-0.50225919, -0.22483602, 0.00071836]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3757.687255859375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-6992.49121094, 11101.02246094, 142.92237854]), + 'frame': 18880, + 'frame_number': 18880, + 'framesequence': 76210, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48030033707618713, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.8945000506938, + 'timestamp_carla': 646894, + 'timestamp_device': 1517496, + 'timestamp_stream': 646.8945000506938, + 'transform': [array([-29.6638279 , 79.84476471, -0.217098 ]), + array([ 0.22899574, -125.76402283, 0.36562288])]} +{'AngularVelocity': array([ 0.08387954, -0.02132448, 5.88152075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.751644134521484, + 'FR_Wheel_Angle': 41.61259078979492, + 'Location': array([-4.91528816e+01, 9.93766785e+01, 4.09411117e-02]), + 'Rotation': array([ 7.46129826e-02, -1.76655579e+02, 1.09977102e+00]), + 'Velocity': array([-4.79363590e-01, -2.23807096e-01, 4.37011709e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3765.39892578125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-6993.58886719, 11115.10351562, 142.84179688]), + 'frame': 18881, + 'frame_number': 18881, + 'framesequence': 76214, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4799524247646332, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.9264500513673, + 'timestamp_carla': 646926, + 'timestamp_device': 1517529, + 'timestamp_stream': 646.9264500513673, + 'transform': [array([-29.69812202, 79.82918549, -0.21671985]), + array([ 0.22836053, -125.92235565, 0.36397678])]} +{'AngularVelocity': array([ 0.06760497, -0.01251579, 5.85528708]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75064468383789, + 'FR_Wheel_Angle': 41.60909652709961, + 'Location': array([-4.92176552e+01, 9.93505630e+01, 4.10121046e-02]), + 'Rotation': array([ 7.44353980e-02, -1.75762329e+02, 1.09599996e+00]), + 'Velocity': array([-0.46405247, -0.22504149, 0.00067819]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3799.05859375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7015.50878906, 11144.61132812, 142.94003296]), + 'frame': 18882, + 'frame_number': 18882, + 'framesequence': 76218, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.9608387500048, + 'timestamp_carla': 646960, + 'timestamp_device': 1517563, + 'timestamp_stream': 646.9608387500048, + 'transform': [array([-29.73527336, 79.81237793, -0.2163206 ]), + array([ 0.22804634, -126.09358978, 0.36218727])]} +{'AngularVelocity': array([ 0.05568861, -0.01263577, 6.01822233]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74870491027832, + 'FR_Wheel_Angle': 41.60856246948242, + 'Location': array([-4.92825661e+01, 9.93232193e+01, 4.10721488e-02]), + 'Rotation': array([ 7.55350590e-02, -1.74853073e+02, 1.08997774e+00]), + 'Velocity': array([-0.46930921, -0.23848565, 0.00066478]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3859.14208984375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7058.84960938, 11189.48339844, 143.21429443]), + 'frame': 18883, + 'frame_number': 18883, + 'framesequence': 76222, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 646.9937691502273, + 'timestamp_carla': 646993, + 'timestamp_device': 1517596, + 'timestamp_stream': 646.9937691502273, + 'transform': [array([-29.77079582, 79.79668427, -0.21592098]), + array([ 0.2279029 , -126.25634003, 0.36048648])]} +{'AngularVelocity': array([ 0.07721061, -0.01791893, 5.96130085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75718116760254, + 'FR_Wheel_Angle': 41.621524810791016, + 'Location': array([-4.93472595e+01, 9.92946625e+01, 4.11394760e-02]), + 'Rotation': array([ 7.57877752e-02, -1.73941269e+02, 1.08498096e+00]), + 'Velocity': array([-0.46212146, -0.2441396 , 0.00058746]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3866.0537109375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7058.55371094, 11204.08203125, 143.13676453]), + 'frame': 18884, + 'frame_number': 18884, + 'framesequence': 76226, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.0281775519252, + 'timestamp_carla': 647028, + 'timestamp_device': 1517629, + 'timestamp_stream': 647.0281775519252, + 'transform': [array([-29.80811691, 79.78042603, -0.21550685]), + array([ 0.22784144, -126.42667389, 0.35868335])]} +{'AngularVelocity': array([ 0.07476576, -0.03415183, 5.43137884]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.760257720947266, + 'FR_Wheel_Angle': 41.62337112426758, + 'Location': array([-4.94103508e+01, 9.92655869e+01, 4.11961637e-02]), + 'Rotation': array([ 7.52208680e-02, -1.73045395e+02, 1.08121264e+00]), + 'Velocity': array([-4.39051002e-01, -2.39730805e-01, 5.97858416e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3872.664306640625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7058.27001953, 11218.01464844, 143.06451416]), + 'frame': 18885, + 'frame_number': 18885, + 'framesequence': 76230, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.061436150223, + 'timestamp_carla': 647061, + 'timestamp_device': 1517662, + 'timestamp_stream': 647.061436150223, + 'transform': [array([-29.84408569, 79.7649765 , -0.21505329]), + array([ 0.22762971, -126.59044647, 0.35675031])]} +{'AngularVelocity': array([-3.85596184e-03, -6.83787912e-02, 5.32001352e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.765605926513672, + 'FR_Wheel_Angle': 41.63327407836914, + 'Location': array([-4.94711761e+01, 9.92363052e+01, 4.11419943e-02]), + 'Rotation': array([ 6.95176646e-02, -1.72175491e+02, 1.06520677e+00]), + 'Velocity': array([-0.4269765 , -0.24137361, -0.00098315]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3879.636962890625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7057.97216797, 11232.65039062, 142.9859314 ]), + 'frame': 18886, + 'frame_number': 18886, + 'framesequence': 76234, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.0950305499136, + 'timestamp_carla': 647095, + 'timestamp_device': 1517696, + 'timestamp_stream': 647.0950305499136, + 'transform': [array([-29.87946701, 79.75032806, -0.2145679 ]), + array([ 0.2274726 , -126.75035095, 0.35467392])]} +{'AngularVelocity': array([ 0.00751153, -0.06714122, 5.3465004 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.767900466918945, + 'FR_Wheel_Angle': 41.634620666503906, + 'Location': array([-4.95297394e+01, 9.92069397e+01, 4.10513952e-02]), + 'Rotation': array([ 6.33978099e-02, -1.71330460e+02, 1.04743028e+00]), + 'Velocity': array([-0.41890919, -0.24451947, -0.00101261]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3886.400634765625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7057.68505859, 11246.78027344, 142.89826965]), + 'frame': 18887, + 'frame_number': 18887, + 'framesequence': 76238, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.1272150501609, + 'timestamp_carla': 647127, + 'timestamp_device': 1517729, + 'timestamp_stream': 647.1272150501609, + 'transform': [array([-29.91386604, 79.73590088, -0.21409148]), + array([ 0.2274726 , -126.90641022, 0.35269323])]} +{'AngularVelocity': array([-0.22107695, -0.19833244, 5.54951668]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.762582778930664, + 'FR_Wheel_Angle': 41.61946105957031, + 'Location': array([-4.95887146e+01, 9.91763153e+01, 4.07419875e-02]), + 'Rotation': array([ 4.82962653e-02, -1.70477936e+02, 1.00795257e+00]), + 'Velocity': array([-0.42739084, -0.25803655, -0.00400028]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3893.03759765625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7057.40332031, 11260.64453125, 142.79925537]), + 'frame': 18888, + 'frame_number': 18888, + 'framesequence': 76242, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.1607734523714, + 'timestamp_carla': 647160, + 'timestamp_device': 1517762, + 'timestamp_stream': 647.1607734523714, + 'transform': [array([-29.95055389, 79.72047424, -0.21366501]), + array([ 0.22691937, -127.07323456, 0.35080114])]} +{'AngularVelocity': array([-0.28734931, -0.21008058, 5.94856644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.758058547973633, + 'FR_Wheel_Angle': 41.62369155883789, + 'Location': array([-4.96483192e+01, 9.91440735e+01, 4.02691923e-02]), + 'Rotation': array([ 2.70612072e-02, -1.69592682e+02, 9.57993090e-01]), + 'Velocity': array([-0.44480559, -0.27892342, -0.00411468]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3899.596435546875, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7057.12695312, 11274.21679688, 142.70657349]), + 'frame': 18889, + 'frame_number': 18889, + 'framesequence': 76246, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.194325748831, + 'timestamp_carla': 647194, + 'timestamp_device': 1517796, + 'timestamp_stream': 647.194325748831, + 'transform': [array([-29.98820686, 79.70410156, -0.21323524]), + array([ 0.22670762, -127.24542999, 0.34894326])]} +{'AngularVelocity': array([8.79533961e-02, 3.83975264e-03, 5.66662931e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76184844970703, + 'FR_Wheel_Angle': 41.62044143676758, + 'Location': array([-4.97084961e+01, 9.91106262e+01, 4.01005447e-02]), + 'Rotation': array([ 1.99304912e-02, -1.68693375e+02, 9.44577336e-01]), + 'Velocity': array([-4.22466606e-01, -2.75408000e-01, 2.22501752e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3906.687255859375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7056.83105469, 11288.77441406, 142.62173462]), + 'frame': 18890, + 'frame_number': 18890, + 'framesequence': 76249, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.2266271524131, + 'timestamp_carla': 647226, + 'timestamp_device': 1517821, + 'timestamp_stream': 647.2266271524131, + 'transform': [array([-30.02384186, 79.68904114, -0.21281753]), + array([ 0.22603826, -127.40769196, 0.34714693])]} +{'AngularVelocity': array([9.20844153e-02, 5.24463784e-03, 5.61476994e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75860023498535, + 'FR_Wheel_Angle': 41.626888275146484, + 'Location': array([-4.97664528e+01, 9.90771484e+01, 4.02353182e-02]), + 'Rotation': array([ 2.16721892e-02, -1.67830872e+02, 9.43406165e-01]), + 'Velocity': array([-0.41074267, -0.27712119, 0.00179678]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3914.112548828125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7056.52441406, 11303.82617188, 142.54075623]), + 'frame': 18891, + 'frame_number': 18891, + 'framesequence': 76254, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.2613993510604, + 'timestamp_carla': 647261, + 'timestamp_device': 1517862, + 'timestamp_stream': 647.2613993510604, + 'transform': [array([-30.06286812, 79.67234039, -0.2125027 ]), + array([ 0.22442634, -127.58608246, 0.34562388])]} +{'AngularVelocity': array([ 1.18771859e-01, -1.79124530e-03, 5.50202847e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76267433166504, + 'FR_Wheel_Angle': 41.629878997802734, + 'Location': array([-4.98254051e+01, 9.90418549e+01, 4.03324030e-02]), + 'Rotation': array([ 2.29562651e-02, -1.66946091e+02, 9.40693736e-01]), + 'Velocity': array([-0.40174532, -0.27975878, 0.00048767]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3921.158447265625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7056.23535156, 11318.078125 , 142.4630127 ]), + 'frame': 18892, + 'frame_number': 18892, + 'framesequence': 76258, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.2947903499007, + 'timestamp_carla': 647294, + 'timestamp_device': 1517896, + 'timestamp_stream': 647.2947903499007, + 'transform': [array([-30.10025597, 79.65663147, -0.21222565]), + array([ 0.22261634, -127.75642395, 0.34433287])]} +{'AngularVelocity': array([0.08458227, 0.01155995, 5.46569014]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76700210571289, + 'FR_Wheel_Angle': 41.636199951171875, + 'Location': array([-4.98810005e+01, 9.90074387e+01, 4.04335670e-02]), + 'Rotation': array([ 2.34343782e-02, -1.66107315e+02, 9.38160717e-01]), + 'Velocity': array([-0.40175661, -0.2834149 , 0.00065654]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3929.003662109375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7055.91503906, 11333.796875 , 142.40769958]), + 'frame': 18893, + 'frame_number': 18893, + 'framesequence': 76262, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.327882450074, + 'timestamp_carla': 647327, + 'timestamp_device': 1517929, + 'timestamp_stream': 647.327882450074, + 'transform': [array([-30.13750458, 79.64104462, -0.21196716]), + array([ 0.22085415, -127.92601776, 0.3431375 ])]} +{'AngularVelocity': array([ 1.22131139e-01, -3.53785604e-03, 5.20662355e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.768056869506836, + 'FR_Wheel_Angle': 41.637611389160156, + 'Location': array([-4.99360199e+01, 9.89721069e+01, 4.04992960e-02]), + 'Rotation': array([ 2.37075854e-02, -1.65260605e+02, 9.34135556e-01]), + 'Velocity': array([-0.37969303, -0.28038216, 0.00043808]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3936.5625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7055.60839844, 11348.87695312, 142.36846924]), + 'frame': 18894, + 'frame_number': 18894, + 'framesequence': 76266, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.3610325492918, + 'timestamp_carla': 647361, + 'timestamp_device': 1517962, + 'timestamp_stream': 647.3610325492918, + 'transform': [array([-30.17479515, 79.62561798, -0.21170071]), + array([ 0.21911246, -128.09553528, 0.34190798])]} +{'AngularVelocity': array([ 0.09918448, -0.00797445, 5.1356287 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77067756652832, + 'FR_Wheel_Angle': 41.645206451416016, + 'Location': array([-4.99899101e+01, 9.89365005e+01, 4.05618548e-02]), + 'Rotation': array([ 2.39398126e-02, -1.64425735e+02, 9.30303514e-01]), + 'Velocity': array([-0.37296039, -0.28476736, 0.00041216]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3944.16259765625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7055.30175781, 11363.94921875, 142.33552551]), + 'frame': 18895, + 'frame_number': 18895, + 'framesequence': 76270, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.39452784881, + 'timestamp_carla': 647394, + 'timestamp_device': 1517996, + 'timestamp_stream': 647.39452784881, + 'transform': [array([-30.21276855, 79.60997772, -0.2114519 ]), + array([ 0.21776691, -128.26777649, 0.3407878 ])]} +{'AngularVelocity': array([-0.2332582 , -0.26136559, 5.21350479]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.769304275512695, + 'FR_Wheel_Angle': 41.63822937011719, + 'Location': array([-5.00431519e+01, 9.89000931e+01, 4.05142494e-02]), + 'Rotation': array([ 1.77311692e-02, -1.63589737e+02, 9.10801649e-01]), + 'Velocity': array([-0.37050691, -0.29304615, -0.00347456]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3951.829833984375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7054.99414062, 11379.07617188, 142.30114746]), + 'frame': 18896, + 'frame_number': 18896, + 'framesequence': 76274, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.4288743510842, + 'timestamp_carla': 647428, + 'timestamp_device': 1518029, + 'timestamp_stream': 647.4288743510842, + 'transform': [array([-30.25105476, 79.59479523, -0.21116363]), + array([ 0.21618231, -128.44033813, 0.33944905])]} +{'AngularVelocity': array([-0.27152193, -0.36320302, 5.51680422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.769166946411133, + 'FR_Wheel_Angle': 41.638465881347656, + 'Location': array([-5.00964851e+01, 9.88621674e+01, 3.98279466e-02]), + 'Rotation': array([-1.29636982e-02, -1.62736481e+02, 8.41084838e-01]), + 'Velocity': array([-0.37603733, -0.30217934, -0.00740401]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3959.69091796875, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7054.68066406, 11394.50195312, 142.27409363]), + 'frame': 18897, + 'frame_number': 18897, + 'framesequence': 76278, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.4632537513971, + 'timestamp_carla': 647463, + 'timestamp_device': 1518062, + 'timestamp_stream': 647.4632537513971, + 'transform': [array([-30.28918457, 79.57975006, -0.2108395 ]), + array([ 0.2145977 , -128.61251831, 0.33796689])]} +{'AngularVelocity': array([-0.33734104, -0.37891006, 5.35332251]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.763498306274414, + 'FR_Wheel_Angle': 41.626121520996094, + 'Location': array([-5.01486092e+01, 9.88239212e+01, 3.90597060e-02]), + 'Rotation': array([-4.61037755e-02, -1.61891373e+02, 7.69754291e-01]), + 'Velocity': array([-0.37435305, -0.31485081, -0.00735655]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3967.618408203125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7054.36474609, 11410.04199219, 142.23120117]), + 'frame': 18898, + 'frame_number': 18898, + 'framesequence': 76282, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.4943450503051, + 'timestamp_carla': 647494, + 'timestamp_device': 1518096, + 'timestamp_stream': 647.4943450503051, + 'transform': [array([-30.32237816, 79.56748199, -0.21053985]), + array([ 0.21343657, -128.76039124, 0.33673057])]} +{'AngularVelocity': array([-0.2751258 , -0.35021019, 5.70880699]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75916862487793, + 'FR_Wheel_Angle': 41.61601257324219, + 'Location': array([-5.02028961e+01, 9.87829590e+01, 3.82416435e-02]), + 'Rotation': array([-8.03571716e-02, -1.60995850e+02, 6.94211066e-01]), + 'Velocity': array([-0.38578662, -0.33166733, -0.00653923]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3975.61767578125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7054.04736328, 11425.62109375, 142.17961121]), + 'frame': 18899, + 'frame_number': 18899, + 'framesequence': 76286, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.5293557494879, + 'timestamp_carla': 647529, + 'timestamp_device': 1518129, + 'timestamp_stream': 647.5293557494879, + 'transform': [array([-30.36165047, 79.55253601, -0.21037857]), + array([ 0.2107728 , -128.93684387, 0.33576745])]} +{'AngularVelocity': array([-0.26958346, -0.33939391, 5.54180336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76019287109375, + 'FR_Wheel_Angle': 41.626197814941406, + 'Location': array([-5.02565727e+01, 9.87410431e+01, 3.75876129e-02]), + 'Rotation': array([-1.09829433e-01, -1.60107254e+02, 6.30989671e-01]), + 'Velocity': array([-0.38016906, -0.33933979, -0.00563415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3982.50048828125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7053.77392578, 11439.08007812, 142.13946533]), + 'frame': 18900, + 'frame_number': 18900, + 'framesequence': 76290, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.5626458488405, + 'timestamp_carla': 647562, + 'timestamp_device': 1518162, + 'timestamp_stream': 647.5626458488405, + 'transform': [array([-30.39785004, 79.53929138, -0.21007968]), + array([ 0.21013759, -129.09767151, 0.33452436])]} +{'AngularVelocity': array([-0.28771475, -0.37929636, 6.10703182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.746912002563477, + 'FR_Wheel_Angle': 41.6091423034668, + 'Location': array([-5.03089943e+01, 9.86986389e+01, 3.69434617e-02]), + 'Rotation': array([-1.39738828e-01, -1.59241364e+02, 5.64596415e-01]), + 'Velocity': array([-0.36789063, -0.34546745, -0.00575967]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3990.83349609375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7053.44628906, 11455.18652344, 142.1242218 ]), + 'frame': 18901, + 'frame_number': 18901, + 'framesequence': 76294, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.5948147512972, + 'timestamp_carla': 647594, + 'timestamp_device': 1518196, + 'timestamp_stream': 647.5948147512972, + 'transform': [array([-30.43369102, 79.52544403, -0.20971335]), + array([ 0.20888767, -129.25915527, 0.33294648])]} +{'AngularVelocity': array([-0.34535918, -0.40631306, 6.3844223 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74785614013672, + 'FR_Wheel_Angle': 41.59741973876953, + 'Location': array([-5.03635063e+01, 9.86533508e+01, 3.62295434e-02]), + 'Rotation': array([ -0.1707752 , -158.31361389, 0.49355975]), + 'Velocity': array([-0.37600607, -0.3686251 , -0.00633264]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3998.454345703125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7053.14648438, 11469.9296875 , 142.08531189]), + 'frame': 18902, + 'frame_number': 18902, + 'framesequence': 76298, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47989749908447266, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.62804505229, + 'timestamp_carla': 647628, + 'timestamp_device': 1518229, + 'timestamp_stream': 647.62804505229, + 'transform': [array([-30.47064781, 79.51148224, -0.2094271 ]), + array([ 0.20745333, -129.42503357, 0.33163521])]} +{'AngularVelocity': array([0.1059355 , 0.06510396, 6.75655603]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.36895179748535, + 'FR_Wheel_Angle': 37.719970703125, + 'Location': array([-5.04191971e+01, 9.86063919e+01, 3.61528285e-02]), + 'Rotation': array([ -0.17330238, -157.36473083, 0.49109873]), + 'Velocity': array([-0.38958475, -0.37892127, 0.00139856]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4006.24658203125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7052.84375 , 11484.7734375 , 142.02468872]), + 'frame': 18903, + 'frame_number': 18903, + 'framesequence': 76302, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4759605824947357, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.6631193496287, + 'timestamp_carla': 647663, + 'timestamp_device': 1518262, + 'timestamp_stream': 647.6631193496287, + 'transform': [array([-30.50912476, 79.49703217, -0.20906654]), + array([ 0.20632634, -129.5975647 , 0.32998213])]} +{'AngularVelocity': array([-0.10161987, 0.03349044, 6.02616787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.45663070678711, + 'FR_Wheel_Angle': 36.986515045166016, + 'Location': array([-5.04733696e+01, 9.85616684e+01, 3.63584794e-02]), + 'Rotation': array([ -0.1687603 , -156.54008484, 0.49780867]), + 'Velocity': array([-0.41646525, -0.38714004, 0.00132533]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4014.309814453125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7052.53320312, 11500.08984375, 141.98272705]), + 'frame': 18904, + 'frame_number': 18904, + 'framesequence': 76306, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45986512303352356, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.69574515149, + 'timestamp_carla': 647695, + 'timestamp_device': 1518296, + 'timestamp_stream': 647.69574515149, + 'transform': [array([-30.54315758, 79.48557281, -0.20879729]), + array([ 0.20559551, -129.74647522, 0.32886875])]} +{'AngularVelocity': array([-0.18930067, 0.0181725 , 6.7153821 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.734764099121094, + 'FR_Wheel_Angle': 37.77973937988281, + 'Location': array([-5.05282898e+01, 9.85159225e+01, 3.64499576e-02]), + 'Rotation': array([ -0.16299562, -155.70748901, 0.49070728]), + 'Velocity': array([-0.4099026 , -0.40559137, 0.00053588]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4022.78173828125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7052.20751953, 11516.08984375, 141.91717529]), + 'frame': 18905, + 'frame_number': 18905, + 'framesequence': 76310, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4364818334579468, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.7296486496925, + 'timestamp_carla': 647729, + 'timestamp_device': 1518329, + 'timestamp_stream': 647.7296486496925, + 'transform': [array([-30.57800674, 79.47423553, -0.20857975]), + array([ 0.20427729, -129.89750671, 0.32786468])]} +{'AngularVelocity': array([-0.14194205, 0.00977312, 6.10325289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.02992057800293, + 'FR_Wheel_Angle': 37.312355041503906, + 'Location': array([-5.05825195e+01, 9.84688950e+01, 3.64750177e-02]), + 'Rotation': array([ -0.15701921, -154.85409546, 0.48523632]), + 'Velocity': array([-0.39918169, -0.40229961, 0.00067927]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4030.05517578125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7051.92480469, 11529.98242188, 141.8842926 ]), + 'frame': 18906, + 'frame_number': 18906, + 'framesequence': 76314, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41322675347328186, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.7634240500629, + 'timestamp_carla': 647763, + 'timestamp_device': 1518362, + 'timestamp_stream': 647.7634240500629, + 'transform': [array([-30.61220551, 79.46360779, -0.20825137]), + array([ 0.20476906, -130.04324341, 0.32656014])]} +{'AngularVelocity': array([-1.64949715e-01, 1.86319579e-03, 6.43496704e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.339757919311523, + 'FR_Wheel_Angle': 37.44896697998047, + 'Location': array([-5.06369667e+01, 9.84204483e+01, 3.64681520e-02]), + 'Rotation': array([-1.51117921e-01, -1.53998596e+02, 4.77570593e-01]), + 'Velocity': array([-3.97182077e-01, -4.17517006e-01, 2.02360156e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4037.456787109375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7051.63769531, 11544.12109375, 141.85894775]), + 'frame': 18907, + 'frame_number': 18907, + 'framesequence': 76318, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3966551721096039, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.795950949192, + 'timestamp_carla': 647795, + 'timestamp_device': 1518396, + 'timestamp_stream': 647.795950949192, + 'transform': [array([-30.64392281, 79.45483398, -0.20781334]), + array([ 0.2056843 , -130.17523193, 0.32483214])]} +{'AngularVelocity': array([-1.56504020e-01, 7.77059060e-04, 7.57501984e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.275901794433594, + 'FR_Wheel_Angle': 37.489933013916016, + 'Location': array([-5.06908188e+01, 9.83708801e+01, 3.64522450e-02]), + 'Rotation': array([-1.45080045e-01, -1.53139740e+02, 4.69843090e-01]), + 'Velocity': array([-3.98413718e-01, -4.31631386e-01, -1.31893161e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4044.59033203125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7051.359375 , 11557.79882812, 141.80845642]), + 'frame': 18908, + 'frame_number': 18908, + 'framesequence': 76322, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3964354395866394, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.8288263492286, + 'timestamp_carla': 647828, + 'timestamp_device': 1518429, + 'timestamp_stream': 647.8288263492286, + 'transform': [array([-30.67549324, 79.44638824, -0.20730557]), + array([ 0.20632634, -130.30581665, 0.3227284 ])]} +{'AngularVelocity': array([-3.24944258e-01, 3.10199976e-04, 7.28797197e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.265830993652344, + 'FR_Wheel_Angle': 37.45893859863281, + 'Location': array([-5.07446518e+01, 9.83193054e+01, 3.62840183e-02]), + 'Rotation': array([-1.35046497e-01, -1.52286346e+02, 4.54490274e-01]), + 'Velocity': array([-0.37777424, -0.42370459, -0.00215394]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4051.00634765625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7051.10644531, 11570.24609375, 141.72328186]), + 'frame': 18909, + 'frame_number': 18909, + 'framesequence': 76326, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.40566423535346985, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.8614713512361, + 'timestamp_carla': 647861, + 'timestamp_device': 1518462, + 'timestamp_stream': 647.8614713512361, + 'transform': [array([-30.70692825, 79.43793488, -0.2068008 ]), + array([ 0.20657223, -130.43609619, 0.32058373])]} +{'AngularVelocity': array([-3.21210891e-01, 5.46798622e-03, 7.27525091e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.2700252532959, + 'FR_Wheel_Angle': 37.468292236328125, + 'Location': array([-5.07947998e+01, 9.82696915e+01, 3.60164531e-02]), + 'Rotation': array([-1.18893094e-01, -1.51480576e+02, 4.31141853e-01]), + 'Velocity': array([-0.37708345, -0.43620396, -0.00201215]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4057.380126953125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7050.85449219, 11582.60644531, 141.60955811]), + 'frame': 18910, + 'frame_number': 18910, + 'framesequence': 76330, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4176214039325714, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.8949429504573, + 'timestamp_carla': 647894, + 'timestamp_device': 1518496, + 'timestamp_stream': 647.8949429504573, + 'transform': [array([-30.74048233, 79.42881012, -0.20645541]), + array([ 0.20571846, -130.57591248, 0.31895128])]} +{'AngularVelocity': array([-3.22406948e-01, -4.95021923e-05, 7.30123281e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.27277374267578, + 'FR_Wheel_Angle': 37.461036682128906, + 'Location': array([-5.08456230e+01, 9.82180328e+01, 3.56844999e-02]), + 'Rotation': array([-1.03094868e-01, -1.50653839e+02, 4.08467978e-01]), + 'Velocity': array([-0.36871949, -0.43749511, -0.00190712]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4063.79541015625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7050.60302734, 11594.97460938, 141.49330139]), + 'frame': 18911, + 'frame_number': 18911, + 'framesequence': 76334, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42891934514045715, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.9279953502119, + 'timestamp_carla': 647928, + 'timestamp_device': 1518529, + 'timestamp_stream': 647.9279953502119, + 'transform': [array([-30.77394485, 79.41913605, -0.20591563]), + array([ 0.20556135, -130.71742249, 0.31658801])]} +{'AngularVelocity': array([-9.77389738e-02, -9.02655476e-04, 7.21529865e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.269039154052734, + 'FR_Wheel_Angle': 37.473087310791016, + 'Location': array([-5.08953438e+01, 9.81661301e+01, 3.54401693e-02]), + 'Rotation': array([-9.06092823e-02, -1.49826233e+02, 3.91729563e-01]), + 'Velocity': array([-3.55766356e-01, -4.33589697e-01, -5.06591787e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4070.75830078125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7050.33203125, 11608.29199219, 141.41624451]), + 'frame': 18912, + 'frame_number': 18912, + 'framesequence': 76338, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.43181249499320984, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.961403850466, + 'timestamp_carla': 647961, + 'timestamp_device': 1518562, + 'timestamp_stream': 647.961403850466, + 'transform': [array([-30.80791473, 79.40931702, -0.20540343]), + array([ 0.20553404, -130.86146545, 0.31434089])]} +{'AngularVelocity': array([-0.06937657, -0.02017258, 7.25218105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.266578674316406, + 'FR_Wheel_Angle': 37.46989440917969, + 'Location': array([-5.09444084e+01, 9.81137772e+01, 3.55404578e-02]), + 'Rotation': array([-9.02677774e-02, -1.49002228e+02, 3.92187506e-01]), + 'Velocity': array([-0.34928447, -0.43939522, 0.00100792]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4057.87158203125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7034.8515625 , 11608.73144531, 141.17663574]), + 'frame': 18913, + 'frame_number': 18913, + 'framesequence': 76342, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4281136691570282, + 'throttle_input': 0.07539482414722443, + 'timestamp': 647.9951220490038, + 'timestamp_carla': 647995, + 'timestamp_device': 1518596, + 'timestamp_stream': 647.9951220490038, + 'transform': [array([-30.84199142, 79.39997101, -0.20496757]), + array([ 0.20550673, -131.00491333, 0.31240794])]} +{'AngularVelocity': array([-0.06677227, -0.01726688, 7.30073261]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.658315658569336, + 'FR_Wheel_Angle': 35.084999084472656, + 'Location': array([-5.09929733e+01, 9.80603867e+01, 3.56844626e-02]), + 'Rotation': array([-9.04521868e-02, -1.48168259e+02, 3.92742693e-01]), + 'Velocity': array([-0.34251884, -0.44323629, 0.00100191]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.66259765625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7018.27783203, 11608.39453125, 140.93855286]), + 'frame': 18914, + 'frame_number': 18914, + 'framesequence': 76346, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42223578691482544, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.0281784497201, + 'timestamp_carla': 648028, + 'timestamp_device': 1518629, + 'timestamp_stream': 648.0281784497201, + 'transform': [array([-30.87678719, 79.3897934 , -0.20448071]), + array([ 0.20580725, -131.15284729, 0.3103247 ])]} +{'AngularVelocity': array([-0.05572435, 0.00937271, 6.25871658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.601051330566406, + 'FR_Wheel_Angle': 32.052371978759766, + 'Location': array([-5.10407639e+01, 9.80083466e+01, 3.58167924e-02]), + 'Rotation': array([-8.97213593e-02, -1.47414566e+02, 3.96298021e-01]), + 'Velocity': array([-0.35992759, -0.43121094, 0.0011143 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4035.207763671875, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7006.11621094, 11611.76171875, 140.75474548]), + 'frame': 18915, + 'frame_number': 18915, + 'framesequence': 76350, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.416779100894928, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.0623456500471, + 'timestamp_carla': 648062, + 'timestamp_device': 1518662, + 'timestamp_stream': 648.0623456500471, + 'transform': [array([-30.9115715 , 79.38049316, -0.2039635 ]), + array([ 0.20653808, -131.29855347, 0.30811852])]} +{'AngularVelocity': array([-0.08425977, -0.03149034, 6.38326216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.281185150146484, + 'FR_Wheel_Angle': 34.03919982910156, + 'Location': array([-5.10889473e+01, 9.79565506e+01, 3.59282978e-02]), + 'Rotation': array([-8.91749412e-02, -1.46702667e+02, 3.94221991e-01]), + 'Velocity': array([-0.34038299, -0.43022636, 0.00099467]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4043.189453125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7006.11621094, 11626.11523438, 140.65040588]), + 'frame': 18916, + 'frame_number': 18916, + 'framesequence': 76354, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4146184027194977, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.0947520509362, + 'timestamp_carla': 648094, + 'timestamp_device': 1518696, + 'timestamp_stream': 648.0947520509362, + 'transform': [array([-30.94433022, 79.37175751, -0.20340747]), + array([ 0.20724159, -131.43574524, 0.3058168 ])]} +{'AngularVelocity': array([-0.07750478, -0.01384255, 6.31498241]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.427099227905273, + 'FR_Wheel_Angle': 32.96681594848633, + 'Location': array([-5.11358376e+01, 9.79038086e+01, 3.60283926e-02]), + 'Rotation': array([-8.85329098e-02, -1.45970306e+02, 3.92884105e-01]), + 'Velocity': array([-0.3366344 , -0.43458876, 0.00059277]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4051.052978515625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7006.11669922, 11640.33300781, 140.53485107]), + 'frame': 18917, + 'frame_number': 18917, + 'framesequence': 76358, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41654103994369507, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.1280612498522, + 'timestamp_carla': 648128, + 'timestamp_device': 1518729, + 'timestamp_stream': 648.1280612498522, + 'transform': [array([-30.97808456, 79.36289215, -0.20297576]), + array([ 0.20690691, -131.57695007, 0.30390435])]} +{'AngularVelocity': array([-0.08434302, -0.01812157, 6.30605221]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.83321189880371, + 'FR_Wheel_Angle': 33.4129753112793, + 'Location': array([-5.11812630e+01, 9.78519287e+01, 3.61245610e-02]), + 'Rotation': array([-8.79181921e-02, -1.45274460e+02, 3.92234415e-01]), + 'Velocity': array([-0.32593879, -0.43042898, 0.00069203]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4058.51708984375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7006.11669922, 11653.765625 , 140.41156006]), + 'frame': 18918, + 'frame_number': 18918, + 'framesequence': 76362, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4194525182247162, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.1616719514132, + 'timestamp_carla': 648161, + 'timestamp_device': 1518762, + 'timestamp_stream': 648.1616719514132, + 'transform': [array([-31.01415062, 79.3523941 , -0.20258716]), + array([ 0.20608045, -131.73040771, 0.30213526])]} +{'AngularVelocity': array([-0.07734303, -0.01348913, 5.99029398]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.685649871826172, + 'FR_Wheel_Angle': 33.345218658447266, + 'Location': array([-5.12250443e+01, 9.78002930e+01, 3.62172201e-02]), + 'Rotation': array([-8.70644152e-02, -1.44578766e+02, 3.91189873e-01]), + 'Velocity': array([-0.31403154, -0.42763886, 0.00064358]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4066.2587890625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7006.11669922, 11667.6484375 , 140.31695557]), + 'frame': 18919, + 'frame_number': 18919, + 'framesequence': 76366, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4217597246170044, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.1944778524339, + 'timestamp_carla': 648194, + 'timestamp_device': 1518796, + 'timestamp_stream': 648.1944778524339, + 'transform': [array([-31.05046082, 79.34178925, -0.20230983]), + array([ 0.20501494, -131.88475037, 0.30085796])]} +{'AngularVelocity': array([-0.37068731, -0.05598374, 6.06330395]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.70114517211914, + 'FR_Wheel_Angle': 33.293983459472656, + 'Location': array([-5.12676735e+01, 9.77487869e+01, 3.62274051e-02]), + 'Rotation': array([-8.20305645e-02, -1.43899368e+02, 3.83026093e-01]), + 'Velocity': array([-0.31162229, -0.43634117, -0.00161376]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4074.830078125, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7006.1171875 , 11682.75976562, 140.23713684]), + 'frame': 18920, + 'frame_number': 18920, + 'framesequence': 76370, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4217597246170044, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.2297012507915, + 'timestamp_carla': 648229, + 'timestamp_device': 1518829, + 'timestamp_stream': 648.2297012507915, + 'transform': [array([-31.08864594, 79.33126831, -0.20218886]), + array([ 0.20168865, -132.04634094, 0.2999905 ])]} +{'AngularVelocity': array([-0.44110179, -0.04460661, 6.17035961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.70491600036621, + 'FR_Wheel_Angle': 33.298309326171875, + 'Location': array([-5.13102951e+01, 9.76957016e+01, 3.57213877e-02]), + 'Rotation': array([-5.92928678e-02, -1.43217865e+02, 3.48663330e-01]), + 'Velocity': array([-0.30880159, -0.44082972, -0.00351296]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4118.34765625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7032.04101562, 11721.25976562, 140.37649536]), + 'frame': 18921, + 'frame_number': 18921, + 'framesequence': 76374, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4203680753707886, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.2636598497629, + 'timestamp_carla': 648263, + 'timestamp_device': 1518862, + 'timestamp_stream': 648.2636598497629, + 'transform': [array([-31.12484741, 79.32144928, -0.20181541]), + array([ 0.20065045, -132.19920349, 0.29835126])]} +{'AngularVelocity': array([-0.43274662, -0.05420538, 6.27070665]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.708187103271484, + 'FR_Wheel_Angle': 33.30226135253906, + 'Location': array([-5.13525925e+01, 9.76416702e+01, 3.51234339e-02]), + 'Rotation': array([-3.52164544e-02, -1.42525162e+02, 3.12867105e-01]), + 'Velocity': array([-0.2991516 , -0.44118574, -0.00376812]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4306.5537109375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7164.93066406, 11857.30957031, 141.30291748]), + 'frame': 18922, + 'frame_number': 18922, + 'framesequence': 76378, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41888484358787537, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.2950542494655, + 'timestamp_carla': 648295, + 'timestamp_device': 1518896, + 'timestamp_stream': 648.2950542494655, + 'transform': [array([-31.15737915, 79.31341553, -0.20143783]), + array([ 0.20046604, -132.33450317, 0.29682806])]} +{'AngularVelocity': array([-0.35767812, -0.00994632, 6.36888409]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.699726104736328, + 'FR_Wheel_Angle': 33.30134201049805, + 'Location': array([-5.13936615e+01, 9.75879669e+01, 3.45538594e-02]), + 'Rotation': array([-1.09897740e-02, -1.41850449e+02, 2.76707023e-01]), + 'Velocity': array([-0.29737633, -0.43407312, -0.0036924 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4340.29443359375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7183.06738281, 11889.79882812, 141.35816956]), + 'frame': 18923, + 'frame_number': 18923, + 'framesequence': 76382, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4189947545528412, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.3290463499725, + 'timestamp_carla': 648329, + 'timestamp_device': 1518929, + 'timestamp_stream': 648.3290463499725, + 'transform': [array([-31.1932373 , 79.30406189, -0.2009652 ]), + array([ 0.20022698, -132.48524475, 0.29475844])]} +{'AngularVelocity': array([-0.4459376 , -0.07149966, 6.15631962]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.713035583496094, + 'FR_Wheel_Angle': 33.29437255859375, + 'Location': array([-5.14348946e+01, 9.75325241e+01, 3.39364521e-02]), + 'Rotation': array([ 1.39540760e-02, -1.41154648e+02, 2.38824949e-01]), + 'Velocity': array([-0.28784388, -0.44654596, -0.00390186]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4336.71044921875, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7174.31640625, 11896.18652344, 141.22715759]), + 'frame': 18924, + 'frame_number': 18924, + 'framesequence': 76386, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.364843249321, + 'timestamp_carla': 648364, + 'timestamp_device': 1518962, + 'timestamp_stream': 648.364843249321, + 'transform': [array([-31.22987175, 79.29498291, -0.20044735]), + array([ 0.20067778, -132.6381073 , 0.29251137])]} +{'AngularVelocity': array([-0.34403667, -0.04550267, 6.00403738]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.69937515258789, + 'FR_Wheel_Angle': 33.06589889526367, + 'Location': array([-5.14746857e+01, 9.74780121e+01, 3.33692431e-02]), + 'Rotation': array([ 3.82012464e-02, -1.40496323e+02, 2.02344492e-01]), + 'Velocity': array([-0.28262091, -0.4409245 , -0.00289338]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4332.81396484375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7164.58837891, 11903.28710938, 141.05039978]), + 'frame': 18925, + 'frame_number': 18925, + 'framesequence': 76390, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.420294851064682, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.3956013508141, + 'timestamp_carla': 648395, + 'timestamp_device': 1518996, + 'timestamp_stream': 648.3956013508141, + 'transform': [array([-31.26190186, 79.28721619, -0.2000296 ]), + array([ 0.20067778, -132.77140808, 0.29082429])]} +{'AngularVelocity': array([-0.38041463, -0.03526722, 5.22173548]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.89794921875, + 'FR_Wheel_Angle': 27.505617141723633, + 'Location': array([-5.15157738e+01, 9.74213333e+01, 3.28372866e-02]), + 'Rotation': array([ 6.15536608e-02, -1.39800278e+02, 1.68780997e-01]), + 'Velocity': array([-0.30932733, -0.47142377, -0.00311236]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4383.83837890625, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7195.17822266, 11947.72460938, 141.13885498]), + 'frame': 18926, + 'frame_number': 18926, + 'framesequence': 76394, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4201483428478241, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.4280561506748, + 'timestamp_carla': 648428, + 'timestamp_device': 1519029, + 'timestamp_stream': 648.4280561506748, + 'transform': [array([-31.29652214, 79.2784729 , -0.19958244]), + array([ 0.2006163 , -132.91651917, 0.28890505])]} +{'AngularVelocity': array([-0.43435785, -0.06476156, 4.87102413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.015220642089844, + 'FR_Wheel_Angle': 29.876588821411133, + 'Location': array([-5.15598488e+01, 9.73626633e+01, 3.22935767e-02]), + 'Rotation': array([ 8.48446041e-02, -1.39177902e+02, 1.35164097e-01]), + 'Velocity': array([-0.32776776, -0.48159128, -0.00316041]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4449.259765625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7237.04882812, 12000.83984375, 141.34434509]), + 'frame': 18927, + 'frame_number': 18927, + 'framesequence': 76398, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42003846168518066, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.4611360505223, + 'timestamp_carla': 648461, + 'timestamp_device': 1519062, + 'timestamp_stream': 648.4611360505223, + 'transform': [array([-31.33171654, 79.27006531, -0.19919078]), + array([ 0.20046604, -133.06295776, 0.28717697])]} +{'AngularVelocity': array([-0.44095349, -0.06297645, 5.18238735]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.144332885742188, + 'FR_Wheel_Angle': 28.82686996459961, + 'Location': array([-5.16021767e+01, 9.73037643e+01, 3.17900740e-02]), + 'Rotation': array([ 1.06612414e-01, -1.38550919e+02, 9.82756987e-02]), + 'Velocity': array([-0.31614405, -0.49223822, -0.00326758]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2906.13134765625, + 'focus_actor_name': 'BP_StreetLight_doble12_42', + 'focus_actor_pt': array([-6100.1171875 , 10959.59472656, 133.41465759]), + 'frame': 18928, + 'frame_number': 18928, + 'framesequence': 76402, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.4939406514168, + 'timestamp_carla': 648493, + 'timestamp_device': 1519096, + 'timestamp_stream': 648.4939406514168, + 'transform': [array([-31.36654472, 79.2614975 , -0.19868225]), + array([ 0.20055483, -133.2086792 , 0.28499129])]} +{'AngularVelocity': array([-0.45099267, -0.06645659, 5.06968641]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.01132583618164, + 'FR_Wheel_Angle': 29.28192710876465, + 'Location': array([-5.16441803e+01, 9.72442398e+01, 3.12548727e-02]), + 'Rotation': array([ 1.29992157e-01, -1.37933167e+02, 6.28779009e-02]), + 'Velocity': array([-0.31794307, -0.49769706, -0.00320823]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4426.5673828125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7206.68554688, 12004.5 , 140.94709778]), + 'frame': 18929, + 'frame_number': 18929, + 'framesequence': 76406, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.5290585495532, + 'timestamp_carla': 648528, + 'timestamp_device': 1519129, + 'timestamp_stream': 648.5290585495532, + 'transform': [array([-31.40244484, 79.25328827, -0.19816086]), + array([ 0.20088951, -133.35762024, 0.28269637])]} +{'AngularVelocity': array([0.07097562, 0.0072498 , 4.02679253]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.000375747680664, + 'FR_Wheel_Angle': 29.040483474731445, + 'Location': array([-5.16858253e+01, 9.71843567e+01, 3.11672483e-02]), + 'Rotation': array([ 1.32341743e-01, -1.37295349e+02, 6.05628043e-02]), + 'Velocity': array([-0.28189743, -0.45741054, 0.00093808]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4425.43896484375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7198.96777344, 12013.22167969, 140.77229309]), + 'frame': 18930, + 'frame_number': 18930, + 'framesequence': 76410, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.5614474490285, + 'timestamp_carla': 648561, + 'timestamp_device': 1519162, + 'timestamp_stream': 648.5614474490285, + 'transform': [array([-31.43631363, 79.24543762, -0.19771977]), + array([ 0.20101929, -133.49832153, 0.28084537])]} +{'AngularVelocity': array([0.11138045, 0.02614881, 4.10007095]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.061574935913086, + 'FR_Wheel_Angle': 29.105913162231445, + 'Location': array([-5.17261467e+01, 9.71252289e+01, 3.14349271e-02]), + 'Rotation': array([ 1.28960788e-01, -1.36653061e+02, 6.48257062e-02]), + 'Velocity': array([-0.27111885, -0.44359374, 0.00151832]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4424.26513671875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7191.07080078, 12022.14648438, 140.58680725]), + 'frame': 18931, + 'frame_number': 18931, + 'framesequence': 76414, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.5951891504228, + 'timestamp_carla': 648595, + 'timestamp_device': 1519195, + 'timestamp_stream': 648.5951891504228, + 'transform': [array([-31.47198677, 79.23696136, -0.19723323]), + array([ 0.20110808, -133.64720154, 0.27873486])]} +{'AngularVelocity': array([0.03392447, 0.00567456, 3.77655101]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.042919158935547, + 'FR_Wheel_Angle': 29.110145568847656, + 'Location': array([-5.17660332e+01, 9.70654144e+01, 3.16219591e-02]), + 'Rotation': array([ 1.27553776e-01, -1.36008057e+02, 6.66847229e-02]), + 'Velocity': array([-0.27803782, -0.46997029, 0.00103159]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4423.20068359375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7183.6171875 , 12030.56738281, 140.43925476]), + 'frame': 18932, + 'frame_number': 18932, + 'framesequence': 76418, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.6271019503474, + 'timestamp_carla': 648627, + 'timestamp_device': 1519229, + 'timestamp_stream': 648.6271019503474, + 'transform': [array([-31.50621796, 79.22862244, -0.19677265]), + array([ 0.20123102, -133.79055786, 0.27680191])]} +{'AngularVelocity': array([0.0907888 , 0.03141044, 3.93956804]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.03982925415039, + 'FR_Wheel_Angle': 29.102659225463867, + 'Location': array([-5.18056450e+01, 9.70046082e+01, 3.17697041e-02]), + 'Rotation': array([ 1.25812083e-01, -1.35355392e+02, 6.90656975e-02]), + 'Velocity': array([-0.26521873, -0.4532806 , 0.00106612]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4422.13623046875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7175.73486328, 12039.47265625, 140.27035522]), + 'frame': 18933, + 'frame_number': 18933, + 'framesequence': 76422, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.6612404510379, + 'timestamp_carla': 648661, + 'timestamp_device': 1519262, + 'timestamp_stream': 648.6612404510379, + 'transform': [array([-31.54311371, 79.2197113 , -0.19633506]), + array([ 0.20108075, -133.94499207, 0.27484158])]} +{'AngularVelocity': array([0.05395468, 0.01679874, 3.91387415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.045400619506836, + 'FR_Wheel_Angle': 29.10859489440918, + 'Location': array([-5.18435211e+01, 9.69447174e+01, 3.18950936e-02]), + 'Rotation': array([ 1.24323100e-01, -1.34720795e+02, 7.05323070e-02]), + 'Velocity': array([-0.25282204, -0.45157683, 0.00054124]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4421.16943359375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7168.15429688, 12048.04003906, 140.11714172]), + 'frame': 18934, + 'frame_number': 18934, + 'framesequence': 76425, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.6938171498477, + 'timestamp_carla': 648693, + 'timestamp_device': 1519287, + 'timestamp_stream': 648.6938171498477, + 'transform': [array([-31.578125 , 79.21149445, -0.1958998 ]), + array([ 0.20110808, -134.09107971, 0.27298376])]} +{'AngularVelocity': array([0.033225 , 0.02703683, 4.16005754]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.04303550720215, + 'FR_Wheel_Angle': 29.108863830566406, + 'Location': array([-5.18795776e+01, 9.68863449e+01, 3.20321172e-02]), + 'Rotation': array([ 1.23571776e-01, -1.34110519e+02, 7.23617226e-02]), + 'Velocity': array([-0.25411704, -0.45632753, 0.00109823]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4423.42138671875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7162.33642578, 12059.52832031, 139.9753418 ]), + 'frame': 18935, + 'frame_number': 18935, + 'framesequence': 76430, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.7281013503671, + 'timestamp_carla': 648728, + 'timestamp_device': 1519329, + 'timestamp_stream': 648.7281013503671, + 'transform': [array([-31.61789322, 79.20103455, -0.19551784]), + array([ 0.20046604, -134.25956726, 0.27120781])]} +{'AngularVelocity': array([0.07321288, 0.02542249, 3.77192259]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.045080184936523, + 'FR_Wheel_Angle': 29.112220764160156, + 'Location': array([-5.19160309e+01, 9.68255920e+01, 3.21330167e-02]), + 'Rotation': array([ 1.22677021e-01, -1.33475952e+02, 7.34966099e-02]), + 'Velocity': array([-0.23534878, -0.4411822 , 0.00054351]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4454.51318359375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7177.609375 , 12090.54882812, 139.98022461]), + 'frame': 18936, + 'frame_number': 18936, + 'framesequence': 76434, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.7611861489713, + 'timestamp_carla': 648761, + 'timestamp_device': 1519362, + 'timestamp_stream': 648.7611861489713, + 'transform': [array([-31.65308571, 79.19350433, -0.19507545]), + array([ 0.20055483, -134.40515137, 0.2693159 ])]} +{'AngularVelocity': array([0.08140926, 0.03356136, 3.87331223]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.047842025756836, + 'FR_Wheel_Angle': 25.980562210083008, + 'Location': array([-5.19507217e+01, 9.67667160e+01, 3.22680175e-02]), + 'Rotation': array([ 1.22301362e-01, -1.32866089e+02, 7.48709366e-02]), + 'Velocity': array([-0.23495765, -0.44564635, 0.00117346]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4454.875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7169.56933594, 12101.5625 , 139.84292603]), + 'frame': 18937, + 'frame_number': 18937, + 'framesequence': 76438, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.7946410514414, + 'timestamp_carla': 648794, + 'timestamp_device': 1519395, + 'timestamp_stream': 648.7946410514414, + 'transform': [array([-31.6893425 , 79.18637085, -0.1948016 ]), + array([ 0.19973521, -134.55392456, 0.26801819])]} +{'AngularVelocity': array([-0.00460438, 0.00599956, 2.96284366]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.2187442779541, + 'FR_Wheel_Angle': 24.187395095825195, + 'Location': array([-5.19860229e+01, 9.67084427e+01, 3.23846713e-02]), + 'Rotation': array([ 1.22007661e-01, -1.32330704e+02, 7.89318457e-02]), + 'Velocity': array([-0.25862661, -0.45666826, 0.00087006]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4455.0693359375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7162.59472656, 12111.11816406, 139.69662476]), + 'frame': 18938, + 'frame_number': 18938, + 'framesequence': 76442, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.8273599520326, + 'timestamp_carla': 648827, + 'timestamp_device': 1519429, + 'timestamp_stream': 648.8273599520326, + 'transform': [array([-31.72519875, 79.1787262 , -0.19431038]), + array([ 0.19979668, -134.70252991, 0.26592135])]} +{'AngularVelocity': array([0.02824404, 0.00934297, 3.75524974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.876426696777344, + 'FR_Wheel_Angle': 25.489824295043945, + 'Location': array([-5.20224648e+01, 9.66487579e+01, 3.24943066e-02]), + 'Rotation': array([ 1.21427096e-01, -1.31802536e+02, 7.75810704e-02]), + 'Velocity': array([-0.2473315 , -0.45499024, 0.00098788]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4455.2490234375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7155.45703125, 12120.89550781, 139.59658813]), + 'frame': 18939, + 'frame_number': 18939, + 'framesequence': 76446, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.8611243516207, + 'timestamp_carla': 648861, + 'timestamp_device': 1519462, + 'timestamp_stream': 648.8611243516207, + 'transform': [array([-31.76271439, 79.17028046, -0.193745 ]), + array([ 0.20032261, -134.85914612, 0.26351705])]} +{'AngularVelocity': array([0.08751792, 0.04112849, 3.07324123]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.04467010498047, + 'FR_Wheel_Angle': 24.745006561279297, + 'Location': array([-5.20570946e+01, 9.65897217e+01, 3.26145440e-02]), + 'Rotation': array([ 1.20498188e-01, -1.31267868e+02, 7.86720589e-02]), + 'Velocity': array([-0.23891263, -0.44092169, 0.00064837]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4455.5263671875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7148.33251953, 12130.65625 , 139.43492126]), + 'frame': 18940, + 'frame_number': 18940, + 'framesequence': 76450, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.8947956524789, + 'timestamp_carla': 648894, + 'timestamp_device': 1519495, + 'timestamp_stream': 648.8947956524789, + 'transform': [array([-31.79923248, 79.16313171, -0.19331734]), + array([ 0.20049337, -135.00920105, 0.26167288])]} +{'AngularVelocity': array([0.0507127 , 0.01412498, 3.17592669]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.391185760498047, + 'FR_Wheel_Angle': 24.983078002929688, + 'Location': array([-5.20917130e+01, 9.65300140e+01, 3.27355079e-02]), + 'Rotation': array([ 1.19972266e-01, -1.30735901e+02, 7.88881704e-02]), + 'Velocity': array([-0.23454478, -0.45226523, 0.0011752 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4455.90869140625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7140.828125 , 12140.9375 , 139.24850464]), + 'frame': 18941, + 'frame_number': 18941, + 'framesequence': 76454, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.9281333498657, + 'timestamp_carla': 648928, + 'timestamp_device': 1519529, + 'timestamp_stream': 648.9281333498657, + 'transform': [array([-31.83648109, 79.15513611, -0.19283508]), + array([ 0.20026113, -135.16430664, 0.25956234])]} +{'AngularVelocity': array([0.02473491, 0.0082974 , 3.00248122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.308069229125977, + 'FR_Wheel_Angle': 25.003599166870117, + 'Location': array([-5.21253319e+01, 9.64703598e+01, 3.28434668e-02]), + 'Rotation': array([ 1.18852116e-01, -1.30214096e+02, 8.01598877e-02]), + 'Velocity': array([-0.22970615, -0.45310131, 0.00085333]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4456.2119140625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7133.62158203, 12150.80957031, 139.10566711]), + 'frame': 18942, + 'frame_number': 18942, + 'framesequence': 76458, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.9618308506906, + 'timestamp_carla': 648961, + 'timestamp_device': 1519562, + 'timestamp_stream': 648.9618308506906, + 'transform': [array([-31.87298203, 79.14790344, -0.19232406]), + array([ 0.20043872, -135.31520081, 0.25736299])]} +{'AngularVelocity': array([0.05371914, 0.01935208, 2.97930765]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.290672302246094, + 'FR_Wheel_Angle': 24.96803855895996, + 'Location': array([-5.21577034e+01, 9.64118118e+01, 3.29572558e-02]), + 'Rotation': array([ 1.17827587e-01, -1.29697815e+02, 8.13530758e-02]), + 'Velocity': array([-0.2173218 , -0.43766212, 0.00079226]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4456.642578125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7126.17871094, 12161.00585938, 138.94342041]), + 'frame': 18943, + 'frame_number': 18943, + 'framesequence': 76462, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 648.9951614513993, + 'timestamp_carla': 648995, + 'timestamp_device': 1519595, + 'timestamp_stream': 648.9951614513993, + 'transform': [array([-31.90847588, 79.14112091, -0.19181244]), + array([ 0.20073925, -135.46150208, 0.25519097])]} +{'AngularVelocity': array([-0.03706954, -0.02173652, 4.55941486]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.31048583984375, + 'FR_Wheel_Angle': 24.970272064208984, + 'Location': array([-5.21900787e+01, 9.63522415e+01, 3.30640674e-02]), + 'Rotation': array([ 1.17499739e-01, -1.29168137e+02, 8.18795562e-02]), + 'Velocity': array([-0.22182645, -0.46794456, 0.00069945]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4457.048828125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7118.92480469, 12170.94335938, 138.7734375 ]), + 'frame': 18944, + 'frame_number': 18944, + 'framesequence': 76466, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.0280823521316, + 'timestamp_carla': 649027, + 'timestamp_device': 1519629, + 'timestamp_stream': 649.0280823521316, + 'transform': [array([-31.94374847, 79.13401031, -0.1912767 ]), + array([ 0.2011354 , -135.60780334, 0.25293705])]} +{'AngularVelocity': array([-0.05203991, -0.02185924, 4.51355457]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.312637329101562, + 'FR_Wheel_Angle': 24.966745376586914, + 'Location': array([-5.22207222e+01, 9.62943802e+01, 3.31654623e-02]), + 'Rotation': array([ 1.16454720e-01, -1.28670227e+02, 8.31568390e-02]), + 'Velocity': array([-2.14731961e-01, -4.62416649e-01, 4.14047245e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4457.45947265625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7111.88476562, 12180.58789062, 138.60585022]), + 'frame': 18945, + 'frame_number': 18945, + 'framesequence': 76470, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.0617676489055, + 'timestamp_carla': 649061, + 'timestamp_device': 1519662, + 'timestamp_stream': 649.0617676489055, + 'transform': [array([-31.97903824, 79.12734985, -0.19078247]), + array([ 0.20140861, -135.75332642, 0.25081292])]} +{'AngularVelocity': array([0.09201462, 0.03924517, 3.89277172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.298316955566406, + 'FR_Wheel_Angle': 24.953826904296875, + 'Location': array([-5.22512016e+01, 9.62360001e+01, 3.32732685e-02]), + 'Rotation': array([ 1.16441056e-01, -1.28164230e+02, 8.41131583e-02]), + 'Velocity': array([-0.20443203, -0.43258345, 0.00084702]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4457.9443359375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7104.84960938, 12190.2265625 , 138.43237305]), + 'frame': 18946, + 'frame_number': 18946, + 'framesequence': 76474, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.0950195491314, + 'timestamp_carla': 649094, + 'timestamp_device': 1519695, + 'timestamp_stream': 649.0950195491314, + 'transform': [array([-32.01388931, 79.12096405, -0.19040798]), + array([ 0.20140861, -135.89645386, 0.24918725])]} +{'AngularVelocity': array([0.09767774, 0.01585066, 3.88166022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.295852661132812, + 'FR_Wheel_Angle': 24.938688278198242, + 'Location': array([-5.22817192e+01, 9.61764984e+01, 3.33767198e-02]), + 'Rotation': array([ 1.16044909e-01, -1.27635628e+02, 8.46245512e-02]), + 'Velocity': array([-0.19644375, -0.43538654, 0.00072686]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4458.42431640625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7097.84228516, 12199.82617188, 138.26823425]), + 'frame': 18947, + 'frame_number': 18947, + 'framesequence': 76478, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.1290241517127, + 'timestamp_carla': 649128, + 'timestamp_device': 1519729, + 'timestamp_stream': 649.1290241517127, + 'transform': [array([-32.05080032, 79.11380005, -0.19001156]), + array([ 0.20110808, -136.04933167, 0.24740462])]} +{'AngularVelocity': array([0.09812144, 0.01197327, 3.86330986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.293075561523438, + 'FR_Wheel_Angle': 24.469806671142578, + 'Location': array([-5.23125267e+01, 9.61149063e+01, 3.34893316e-02]), + 'Rotation': array([ 1.15341395e-01, -1.27094284e+02, 8.55186433e-02]), + 'Velocity': array([-0.19453493, -0.44426432, 0.00090784]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4458.91259765625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7090.94921875, 12209.26953125, 138.14346313]), + 'frame': 18948, + 'frame_number': 18948, + 'framesequence': 76482, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4196905493736267, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.1620405502617, + 'timestamp_carla': 649161, + 'timestamp_device': 1519762, + 'timestamp_stream': 649.1620405502617, + 'transform': [array([-32.08612823, 79.10723114, -0.18958527]), + array([ 0.2011354 , -136.19511414, 0.24557407])]} +{'AngularVelocity': array([0.06505238, 0.03662441, 2.6490171 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.862943649291992, + 'FR_Wheel_Angle': 19.113201141357422, + 'Location': array([-5.23434906e+01, 9.60524216e+01, 3.35943103e-02]), + 'Rotation': array([ 1.14487626e-01, -1.26574493e+02, 8.80805776e-02]), + 'Velocity': array([-0.2118779 , -0.45976573, 0.00096665]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4459.52001953125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7083.58544922, 12219.35742188, 138.00654602]), + 'frame': 18949, + 'frame_number': 18949, + 'framesequence': 76486, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4135746657848358, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.1966983489692, + 'timestamp_carla': 649196, + 'timestamp_device': 1519795, + 'timestamp_stream': 649.1966983489692, + 'transform': [array([-32.1232338 , 79.10063934, -0.18923217]), + array([ 0.20098513, -136.34744263, 0.24396898])]} +{'AngularVelocity': array([0.05913049, 0.00934766, 2.59092903]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.43006706237793, + 'FR_Wheel_Angle': 21.552444458007812, + 'Location': array([-5.23746490e+01, 9.59922867e+01, 3.37106213e-02]), + 'Rotation': array([ 1.13169394e-01, -1.26164528e+02, 9.05817971e-02]), + 'Velocity': array([-0.20991544, -0.43961313, 0.00090346]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4460.1103515625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7076.55908203, 12228.98339844, 137.86651611]), + 'frame': 18950, + 'frame_number': 18950, + 'framesequence': 76490, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3955748379230499, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.2276073507965, + 'timestamp_carla': 649227, + 'timestamp_device': 1519829, + 'timestamp_stream': 649.2276073507965, + 'transform': [array([-32.15704346, 79.0946579 , -0.18889171]), + array([ 0.20110808, -136.48562622, 0.2425824 ])]} +{'AngularVelocity': array([0.05179039, 0.01662025, 2.65676045]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.459291458129883, + 'FR_Wheel_Angle': 20.503923416137695, + 'Location': array([-5.24049606e+01, 9.59318542e+01, 3.38074379e-02]), + 'Rotation': array([ 1.12301961e-01, -1.25721222e+02, 8.92669708e-02]), + 'Velocity': array([-0.19980402, -0.44150603, 0.0006838 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4460.43115234375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7069.00146484, 12238.82519531, 137.74142456]), + 'frame': 18951, + 'frame_number': 18951, + 'framesequence': 76494, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.37310707569122314, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.2617774493992, + 'timestamp_carla': 649261, + 'timestamp_device': 1519862, + 'timestamp_stream': 649.2617774493992, + 'transform': [array([-32.19271469, 79.08961487, -0.18848541]), + array([ 0.20178427, -136.62817383, 0.24083392])]} +{'AngularVelocity': array([0.05474122, 0.02299342, 2.78190899]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.43510627746582, + 'FR_Wheel_Angle': 20.962854385375977, + 'Location': array([-5.24346046e+01, 9.58718338e+01, 3.39172259e-02]), + 'Rotation': array([ 1.12301961e-01, -1.25303841e+02, 8.98969471e-02]), + 'Velocity': array([-0.20341001, -0.44956118, 0.00084916]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4434.05078125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7043.76757812, 12228.38964844, 137.52313232]), + 'frame': 18952, + 'frame_number': 18952, + 'framesequence': 76498, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3495040833950043, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.2945890501142, + 'timestamp_carla': 649294, + 'timestamp_device': 1519895, + 'timestamp_stream': 649.2945890501142, + 'transform': [array([-32.22584152, 79.08562469, -0.18802792]), + array([ 0.20269269, -136.75830078, 0.23896249])]} +{'AngularVelocity': array([0.06256991, 0.0235325 , 2.62220979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.367267608642578, + 'FR_Wheel_Angle': 20.755962371826172, + 'Location': array([-5.24639015e+01, 9.58113098e+01, 3.40362824e-02]), + 'Rotation': array([ 1.11489169e-01, -1.24870293e+02, 9.04495865e-02]), + 'Velocity': array([-0.19700897, -0.4465737 , 0.00124746]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4434.3798828125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7036.80664062, 12237.63769531, 137.38682556]), + 'frame': 18953, + 'frame_number': 18953, + 'framesequence': 76502, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3348735272884369, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.3278277516365, + 'timestamp_carla': 649327, + 'timestamp_device': 1519929, + 'timestamp_stream': 649.3278277516365, + 'transform': [array([-32.25829697, 79.08239746, -0.18756615]), + array([ 0.2035806 , -136.88346863, 0.23704997])]} +{'AngularVelocity': array([0.0363779 , 0.01344173, 2.37228298]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.420907974243164, + 'FR_Wheel_Angle': 20.793668746948242, + 'Location': array([-5.24933395e+01, 9.57493057e+01, 3.41174975e-02]), + 'Rotation': array([ 1.10601246e-01, -1.24429665e+02, 9.11637470e-02]), + 'Velocity': array([-0.19387397, -0.45199504, 0.00102434]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4434.62548828125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7030.45019531, 12246.08300781, 137.24201965]), + 'frame': 18954, + 'frame_number': 18954, + 'framesequence': 76506, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3374919891357422, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.3642208501697, + 'timestamp_carla': 649364, + 'timestamp_device': 1519962, + 'timestamp_stream': 649.3642208501697, + 'transform': [array([-32.29375839, 79.07902527, -0.18710682]), + array([ 0.2035806 , -137.01979065, 0.2349395 ])]} +{'AngularVelocity': array([0.06445862, 0.03432016, 2.37655973]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.411731719970703, + 'FR_Wheel_Angle': 20.798789978027344, + 'Location': array([-5.25211906e+01, 9.56894150e+01, 3.42288502e-02]), + 'Rotation': array([ 1.10170946e-01, -1.24008759e+02, 9.18821543e-02]), + 'Velocity': array([-0.19115348, -0.44999143, 0.00057507]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4434.806640625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7024.33496094, 12254.20507812, 137.09335327]), + 'frame': 18955, + 'frame_number': 18955, + 'framesequence': 76510, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.34866178035736084, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.3942525498569, + 'timestamp_carla': 649394, + 'timestamp_device': 1519995, + 'timestamp_stream': 649.3942525498569, + 'transform': [array([-32.32474518, 79.07537079, -0.18675834]), + array([ 0.20300004, -137.14054871, 0.23349139])]} +{'AngularVelocity': array([0.06578029, 0.02760316, 2.22053218]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.41228485107422, + 'FR_Wheel_Angle': 20.7971134185791, + 'Location': array([-5.25489006e+01, 9.56286469e+01, 3.43328007e-02]), + 'Rotation': array([ 1.09419622e-01, -1.23580986e+02, 9.27214399e-02]), + 'Velocity': array([-0.18489791, -0.44593108, 0.00063227]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4435.01513671875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7017.67871094, 12263.04882812, 136.92764282]), + 'frame': 18956, + 'frame_number': 18956, + 'framesequence': 76514, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3608020544052124, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.4280177503824, + 'timestamp_carla': 649427, + 'timestamp_device': 1520029, + 'timestamp_stream': 649.4280177503824, + 'transform': [array([-32.35821152, 79.07204437, -0.18631397]), + array([ 0.20202333, -137.27058411, 0.23142867])]} +{'AngularVelocity': array([0.09183507, 0.03469061, 2.43401003]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.412471771240234, + 'FR_Wheel_Angle': 20.793132781982422, + 'Location': array([-5.25769043e+01, 9.55662384e+01, 3.44148539e-02]), + 'Rotation': array([ 1.08996153e-01, -1.23139450e+02, 9.33578834e-02]), + 'Velocity': array([-1.80588588e-01, -4.44292814e-01, 2.33650208e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4435.30419921875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7011.79003906, 12270.87109375, 136.81987 ]), + 'frame': 18957, + 'frame_number': 18957, + 'framesequence': 76518, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3705069124698639, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.4612984508276, + 'timestamp_carla': 649461, + 'timestamp_device': 1520062, + 'timestamp_stream': 649.4612984508276, + 'transform': [array([-32.39083862, 79.06908417, -0.18587306]), + array([ 0.2011354 , -137.3974762 , 0.22940694])]} +{'AngularVelocity': array([0.07184134, 0.02983371, 2.57638001]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.420490264892578, + 'FR_Wheel_Angle': 20.802072525024414, + 'Location': array([-5.26035957e+01, 9.55052414e+01, 3.45205590e-02]), + 'Rotation': array([ 1.07718907e-01, -1.22715202e+02, 9.43992138e-02]), + 'Velocity': array([-1.74641341e-01, -4.40379351e-01, 3.58352641e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4436.6025390625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7006.11230469, 12280.06054688, 136.66523743]), + 'frame': 18958, + 'frame_number': 18958, + 'framesequence': 76522, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.37167882919311523, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.4948933497071, + 'timestamp_carla': 649494, + 'timestamp_device': 1520095, + 'timestamp_stream': 649.4948933497071, + 'transform': [array([-32.42571259, 79.06504822, -0.18559512]), + array([ 0.19949615, -137.53538513, 0.22795205])]} +{'AngularVelocity': array([0.02659573, 0.01143142, 2.47552371]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.414653778076172, + 'FR_Wheel_Angle': 20.795352935791016, + 'Location': array([-5.26297951e+01, 9.54444351e+01, 3.46275233e-02]), + 'Rotation': array([ 1.07855514e-01, -1.22295586e+02, 9.46842059e-02]), + 'Velocity': array([-0.1801458 , -0.46606424, 0.000908 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4446.0966796875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7006.11230469, 12295.09472656, 136.54676819]), + 'frame': 18959, + 'frame_number': 18959, + 'framesequence': 76526, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3671376705169678, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.5285531505942, + 'timestamp_carla': 649528, + 'timestamp_device': 1520129, + 'timestamp_stream': 649.5285531505942, + 'transform': [array([-32.45969009, 79.06171417, -0.18532848]), + array([ 0.19841698, -137.66848755, 0.22659962])]} +{'AngularVelocity': array([0.04944161, 0.03925284, 2.59727859]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.001142501831055, + 'FR_Wheel_Angle': 17.30362892150879, + 'Location': array([-5.26557808e+01, 9.53827744e+01, 3.47208306e-02]), + 'Rotation': array([ 1.06708042e-01, -1.21873161e+02, 9.60966572e-02]), + 'Velocity': array([-0.17714339, -0.45414007, 0.00071895]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4456.58251953125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7006.11230469, 12311.48144531, 136.47520447]), + 'frame': 18960, + 'frame_number': 18960, + 'framesequence': 76530, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3608569800853729, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.5618404522538, + 'timestamp_carla': 649561, + 'timestamp_device': 1520162, + 'timestamp_stream': 649.5618404522538, + 'transform': [array([-32.49318314, 79.0582428 , -0.1849834 ]), + array([ 0.19796619, -137.79998779, 0.22499451])]} +{'AngularVelocity': array([0.05148597, 0.02778017, 2.92943454]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.288784980773926, + 'FR_Wheel_Angle': 15.995829582214355, + 'Location': array([-5.26827583e+01, 9.53220901e+01, 3.48218828e-02]), + 'Rotation': array([ 1.06899284e-01, -1.21513596e+02, 9.96389166e-02]), + 'Velocity': array([-0.19623134, -0.45273829, 0.00068067]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4466.7421875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7006.11230469, 12327.390625 , 136.40905762]), + 'frame': 18961, + 'frame_number': 18961, + 'framesequence': 76534, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3552354574203491, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.5958887524903, + 'timestamp_carla': 649595, + 'timestamp_device': 1520195, + 'timestamp_stream': 649.5958887524903, + 'transform': [array([-32.52629852, 79.05545044, -0.18466969]), + array([ 0.19747442, -137.92863464, 0.22348501])]} +{'AngularVelocity': array([ 0.06508298, -0.01387904, 2.38613939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.97353458404541, + 'FR_Wheel_Angle': 17.064828872680664, + 'Location': array([-5.27109108e+01, 9.52597504e+01, 3.49125192e-02]), + 'Rotation': array([ 1.06168456e-01, -1.21157249e+02, 9.76996869e-02]), + 'Velocity': array([-1.78375006e-01, -4.46321964e-01, 3.27367772e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4476.8701171875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7006.11230469, 12343.16601562, 136.32241821]), + 'frame': 18962, + 'frame_number': 18962, + 'framesequence': 76538, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35455796122550964, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.6287066489458, + 'timestamp_carla': 649628, + 'timestamp_device': 1520229, + 'timestamp_stream': 649.6287066489458, + 'transform': [array([-32.55786514, 79.05297852, -0.18438953]), + array([ 0.19690068, -138.05078125, 0.22215995])]} +{'AngularVelocity': array([0.08564363, 0.00910181, 2.31439066]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.121861457824707, + 'FR_Wheel_Angle': 16.49679946899414, + 'Location': array([-5.27378120e+01, 9.51977844e+01, 3.50244790e-02]), + 'Rotation': array([ 1.05055131e-01, -1.20795601e+02, 9.81456339e-02]), + 'Velocity': array([-0.17479253, -0.43880177, 0.00076332]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4554.3701171875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7051.38378906, 12408.84179688, 136.50466919]), + 'frame': 18963, + 'frame_number': 18963, + 'framesequence': 76542, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35681021213531494, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.6635218523443, + 'timestamp_carla': 649663, + 'timestamp_device': 1520262, + 'timestamp_stream': 649.6635218523443, + 'transform': [array([-32.59207916, 79.05003357, -0.18417579]), + array([ 0.19558245, -138.18397522, 0.22095105])]} +{'AngularVelocity': array([ 0.06940152, -0.00265159, 2.48443222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.463708877563477, + 'FR_Wheel_Angle': 16.643890380859375, + 'Location': array([-5.27646713e+01, 9.51355515e+01, 3.51304524e-02]), + 'Rotation': array([ 1.04358457e-01, -1.20446388e+02, 9.84028056e-02]), + 'Velocity': array([-0.17139623, -0.44294104, 0.0011211 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4564.4833984375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7051.69628906, 12424.20507812, 136.43772888]), + 'frame': 18964, + 'frame_number': 18964, + 'framesequence': 76546, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3601611256599426, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.695145752281, + 'timestamp_carla': 649694, + 'timestamp_device': 1520295, + 'timestamp_stream': 649.695145752281, + 'transform': [array([-32.62357712, 79.04750061, -0.18403655]), + array([ 0.19427106, -138.30632019, 0.220186 ])]} +{'AngularVelocity': array([ 0.03291249, -0.01681037, 3.34815478]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.376203536987305, + 'FR_Wheel_Angle': 16.6656494140625, + 'Location': array([-5.27915993e+01, 9.50718842e+01, 3.52144502e-02]), + 'Rotation': array([ 1.04180872e-01, -1.20078506e+02, 9.86202136e-02]), + 'Velocity': array([-1.75362691e-01, -4.65864539e-01, 4.65421675e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4575.62744140625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7052.03808594, 12441.02734375, 136.38214111]), + 'frame': 18965, + 'frame_number': 18965, + 'framesequence': 76550, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36219367384910583, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.7279482521117, + 'timestamp_carla': 649727, + 'timestamp_device': 1520329, + 'timestamp_stream': 649.7279482521117, + 'transform': [array([-32.6574707 , 79.04405212, -0.18381816]), + array([ 0.19292551, -138.43986511, 0.21901114])]} +{'AngularVelocity': array([0.08122803, 0.00654699, 2.20953417]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.361685752868652, + 'FR_Wheel_Angle': 16.62205696105957, + 'Location': array([-5.28171120e+01, 9.50100784e+01, 3.53242755e-02]), + 'Rotation': array([ 1.03094868e-01, -1.19735085e+02, 9.94651765e-02]), + 'Velocity': array([-0.16531263, -0.4421019 , 0.00054842]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4585.9375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7052.35449219, 12456.56054688, 136.36131287]), + 'frame': 18966, + 'frame_number': 18966, + 'framesequence': 76554, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36175423860549927, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.7625032514334, + 'timestamp_carla': 649762, + 'timestamp_device': 1520362, + 'timestamp_stream': 649.7625032514334, + 'transform': [array([-32.69072723, 79.04195404, -0.18324637]), + array([ 0.19415495, -138.56838989, 0.21662745])]} +{'AngularVelocity': array([0.09959295, 0.01963215, 2.47603512]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.368847846984863, + 'FR_Wheel_Angle': 16.63036346435547, + 'Location': array([-5.28426971e+01, 9.49471741e+01, 3.54149155e-02]), + 'Rotation': array([ 1.02876306e-01, -1.19389473e+02, 9.98459533e-02]), + 'Velocity': array([-0.16387749, -0.44363892, 0.00049173]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4597.3515625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7052.70068359, 12473.578125 , 136.31002808]), + 'frame': 18967, + 'frame_number': 18967, + 'framesequence': 76558, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36027100682258606, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.7966842502356, + 'timestamp_carla': 649796, + 'timestamp_device': 1520395, + 'timestamp_stream': 649.7966842502356, + 'transform': [array([-32.72381592, 79.03990173, -0.18138061]), + array([ 0.20245363, -138.69659424, 0.20991345])]} +{'AngularVelocity': array([-0.04647803, -0.01972657, 3.37130976]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.372233390808105, + 'FR_Wheel_Angle': 16.631961822509766, + 'Location': array([-5.28679543e+01, 9.48839493e+01, 3.55076492e-02]), + 'Rotation': array([ 1.02364041e-01, -1.19028809e+02, 1.00121766e-01]), + 'Velocity': array([-0.17703782, -0.49894539, 0.00058209]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4608.33203125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7053.03662109, 12490.08984375, 136.15774536]), + 'frame': 18968, + 'frame_number': 18968, + 'framesequence': 76562, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35884273052215576, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.8278795517981, + 'timestamp_carla': 649827, + 'timestamp_device': 1520429, + 'timestamp_stream': 649.8278795517981, + 'transform': [array([-32.75344086, 79.03822327, -0.17904396]), + array([ 0.21304041, -138.81112671, 0.20172411])]} +{'AngularVelocity': array([-0.03931366, -0.02299116, 3.30762172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.371150970458984, + 'FR_Wheel_Angle': 16.633033752441406, + 'Location': array([-5.28926735e+01, 9.48206940e+01, 3.55937853e-02]), + 'Rotation': array([ 1.01742491e-01, -1.18683495e+02, 1.00744233e-01]), + 'Velocity': array([-1.71275914e-01, -4.93905544e-01, 3.59268190e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4619.39501953125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7053.37402344, 12506.67773438, 135.65991211]), + 'frame': 18969, + 'frame_number': 18969, + 'framesequence': 76566, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35908079147338867, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.8627416491508, + 'timestamp_carla': 649862, + 'timestamp_device': 1520462, + 'timestamp_stream': 649.8627416491508, + 'transform': [array([-32.78563309, 79.03668213, -0.17618671]), + array([ 0.22564211, -138.93527222, 0.19158138])]} +{'AngularVelocity': array([-0.03295962, -0.02163339, 3.38616514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.377147674560547, + 'FR_Wheel_Angle': 16.63681411743164, + 'Location': array([-5.29161301e+01, 9.47594681e+01, 3.57129574e-02]), + 'Rotation': array([ 1.00909211e-01, -1.18353104e+02, 1.01638697e-01]), + 'Velocity': array([-0.16624056, -0.48612389, 0.00074678]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4629.3466796875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7053.67724609, 12521.58105469, 135.04119873]), + 'frame': 18970, + 'frame_number': 18970, + 'framesequence': 76570, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.8953437507153, + 'timestamp_carla': 649895, + 'timestamp_device': 1520495, + 'timestamp_stream': 649.8953437507153, + 'transform': [array([-32.8149147 , 79.03585052, -0.17353275]), + array([ 0.23693925, -139.04727173, 0.18227188])]} +{'AngularVelocity': array([-0.04778064, -0.01445334, 3.19077134]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.317815780639648, + 'FR_Wheel_Angle': 15.608637809753418, + 'Location': array([-5.29395142e+01, 9.46972809e+01, 3.57773490e-02]), + 'Rotation': array([ 1.00137398e-01, -1.18018547e+02, 1.02138430e-01]), + 'Velocity': array([-0.16270135, -0.48422918, 0.00048756]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4640.2021484375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7054.0078125 , 12537.828125 , 134.26409912]), + 'frame': 18971, + 'frame_number': 18971, + 'framesequence': 76574, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36030763387680054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.9272253513336, + 'timestamp_carla': 649926, + 'timestamp_device': 1520529, + 'timestamp_stream': 649.9272253513336, + 'transform': [array([-32.84404755, 79.03496552, -0.17092864]), + array([ 0.24841397, -139.15878296, 0.17322885])]} +{'AngularVelocity': array([-0.03331983, 0.01846711, 2.52030849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.154428482055664, + 'FR_Wheel_Angle': 10.747867584228516, + 'Location': array([-5.29626846e+01, 9.46367264e+01, 3.58959101e-02]), + 'Rotation': array([ 1.00513056e-01, -1.17714455e+02, 1.04550272e-01]), + 'Velocity': array([-0.18073356, -0.4890565 , 0.00069851]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4650.029296875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7054.30761719, 12552.57421875, 133.5511322 ]), + 'frame': 18972, + 'frame_number': 18972, + 'framesequence': 76578, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36003297567367554, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.9640236496925, + 'timestamp_carla': 649963, + 'timestamp_device': 1520562, + 'timestamp_stream': 649.9640236496925, + 'transform': [array([-32.87717819, 79.03410339, -0.16804065]), + array([ 0.26046243, -139.28582764, 0.16293581])]} +{'AngularVelocity': array([-0.04022551, -0.03770297, 2.66411257]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.488249778747559, + 'FR_Wheel_Angle': 13.382890701293945, + 'Location': array([-5.29877930e+01, 9.45753403e+01, 3.59768942e-02]), + 'Rotation': array([ 9.99188349e-02, -1.17483055e+02, 1.05405107e-01]), + 'Velocity': array([-0.17862482, -0.47754827, 0.00060607]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4659.88330078125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7054.60742188, 12567.30957031, 132.85726929]), + 'frame': 18973, + 'frame_number': 18973, + 'framesequence': 76582, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 649.9940613508224, + 'timestamp_carla': 649993, + 'timestamp_device': 1520595, + 'timestamp_stream': 649.9940613508224, + 'transform': [array([-32.90481567, 79.03314972, -0.16553742]), + array([ 0.27154782, -139.39207458, 0.15432297])]} +{'AngularVelocity': array([-0.03435668, -0.01127946, 2.83965397]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.048527717590332, + 'FR_Wheel_Angle': 12.073613166809082, + 'Location': array([-5.30121994e+01, 9.45128784e+01, 3.60639468e-02]), + 'Rotation': array([ 9.99734700e-02, -1.17215263e+02, 1.03354685e-01]), + 'Velocity': array([-0.17695923, -0.49572563, 0.00055206]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4671.203125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7054.95019531, 12584.18945312, 132.05989075]), + 'frame': 18974, + 'frame_number': 18974, + 'framesequence': 76586, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.0291215516627, + 'timestamp_carla': 650028, + 'timestamp_device': 1520629, + 'timestamp_stream': 650.0291215516627, + 'transform': [array([-32.93768311, 79.03143311, -0.1626393 ]), + array([ 0.28436124, -139.51951599, 0.14413235])]} +{'AngularVelocity': array([-0.0331752 , -0.00892296, 1.71813202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.253210067749023, + 'FR_Wheel_Angle': 12.678995132446289, + 'Location': array([-5.30362549e+01, 9.44515915e+01, 3.61509211e-02]), + 'Rotation': array([ 9.87030566e-02, -1.16958488e+02, 1.04824923e-01]), + 'Velocity': array([-0.17497303, -0.47910801, 0.00125065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4680.6259765625, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15478516, 12598.25878906, 131.39465332]), + 'frame': 18975, + 'frame_number': 18975, + 'framesequence': 76590, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.0611645504832, + 'timestamp_carla': 650060, + 'timestamp_device': 1520662, + 'timestamp_stream': 650.0611645504832, + 'transform': [array([-32.96786499, 79.02981567, -0.16004959]), + array([ 2.95473963e-01, -1.39636673e+02, 1.35109693e-01])]} +{'AngularVelocity': array([-0.05122477, -0.0072142 , 1.8868984 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.08663272857666, + 'FR_Wheel_Angle': 12.441774368286133, + 'Location': array([-5.30606194e+01, 9.43891678e+01, 3.62628065e-02]), + 'Rotation': array([ 9.95978117e-02, -1.16689049e+02, 1.04257382e-01]), + 'Velocity': array([-0.18349616, -0.51121366, 0.00089207]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4691.6669921875, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15429688, 12614.88378906, 130.59822083]), + 'frame': 18976, + 'frame_number': 18976, + 'framesequence': 76594, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.0955038517714, + 'timestamp_carla': 650095, + 'timestamp_device': 1520695, + 'timestamp_stream': 650.0955038517714, + 'transform': [array([-32.99953842, 79.02857208, -0.15762459]), + array([ 3.05357248e-01, -1.39759003e+02, 1.26524195e-01])]} +{'AngularVelocity': array([-0.00669453, -0.00657693, 1.97313392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.147566795349121, + 'FR_Wheel_Angle': 12.466009140014648, + 'Location': array([-5.30853004e+01, 9.43252487e+01, 3.63588221e-02]), + 'Rotation': array([ 9.85049829e-02, -1.16403572e+02, 1.04708008e-01]), + 'Velocity': array([-0.17381975, -0.49206236, 0.00066565]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4701.9033203125, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15429688, 12630.23828125, 129.894104 ]), + 'frame': 18977, + 'frame_number': 18977, + 'framesequence': 76598, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.1277777515352, + 'timestamp_carla': 650127, + 'timestamp_device': 1520728, + 'timestamp_stream': 650.1277777515352, + 'transform': [array([-33.02959061, 79.02720642, -0.15549031]), + array([ 3.13662767e-01, -1.39875580e+02, 1.18976764e-01])]} +{'AngularVelocity': array([-0.03919263, -0.01110839, 1.86482513]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.141587257385254, + 'FR_Wheel_Angle': 12.469696998596191, + 'Location': array([-5.31097679e+01, 9.42607193e+01, 3.64543796e-02]), + 'Rotation': array([ 9.78492871e-02, -1.16130104e+02, 1.05097272e-01]), + 'Velocity': array([-0.17678195, -0.50935394, 0.0013871 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4712.63427734375, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15478516, 12646.34570312, 129.22169495]), + 'frame': 18978, + 'frame_number': 18978, + 'framesequence': 76602, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.1615809500217, + 'timestamp_carla': 650161, + 'timestamp_device': 1520762, + 'timestamp_stream': 650.1615809500217, + 'transform': [array([-33.06023788, 79.0258255 , -0.15331735]), + array([ 3.22268784e-01, -1.39994659e+02, 1.11210823e-01])]} +{'AngularVelocity': array([0.04559188, 0.00941751, 1.60952866]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.140085220336914, + 'FR_Wheel_Angle': 12.467058181762695, + 'Location': array([-5.31334839e+01, 9.41973648e+01, 3.65543626e-02]), + 'Rotation': array([ 9.65242311e-02, -1.15855194e+02, 1.05756037e-01]), + 'Velocity': array([-0.15935813, -0.46261707, 0.00090941]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4722.96240234375, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15478516, 12661.765625 , 128.63140869]), + 'frame': 18979, + 'frame_number': 18979, + 'framesequence': 76606, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.1955760493875, + 'timestamp_carla': 650195, + 'timestamp_device': 1520795, + 'timestamp_stream': 650.1955760493875, + 'transform': [array([-33.09001923, 79.02511597, -0.15121499]), + array([ 3.31482708e-01, -1.40108917e+02, 1.03800043e-01])]} +{'AngularVelocity': array([-0.02649628, -0.01063965, 1.62633407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.14204216003418, + 'FR_Wheel_Angle': 12.467222213745117, + 'Location': array([-5.31570511e+01, 9.41331329e+01, 3.66359986e-02]), + 'Rotation': array([ 9.65652093e-02, -1.15579338e+02, 1.06108397e-01]), + 'Velocity': array([-0.16792814, -0.49814785, 0.00060821]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4733.59619140625, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15527344, 12677.5859375 , 128.01864624]), + 'frame': 18980, + 'frame_number': 18980, + 'framesequence': 76610, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.2316142506897, + 'timestamp_carla': 650231, + 'timestamp_device': 1520828, + 'timestamp_stream': 650.2316142506897, + 'transform': [array([-33.12355804, 79.0234375 , -0.14906426]), + array([ 3.40512246e-01, -1.40239639e+02, 9.61160585e-02])]} +{'AngularVelocity': array([0.04715019, 0.00975495, 1.67052674]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.137351036071777, + 'FR_Wheel_Angle': 12.459321022033691, + 'Location': array([-5.31804543e+01, 9.40688171e+01, 3.67267877e-02]), + 'Rotation': array([ 9.53972489e-02, -1.15293953e+02, 1.06736332e-01]), + 'Velocity': array([-0.15364507, -0.45968771, 0.00080065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4743.81396484375, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15478516, 12692.84863281, 127.43076324]), + 'frame': 18981, + 'frame_number': 18981, + 'framesequence': 76614, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.2639769501984, + 'timestamp_carla': 650263, + 'timestamp_device': 1520862, + 'timestamp_stream': 650.2639769501984, + 'transform': [array([-33.15427017, 79.02162933, -0.14705549]), + array([ 3.49179745e-01, -1.40359787e+02, 8.91150385e-02])]} +{'AngularVelocity': array([-0.08138945, 0.00707656, 2.49510813]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.142791748046875, + 'FR_Wheel_Angle': 12.459797859191895, + 'Location': array([-5.32031136e+01, 9.40047607e+01, 3.68172750e-02]), + 'Rotation': array([ 9.64695886e-02, -1.15033028e+02, 1.06541462e-01]), + 'Velocity': array([-0.17800993, -0.53979987, 0.00061884]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4755.67431640625, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15478516, 12710.35742188, 126.81941223]), + 'frame': 18982, + 'frame_number': 18982, + 'framesequence': 76618, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.2964238524437, + 'timestamp_carla': 650296, + 'timestamp_device': 1520895, + 'timestamp_stream': 650.2964238524437, + 'transform': [array([-33.18392944, 79.02041626, -0.14506982]), + array([ 3.57293993e-01, -1.40474991e+02, 8.20935667e-02])]} +{'AngularVelocity': array([-0.02611819, 0.00271414, 1.6472851 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.970905303955078, + 'FR_Wheel_Angle': 8.066902160644531, + 'Location': array([-5.32268333e+01, 9.39379883e+01, 3.69163416e-02]), + 'Rotation': array([ 9.60870981e-02, -1.14736176e+02, 1.07605286e-01]), + 'Velocity': array([-0.17462444, -0.52716208, 0.00100507]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4766.68017578125, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15527344, 12726.51367188, 126.26335907]), + 'frame': 18983, + 'frame_number': 18983, + 'framesequence': 76622, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.3298703506589, + 'timestamp_carla': 650329, + 'timestamp_device': 1520928, + 'timestamp_stream': 650.3298703506589, + 'transform': [array([-33.21537399, 79.01876068, -0.14308777]), + array([ 3.65544885e-01, -1.40597992e+02, 7.50652403e-02])]} +{'AngularVelocity': array([-2.46791858e-02, -5.85330999e-04, 7.67657876e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.794056415557861, + 'FR_Wheel_Angle': 8.181207656860352, + 'Location': array([-5.32523994e+01, 9.38710785e+01, 3.70115936e-02]), + 'Rotation': array([ 9.53152850e-02, -1.14532593e+02, 1.11426950e-01]), + 'Velocity': array([-0.19528629, -0.51668954, 0.00091963]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4777.27490234375, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15527344, 12742.09667969, 125.70142365]), + 'frame': 18984, + 'frame_number': 18984, + 'framesequence': 76626, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.3616521507502, + 'timestamp_carla': 650361, + 'timestamp_device': 1520962, + 'timestamp_stream': 650.3616521507502, + 'transform': [array([-33.24480057, 79.01776886, -0.14135489]), + array([ 3.72709751e-01, -1.40711853e+02, 6.89726099e-02])]} +{'AngularVelocity': array([-0.04213525, -0.02159236, 1.22221804]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.1891450881958, + 'FR_Wheel_Angle': 8.451327323913574, + 'Location': array([-5.32785568e+01, 9.38025970e+01, 3.71046737e-02]), + 'Rotation': array([ 9.49191302e-02, -1.14322540e+02, 1.08475178e-01]), + 'Velocity': array([-0.18544772, -0.53180939, 0.00081762]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4788.705078125, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15527344, 12758.79785156, 125.13646698]), + 'frame': 18985, + 'frame_number': 18985, + 'framesequence': 76630, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.394899751991, + 'timestamp_carla': 650394, + 'timestamp_device': 1520995, + 'timestamp_stream': 650.394899751991, + 'transform': [array([-33.27613068, 79.01678467, -0.14048737]), + array([ 3.74232888e-01, -1.40833359e+02, 6.56531230e-02])]} +{'AngularVelocity': array([-0.03512331, -0.00239556, 0.96536094]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.498550891876221, + 'FR_Wheel_Angle': 8.292802810668945, + 'Location': array([-5.33032951e+01, 9.37365494e+01, 3.72236893e-02]), + 'Rotation': array([ 9.40175503e-02, -1.14118134e+02, 1.09282270e-01]), + 'Velocity': array([-0.18719803, -0.5243935 , 0.00080711]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4799.31591796875, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15527344, 12774.34277344, 124.64667511]), + 'frame': 18986, + 'frame_number': 18986, + 'framesequence': 76634, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.4272933490574, + 'timestamp_carla': 650427, + 'timestamp_device': 1521028, + 'timestamp_stream': 650.4272933490574, + 'transform': [array([-33.30641556, 79.01579285, -0.14004493]), + array([ 3.73993814e-01, -1.40950851e+02, 6.37952611e-02])]} +{'AngularVelocity': array([-0.03023816, -0.01049524, 1.00206816]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.745511054992676, + 'FR_Wheel_Angle': 8.25822639465332, + 'Location': array([-5.33280830e+01, 9.36698608e+01, 3.73100564e-02]), + 'Rotation': array([ 9.33208689e-02, -1.13918358e+02, 1.08898759e-01]), + 'Velocity': array([-0.17894705, -0.51651031, 0.00052826]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4810.72314453125, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15576172, 12790.99609375, 124.38586426]), + 'frame': 18987, + 'frame_number': 18987, + 'framesequence': 76638, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.4615040495992, + 'timestamp_carla': 650461, + 'timestamp_device': 1521062, + 'timestamp_stream': 650.4615040495992, + 'transform': [array([-33.33872986, 79.01448822, -0.13983649]), + array([ 3.72709751e-01, -1.41076874e+02, 6.26409203e-02])]} +{'AngularVelocity': array([-0.05746915, 0.00703124, 1.51865172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.728758335113525, + 'FR_Wheel_Angle': 8.324061393737793, + 'Location': array([-5.33530884e+01, 9.36013260e+01, 3.74026373e-02]), + 'Rotation': array([ 9.38672870e-02, -1.13709801e+02, 1.08830743e-01]), + 'Velocity': array([-0.18956648, -0.55036968, 0.00078905]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4821.8388671875, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15527344, 12807.16601562, 124.24408722]), + 'frame': 18988, + 'frame_number': 18988, + 'framesequence': 76642, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.4945847503841, + 'timestamp_carla': 650494, + 'timestamp_device': 1521095, + 'timestamp_stream': 650.4945847503841, + 'transform': [array([-33.36921692, 79.01412964, -0.13983501]), + array([ 3.70968044e-01, -1.41194107e+02, 6.23130612e-02])]} +{'AngularVelocity': array([-0.05587723, 0.00618501, 1.48153389]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.688482284545898, + 'FR_Wheel_Angle': 8.30226993560791, + 'Location': array([-5.33775139e+01, 9.35330124e+01, 3.75121571e-02]), + 'Rotation': array([ 9.34096649e-02, -1.13535385e+02, 1.09218322e-01]), + 'Velocity': array([-0.18874533, -0.55336577, 0.00118912]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4825.63037109375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7049.9765625 , 12818.16503906, 124.14948273]), + 'frame': 18989, + 'frame_number': 18989, + 'framesequence': 76646, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.5273583494127, + 'timestamp_carla': 650527, + 'timestamp_device': 1521128, + 'timestamp_stream': 650.5273583494127, + 'transform': [array([-33.40149689, 79.01242065, -0.13975953]), + array([ 3.69506389e-01, -1.41320862e+02, 6.16778173e-02])]} +{'AngularVelocity': array([-0.05755995, 0.00614949, 1.49400473]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.687872886657715, + 'FR_Wheel_Angle': 8.30158805847168, + 'Location': array([-5.34019852e+01, 9.34639740e+01, 3.76171395e-02]), + 'Rotation': array([ 9.30749848e-02, -1.13360588e+02, 1.09513380e-01]), + 'Velocity': array([-0.1887476 , -0.55879688, 0.00120419]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4816.27392578125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7037.09960938, 12818.42578125, 124.11021423]), + 'frame': 18990, + 'frame_number': 18990, + 'framesequence': 76650, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.5624813511968, + 'timestamp_carla': 650562, + 'timestamp_device': 1521162, + 'timestamp_stream': 650.5624813511968, + 'transform': [array([-33.43517303, 79.0110321 , -0.13968004]), + array([ 3.67949098e-01, -1.41452621e+02, 6.09060004e-02])]} +{'AngularVelocity': array([-0.0596737 , 0.00520385, 1.51077867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.687479019165039, + 'FR_Wheel_Angle': 8.301702499389648, + 'Location': array([-5.34266357e+01, 9.33937378e+01, 3.77039239e-02]), + 'Rotation': array([ 9.26993191e-02, -1.13182716e+02, 1.09796211e-01]), + 'Velocity': array([-0.1879708 , -0.56240511, 0.00057178]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4806.3828125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7023.26269531, 12818.70800781, 124.04399109]), + 'frame': 18991, + 'frame_number': 18991, + 'framesequence': 76654, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.5984930507839, + 'timestamp_carla': 650598, + 'timestamp_device': 1521195, + 'timestamp_stream': 650.5984930507839, + 'transform': [array([-33.46978378, 79.0098114 , -0.13966461]), + array([ 3.66364509e-01, -1.41587708e+02, 6.03937097e-02])]} +{'AngularVelocity': array([-0.06190178, 0.00499643, 1.50210583]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.685964584350586, + 'FR_Wheel_Angle': 8.299452781677246, + 'Location': array([-5.34512825e+01, 9.33227921e+01, 3.77961993e-02]), + 'Rotation': array([ 9.22553614e-02, -1.13003181e+02, 1.10090740e-01]), + 'Velocity': array([-1.86862096e-01, -5.64943254e-01, 3.95183568e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4806.685546875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7015.50488281, 12827.26074219, 123.97491455]), + 'frame': 18992, + 'frame_number': 18992, + 'framesequence': 76658, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.63044565171, + 'timestamp_carla': 650630, + 'timestamp_device': 1521228, + 'timestamp_stream': 650.63044565171, + 'transform': [array([-33.49920273, 79.00965881, -0.13956982]), + array([ 3.65483403e-01, -1.41700760e+02, 5.98199405e-02])]} +{'AngularVelocity': array([-0.05803626, 0.00604326, 1.52947176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.686591148376465, + 'FR_Wheel_Angle': 8.301447868347168, + 'Location': array([-5.34754448e+01, 9.32528610e+01, 3.79096121e-02]), + 'Rotation': array([ 9.15996656e-02, -1.12809021e+02, 1.10427670e-01]), + 'Velocity': array([-0.1837306 , -0.56143802, 0.0010977 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4813.16162109375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7011.36914062, 12840.85546875, 123.93386078]), + 'frame': 18993, + 'frame_number': 18993, + 'framesequence': 76662, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.6632032506168, + 'timestamp_carla': 650663, + 'timestamp_device': 1521262, + 'timestamp_stream': 650.6632032506168, + 'transform': [array([-33.53054047, 79.00872803, -0.13940889]), + array([ 3.64376903e-01, -1.41822861e+02, 5.88841587e-02])]} +{'AngularVelocity': array([-0.05988252, 0.00556258, 1.51022553]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.204868316650391, + 'FR_Wheel_Angle': 6.408563613891602, + 'Location': array([-5.34995499e+01, 9.31820221e+01, 3.80060859e-02]), + 'Rotation': array([ 9.15381908e-02, -1.12630638e+02, 1.10628113e-01]), + 'Velocity': array([-0.18407518, -0.56850189, 0.00106299]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4804.97998046875, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-6999.48779297, 12841.640625 , 123.87628937]), + 'frame': 18994, + 'frame_number': 18994, + 'framesequence': 76666, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35598623752593994, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.6961496509612, + 'timestamp_carla': 650696, + 'timestamp_device': 1521295, + 'timestamp_stream': 650.6961496509612, + 'transform': [array([-33.56191635, 79.0080719 , -0.13925368]), + array([ 3.63673389e-01, -1.41944412e+02, 5.80167323e-02])]} +{'AngularVelocity': array([-0.0452019 , 0.04403673, 0.5768826 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.3750038146972656, + 'FR_Wheel_Angle': 2.7483596801757812, + 'Location': array([-5.35247726e+01, 9.31110153e+01, 3.81103791e-02]), + 'Rotation': array([ 9.15040374e-02, -1.12506996e+02, 1.14205241e-01]), + 'Velocity': array([-0.20936859, -0.56495571, 0.00105215]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4807.30517578125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-6993.52734375, 12851.140625 , 123.79830933]), + 'frame': 18995, + 'frame_number': 18995, + 'framesequence': 76670, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3409528136253357, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.7291697524488, + 'timestamp_carla': 650729, + 'timestamp_device': 1521328, + 'timestamp_stream': 650.7291697524488, + 'transform': [array([-33.5929718 , 79.00788116, -0.13884376]), + array([ 3.64349604e-01, -1.42063934e+02, 5.62749803e-02])]} +{'AngularVelocity': array([-0.069235 , -0.01520486, 0.77626395]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.778692245483398, + 'FR_Wheel_Angle': 4.961157321929932, + 'Location': array([-5.35517273e+01, 9.30399780e+01, 3.82065475e-02]), + 'Rotation': array([ 9.13332850e-02, -1.12448967e+02, 1.13121189e-01]), + 'Velocity': array([-2.06862807e-01, -5.69108248e-01, 5.02347946e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4817.76318359375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-6992.60351562, 12867.02246094, 123.7338562 ]), + 'frame': 18996, + 'frame_number': 18996, + 'framesequence': 76674, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3184301555156708, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.7643114514649, + 'timestamp_carla': 650764, + 'timestamp_device': 1521362, + 'timestamp_stream': 650.7643114514649, + 'transform': [array([-33.62358475, 79.0087204 , -0.13812855]), + array([ 3.67156804e-01, -1.42179047e+02, 5.34540862e-02])]} +{'AngularVelocity': array([-0.05747178, 0.0191353 , 0.72044408]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.6474416255950928, + 'FR_Wheel_Angle': 3.8214304447174072, + 'Location': array([-5.35781441e+01, 9.29676743e+01, 3.83035950e-02]), + 'Rotation': array([ 9.09644514e-02, -1.12353790e+02, 1.11951172e-01]), + 'Velocity': array([-2.06134558e-01, -5.70437372e-01, 5.28850534e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8734.5625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9393.296875 , 15963.765625 , 127.4324646]), + 'frame': 18997, + 'frame_number': 18997, + 'framesequence': 76678, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2925199270248413, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.7957440502942, + 'timestamp_carla': 650795, + 'timestamp_device': 1521395, + 'timestamp_stream': 650.7957440502942, + 'transform': [array([-33.65117645, 79.00999451, -0.13753243]), + array([ 3.69561017e-01, -1.42280899e+02, 5.12752272e-02])]} +{'AngularVelocity': array([-0.04566305, 0.00630986, 0.82715404]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.1530961990356445, + 'FR_Wheel_Angle': 4.254249572753906, + 'Location': array([-5.36044388e+01, 9.28969040e+01, 3.84232625e-02]), + 'Rotation': array([ 9.04863402e-02, -1.12257751e+02, 1.11933842e-01]), + 'Velocity': array([-0.20136489, -0.55950141, 0.00129075]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8704.744140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9361.8671875 , 15952.40820312, 126.9707489 ]), + 'frame': 18998, + 'frame_number': 18998, + 'framesequence': 76682, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2765343189239502, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.8301397524774, + 'timestamp_carla': 650830, + 'timestamp_device': 1521428, + 'timestamp_stream': 650.8301397524774, + 'transform': [array([-33.68130112, 79.01187134, -0.13689703]), + array([ 3.71575922e-01, -1.42390564e+02, 4.87821624e-02])]} +{'AngularVelocity': array([-0.04344817, 0.01209216, 0.6083492 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9701623916625977, + 'FR_Wheel_Angle': 4.184373378753662, + 'Location': array([-5.36309662e+01, 9.28246689e+01, 3.85307223e-02]), + 'Rotation': array([ 9.08551738e-02, -1.12139206e+02, 1.11716740e-01]), + 'Velocity': array([-0.20465232, -0.57291055, 0.00129303]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8694.5927734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9344.09472656, 15955.16503906, 126.63117981]), + 'frame': 18999, + 'frame_number': 18999, + 'framesequence': 76686, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2746116816997528, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.8614011518657, + 'timestamp_carla': 650861, + 'timestamp_device': 1521462, + 'timestamp_stream': 650.8614011518657, + 'transform': [array([-33.70744705, 79.01431274, -0.13623156]), + array([ 3.73256147e-01, -1.42484039e+02, 4.62481268e-02])]} +{'AngularVelocity': array([ 2.19549760e-02, -2.85538088e-04, 1.88345385e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9764363765716553, + 'FR_Wheel_Angle': 4.135927677154541, + 'Location': array([-5.36580505e+01, 9.27506943e+01, 3.86323072e-02]), + 'Rotation': array([ 9.04453620e-02, -1.12023689e+02, 1.11999609e-01]), + 'Velocity': array([-0.19544452, -0.54808557, 0.00118779]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8692.3330078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9330.29882812, 15965. , 126.24947357]), + 'frame': 19000, + 'frame_number': 19000, + 'framesequence': 76690, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.28360241651535034, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.8953917510808, + 'timestamp_carla': 650895, + 'timestamp_device': 1521495, + 'timestamp_stream': 650.8953917510808, + 'transform': [array([-33.73760986, 79.01622009, -0.13553749]), + array([ 3.74444604e-01, -1.42593872e+02, 4.34340313e-02])]} +{'AngularVelocity': array([-2.94870026e-02, -3.72940645e-04, 1.17301929e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9777474403381348, + 'FR_Wheel_Angle': 4.136093616485596, + 'Location': array([-5.36845169e+01, 9.26775360e+01, 3.87451462e-02]), + 'Rotation': array([ 8.99740756e-02, -1.11928032e+02, 1.11904874e-01]), + 'Velocity': array([-0.19979295, -0.56994379, 0.0006395 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4904.72216796875, + 'focus_actor_name': 'BP_StreetLight_simple14_35', + 'focus_actor_pt': array([-7013.18359375, 12970.68066406, 122.80954742]), + 'frame': 19001, + 'frame_number': 19001, + 'framesequence': 76694, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2967863976955414, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.9275069497526, + 'timestamp_carla': 650927, + 'timestamp_device': 1521528, + 'timestamp_stream': 650.9275069497526, + 'transform': [array([-33.76574707, 79.01837921, -0.13487917]), + array([ 3.75032008e-01, -1.42696289e+02, 4.07770239e-02])]} +{'AngularVelocity': array([-2.43441444e-02, -1.09439436e-03, 1.18685186e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9785516262054443, + 'FR_Wheel_Angle': 4.135454177856445, + 'Location': array([-5.37103653e+01, 9.26054764e+01, 3.88498977e-02]), + 'Rotation': array([ 8.91203061e-02, -1.11838020e+02, 1.12134501e-01]), + 'Velocity': array([-0.19324133, -0.55468744, 0.00088476]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4899.73974609375, + 'focus_actor_name': 'BP_StreetLight_simple14_35', + 'focus_actor_pt': array([-7003.45214844, 12973.89355469, 122.56463623]), + 'frame': 19002, + 'frame_number': 19002, + 'framesequence': 76698, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30883514881134033, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.9616500511765, + 'timestamp_carla': 650961, + 'timestamp_device': 1521562, + 'timestamp_stream': 650.9616500511765, + 'transform': [array([-33.79683304, 79.01999664, -0.13414724]), + array([ 3.75824302e-01, -1.42811462e+02, 3.77580076e-02])]} +{'AngularVelocity': array([0.00614418, 0.00192049, 0.85355097]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.976499557495117, + 'FR_Wheel_Angle': 4.134817600250244, + 'Location': array([-5.37362823e+01, 9.25331726e+01, 3.89524363e-02]), + 'Rotation': array([ 8.92978907e-02, -1.11741463e+02, 1.12380818e-01]), + 'Velocity': array([-0.18960829, -0.54158127, 0.00076241]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8645.5673828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9267.30273438, 15960.1640625 , 125.00520325]), + 'frame': 19003, + 'frame_number': 19003, + 'framesequence': 76702, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3131565451622009, + 'throttle_input': 0.07539482414722443, + 'timestamp': 650.9953754507005, + 'timestamp_carla': 650995, + 'timestamp_device': 1521595, + 'timestamp_stream': 650.9953754507005, + 'transform': [array([-33.82791138, 79.02140045, -0.13375716]), + array([ 3.74697328e-01, -1.42927460e+02, 3.59275043e-02])]} +{'AngularVelocity': array([-0.03061052, -0.00459927, 1.23215115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9772539138793945, + 'FR_Wheel_Angle': 4.136388778686523, + 'Location': array([-5.37626686e+01, 9.24594116e+01, 3.90510075e-02]), + 'Rotation': array([ 8.95369425e-02, -1.11644592e+02, 1.12356193e-01]), + 'Velocity': array([-0.19551365, -0.56677407, 0.00113604]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21220.25, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-16854.80078125, 25989.8203125 , 132.83639526]), + 'frame': 19004, + 'frame_number': 19004, + 'framesequence': 76706, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30929291248321533, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.0288736522198, + 'timestamp_carla': 651028, + 'timestamp_device': 1521628, + 'timestamp_stream': 651.0288736522198, + 'transform': [array([-33.85866547, 79.02298737, -0.13360251]), + array([ 3.72921467e-01, -1.43041992e+02, 3.49644013e-02])]} +{'AngularVelocity': array([-0.06196502, 0.01647917, 0.55309182]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.97622013092041, + 'FR_Wheel_Angle': 4.0854902267456055, + 'Location': array([-5.37881088e+01, 9.23873672e+01, 3.91605645e-02]), + 'Rotation': array([ 8.94208327e-02, -1.11558136e+02, 1.12506405e-01]), + 'Velocity': array([-0.20204763, -0.58347154, 0.0008086 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8615.0859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9222.59765625, 15959.85253906, 124.25476837]), + 'frame': 19005, + 'frame_number': 19005, + 'framesequence': 76710, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30260932445526123, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.061432749033, + 'timestamp_carla': 651061, + 'timestamp_device': 1521662, + 'timestamp_stream': 651.061432749033, + 'transform': [array([-33.88889694, 79.02455902, -0.13358918]), + array([ 3.71090978e-01, -1.43154327e+02, 3.45818847e-02])]} +{'AngularVelocity': array([-0.02425908, 0.03124248, 0.11883696]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3577616512775421, + 'FR_Wheel_Angle': -1.190040946006775, + 'Location': array([-5.38150673e+01, 9.23127975e+01, 3.92655469e-02]), + 'Rotation': array([ 8.95027965e-02, -1.11444473e+02, 1.14161313e-01]), + 'Velocity': array([-0.21130168, -0.57637918, 0.00099826]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8606.34375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9204.30175781, 15964.68164062, 124.10377502]), + 'frame': 19006, + 'frame_number': 19006, + 'framesequence': 76714, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2966948449611664, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.0958503521979, + 'timestamp_carla': 651095, + 'timestamp_device': 1521695, + 'timestamp_stream': 651.0958503521979, + 'transform': [array([-33.92063904, 79.02667999, -0.13362868]), + array([ 3.69076073e-01, -1.43271317e+02, 3.42950039e-02])]} +{'AngularVelocity': array([-0.03265057, 0.00210105, -0.85142559]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.4657815098762512, + 'FR_Wheel_Angle': 0.3464724123477936, + 'Location': array([-5.38442268e+01, 9.22394028e+01, 3.93706039e-02]), + 'Rotation': array([ 8.87856260e-02, -1.11451035e+02, 1.17019400e-01]), + 'Velocity': array([-0.22737993, -0.55665654, 0.00078753]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21164.939453125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-16722.37890625, 26026.32226562, 131.62490845]), + 'frame': 19007, + 'frame_number': 19007, + 'framesequence': 76718, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2936185896396637, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.1285452507436, + 'timestamp_carla': 651128, + 'timestamp_device': 1521728, + 'timestamp_stream': 651.1285452507436, + 'transform': [array([-33.95098877, 79.02871704, -0.13365585]), + array([ 3.67095321e-01, -1.43383133e+02, 3.40286270e-02])]} +{'AngularVelocity': array([-0.06418978, 0.01260702, 0.10649939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.3112435042858124, + 'FR_Wheel_Angle': -0.09890390932559967, + 'Location': array([-5.38724823e+01, 9.21673203e+01, 3.94758880e-02]), + 'Rotation': array([ 8.86831731e-02, -1.11431595e+02, 1.13355681e-01]), + 'Velocity': array([-2.19817877e-01, -5.73713481e-01, 4.50849533e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8570.8740234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9156.98046875, 15959.84179688, 123.97708893]), + 'frame': 19008, + 'frame_number': 19008, + 'framesequence': 76722, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.295596182346344, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.1645450517535, + 'timestamp_carla': 651164, + 'timestamp_device': 1521762, + 'timestamp_stream': 651.1645450517535, + 'transform': [array([-33.98302841, 79.03149414, -0.13361052]), + array([ 3.65141898e-01, -1.43500076e+02, 3.33114453e-02])]} +{'AngularVelocity': array([-0.06102245, 0.02374775, -0.17443116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.09010631591081619, + 'FR_Wheel_Angle': 0.0977020338177681, + 'Location': array([-5.39007492e+01, 9.20945587e+01, 3.95820886e-02]), + 'Rotation': array([ 8.92295837e-02, -1.11453140e+02, 1.13820910e-01]), + 'Velocity': array([-2.28020549e-01, -5.78800321e-01, 4.47988510e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8565.8759765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9141.3046875 , 15967.26660156, 123.9322052 ]), + 'frame': 19009, + 'frame_number': 19009, + 'framesequence': 76726, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299203485250473, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.1956122517586, + 'timestamp_carla': 651195, + 'timestamp_device': 1521795, + 'timestamp_stream': 651.1956122517586, + 'transform': [array([-34.01076126, 79.03380585, -0.13351344]), + array([ 3.63646090e-01, -1.43601593e+02, 3.26557271e-02])]} +{'AngularVelocity': array([-0.05419661, 0.02016776, -0.08192629]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.048219408839941025, + 'FR_Wheel_Angle': -0.05706800892949104, + 'Location': array([-5.39289246e+01, 9.20221481e+01, 3.97092700e-02]), + 'Rotation': array([ 8.94413218e-02, -1.11473412e+02, 1.13159902e-01]), + 'Velocity': array([-0.22694936, -0.58153921, 0.00117721]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21122.26171875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-16596.8125 , 26072.828125 , 131.11962891]), + 'frame': 19010, + 'frame_number': 19010, + 'framesequence': 76730, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3019501566886902, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.2299362495542, + 'timestamp_carla': 651229, + 'timestamp_device': 1521828, + 'timestamp_stream': 651.2299362495542, + 'transform': [array([-34.04065704, 79.03699493, -0.13320582]), + array([ 3.63407016e-01, -1.43709991e+02, 3.11667249e-02])]} +{'AngularVelocity': array([-0.05526777, 0.01965185, -0.08865161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.01141784992069006, + 'FR_Wheel_Angle': -0.016492174938321114, + 'Location': array([-5.39576836e+01, 9.19482880e+01, 3.98169234e-02]), + 'Rotation': array([ 8.94891322e-02, -1.11496681e+02, 1.13094613e-01]), + 'Velocity': array([-0.22869907, -0.58482873, 0.00115415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8528.865234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9094.54003906, 15959.83203125, 123.7000351 ]), + 'frame': 19011, + 'frame_number': 19011, + 'framesequence': 76734, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30224311351776123, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.26371435076, + 'timestamp_carla': 651263, + 'timestamp_device': 1521862, + 'timestamp_stream': 651.26371435076, + 'transform': [array([-34.07037354, 79.03984833, -0.13283303]), + array([ 3.63092840e-01, -1.43818497e+02, 2.94522978e-02])]} +{'AngularVelocity': array([-0.05640522, 0.02142363, -0.10266249]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016494009643793106, + 'FR_Wheel_Angle': -0.016491645947098732, + 'Location': array([-5.39867477e+01, 9.18736954e+01, 3.99162173e-02]), + 'Rotation': array([ 8.94276649e-02, -1.11519699e+02, 1.13050111e-01]), + 'Velocity': array([-0.2298601 , -0.58626312, 0.00063826]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8522.0107421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9078.22851562, 15965.3828125 , 123.47159576]), + 'frame': 19012, + 'frame_number': 19012, + 'framesequence': 76738, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30077823996543884, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.2958241514862, + 'timestamp_carla': 651295, + 'timestamp_device': 1521895, + 'timestamp_stream': 651.2958241514862, + 'transform': [array([-34.09844208, 79.04272461, -0.13260058]), + array([ 3.62150282e-01, -1.43920853e+02, 2.82979887e-02])]} +{'AngularVelocity': array([-0.0581602 , 0.02220783, -0.12559089]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016491061076521873, + 'FR_Wheel_Angle': -0.016489561647176743, + 'Location': array([-5.40157509e+01, 9.17994156e+01, 4.00272273e-02]), + 'Rotation': array([ 8.94413218e-02, -1.11542435e+02, 1.12993017e-01]), + 'Velocity': array([-2.31117934e-01, -5.88662386e-01, 4.37736511e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21090.962890625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-16485.90429688, 26121.47070312, 129.67582703]), + 'frame': 19013, + 'frame_number': 19013, + 'framesequence': 76742, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2990936040878296, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.3287576511502, + 'timestamp_carla': 651328, + 'timestamp_device': 1521928, + 'timestamp_stream': 651.3287576511502, + 'transform': [array([-34.12737656, 79.04572296, -0.1324366 ]), + array([ 3.60989124e-01, -1.44026367e+02, 2.73485333e-02])]} +{'AngularVelocity': array([-0.04874394, 0.01599015, -0.04693706]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.01649273745715618, + 'FR_Wheel_Angle': -0.01649169810116291, + 'Location': array([-5.40446625e+01, 9.17258987e+01, 4.01557833e-02]), + 'Rotation': array([ 8.94344896e-02, -1.11552917e+02, 1.13011159e-01]), + 'Velocity': array([-0.2297096 , -0.58364433, 0.00104614]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8488.6455078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9034.65722656, 15959.82226562, 123.02648163]), + 'frame': 19014, + 'frame_number': 19014, + 'framesequence': 76746, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29883724451065063, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.3625869490206, + 'timestamp_carla': 651362, + 'timestamp_device': 1521962, + 'timestamp_stream': 651.3625869490206, + 'transform': [array([-34.15709686, 79.0488739 , -0.13229242]), + array([ 3.59705061e-01, -1.44134720e+02, 2.64264699e-02])]} +{'AngularVelocity': array([-0.05729695, 0.02234792, 0.09337614]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016493845731019974, + 'FR_Wheel_Angle': -0.01648850366473198, + 'Location': array([-5.40743484e+01, 9.16507111e+01, 4.02501971e-02]), + 'Rotation': array([ 8.92705694e-02, -1.11536179e+02, 1.12919696e-01]), + 'Velocity': array([-0.23155698, -0.58871055, 0.00060172]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8475.91015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-9015.23046875, 15960.15917969, 122.87802887]), + 'frame': 19015, + 'frame_number': 19015, + 'framesequence': 76750, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.3952678516507, + 'timestamp_carla': 651395, + 'timestamp_device': 1521995, + 'timestamp_stream': 651.3952678516507, + 'transform': [array([-34.18569565, 79.05202484, -0.13215889]), + array([ 3.58393669e-01, -1.44238892e+02, 2.55931523e-02])]} +{'AngularVelocity': array([-0.05517857, 0.0215752 , 0.09101138]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.016493136063218117, + 'FR_Wheel_Angle': -0.01648973859846592, + 'Location': array([-5.41032600e+01, 9.15774765e+01, 4.03806567e-02]), + 'Rotation': array([ 8.94071683e-02, -1.11515663e+02, 1.12901032e-01]), + 'Velocity': array([-0.23272991, -0.59234035, 0.00087762]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 21042.65625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-16365.5546875 , 26155.12695312, 128.53504944]), + 'frame': 19016, + 'frame_number': 19016, + 'framesequence': 76754, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30044862627983093, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.428649649024, + 'timestamp_carla': 651428, + 'timestamp_device': 1522028, + 'timestamp_stream': 651.428649649024, + 'transform': [array([-34.21512985, 79.05518341, -0.13203546]), + array([ 3.57020795e-01, -1.44346405e+02, 2.47598477e-02])]} +{'AngularVelocity': array([-0.05225285, 0.02902012, 0.00761469]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.6758993864059448, + 'FR_Wheel_Angle': -3.226078748703003, + 'Location': array([-5.41329803e+01, 9.15022736e+01, 4.04898338e-02]), + 'Rotation': array([ 8.93593580e-02, -1.11494934e+02, 1.13139249e-01]), + 'Velocity': array([-0.23508303, -0.59290761, 0.00102926]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8449.1689453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8975.52441406, 15959.8125 , 122.60225677]), + 'frame': 19017, + 'frame_number': 19017, + 'framesequence': 76758, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3002105951309204, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.4614253491163, + 'timestamp_carla': 651461, + 'timestamp_device': 1522062, + 'timestamp_stream': 651.4614253491163, + 'transform': [array([-34.24387741, 79.05845642, -0.13191546]), + array([ 3.55688900e-01, -1.44451202e+02, 2.39675138e-02])]} +{'AngularVelocity': array([-0.04502067, 0.05210802, -1.11493337]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.665580749511719, + 'FR_Wheel_Angle': -4.673186779022217, + 'Location': array([-5.41643867e+01, 9.14282532e+01, 4.06073257e-02]), + 'Rotation': array([ 8.94959643e-02, -1.11564301e+02, 1.17394820e-01]), + 'Velocity': array([-0.26625204, -0.58216149, 0.00078778]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8435.9619140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8955.65039062, 15959.81054688, 122.47135162]), + 'frame': 19018, + 'frame_number': 19018, + 'framesequence': 76762, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2997894287109375, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.4962957501411, + 'timestamp_carla': 651496, + 'timestamp_device': 1522095, + 'timestamp_stream': 651.4962957501411, + 'transform': [array([-34.27447128, 79.0621109 , -0.13181958]), + array([ 3.54186267e-01, -1.44562607e+02, 2.31752209e-02])]} +{'AngularVelocity': array([-0.06458847, 0.00372504, -0.64137834]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.333251953125, + 'FR_Wheel_Angle': -3.5088419914245605, + 'Location': array([-5.41976128e+01, 9.13528900e+01, 4.07167338e-02]), + 'Rotation': array([ 8.95369425e-02, -1.11667839e+02, 1.14182517e-01]), + 'Velocity': array([-0.25604668, -0.58540738, 0.00097347]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 17051.568359375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-13952.8515625 , 22980.08984375, 125.95684052]), + 'frame': 19019, + 'frame_number': 19019, + 'framesequence': 76766, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.5290942490101, + 'timestamp_carla': 651528, + 'timestamp_device': 1522128, + 'timestamp_stream': 651.5290942490101, + 'transform': [array([-34.30363083, 79.06546783, -0.13171755]), + array([ 3.53148073e-01, -1.44668701e+02, 2.25126836e-02])]} +{'AngularVelocity': array([-0.0495729 , 0.03884594, -0.82624418]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.520242214202881, + 'FR_Wheel_Angle': -4.200474262237549, + 'Location': array([-5.42291870e+01, 9.12799225e+01, 4.08437252e-02]), + 'Rotation': array([ 8.94481540e-02, -1.11752502e+02, 1.13681115e-01]), + 'Velocity': array([-0.25938258, -0.57936043, 0.00093719]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8409.5458984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8915.84375 , 15959.8046875 , 122.22184753]), + 'frame': 19020, + 'frame_number': 19020, + 'framesequence': 76770, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.5620840489864, + 'timestamp_carla': 651561, + 'timestamp_device': 1522162, + 'timestamp_stream': 651.5620840489864, + 'transform': [array([-34.33469009, 79.06784058, -0.13155484]), + array([ 3.51898164e-01, -1.44783997e+02, 2.15495862e-02])]} +{'AngularVelocity': array([-0.05645413, 0.02466582, -0.75812906]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.036663055419922, + 'FR_Wheel_Angle': -3.98685884475708, + 'Location': array([-5.42613373e+01, 9.12069092e+01, 4.09730040e-02]), + 'Rotation': array([ 8.99467543e-02, -1.11842262e+02, 1.13130793e-01]), + 'Velocity': array([-0.26095533, -0.58523262, 0.00128398]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8396.689453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8896.40625 , 15959.80078125, 122.11789703]), + 'frame': 19021, + 'frame_number': 19021, + 'framesequence': 76774, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.5948776490986, + 'timestamp_carla': 651594, + 'timestamp_device': 1522195, + 'timestamp_stream': 651.5948776490986, + 'transform': [array([-34.36558914, 79.07022095, -0.13139522]), + array([ 3.50518465e-01, -1.44898880e+02, 2.05865204e-02])]} +{'AngularVelocity': array([-0.05345779, 0.03116421, -0.7950986 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.128550052642822, + 'FR_Wheel_Angle': -3.9718456268310547, + 'Location': array([-5.42943306e+01, 9.11320267e+01, 4.10798527e-02]), + 'Rotation': array([ 9.01653245e-02, -1.11930840e+02, 1.12895846e-01]), + 'Velocity': array([-0.26350898, -0.58624572, 0.00082151]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8406.970703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8889.23046875, 15979.41894531, 121.97879791]), + 'frame': 19022, + 'frame_number': 19022, + 'framesequence': 76778, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.6289066523314, + 'timestamp_carla': 651628, + 'timestamp_device': 1522228, + 'timestamp_stream': 651.6289066523314, + 'transform': [array([-34.39786148, 79.07294464, -0.13134012]), + array([ 3.48599166e-01, -1.45018707e+02, 1.99512914e-02])]} +{'AngularVelocity': array([-0.05213781, 0.03046137, -0.79551178]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.164745807647705, + 'FR_Wheel_Angle': -4.002823352813721, + 'Location': array([-5.43269234e+01, 9.10583649e+01, 4.12097834e-02]), + 'Rotation': array([ 9.03565660e-02, -1.12019112e+02, 1.12651810e-01]), + 'Velocity': array([-0.26517475, -0.588 , 0.00116274]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8369.341796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8854.48925781, 15959.79394531, 121.822258 ]), + 'frame': 19023, + 'frame_number': 19023, + 'framesequence': 76782, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.6624263487756, + 'timestamp_carla': 651662, + 'timestamp_device': 1522261, + 'timestamp_stream': 651.6624263487756, + 'transform': [array([-34.42961884, 79.07588196, -0.13127232]), + array([ 3.47103357e-01, -1.45136230e+02, 1.93433836e-02])]} +{'AngularVelocity': array([-0.05064991, 0.02997303, -0.79478449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.16452169418335, + 'FR_Wheel_Angle': -4.003170013427734, + 'Location': array([-5.43599243e+01, 9.09841080e+01, 4.13314700e-02]), + 'Rotation': array([ 9.04180408e-02, -1.12109657e+02, 1.12470828e-01]), + 'Velocity': array([-0.26567253, -0.58661991, 0.00125343]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8355.197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8832.75976562, 15959.79003906, 121.72190094]), + 'frame': 19024, + 'frame_number': 19024, + 'framesequence': 76786, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.695478849113, + 'timestamp_carla': 651695, + 'timestamp_device': 1522295, + 'timestamp_stream': 651.695478849113, + 'transform': [array([-34.46020126, 79.07918549, -0.13116869]), + array([ 3.45614374e-01, -1.45248810e+02, 1.85988750e-02])]} +{'AngularVelocity': array([-0.05325286, 0.03140177, -0.79608339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.164000034332275, + 'FR_Wheel_Angle': -4.003259658813477, + 'Location': array([-5.43933525e+01, 9.09092102e+01, 4.14485820e-02]), + 'Rotation': array([ 9.06161144e-02, -1.12199409e+02, 1.12324111e-01]), + 'Velocity': array([-0.26773033, -0.58866292, 0.00092893]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8349.095703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8815.92480469, 15966.11914062, 121.62898254]), + 'frame': 19025, + 'frame_number': 19025, + 'framesequence': 76790, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.7294352501631, + 'timestamp_carla': 651729, + 'timestamp_device': 1522328, + 'timestamp_stream': 651.7294352501631, + 'transform': [array([-34.49224472, 79.08210754, -0.13098839]), + array([ 3.44480574e-01, -1.45367554e+02, 1.75333712e-02])]} +{'AngularVelocity': array([-0.05206164, 0.03115828, -0.79961818]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.16414213180542, + 'FR_Wheel_Angle': -4.002825736999512, + 'Location': array([-5.44267769e+01, 9.08346252e+01, 4.15750779e-02]), + 'Rotation': array([ 9.08005312e-02, -1.12288765e+02, 1.12183772e-01]), + 'Velocity': array([-0.26919809, -0.58947241, 0.00119849]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8328.1533203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8791.203125 , 15959.78515625, 121.51187897]), + 'frame': 19026, + 'frame_number': 19026, + 'framesequence': 76794, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.7633430510759, + 'timestamp_carla': 651763, + 'timestamp_device': 1522361, + 'timestamp_stream': 651.7633430510759, + 'transform': [array([-34.52398682, 79.08531952, -0.13085888]), + array([ 3.42984766e-01, -1.45484940e+02, 1.66522246e-02])]} +{'AngularVelocity': array([-0.05187992, 0.03130145, -0.80225074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.1642866134643555, + 'FR_Wheel_Angle': -4.002752304077148, + 'Location': array([-5.44603462e+01, 9.07600479e+01, 4.16979119e-02]), + 'Rotation': array([ 9.09917727e-02, -1.12378693e+02, 1.12052433e-01]), + 'Velocity': array([-0.27087829, -0.5906918 , 0.00106951]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8308.6318359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8766.62011719, 15955.07617188, 121.34815216]), + 'frame': 19027, + 'frame_number': 19027, + 'framesequence': 76798, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.7962631508708, + 'timestamp_carla': 651796, + 'timestamp_device': 1522395, + 'timestamp_stream': 651.7962631508708, + 'transform': [array([-34.55547333, 79.08830261, -0.13075851]), + array([ 3.41707528e-01, -1.45601624e+02, 1.59555729e-02])]} +{'AngularVelocity': array([-0.05233803, 0.03167024, -0.80230963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.189338207244873, + 'FR_Wheel_Angle': -4.542452335357666, + 'Location': array([-5.44943352e+01, 9.06848602e+01, 4.18191440e-02]), + 'Rotation': array([ 9.11147222e-02, -1.12469299e+02, 1.11912340e-01]), + 'Velocity': array([-0.27205732, -0.590783 , 0.00102983]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8300.875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8748.90625 , 15959.88183594, 121.2157135 ]), + 'frame': 19028, + 'frame_number': 19028, + 'framesequence': 76802, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.8312985524535, + 'timestamp_carla': 651831, + 'timestamp_device': 1522428, + 'timestamp_stream': 651.8312985524535, + 'transform': [array([-34.58778381, 79.09225464, -0.13064343]), + array([ 3.40116084e-01, -1.45720139e+02, 1.50744515e-02])]} +{'AngularVelocity': array([-0.03568726, 0.06769218, -1.499807 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.206850051879883, + 'FR_Wheel_Angle': -9.164209365844727, + 'Location': array([-5.45288353e+01, 9.06105042e+01, 4.19488810e-02]), + 'Rotation': array([ 9.12786424e-02, -1.12590797e+02, 1.14100307e-01]), + 'Velocity': array([-0.29046556, -0.58206987, 0.00140483]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 14167.8759765625, + 'focus_actor_name': 'BP_RepSpline18', + 'focus_actor_pt': array([-12050.1640625 , 20811.9921875 , 122.74682617]), + 'frame': 19029, + 'frame_number': 19029, + 'framesequence': 76806, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.8622919507325, + 'timestamp_carla': 651862, + 'timestamp_device': 1522461, + 'timestamp_stream': 651.8622919507325, + 'transform': [array([-34.61690521, 79.0954895 , -0.13046965]), + array([ 3.38777363e-01, -1.45827927e+02, 1.41386725e-02])]} +{'AngularVelocity': array([-0.06098413, 0.01725951, -1.81399572]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.078001022338867, + 'FR_Wheel_Angle': -6.925233364105225, + 'Location': array([-5.45660400e+01, 9.05368729e+01, 4.20752987e-02]), + 'Rotation': array([ 9.16133225e-02, -1.12817886e+02, 1.15065046e-01]), + 'Velocity': array([-0.30340165, -0.57667702, 0.0011148 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8268.7587890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8704.109375 , 15955.70996094, 120.97338867]), + 'frame': 19030, + 'frame_number': 19030, + 'framesequence': 76810, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.8960523493588, + 'timestamp_carla': 651895, + 'timestamp_device': 1522495, + 'timestamp_stream': 651.8960523493588, + 'transform': [array([-34.64818192, 79.09953308, -0.13037786]), + array([ 3.37274730e-01, -1.45942688e+02, 1.34009896e-02])]} +{'AngularVelocity': array([-0.04928812, 0.03911951, -1.56611252]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.317830085754395, + 'FR_Wheel_Angle': -8.027303695678711, + 'Location': array([-5.46026001e+01, 9.04633789e+01, 4.22035865e-02]), + 'Rotation': array([ 9.20367911e-02, -1.13003822e+02, 1.11837894e-01]), + 'Velocity': array([-0.29862818, -0.58059597, 0.00114872]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8254.1630859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8683.68164062, 15953.81054688, 120.83496857]), + 'frame': 19031, + 'frame_number': 19031, + 'framesequence': 76814, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.9281778521836, + 'timestamp_carla': 651928, + 'timestamp_device': 1522528, + 'timestamp_stream': 651.9281778521836, + 'transform': [array([-34.67752457, 79.10347748, -0.13020299]), + array([ 3.36058944e-01, -1.46050385e+02, 1.24106063e-02])]} +{'AngularVelocity': array([-0.05250441, 0.03736421, -1.71817839]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.251044273376465, + 'FR_Wheel_Angle': -7.522654056549072, + 'Location': array([-5.46402855e+01, 9.03890381e+01, 4.23226058e-02]), + 'Rotation': array([ 9.22963396e-02, -1.13210793e+02, 1.12044312e-01]), + 'Velocity': array([-0.3047294 , -0.57689011, 0.00081043]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8262.1943359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8675.19042969, 15971.31054688, 120.72773743]), + 'frame': 19032, + 'frame_number': 19032, + 'framesequence': 76818, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.9627461507916, + 'timestamp_carla': 651962, + 'timestamp_device': 1522561, + 'timestamp_stream': 651.9627461507916, + 'transform': [array([-34.70857239, 79.10795593, -0.13003577]), + array([ 3.34713399e-01, -1.46164062e+02, 1.13382414e-02])]} +{'AngularVelocity': array([-0.05033363, 0.04267697, -1.67596459]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.397970199584961, + 'FR_Wheel_Angle': -7.749814987182617, + 'Location': array([-5.46776276e+01, 9.03157806e+01, 4.24580276e-02]), + 'Rotation': array([ 9.27061513e-02, -1.13408653e+02, 1.11091822e-01]), + 'Velocity': array([-0.30595392, -0.57803053, 0.00069796]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8224.12109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8641.703125 , 15949.90234375, 120.57531738]), + 'frame': 19033, + 'frame_number': 19033, + 'framesequence': 76822, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 651.9967078492045, + 'timestamp_carla': 651996, + 'timestamp_device': 1522595, + 'timestamp_stream': 651.9967078492045, + 'transform': [array([-34.73941422, 79.11186981, -0.12980233]), + array([ 3.33682030e-01, -1.46277985e+02, 1.00678094e-02])]} +{'AngularVelocity': array([-0.05033413, 0.03915421, -1.6624217 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.307445526123047, + 'FR_Wheel_Angle': -7.706753730773926, + 'Location': array([-5.47156868e+01, 9.02418518e+01, 4.25872691e-02]), + 'Rotation': array([ 9.29998532e-02, -1.13610931e+02, 1.10726088e-01]), + 'Velocity': array([-0.30760363, -0.57615471, 0.00116125]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8208.8505859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8620.34960938, 15947.9140625 , 120.41475677]), + 'frame': 19034, + 'frame_number': 19034, + 'framesequence': 76827, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.0335763506591, + 'timestamp_carla': 652033, + 'timestamp_device': 1522636, + 'timestamp_stream': 652.0335763506591, + 'transform': [array([-34.77301025, 79.11637878, -0.12972544]), + array([ 3.32090616e-01, -1.46401764e+02, 9.28915944e-03])]} +{'AngularVelocity': array([-0.0488175 , 0.03996084, -1.68501008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.325721740722656, + 'FR_Wheel_Angle': -7.7076802253723145, + 'Location': array([-5.47530937e+01, 9.01697540e+01, 4.27363478e-02]), + 'Rotation': array([ 9.35052857e-02, -1.13808861e+02, 1.10418268e-01]), + 'Velocity': array([-0.3109991 , -0.57715738, 0.00126444]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8208.9716796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8607.515625 , 15958.63085938, 120.23010254]), + 'frame': 19035, + 'frame_number': 19035, + 'framesequence': 76830, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.0643598511815, + 'timestamp_carla': 652064, + 'timestamp_device': 1522661, + 'timestamp_stream': 652.0643598511815, + 'transform': [array([-34.8017807 , 79.11994171, -0.1296069 ]), + array([ 3.30840677e-01, -1.46508194e+02, 8.64027999e-03])]} +{'AngularVelocity': array([-0.05011673, 0.04178647, -1.68573034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.324941635131836, + 'FR_Wheel_Angle': -7.7074761390686035, + 'Location': array([-5.47918968e+01, 9.00956192e+01, 4.28597927e-02]), + 'Rotation': array([ 9.38331336e-02, -1.14012543e+02, 1.10077746e-01]), + 'Velocity': array([-0.31320128, -0.57624328, 0.00091791]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8177.3134765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8575.96582031, 15943.78125 , 120.10844421]), + 'frame': 19036, + 'frame_number': 19036, + 'framesequence': 76835, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.1041374504566, + 'timestamp_carla': 652103, + 'timestamp_device': 1522703, + 'timestamp_stream': 652.1041374504566, + 'transform': [array([-34.83972168, 79.12477112, -0.1295854 ]), + array([ 3.28887254e-01, -1.46648560e+02, 7.90259801e-03])]} +{'AngularVelocity': array([-0.04814351, 0.04046149, -1.69724154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.32470989227295, + 'FR_Wheel_Angle': -7.707335948944092, + 'Location': array([-5.48300514e+01, 9.00233688e+01, 4.30064276e-02]), + 'Rotation': array([ 9.43317339e-02, -1.14211212e+02, 1.09782748e-01]), + 'Velocity': array([-0.31633162, -0.5773322 , 0.00122461]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8163.34130859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8556.20507812, 15941.94335938, 120.0147934 ]), + 'frame': 19037, + 'frame_number': 19037, + 'framesequence': 76838, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.1333583518863, + 'timestamp_carla': 652133, + 'timestamp_device': 1522728, + 'timestamp_stream': 652.1333583518863, + 'transform': [array([-34.86830139, 79.12812805, -0.12956572]), + array([ 3.27487051e-01, -1.46754807e+02, 7.45860767e-03])]} +{'AngularVelocity': array([-0.04857887, 0.04079136, -1.68915939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.324871063232422, + 'FR_Wheel_Angle': -7.708439350128174, + 'Location': array([-5.48693581e+01, 8.99495850e+01, 4.31290716e-02]), + 'Rotation': array([ 9.45981145e-02, -1.14414391e+02, 1.09454021e-01]), + 'Velocity': array([-0.31814629, -0.57567716, 0.00121558]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8161.26220703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8539.17578125, 15953.09960938, 119.90111542]), + 'frame': 19038, + 'frame_number': 19038, + 'framesequence': 76843, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2996978759765625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.1721965521574, + 'timestamp_carla': 652171, + 'timestamp_device': 1522770, + 'timestamp_stream': 652.1721965521574, + 'transform': [array([-34.90400696, 79.13322449, -0.12932946]), + array([ 3.26264471e-01, -1.46886520e+02, 6.10622065e-03])]} +{'AngularVelocity': array([ 0.04029547, -0.04251261, -1.33611834]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.3143892288208, + 'FR_Wheel_Angle': -7.696390628814697, + 'Location': array([-5.49117470e+01, 8.98707047e+01, 4.32734974e-02]), + 'Rotation': array([ 9.44068730e-02, -1.14630264e+02, 1.08932637e-01]), + 'Velocity': array([-0.28795177, -0.51543927, 0.00105671]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20553.53125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-15320.83203125, 26326.85351562, 121.44754028]), + 'frame': 19039, + 'frame_number': 19039, + 'framesequence': 76847, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2975371778011322, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.2076788507402, + 'timestamp_carla': 652207, + 'timestamp_device': 1522803, + 'timestamp_stream': 652.2076788507402, + 'transform': [array([-34.93746948, 79.13742828, -0.12911962]), + array([ 3.24925750e-01, -1.47010986e+02, 5.02023613e-03])]} +{'AngularVelocity': array([ 0.05083087, -0.03099131, -1.61036777]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.583961486816406, + 'FR_Wheel_Angle': -11.694270133972168, + 'Location': array([-5.49517174e+01, 8.97974167e+01, 4.34086882e-02]), + 'Rotation': array([ 9.48303416e-02, -1.14843529e+02, 1.09590851e-01]), + 'Velocity': array([-0.29612446, -0.50973374, 0.00082762]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8114.19921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8486.46289062, 15935.45019531, 119.63305664]), + 'frame': 19040, + 'frame_number': 19040, + 'framesequence': 76851, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.281972736120224, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.2396420501173, + 'timestamp_carla': 652239, + 'timestamp_device': 1522836, + 'timestamp_stream': 652.2396420501173, + 'transform': [array([-34.96824265, 79.14151001, -0.12906195]), + array([ 3.23580205e-01, -1.47124786e+02, 4.64454247e-03])]} +{'AngularVelocity': array([ 0.03369541, -0.06121147, -2.25041056]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.132274627685547, + 'FR_Wheel_Angle': -11.015008926391602, + 'Location': array([-5.49939995e+01, 8.97259064e+01, 4.35501747e-02]), + 'Rotation': array([ 9.52059999e-02, -1.15160370e+02, 1.12482391e-01]), + 'Velocity': array([-0.31870663, -0.49562469, 0.00087763]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8111.7216796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8471.02539062, 15944.62695312, 119.47936249]), + 'frame': 19041, + 'frame_number': 19041, + 'framesequence': 76855, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2597430348396301, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.272856850177, + 'timestamp_carla': 652272, + 'timestamp_device': 1522870, + 'timestamp_stream': 652.272856850177, + 'transform': [array([-34.99875641, 79.14644623, -0.12891799]), + array([ 3.23423088e-01, -1.47235260e+02, 3.92054440e-03])]} +{'AngularVelocity': array([ 0.03173536, -0.06347325, -1.85685384]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.001875877380371, + 'FR_Wheel_Angle': -11.146012306213379, + 'Location': array([-5.50365143e+01, 8.96548004e+01, 4.36926931e-02]), + 'Rotation': array([ 9.59436595e-02, -1.15459244e+02, 1.08477600e-01]), + 'Velocity': array([-0.31246993, -0.50261605, 0.00087984]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8552.765625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-8697.55078125, 16325.31640625, 119.46357727]), + 'frame': 19042, + 'frame_number': 19042, + 'framesequence': 76859, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23705558478832245, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.3064535520971, + 'timestamp_carla': 652306, + 'timestamp_device': 1522903, + 'timestamp_stream': 652.3064535520971, + 'transform': [array([-35.02809143, 79.15254211, -0.12880713]), + array([ 3.23238671e-01, -1.47338211e+02, 3.28530651e-03])]} +{'AngularVelocity': array([ 0.03520636, -0.05262242, -2.0974195 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.638940811157227, + 'FR_Wheel_Angle': -11.093310356140137, + 'Location': array([-5.50792961e+01, 8.95839539e+01, 4.38380726e-02]), + 'Rotation': array([ 9.64695886e-02, -1.15761047e+02, 1.08450010e-01]), + 'Velocity': array([-0.32093078, -0.49915749, 0.0010128 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8069.6044921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8422.89355469, 15929.53125 , 119.32051086]), + 'frame': 19043, + 'frame_number': 19043, + 'framesequence': 76863, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21740776300430298, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.3393254503608, + 'timestamp_carla': 652339, + 'timestamp_device': 1522936, + 'timestamp_stream': 652.3393254503608, + 'transform': [array([-35.05504227, 79.15956879, -0.12869123]), + array([ 3.22781056e-01, -1.47429733e+02, 2.60913325e-03])]} +{'AngularVelocity': array([ 0.03566188, -0.05686196, -2.01408696]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.44905948638916, + 'FR_Wheel_Angle': -11.191463470458984, + 'Location': array([-5.51229324e+01, 8.95126114e+01, 4.39755917e-02]), + 'Rotation': array([ 9.69750211e-02, -1.16067772e+02, 1.07161649e-01]), + 'Velocity': array([-0.32040787, -0.49733478, 0.00088807]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8056.32666015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8404.25390625, 15927.796875 , 119.227211 ]), + 'frame': 19044, + 'frame_number': 19044, + 'framesequence': 76867, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2154851108789444, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.3704633489251, + 'timestamp_carla': 652370, + 'timestamp_device': 1522970, + 'timestamp_stream': 652.3704633489251, + 'transform': [array([-35.08037567, 79.16642761, -0.12855935]), + array([ 3.21865827e-01, -1.47514923e+02, 1.85779401e-03])]} +{'AngularVelocity': array([ 0.03452877, -0.05475639, -2.01080179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.423314094543457, + 'FR_Wheel_Angle': -11.139913558959961, + 'Location': array([-5.51664925e+01, 8.94422989e+01, 4.41212356e-02]), + 'Rotation': array([ 9.75282639e-02, -1.16368332e+02, 1.06720306e-01]), + 'Velocity': array([-0.32484877, -0.4969629 , 0.00096033]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20469.041015625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-15076.32226562, 26396.9140625 , 119.69480896]), + 'frame': 19045, + 'frame_number': 19045, + 'framesequence': 76871, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2240913063287735, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.4044925495982, + 'timestamp_carla': 652404, + 'timestamp_device': 1523003, + 'timestamp_stream': 652.4044925495982, + 'transform': [array([-35.10767365, 79.1740799 , -0.12841226]), + array([ 3.20192426e-01, -1.47606644e+02, 8.26412404e-04])]} +{'AngularVelocity': array([ 0.03690179, -0.05847424, -2.06086636]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.467772483825684, + 'FR_Wheel_Angle': -11.142531394958496, + 'Location': array([-5.52107124e+01, 8.93717194e+01, 4.42668051e-02]), + 'Rotation': array([ 9.79449078e-02, -1.16673561e+02, 1.06088296e-01]), + 'Velocity': array([-0.32450551, -0.49090174, 0.00086077]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8033.2861328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8372.37792969, 15924.83007812, 119.0220108 ]), + 'frame': 19046, + 'frame_number': 19046, + 'framesequence': 76875, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23621326684951782, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.4393441490829, + 'timestamp_carla': 652439, + 'timestamp_device': 1523036, + 'timestamp_stream': 652.4393441490829, + 'transform': [array([-35.13687515, 79.18138123, -0.12829106]), + array([ 3.17836016e-01, -1.47707001e+02, -1.83170603e-04])]} +{'AngularVelocity': array([ 0.03000546, -0.04810942, -2.01228952]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.468718528747559, + 'FR_Wheel_Angle': -11.142289161682129, + 'Location': array([-5.52551422e+01, 8.93016205e+01, 4.44018058e-02]), + 'Rotation': array([ 9.80883390e-02, -1.16977638e+02, 1.05460010e-01]), + 'Velocity': array([-0.32472897, -0.48526821, 0.00119129]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8021.35205078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8355.89355469, 15923.29492188, 118.87372589]), + 'frame': 19047, + 'frame_number': 19047, + 'framesequence': 76879, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2478957623243332, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.4722077511251, + 'timestamp_carla': 652471, + 'timestamp_device': 1523070, + 'timestamp_stream': 652.4722077511251, + 'transform': [array([-35.16506577, 79.18810272, -0.12817314]), + array([ 3.15588862e-01, -1.47805008e+02, -1.06819370e-03])]} +{'AngularVelocity': array([ 0.03753101, -0.05964612, -2.02950788]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.468107223510742, + 'FR_Wheel_Angle': -11.141563415527344, + 'Location': array([-5.52990952e+01, 8.92330627e+01, 4.45525236e-02]), + 'Rotation': array([ 9.92153212e-02, -1.17278191e+02, 1.05160378e-01]), + 'Velocity': array([-0.32889858, -0.48617876, 0.00079655]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8008.48486328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8337.9140625 , 15921.62109375, 118.72895813]), + 'frame': 19048, + 'frame_number': 19048, + 'framesequence': 76883, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25161290168762207, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.5053452514112, + 'timestamp_carla': 652505, + 'timestamp_device': 1523103, + 'timestamp_stream': 652.5053452514112, + 'transform': [array([-35.19396973, 79.19467926, -0.12803109]), + array([ 3.13628614e-01, -1.47906448e+02, -2.04477180e-03])]} +{'AngularVelocity': array([ 0.02905302, -0.04910338, -2.080935 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.4678373336792, + 'FR_Wheel_Angle': -11.142255783081055, + 'Location': array([-5.53439255e+01, 8.91639709e+01, 4.46969867e-02]), + 'Rotation': array([ 9.94748697e-02, -1.17579269e+02, 1.04573257e-01]), + 'Velocity': array([-0.33278459, -0.48644951, 0.00132512]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8020.884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8333.65039062, 15941.0234375 , 118.60359955]), + 'frame': 19049, + 'frame_number': 19049, + 'framesequence': 76887, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24871975183486938, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.5390415489674, + 'timestamp_carla': 652538, + 'timestamp_device': 1523136, + 'timestamp_stream': 652.5390415489674, + 'transform': [array([-35.22401428, 79.20106506, -0.12787163]), + array([ 3.12009841e-01, -1.48012817e+02, -3.08238179e-03])]} +{'AngularVelocity': array([ 0.02872629, -0.05413189, -2.15600228]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.469022750854492, + 'FR_Wheel_Angle': -11.142984390258789, + 'Location': array([-5.53885307e+01, 8.90959854e+01, 4.48534675e-02]), + 'Rotation': array([ 9.97275859e-02, -1.17879021e+02, 1.03937320e-01]), + 'Velocity': array([-0.33095625, -0.47928837, 0.00150755]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7983.244140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8302.33789062, 15918.31054688, 118.46642303]), + 'frame': 19050, + 'frame_number': 19050, + 'framesequence': 76891, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24304331839084625, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.5719477497041, + 'timestamp_carla': 652571, + 'timestamp_device': 1523170, + 'timestamp_stream': 652.5719477497041, + 'transform': [array([-35.25207901, 79.20804596, -0.12774211]), + array([ 3.10602844e-01, -1.48110535e+02, -3.93689470e-03])]} +{'AngularVelocity': array([ 0.03126327, -0.05049615, -1.96693814]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.049381256103516, + 'FR_Wheel_Angle': -12.737334251403809, + 'Location': array([-5.54339981e+01, 8.90274506e+01, 4.49842736e-02]), + 'Rotation': array([ 1.00362793e-01, -1.18182404e+02, 1.03569716e-01]), + 'Velocity': array([-0.3335948 , -0.47638592, 0.00102266]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7969.96728515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8283.45605469, 15916.55078125, 118.31983948]), + 'frame': 19051, + 'frame_number': 19051, + 'framesequence': 76895, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2373119443655014, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.6063717491925, + 'timestamp_carla': 652606, + 'timestamp_device': 1523203, + 'timestamp_stream': 652.6063717491925, + 'transform': [array([-35.28147507, 79.21540833, -0.12762606]), + array([ 3.09264123e-01, -1.48212738e+02, -4.79137385e-03])]} +{'AngularVelocity': array([ 0.03686442, -0.03749434, -2.8868134 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.29556655883789, + 'FR_Wheel_Angle': -15.37816333770752, + 'Location': array([-5.54812889e+01, 8.89595490e+01, 4.51306440e-02]), + 'Rotation': array([ 1.00909211e-01, -1.18543900e+02, 1.06468633e-01]), + 'Velocity': array([-0.35672736, -0.45987877, 0.00129826]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7959.48291015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8267.08398438, 15916.45507812, 118.1996994 ]), + 'frame': 19052, + 'frame_number': 19052, + 'framesequence': 76899, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23467512428760529, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.6386074498296, + 'timestamp_carla': 652638, + 'timestamp_device': 1523236, + 'timestamp_stream': 652.6386074498296, + 'transform': [array([-35.30921936, 79.22245026, -0.1275056 ]), + array([ 3.08321565e-01, -1.48308670e+02, -5.52381529e-03])]} +{'AngularVelocity': array([ 0.01460566, -0.09165162, -2.63859105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.822479248046875, + 'FR_Wheel_Angle': -13.764970779418945, + 'Location': array([-5.55299110e+01, 8.88937683e+01, 4.52736951e-02]), + 'Rotation': array([ 1.01694681e-01, -1.18968040e+02, 1.04535356e-01]), + 'Velocity': array([-0.35647303, -0.45592681, 0.0009352 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20353.306640625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-14784.42480469, 26460.50195312, 117.04025269]), + 'frame': 19053, + 'frame_number': 19053, + 'framesequence': 76903, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23599354922771454, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.6728979498148, + 'timestamp_carla': 652672, + 'timestamp_device': 1523270, + 'timestamp_stream': 652.6728979498148, + 'transform': [array([-35.33801651, 79.23003387, -0.12732017]), + array([ 3.07092130e-01, -1.48408005e+02, -6.65296614e-03])]} +{'AngularVelocity': array([ 0.02698409, -0.05727902, -2.72177768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.9282169342041, + 'FR_Wheel_Angle': -14.612053871154785, + 'Location': array([-5.55773659e+01, 8.88290710e+01, 4.54364680e-02]), + 'Rotation': array([ 1.02555282e-01, -1.19349083e+02, 1.02550313e-01]), + 'Velocity': array([-0.36222565, -0.45883328, 0.00115046]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7932.9716796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8231.20117188, 15911.6875 , 117.97670746]), + 'frame': 19054, + 'frame_number': 19054, + 'framesequence': 76907, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23875850439071655, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.7076981514692, + 'timestamp_carla': 652707, + 'timestamp_device': 1523303, + 'timestamp_stream': 652.7076981514692, + 'transform': [array([-35.366745 , 79.23806763, -0.12717773]), + array([ 3.05357248e-01, -1.48506714e+02, -7.66006485e-03])]} +{'AngularVelocity': array([-0.04323691, 0.05527116, -3.23342538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.438339233398438, + 'FR_Wheel_Angle': -14.263174057006836, + 'Location': array([-5.56306610e+01, 8.87583313e+01, 4.55853529e-02]), + 'Rotation': array([ 1.03415892e-01, -1.19785881e+02, 1.01860546e-01]), + 'Velocity': array([-0.40267104, -0.50317025, 0.00135718]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7920.61962890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8213.75390625, 15910.06445312, 117.818573 ]), + 'frame': 19055, + 'frame_number': 19055, + 'framesequence': 76911, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2416333556175232, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.738941449672, + 'timestamp_carla': 652738, + 'timestamp_device': 1523336, + 'timestamp_stream': 652.738941449672, + 'transform': [array([-35.39259338, 79.24521637, -0.12701301]), + array([ 3.03984374e-01, -1.48595840e+02, -8.57561640e-03])]} +{'AngularVelocity': array([ 0.02496791, -0.06168029, -2.72199869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.634279251098633, + 'FR_Wheel_Angle': -14.331998825073242, + 'Location': array([-5.56758614e+01, 8.86990128e+01, 4.57429402e-02]), + 'Rotation': array([ 1.03873514e-01, -1.20147583e+02, 1.00872561e-01]), + 'Velocity': array([-0.36908007, -0.45274279, 0.00110913]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7912.5361328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8198.64355469, 15912.0234375 , 117.67670441]), + 'frame': 19056, + 'frame_number': 19056, + 'framesequence': 76915, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2418714016675949, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.7730564512312, + 'timestamp_carla': 652772, + 'timestamp_device': 1523370, + 'timestamp_stream': 652.7730564512312, + 'transform': [array([-35.42093658, 79.25283813, -0.12685481]), + array([ 3.02488565e-01, -1.48694153e+02, -9.61320475e-03])]} +{'AngularVelocity': array([ 0.02838374, -0.07383945, -2.75144577]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.62061309814453, + 'FR_Wheel_Angle': -14.364173889160156, + 'Location': array([-5.57261772e+01, 8.86338882e+01, 4.58878204e-02]), + 'Rotation': array([ 1.04399435e-01, -1.20550140e+02, 9.99599323e-02]), + 'Velocity': array([-0.36760756, -0.44528431, 0.00089211]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7905.42041015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8185.09326172, 15913.90625 , 117.55220795]), + 'frame': 19057, + 'frame_number': 19057, + 'framesequence': 76919, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2404431253671646, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.8055692501366, + 'timestamp_carla': 652805, + 'timestamp_device': 1523403, + 'timestamp_stream': 652.8055692501366, + 'transform': [array([-35.44698715, 79.26062012, -0.12673585]), + array([ 3.01300108e-01, -1.48783279e+02, -1.03761610e-02])]} +{'AngularVelocity': array([ 0.01859766, -0.05844918, -2.79468536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.619140625, + 'FR_Wheel_Angle': -14.36471176147461, + 'Location': array([-5.57759361e+01, 8.85704117e+01, 4.60527688e-02]), + 'Rotation': array([ 1.05082452e-01, -1.20943245e+02, 9.93311554e-02]), + 'Velocity': array([-0.37567827, -0.44864604, 0.00132889]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7885.26611328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8163.7421875 , 15905.40820312, 117.40821075]), + 'frame': 19058, + 'frame_number': 19058, + 'framesequence': 76923, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23908811807632446, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.8379231505096, + 'timestamp_carla': 652837, + 'timestamp_device': 1523436, + 'timestamp_stream': 652.8379231505096, + 'transform': [array([-35.47400284, 79.26818848, -0.12666401]), + array([ 2.99804300e-01, -1.48876587e+02, -1.09865163e-02])]} +{'AngularVelocity': array([ 0.01940177, -0.05839565, -2.73290062]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.6203670501709, + 'FR_Wheel_Angle': -14.364677429199219, + 'Location': array([-5.58266411e+01, 8.85066299e+01, 4.62038331e-02]), + 'Rotation': array([ 1.05574228e-01, -1.21342430e+02, 9.85376909e-02]), + 'Velocity': array([-0.37626007, -0.44288105, 0.00129213]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7866.4775390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8144.19628906, 15897.296875 , 117.30551147]), + 'frame': 19059, + 'frame_number': 19059, + 'framesequence': 76927, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23908811807632446, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.8711932487786, + 'timestamp_carla': 652870, + 'timestamp_device': 1523470, + 'timestamp_stream': 652.8711932487786, + 'transform': [array([-35.50067902, 79.27632141, -0.12653565]), + array([ 2.98615843e-01, -1.48967743e+02, -1.18410205e-02])]} +{'AngularVelocity': array([ 0.02411748, -0.06839656, -2.69373631]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.62132453918457, + 'FR_Wheel_Angle': -14.365135192871094, + 'Location': array([-5.58774757e+01, 8.84436035e+01, 4.63555790e-02]), + 'Rotation': array([ 1.06223099e-01, -1.21737076e+02, 9.78031978e-02]), + 'Velocity': array([-0.37503776, -0.43541113, 0.00101683]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7857.03369140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8129.03027344, 15897.45117188, 117.22105408]), + 'frame': 19060, + 'frame_number': 19060, + 'framesequence': 76931, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23994874954223633, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.9053151495755, + 'timestamp_carla': 652905, + 'timestamp_device': 1523503, + 'timestamp_stream': 652.9053151495755, + 'transform': [array([-35.52985764, 79.2840271 , -0.12642863]), + array([ 2.97147363e-01, -1.49069473e+02, -1.26650147e-02])]} +{'AngularVelocity': array([ 0.01443337, -0.0485541 , -2.81451273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.620952606201172, + 'FR_Wheel_Angle': -14.364115715026855, + 'Location': array([-5.59289703e+01, 8.83806458e+01, 4.65196110e-02]), + 'Rotation': array([ 1.06776342e-01, -1.22135605e+02, 9.71078649e-02]), + 'Velocity': array([-0.38145447, -0.43653169, 0.00181272]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7847.27685546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8113.98632812, 15897.18261719, 117.1030426 ]), + 'frame': 19061, + 'frame_number': 19061, + 'framesequence': 76935, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2404431253671646, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.9389313496649, + 'timestamp_carla': 652938, + 'timestamp_device': 1523536, + 'timestamp_stream': 652.9389313496649, + 'transform': [array([-35.5569191 , 79.29219055, -0.12627438]), + array([ 2.95774490e-01, -1.49162445e+02, -1.36416033e-02])]} +{'AngularVelocity': array([ 0.01971045, -0.06020232, -2.71107841]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.621173858642578, + 'FR_Wheel_Angle': -14.388995170593262, + 'Location': array([-5.59797020e+01, 8.83194733e+01, 4.66715507e-02]), + 'Rotation': array([ 1.07650608e-01, -1.22525528e+02, 9.65060666e-02]), + 'Velocity': array([-0.38350549, -0.43290859, 0.0011971 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7858.41748046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8108.47949219, 15915.59765625, 116.98487854]), + 'frame': 19062, + 'frame_number': 19062, + 'framesequence': 76939, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24004030227661133, + 'throttle_input': 0.07539482414722443, + 'timestamp': 652.9717631489038, + 'timestamp_carla': 652971, + 'timestamp_device': 1523570, + 'timestamp_stream': 652.9717631489038, + 'transform': [array([-35.58332825, 79.30008698, -0.12610765]), + array([ 2.94586033e-01, -1.49253387e+02, -1.46181649e-02])]} +{'AngularVelocity': array([ 0.02605177, -0.03811678, -3.06596875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.3520565032959, + 'FR_Wheel_Angle': -18.22308349609375, + 'Location': array([-5.60315971e+01, 8.82582016e+01, 4.68312353e-02]), + 'Rotation': array([ 1.08101398e-01, -1.22930695e+02, 9.68738720e-02]), + 'Velocity': array([-0.39325884, -0.42419666, 0.00162549]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7824.47705078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8080.82421875, 15894.65332031, 116.85642242]), + 'frame': 19063, + 'frame_number': 19063, + 'framesequence': 76943, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.0044485516846, + 'timestamp_carla': 653004, + 'timestamp_device': 1523603, + 'timestamp_stream': 653.0044485516846, + 'transform': [array([-35.60932159, 79.30802917, -0.12594812]), + array([ 2.93424904e-01, -1.49342758e+02, -1.55642172e-02])]} +{'AngularVelocity': array([ 0.00894728, -0.09250446, -3.53984356]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.21988296508789, + 'FR_Wheel_Angle': -17.11286163330078, + 'Location': array([-5.60862732e+01, 8.81983795e+01, 4.69760783e-02]), + 'Rotation': array([ 1.08620495e-01, -1.23445251e+02, 9.86431167e-02]), + 'Velocity': array([-0.40223455, -0.39757884, 0.00092388]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7811.650390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8064.26074219, 15891.59375 , 116.72434235]), + 'frame': 19064, + 'frame_number': 19064, + 'framesequence': 76947, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.0372094511986, + 'timestamp_carla': 653037, + 'timestamp_device': 1523636, + 'timestamp_stream': 653.0372094511986, + 'transform': [array([-35.63514709, 79.31599426, -0.1257991 ]), + array([ 2.92236447e-01, -1.49431519e+02, -1.64797530e-02])]} +{'AngularVelocity': array([ 0.00736243, -0.07381517, -3.23841882]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.45171356201172, + 'FR_Wheel_Angle': -17.44447898864746, + 'Location': array([-5.61402245e+01, 8.81400681e+01, 4.71407212e-02]), + 'Rotation': array([ 1.09665513e-01, -1.23926178e+02, 9.46551040e-02]), + 'Velocity': array([-0.40267485, -0.40587807, 0.00123396]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7799.08740234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8048.03613281, 15888.59765625, 116.59624481]), + 'frame': 19065, + 'frame_number': 19065, + 'framesequence': 76951, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.0712101496756, + 'timestamp_carla': 653071, + 'timestamp_device': 1523670, + 'timestamp_stream': 653.0712101496756, + 'transform': [array([-35.66160202, 79.32428741, -0.12566136]), + array([ 2.91047990e-01, -1.49522339e+02, -1.73953138e-02])]} +{'AngularVelocity': array([ 0.01391269, -0.07344937, -3.39033318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.86857032775879, + 'FR_Wheel_Angle': -17.336641311645508, + 'Location': array([-5.61947250e+01, 8.80821686e+01, 4.72997949e-02]), + 'Rotation': array([ 1.10491961e-01, -1.24414032e+02, 9.42310765e-02]), + 'Velocity': array([-0.40925598, -0.39818117, 0.00109608]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7806.72900390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8042.17626953, 15902.91601562, 116.46714783]), + 'frame': 19066, + 'frame_number': 19066, + 'framesequence': 76955, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.1051511503756, + 'timestamp_carla': 653104, + 'timestamp_device': 1523703, + 'timestamp_stream': 653.1051511503756, + 'transform': [array([-35.68959045, 79.33188629, -0.12552844]), + array([ 2.89791256e-01, -1.49620346e+02, -1.82802975e-02])]} +{'AngularVelocity': array([ 0.01149286, -0.07106309, -3.34001875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.776187896728516, + 'FR_Wheel_Angle': -17.42718505859375, + 'Location': array([-5.62499924e+01, 8.80244598e+01, 4.74624522e-02]), + 'Rotation': array([ 1.11222796e-01, -1.24904861e+02, 9.26632807e-02]), + 'Velocity': array([-0.41125014, -0.39624044, 0.00124686]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 11161.5400390625, + 'focus_actor_name': 'BP_RepSpline17_5', + 'focus_actor_pt': array([-9733.75585938, 18802.09960938, 115.32171631]), + 'frame': 19067, + 'frame_number': 19067, + 'framesequence': 76959, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.1372186504304, + 'timestamp_carla': 653136, + 'timestamp_device': 1523736, + 'timestamp_stream': 653.1372186504304, + 'transform': [array([-35.71522141, 79.33965302, -0.12546854]), + array([ 2.88425207e-01, -1.49709030e+02, -1.87990982e-02])]} +{'AngularVelocity': array([ 0.01220634, -0.07100583, -3.3055706 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.762554168701172, + 'FR_Wheel_Angle': -17.39698028564453, + 'Location': array([-5.63056831e+01, 8.79672928e+01, 4.76198457e-02]), + 'Rotation': array([ 1.11817017e-01, -1.25396034e+02, 9.16032270e-02]), + 'Velocity': array([-0.41188288, -0.38955474, 0.00115553]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7760.51513671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7997.9609375 , 15879.35351562, 116.23069 ]), + 'frame': 19068, + 'frame_number': 19068, + 'framesequence': 76963, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.1736193522811, + 'timestamp_carla': 653173, + 'timestamp_device': 1523769, + 'timestamp_stream': 653.1736193522811, + 'transform': [array([-35.74411392, 79.34824371, -0.12532698]), + array([ 2.87134320e-01, -1.49809311e+02, -1.98367368e-02])]} +{'AngularVelocity': array([ 0.01448332, -0.07834488, -3.3242681 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.769689559936523, + 'FR_Wheel_Angle': -17.396770477294922, + 'Location': array([-5.63612862e+01, 8.79111328e+01, 4.77837250e-02]), + 'Rotation': array([ 1.12575173e-01, -1.25881935e+02, 9.06236619e-02]), + 'Velocity': array([-0.41184157, -0.38306561, 0.00089653]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7748.2861328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7982.05664062, 15876.41601562, 116.162117 ]), + 'frame': 19069, + 'frame_number': 19069, + 'framesequence': 76967, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.2048851512372, + 'timestamp_carla': 653204, + 'timestamp_device': 1523803, + 'timestamp_stream': 653.2048851512372, + 'transform': [array([-35.76812363, 79.35620117, -0.12524904]), + array([ 2.85891205e-01, -1.49891464e+02, -2.03555301e-02])]} +{'AngularVelocity': array([ 0.0125636 , -0.07889204, -3.32239294]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.769916534423828, + 'FR_Wheel_Angle': -17.397476196289062, + 'Location': array([-5.64171906e+01, 8.78556519e+01, 4.79449369e-02]), + 'Rotation': array([ 1.13340154e-01, -1.26366577e+02, 8.97441283e-02]), + 'Velocity': array([-0.41507182, -0.37969643, 0.00097677]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7757.04443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7975.44580078, 15892.55273438, 116.0140152 ]), + 'frame': 19070, + 'frame_number': 19070, + 'framesequence': 76971, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.2401656508446, + 'timestamp_carla': 653239, + 'timestamp_device': 1523836, + 'timestamp_stream': 653.2401656508446, + 'transform': [array([-35.79567337, 79.36491394, -0.12516671]), + array([ 2.84545660e-01, -1.49986404e+02, -2.10879352e-02])]} +{'AngularVelocity': array([ 0.0090055 , -0.06897193, -3.32847428]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.770103454589844, + 'FR_Wheel_Angle': -17.39710807800293, + 'Location': array([-5.64739151e+01, 8.78003387e+01, 4.81053069e-02]), + 'Rotation': array([ 1.13975361e-01, -1.26853844e+02, 8.88119340e-02]), + 'Velocity': array([-0.42004368, -0.37759879, 0.0013363 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8444.7412109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-8311.4140625 , 16494.55859375, 115.7004776 ]), + 'frame': 19071, + 'frame_number': 19071, + 'framesequence': 76975, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.2723003514111, + 'timestamp_carla': 653272, + 'timestamp_device': 1523869, + 'timestamp_stream': 653.2723003514111, + 'transform': [array([-35.82221603, 79.37283325, -0.1251775 ]), + array([ 2.82803953e-01, -1.50078857e+02, -2.13320870e-02])]} +{'AngularVelocity': array([ 0.00837561, -0.07009596, -3.30690861]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.769922256469727, + 'FR_Wheel_Angle': -17.397598266601562, + 'Location': array([-5.65309105e+01, 8.77457275e+01, 4.82705981e-02]), + 'Rotation': array([ 1.14726678e-01, -1.27336914e+02, 8.79709497e-02]), + 'Velocity': array([-0.42324015, -0.37376243, 0.00128103]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7710.27197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7932.59570312, 15867.28320312, 115.85784912]), + 'frame': 19072, + 'frame_number': 19072, + 'framesequence': 76979, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.3046439513564, + 'timestamp_carla': 653304, + 'timestamp_device': 1523903, + 'timestamp_stream': 653.3046439513564, + 'transform': [array([-35.84807205, 79.38114929, -0.12510674]), + array([ 2.81458408e-01, -1.50168060e+02, -2.19119117e-02])]} +{'AngularVelocity': array([ 0.01018834, -0.07083051, -3.28727722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.77033233642578, + 'FR_Wheel_Angle': -17.39803695678711, + 'Location': array([-5.65882492e+01, 8.76916962e+01, 4.84345146e-02]), + 'Rotation': array([ 1.15437023e-01, -1.27820206e+02, 8.70051757e-02]), + 'Velocity': array([-0.42548048, -0.36925119, 0.0011911 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7697.7783203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7916.21875 , 15864.25878906, 115.8286438 ]), + 'frame': 19073, + 'frame_number': 19073, + 'framesequence': 76983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.3363024517894, + 'timestamp_carla': 653336, + 'timestamp_device': 1523936, + 'timestamp_stream': 653.3363024517894, + 'transform': [array([-35.87359619, 79.38920593, -0.12500048]), + array([ 2.80304104e-01, -1.50256500e+02, -2.26138718e-02])]} +{'AngularVelocity': array([ 0.00739244, -0.06934199, -3.32883024]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.704824447631836, + 'FR_Wheel_Angle': -18.97169303894043, + 'Location': array([-5.66465988e+01, 8.76376572e+01, 4.85964492e-02]), + 'Rotation': array([ 1.15983434e-01, -1.28306442e+02, 8.60335529e-02]), + 'Velocity': array([-0.42702416, -0.36415049, 0.00138787]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7704.115234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7909.61328125, 15877.32617188, 115.7473526 ]), + 'frame': 19074, + 'frame_number': 19074, + 'framesequence': 76987, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.3709639497101, + 'timestamp_carla': 653370, + 'timestamp_device': 1523969, + 'timestamp_stream': 653.3709639497101, + 'transform': [array([-35.90211487, 79.39794922, -0.12491926]), + array([ 2.78808296e-01, -1.50355927e+02, -2.33767908e-02])]} +{'AngularVelocity': array([ 0.01928248, -0.07832947, -4.08280373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.686933517456055, + 'FR_Wheel_Angle': -21.134798049926758, + 'Location': array([-5.67052917e+01, 8.75861588e+01, 4.87577319e-02]), + 'Rotation': array([ 1.16406910e-01, -1.28849289e+02, 8.83242860e-02]), + 'Velocity': array([-0.43759462, -0.33386618, 0.00084622]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8394.9521484375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-8242.65136719, 16484.6171875 , 115.37844086]), + 'frame': 19075, + 'frame_number': 19075, + 'framesequence': 76991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.4048943519592, + 'timestamp_carla': 653404, + 'timestamp_device': 1524003, + 'timestamp_stream': 653.4048943519592, + 'transform': [array([-35.92906189, 79.40670013, -0.12474973]), + array([ 2.77647167e-01, -1.50449249e+02, -2.44143847e-02])]} +{'AngularVelocity': array([-0.02306486, -0.0941789 , -3.95975852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.007959365844727, + 'FR_Wheel_Angle': -19.777931213378906, + 'Location': array([-5.67647629e+01, 8.75369873e+01, 4.89366800e-02]), + 'Rotation': array([ 1.17397286e-01, -1.29438797e+02, 8.56306925e-02]), + 'Velocity': array([-0.44412673, -0.33855656, 0.00145468]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7660.51708984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7867.40917969, 15855.24902344, 115.56147003]), + 'frame': 19076, + 'frame_number': 19076, + 'framesequence': 76995, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.4399891495705, + 'timestamp_carla': 653439, + 'timestamp_device': 1524036, + 'timestamp_stream': 653.4399891495705, + 'transform': [array([-35.95663834, 79.4157486 , -0.12458088]), + array([ 2.76486039e-01, -1.50544769e+02, -2.54825111e-02])]} +{'AngularVelocity': array([ 0.00639073, -0.09346244, -3.95530605]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.33126449584961, + 'FR_Wheel_Angle': -20.495140075683594, + 'Location': array([-5.68250618e+01, 8.74870911e+01, 4.90860641e-02]), + 'Rotation': array([ 1.18312530e-01, -1.30009659e+02, 8.35018307e-02]), + 'Velocity': array([-0.44009688, -0.32671058, 0.00069911]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7648.04296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7851.05957031, 15852.22851562, 115.42385101]), + 'frame': 19077, + 'frame_number': 19077, + 'framesequence': 76999, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.4722413495183, + 'timestamp_carla': 653471, + 'timestamp_device': 1524069, + 'timestamp_stream': 653.4722413495183, + 'transform': [array([-35.98258972, 79.42373657, -0.12439149]), + array([ 2.75509328e-01, -1.50635422e+02, -2.64896210e-02])]} +{'AngularVelocity': array([-0.00406499, -0.07816114, -3.88746309]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.758338928222656, + 'FR_Wheel_Angle': -20.214420318603516, + 'Location': array([-5.68850784e+01, 8.74389648e+01, 4.92643639e-02]), + 'Rotation': array([ 1.18940905e-01, -1.30582275e+02, 8.22167918e-02]), + 'Velocity': array([-0.44723201, -0.32472533, 0.00136403]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7653.28076171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7843.20019531, 15864.78320312, 115.2762146 ]), + 'frame': 19078, + 'frame_number': 19078, + 'framesequence': 77003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.5045600496233, + 'timestamp_carla': 653504, + 'timestamp_device': 1524103, + 'timestamp_stream': 653.5045600496233, + 'transform': [array([-36.00776672, 79.43215942, -0.1242633 ]), + array([ 2.74382353e-01, -1.50722519e+02, -2.72830687e-02])]} +{'AngularVelocity': array([-0.00916776, -0.09030963, -3.96684861]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.929996490478516, + 'FR_Wheel_Angle': -20.247053146362305, + 'Location': array([-5.69451408e+01, 8.73915710e+01, 4.94158827e-02]), + 'Rotation': array([ 1.18797474e-01, -1.31146790e+02, 7.86763877e-02]), + 'Velocity': array([-0.45181727, -0.32168284, 0.00128226]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8343.76171875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-8171.84863281, 16474.05664062, 114.8208313 ]), + 'frame': 19079, + 'frame_number': 19079, + 'framesequence': 77007, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.5395464487374, + 'timestamp_carla': 653539, + 'timestamp_device': 1524136, + 'timestamp_stream': 653.5395464487374, + 'transform': [array([-36.03607941, 79.44097137, -0.12418052]), + array([ 2.72852391e-01, -1.50821594e+02, -2.80460194e-02])]} +{'AngularVelocity': array([-0.00590504, -0.10648989, -3.87370062]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.931360244750977, + 'FR_Wheel_Angle': -20.281112670898438, + 'Location': array([-5.70064964e+01, 8.73441849e+01, 4.95407768e-02]), + 'Rotation': array([ 1.18292041e-01, -1.31718552e+02, 7.48542398e-02]), + 'Velocity': array([-0.44891351, -0.31271893, 0.00074176]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7611.8681640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7803.46875 , 15843.44140625, 115.0521698 ]), + 'frame': 19080, + 'frame_number': 19080, + 'framesequence': 77011, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.5712389498949, + 'timestamp_carla': 653570, + 'timestamp_device': 1524169, + 'timestamp_stream': 653.5712389498949, + 'transform': [array([-36.06203079, 79.44908142, -0.12412273]), + array([ 2.71547824e-01, -1.50912445e+02, -2.85342950e-02])]} +{'AngularVelocity': array([-0.22875473, -0.76839364, -3.96900344]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.931495666503906, + 'FR_Wheel_Angle': -20.28252601623535, + 'Location': array([-5.70674858e+01, 8.72980042e+01, 4.95203659e-02]), + 'Rotation': array([ 1.08722948e-01, -1.32287964e+02, 4.87229377e-02]), + 'Velocity': array([-0.45490825, -0.30573151, -0.00611243]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7598.92236328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7786.32226562, 15840.27539062, 114.95264435]), + 'frame': 19081, + 'frame_number': 19081, + 'framesequence': 77015, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.6053557507694, + 'timestamp_carla': 653605, + 'timestamp_device': 1524203, + 'timestamp_stream': 653.6053557507694, + 'transform': [array([-36.0899353 , 79.45772552, -0.12400365]), + array([ 2.70291060e-01, -1.51010452e+02, -2.93887816e-02])]} +{'AngularVelocity': array([ 4.19339573e-04, -7.73813426e-02, -3.89516664e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.930429458618164, + 'FR_Wheel_Angle': -20.281097412109375, + 'Location': array([-5.71290092e+01, 8.72525253e+01, 4.93706018e-02]), + 'Rotation': array([ 9.88601521e-02, -1.32854797e+02, 3.06163076e-02]), + 'Velocity': array([-0.45788595, -0.30529326, 0.00066135]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7600.9541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7777.38085938, 15849.484375 , 114.88625336]), + 'frame': 19082, + 'frame_number': 19082, + 'framesequence': 77019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.6374687515199, + 'timestamp_carla': 653637, + 'timestamp_device': 1524236, + 'timestamp_stream': 653.6374687515199, + 'transform': [array([-36.11457825, 79.46691895, -0.12398996]), + array([ 2.68918186e-01, -1.51094757e+02, -2.97245085e-02])]} +{'AngularVelocity': array([-0.00718027, -0.07837997, -3.92100859]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.929271697998047, + 'FR_Wheel_Angle': -20.280765533447266, + 'Location': array([-5.71914787e+01, 8.72072220e+01, 4.95244861e-02]), + 'Rotation': array([ 9.99461561e-02, -1.33424057e+02, 2.96608862e-02]), + 'Velocity': array([-0.46296355, -0.3023082 , 0.00137341]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8300.3837890625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-8105.62890625, 16469.26757812, 114.41062164]), + 'frame': 19083, + 'frame_number': 19083, + 'framesequence': 77023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.6714766509831, + 'timestamp_carla': 653671, + 'timestamp_device': 1524269, + 'timestamp_stream': 653.6714766509831, + 'transform': [array([-36.14237595, 79.47576904, -0.12386666]), + array([ 2.67818540e-01, -1.51192062e+02, -3.05789784e-02])]} +{'AngularVelocity': array([-0.13763988, -0.42605338, -4.24521971]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.928955078125, + 'FR_Wheel_Angle': -20.278196334838867, + 'Location': array([-5.72545433e+01, 8.71623917e+01, 4.96543013e-02]), + 'Rotation': array([ 9.77263376e-02, -1.33999298e+02, 2.04016045e-02]), + 'Velocity': array([-0.46336204, -0.29368672, -0.00201748]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7563.36669921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7739.30371094, 15831.59375 , 114.7408905 ]), + 'frame': 19084, + 'frame_number': 19084, + 'framesequence': 77027, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23982055485248566, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.705868549645, + 'timestamp_carla': 653705, + 'timestamp_device': 1524303, + 'timestamp_stream': 653.705868549645, + 'transform': [array([-36.1718483 , 79.48410797, -0.12368758]), + array([ 2.66657412e-01, -1.51296829e+02, -3.16776335e-02])]} +{'AngularVelocity': array([-0.29149053, -0.94253147, -5.05606747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.92711067199707, + 'FR_Wheel_Angle': -20.625288009643555, + 'Location': array([-5.73202057e+01, 8.71168213e+01, 4.85857651e-02]), + 'Rotation': array([ 4.22515497e-02, -1.34614761e+02, -1.02569565e-01]), + 'Velocity': array([-0.50213408, -0.30993241, -0.01149254]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7550.86181640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7722.6640625 , 15828.52148438, 114.63108826]), + 'frame': 19085, + 'frame_number': 19085, + 'framesequence': 77031, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23599354922771454, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.7392350509763, + 'timestamp_carla': 653738, + 'timestamp_device': 1524336, + 'timestamp_stream': 653.7392350509763, + 'transform': [array([-36.19927979, 79.49262238, -0.12348045]), + array([ 2.65803635e-01, -1.51393265e+02, -3.28068025e-02])]} +{'AngularVelocity': array([ 0.01259157, -0.09173523, -5.30761957]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.831762313842773, + 'FR_Wheel_Angle': -24.11058807373047, + 'Location': array([-5.73856888e+01, 8.70727386e+01, 4.76595201e-02]), + 'Rotation': array([ 3.14871711e-03, -1.35273254e+02, -1.74377441e-01]), + 'Velocity': array([-0.50608063, -0.29715672, -0.00181297]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7550.66162109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7711.1015625 , 15836.6796875 , 114.48349762]), + 'frame': 19086, + 'frame_number': 19086, + 'framesequence': 77035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21987976133823395, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.7722698524594, + 'timestamp_carla': 653771, + 'timestamp_device': 1524369, + 'timestamp_stream': 653.7722698524594, + 'transform': [array([-36.22563934, 79.50144958, -0.12332223]), + array([ 2.65257210e-01, -1.51484528e+02, -3.36918235e-02])]} +{'AngularVelocity': array([-0.03691361, -0.01538829, -5.70936108]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.963462829589844, + 'FR_Wheel_Angle': -22.513431549072266, + 'Location': array([-5.74529076e+01, 8.70310822e+01, 4.78534214e-02]), + 'Rotation': array([ 6.70041516e-03, -1.36028214e+02, -1.67083725e-01]), + 'Velocity': array([-0.50649625, -0.27689052, 0.00310517]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8258.8330078125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-8039.63525391, 16466.1328125 , 113.9258728 ]), + 'frame': 19087, + 'frame_number': 19087, + 'framesequence': 77039, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1985473334789276, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.804576549679, + 'timestamp_carla': 653804, + 'timestamp_device': 1524403, + 'timestamp_stream': 653.804576549679, + 'transform': [array([-36.25059128, 79.51058197, -0.12321892]), + array([ 2.64949858e-01, -1.51569000e+02, -3.43021862e-02])]} +{'AngularVelocity': array([-0.03349553, -0.04754636, -5.5614562 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.07071876525879, + 'FR_Wheel_Angle': -23.25994873046875, + 'Location': array([-5.75206909e+01, 8.69893570e+01, 4.81718332e-02]), + 'Rotation': array([ 1.19733205e-02, -1.36758255e+02, -1.65252686e-01]), + 'Velocity': array([-0.50619519, -0.27689394, 0.00232242]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7513.7490234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7672.99755859, 15819.3515625 , 114.23503113]), + 'frame': 19088, + 'frame_number': 19088, + 'framesequence': 77043, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17540207505226135, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.838959351182, + 'timestamp_carla': 653838, + 'timestamp_device': 1524436, + 'timestamp_stream': 653.838959351182, + 'transform': [array([-36.27499771, 79.52172852, -0.12321512]), + array([ 2.64430761e-01, -1.51647293e+02, -3.46073397e-02])]} +{'AngularVelocity': array([-0.20428096, -0.55560088, -4.90474939]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.01931381225586, + 'FR_Wheel_Angle': -22.898469924926758, + 'Location': array([-5.75898895e+01, 8.69484940e+01, 4.80634198e-02]), + 'Rotation': array([-3.41509446e-03, -1.37500092e+02, -2.04345688e-01]), + 'Velocity': array([-0.52156246, -0.25952241, -0.00500676]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7502.9375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7658.74414062, 15816.71875 , 114.15805817]), + 'frame': 19089, + 'frame_number': 19089, + 'framesequence': 77047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15595568716526031, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.8718164488673, + 'timestamp_carla': 653871, + 'timestamp_device': 1524469, + 'timestamp_stream': 653.8718164488673, + 'transform': [array([-36.29656219, 79.53309631, -0.12311787]), + array([ 2.64007300e-01, -1.51713470e+02, -3.52176912e-02])]} +{'AngularVelocity': array([-0.0276961 , -0.14284931, -4.9190011 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.124696731567383, + 'FR_Wheel_Angle': -23.03522300720215, + 'Location': array([-5.76612091e+01, 8.69082336e+01, 4.76927832e-02]), + 'Rotation': array([-2.26420760e-02, -1.38211990e+02, -2.44171083e-01]), + 'Velocity': array([-0.52984381, -0.26022455, -0.00079445]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7494.2880859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7646.32617188, 15815.7265625 , 114.11808777]), + 'frame': 19090, + 'frame_number': 19090, + 'framesequence': 77051, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1546189785003662, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.9062771499157, + 'timestamp_carla': 653905, + 'timestamp_device': 1524503, + 'timestamp_stream': 653.9062771499157, + 'transform': [array([-36.3186264 , 79.54521942, -0.12299304]), + array([ 2.63023734e-01, -1.51780075e+02, -3.60721983e-02])]} +{'AngularVelocity': array([-0.01257136, -0.04968263, -4.98304033]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.043657302856445, + 'FR_Wheel_Angle': -23.01898193359375, + 'Location': array([-5.77329025e+01, 8.68688431e+01, 4.78443801e-02]), + 'Rotation': array([-2.18770951e-02, -1.38922836e+02, -2.45178193e-01]), + 'Velocity': array([-0.5364632 , -0.25636724, 0.00201956]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7503.49755859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7643.76318359, 15829.61132812, 114.02990723]), + 'frame': 19091, + 'frame_number': 19091, + 'framesequence': 77055, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1644703596830368, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.9388822503388, + 'timestamp_carla': 653938, + 'timestamp_device': 1524536, + 'timestamp_stream': 653.9388822503388, + 'transform': [array([-36.34046173, 79.5563736 , -0.12288099]), + array([ 2.61316180e-01, -1.51847549e+02, -3.68656442e-02])]} +{'AngularVelocity': array([-0.01689602, -0.06585556, -4.95042562]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.07011604309082, + 'FR_Wheel_Angle': -23.020038604736328, + 'Location': array([-5.78050423e+01, 8.68303680e+01, 4.80963401e-02]), + 'Rotation': array([-1.92269813e-02, -1.39632248e+02, -2.43713304e-01]), + 'Velocity': array([-0.53636509, -0.24768727, 0.00184613]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8233.037109375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-7981.78613281, 16478.30859375, 113.45476532]), + 'frame': 19092, + 'frame_number': 19092, + 'framesequence': 77059, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17778252065181732, + 'throttle_input': 0.07539482414722443, + 'timestamp': 653.9725046493113, + 'timestamp_carla': 653972, + 'timestamp_device': 1524569, + 'timestamp_stream': 653.9725046493113, + 'transform': [array([-36.36368942, 79.56759644, -0.12277216]), + array([ 2.59123713e-01, -1.51921051e+02, -3.77506688e-02])]} +{'AngularVelocity': array([ 0.00541231, -0.06927329, -4.91018391]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.071718215942383, + 'FR_Wheel_Angle': -23.02044677734375, + 'Location': array([-5.78779144e+01, 8.67926941e+01, 4.83196154e-02]), + 'Rotation': array([-1.79770570e-02, -1.40344040e+02, -2.42553696e-01]), + 'Velocity': array([-0.53551203, -0.23929189, 0.00129222]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7465.8046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7611.93457031, 15808.07617188, 113.8331604 ]), + 'frame': 19093, + 'frame_number': 19093, + 'framesequence': 77063, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19017915427684784, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.0060060508549, + 'timestamp_carla': 654005, + 'timestamp_device': 1524603, + 'timestamp_stream': 654.0060060508549, + 'transform': [array([-36.38899994, 79.57808685, -0.12270449]), + array([ 2.56685317e-01, -1.52004532e+02, -3.84830907e-02])]} +{'AngularVelocity': array([-0.01845341, -0.13016777, -4.91166925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.07187271118164, + 'FR_Wheel_Angle': -23.020462036132812, + 'Location': array([-5.79509621e+01, 8.67560806e+01, 4.83594798e-02]), + 'Rotation': array([-2.44452450e-02, -1.41053162e+02, -2.52502441e-01]), + 'Velocity': array([-5.39029360e-01, -2.32338995e-01, 2.64835344e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7456.19091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7599.66455078, 15805.80957031, 113.72163391]), + 'frame': 19094, + 'frame_number': 19094, + 'framesequence': 77067, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19294412434101105, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.0390227511525, + 'timestamp_carla': 654038, + 'timestamp_device': 1524636, + 'timestamp_stream': 654.0390227511525, + 'transform': [array([-36.41421127, 79.5884552 , -0.12263147]), + array([ 2.54581630e-01, -1.52088318e+02, -3.91850173e-02])]} +{'AngularVelocity': array([ 0.33932817, -0.02523956, -4.99580812]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.070369720458984, + 'FR_Wheel_Angle': -23.020116806030273, + 'Location': array([-5.80241890e+01, 8.67205963e+01, 4.82883714e-02]), + 'Rotation': array([-3.59472819e-02, -1.41761627e+02, -2.36968949e-01]), + 'Velocity': array([-0.54543561, -0.23088609, -0.00364909]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7445.56884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7585.77148438, 15803.24707031, 113.63179016]), + 'frame': 19095, + 'frame_number': 19095, + 'framesequence': 77071, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18884243071079254, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.0725544504821, + 'timestamp_carla': 654072, + 'timestamp_device': 1524669, + 'timestamp_stream': 654.0725544504821, + 'transform': [array([-36.43904877, 79.59927368, -0.12251412]), + array([ 2.53017515e-01, -1.52170059e+02, -4.00394723e-02])]} +{'AngularVelocity': array([-0.19135164, -0.43415773, -5.02958107]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.06680679321289, + 'FR_Wheel_Angle': -23.017953872680664, + 'Location': array([-5.80978889e+01, 8.66858292e+01, 4.79570292e-02]), + 'Rotation': array([-5.65198138e-02, -1.42468719e+02, -2.60192841e-01]), + 'Velocity': array([-0.55681717, -0.22199842, -0.00408686]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7448.587890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7578.23828125, 15812.7109375 , 113.53652954]), + 'frame': 19096, + 'frame_number': 19096, + 'framesequence': 77075, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18199409544467926, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.1057137511671, + 'timestamp_carla': 654105, + 'timestamp_device': 1524703, + 'timestamp_stream': 654.1057137511671, + 'transform': [array([-36.46315765, 79.61035919, -0.12240991]), + array([ 2.51924694e-01, -1.52248383e+02, -4.07719016e-02])]} +{'AngularVelocity': array([-0.18723163, -0.43228218, -5.18802214]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.206787109375, + 'FR_Wheel_Angle': -25.493200302124023, + 'Location': array([-5.81731720e+01, 8.66516800e+01, 4.74779792e-02]), + 'Rotation': array([-8.29458162e-02, -1.43189438e+02, -3.12957704e-01]), + 'Velocity': array([-0.56517094, -0.21301441, -0.00441355]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7438.65234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7564.875 , 15810.6171875, 113.4296875]), + 'frame': 19097, + 'frame_number': 19097, + 'framesequence': 77079, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17576831579208374, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.1388177499175, + 'timestamp_carla': 654138, + 'timestamp_device': 1524736, + 'timestamp_stream': 654.1388177499175, + 'transform': [array([-36.48723221, 79.62155151, -0.12228646]), + array([ 2.51036763e-01, -1.52326141e+02, -4.15653661e-02])]} +{'AngularVelocity': array([ 1.05161726, -0.24709448, -6.33605289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.413124084472656, + 'FR_Wheel_Angle': -25.90813636779785, + 'Location': array([-5.82517090e+01, 8.66200562e+01, 4.59196754e-02]), + 'Rotation': array([ -0.16116513, -144.04176331, -0.24374388]), + 'Velocity': array([-0.58953786, -0.1924957 , -0.02182532]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7414.58984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7545.35253906, 15795.78320312, 113.34819794]), + 'frame': 19098, + 'frame_number': 19098, + 'framesequence': 77083, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17382733523845673, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.1726316511631, + 'timestamp_carla': 654172, + 'timestamp_device': 1524769, + 'timestamp_stream': 654.1726316511631, + 'transform': [array([-36.51130676, 79.63330078, -0.12218326]), + array([ 2.49902949e-01, -1.52403122e+02, -4.23283093e-02])]} +{'AngularVelocity': array([-0.29228017, -0.4782638 , -5.82252169]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.482200622558594, + 'FR_Wheel_Angle': -25.449256896972656, + 'Location': array([-5.83314323e+01, 8.65893173e+01, 4.47869003e-02]), + 'Rotation': array([ -0.20492615, -144.90429688, -0.27807611]), + 'Velocity': array([-0.59437716, -0.18650812, -0.00508532]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7395.57470703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7528.29296875, 15785.34863281, 113.25637054]), + 'frame': 19099, + 'frame_number': 19099, + 'framesequence': 77088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17607958614826202, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.207747451961, + 'timestamp_carla': 654207, + 'timestamp_device': 1524811, + 'timestamp_stream': 654.207747451961, + 'transform': [array([-36.53853607, 79.64479828, -0.12210725]), + array([ 2.48413965e-01, -1.52492905e+02, -4.30607572e-02])]} +{'AngularVelocity': array([-0.07571995, -0.08433858, -6.05727768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.523223876953125, + 'FR_Wheel_Angle': -25.713186264038086, + 'Location': array([-5.84107323e+01, 8.65598602e+01, 4.47866730e-02]), + 'Rotation': array([ -0.2101171 , -145.74488831, -0.30053711]), + 'Velocity': array([-0.59323794, -0.17352317, 0.00240582]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7388.8642578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7517.08447266, 15785.78027344, 113.16079712]), + 'frame': 19100, + 'frame_number': 19100, + 'framesequence': 77091, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17957700788974762, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.2410704493523, + 'timestamp_carla': 654240, + 'timestamp_device': 1524836, + 'timestamp_stream': 654.2410704493523, + 'transform': [array([-36.56281281, 79.65621185, -0.12196415]), + array([ 2.46952310e-01, -1.52571503e+02, -4.39762883e-02])]} +{'AngularVelocity': array([ 0.1729749 , -0.23324187, -6.08068132]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.09687423706055, + 'FR_Wheel_Angle': -25.644393920898438, + 'Location': array([-5.84914780e+01, 8.65315628e+01, 4.46203500e-02]), + 'Rotation': array([ -0.23037544, -146.61151123, -0.26062009]), + 'Velocity': array([-0.60311806, -0.17344494, -0.00543495]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7372.2763671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7499.88330078, 15778.26757812, 113.07383728]), + 'frame': 19101, + 'frame_number': 19101, + 'framesequence': 77095, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18232367932796478, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.272149451077, + 'timestamp_carla': 654271, + 'timestamp_device': 1524869, + 'timestamp_stream': 654.272149451077, + 'transform': [array([-36.58529282, 79.66694641, -0.12181838]), + array([ 2.45572612e-01, -1.52644257e+02, -4.48307730e-02])]} +{'AngularVelocity': array([-0.28594387, -0.45912316, -6.10256481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.15304946899414, + 'FR_Wheel_Angle': -25.61585235595703, + 'Location': array([-5.85734100e+01, 8.65039444e+01, 4.41122726e-02]), + 'Rotation': array([ -0.25961548, -147.47384644, -0.30664057]), + 'Velocity': array([-0.60850507, -0.15790735, -0.00421403]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7378.3134765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7494.37304688, 15790.03613281, 112.94947815]), + 'frame': 19102, + 'frame_number': 19102, + 'framesequence': 77099, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18221381306648254, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.3058105520904, + 'timestamp_carla': 654305, + 'timestamp_device': 1524903, + 'timestamp_stream': 654.3058105520904, + 'transform': [array([-36.61034012, 79.67848206, -0.12171897]), + array([ 2.44110942e-01, -1.52726120e+02, -4.56242301e-02])]} +{'AngularVelocity': array([-0.28478587, -0.44120231, -6.09150887]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.20454025268555, + 'FR_Wheel_Angle': -25.64630699157715, + 'Location': array([-5.86557693e+01, 8.64776840e+01, 4.36850265e-02]), + 'Rotation': array([ -0.28457299, -148.33856201, -0.36639401]), + 'Velocity': array([-0.61555165, -0.14963555, -0.00395785]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7385.5556640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7490.015625 , 15802.40917969, 112.83239746]), + 'frame': 19103, + 'frame_number': 19103, + 'framesequence': 77103, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18045595288276672, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.3380647487938, + 'timestamp_carla': 654337, + 'timestamp_device': 1524936, + 'timestamp_stream': 654.3380647487938, + 'transform': [array([-36.63405228, 79.68971252, -0.12160694]), + array([ 2.42854193e-01, -1.52803238e+02, -4.63871621e-02])]} +{'AngularVelocity': array([-0.14149442, -0.41927305, -6.15363169]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.199928283691406, + 'FR_Wheel_Angle': -25.645183563232422, + 'Location': array([-5.87388954e+01, 8.64526062e+01, 4.32139486e-02]), + 'Rotation': array([ -0.31259042, -149.2071991 , -0.41610715]), + 'Velocity': array([-0.61904043, -0.14251013, -0.00553335]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7347.29931640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7463.796875 , 15775.02441406, 112.75723267]), + 'frame': 19104, + 'frame_number': 19104, + 'framesequence': 77107, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17900937795639038, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.3705076500773, + 'timestamp_carla': 654370, + 'timestamp_device': 1524969, + 'timestamp_stream': 654.3705076500773, + 'transform': [array([-36.65789413, 79.70106506, -0.12149658]), + array([ 2.41727218e-01, -1.52880661e+02, -4.71501090e-02])]} +{'AngularVelocity': array([ 0.23308738, -0.12130278, -6.28658581]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.1986198425293, + 'FR_Wheel_Angle': -25.643632888793945, + 'Location': array([-5.88230362e+01, 8.64285736e+01, 4.27163988e-02]), + 'Rotation': array([ -0.34015024, -150.0843811 , -0.44482419]), + 'Velocity': array([-0.62050724, -0.13473119, -0.00377672]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7334.8076171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7449.95019531, 15770.1484375 , 112.66700745]), + 'frame': 19105, + 'frame_number': 19105, + 'framesequence': 77111, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17889949679374695, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.405138451606, + 'timestamp_carla': 654404, + 'timestamp_device': 1525003, + 'timestamp_stream': 654.405138451606, + 'transform': [array([-36.68223572, 79.71372986, -0.12143738]), + array([ 2.40996376e-01, -1.52958237e+02, -4.77604792e-02])]} +{'AngularVelocity': array([ 0.29251021, -0.3596606 , -6.30684423]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.18916320800781, + 'FR_Wheel_Angle': -25.63738250732422, + 'Location': array([-5.89089050e+01, 8.64054184e+01, 4.19835187e-02]), + 'Rotation': array([ -0.38061911, -150.98518372, -0.39916986]), + 'Velocity': array([-0.63684088, -0.12871629, -0.01057777]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7322.310546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7436.09472656, 15765.26953125, 112.57739258]), + 'frame': 19106, + 'frame_number': 19106, + 'framesequence': 77115, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1798516809940338, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.4375700503588, + 'timestamp_carla': 654437, + 'timestamp_device': 1525036, + 'timestamp_stream': 654.4375700503588, + 'transform': [array([-36.70503235, 79.72587585, -0.1214387 ]), + array([ 2.40320191e-01, -1.53030487e+02, -4.80046161e-02])]} +{'AngularVelocity': array([ 0.26419327, -0.41464624, -6.55057573]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.181480407714844, + 'FR_Wheel_Angle': -25.632566452026367, + 'Location': array([-5.89959183e+01, 8.63834229e+01, 4.07166965e-02]), + 'Rotation': array([ -0.44149658, -151.89115906, -0.38220218]), + 'Velocity': array([-0.6538071 , -0.12238729, -0.0120385 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7324.84228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7429.12402344, 15773.890625 , 112.49182129]), + 'frame': 19107, + 'frame_number': 19107, + 'framesequence': 77119, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18052919209003448, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.4715386517346, + 'timestamp_carla': 654471, + 'timestamp_device': 1525069, + 'timestamp_stream': 654.4715386517346, + 'transform': [array([-36.72941208, 79.73808289, -0.12133287]), + array([ 2.39719138e-01, -1.53109070e+02, -4.87675630e-02])]} +{'AngularVelocity': array([ 0.13393237, -0.44415241, -6.56032133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.30280685424805, + 'FR_Wheel_Angle': -26.240177154541016, + 'Location': array([-5.90865173e+01, 8.63620071e+01, 3.93496603e-02]), + 'Rotation': array([ -0.50417721, -152.83154297, -0.36752328]), + 'Velocity': array([-0.66457444, -0.11262714, -0.01163368]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8446.7919921875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-7930.390625 , 16779.7734375 , 111.51691437]), + 'frame': 19108, + 'frame_number': 19108, + 'framesequence': 77123, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18018129467964172, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.5057271495461, + 'timestamp_carla': 654505, + 'timestamp_device': 1525103, + 'timestamp_stream': 654.5057271495461, + 'transform': [array([-36.75349045, 79.75019073, -0.12118892]), + array([ 2.39131734e-01, -1.53186752e+02, -4.96830493e-02])]} +{'AngularVelocity': array([ 0.03051957, -0.38797292, -7.35145426]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.73261260986328, + 'FR_Wheel_Angle': -29.178220748901367, + 'Location': array([-5.91764030e+01, 8.63432312e+01, 3.86120901e-02]), + 'Rotation': array([ -0.5415315 , -153.79675293, -0.40393057]), + 'Velocity': array([-0.67129499, -0.07675502, -0.00724782]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7285.31201171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7395.41015625, 15750.94335938, 112.38679504]), + 'frame': 19109, + 'frame_number': 19109, + 'framesequence': 77127, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17983338236808777, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.538370449096, + 'timestamp_carla': 654537, + 'timestamp_device': 1525136, + 'timestamp_stream': 654.538370449096, + 'transform': [array([-36.77511597, 79.76216888, -0.12111535]), + array([ 2.38551170e-01, -1.53255005e+02, -5.02324104e-02])]} +{'AngularVelocity': array([ 0.49489436, -0.10363942, -7.68616343]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.77318572998047, + 'FR_Wheel_Angle': -27.650981903076172, + 'Location': array([-5.92668839e+01, 8.63288193e+01, 3.78029533e-02]), + 'Rotation': array([ -0.58539498, -154.87237549, -0.35958856]), + 'Velocity': array([-0.68486112, -0.06428732, -0.00632818]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7272.88427734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7381.66699219, 15746.10351562, 112.27713013]), + 'frame': 19110, + 'frame_number': 19110, + 'framesequence': 77131, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.5719658508897, + 'timestamp_carla': 654571, + 'timestamp_device': 1525169, + 'timestamp_stream': 654.5719658508897, + 'transform': [array([-36.79796219, 79.77423859, -0.12106391]), + array([ 2.37847671e-01, -1.53328171e+02, -5.07512093e-02])]} +{'AngularVelocity': array([ 0.39027739, -0.22954504, -7.55143976]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.50621795654297, + 'FR_Wheel_Angle': -28.41232681274414, + 'Location': array([-5.93607101e+01, 8.63144913e+01, 3.70979197e-02]), + 'Rotation': array([ -0.62240779, -155.94169617, -0.29125971]), + 'Velocity': array([-0.69130582, -0.05684136, -0.00781609]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7261.84765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7369.60498047, 15741.85644531, 112.2131424 ]), + 'frame': 19111, + 'frame_number': 19111, + 'framesequence': 77135, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.6064033508301, + 'timestamp_carla': 654605, + 'timestamp_device': 1525203, + 'timestamp_stream': 654.6064033508301, + 'transform': [array([-36.82136536, 79.78651428, -0.12100278]), + array([ 2.37246603e-01, -1.53403336e+02, -5.13310283e-02])]} +{'AngularVelocity': array([-0.08745205, -0.47500014, -7.66879082]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.179603576660156, + 'FR_Wheel_Angle': -28.068092346191406, + 'Location': array([-5.94560966e+01, 8.63021545e+01, 3.59372236e-02]), + 'Rotation': array([ -0.68157768, -157.03987122, -0.2744751 ]), + 'Velocity': array([-0.70222932, -0.03859814, -0.00999195]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7268.93896484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7365.15527344, 15754.10742188, 112.13741302]), + 'frame': 19112, + 'frame_number': 19112, + 'framesequence': 77139, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.6375188492239, + 'timestamp_carla': 654637, + 'timestamp_device': 1525236, + 'timestamp_stream': 654.6375188492239, + 'transform': [array([-36.84228516, 79.79776001, -0.12098873]), + array([ 2.36631885e-01, -1.53470139e+02, -5.15751801e-02])]} +{'AngularVelocity': array([ 0.19202162, -0.45384246, -7.84959793]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.34410095214844, + 'FR_Wheel_Angle': -28.16320037841797, + 'Location': array([-5.95520096e+01, 8.62915039e+01, 3.48760113e-02]), + 'Rotation': array([ -0.73391747, -158.13183594, -0.28439328]), + 'Velocity': array([-0.71094882, -0.02636426, -0.01210398]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19788.97265625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-12962.63867188, 26955.30664062, 100.84230042]), + 'frame': 19113, + 'frame_number': 19113, + 'framesequence': 77143, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.6707862503827, + 'timestamp_carla': 654670, + 'timestamp_device': 1525269, + 'timestamp_stream': 654.6707862503827, + 'transform': [array([-36.865242 , 79.80970764, -0.12101269]), + array([ 2.35866904e-01, -1.53544098e+02, -5.17887734e-02])]} +{'AngularVelocity': array([ 0.20628949, -0.45442382, -7.97505999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.286949157714844, + 'FR_Wheel_Angle': -28.16077995300293, + 'Location': array([-5.96483841e+01, 8.62826614e+01, 3.35549824e-02]), + 'Rotation': array([ -0.79622924, -159.23173523, -0.26956171]), + 'Velocity': array([-0.72873878, -0.01432749, -0.01281487]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7227.5732421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7331.83789062, 15728.55761719, 112.06233215]), + 'frame': 19114, + 'frame_number': 19114, + 'framesequence': 77147, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.7059750519693, + 'timestamp_carla': 654705, + 'timestamp_device': 1525302, + 'timestamp_stream': 654.7059750519693, + 'transform': [array([-36.88986588, 79.82247925, -0.12110208]), + array([ 2.34924346e-01, -1.53623611e+02, -5.18193059e-02])]} +{'AngularVelocity': array([ 0.46249983, -0.20823725, -8.08221722]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.285709381103516, + 'FR_Wheel_Angle': -28.160280227661133, + 'Location': array([-5.97475319e+01, 8.62754593e+01, 3.22601199e-02]), + 'Rotation': array([ -0.85409462, -160.36236572, -0.23992918]), + 'Velocity': array([-0.73182613, -0.00192466, -0.00877705]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7215.91259765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7318.93261719, 15724.01367188, 112.04056549]), + 'frame': 19115, + 'frame_number': 19115, + 'framesequence': 77151, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.7375045493245, + 'timestamp_carla': 654737, + 'timestamp_device': 1525336, + 'timestamp_stream': 654.7375045493245, + 'transform': [array([-36.91188812, 79.83374023, -0.12104063]), + array([ 2.34309629e-01, -1.53695053e+02, -5.22770844e-02])]} +{'AngularVelocity': array([-0.26412994, -0.05177571, -8.01629353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.28829574584961, + 'FR_Wheel_Angle': -28.159976959228516, + 'Location': array([-5.98477287e+01, 8.62700653e+01, 3.12399566e-02]), + 'Rotation': array([ -0.85848641, -161.49295044, -0.2467041 ]), + 'Velocity': array([-0.73117566, 0.01930199, -0.00398616]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7205.31201171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7305.94189453, 15720.82617188, 112.04118347]), + 'frame': 19116, + 'frame_number': 19116, + 'framesequence': 77155, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.7713160514832, + 'timestamp_carla': 654770, + 'timestamp_device': 1525369, + 'timestamp_stream': 654.7713160514832, + 'transform': [array([-36.93485641, 79.84605408, -0.12100678]), + array([ 2.33667582e-01, -1.53768875e+02, -5.27348332e-02])]} +{'AngularVelocity': array([ 0.50664502, -0.15811379, -8.12948322]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.28196716308594, + 'FR_Wheel_Angle': -28.15833854675293, + 'Location': array([-5.99471130e+01, 8.62669220e+01, 3.07995118e-02]), + 'Rotation': array([ -0.87976247, -162.6260376 , -0.19805913]), + 'Velocity': array([-0.73688978, 0.02684157, -0.00520773]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7212.51611328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7301.68554688, 15732.91503906, 111.9737854 ]), + 'frame': 19117, + 'frame_number': 19117, + 'framesequence': 77159, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.8045065514743, + 'timestamp_carla': 654804, + 'timestamp_device': 1525402, + 'timestamp_stream': 654.8045065514743, + 'transform': [array([-36.95738602, 79.85827637, -0.12103858]), + array([ 2.32697695e-01, -1.53841293e+02, -5.29179350e-02])]} +{'AngularVelocity': array([ 0.48739204, -0.19520572, -8.11572456]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.28219985961914, + 'FR_Wheel_Angle': -28.15560531616211, + 'Location': array([-6.00488892e+01, 8.62655563e+01, 3.01674176e-02]), + 'Rotation': array([-9.18236911e-01, -1.63786774e+02, -1.24511726e-01]), + 'Velocity': array([-0.73635453, 0.04189392, -0.00668679]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 20214.779296875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-13040.9375 , 27402.04101562, 99.94364166]), + 'frame': 19118, + 'frame_number': 19118, + 'framesequence': 77163, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.8377829492092, + 'timestamp_carla': 654837, + 'timestamp_device': 1525436, + 'timestamp_stream': 654.8377829492092, + 'transform': [array([-36.98009872, 79.87059021, -0.12104431]), + array([ 2.31966868e-01, -1.53914276e+02, -5.31926081e-02])]} +{'AngularVelocity': array([-0.28927571, 0.08325313, -8.21772766]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.27044677734375, + 'FR_Wheel_Angle': -28.151704788208008, + 'Location': array([-6.01491280e+01, 8.62660904e+01, 2.82868091e-02]), + 'Rotation': array([-9.08783913e-01, -1.64913300e+02, -1.32018998e-01]), + 'Velocity': array([-0.752509 , 0.06263366, -0.01747984]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7169.42919921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7267.45214844, 15705.88476562, 111.92447662]), + 'frame': 19119, + 'frame_number': 19119, + 'framesequence': 77167, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.870942350477, + 'timestamp_carla': 654870, + 'timestamp_device': 1525469, + 'timestamp_stream': 654.870942350477, + 'transform': [array([-37.00343323, 79.88249969, -0.12099639]), + array([ 2.31290683e-01, -1.53990417e+02, -5.36808819e-02])]} +{'AngularVelocity': array([-0.15826961, 0.01636377, -8.58649063]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.26959228515625, + 'FR_Wheel_Angle': -30.64712905883789, + 'Location': array([-6.02527313e+01, 8.62690201e+01, 2.60830596e-02]), + 'Rotation': array([ -0.86825359, -166.08763123, -0.185791 ]), + 'Velocity': array([-0.74718183, 0.08562276, -0.00692938]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7158.076171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7254.89697266, 15701.46386719, 111.8955307 ]), + 'frame': 19120, + 'frame_number': 19120, + 'framesequence': 77171, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.905020751059, + 'timestamp_carla': 654904, + 'timestamp_device': 1525502, + 'timestamp_stream': 654.905020751059, + 'transform': [array([-37.02755737, 79.89463806, -0.12096778]), + array([ 2.30498388e-01, -1.54069473e+02, -5.41386642e-02])]} +{'AngularVelocity': array([-0.01449925, -0.01313185, -9.09013271]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.41267776489258, + 'FR_Wheel_Angle': -30.092763900756836, + 'Location': array([-6.03534622e+01, 8.62764816e+01, 2.55987067e-02]), + 'Rotation': array([-8.53514075e-01, -1.67352554e+02, -1.56249985e-01]), + 'Velocity': array([-7.36366093e-01, 1.18208475e-01, -2.53772723e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7148.37841796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7242.72460938, 15698.65820312, 111.83976746]), + 'frame': 19121, + 'frame_number': 19121, + 'framesequence': 77175, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.9365492500365, + 'timestamp_carla': 654936, + 'timestamp_device': 1525536, + 'timestamp_stream': 654.9365492500365, + 'transform': [array([-37.04996109, 79.90603638, -0.12095373]), + array([ 2.29856342e-01, -1.54142822e+02, -5.44133186e-02])]} +{'AngularVelocity': array([-0.06644672, -0.10982048, -9.02998638]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.438621520996094, + 'FR_Wheel_Angle': -30.651500701904297, + 'Location': array([-6.04537086e+01, 8.62862854e+01, 2.58451365e-02]), + 'Rotation': array([-8.57420921e-01, -1.68613419e+02, -1.55639619e-01]), + 'Velocity': array([-0.72614533, 0.13585782, 0.00188818]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7156.447265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7238.02246094, 15712.01074219, 111.76998138]), + 'frame': 19122, + 'frame_number': 19122, + 'framesequence': 77179, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 654.9719462506473, + 'timestamp_carla': 654971, + 'timestamp_device': 1525569, + 'timestamp_stream': 654.9719462506473, + 'transform': [array([-37.07587814, 79.91868591, -0.12098149]), + array([ 2.28941098e-01, -1.54228470e+02, -5.47184944e-02])]} +{'AngularVelocity': array([ 0.29928067, 0.86527705, -8.72571564]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44448471069336, + 'FR_Wheel_Angle': -30.647737503051758, + 'Location': array([-6.05559692e+01, 8.62992096e+01, 2.48174574e-02]), + 'Rotation': array([-8.10033083e-01, -1.69911896e+02, -1.24481164e-01]), + 'Velocity': array([-0.74477184, 0.15057744, -0.01592235]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8513.6669921875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-7822.30761719, 16939.00390625, 110.44423676]), + 'frame': 19123, + 'frame_number': 19123, + 'framesequence': 77183, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.0066029503942, + 'timestamp_carla': 655006, + 'timestamp_device': 1525602, + 'timestamp_stream': 655.0066029503942, + 'transform': [array([-37.10082245, 79.9311142 , -0.12092046]), + array([ 2.28264913e-01, -1.54310715e+02, -5.52983396e-02])]} +{'AngularVelocity': array([-1.62062004e-01, 5.32450574e-03, -9.16036892e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.43503952026367, + 'FR_Wheel_Angle': -30.64990234375, + 'Location': array([-6.06536789e+01, 8.63136520e+01, 2.28493009e-02]), + 'Rotation': array([-7.43438721e-01, -1.71157394e+02, -1.05560273e-01]), + 'Velocity': array([-0.72549927, 0.17092426, -0.00385894]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7110.26220703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7201.3359375 , 15682.60449219, 111.7312088 ]), + 'frame': 19124, + 'frame_number': 19124, + 'framesequence': 77187, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.0406228490174, + 'timestamp_carla': 655040, + 'timestamp_device': 1525636, + 'timestamp_stream': 655.0406228490174, + 'transform': [array([-37.12466812, 79.94352722, -0.12086498]), + array([ 2.27602378e-01, -1.54388672e+02, -5.58171086e-02])]} +{'AngularVelocity': array([-0.0937378 , -0.12037357, -9.00353813]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44038009643555, + 'FR_Wheel_Angle': -30.652128219604492, + 'Location': array([-6.07533493e+01, 8.63307877e+01, 2.28260327e-02]), + 'Rotation': array([-7.46826530e-01, -1.72442703e+02, -1.12396240e-01]), + 'Velocity': array([-0.71284813, 0.18499419, 0.00131534]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7097.89404296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7187.42871094, 15677.70703125, 111.66687012]), + 'frame': 19125, + 'frame_number': 19125, + 'framesequence': 77191, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.071931950748, + 'timestamp_carla': 655071, + 'timestamp_device': 1525669, + 'timestamp_stream': 655.071931950748, + 'transform': [array([-37.14577484, 79.95526886, -0.1206767 ]), + array([ 2.25491852e-01, -1.54457016e+02, -5.69157712e-02])]} +{'AngularVelocity': array([ 0.21242526, 0.16866976, -9.08277988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.43928146362305, + 'FR_Wheel_Angle': -30.652576446533203, + 'Location': array([-6.08508415e+01, 8.63498001e+01, 2.24562734e-02]), + 'Rotation': array([-7.28671849e-01, -1.73703964e+02, -7.06787035e-02]), + 'Velocity': array([-0.71103883, 0.19838439, -0.00385762]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7094.84228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7178.03564453, 15680.921875 , 111.60131836]), + 'frame': 19126, + 'frame_number': 19126, + 'framesequence': 77195, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.1052405498922, + 'timestamp_carla': 655104, + 'timestamp_device': 1525702, + 'timestamp_stream': 655.1052405498922, + 'transform': [array([-37.16778564, 79.96794128, -0.12004607]), + array([ 2.19119281e-01, -1.54528259e+02, -6.02726936e-02])]} +{'AngularVelocity': array([-0.09736207, -0.09979862, -8.92420769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44479751586914, + 'FR_Wheel_Angle': -30.6556453704834, + 'Location': array([-6.09485931e+01, 8.63710938e+01, 2.23193634e-02]), + 'Rotation': array([-7.25584626e-01, -1.74973740e+02, -6.19506724e-02]), + 'Velocity': array([-0.69847393, 0.21468376, 0.00070306]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7101.76953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7173.96875 , 15692.47460938, 111.45960999]), + 'frame': 19127, + 'frame_number': 19127, + 'framesequence': 77199, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.1388528496027, + 'timestamp_carla': 655138, + 'timestamp_device': 1525736, + 'timestamp_stream': 655.1388528496027, + 'transform': [array([-37.19020844, 79.98036194, -0.11906132]), + array([ 2.11729020e-01, -1.54601669e+02, -6.51249811e-02])]} +{'AngularVelocity': array([-0.15259802, -0.06586476, -8.84247875]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44939041137695, + 'FR_Wheel_Angle': -30.65765380859375, + 'Location': array([-6.10444756e+01, 8.63942184e+01, 2.24054232e-02]), + 'Rotation': array([-7.28029847e-01, -1.76223206e+02, -7.18994066e-02]), + 'Velocity': array([-6.87694669e-01, 2.28804961e-01, 7.88116449e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7064.955078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7150.77929688, 15664.80273438, 111.08783722]), + 'frame': 19128, + 'frame_number': 19128, + 'framesequence': 77203, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.1721196509898, + 'timestamp_carla': 655171, + 'timestamp_device': 1525769, + 'timestamp_stream': 655.1721196509898, + 'transform': [array([-37.21209335, 79.99300385, -0.11805312]), + array([ 2.03614756e-01, -1.54672760e+02, -7.00688213e-02])]} +{'AngularVelocity': array([-4.62560542e-02, -5.05144475e-03, -8.81179142e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.45262908935547, + 'FR_Wheel_Angle': -30.65987777709961, + 'Location': array([-6.11386414e+01, 8.64190903e+01, 2.23665517e-02]), + 'Rotation': array([-7.25550473e-01, -1.77461166e+02, -7.18688890e-02]), + 'Velocity': array([-0.67787808, 0.2402692 , -0.00072356]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7053.9228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7138.484375 , 15660.47265625, 110.51332092]), + 'frame': 19129, + 'frame_number': 19129, + 'framesequence': 77207, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17981506884098053, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.2049675509334, + 'timestamp_carla': 655204, + 'timestamp_device': 1525802, + 'timestamp_stream': 655.2049675509334, + 'transform': [array([-37.23356247, 80.00563049, -0.11697819]), + array([ 1.95316076e-01, -1.54742294e+02, -7.52568096e-02])]} +{'AngularVelocity': array([ 0.07153553, 0.07096263, -8.74623489]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.451744079589844, + 'FR_Wheel_Angle': -30.658235549926758, + 'Location': array([-6.12318649e+01, 8.64459381e+01, 2.22313963e-02]), + 'Rotation': array([-7.20339060e-01, -1.78690445e+02, -6.72607347e-02]), + 'Velocity': array([-0.67221946, 0.2540873 , -0.00209956]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7043.20751953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7126.6015625 , 15656.2890625 , 109.93211365]), + 'frame': 19130, + 'frame_number': 19130, + 'framesequence': 77211, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17935729026794434, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.2395627498627, + 'timestamp_carla': 655239, + 'timestamp_device': 1525836, + 'timestamp_stream': 655.2395627498627, + 'transform': [array([-37.25658035, 80.01888275, -0.11583148]), + array([ 1.86737359e-01, -1.54817322e+02, -8.08110014e-02])]} +{'AngularVelocity': array([ 0.04059467, 0.3603614 , -8.85393715]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44904327392578, + 'FR_Wheel_Angle': -30.65712547302246, + 'Location': array([-6.13257065e+01, 8.64749527e+01, 2.09368039e-02]), + 'Rotation': array([-6.71291471e-01, -1.79934753e+02, -5.07201999e-02]), + 'Velocity': array([-0.66950774, 0.26953492, -0.0090594 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7035.693359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7116.27050781, 15654.88574219, 109.31915283]), + 'frame': 19131, + 'frame_number': 19131, + 'framesequence': 77215, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16926786303520203, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.2728991508484, + 'timestamp_carla': 655272, + 'timestamp_device': 1525869, + 'timestamp_stream': 655.2728991508484, + 'transform': [array([-37.27764511, 80.03206635, -0.1146827 ]), + array([ 1.78739205e-01, -1.54884415e+02, -8.62431154e-02])]} +{'AngularVelocity': array([ 0.04554848, 0.34687185, -8.90766144]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44476318359375, + 'FR_Wheel_Angle': -30.65386962890625, + 'Location': array([-6.14193916e+01, 8.65061874e+01, 1.92653555e-02]), + 'Rotation': array([-6.13275826e-01, 1.78814941e+02, -3.40881348e-02]), + 'Velocity': array([-0.66893125, 0.28688627, -0.00948306]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7043.314453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7111.81152344, 15667.54492188, 108.64053345]), + 'frame': 19132, + 'frame_number': 19132, + 'framesequence': 77219, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14888760447502136, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.3056066520512, + 'timestamp_carla': 655305, + 'timestamp_device': 1525902, + 'timestamp_stream': 655.3056066520512, + 'transform': [array([-37.29748917, 80.04534912, -0.11355507]), + array([ 1.71506047e-01, -1.54945694e+02, -9.14921239e-02])]} +{'AngularVelocity': array([-0.15568706, 0.23010442, -8.95028591]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.442928314208984, + 'FR_Wheel_Angle': -30.65376091003418, + 'Location': array([-6.15128899e+01, 8.65396347e+01, 1.77008342e-02]), + 'Rotation': array([-5.59474409e-01, 1.77558411e+02, -2.21557599e-02]), + 'Velocity': array([-0.66623539, 0.30408415, -0.0071641 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19727.923828125, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-12488.94335938, 27158.10742188, 88.89772034]), + 'frame': 19133, + 'frame_number': 19133, + 'framesequence': 77223, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1268959641456604, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.338449049741, + 'timestamp_carla': 655338, + 'timestamp_device': 1525936, + 'timestamp_stream': 655.338449049741, + 'transform': [array([-37.31531143, 80.05942535, -0.11239699]), + array([ 1.64429963e-01, -1.54996948e+02, -9.68632102e-02])]} +{'AngularVelocity': array([-0.0151302 , 0.0668728 , -8.97861767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.444217681884766, + 'FR_Wheel_Angle': -30.65612030029297, + 'Location': array([-6.16053925e+01, 8.65751648e+01, 1.69925969e-02]), + 'Rotation': array([-5.37078261e-01, 1.76305710e+02, -4.70886156e-02]), + 'Velocity': array([-0.65904927, 0.31815335, -0.00245216]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7001.98046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7081.25585938, 15640.3203125 , 107.42552948]), + 'frame': 19134, + 'frame_number': 19134, + 'framesequence': 77227, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10397046059370041, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.3706209510565, + 'timestamp_carla': 655370, + 'timestamp_device': 1525969, + 'timestamp_stream': 655.3706209510565, + 'transform': [array([-37.3311615 , 80.07374573, -0.11125825]), + array([ 1.57654420e-01, -1.55038940e+02, -1.02112204e-01])]} +{'AngularVelocity': array([ 0.28499261, 0.15020855, -8.97188091]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44384002685547, + 'FR_Wheel_Angle': -30.653915405273438, + 'Location': array([-6.16979332e+01, 8.66129990e+01, 1.62657443e-02]), + 'Rotation': array([-5.09648204e-01, 1.75032150e+02, -2.86864955e-03]), + 'Velocity': array([-0.6509394 , 0.32910278, -0.00454375]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6993.8310546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7072.78613281, 15637.33886719, 106.79832458]), + 'frame': 19135, + 'frame_number': 19135, + 'framesequence': 77231, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09428388625383377, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.4052537493408, + 'timestamp_carla': 655404, + 'timestamp_device': 1526002, + 'timestamp_stream': 655.4052537493408, + 'transform': [array([-37.34689331, 80.0895462 , -0.11012109]), + array([ 1.50605664e-01, -1.55077484e+02, -1.07483290e-01])]} +{'AngularVelocity': array([ 0.27164003, 0.15098733, -9.00150299]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44109344482422, + 'FR_Wheel_Angle': -30.652271270751953, + 'Location': array([-6.17888527e+01, 8.66525192e+01, 1.53927896e-02]), + 'Rotation': array([-4.77505326e-01, 1.73772141e+02, 4.74130213e-02]), + 'Velocity': array([-0.64553326, 0.34431231, -0.0051043 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6986.85498046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7065.8515625 , 15634.89648438, 106.18457031]), + 'frame': 19136, + 'frame_number': 19136, + 'framesequence': 77235, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10007020086050034, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.4383127503097, + 'timestamp_carla': 655437, + 'timestamp_device': 1526036, + 'timestamp_stream': 655.4383127503097, + 'transform': [array([-37.36236572, 80.10449982, -0.1091436 ]), + array([ 1.43495440e-01, -1.55116241e+02, -1.12152457e-01])]} +{'AngularVelocity': array([-0.01245581, 0.30522656, -9.06637287]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4405403137207, + 'FR_Wheel_Angle': -30.651308059692383, + 'Location': array([-6.18804092e+01, 8.66946182e+01, 1.40313245e-02]), + 'Rotation': array([-4.27610815e-01, 1.72496292e+02, 6.70484304e-02]), + 'Velocity': array([-0.64332092, 0.36246741, -0.00751318]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6980.17041015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7059.49511719, 15632.65820312, 105.55534363]), + 'frame': 19137, + 'frame_number': 19137, + 'framesequence': 77239, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1105075255036354, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.4708905518055, + 'timestamp_carla': 655470, + 'timestamp_device': 1526069, + 'timestamp_stream': 655.4708905518055, + 'transform': [array([-37.37810898, 80.11908722, -0.1082304 ]), + array([ 1.35982230e-01, -1.55156982e+02, -1.16608001e-01])]} +{'AngularVelocity': array([ 0.03025444, 0.27847314, -9.04471302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.437477111816406, + 'FR_Wheel_Angle': -30.649484634399414, + 'Location': array([-6.19695358e+01, 8.67380066e+01, 1.29427621e-02]), + 'Rotation': array([-3.90802920e-01, 1.71237854e+02, 5.50500564e-02]), + 'Velocity': array([-0.63404721, 0.37718272, -0.00747686]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6974.6865234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7053.59667969, 15631.42773438, 105.01040649]), + 'frame': 19138, + 'frame_number': 19138, + 'framesequence': 77243, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12248299270868301, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.5048183500767, + 'timestamp_carla': 655504, + 'timestamp_device': 1526102, + 'timestamp_stream': 655.5048183500767, + 'transform': [array([-37.39586258, 80.13385773, -0.10733555]), + array([ 1.28107026e-01, -1.55206085e+02, -1.21094085e-01])]} +{'AngularVelocity': array([ 0.08565606, 0.315054 , -9.14158821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.433963775634766, + 'FR_Wheel_Angle': -30.648054122924805, + 'Location': array([-6.20594063e+01, 8.67842789e+01, 1.14857387e-02]), + 'Rotation': array([-3.38224113e-01, 1.69956238e+02, 6.88291490e-02]), + 'Velocity': array([-0.63095021, 0.3932851 , -0.008462 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6978.044921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7051.17871094, 15638.29296875, 104.47402954]), + 'frame': 19139, + 'frame_number': 19139, + 'framesequence': 77247, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13125401735305786, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.5375036522746, + 'timestamp_carla': 655537, + 'timestamp_device': 1526136, + 'timestamp_stream': 655.5375036522746, + 'transform': [array([-37.41333008, 80.14796448, -0.10647503]), + array([ 1.20546006e-01, -1.55255524e+02, -1.25366509e-01])]} +{'AngularVelocity': array([ 0.16999945, 0.23124181, -9.17569447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.433013916015625, + 'FR_Wheel_Angle': -30.647886276245117, + 'Location': array([-6.21487427e+01, 8.68327637e+01, 9.97740682e-03]), + 'Rotation': array([-2.85522372e-01, 1.68664673e+02, 8.57961997e-02]), + 'Velocity': array([-0.62243539, 0.40860519, -0.00805218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6982.40380859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7048.26757812, 15646.5625 , 103.93206787]), + 'frame': 19140, + 'frame_number': 19140, + 'framesequence': 77251, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13061311841011047, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.5709028504789, + 'timestamp_carla': 655570, + 'timestamp_device': 1526169, + 'timestamp_stream': 655.5709028504789, + 'transform': [array([-37.4318161 , 80.16220093, -0.10561875]), + array([ 1.13463096e-01, -1.55309036e+02, -1.29608408e-01])]} +{'AngularVelocity': array([-3.47064584e-02, -4.99018002e-03, -9.08760071e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.43536376953125, + 'FR_Wheel_Angle': -30.648948669433594, + 'Location': array([-6.22364426e+01, 8.68831024e+01, 9.14946571e-03]), + 'Rotation': array([-2.58666068e-01, 1.67378372e+02, 1.20218903e-01]), + 'Velocity': array([-0.61126935, 0.42153141, -0.00161502]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12659.5087890625, + 'focus_actor_name': 'BP_RepSpline18', + 'focus_actor_pt': array([-9419.7421875, 20806.65625 , 91.0007782]), + 'frame': 19141, + 'frame_number': 19141, + 'framesequence': 77255, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12585224211215973, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.6043978519738, + 'timestamp_carla': 655604, + 'timestamp_device': 1526202, + 'timestamp_stream': 655.6043978519738, + 'transform': [array([-37.44955826, 80.17676544, -0.10474653]), + array([ 1.06742188e-01, -1.55359146e+02, -1.33880839e-01])]} +{'AngularVelocity': array([-0.12415992, 0.26100233, -8.71745682]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44721221923828, + 'FR_Wheel_Angle': -30.656721115112305, + 'Location': array([-6.23232765e+01, 8.69354553e+01, 8.71191919e-03]), + 'Rotation': array([-2.41938949e-01, 1.66099014e+02, 9.89742652e-02]), + 'Velocity': array([-0.61016154, 0.43617815, -0.00531855]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6942.76611328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7021.61865234, 15619.3203125 , 103.00672913]), + 'frame': 19142, + 'frame_number': 19142, + 'framesequence': 77259, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11984618753194809, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.6388965509832, + 'timestamp_carla': 655638, + 'timestamp_device': 1526236, + 'timestamp_stream': 655.6388965509832, + 'transform': [array([-37.46770859, 80.19178772, -0.10386174]), + array([ 1.00246683e-01, -1.55410019e+02, -1.38214335e-01])]} +{'AngularVelocity': array([ 0.05031873, 0.33480066, -8.83618832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.438724517822266, + 'FR_Wheel_Angle': -30.648996353149414, + 'Location': array([-6.24082146e+01, 8.69891586e+01, 7.37986527e-03]), + 'Rotation': array([-1.92693293e-01, 1.64832764e+02, 1.07545942e-01]), + 'Velocity': array([-0.59526318, 0.44452631, -0.0090091 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6934.8525390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7013.46142578, 15616.44824219, 102.51876068]), + 'frame': 19143, + 'frame_number': 19143, + 'framesequence': 77263, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11528673022985458, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.6711500510573, + 'timestamp_carla': 655670, + 'timestamp_device': 1526269, + 'timestamp_stream': 655.6711500510573, + 'transform': [array([-37.48413849, 80.20606232, -0.10309891]), + array([ 9.49669480e-02, -1.55454803e+02, -1.41845912e-01])]} +{'AngularVelocity': array([ 0.12879549, 0.28426006, -9.14345264]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.434600830078125, + 'FR_Wheel_Angle': -30.646377563476562, + 'Location': array([-6.24916725e+01, 8.70445023e+01, 5.90949040e-03]), + 'Rotation': array([-1.40469655e-01, 1.63562454e+02, 1.23431638e-01]), + 'Velocity': array([-0.58340609, 0.46076548, -0.008446 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6926.80712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7005.19335938, 15613.53710938, 102.02313232]), + 'frame': 19144, + 'frame_number': 19144, + 'framesequence': 77267, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11528673022985458, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.7049090489745, + 'timestamp_carla': 655704, + 'timestamp_device': 1526302, + 'timestamp_stream': 655.7049090489745, + 'transform': [array([-37.50248718, 80.22071838, -0.10269862]), + array([ 9.26446840e-02, -1.55506241e+02, -1.43829525e-01])]} +{'AngularVelocity': array([ 0.12456053, 0.27920654, -9.22592545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.430973052978516, + 'FR_Wheel_Angle': -30.647884368896484, + 'Location': array([-6.25740547e+01, 8.71018372e+01, 4.46806895e-03]), + 'Rotation': array([-8.95984173e-02, 1.62285919e+02, 1.39070481e-01]), + 'Velocity': array([-0.5774712 , 0.47667933, -0.00812743]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6919.62841796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6997.93115234, 15610.97949219, 101.61230469]), + 'frame': 19145, + 'frame_number': 19145, + 'framesequence': 77271, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11753898859024048, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.7401728518307, + 'timestamp_carla': 655739, + 'timestamp_device': 1526336, + 'timestamp_stream': 655.7401728518307, + 'transform': [array([-37.52150345, 80.23612976, -0.10254746]), + array([ 9.13401172e-02, -1.55559326e+02, -1.44806087e-01])]} +{'AngularVelocity': array([ 0.03111014, -0.01414828, -9.13409996]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.43598937988281, + 'FR_Wheel_Angle': -30.650714874267578, + 'Location': array([-6.26557846e+01, 8.71617432e+01, 3.88022419e-03]), + 'Rotation': array([-7.22633973e-02, 1.60999786e+02, 1.42797604e-01]), + 'Velocity': array([-0.56232542, 0.48660406, -0.00070879]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6913.3193359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6990.34179688, 15609.61914062, 101.39073181]), + 'frame': 19146, + 'frame_number': 19146, + 'framesequence': 77275, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12030397355556488, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.7714592516422, + 'timestamp_carla': 655771, + 'timestamp_device': 1526369, + 'timestamp_stream': 655.7714592516422, + 'transform': [array([-37.53914642, 80.24958801, -0.10250289]), + array([ 9.05136615e-02, -1.55609909e+02, -1.45172298e-01])]} +{'AngularVelocity': array([-0.11169621, -0.04453968, -9.01272392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44012451171875, + 'FR_Wheel_Angle': -30.653528213500977, + 'Location': array([-6.27348747e+01, 8.72225494e+01, 3.95079609e-03]), + 'Rotation': array([-7.44900405e-02, 1.59732880e+02, 1.44666433e-01]), + 'Velocity': array([-0.5451991 , 0.49518359, 0.00091349]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6918.1240234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6987.20166016, 15618.53515625, 101.25679016]), + 'frame': 19147, + 'frame_number': 19147, + 'framesequence': 77279, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12209846079349518, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.8039708510041, + 'timestamp_carla': 655803, + 'timestamp_device': 1526402, + 'timestamp_stream': 655.8039708510041, + 'transform': [array([-37.55721283, 80.26369476, -0.10251229]), + array([ 8.97555128e-02, -1.55661438e+02, -1.45416439e-01])]} +{'AngularVelocity': array([-0.20473352, 0.09790322, -8.93934059]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44231414794922, + 'FR_Wheel_Angle': -30.653959274291992, + 'Location': array([-6.28128319e+01, 8.72852554e+01, 4.01770603e-03]), + 'Rotation': array([-7.51662254e-02, 1.58465607e+02, 1.39453605e-01]), + 'Velocity': array([-0.53177196, 0.50479114, -0.00083242]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6910.79541015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6979.23535156, 15616.05957031, 101.23041534]), + 'frame': 19148, + 'frame_number': 19148, + 'framesequence': 77283, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12127445638179779, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.8367089517415, + 'timestamp_carla': 655836, + 'timestamp_device': 1526436, + 'timestamp_stream': 655.8367089517415, + 'transform': [array([-37.57556152, 80.2778244 , -0.10254003]), + array([ 8.91749412e-02, -1.55714157e+02, -1.45599529e-01])]} +{'AngularVelocity': array([-0.23619732, 0.1878752 , -8.89403915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44552993774414, + 'FR_Wheel_Angle': -30.654577255249023, + 'Location': array([-6.28898964e+01, 8.73499527e+01, 3.54262348e-03]), + 'Rotation': array([-5.69706038e-02, 1.57191376e+02, 1.08068220e-01]), + 'Velocity': array([-0.51611894, 0.514498 , -0.00319202]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6900.7763671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6970.08496094, 15611.23828125, 101.22218323]), + 'frame': 19149, + 'frame_number': 19149, + 'framesequence': 77287, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11993774026632309, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.871380649507, + 'timestamp_carla': 655871, + 'timestamp_device': 1526469, + 'timestamp_stream': 655.871380649507, + 'transform': [array([-37.59468842, 80.29289246, -0.10258672]), + array([ 8.86831731e-02, -1.55768692e+02, -1.45782620e-01])]} +{'AngularVelocity': array([-0.06229883, 0.2671133 , -9.77624702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.4884033203125, + 'FR_Wheel_Angle': -28.12187957763672, + 'Location': array([-6.29743729e+01, 8.74243698e+01, 2.82942760e-03]), + 'Rotation': array([-3.43285277e-02, 1.55762833e+02, 7.28806183e-02]), + 'Velocity': array([-0.54519761, 0.56294954, -0.0041379 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6867.1865234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6951.12597656, 15584.99023438, 101.27947998]), + 'frame': 19150, + 'frame_number': 19150, + 'framesequence': 77291, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1190221905708313, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.9064080491662, + 'timestamp_carla': 655906, + 'timestamp_device': 1526502, + 'timestamp_stream': 655.9064080491662, + 'transform': [array([-37.614048 , 80.30812073, -0.10263763]), + array([ 8.82255509e-02, -1.55823914e+02, -1.45935208e-01])]} +{'AngularVelocity': array([-0.10961284, 0.30821753, -7.93507242]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.28139305114746, + 'FR_Wheel_Angle': -23.03570556640625, + 'Location': array([-6.30539246e+01, 8.74934540e+01, 2.29182234e-03]), + 'Rotation': array([-1.21167554e-02, 1.54574631e+02, 3.40432115e-02]), + 'Velocity': array([-0.57407397, 0.53846395, -0.00275971]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6860.560546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6943.12792969, 15583.48828125, 101.26696777]), + 'frame': 19151, + 'frame_number': 19151, + 'framesequence': 77295, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11951658874750137, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.9396698512137, + 'timestamp_carla': 655939, + 'timestamp_device': 1526536, + 'timestamp_stream': 655.9396698512137, + 'transform': [array([-37.63242722, 80.32265472, -0.10268075]), + array([ 8.77679288e-02, -1.55876297e+02, -1.46026775e-01])]} +{'AngularVelocity': array([-0.21010345, 0.17883728, -5.44391012]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.758901596069336, + 'FR_Wheel_Angle': -18.36795997619629, + 'Location': array([-6.31236839e+01, 8.75490036e+01, 1.72179216e-03]), + 'Rotation': array([ 6.32475503e-03, 1.53789413e+02, -4.27246036e-04]), + 'Velocity': array([-0.54064 , 0.45929697, -0.00310264]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6856.30615234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6936.0390625 , 15584.19726562, 101.25356293]), + 'frame': 19152, + 'frame_number': 19152, + 'framesequence': 77299, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12030397355556488, + 'throttle_input': 0.07539482414722443, + 'timestamp': 655.9713603518903, + 'timestamp_carla': 655970, + 'timestamp_device': 1526569, + 'timestamp_stream': 655.9713603518903, + 'transform': [array([-37.65026093, 80.33648682, -0.10272123]), + array([ 8.72829854e-02, -1.55927582e+02, -1.46087795e-01])]} +{'AngularVelocity': array([ 0.06294922, -0.01152485, -4.9235096 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.164249420166016, + 'FR_Wheel_Angle': -12.555481910705566, + 'Location': array([-6.31993599e+01, 8.76041260e+01, 1.67178153e-03]), + 'Rotation': array([ 1.00130569e-02, 1.53169724e+02, -4.36401367e-03]), + 'Velocity': array([-6.21288776e-01, 4.68203038e-01, 8.77571074e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6848.3232421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6927.70703125, 15581.26367188, 101.25841522]), + 'frame': 19153, + 'frame_number': 19153, + 'framesequence': 77303, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12032227963209152, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.0057343505323, + 'timestamp_carla': 656005, + 'timestamp_device': 1526602, + 'timestamp_stream': 656.0057343505323, + 'transform': [array([-37.66927338, 80.3515625 , -0.10274931]), + array([ 8.67570564e-02, -1.55981918e+02, -1.46331936e-01])]} +{'AngularVelocity': array([-0.07826996, -0.05156863, -2.11551642]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.167415618896484, + 'FR_Wheel_Angle': -5.8566365242004395, + 'Location': array([-6.32816353e+01, 8.76583710e+01, 1.58877368e-03]), + 'Rotation': array([ 1.04023777e-02, 1.52752335e+02, -1.10778809e-02]), + 'Velocity': array([-0.58485222, 0.38152602, -0.0012232 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6834.697265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6917.17578125, 15573.03515625, 101.28202057]), + 'frame': 19154, + 'frame_number': 19154, + 'framesequence': 77307, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1200842335820198, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.0368333496153, + 'timestamp_carla': 656036, + 'timestamp_device': 1526636, + 'timestamp_stream': 656.0368333496153, + 'transform': [array([-37.6867485 , 80.36521149, -0.10278513]), + array([ 8.62994343e-02, -1.56032196e+02, -1.46392956e-01])]} +{'AngularVelocity': array([-0.02135995, -0.05053 , -0.53670871]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.33869314193725586, + 'FR_Wheel_Angle': 0.7558122277259827, + 'Location': array([-6.33667526e+01, 8.77076416e+01, 1.67788507e-03]), + 'Rotation': array([ 9.70569812e-03, 1.52561905e+02, -1.16577139e-02]), + 'Velocity': array([-0.62912583, 0.34676853, 0.00063157]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6839.09228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6913.71337891, 15581.54296875, 101.23475647]), + 'frame': 19155, + 'frame_number': 19155, + 'framesequence': 77311, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.0706496499479, + 'timestamp_carla': 656070, + 'timestamp_device': 1526669, + 'timestamp_stream': 656.0706496499479, + 'transform': [array([-37.70533752, 80.38009644, -0.10279364]), + array([ 8.58486444e-02, -1.56085236e+02, -1.46698162e-01])]} +{'AngularVelocity': array([ 0.0315168 , -0.0734905 , 0.27888286]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.29864004254341125, + 'FR_Wheel_Angle': 0.04549542814493179, + 'Location': array([-6.34560890e+01, 8.77540131e+01, 1.69573782e-03]), + 'Rotation': array([ 8.85875523e-03, 1.52580414e+02, -7.65991071e-03]), + 'Velocity': array([-6.41546309e-01, 3.26811135e-01, -9.72080234e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6837.44189453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6908.16943359, 15584.15820312, 101.2273941 ]), + 'frame': 19156, + 'frame_number': 19156, + 'framesequence': 77315, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.1045352518559, + 'timestamp_carla': 656104, + 'timestamp_device': 1526702, + 'timestamp_stream': 656.1045352518559, + 'transform': [array([-37.72410583, 80.39492798, -0.10279825]), + array([ 8.53841901e-02, -1.56139206e+02, -1.47003323e-01])]} +{'AngularVelocity': array([ 0.0034811 , -0.07100905, -0.01588674]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037909378297626972, + 'FR_Wheel_Angle': 0.0037972352001816034, + 'Location': array([-6.35461617e+01, 8.78002930e+01, 1.72453874e-03]), + 'Rotation': array([ 8.40796251e-03, 1.52568451e+02, -7.62939279e-04]), + 'Velocity': array([-0.63819695, 0.33000511, 0.00088799]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6840.61767578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6904.328125 , 15591.45214844, 101.17701721]), + 'frame': 19157, + 'frame_number': 19157, + 'framesequence': 77319, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.1373660489917, + 'timestamp_carla': 656136, + 'timestamp_device': 1526736, + 'timestamp_stream': 656.1373660489917, + 'transform': [array([-37.7418251 , 80.40945435, -0.10281163]), + array([ 8.49334002e-02, -1.56189484e+02, -1.47216931e-01])]} +{'AngularVelocity': array([ 0.03898865, 0.04456696, -0.00570267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037963297218084335, + 'FR_Wheel_Angle': 0.003796094562858343, + 'Location': array([-6.36352081e+01, 8.78464050e+01, 1.70374871e-03]), + 'Rotation': array([7.71128293e-03, 1.52567764e+02, 2.25002016e-03]), + 'Velocity': array([-0.67899251, 0.35157776, 0.00101082]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12575.4072265625, + 'focus_actor_name': 'BP_RepSpline18', + 'focus_actor_pt': array([-9218.91308594, 20840.50390625, 86.42184448]), + 'frame': 19158, + 'frame_number': 19158, + 'framesequence': 77323, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.1717541515827, + 'timestamp_carla': 656171, + 'timestamp_device': 1526769, + 'timestamp_stream': 656.1717541515827, + 'transform': [array([-37.7602272 , 80.42449951, -0.10279658]), + array([ 8.44689459e-02, -1.56241821e+02, -1.47613660e-01])]} +{'AngularVelocity': array([ 0.02549027, 0.02346406, -0.54045963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037950275000184774, + 'FR_Wheel_Angle': 0.003795998403802514, + 'Location': array([-6.37211494e+01, 8.78908997e+01, 1.72854424e-03]), + 'Rotation': array([8.29867925e-03, 1.52558640e+02, 3.62948421e-03]), + 'Velocity': array([-6.73847318e-01, 3.50279421e-01, -2.79083237e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6799.60791015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6877.67480469, 15562.55859375, 101.20886993]), + 'frame': 19159, + 'frame_number': 19159, + 'framesequence': 77327, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.2060972489417, + 'timestamp_carla': 656205, + 'timestamp_device': 1526802, + 'timestamp_stream': 656.2060972489417, + 'transform': [array([-37.77951431, 80.43929291, -0.10284325]), + array([ 8.39498490e-02, -1.56298126e+02, -1.47735730e-01])]} +{'AngularVelocity': array([ 0.01589359, 0.02558332, -0.30596086]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037961697671562433, + 'FR_Wheel_Angle': 0.003797039156779647, + 'Location': array([-6.38062935e+01, 8.79352875e+01, 1.73808099e-03]), + 'Rotation': array([7.98449107e-03, 1.52574280e+02, 4.29393444e-03]), + 'Velocity': array([-6.66159451e-01, 3.46390098e-01, 1.14846225e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6789.6689453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6868.63964844, 15557.79882812, 101.18210602]), + 'frame': 19160, + 'frame_number': 19160, + 'framesequence': 77331, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.2366554513574, + 'timestamp_carla': 656236, + 'timestamp_device': 1526835, + 'timestamp_stream': 656.2366554513574, + 'transform': [array([-37.79616165, 80.45266724, -0.1028361 ]), + array([ 8.36220011e-02, -1.56345886e+02, -1.47918880e-01])]} +{'AngularVelocity': array([0.02974554, 0.05115153, 0.17475776]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037970750126987696, + 'FR_Wheel_Angle': 0.003796948352828622, + 'Location': array([-6.38942108e+01, 8.79810562e+01, 1.71065331e-03]), + 'Rotation': array([8.21671728e-03, 1.52595978e+02, 4.45144903e-03]), + 'Velocity': array([-6.78705037e-01, 3.52378786e-01, -1.15156174e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6779.173828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6858.96484375, 15552.703125 , 101.18888092]), + 'frame': 19161, + 'frame_number': 19161, + 'framesequence': 77335, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.2719141505659, + 'timestamp_carla': 656271, + 'timestamp_device': 1526869, + 'timestamp_stream': 656.2719141505659, + 'transform': [array([-37.81559372, 80.46789551, -0.10279363]), + array([ 8.32804888e-02, -1.56402252e+02, -1.48468167e-01])]} +{'AngularVelocity': array([ 0.02781511, 0.05119558, -0.00054748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003796912496909499, + 'FR_Wheel_Angle': 0.003795991651713848, + 'Location': array([-6.39796219e+01, 8.80252609e+01, 1.72171590e-03]), + 'Rotation': array([7.80007569e-03, 1.52596588e+02, 4.48970031e-03]), + 'Velocity': array([-6.71256006e-01, 3.47340763e-01, -3.16524493e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6773.083984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6851.92773438, 15551.02734375, 101.18038177]), + 'frame': 19162, + 'frame_number': 19162, + 'framesequence': 77339, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.3062029518187, + 'timestamp_carla': 656305, + 'timestamp_device': 1526902, + 'timestamp_stream': 656.3062029518187, + 'transform': [array([-37.83385086, 80.4828949 , -0.10276796]), + array([ 8.29458162e-02, -1.56454376e+02, -1.48864910e-01])]} +{'AngularVelocity': array([0.02129688, 0.04703705, 0.03990154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037970247212797403, + 'FR_Wheel_Angle': 0.003795664058998227, + 'Location': array([-6.40636063e+01, 8.80689316e+01, 1.73125265e-03]), + 'Rotation': array([8.19622632e-03, 1.52614120e+02, 4.67794994e-03]), + 'Velocity': array([-6.71432376e-01, 3.47582817e-01, 5.98425861e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6776.53564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6847.86816406, 15558.734375 , 101.09945679]), + 'frame': 19163, + 'frame_number': 19163, + 'framesequence': 77343, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.337378051132, + 'timestamp_carla': 656337, + 'timestamp_device': 1526935, + 'timestamp_stream': 656.337378051132, + 'transform': [array([-37.84984589, 80.49685669, -0.10278848]), + array([ 8.25155079e-02, -1.56498947e+02, -1.48956448e-01])]} +{'AngularVelocity': array([-0.02776251, -0.05822949, 0.63829547]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003797275945544243, + 'FR_Wheel_Angle': 0.0037938826717436314, + 'Location': array([-6.41487198e+01, 8.81131744e+01, 1.66743272e-03]), + 'Rotation': array([7.41758524e-03, 1.52632187e+02, 4.82382160e-03]), + 'Velocity': array([-0.60571706, 0.31508699, -0.00067458]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6779.65234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6844.10546875, 15565.87792969, 101.03897858]), + 'frame': 19164, + 'frame_number': 19164, + 'framesequence': 77347, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.3701608516276, + 'timestamp_carla': 656369, + 'timestamp_device': 1526969, + 'timestamp_stream': 656.3701608516276, + 'transform': [array([-37.86648178, 80.5117569 , -0.10284734]), + array([ 8.20305645e-02, -1.56544861e+02, -1.48986965e-01])]} +{'AngularVelocity': array([-0.02503924, -0.04716237, -0.16983725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037942123599350452, + 'FR_Wheel_Angle': 0.003793915966525674, + 'Location': array([-6.42356873e+01, 8.81582336e+01, 1.70195580e-03]), + 'Rotation': array([6.78920746e-03, 1.52638519e+02, 4.56429552e-03]), + 'Velocity': array([-5.94074130e-01, 3.06838632e-01, 2.38409033e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6741.439453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6824.61816406, 15534.609375 , 101.12430573]), + 'frame': 19165, + 'frame_number': 19165, + 'framesequence': 77351, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.4042132496834, + 'timestamp_carla': 656403, + 'timestamp_device': 1527002, + 'timestamp_stream': 656.4042132496834, + 'transform': [array([-37.88367081, 80.52732849, -0.10286704]), + array([ 8.12109411e-02, -1.56592194e+02, -1.49261639e-01])]} +{'AngularVelocity': array([-0.01794679, -0.03617262, 0.29656184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037933806888759136, + 'FR_Wheel_Angle': 0.0037930214311927557, + 'Location': array([-6.43200150e+01, 8.82017593e+01, 1.73209189e-03]), + 'Rotation': array([7.99815077e-03, 1.52637619e+02, 4.62733489e-03]), + 'Velocity': array([-6.12333298e-01, 3.16233277e-01, 2.51951220e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6732.67138671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6816.79492188, 15530.48828125, 101.13897705]), + 'frame': 19166, + 'frame_number': 19166, + 'framesequence': 77355, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.4379085488617, + 'timestamp_carla': 656437, + 'timestamp_device': 1527035, + 'timestamp_stream': 656.4379085488617, + 'transform': [array([-37.90052795, 80.54280853, -0.10276205]), + array([ 7.94965699e-02, -1.56638428e+02, -1.50085628e-01])]} +{'AngularVelocity': array([0.03001829, 0.05795493, 0.00151929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037930309772491455, + 'FR_Wheel_Angle': 0.0037978379987180233, + 'Location': array([-6.4401535e+01, 8.8243866e+01, 1.6928768e-03]), + 'Rotation': array([8.72215070e-03, 1.52643143e+02, 4.68202028e-03]), + 'Velocity': array([-0.66983211, 0.34590018, -0.0013748 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6723.6279296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6808.7421875 , 15526.24707031, 101.12490082]), + 'frame': 19167, + 'frame_number': 19167, + 'framesequence': 77359, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.4719663523138, + 'timestamp_carla': 656471, + 'timestamp_device': 1527069, + 'timestamp_stream': 656.4719663523138, + 'transform': [array([-37.9175415 , 80.5585022 , -0.10258082]), + array([ 7.75158107e-02, -1.56685165e+02, -1.51245296e-01])]} +{'AngularVelocity': array([-0.01387155, -0.04521552, -0.45716876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003794102231040597, + 'FR_Wheel_Angle': 0.0037945001386106014, + 'Location': array([-6.44868011e+01, 8.82878265e+01, 1.66052813e-03]), + 'Rotation': array([7.56784901e-03, 1.52631149e+02, 4.82419832e-03]), + 'Velocity': array([-6.04660213e-01, 3.13961446e-01, -2.81629560e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6714.78564453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6800.89550781, 15522.11328125, 101.04905701]), + 'frame': 19168, + 'frame_number': 19168, + 'framesequence': 77363, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.5051049515605, + 'timestamp_carla': 656504, + 'timestamp_device': 1527102, + 'timestamp_stream': 656.5051049515605, + 'transform': [array([-37.93413162, 80.57379913, -0.10237338]), + array([ 7.54667595e-02, -1.56730728e+02, -1.52465954e-01])]} +{'AngularVelocity': array([-0.0046579 , -0.01000795, -0.57819074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003794255666434765, + 'FR_Wheel_Angle': 0.0037940999027341604, + 'Location': array([-6.45720901e+01, 8.83319092e+01, 1.73026079e-03]), + 'Rotation': array([7.88203813e-03, 1.52626709e+02, 4.75878920e-03]), + 'Velocity': array([-6.21552348e-01, 3.21461886e-01, 5.20586967e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6708.916015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6794.18554688, 15520.74414062, 100.92562103]), + 'frame': 19169, + 'frame_number': 19169, + 'framesequence': 77367, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.5374680496752, + 'timestamp_carla': 656537, + 'timestamp_device': 1527135, + 'timestamp_stream': 656.5374680496752, + 'transform': [array([-37.95044708, 80.58882904, -0.10216614]), + array([ 7.34586790e-02, -1.56775711e+02, -1.53656155e-01])]} +{'AngularVelocity': array([-0.01086819, -0.02117144, -0.52622509]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003794407472014427, + 'FR_Wheel_Angle': 0.003794353222474456, + 'Location': array([-6.46567383e+01, 8.83757019e+01, 1.73354149e-03]), + 'Rotation': array([8.38064123e-03, 1.52616272e+02, 4.82665375e-03]), + 'Velocity': array([-6.24057114e-01, 3.23398471e-01, -2.82192232e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6711.4326171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6790.90332031, 15526.97265625, 100.77590942]), + 'frame': 19170, + 'frame_number': 19170, + 'framesequence': 77371, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.5716515518725, + 'timestamp_carla': 656571, + 'timestamp_device': 1527169, + 'timestamp_stream': 656.5716515518725, + 'transform': [array([-37.96775436, 80.6046524 , -0.10192844]), + array([ 7.13481531e-02, -1.56823593e+02, -1.55059949e-01])]} +{'AngularVelocity': array([-0.03536063, -0.06669948, 0.0630934 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037938093300908804, + 'FR_Wheel_Angle': 0.003793967654928565, + 'Location': array([-6.47416458e+01, 8.84196243e+01, 1.71923637e-03]), + 'Rotation': array([7.84105714e-03, 1.52611328e+02, 4.70315339e-03]), + 'Velocity': array([-5.96029341e-01, 3.08203101e-01, -4.56809998e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6713.93505859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6787.66308594, 15533.12695312, 100.62991333]), + 'frame': 19171, + 'frame_number': 19171, + 'framesequence': 77375, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.6057499498129, + 'timestamp_carla': 656605, + 'timestamp_device': 1527202, + 'timestamp_stream': 656.6057499498129, + 'transform': [array([-37.98480988, 80.62041473, -0.10166319]), + array([ 6.92717731e-02, -1.56870605e+02, -1.56555280e-01])]} +{'AngularVelocity': array([-0.02397172, -0.04622864, -0.01474888]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037939860485494137, + 'FR_Wheel_Angle': 0.003793986514210701, + 'Location': array([-6.48243408e+01, 8.84623871e+01, 1.73613545e-03]), + 'Rotation': array([7.66347162e-03, 1.52612228e+02, 4.70493129e-03]), + 'Velocity': array([-6.01560652e-01, 3.11001599e-01, 2.30307574e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 12708.9521484375, + 'focus_actor_name': 'BP_RepSpline18', + 'focus_actor_pt': array([-9142.58203125, 21048.3828125 , 84.2406311 ]), + 'frame': 19172, + 'frame_number': 19172, + 'framesequence': 77379, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.6359555497766, + 'timestamp_carla': 656635, + 'timestamp_device': 1527235, + 'timestamp_stream': 656.6359555497766, + 'transform': [array([-38.00017548, 80.63434601, -0.10142546]), + array([ 6.74139634e-02, -1.56913406e+02, -1.57775953e-01])]} +{'AngularVelocity': array([-0.02086188, -0.04105274, 0.05187375]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003793909214437008, + 'FR_Wheel_Angle': 0.0037944400683045387, + 'Location': array([-6.49082336e+01, 8.85057602e+01, 1.72938348e-03]), + 'Rotation': array([7.84788653e-03, 1.52611969e+02, 4.71535139e-03]), + 'Velocity': array([-6.03074372e-01, 3.11815530e-01, 1.28450396e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6670.71435546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6761.74609375, 15501.48828125, 100.40499878]), + 'frame': 19173, + 'frame_number': 19173, + 'framesequence': 77383, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.6703834496439, + 'timestamp_carla': 656670, + 'timestamp_device': 1527269, + 'timestamp_stream': 656.6703834496439, + 'transform': [array([-38.01638412, 80.65093231, -0.10129273]), + array([ 6.51804954e-02, -1.56956161e+02, -1.58783033e-01])]} +{'AngularVelocity': array([0.0271595 , 0.05718657, 0.04376023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037965881638228893, + 'FR_Wheel_Angle': 0.0037955192383378744, + 'Location': array([-6.49929123e+01, 8.85496140e+01, 1.64603232e-03]), + 'Rotation': array([8.03230237e-03, 1.52614716e+02, 4.80591599e-03]), + 'Velocity': array([-0.64965016, 0.33623028, -0.00066011]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6662.69580078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6754.5859375 , 15497.71679688, 100.28648376]), + 'frame': 19174, + 'frame_number': 19174, + 'framesequence': 77387, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.704233251512, + 'timestamp_carla': 656703, + 'timestamp_device': 1527302, + 'timestamp_stream': 656.704233251512, + 'transform': [array([-38.03497314, 80.66631317, -0.10123189]), + array([ 6.50643781e-02, -1.57009705e+02, -1.59271330e-01])]} +{'AngularVelocity': array([ 0.03057354, 0.05206569, -0.11258466]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003799139056354761, + 'FR_Wheel_Angle': 0.003798682941123843, + 'Location': array([-6.50735855e+01, 8.85912476e+01, 1.67017931e-03]), + 'Rotation': array([7.90252816e-03, 1.52622940e+02, 4.61604167e-03]), + 'Velocity': array([-0.64299017, 0.33189717, 0.00067193]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6654.39306640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6747.4140625 , 15493.93847656, 100.19021606]), + 'frame': 19175, + 'frame_number': 19175, + 'framesequence': 77391, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12006592750549316, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.7381074503064, + 'timestamp_carla': 656737, + 'timestamp_device': 1527335, + 'timestamp_stream': 656.7381074503064, + 'transform': [array([-38.05255127, 80.68200684, -0.10126965]), + array([ 6.53990582e-02, -1.57058746e+02, -1.59332365e-01])]} +{'AngularVelocity': array([-0.00698696, -0.01392877, 0.0043125 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037977308966219425, + 'FR_Wheel_Angle': 0.0037981353234499693, + 'Location': array([-6.51545792e+01, 8.86330872e+01, 1.69146538e-03]), + 'Rotation': array([7.82056618e-03, 1.52619797e+02, 4.77171829e-03]), + 'Velocity': array([-6.03791237e-01, 3.12077641e-01, -1.07011794e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6644.65087890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6738.52587891, 15489.2578125 , 100.15610504]), + 'frame': 19176, + 'frame_number': 19176, + 'framesequence': 77395, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11479232460260391, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.7718680500984, + 'timestamp_carla': 656771, + 'timestamp_device': 1527369, + 'timestamp_stream': 656.7718680500984, + 'transform': [array([-38.06910706, 80.69810486, -0.10139427]), + array([ 6.58840016e-02, -1.57103241e+02, -1.59027174e-01])]} +{'AngularVelocity': array([-0.00605646, -0.01151374, 0.00684515]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037970179691910744, + 'FR_Wheel_Angle': 0.0037971714045852423, + 'Location': array([-6.52370300e+01, 8.86757126e+01, 1.66922563e-03]), + 'Rotation': array([7.98449107e-03, 1.52619949e+02, 4.76240227e-03]), + 'Velocity': array([-6.03393376e-01, 3.11912715e-01, -3.62701394e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6645.7958984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6734.37402344, 15494.390625 , 100.13943481]), + 'frame': 19177, + 'frame_number': 19177, + 'framesequence': 77399, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09869686514139175, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.8054452501237, + 'timestamp_carla': 656805, + 'timestamp_device': 1527402, + 'timestamp_stream': 656.8054452501237, + 'transform': [array([-38.08725357, 80.71367645, -0.10155875]), + array([ 6.68607205e-02, -1.57154114e+02, -1.58508405e-01])]} +{'AngularVelocity': array([ 0.0055022 , 0.01092056, -0.03285497]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003797847079113126, + 'FR_Wheel_Angle': 0.0037985434755682945, + 'Location': array([-6.53176193e+01, 8.87173843e+01, 1.67929649e-03]), + 'Rotation': array([8.20305664e-03, 1.52620926e+02, 4.74725384e-03]), + 'Velocity': array([-6.16318345e-01, 3.18564028e-01, 3.96881107e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6648.16015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6731.18115234, 15500.45117188, 100.16070557]), + 'frame': 19178, + 'frame_number': 19178, + 'framesequence': 77403, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0750938430428505, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.8375083506107, + 'timestamp_carla': 656837, + 'timestamp_device': 1527435, + 'timestamp_stream': 656.8375083506107, + 'transform': [array([-38.10222626, 80.72924805, -0.10165218]), + array([ 6.81721121e-02, -1.57191589e+02, -1.58203229e-01])]} +{'AngularVelocity': array([-0.00870864, -0.01733617, 0.04231044]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037973644211888313, + 'FR_Wheel_Angle': 0.0037974966689944267, + 'Location': array([-6.53992233e+01, 8.87595673e+01, 1.69028284e-03]), + 'Rotation': array([8.02547205e-03, 1.52622299e+02, 4.74305497e-03]), + 'Velocity': array([-6.00055516e-01, 3.10185283e-01, 5.77831270e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 18893.9140625, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-11480.87109375, 26789.6484375 , 66.3377533 ]), + 'frame': 19179, + 'frame_number': 19179, + 'framesequence': 77407, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05143589898943901, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.870447549969, + 'timestamp_carla': 656870, + 'timestamp_device': 1527469, + 'timestamp_stream': 656.870447549969, + 'transform': [array([-38.11560059, 80.74598694, -0.10177851]), + array([ 6.98591694e-02, -1.57219879e+02, -1.57775983e-01])]} +{'AngularVelocity': array([ 0.01424835, 0.02767599, -0.01802472]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037987367250025272, + 'FR_Wheel_Angle': 0.00379877514205873, + 'Location': array([-6.54805222e+01, 8.88015976e+01, 1.66514388e-03]), + 'Rotation': array([8.12109467e-03, 1.52621384e+02, 4.73530823e-03]), + 'Velocity': array([-6.17308855e-01, 3.19031894e-01, -3.67574685e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6610.5712890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6708.45703125, 15473.41601562, 100.34512329]), + 'frame': 19180, + 'frame_number': 19180, + 'framesequence': 77411, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.035340435802936554, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.9041158519685, + 'timestamp_carla': 656903, + 'timestamp_device': 1527502, + 'timestamp_stream': 656.9041158519685, + 'transform': [array([-38.12766647, 80.7635498 , -0.1018144 ]), + array([ 7.05900043e-02, -1.57240829e+02, -1.57837033e-01])]} +{'AngularVelocity': array([-5.55448420e-03, -1.09747145e-02, -8.99849474e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003797425189986825, + 'FR_Wheel_Angle': 0.00379760074429214, + 'Location': array([-6.55615005e+01, 8.88434448e+01, 1.70939439e-03]), + 'Rotation': array([8.12109467e-03, 1.52621567e+02, 4.73659206e-03]), + 'Velocity': array([-5.99473894e-01, 3.09832484e-01, -5.72948426e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6604.54296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6703.79931641, 15470.96484375, 100.40291595]), + 'frame': 19181, + 'frame_number': 19181, + 'framesequence': 77415, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.035248879343271255, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.9380590505898, + 'timestamp_carla': 656937, + 'timestamp_device': 1527535, + 'timestamp_stream': 656.9380590505898, + 'transform': [array([-38.14039993, 80.78120422, -0.10184075]), + array([ 7.00640753e-02, -1.57263947e+02, -1.58050641e-01])]} +{'AngularVelocity': array([0.00466066, 0.00908224, 0.06194748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0037987176328897476, + 'FR_Wheel_Angle': 0.0037984587252140045, + 'Location': array([-6.56408081e+01, 8.88844376e+01, 1.68688770e-03]), + 'Rotation': array([8.30550957e-03, 1.52621307e+02, 4.73240810e-03]), + 'Velocity': array([-6.11737907e-01, 3.16169113e-01, 2.69699085e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6599.52490234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6700.35839844, 15469.15136719, 100.4029007 ]), + 'frame': 19182, + 'frame_number': 19182, + 'framesequence': 77419, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04603412002325058, + 'throttle_input': 0.07539482414722443, + 'timestamp': 656.9708630517125, + 'timestamp_carla': 656970, + 'timestamp_device': 1527569, + 'timestamp_stream': 656.9708630517125, + 'transform': [array([-38.15213394, 80.79833984, -0.10180376]), + array([ 6.85409456e-02, -1.57284348e+02, -1.58569470e-01])]} +{'AngularVelocity': array([0.00278805, 0.00499876, 0.0110435 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003797766286879778, + 'FR_Wheel_Angle': 0.0037981043569743633, + 'Location': array([-6.57169189e+01, 8.89237976e+01, 1.76012993e-03]), + 'Rotation': array([8.31917021e-03, 1.52621628e+02, 4.73985402e-03]), + 'Velocity': array([-6.09314322e-01, 3.14977497e-01, 5.04083640e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6594.20068359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6696.59472656, 15467.16894531, 100.38659668]), + 'frame': 19183, + 'frame_number': 19183, + 'framesequence': 77423, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.058980073779821396, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.0040588490665, + 'timestamp_carla': 657003, + 'timestamp_device': 1527602, + 'timestamp_stream': 657.0040588490665, + 'transform': [array([-38.16516113, 80.81548309, -0.10164421]), + array([ 6.52761161e-02, -1.57310440e+02, -1.59759626e-01])]} +{'AngularVelocity': array([-0.00497332, -0.0096297 , -0.18620767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003798469202592969, + 'FR_Wheel_Angle': 0.0037992370780557394, + 'Location': array([-6.57967987e+01, 8.89650879e+01, 1.74242968e-03]), + 'Rotation': array([7.99815077e-03, 1.52621811e+02, 4.73788800e-03]), + 'Velocity': array([-5.99220932e-01, 3.09723824e-01, -1.87339785e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6589.32568359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6693.2578125 , 15465.41210938, 100.33798981]), + 'frame': 19184, + 'frame_number': 19184, + 'framesequence': 77427, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0708639845252037, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.0367623493075, + 'timestamp_carla': 657036, + 'timestamp_device': 1527635, + 'timestamp_stream': 657.0367623493075, + 'transform': [array([-38.17911148, 80.83209229, -0.10160057]), + array([ 6.33295104e-02, -1.57341614e+02, -1.60339445e-01])]} +{'AngularVelocity': array([ 1.78798195e-02, 3.45073603e-02, -4.62050775e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.58790054e+01, 8.90075836e+01, 1.71484938e-03]), + 'Rotation': array([1.02726035e-02, 1.52621384e+02, 4.73965332e-03]), + 'Velocity': array([-6.59704089e-01, 3.41009349e-01, -3.40185157e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6583.61572265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6689.00097656, 15463.16796875, 100.21591187]), + 'frame': 19185, + 'frame_number': 19185, + 'framesequence': 77431, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07306131720542908, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.0702407509089, + 'timestamp_carla': 657069, + 'timestamp_device': 1527669, + 'timestamp_stream': 657.0702407509089, + 'transform': [array([-38.19414139, 80.84898376, -0.10162981]), + array([ 6.21888675e-02, -1.57377090e+02, -1.60583615e-01])]} +{'AngularVelocity': array([-7.75640877e-03, -1.49413785e-02, 2.82034966e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.59689789e+01, 8.90540695e+01, 1.69951434e-03]), + 'Rotation': array([1.12151699e-02, 1.52621429e+02, 4.73756157e-03]), + 'Velocity': array([-6.74404502e-01, 3.48608643e-01, -2.45246891e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6577.2265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6683.92236328, 15460.49316406, 100.16466522]), + 'frame': 19186, + 'frame_number': 19186, + 'framesequence': 77435, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06883145123720169, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.1030052490532, + 'timestamp_carla': 657102, + 'timestamp_device': 1527702, + 'timestamp_stream': 657.1030052490532, + 'transform': [array([-38.20871353, 80.86548615, -0.10163426]), + array([ 6.18610196e-02, -1.57411270e+02, -1.60827741e-01])]} +{'AngularVelocity': array([-9.30110458e-03, -1.79722663e-02, 4.80872222e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.60574799e+01, 8.90998001e+01, 1.71374320e-03]), + 'Rotation': array([8.45577382e-03, 1.52621506e+02, 4.73816739e-03]), + 'Velocity': array([-6.47394717e-01, 3.34646761e-01, 1.57003393e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6572.3583984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6678.98730469, 15459.4609375 , 100.14535522]), + 'frame': 19187, + 'frame_number': 19187, + 'framesequence': 77439, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.062111273407936096, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.1377656497061, + 'timestamp_carla': 657137, + 'timestamp_device': 1527735, + 'timestamp_stream': 657.1377656497061, + 'transform': [array([-38.22392654, 80.88327789, -0.10170817]), + array([ 6.19498119e-02, -1.57445862e+02, -1.60827741e-01])]} +{'AngularVelocity': array([-5.30135492e-03, -1.02091935e-02, 4.61306490e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.61414185e+01, 8.91432190e+01, 1.72636984e-03]), + 'Rotation': array([6.44086814e-03, 1.52621521e+02, 4.73881001e-03]), + 'Velocity': array([-6.13949239e-01, 3.17358136e-01, -2.29454035e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6573.70703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6676.5625 , 15464.0625 , 100.10917664]), + 'frame': 19188, + 'frame_number': 19188, + 'framesequence': 77443, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05562914162874222, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.1705291494727, + 'timestamp_carla': 657170, + 'timestamp_device': 1527769, + 'timestamp_stream': 657.1705291494727, + 'transform': [array([-38.23722458, 80.90013123, -0.10170263]), + array([ 6.22230209e-02, -1.57474014e+02, -1.61041364e-01])]} +{'AngularVelocity': array([-2.46795313e-03, -4.72002989e-03, 2.25534222e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.62231445e+01, 8.91854553e+01, 1.72114372e-03]), + 'Rotation': array([5.45049086e-03, 1.52621521e+02, 4.73986147e-03]), + 'Velocity': array([-5.79873383e-01, 2.99743921e-01, 7.39002207e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6574.96142578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6674.10839844, 15468.72167969, 100.09794617]), + 'frame': 19189, + 'frame_number': 19189, + 'framesequence': 77447, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05381634086370468, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.2054293490946, + 'timestamp_carla': 657205, + 'timestamp_device': 1527802, + 'timestamp_stream': 657.2054293490946, + 'transform': [array([-38.25157166, 80.91838074, -0.10181708]), + array([ 6.24689050e-02, -1.57503983e+02, -1.60858274e-01])]} +{'AngularVelocity': array([-3.09705538e-05, -5.78521249e-05, 9.24656251e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.62960739e+01, 8.92231827e+01, 1.70649530e-03]), + 'Rotation': array([5.32754743e-03, 1.52621521e+02, 4.74067638e-03]), + 'Velocity': array([-5.50333381e-01, 2.84474820e-01, 2.44741444e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6575.73046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6672.10839844, 15472.51855469, 100.06534576]), + 'frame': 19190, + 'frame_number': 19190, + 'framesequence': 77452, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05616016313433647, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.2410977520049, + 'timestamp_carla': 657240, + 'timestamp_device': 1527844, + 'timestamp_stream': 657.2410977520049, + 'transform': [array([-38.2657814 , 80.93717957, -0.10187661]), + array([ 6.24074340e-02, -1.57532623e+02, -1.60949782e-01])]} +{'AngularVelocity': array([1.63959354e-04, 2.08069192e-04, 6.16076431e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0038316359277814627, + 'Location': array([-6.63669434e+01, 8.92598190e+01, 1.74780842e-03]), + 'Rotation': array([5.32754743e-03, 1.52621521e+02, 4.74067638e-03]), + 'Velocity': array([-5.19890785e-01, 2.68738389e-01, 4.00447840e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7861.06640625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-7161.47705078, 16663.35546875, 96.46990967]), + 'frame': 19191, + 'frame_number': 19191, + 'framesequence': 77456, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059694208204746246, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.2742475494742, + 'timestamp_carla': 657274, + 'timestamp_device': 1527877, + 'timestamp_stream': 657.2742475494742, + 'transform': [array([-38.27930069, 80.95439911, -0.10186581]), + array([ 6.21888675e-02, -1.57560974e+02, -1.61224455e-01])]} +{'AngularVelocity': array([ 1.68510436e-04, 1.52179156e-04, -1.35908749e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451857399195433, + 'FR_Wheel_Angle': 0.0038453275337815285, + 'Location': array([-6.63922501e+01, 8.92728882e+01, 1.87453267e-03]), + 'Rotation': array([-2.00534351e-02, 1.52621414e+02, 4.76100203e-03]), + 'Velocity': array([ 1.65226163e-06, -8.73276690e-07, -6.13126729e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6537.90283203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6652.95214844, 15444.17773438, 100.16667175]), + 'frame': 19192, + 'frame_number': 19192, + 'framesequence': 77460, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.062276072800159454, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.3090309500694, + 'timestamp_carla': 657308, + 'timestamp_device': 1527910, + 'timestamp_stream': 657.3090309500694, + 'transform': [array([-38.29275894, 80.97257233, -0.10187769]), + array([ 6.18883409e-02, -1.57587921e+02, -1.61499128e-01])]} +{'AngularVelocity': array([4.30075340e-02, 8.33663195e-02, 7.31177465e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451850414276123, + 'FR_Wheel_Angle': 0.0038453286979347467, + 'Location': array([-6.63923264e+01, 8.92729263e+01, 1.82192796e-03]), + 'Rotation': array([-8.57188739e-03, 1.52621414e+02, 4.75044781e-03]), + 'Velocity': array([ 5.80985834e-05, -2.99925450e-05, 3.66878492e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6531.92431640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6648.38476562, 15441.77246094, 100.14696503]), + 'frame': 19193, + 'frame_number': 19193, + 'framesequence': 77464, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06187322735786438, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.3422465510666, + 'timestamp_carla': 657342, + 'timestamp_device': 1527944, + 'timestamp_stream': 657.3422465510666, + 'transform': [array([-38.30511093, 80.98996735, -0.10188325]), + array([ 6.17107563e-02, -1.57611740e+02, -1.61712706e-01])]} +{'AngularVelocity': array([2.24166289e-02, 4.31776084e-02, 3.75993523e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451869040727615, + 'FR_Wheel_Angle': 0.0038453307934105396, + 'Location': array([-6.63923798e+01, 8.92729568e+01, 1.77805894e-03]), + 'Rotation': array([5.19094348e-04, 1.52621414e+02, 4.74424334e-03]), + 'Velocity': array([ 3.01214532e-05, -1.56544702e-05, 3.13034048e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6526.04638671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6644.03515625, 15439.48046875, 100.12584686]), + 'frame': 19194, + 'frame_number': 19194, + 'framesequence': 77467, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06033509597182274, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.3724301494658, + 'timestamp_carla': 657372, + 'timestamp_device': 1527969, + 'timestamp_stream': 657.3724301494658, + 'transform': [array([-38.31661606, 81.00576782, -0.10192408]), + array([ 6.16151318e-02, -1.57634460e+02, -1.61682203e-01])]} +{'AngularVelocity': array([1.01971561e-02, 1.96374655e-02, 1.25707288e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451883010566235, + 'FR_Wheel_Angle': 0.003845331259071827, + 'Location': array([-6.63924103e+01, 8.92729797e+01, 1.74891471e-03]), + 'Rotation': array([4.93822666e-03, 1.52621414e+02, 4.74185962e-03]), + 'Velocity': array([ 1.37419775e-05, -7.07264098e-06, 3.09452997e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6520.70556640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6640.18359375, 15437.453125 , 100.11190796]), + 'frame': 19195, + 'frame_number': 19195, + 'framesequence': 77471, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059236425906419754, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.4038948491216, + 'timestamp_carla': 657403, + 'timestamp_device': 1528002, + 'timestamp_stream': 657.4038948491216, + 'transform': [array([-38.32899094, 81.02213287, -0.10197576]), + array([ 6.16151318e-02, -1.57659790e+02, -1.61682233e-01])]} +{'AngularVelocity': array([4.57260106e-03, 8.87168851e-03, 5.03823010e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451887667179108, + 'FR_Wheel_Angle': 0.0038453321903944016, + 'Location': array([-6.63924179e+01, 8.92729874e+01, 1.73815724e-03]), + 'Rotation': array([6.91898121e-03, 1.52621414e+02, 4.74050362e-03]), + 'Velocity': array([ 6.20310357e-06, -3.19046717e-06, 1.34844784e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6515.70654296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6636.52099609, 15435.5234375 , 100.12683868]), + 'frame': 19196, + 'frame_number': 19196, + 'framesequence': 77475, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059236425906419754, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.4375657513738, + 'timestamp_carla': 657437, + 'timestamp_device': 1528035, + 'timestamp_stream': 657.4375657513738, + 'transform': [array([-38.34205627, 81.03964996, -0.10203116]), + array([ 6.15536608e-02, -1.57686188e+02, -1.61773801e-01])]} +{'AngularVelocity': array([2.05505989e-03, 3.88306985e-03, 4.66141934e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451889995485544, + 'FR_Wheel_Angle': 0.0038453321903944016, + 'Location': array([-6.63924255e+01, 8.92729874e+01, 1.72202103e-03]), + 'Rotation': array([7.82056618e-03, 1.52621414e+02, 4.74017998e-03]), + 'Velocity': array([ 2.68167423e-06, -1.49598031e-06, 2.61001580e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6510.2841796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6632.45703125, 15433.3828125 , 100.13697052]), + 'frame': 19197, + 'frame_number': 19197, + 'framesequence': 77479, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.4700532518327, + 'timestamp_carla': 657469, + 'timestamp_device': 1528069, + 'timestamp_stream': 657.4700532518327, + 'transform': [array([-38.35461044, 81.05648041, -0.10207098]), + array([ 6.14580400e-02, -1.57711594e+02, -1.61865324e-01])]} +{'AngularVelocity': array([9.18991165e-04, 1.69794692e-03, 2.28931256e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451889995485544, + 'FR_Wheel_Angle': 0.0038453321903944016, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70771591e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 1.16887861e-06, -6.74984676e-07, -4.02832025e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6504.58203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6628.21972656, 15431.1484375 , 100.13473511]), + 'frame': 19198, + 'frame_number': 19198, + 'framesequence': 77483, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0604083389043808, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.5046299509704, + 'timestamp_carla': 657504, + 'timestamp_device': 1528102, + 'timestamp_stream': 657.5046299509704, + 'transform': [array([-38.36963654, 81.07408905, -0.10219505]), + array([ 6.11575097e-02, -1.57745865e+02, -1.61712691e-01])]} +{'AngularVelocity': array([3.91044450e-04, 7.95010594e-04, 7.41291295e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451889995485544, + 'FR_Wheel_Angle': 0.0038453321903944016, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.71622273e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 5.31990054e-07, -3.20781965e-07, 4.05616738e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6499.10791015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6624.14794922, 15429.00585938, 100.13355255]), + 'frame': 19199, + 'frame_number': 19199, + 'framesequence': 77487, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06018860638141632, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.537525549531, + 'timestamp_carla': 657537, + 'timestamp_device': 1528135, + 'timestamp_stream': 657.537525549531, + 'transform': [array([-38.38431549, 81.09085083, -0.10229877]), + array([ 6.10345677e-02, -1.57779999e+02, -1.61529630e-01])]} +{'AngularVelocity': array([1.73017761e-04, 3.38343089e-04, 1.28410562e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451889995485544, + 'FR_Wheel_Angle': 0.0038453321903944016, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.73235894e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 2.15771806e-07, -1.59813638e-07, -2.62069698e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6497.09765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6620.51123047, 15430.57128906, 100.14924622]), + 'frame': 19200, + 'frame_number': 19200, + 'framesequence': 77491, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.5717309489846, + 'timestamp_carla': 657571, + 'timestamp_device': 1528169, + 'timestamp_stream': 657.5717309489846, + 'transform': [array([-38.39861298, 81.10864258, -0.10239498]), + array([ 6.09116219e-02, -1.57811203e+02, -1.61438078e-01])]} +{'AngularVelocity': array([1.23631937e-04, 1.33491092e-04, 9.33175048e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038451889995485544, + 'FR_Wheel_Angle': 0.0038453321903944016, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.70134543e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 7.53435785e-08, -1.21233199e-07, -2.52637867e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6498.41552734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6618.11230469, 15435.12402344, 100.16075134]), + 'frame': 19201, + 'frame_number': 19201, + 'framesequence': 77495, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.6035502515733, + 'timestamp_carla': 657603, + 'timestamp_device': 1528202, + 'timestamp_stream': 657.6035502515733, + 'transform': [array([-38.4119339 , 81.12516785, -0.10244387]), + array([ 6.08228296e-02, -1.57840332e+02, -1.61438063e-01])]} +{'AngularVelocity': array([ 3.63458312e-05, 7.49972460e-05, -6.59344856e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72156328e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 5.29635393e-08, -2.60181103e-08, -7.64560682e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6499.36669921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6615.91455078, 15439.296875 , 100.16107941]), + 'frame': 19202, + 'frame_number': 19202, + 'framesequence': 77499, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.636934351176, + 'timestamp_carla': 657636, + 'timestamp_device': 1528235, + 'timestamp_stream': 657.636934351176, + 'transform': [array([-38.42663574, 81.14241028, -0.10254343]), + array([ 6.06315844e-02, -1.57874008e+02, -1.61315992e-01])]} +{'AngularVelocity': array([1.63493332e-05, 3.30029798e-05, 3.17396709e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72224990e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 2.06725481e-08, -1.68088192e-08, 3.21197513e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6500.27294921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6613.859375 , 15443.19921875, 100.15394592]), + 'frame': 19203, + 'frame_number': 19203, + 'framesequence': 77503, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.6699928492308, + 'timestamp_carla': 657669, + 'timestamp_device': 1528269, + 'timestamp_stream': 657.6699928492308, + 'transform': [array([-38.44046783, 81.15969849, -0.10259374]), + array([ 6.05154745e-02, -1.57904312e+02, -1.61377043e-01])]} +{'AngularVelocity': array([1.69041687e-05, 1.86230936e-05, 1.20749000e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72152510e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([ 1.07424745e-08, -1.66236873e-08, 6.08444207e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 14206.1923828125, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-9513.42480469, 22584.953125 , 78.46554565]), + 'frame': 19204, + 'frame_number': 19204, + 'framesequence': 77507, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.7038285508752, + 'timestamp_carla': 657703, + 'timestamp_device': 1528302, + 'timestamp_stream': 657.7038285508752, + 'transform': [array([-38.45537186, 81.17733002, -0.10268077]), + array([ 6.03925288e-02, -1.57938385e+02, -1.61316007e-01])]} +{'AngularVelocity': array([ 2.02043225e-06, 1.27010671e-05, -5.08936893e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-6.63924332e+01, 8.92729874e+01, 1.72923086e-03]), + 'Rotation': array([8.05962272e-03, 1.52621414e+02, 4.73898230e-03]), + 'Velocity': array([2.30778188e-08, 2.75827006e-08, 4.15101036e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6460.5048828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6593.56933594, 15412.89648438, 100.26041412]), + 'frame': 19205, + 'frame_number': 19205, + 'framesequence': 77511, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06011535972356796, + 'throttle_input': 0.07539482414722443, + 'timestamp': 657.7368214502931, + 'timestamp_carla': 657736, + 'timestamp_device': 1528335, + 'timestamp_stream': 657.7368214502931, + 'transform': [array([-38.46907806, 81.194664 , -0.102713 ]), + array([ 6.03037365e-02, -1.57968201e+02, -1.61438078e-01])]} \ No newline at end of file diff --git a/PythonAPI/data/vehicle_logs/forward_1.txt b/PythonAPI/data/vehicle_logs/forward_1.txt new file mode 100644 index 0000000..4bf6369 --- /dev/null +++ b/PythonAPI/data/vehicle_logs/forward_1.txt @@ -0,0 +1,22419 @@ +{'AngularVelocity': array([ 2.90770032e-07, -5.83290193e-06, -2.58249533e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71800880e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-2.96984348e-09, 1.22884325e-09, 8.62455345e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31783295]), + 'frame': 25133, + 'frame_number': 25133, + 'framesequence': 101227, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.3300756514072, + 'timestamp_carla': 855329, + 'timestamp_device': 1725926, + 'timestamp_stream': 855.3300756514072, + 'transform': [array([-35.09139633, 68.05452728, -0.10173368]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 3.31231022e-05, -7.52617598e-06, 3.27363381e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.70919327e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.65250427e-08, -3.92864052e-08, -4.10766603e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31633759]), + 'frame': 25134, + 'frame_number': 25134, + 'framesequence': 101231, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.3600961491466, + 'timestamp_carla': 855359, + 'timestamp_device': 1725959, + 'timestamp_stream': 855.3600961491466, + 'transform': [array([-35.09139633, 68.05452728, -0.10171701]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-6.07460242e-05, 1.44063397e-05, -1.49457957e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71632273e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([1.35794194e-08, 4.85558118e-08, 6.59751880e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31673431]), + 'frame': 25135, + 'frame_number': 25135, + 'framesequence': 101235, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.3976274505258, + 'timestamp_carla': 855396, + 'timestamp_device': 1725992, + 'timestamp_stream': 855.3976274505258, + 'transform': [array([-35.09139633, 68.05452728, -0.10176802]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 4.96304710e-05, -1.91865456e-05, 2.72055378e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71804307e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-8.83430484e-09, -3.01936183e-08, -1.85632700e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31839752]), + 'frame': 25136, + 'frame_number': 25136, + 'framesequence': 101239, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.4264186508954, + 'timestamp_carla': 855425, + 'timestamp_device': 1726026, + 'timestamp_stream': 855.4264186508954, + 'transform': [array([-35.09139633, 68.05452728, -0.10179663]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-5.36204561e-06, -3.06811512e-06, -2.10792916e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71463294e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 6.32245456e-09, 1.61099436e-08, -3.32641590e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31330109]), + 'frame': 25137, + 'frame_number': 25137, + 'framesequence': 101243, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.4637711495161, + 'timestamp_carla': 855462, + 'timestamp_device': 1726059, + 'timestamp_stream': 855.4637711495161, + 'transform': [array([-35.09139633, 68.05452728, -0.10180669]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 1.59379101e-06, -3.87854152e-06, 3.17091930e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71789816e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-6.00567640e-09, -5.34402034e-09, 2.14776985e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31044006]), + 'frame': 25138, + 'frame_number': 25138, + 'framesequence': 101247, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.4929898492992, + 'timestamp_carla': 855492, + 'timestamp_device': 1726092, + 'timestamp_stream': 855.4929898492992, + 'transform': [array([-35.09139633, 68.05452728, -0.10182184]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-6.64362460e-07, -4.99486760e-06, 4.21975477e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71814626e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.26973880e-08, -1.13587317e-08, 4.23793797e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.30943298]), + 'frame': 25139, + 'frame_number': 25139, + 'framesequence': 101252, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.5309051498771, + 'timestamp_carla': 855530, + 'timestamp_device': 1726134, + 'timestamp_stream': 855.5309051498771, + 'transform': [array([-35.09139633, 68.05452728, -0.10182039]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 4.30335240e-05, -1.37217567e-05, -1.29390287e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71690649e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.87463911e-09, -2.02434318e-08, 3.43666063e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.30791473]), + 'frame': 25140, + 'frame_number': 25140, + 'framesequence': 101255, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.5594221502542, + 'timestamp_carla': 855558, + 'timestamp_device': 1726159, + 'timestamp_stream': 855.5594221502542, + 'transform': [array([-35.09139633, 68.05452728, -0.10181856]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.50637088e-05, 5.58335614e-06, -6.85593005e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71782179e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([1.70107999e-08, 2.86672943e-08, 5.62701200e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.30805969]), + 'frame': 25141, + 'frame_number': 25141, + 'framesequence': 101260, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.6005213521421, + 'timestamp_carla': 855599, + 'timestamp_device': 1726201, + 'timestamp_stream': 855.6005213521421, + 'transform': [array([-35.09139633, 68.05452728, -0.10176733]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 4.26277184e-05, -1.39622207e-05, -3.30611294e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71615882e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 3.42227158e-09, -1.29314071e-08, -1.52101507e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3082428 ]), + 'frame': 25142, + 'frame_number': 25142, + 'framesequence': 101263, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.6293609514832, + 'timestamp_carla': 855628, + 'timestamp_device': 1726226, + 'timestamp_stream': 855.6293609514832, + 'transform': [array([-35.09139633, 68.05452728, -0.10178716]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.95680113e-05, 6.90400475e-06, 1.57276102e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71614727e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-3.14190740e-09, 3.42799145e-09, 2.24113455e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31336975]), + 'frame': 25143, + 'frame_number': 25143, + 'framesequence': 101268, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.6704018525779, + 'timestamp_carla': 855669, + 'timestamp_device': 1726267, + 'timestamp_stream': 855.6704018525779, + 'transform': [array([-35.09139633, 68.05452728, -0.10175055]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-2.00614177e-05, 8.61324315e-06, 4.77592321e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71641065e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-4.13583168e-09, 1.02524611e-09, 1.23023983e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31138611]), + 'frame': 25144, + 'frame_number': 25144, + 'framesequence': 101272, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.6986953504384, + 'timestamp_carla': 855697, + 'timestamp_device': 1726301, + 'timestamp_stream': 855.6986953504384, + 'transform': [array([-35.09139633, 68.05452728, -0.10177115]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.95773700e-05, 7.20803109e-06, 5.14582332e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71311824e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-4.54709381e-09, 1.44346812e-09, -2.35576619e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31504822]), + 'frame': 25145, + 'frame_number': 25145, + 'framesequence': 101276, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.7328110523522, + 'timestamp_carla': 855732, + 'timestamp_device': 1726334, + 'timestamp_stream': 855.7328110523522, + 'transform': [array([-35.09139633, 68.05452728, -0.10175661]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-8.19272555e-06, -1.57248382e-06, 3.83925869e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71874492e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.40123868e-08, -1.08924416e-08, 3.19118495e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31298828]), + 'frame': 25146, + 'frame_number': 25146, + 'framesequence': 101280, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.766030151397, + 'timestamp_carla': 855765, + 'timestamp_device': 1726367, + 'timestamp_stream': 855.766030151397, + 'transform': [array([-35.09139633, 68.05452728, -0.10174242]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 4.37831877e-05, -1.44645128e-05, 5.22940180e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71182892e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.31956215e-08, -3.60762762e-08, -7.43980403e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31443787]), + 'frame': 25147, + 'frame_number': 25147, + 'framesequence': 101283, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.7979290522635, + 'timestamp_carla': 855797, + 'timestamp_device': 1726392, + 'timestamp_stream': 855.7979290522635, + 'transform': [array([-35.09139633, 68.05452728, -0.1017264 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-6.06182448e-06, -4.02283786e-06, -5.43585532e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71435429e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([8.84472406e-09, 2.05938289e-08, 6.74829469e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31585693]), + 'frame': 25148, + 'frame_number': 25148, + 'framesequence': 101288, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.8318775519729, + 'timestamp_carla': 855831, + 'timestamp_device': 1726434, + 'timestamp_stream': 855.8318775519729, + 'transform': [array([-35.09139633, 68.05452728, -0.10173334]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-3.94109929e-06, -3.48964409e-06, -3.33142935e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71547970e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 4.88295182e-09, 1.36098919e-08, -2.07691191e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31745911]), + 'frame': 25149, + 'frame_number': 25149, + 'framesequence': 101292, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.8649615496397, + 'timestamp_carla': 855864, + 'timestamp_device': 1726467, + 'timestamp_stream': 855.8649615496397, + 'transform': [array([-35.09139633, 68.05452728, -0.10173223]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-2.81467851e-06, -4.21627647e-06, 8.62538130e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71639538e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.96783088e-08, -2.08107256e-08, 1.19352335e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31676483]), + 'frame': 25150, + 'frame_number': 25150, + 'framesequence': 101296, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.8989104516804, + 'timestamp_carla': 855898, + 'timestamp_device': 1726500, + 'timestamp_stream': 855.8989104516804, + 'transform': [array([-35.09139633, 68.05452728, -0.10173941]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 4.73058208e-05, -1.67512262e-05, 6.82383039e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71673475e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.95043253e-08, -4.44601014e-08, 2.71887780e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31687927]), + 'frame': 25151, + 'frame_number': 25151, + 'framesequence': 101299, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.9287701509893, + 'timestamp_carla': 855927, + 'timestamp_device': 1726525, + 'timestamp_stream': 855.9287701509893, + 'transform': [array([-35.09139633, 68.05452728, -0.10178842]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.22052352e-05, 3.87117871e-06, 5.46895362e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71639538e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.56112123e-09, 3.03505243e-09, 1.99890128e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31616211]), + 'frame': 25152, + 'frame_number': 25152, + 'framesequence': 101304, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.965776052326, + 'timestamp_carla': 855964, + 'timestamp_device': 1726567, + 'timestamp_stream': 855.965776052326, + 'transform': [array([-35.09139633, 68.05452728, -0.10179609]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 2.35237871e-06, -6.15611043e-06, 2.04014450e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71707413e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-7.13893078e-09, -5.26473709e-09, 5.60693734e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31125641]), + 'frame': 25153, + 'frame_number': 25153, + 'framesequence': 101307, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 855.9961664490402, + 'timestamp_carla': 855995, + 'timestamp_device': 1726592, + 'timestamp_stream': 855.9961664490402, + 'transform': [array([-35.09139633, 68.05452728, -0.10175226]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.46668744e-05, 6.68814209e-06, 1.76805043e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71770743e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.80070481e-09, 1.90747440e-09, 2.03247066e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31049347]), + 'frame': 25154, + 'frame_number': 25154, + 'framesequence': 101312, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.0322983525693, + 'timestamp_carla': 856031, + 'timestamp_device': 1726634, + 'timestamp_stream': 856.0322983525693, + 'transform': [array([-35.09139633, 68.05452728, -0.10176744]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-6.55837066e-05, 1.90993233e-05, -7.45662199e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71646392e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 2.68613487e-08, 6.61569999e-08, -1.52893059e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31487274]), + 'frame': 25155, + 'frame_number': 25155, + 'framesequence': 101316, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.0650150515139, + 'timestamp_carla': 856064, + 'timestamp_device': 1726667, + 'timestamp_stream': 856.0650150515139, + 'transform': [array([-35.09139633, 68.05452728, -0.10174932]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-2.46375421e-05, 1.60137424e-05, 1.40894652e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71636073e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 1.23645172e-09, 4.38699743e-09, -2.01797484e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31335449]), + 'frame': 25156, + 'frame_number': 25156, + 'framesequence': 101320, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.1007660515606, + 'timestamp_carla': 856099, + 'timestamp_device': 1726700, + 'timestamp_stream': 856.1007660515606, + 'transform': [array([-35.09139633, 68.05452728, -0.10176294]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 5.05942444e-05, -1.52847369e-05, 2.46958926e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71667738e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([-1.07393605e-08, -3.69257940e-08, 1.28545755e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31517029]), + 'frame': 25157, + 'frame_number': 25157, + 'framesequence': 101324, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.1371943503618, + 'timestamp_carla': 856136, + 'timestamp_device': 1726734, + 'timestamp_stream': 856.1371943503618, + 'transform': [array([-35.09139633, 68.05452728, -0.10177637]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-2.09102309e-05, 1.33059948e-05, -1.21224497e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71541861e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 2.65100777e-08, 3.53817207e-08, -1.86481469e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31380463]), + 'frame': 25158, + 'frame_number': 25158, + 'framesequence': 101328, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.1682039499283, + 'timestamp_carla': 856167, + 'timestamp_device': 1726767, + 'timestamp_stream': 856.1682039499283, + 'transform': [array([-35.09139633, 68.05452728, -0.10174402]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-2.22924828e-05, 1.33536969e-05, -6.17601470e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-4.46354256e+01, 7.73255463e+01, 5.71485423e-02]), + 'Rotation': array([8.48992448e-03, 1.42177124e+02, 4.70454944e-03]), + 'Velocity': array([ 6.22336982e-09, 1.15870700e-08, -3.83682229e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31246185]), + 'frame': 25159, + 'frame_number': 25159, + 'framesequence': 101332, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.2006832510233, + 'timestamp_carla': 856199, + 'timestamp_device': 1726800, + 'timestamp_stream': 856.2006832510233, + 'transform': [array([-35.09139633, 68.05452728, -0.10173479]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.01713118, 0.02381132, 0.65910363]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038435349706560373, + 'FR_Wheel_Angle': 0.003843676997348666, + 'Location': array([-4.46353226e+01, 7.73254166e+01, 5.71770370e-02]), + 'Rotation': array([8.39430187e-03, 1.42173187e+02, 4.65753861e-03]), + 'Velocity': array([-9.95661039e-03, 7.20957574e-03, -5.37872293e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31569672]), + 'frame': 25160, + 'frame_number': 25160, + 'framesequence': 101336, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.233644451946, + 'timestamp_carla': 856232, + 'timestamp_device': 1726834, + 'timestamp_stream': 856.233644451946, + 'transform': [array([-35.09139633, 68.05452728, -0.10173479]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.02004263, 0.02713851, 0.64853126]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003843839978799224, + 'FR_Wheel_Angle': 0.003844088176265359, + 'Location': array([-4.46345444e+01, 7.73247299e+01, 5.71641065e-02]), + 'Rotation': array([8.60603806e-03, 1.42172180e+02, 4.64431383e-03]), + 'Velocity': array([-0.01237425, 0.00883584, 0.00030344]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31661987]), + 'frame': 25161, + 'frame_number': 25161, + 'framesequence': 101340, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.2672446519136, + 'timestamp_carla': 856266, + 'timestamp_device': 1726867, + 'timestamp_stream': 856.2672446519136, + 'transform': [array([-35.09139633, 68.05452728, -0.10174013]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.03601921, 0.04164718, 0.95912886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003843661630526185, + 'FR_Wheel_Angle': 0.003839625511318445, + 'Location': array([-4.46361847e+01, 7.73257980e+01, 5.71320243e-02]), + 'Rotation': array([1.01564908e-02, 1.42172455e+02, 4.57350863e-03]), + 'Velocity': array([-0.04452866, 0.03328687, -0.00047213]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31661987]), + 'frame': 25162, + 'frame_number': 25162, + 'framesequence': 101345, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.3026081509888, + 'timestamp_carla': 856301, + 'timestamp_device': 1726909, + 'timestamp_stream': 856.3026081509888, + 'transform': [array([-35.09139633, 68.05452728, -0.10175825]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.00427289, -0.00295906, -0.16125479]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003827050095424056, + 'FR_Wheel_Angle': 0.003824874060228467, + 'Location': array([-4.46597595e+01, 7.73438873e+01, 5.70780449e-02]), + 'Rotation': array([1.86190940e-02, 1.42158478e+02, 4.80557745e-03]), + 'Velocity': array([-2.01011926e-01, 1.55713484e-01, 1.89485552e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31608582]), + 'frame': 25163, + 'frame_number': 25163, + 'framesequence': 101349, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.3458429500461, + 'timestamp_carla': 856345, + 'timestamp_device': 1726942, + 'timestamp_stream': 856.3458429500461, + 'transform': [array([-35.09139633, 68.05452728, -0.1017626 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.03634108, 0.04441216, 0.0757617 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003816615091636777, + 'FR_Wheel_Angle': 0.0038108734879642725, + 'Location': array([-4.47082367e+01, 7.73814087e+01, 5.70969284e-02]), + 'Rotation': array([2.13989820e-02, 1.42156372e+02, 4.76954225e-03]), + 'Velocity': array([-3.82071108e-01, 2.96623439e-01, -1.38473506e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31427765]), + 'frame': 25164, + 'frame_number': 25164, + 'framesequence': 101353, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.3783395513892, + 'timestamp_carla': 856377, + 'timestamp_device': 1726975, + 'timestamp_stream': 856.3783395513892, + 'transform': [array([-35.09139633, 68.05452728, -0.10174891]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.00151689, 0.0059796 , -0.9902299 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038016217295080423, + 'FR_Wheel_Angle': 0.0037997993640601635, + 'Location': array([-4.47801933e+01, 7.74370804e+01, 5.70891462e-02]), + 'Rotation': array([2.18634345e-02, 1.42131607e+02, 4.79676668e-03]), + 'Velocity': array([-5.01584053e-01, 3.89237076e-01, -6.85405685e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31384277]), + 'frame': 25165, + 'frame_number': 25165, + 'framesequence': 101357, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.4094484522939, + 'timestamp_carla': 856408, + 'timestamp_device': 1727009, + 'timestamp_stream': 856.4094484522939, + 'transform': [array([-35.09139633, 68.05452728, -0.10173231]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02265861, -0.02212758, 0.45464534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003790654242038727, + 'FR_Wheel_Angle': 0.0037867368664592505, + 'Location': array([-4.48743248e+01, 7.75101776e+01, 5.70763275e-02]), + 'Rotation': array([2.06340011e-02, 1.42125870e+02, 4.66837641e-03]), + 'Velocity': array([-6.07169747e-01, 4.70699191e-01, -3.91550042e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31520844]), + 'frame': 25166, + 'frame_number': 25166, + 'framesequence': 101361, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.442456651479, + 'timestamp_carla': 856441, + 'timestamp_device': 1727042, + 'timestamp_stream': 856.442456651479, + 'transform': [array([-35.09139633, 68.05452728, -0.10173628]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02369411, -0.03045038, 0.00393358]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.4339548349380493, + 'FR_Wheel_Angle': -1.5794730186462402, + 'Location': array([-4.49902954e+01, 7.76002045e+01, 5.70881180e-02]), + 'Rotation': array([2.18702648e-02, 1.42128387e+02, 4.69839200e-03]), + 'Velocity': array([-7.54562497e-01, 5.85813165e-01, 2.08950034e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31687164]), + 'frame': 25167, + 'frame_number': 25167, + 'framesequence': 101365, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.4720466509461, + 'timestamp_carla': 856471, + 'timestamp_device': 1727075, + 'timestamp_stream': 856.4720466509461, + 'transform': [array([-35.09139633, 68.05452728, -0.10178675]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.00901864, -0.08206695, -3.02375913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.698518753051758, + 'FR_Wheel_Angle': -9.684711456298828, + 'Location': array([-4.51551666e+01, 7.77361679e+01, 5.70410825e-02]), + 'Rotation': array([1.95821505e-02, 1.41857391e+02, 1.65042505e-02]), + 'Velocity': array([-8.17311227e-01, 7.49026120e-01, 5.19027701e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31647491]), + 'frame': 25168, + 'frame_number': 25168, + 'framesequence': 101368, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.5045777522027, + 'timestamp_carla': 856503, + 'timestamp_device': 1727100, + 'timestamp_stream': 856.5045777522027, + 'transform': [array([-35.09139633, 68.05452728, -0.10176424]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01328871, -0.05746371, -7.04219723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.530702590942383, + 'FR_Wheel_Angle': -17.057504653930664, + 'Location': array([-4.52985153e+01, 7.78755188e+01, 5.71234785e-02]), + 'Rotation': array([1.81819629e-02, 1.40978287e+02, 2.86012962e-02]), + 'Velocity': array([-8.28702271e-01, 9.31303442e-01, 6.70242298e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31142426]), + 'frame': 25169, + 'frame_number': 25169, + 'framesequence': 101372, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.5382053516805, + 'timestamp_carla': 856537, + 'timestamp_device': 1727134, + 'timestamp_stream': 856.5382053516805, + 'transform': [array([-35.09139633, 68.05452728, -0.10175848]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.03998478, -0.0376447 , -11.49894428]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.058012008666992, + 'FR_Wheel_Angle': -24.89512062072754, + 'Location': array([-4.54417191e+01, 7.80424423e+01, 5.71358390e-02]), + 'Rotation': array([1.55728301e-02, 1.39360855e+02, 3.79456915e-02]), + 'Velocity': array([-7.75399506e-01, 1.10080719e+00, 3.88336164e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31367493]), + 'frame': 25170, + 'frame_number': 25170, + 'framesequence': 101376, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.5703367516398, + 'timestamp_carla': 856569, + 'timestamp_device': 1727167, + 'timestamp_stream': 856.5703367516398, + 'transform': [array([-35.09139633, 68.05452728, -0.1017447 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-7.12998360e-02, -1.70471705e-02, -1.73065529e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.726558685302734, + 'FR_Wheel_Angle': -30.35403823852539, + 'Location': array([-4.55977783e+01, 7.82744293e+01, 5.71401864e-02]), + 'Rotation': array([1.21304151e-02, 1.36386475e+02, 4.75307554e-02]), + 'Velocity': array([-6.36024356e-01, 1.29143655e+00, -2.53229140e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31425476]), + 'frame': 25171, + 'frame_number': 25171, + 'framesequence': 101381, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.6059002503753, + 'timestamp_carla': 856605, + 'timestamp_device': 1727209, + 'timestamp_stream': 856.6059002503753, + 'transform': [array([-35.09139633, 68.05452728, -0.10176347]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.1182848 , 0.06647524, -18.70059586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.820125579833984, + 'FR_Wheel_Angle': -30.068208694458008, + 'Location': array([-4.57139091e+01, 7.84937592e+01, 5.71320243e-02]), + 'Rotation': array([1.20279621e-02, 1.33254852e+02, 4.02212217e-02]), + 'Velocity': array([-5.89755833e-01, 1.41646826e+00, -1.27258303e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31562805]), + 'frame': 25172, + 'frame_number': 25172, + 'framesequence': 101384, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.6379192508757, + 'timestamp_carla': 856637, + 'timestamp_device': 1727234, + 'timestamp_stream': 856.6379192508757, + 'transform': [array([-35.09139633, 68.05452728, -0.10174715]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.09453829, 0.0405468 , -20.14702415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.8317985534668, + 'FR_Wheel_Angle': -30.284626007080078, + 'Location': array([-4.58216591e+01, 7.87304001e+01, 5.71366400e-02]), + 'Rotation': array([1.15361884e-02, 1.29939102e+02, 3.68623137e-02]), + 'Velocity': array([-5.18735588e-01, 1.52609813e+00, -9.32311959e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31375122]), + 'frame': 25173, + 'frame_number': 25173, + 'framesequence': 101388, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.6709495522082, + 'timestamp_carla': 856670, + 'timestamp_device': 1727267, + 'timestamp_stream': 856.6709495522082, + 'transform': [array([-35.09139633, 68.05452728, -0.1017449 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.1222651 , 0.05588828, -20.86083603]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.790035247802734, + 'FR_Wheel_Angle': -30.263179779052734, + 'Location': array([-4.59189873e+01, 7.89833984e+01, 5.71515150e-02]), + 'Rotation': array([1.06414342e-02, 1.26475250e+02, 3.40868719e-02]), + 'Velocity': array([-4.42127913e-01, 1.61053085e+00, -3.80525569e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31538391]), + 'frame': 25174, + 'frame_number': 25174, + 'framesequence': 101393, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.7056427523494, + 'timestamp_carla': 856704, + 'timestamp_device': 1727309, + 'timestamp_stream': 856.7056427523494, + 'transform': [array([-35.09139633, 68.05452728, -0.10175688]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.19659221, 0.09617496, -20.8705349 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.80227279663086, + 'FR_Wheel_Angle': -30.278512954711914, + 'Location': array([-4.60024910e+01, 7.92477646e+01, 5.70048802e-02]), + 'Rotation': array([-6.42037718e-04, 1.22910912e+02, 1.35883344e-02]), + 'Velocity': array([-3.37206274e-01, 1.62857342e+00, -1.06937881e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31561279]), + 'frame': 25175, + 'frame_number': 25175, + 'framesequence': 101396, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.736284751445, + 'timestamp_carla': 856735, + 'timestamp_device': 1727334, + 'timestamp_stream': 856.736284751445, + 'transform': [array([-35.09139633, 68.05452728, -0.10173555]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.21223594, 0.17844039, -18.92865753]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.34947967529297, + 'FR_Wheel_Angle': -27.80059051513672, + 'Location': array([-4.60806923e+01, 7.95679398e+01, 5.67235835e-02]), + 'Rotation': array([-1.58118866e-02, 1.18672089e+02, -1.78527832e-02]), + 'Velocity': array([-2.30172262e-01, 1.55085802e+00, -1.37881271e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31441498]), + 'frame': 25176, + 'frame_number': 25176, + 'framesequence': 101400, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.7696972489357, + 'timestamp_carla': 856768, + 'timestamp_device': 1727367, + 'timestamp_stream': 856.7696972489357, + 'transform': [array([-35.09139633, 68.05452728, -0.10174223]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.13174435, -0.08394881, -16.95018387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.32143783569336, + 'FR_Wheel_Angle': -28.386110305786133, + 'Location': array([-4.61335106e+01, 7.98157043e+01, 5.65127060e-02]), + 'Rotation': array([-2.77032461e-02, 1.15760910e+02, -3.28369178e-02]), + 'Velocity': array([-0.18209426, 1.4870851 , -0.00283122]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31654358]), + 'frame': 25177, + 'frame_number': 25177, + 'framesequence': 101404, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.802968852222, + 'timestamp_carla': 856802, + 'timestamp_device': 1727400, + 'timestamp_stream': 856.802968852222, + 'transform': [array([-35.09139633, 68.05452728, -0.10174558]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.46919042e-01, -5.10139065e-03, -1.63376255e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.447879791259766, + 'FR_Wheel_Angle': -27.70878791809082, + 'Location': array([-4.61754951e+01, 8.00948105e+01, 5.59936799e-02]), + 'Rotation': array([-4.83030938e-02, 1.12427582e+02, -2.29492150e-02]), + 'Velocity': array([-0.08617754, 1.42574596, -0.00312669]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31587982]), + 'frame': 25178, + 'frame_number': 25178, + 'framesequence': 101408, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.8358712494373, + 'timestamp_carla': 856834, + 'timestamp_device': 1727434, + 'timestamp_stream': 856.8358712494373, + 'transform': [array([-35.09139633, 68.05452728, -0.10174558]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.37431115e-01, -8.04715604e-03, -1.59674463e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.83833312988281, + 'FR_Wheel_Angle': -27.864885330200195, + 'Location': array([-4.61983490e+01, 8.03258591e+01, 5.55930585e-02]), + 'Rotation': array([-6.39032498e-02, 1.09705330e+02, -1.72424316e-02]), + 'Velocity': array([-0.0123838 , 1.37864363, -0.00277513]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31554413]), + 'frame': 25179, + 'frame_number': 25179, + 'framesequence': 101412, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.8686033524573, + 'timestamp_carla': 856867, + 'timestamp_device': 1727467, + 'timestamp_stream': 856.8686033524573, + 'transform': [array([-35.09139633, 68.05452728, -0.10174444]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.16130713, 0.03131939, -14.85194016]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.934532165527344, + 'FR_Wheel_Angle': -27.954164505004883, + 'Location': array([-4.62108307e+01, 8.05990982e+01, 5.51128648e-02]), + 'Rotation': array([-8.24198872e-02, 1.06494934e+02, -1.32751465e-02]), + 'Velocity': array([ 0.06144793, 1.29495478, -0.00314569]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31554413]), + 'frame': 25180, + 'frame_number': 25180, + 'framesequence': 101416, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.9015743508935, + 'timestamp_carla': 856900, + 'timestamp_device': 1727500, + 'timestamp_stream': 856.9015743508935, + 'transform': [array([-35.09139633, 68.05452728, -0.10174581]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.12822993, 0.0208228 , -14.04114342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.03996658325195, + 'FR_Wheel_Angle': -28.011531829833984, + 'Location': array([-4.62095604e+01, 8.08156738e+01, 5.48148230e-02]), + 'Rotation': array([-9.73506793e-02, 1.03954056e+02, -1.08642615e-02]), + 'Velocity': array([ 0.11361735, 1.21690094, -0.00202871]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31565857]), + 'frame': 25181, + 'frame_number': 25181, + 'framesequence': 101420, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.9352580495179, + 'timestamp_carla': 856934, + 'timestamp_device': 1727534, + 'timestamp_stream': 856.9352580495179, + 'transform': [array([-35.09139633, 68.05452728, -0.10175218]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.12447694, 0.03512086, -12.91664314]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.04833221435547, + 'FR_Wheel_Angle': -28.021516799926758, + 'Location': array([-4.61979523e+01, 8.10377274e+01, 5.44603989e-02]), + 'Rotation': array([-1.12062909e-01, 1.01369682e+02, -8.57543573e-03]), + 'Velocity': array([ 0.15641125, 1.11469817, -0.00195496]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31552124]), + 'frame': 25182, + 'frame_number': 25182, + 'framesequence': 101424, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.9676920510828, + 'timestamp_carla': 856966, + 'timestamp_device': 1727567, + 'timestamp_stream': 856.9676920510828, + 'transform': [array([-35.09139633, 68.05452728, -0.10174677]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.11726945, 0.0416284 , -12.20300484]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.093746185302734, + 'FR_Wheel_Angle': -28.049339294433594, + 'Location': array([-4.61809006e+01, 8.12187500e+01, 5.41833006e-02]), + 'Rotation': array([-1.23134643e-01, 9.92401581e+01, -5.88987768e-03]), + 'Velocity': array([ 0.18642743, 1.03964317, -0.00191575]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31488037]), + 'frame': 25183, + 'frame_number': 25183, + 'framesequence': 101428, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 856.9993670508265, + 'timestamp_carla': 856998, + 'timestamp_device': 1727600, + 'timestamp_stream': 856.9993670508265, + 'transform': [array([-35.09139633, 68.05452728, -0.10173868]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ -0.12218849, 0.0575026 , -10.73781013]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.981285095214844, + 'FR_Wheel_Angle': -27.36992645263672, + 'Location': array([-4.61586647e+01, 8.13865814e+01, 5.39200865e-02]), + 'Rotation': array([-1.34220034e-01, 9.72948532e+01, -4.27246140e-03]), + 'Velocity': array([ 0.20335166, 0.94021559, -0.00182817]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31542206]), + 'frame': 25184, + 'frame_number': 25184, + 'framesequence': 101432, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.0314740501344, + 'timestamp_carla': 857030, + 'timestamp_device': 1727634, + 'timestamp_stream': 857.0314740501344, + 'transform': [array([-35.09139633, 68.05452728, -0.10173731]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 5.12870494e-03, -7.06172213e-02, -8.89277172e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.35033416748047, + 'FR_Wheel_Angle': -24.887540817260742, + 'Location': array([-4.61316185e+01, 8.15689240e+01, 5.36227673e-02]), + 'Rotation': array([-1.44076005e-01, 9.53524857e+01, -7.50732142e-03]), + 'Velocity': array([ 0.17926587, 0.91527754, -0.00103696]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31623077]), + 'frame': 25185, + 'frame_number': 25185, + 'framesequence': 101436, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.0659046508372, + 'timestamp_carla': 857064, + 'timestamp_device': 1727667, + 'timestamp_stream': 857.0659046508372, + 'transform': [array([-35.09139633, 68.05452728, -0.10175451]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.01150563, -0.09425011, -8.739604 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.74703598022461, + 'FR_Wheel_Angle': -25.709346771240234, + 'Location': array([-4.61086502e+01, 8.17077103e+01, 5.34374900e-02]), + 'Rotation': array([-1.53201133e-01, 9.39233322e+01, -6.10356918e-04]), + 'Velocity': array([ 0.20121194, 0.82668102, -0.00156627]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3163681 ]), + 'frame': 25186, + 'frame_number': 25186, + 'framesequence': 101440, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.0987820513546, + 'timestamp_carla': 857097, + 'timestamp_device': 1727700, + 'timestamp_stream': 857.0987820513546, + 'transform': [array([-35.09139633, 68.05452728, -0.1017523 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.01810826, -0.09696967, -7.9697051 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.35851287841797, + 'FR_Wheel_Angle': -25.747629165649414, + 'Location': array([-4.60844307e+01, 8.18341141e+01, 5.32419086e-02]), + 'Rotation': array([-1.60434306e-01, 9.26137848e+01, 9.62546794e-04]), + 'Velocity': array([ 0.19772132, 0.75445205, -0.00154847]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31465149]), + 'frame': 25187, + 'frame_number': 25187, + 'framesequence': 101444, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.1318479515612, + 'timestamp_carla': 857130, + 'timestamp_device': 1727734, + 'timestamp_stream': 857.1318479515612, + 'transform': [array([-35.09139633, 68.05452728, -0.1017523 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.021046 , -0.08932238, -7.04115629]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.20269012451172, + 'FR_Wheel_Angle': -25.671022415161133, + 'Location': array([-4.60551682e+01, 8.19679794e+01, 5.30495346e-02]), + 'Rotation': array([-1.68152422e-01, 9.12085571e+01, 3.53896664e-03]), + 'Velocity': array([ 0.19492473, 0.67170453, -0.00153556]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31487274]), + 'frame': 25188, + 'frame_number': 25188, + 'framesequence': 101448, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.1645571514964, + 'timestamp_carla': 857163, + 'timestamp_device': 1727767, + 'timestamp_stream': 857.1645571514964, + 'transform': [array([-35.09139633, 68.05452728, -0.10174967]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03192228, -0.08580184, -6.55329227]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.226654052734375, + 'FR_Wheel_Angle': -25.665748596191406, + 'Location': array([-4.60306892e+01, 8.20682831e+01, 5.29072471e-02]), + 'Rotation': array([-1.74005896e-01, 9.01501694e+01, 5.86945377e-03]), + 'Velocity': array([ 0.19304156, 0.57643044, -0.0009326 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31487274]), + 'frame': 25189, + 'frame_number': 25189, + 'framesequence': 101452, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.1979714520276, + 'timestamp_carla': 857197, + 'timestamp_device': 1727800, + 'timestamp_stream': 857.1979714520276, + 'transform': [array([-35.09139633, 68.05452728, -0.10175329]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01967984, -0.11722642, -6.05553961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.260597229003906, + 'FR_Wheel_Angle': -25.686532974243164, + 'Location': array([-4.60066528e+01, 8.21589661e+01, 5.27823530e-02]), + 'Rotation': array([-1.79292455e-01, 8.91725311e+01, 9.22958460e-03]), + 'Velocity': array([ 0.18449546, 0.51828331, -0.00080805]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31513214]), + 'frame': 25190, + 'frame_number': 25190, + 'framesequence': 101456, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.2331813499331, + 'timestamp_carla': 857232, + 'timestamp_device': 1727834, + 'timestamp_stream': 857.2331813499331, + 'transform': [array([-35.09139633, 68.05452728, -0.10176946]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02179381, -0.03747252, -5.30002022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.28015899658203, + 'FR_Wheel_Angle': -25.697599411010742, + 'Location': array([-4.59832077e+01, 8.22419815e+01, 5.25119305e-02]), + 'Rotation': array([-1.78855330e-01, 8.82757950e+01, 1.22510511e-02]), + 'Velocity': array([ 0.1671412 , 0.45250824, -0.00158934]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31477356]), + 'frame': 25191, + 'frame_number': 25191, + 'framesequence': 101460, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.2644938491285, + 'timestamp_carla': 857263, + 'timestamp_device': 1727867, + 'timestamp_stream': 857.2644938491285, + 'transform': [array([-35.09139633, 68.05452728, -0.10174967]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03060369, 0.01406036, -5.0727067 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.30350112915039, + 'FR_Wheel_Angle': -25.712751388549805, + 'Location': array([-4.59562454e+01, 8.23317642e+01, 5.22053801e-02]), + 'Rotation': array([-1.77427813e-01, 8.73085175e+01, 1.56588424e-02]), + 'Velocity': array([ 0.15570511, 0.40634224, -0.00149111]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31315613]), + 'frame': 25192, + 'frame_number': 25192, + 'framesequence': 101464, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.2975177504122, + 'timestamp_carla': 857296, + 'timestamp_device': 1727900, + 'timestamp_stream': 857.2975177504122, + 'transform': [array([-35.09139633, 68.05452728, -0.10174967]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02548754, 0.02515022, -4.43202829]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.886852264404297, + 'FR_Wheel_Angle': -23.895376205444336, + 'Location': array([-4.59349632e+01, 8.23988647e+01, 5.20029739e-02]), + 'Rotation': array([-1.77031666e-01, 8.65997620e+01, 1.72188152e-02]), + 'Velocity': array([ 0.14188772, 0.36776093, -0.00067237]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31513214]), + 'frame': 25193, + 'frame_number': 25193, + 'framesequence': 101468, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.3320586495101, + 'timestamp_carla': 857331, + 'timestamp_device': 1727934, + 'timestamp_stream': 857.3320586495101, + 'transform': [array([-35.09139633, 68.05452728, -0.1017613 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.04155857, -0.02020766, -3.49480057]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.965938568115234, + 'FR_Wheel_Angle': -23.557308197021484, + 'Location': array([-4.59174080e+01, 8.24583664e+01, 5.17372042e-02]), + 'Rotation': array([-1.76819921e-01, 8.60594406e+01, 1.67667475e-02]), + 'Velocity': array([ 0.11697848, 0.32315344, -0.00110138]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31513214]), + 'frame': 25194, + 'frame_number': 25194, + 'framesequence': 101472, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.3646786510944, + 'timestamp_carla': 857363, + 'timestamp_device': 1727967, + 'timestamp_stream': 857.3646786510944, + 'transform': [array([-35.09139633, 68.05452728, -0.10175321]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05940557, 0.07748187, -2.20639491]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.866491317749023, + 'FR_Wheel_Angle': -22.84133529663086, + 'Location': array([-4.58978958e+01, 8.25221405e+01, 5.16241342e-02]), + 'Rotation': array([-1.77673697e-01, 8.54614792e+01, 1.90777555e-02]), + 'Velocity': array([ 0.08729888, 0.2396128 , -0.00041533]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31397247]), + 'frame': 25195, + 'frame_number': 25195, + 'framesequence': 101476, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.3996841497719, + 'timestamp_carla': 857398, + 'timestamp_device': 1728000, + 'timestamp_stream': 857.3996841497719, + 'transform': [array([-35.09139633, 68.05452728, -0.10176668]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05331019, 0.07054098, -1.76509607]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.411434173583984, + 'FR_Wheel_Angle': -23.17720603942871, + 'Location': array([-4.58852959e+01, 8.25627594e+01, 5.15062213e-02]), + 'Rotation': array([-1.77543923e-01, 8.50787735e+01, 2.07319167e-02]), + 'Velocity': array([ 0.07197432, 0.19055636, -0.00044287]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31478119]), + 'frame': 25196, + 'frame_number': 25196, + 'framesequence': 101480, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.4343920499086, + 'timestamp_carla': 857433, + 'timestamp_device': 1728033, + 'timestamp_stream': 857.4343920499086, + 'transform': [array([-35.09139633, 68.05452728, -0.10177118]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.06631383, 0.09522194, -1.04313648]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.31212043762207, + 'FR_Wheel_Angle': -23.194852828979492, + 'Location': array([-4.58748436e+01, 8.25958710e+01, 5.13203330e-02]), + 'Rotation': array([-1.77769318e-01, 8.47687531e+01, 2.12005414e-02]), + 'Velocity': array([4.73150946e-02, 1.24579340e-01, 1.23567574e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31343079]), + 'frame': 25197, + 'frame_number': 25197, + 'framesequence': 101484, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.470269151032, + 'timestamp_carla': 857469, + 'timestamp_device': 1728067, + 'timestamp_stream': 857.470269151032, + 'transform': [array([-35.09139633, 68.05452728, -0.10178259]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.04863707, 0.07087216, -0.62634194]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.312015533447266, + 'FR_Wheel_Angle': -23.1761417388916, + 'Location': array([-4.58673286e+01, 8.26191101e+01, 5.12928665e-02]), + 'Rotation': array([-1.77455142e-01, 8.45535507e+01, 2.22513005e-02]), + 'Velocity': array([0.03288436, 0.08331726, 0.00137523]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31298065]), + 'frame': 25198, + 'frame_number': 25198, + 'framesequence': 101488, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.500192951411, + 'timestamp_carla': 857499, + 'timestamp_device': 1728100, + 'timestamp_stream': 857.500192951411, + 'transform': [array([-35.09139633, 68.05452728, -0.10181856]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05628911, 0.08683123, -0.27223825]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.329702377319336, + 'FR_Wheel_Angle': -23.1898136138916, + 'Location': array([-4.58618660e+01, 8.26357956e+01, 5.12652844e-02]), + 'Rotation': array([-1.76601365e-01, 8.43998947e+01, 2.31752805e-02]), + 'Velocity': array([ 0.0174319 , 0.04401792, -0.00012565]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31184387]), + 'frame': 25199, + 'frame_number': 25199, + 'framesequence': 101492, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.5347166508436, + 'timestamp_carla': 857533, + 'timestamp_device': 1728133, + 'timestamp_stream': 857.5347166508436, + 'transform': [array([-35.09139633, 68.05452728, -0.10179445]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05498593, 0.08672751, -0.04431213]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.34280776977539, + 'FR_Wheel_Angle': -23.197519302368164, + 'Location': array([-4.58581543e+01, 8.26469574e+01, 5.12122624e-02]), + 'Rotation': array([-1.75720274e-01, 8.42998505e+01, 2.41966378e-02]), + 'Velocity': array([ 0.00819368, 0.01936728, -0.00029662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3082428 ]), + 'frame': 25200, + 'frame_number': 25200, + 'framesequence': 101496, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.5675392523408, + 'timestamp_carla': 857566, + 'timestamp_device': 1728167, + 'timestamp_stream': 857.5675392523408, + 'transform': [array([-35.09139633, 68.05452728, -0.10176737]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.0520663 , 0.08195062, 0.05346042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.347999572753906, + 'FR_Wheel_Angle': -23.20391845703125, + 'Location': array([-4.58554077e+01, 8.26551285e+01, 5.11843748e-02]), + 'Rotation': array([-1.74832344e-01, 8.42263641e+01, 2.51689442e-02]), + 'Velocity': array([0.00370663, 0.00763164, 0.00015802]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31065369]), + 'frame': 25201, + 'frame_number': 25201, + 'framesequence': 101500, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.6018290519714, + 'timestamp_carla': 857600, + 'timestamp_device': 1728200, + 'timestamp_stream': 857.6018290519714, + 'transform': [array([-35.09139633, 68.05452728, -0.10176206]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05248854, 0.07240535, 0.0881056 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.622692108154297, + 'FR_Wheel_Angle': -19.69567108154297, + 'Location': array([-4.58527145e+01, 8.26632080e+01, 5.11587039e-02]), + 'Rotation': array([-1.73944414e-01, 8.41564560e+01, 2.59858202e-02]), + 'Velocity': array([0.00171725, 0.00288927, 0.00026775]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31336212]), + 'frame': 25202, + 'frame_number': 25202, + 'framesequence': 101504, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.6332453489304, + 'timestamp_carla': 857632, + 'timestamp_device': 1728233, + 'timestamp_stream': 857.6332453489304, + 'transform': [array([-35.09139633, 68.05452728, -0.10173932]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.0449204 , -0.00980695, -0.20790027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.544065475463867, + 'FR_Wheel_Angle': -21.018829345703125, + 'Location': array([-4.58497849e+01, 8.26731720e+01, 5.10881692e-02]), + 'Rotation': array([-1.70624942e-01, 8.40697556e+01, 2.90086698e-02]), + 'Velocity': array([ 0.03281762, 0.10639896, -0.00044718]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31389618]), + 'frame': 25203, + 'frame_number': 25203, + 'framesequence': 101508, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.6646010503173, + 'timestamp_carla': 857663, + 'timestamp_device': 1728267, + 'timestamp_stream': 857.6646010503173, + 'transform': [array([-35.09139633, 68.05452728, -0.10172632]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.00327434, 0.08874895, -1.16592586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.716585159301758, + 'FR_Wheel_Angle': -20.183626174926758, + 'Location': array([-4.58427010e+01, 8.26963730e+01, 5.10079078e-02]), + 'Rotation': array([-1.67694792e-01, 8.38641129e+01, 3.15841623e-02]), + 'Velocity': array([ 0.05223915, 0.17439021, -0.00018734]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31616974]), + 'frame': 25204, + 'frame_number': 25204, + 'framesequence': 101512, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.6989937499166, + 'timestamp_carla': 857698, + 'timestamp_device': 1728300, + 'timestamp_stream': 857.6989937499166, + 'transform': [array([-35.09139633, 68.05452728, -0.10174211]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.04237274, -0.08727627, -1.92470133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.15733528137207, + 'FR_Wheel_Angle': -20.35172462463379, + 'Location': array([-4.58311577e+01, 8.27342377e+01, 5.08872122e-02]), + 'Rotation': array([-1.66991279e-01, 8.35418777e+01, 3.35585214e-02]), + 'Velocity': array([ 0.10201973, 0.2797004 , -0.00071512]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31746674]), + 'frame': 25205, + 'frame_number': 25205, + 'framesequence': 101516, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.7325051501393, + 'timestamp_carla': 857731, + 'timestamp_device': 1728333, + 'timestamp_stream': 857.7325051501393, + 'transform': [array([-35.09139633, 68.05452728, -0.10174497]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.04299939, -0.07713099, -3.23754668]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.065048217773438, + 'FR_Wheel_Angle': -20.34078598022461, + 'Location': array([-4.58158379e+01, 8.27842255e+01, 5.07204346e-02]), + 'Rotation': array([-1.65918946e-01, 8.31276016e+01, 3.53182405e-02]), + 'Velocity': array([ 0.13211887, 0.36716437, -0.00105427]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31588745]), + 'frame': 25206, + 'frame_number': 25206, + 'framesequence': 101520, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.7647789493203, + 'timestamp_carla': 857763, + 'timestamp_device': 1728367, + 'timestamp_stream': 857.7647789493203, + 'transform': [array([-35.09139633, 68.05452728, -0.10173837]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-1.51870982e-03, -7.65900267e-03, -4.82641172e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.97745704650879, + 'FR_Wheel_Angle': -20.30829620361328, + 'Location': array([-4.57944412e+01, 8.28514023e+01, 5.04969694e-02]), + 'Rotation': array([-1.64641708e-01, 8.25755997e+01, 3.84052694e-02]), + 'Velocity': array([ 0.16487463, 0.44495094, -0.00135839]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31560516]), + 'frame': 25207, + 'frame_number': 25207, + 'framesequence': 101524, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.798326049, + 'timestamp_carla': 857797, + 'timestamp_device': 1728400, + 'timestamp_stream': 857.798326049, + 'transform': [array([-35.09139633, 68.05452728, -0.10174444]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.0385187 , -0.07122643, -4.77060413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.94704246520996, + 'FR_Wheel_Angle': -20.282087326049805, + 'Location': array([-4.57663460e+01, 8.29358978e+01, 5.02304360e-02]), + 'Rotation': array([-1.63446411e-01, 8.19055176e+01, 4.15544733e-02]), + 'Velocity': array([ 0.22383448, 0.58050936, -0.00174767]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31626129]), + 'frame': 25208, + 'frame_number': 25208, + 'framesequence': 101529, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.8459030501544, + 'timestamp_carla': 857845, + 'timestamp_device': 1728442, + 'timestamp_stream': 857.8459030501544, + 'transform': [array([-35.09139633, 68.05452728, -0.10179548]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.0369815 , 0.03509777, -5.1004529 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.88237762451172, + 'FR_Wheel_Angle': -20.24174690246582, + 'Location': array([-4.57332573e+01, 8.30319901e+01, 4.99396808e-02]), + 'Rotation': array([-1.64552912e-01, 8.11226044e+01, 4.32683490e-02]), + 'Velocity': array([ 0.24261224, 0.60505742, -0.00142631]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31565857]), + 'frame': 25209, + 'frame_number': 25209, + 'framesequence': 101533, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.8725664503872, + 'timestamp_carla': 857871, + 'timestamp_device': 1728475, + 'timestamp_stream': 857.8725664503872, + 'transform': [array([-35.09139633, 68.05452728, -0.10179201]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.04576045, 0.04488507, -5.76636791]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.83938980102539, + 'FR_Wheel_Angle': -20.214130401611328, + 'Location': array([-4.56927032e+01, 8.31450043e+01, 4.95763309e-02]), + 'Rotation': array([-1.64033815e-01, 8.01829758e+01, 4.69186381e-02]), + 'Velocity': array([ 0.28738242, 0.68535864, -0.00232156]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3105545 ]), + 'frame': 25210, + 'frame_number': 25210, + 'framesequence': 101536, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.899445451796, + 'timestamp_carla': 857898, + 'timestamp_device': 1728500, + 'timestamp_stream': 857.899445451796, + 'transform': [array([-35.09139633, 68.05452728, -0.10179075]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02869342, 0.05765704, -6.01371717]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.821842193603516, + 'FR_Wheel_Angle': -17.706926345825195, + 'Location': array([-4.56445885e+01, 8.32732315e+01, 4.91704084e-02]), + 'Rotation': array([-1.63268834e-01, 7.91302948e+01, 4.96198013e-02]), + 'Velocity': array([ 0.33065009, 0.78069913, -0.00201086]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31089783]), + 'frame': 25211, + 'frame_number': 25211, + 'framesequence': 101539, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.9287468492985, + 'timestamp_carla': 857927, + 'timestamp_device': 1728525, + 'timestamp_stream': 857.9287468492985, + 'transform': [array([-35.09139633, 68.05452728, -0.10181345]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.03153602, -0.10920359, -6.26985502]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.017717361450195, + 'FR_Wheel_Angle': -17.46303367614746, + 'Location': array([-4.55941200e+01, 8.34133072e+01, 4.87145893e-02]), + 'Rotation': array([-1.61561280e-01, 7.81816406e+01, 5.00800610e-02]), + 'Velocity': array([ 0.37956625, 0.93135452, -0.00281368]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31102753]), + 'frame': 25212, + 'frame_number': 25212, + 'framesequence': 101544, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.9644757509232, + 'timestamp_carla': 857963, + 'timestamp_device': 1728567, + 'timestamp_stream': 857.9644757509232, + 'transform': [array([-35.09139633, 68.05452728, -0.101798 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.04031724, -0.07284876, -7.11038828]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.58234214782715, + 'FR_Wheel_Angle': -17.015729904174805, + 'Location': array([-4.55318298e+01, 8.35741425e+01, 4.81973179e-02]), + 'Rotation': array([-1.61588609e-01, 7.70481110e+01, 5.74294552e-02]), + 'Velocity': array([ 0.44006363, 1.00113416, -0.00380378]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.30875397]), + 'frame': 25213, + 'frame_number': 25213, + 'framesequence': 101548, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 857.997839551419, + 'timestamp_carla': 857997, + 'timestamp_device': 1728600, + 'timestamp_stream': 857.997839551419, + 'transform': [array([-35.09139633, 68.05452728, -0.10177023]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02943492, -0.08711473, -7.67721748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.73936653137207, + 'FR_Wheel_Angle': -17.324710845947266, + 'Location': array([-4.54643250e+01, 8.37403870e+01, 4.77189533e-02]), + 'Rotation': array([-1.61561280e-01, 7.58856125e+01, 6.16024919e-02]), + 'Velocity': array([ 0.49066511, 1.05673766, -0.00284136]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31030273]), + 'frame': 25214, + 'frame_number': 25214, + 'framesequence': 101552, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.0327191501856, + 'timestamp_carla': 858031, + 'timestamp_device': 1728633, + 'timestamp_stream': 858.0327191501856, + 'transform': [array([-35.09139633, 68.05452728, -0.10176546]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.03062121, -0.0825294 , -8.05485249]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.586219787597656, + 'FR_Wheel_Angle': -17.242597579956055, + 'Location': array([-4.53876305e+01, 8.39182205e+01, 4.71489243e-02]), + 'Rotation': array([-1.61738873e-01, 7.46061020e+01, 6.55806214e-02]), + 'Velocity': array([ 0.53534049, 1.09296596, -0.00340889]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31307983]), + 'frame': 25215, + 'frame_number': 25215, + 'framesequence': 101556, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.0651546493173, + 'timestamp_carla': 858064, + 'timestamp_device': 1728667, + 'timestamp_stream': 858.0651546493173, + 'transform': [array([-35.09139633, 68.05452728, -0.1017452 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.03015906, -0.0828966 , -8.26055622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.53113555908203, + 'FR_Wheel_Angle': -17.224872589111328, + 'Location': array([-4.52861557e+01, 8.41383286e+01, 4.64548767e-02]), + 'Rotation': array([-1.61438346e-01, 7.30014954e+01, 7.07034096e-02]), + 'Velocity': array([ 0.5891301 , 1.122136 , -0.00323096]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31355286]), + 'frame': 25216, + 'frame_number': 25216, + 'framesequence': 101560, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.0978066511452, + 'timestamp_carla': 858096, + 'timestamp_device': 1728700, + 'timestamp_stream': 858.0978066511452, + 'transform': [array([-35.09139633, 68.05452728, -0.1017357 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.03159233, -0.08591532, -8.54035664]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.517112731933594, + 'FR_Wheel_Angle': -17.21588134765625, + 'Location': array([-4.51940651e+01, 8.43251038e+01, 4.58720662e-02]), + 'Rotation': array([-0.16058457, 71.63205719, 0.07504994]), + 'Velocity': array([ 0.63452619, 1.1422025 , -0.00367386]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31558228]), + 'frame': 25217, + 'frame_number': 25217, + 'framesequence': 101564, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.1328697502613, + 'timestamp_carla': 858131, + 'timestamp_device': 1728733, + 'timestamp_stream': 858.1328697502613, + 'transform': [array([-35.09139633, 68.05452728, -0.10174997]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.03008497, -0.08547939, -8.70794296]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.501192092895508, + 'FR_Wheel_Angle': -17.204086303710938, + 'Location': array([-4.50949631e+01, 8.45144501e+01, 4.52877693e-02]), + 'Rotation': array([-0.15929367, 70.23098755, 0.07956723]), + 'Velocity': array([ 0.68088943, 1.15818977, -0.00335713]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31652832]), + 'frame': 25218, + 'frame_number': 25218, + 'framesequence': 101568, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.1679697521031, + 'timestamp_carla': 858167, + 'timestamp_device': 1728767, + 'timestamp_stream': 858.1679697521031, + 'transform': [array([-35.09139633, 68.05452728, -0.10175897]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.0294995 , -0.08920239, -8.99938297]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.488832473754883, + 'FR_Wheel_Angle': -17.1947021484375, + 'Location': array([-4.49642067e+01, 8.47484055e+01, 4.45397831e-02]), + 'Rotation': array([-0.1575588 , 68.47969055, 0.08504216]), + 'Velocity': array([ 0.73685086, 1.17085302, -0.00400531]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31510162]), + 'frame': 25219, + 'frame_number': 25219, + 'framesequence': 101572, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.1986737512052, + 'timestamp_carla': 858197, + 'timestamp_device': 1728800, + 'timestamp_stream': 858.1986737512052, + 'transform': [array([-35.09139633, 68.05452728, -0.1017336 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.0622859 , -0.01260623, -7.71070099]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.84885597229004, + 'FR_Wheel_Angle': -13.39842414855957, + 'Location': array([-4.48500900e+01, 8.49425049e+01, 4.39458750e-02]), + 'Rotation': array([-0.15551656, 67.08007812, 0.08470137]), + 'Velocity': array([ 0.75297326, 1.20375323, -0.00353101]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31420135]), + 'frame': 25220, + 'frame_number': 25220, + 'framesequence': 101576, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.2325141504407, + 'timestamp_carla': 858231, + 'timestamp_device': 1728833, + 'timestamp_stream': 858.2325141504407, + 'transform': [array([-35.09139633, 68.05452728, -0.10174097]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-2.64316960e-03, -1.35731488e-01, -7.59453487e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.256906509399414, + 'FR_Wheel_Angle': -14.74831771850586, + 'Location': array([-4.47324905e+01, 8.51455154e+01, 4.33038995e-02]), + 'Rotation': array([-0.15414371, 65.91506958, 0.08746614]), + 'Velocity': array([ 0.78168857, 1.21739352, -0.0037478 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31674194]), + 'frame': 25221, + 'frame_number': 25221, + 'framesequence': 101580, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.2663764506578, + 'timestamp_carla': 858265, + 'timestamp_device': 1728867, + 'timestamp_stream': 858.2663764506578, + 'transform': [array([-35.09139633, 68.05452728, -0.10174623]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02861881, -0.07451076, -7.5156827 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.214929580688477, + 'FR_Wheel_Angle': -14.225720405578613, + 'Location': array([-4.45815811e+01, 8.53886185e+01, 4.25324142e-02]), + 'Rotation': array([-0.15252495, 64.40692139, 0.09397053]), + 'Velocity': array([ 0.82629436, 1.22498322, -0.00394587]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31600189]), + 'frame': 25222, + 'frame_number': 25222, + 'framesequence': 101584, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.2966769523919, + 'timestamp_carla': 858295, + 'timestamp_device': 1728900, + 'timestamp_stream': 858.2966769523919, + 'transform': [array([-35.09139633, 68.05452728, -0.10172606]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.025165 , -0.07221904, -7.72280312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.2827205657959, + 'FR_Wheel_Angle': -14.148080825805664, + 'Location': array([-4.44219475e+01, 8.56323776e+01, 4.17716503e-02]), + 'Rotation': array([-0.15102914, 62.89263153, 0.09962536]), + 'Velocity': array([ 0.87026417, 1.21334183, -0.00384532]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31547546]), + 'frame': 25223, + 'frame_number': 25223, + 'framesequence': 101588, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.3323560506105, + 'timestamp_carla': 858331, + 'timestamp_device': 1728933, + 'timestamp_stream': 858.3323560506105, + 'transform': [array([-35.09139633, 68.05452728, -0.10175481]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02005635, -0.06881864, -7.68154526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.354717254638672, + 'FR_Wheel_Angle': -14.166836738586426, + 'Location': array([-4.42849464e+01, 8.58308945e+01, 4.11660671e-02]), + 'Rotation': array([-0.1504554 , 61.6352005 , 0.10289562]), + 'Velocity': array([ 0.88860214, 1.18172562, -0.00344067]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31749725]), + 'frame': 25224, + 'frame_number': 25224, + 'framesequence': 101592, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.3653626516461, + 'timestamp_carla': 858364, + 'timestamp_device': 1728967, + 'timestamp_stream': 858.3653626516461, + 'transform': [array([-35.09139633, 68.05452728, -0.10174982]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02210934, -0.07198736, -7.53649521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.364213943481445, + 'FR_Wheel_Angle': -14.173258781433105, + 'Location': array([-4.41453590e+01, 8.60240250e+01, 4.05740626e-02]), + 'Rotation': array([-0.14984068, 60.38565826, 0.10572386]), + 'Velocity': array([ 0.89491493, 1.13732135, -0.0034049 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31462097]), + 'frame': 25225, + 'frame_number': 25225, + 'framesequence': 101596, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.3972238488495, + 'timestamp_carla': 858396, + 'timestamp_device': 1729000, + 'timestamp_stream': 858.3972238488495, + 'transform': [array([-35.09139633, 68.05452728, -0.10173937]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02417782, -0.07743338, -7.43221521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.376195907592773, + 'FR_Wheel_Angle': -14.181957244873047, + 'Location': array([-4.40030899e+01, 8.62122345e+01, 3.99718769e-02]), + 'Rotation': array([-0.1486454 , 59.13737106, 0.10846329]), + 'Velocity': array([ 0.89521497, 1.08830988, -0.00299441]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31511688]), + 'frame': 25226, + 'frame_number': 25226, + 'framesequence': 101600, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.4305900521576, + 'timestamp_carla': 858429, + 'timestamp_device': 1729033, + 'timestamp_stream': 858.4305900521576, + 'transform': [array([-35.09139633, 68.05452728, -0.10174444]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.0242073 , -0.07764509, -7.2190299 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.389402389526367, + 'FR_Wheel_Angle': -14.191577911376953, + 'Location': array([-4.38368759e+01, 8.64216995e+01, 3.93324941e-02]), + 'Rotation': array([-0.14624117, 57.72259521, 0.11196837]), + 'Velocity': array([ 0.898449 , 1.03825271, -0.00293789]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31616211]), + 'frame': 25227, + 'frame_number': 25227, + 'framesequence': 101603, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.4622986502945, + 'timestamp_carla': 858461, + 'timestamp_device': 1729058, + 'timestamp_stream': 858.4622986502945, + 'transform': [array([-35.09139633, 68.05452728, -0.1017362 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.0391012 , -0.06159138, -6.8535099 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.593979835510254, + 'FR_Wheel_Angle': -12.387097358703613, + 'Location': array([-4.36663132e+01, 8.66263962e+01, 3.86753343e-02]), + 'Rotation': array([-0.14376181, 56.30737686, 0.1144828 ]), + 'Velocity': array([ 0.89209747, 0.99212712, -0.00314606]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31565857]), + 'frame': 25228, + 'frame_number': 25228, + 'framesequence': 101608, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.4974655508995, + 'timestamp_carla': 858496, + 'timestamp_device': 1729100, + 'timestamp_stream': 858.4974655508995, + 'transform': [array([-35.09139633, 68.05452728, -0.10175829]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.0131217 , -0.08566063, -4.77278185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.093043327331543, + 'FR_Wheel_Angle': -10.68903923034668, + 'Location': array([-4.35311623e+01, 8.67911606e+01, 3.81681733e-02]), + 'Rotation': array([-0.14165811, 55.44621658, 0.10856947]), + 'Velocity': array([ 0.84663343, 0.99561697, -0.00283182]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31648254]), + 'frame': 25229, + 'frame_number': 25229, + 'framesequence': 101612, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.5309580489993, + 'timestamp_carla': 858530, + 'timestamp_device': 1729133, + 'timestamp_stream': 858.5309580489993, + 'transform': [array([-35.09139633, 68.05452728, -0.10175722]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02807746, -0.0668063 , -5.34871626]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.218666076660156, + 'FR_Wheel_Angle': -10.71051025390625, + 'Location': array([-4.33969536e+01, 8.69498978e+01, 3.76734436e-02]), + 'Rotation': array([-0.14034672, 54.58660889, 0.11740542]), + 'Velocity': array([ 0.85493523, 0.94553989, -0.00293794]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31427002]), + 'frame': 25230, + 'frame_number': 25230, + 'framesequence': 101616, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.5630238503218, + 'timestamp_carla': 858562, + 'timestamp_device': 1729167, + 'timestamp_stream': 858.5630238503218, + 'transform': [array([-35.09139633, 68.05452728, -0.10174643]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02050065, -0.07670754, -5.14063263]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.403804779052734, + 'FR_Wheel_Angle': -10.991580963134766, + 'Location': array([-4.32363625e+01, 8.71344223e+01, 3.70952487e-02]), + 'Rotation': array([-0.13881676, 53.59316635, 0.11971702]), + 'Velocity': array([ 0.83616257, 0.89770788, -0.00284968]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31437683]), + 'frame': 25231, + 'frame_number': 25231, + 'framesequence': 101620, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.5972614511847, + 'timestamp_carla': 858596, + 'timestamp_device': 1729200, + 'timestamp_stream': 858.5972614511847, + 'transform': [array([-35.09139633, 68.05452728, -0.10175627]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02574275, -0.07165338, -4.62694883]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.370368003845215, + 'FR_Wheel_Angle': -11.038857460021973, + 'Location': array([-4.30771713e+01, 8.73106613e+01, 3.65252569e-02]), + 'Rotation': array([-0.13738924, 52.63850784, 0.12198457]), + 'Velocity': array([ 0.81285095, 0.84443641, -0.00308905]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31546021]), + 'frame': 25232, + 'frame_number': 25232, + 'framesequence': 101623, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.6298651508987, + 'timestamp_carla': 858628, + 'timestamp_device': 1729225, + 'timestamp_stream': 858.6298651508987, + 'transform': [array([-35.09139633, 68.05452728, -0.10174967]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01777387, 0.03250476, -4.37772751]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.330716133117676, + 'FR_Wheel_Angle': -11.03242015838623, + 'Location': array([-4.29470558e+01, 8.74503784e+01, 3.61400135e-02]), + 'Rotation': array([-0.1360437 , 51.87628555, 0.12346309]), + 'Velocity': array([ 0.75808859, 0.76723051, -0.00194065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31447601]), + 'frame': 25233, + 'frame_number': 25233, + 'framesequence': 101627, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.6625542491674, + 'timestamp_carla': 858661, + 'timestamp_device': 1729258, + 'timestamp_stream': 858.6625542491674, + 'transform': [array([-35.09139633, 68.05452728, -0.1017465 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02093354, 0.04045217, -4.02430582]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.341449737548828, + 'FR_Wheel_Angle': -11.041720390319824, + 'Location': array([-4.28212166e+01, 8.75819931e+01, 3.57087217e-02]), + 'Rotation': array([-0.13467084, 51.15258408, 0.12497806]), + 'Velocity': array([ 0.73480773, 0.72455674, -0.00189026]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31513214]), + 'frame': 25234, + 'frame_number': 25234, + 'framesequence': 101632, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.6969535499811, + 'timestamp_carla': 858696, + 'timestamp_device': 1729300, + 'timestamp_stream': 858.6969535499811, + 'transform': [array([-35.09139633, 68.05452728, -0.10175787]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02359523, 0.05299708, -4.11751032]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.350166320800781, + 'FR_Wheel_Angle': -11.049262046813965, + 'Location': array([-4.26753654e+01, 8.77303696e+01, 3.52299772e-02]), + 'Rotation': array([-0.13296328, 50.32595444, 0.12666377]), + 'Velocity': array([ 0.70571744, 0.67614716, -0.00258642]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31545258]), + 'frame': 25235, + 'frame_number': 25235, + 'framesequence': 101635, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.7294236496091, + 'timestamp_carla': 858728, + 'timestamp_device': 1729325, + 'timestamp_stream': 858.7294236496091, + 'transform': [array([-35.09139633, 68.05452728, -0.10174982]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01953901, 0.04048175, -3.8617022 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.358763694763184, + 'FR_Wheel_Angle': -11.056927680969238, + 'Location': array([-4.25594139e+01, 8.78454742e+01, 3.48872654e-02]), + 'Rotation': array([-0.13125573, 49.65882111, 0.12818095]), + 'Velocity': array([ 0.69290334, 0.64843428, -0.00155474]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3143158 ]), + 'frame': 25236, + 'frame_number': 25236, + 'framesequence': 101640, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.7635144516826, + 'timestamp_carla': 858762, + 'timestamp_device': 1729367, + 'timestamp_stream': 858.7635144516826, + 'transform': [array([-35.09139633, 68.05452728, -0.10175722]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.00237274, 0.07837447, -2.31613779]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.656148910522461, + 'FR_Wheel_Angle': -6.198800563812256, + 'Location': array([-4.24458199e+01, 8.79581528e+01, 3.45360078e-02]), + 'Rotation': array([-0.12957551, 49.07349014, 0.12457403]), + 'Velocity': array([ 0.65023762, 0.64389551, -0.00199154]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31511688]), + 'frame': 25237, + 'frame_number': 25237, + 'framesequence': 101644, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.8033235520124, + 'timestamp_carla': 858802, + 'timestamp_device': 1729400, + 'timestamp_stream': 858.8033235520124, + 'transform': [array([-35.09139633, 68.05452728, -0.10181516]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05629535, 0.01418147, -2.48594117]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.024200439453125, + 'FR_Wheel_Angle': -8.346580505371094, + 'Location': array([-4.23381157e+01, 8.80684052e+01, 3.41895968e-02]), + 'Rotation': array([-0.12909056, 48.6987648 , 0.12784025]), + 'Velocity': array([ 0.62941951, 0.60786039, -0.00170332]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31437683]), + 'frame': 25238, + 'frame_number': 25238, + 'framesequence': 101648, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.830668952316, + 'timestamp_carla': 858829, + 'timestamp_device': 1729433, + 'timestamp_stream': 858.830668952316, + 'transform': [array([-35.09139633, 68.05452728, -0.1018112 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03067199, 0.05414255, -2.32491493]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.87100887298584, + 'FR_Wheel_Angle': -7.481212615966797, + 'Location': array([-4.22324753e+01, 8.81735916e+01, 3.38448994e-02]), + 'Rotation': array([-0.1279909 , 48.27774429, 0.12925936]), + 'Velocity': array([ 0.60340232, 0.583395 , -0.00237702]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.30858612]), + 'frame': 25239, + 'frame_number': 25239, + 'framesequence': 101651, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.8629778511822, + 'timestamp_carla': 858862, + 'timestamp_device': 1729458, + 'timestamp_stream': 858.8629778511822, + 'transform': [array([-35.09139633, 68.05452728, -0.10177534]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.02327661, 0.12854114, -2.23284602]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.271842002868652, + 'FR_Wheel_Angle': -7.578603267669678, + 'Location': array([-4.21310196e+01, 8.82736130e+01, 3.35225202e-02]), + 'Rotation': array([-0.1276494 , 47.88738251, 0.12940879]), + 'Velocity': array([ 0.59602064, 0.56559116, -0.00299026]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.30898285]), + 'frame': 25240, + 'frame_number': 25240, + 'framesequence': 101656, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.8969229497015, + 'timestamp_carla': 858896, + 'timestamp_device': 1729500, + 'timestamp_stream': 858.8969229497015, + 'transform': [array([-35.09139633, 68.05452728, -0.10176507]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01438454, 0.1144992 , -2.38770127]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.24972152709961, + 'FR_Wheel_Angle': -7.650876998901367, + 'Location': array([-4.20309563e+01, 8.83707962e+01, 3.28708179e-02]), + 'Rotation': array([-0.14135759, 47.48082352, 0.09910912]), + 'Velocity': array([ 0.587641 , 0.54674059, -0.00338797]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31256866]), + 'frame': 25241, + 'frame_number': 25241, + 'framesequence': 101659, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.9285227507353, + 'timestamp_carla': 858927, + 'timestamp_device': 1729525, + 'timestamp_stream': 858.9285227507353, + 'transform': [array([-35.09139633, 68.05452728, -0.10174303]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.20015618, 0.77116728, -1.99799347]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.260833740234375, + 'FR_Wheel_Angle': -7.652997016906738, + 'Location': array([-4.19132500e+01, 8.84831696e+01, 3.20790000e-02]), + 'Rotation': array([-0.16110367, 47.04369736, 0.05365208]), + 'Velocity': array([ 0.56988835, 0.51389736, -0.0105214 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.313591 ]), + 'frame': 25242, + 'frame_number': 25242, + 'framesequence': 101664, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.9634781517088, + 'timestamp_carla': 858962, + 'timestamp_device': 1729566, + 'timestamp_stream': 858.9634781517088, + 'transform': [array([-35.09139633, 68.05452728, -0.10175539]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.27113754, 1.01569486, -2.03919768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.262450218200684, + 'FR_Wheel_Angle': -7.654239177703857, + 'Location': array([-4.18174324e+01, 8.85728607e+01, 3.01620755e-02]), + 'Rotation': array([-0.23025249, 46.69190979, -0.09124755]), + 'Velocity': array([ 0.57276857, 0.50664717, -0.01564506]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3157959 ]), + 'frame': 25243, + 'frame_number': 25243, + 'framesequence': 101668, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 858.9963320493698, + 'timestamp_carla': 858995, + 'timestamp_device': 1729600, + 'timestamp_stream': 858.9963320493698, + 'transform': [array([-35.09139633, 68.05452728, -0.10174661]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05179736, 0.00394946, -1.80788457]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.264781951904297, + 'FR_Wheel_Angle': -7.656973838806152, + 'Location': array([-4.17217636e+01, 8.86612473e+01, 2.86738109e-02]), + 'Rotation': array([-0.26956707, 46.35869598, -0.16430664]), + 'Velocity': array([ 0.55294985, 0.49557635, -0.00216521]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31455994]), + 'frame': 25244, + 'frame_number': 25244, + 'framesequence': 101671, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.0299280509353, + 'timestamp_carla': 859029, + 'timestamp_device': 1729625, + 'timestamp_stream': 859.0299280509353, + 'transform': [array([-35.09139633, 68.05452728, -0.10174661]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01552441, 0.05210646, -1.77293026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.270308494567871, + 'FR_Wheel_Angle': -7.626296043395996, + 'Location': array([-4.16291389e+01, 8.87463760e+01, 2.85426602e-02]), + 'Rotation': array([-0.26510695, 46.0349617 , -0.15753171]), + 'Velocity': array([ 5.30073404e-01, 4.69484270e-01, -4.40077769e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31543732]), + 'frame': 25245, + 'frame_number': 25245, + 'framesequence': 101676, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.0634507499635, + 'timestamp_carla': 859062, + 'timestamp_device': 1729666, + 'timestamp_stream': 859.0634507499635, + 'transform': [array([-35.09139633, 68.05452728, -0.10174661]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.00146834, 0.09866497, -0.6409632 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.145648717880249, + 'FR_Wheel_Angle': -2.399831771850586, + 'Location': array([-4.15408440e+01, 8.88288345e+01, 2.83228196e-02]), + 'Rotation': array([-0.26547578, 45.79889297, -0.1661987 ]), + 'Velocity': array([ 0.4959363 , 0.47593367, -0.00178946]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31543732]), + 'frame': 25246, + 'frame_number': 25246, + 'framesequence': 101680, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.0966723524034, + 'timestamp_carla': 859095, + 'timestamp_device': 1729700, + 'timestamp_stream': 859.0966723524034, + 'transform': [array([-35.09139633, 68.05452728, -0.10174509]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03981647, 0.0665001 , -0.96730179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.911790370941162, + 'FR_Wheel_Angle': -4.6168742179870605, + 'Location': array([-4.14564285e+01, 8.89108963e+01, 2.80102435e-02]), + 'Rotation': array([-0.26822153, 45.67704391, -0.16967773]), + 'Velocity': array([ 0.48388359, 0.4523851 , -0.00173656]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31543732]), + 'frame': 25247, + 'frame_number': 25247, + 'framesequence': 101683, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.1287534497678, + 'timestamp_carla': 859127, + 'timestamp_device': 1729725, + 'timestamp_stream': 859.1287534497678, + 'transform': [array([-35.09139633, 68.05452728, -0.10173669]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.0126274 , 0.07384026, -0.61283135]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.8535068035125732, + 'FR_Wheel_Angle': -3.8781580924987793, + 'Location': array([-4.13742714e+01, 8.89893570e+01, 2.76890080e-02]), + 'Rotation': array([-0.27123362, 45.53181839, -0.1764221 ]), + 'Velocity': array([ 0.47050676, 0.44501066, -0.00155473]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3155899 ]), + 'frame': 25248, + 'frame_number': 25248, + 'framesequence': 101688, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.1650498509407, + 'timestamp_carla': 859164, + 'timestamp_device': 1729766, + 'timestamp_stream': 859.1650498509407, + 'transform': [array([-35.09139633, 68.05452728, -0.10176615]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02124365, 0.09113011, -0.66334087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.105225086212158, + 'FR_Wheel_Angle': -3.926732301712036, + 'Location': array([-4.12939720e+01, 8.90659256e+01, 2.73569003e-02]), + 'Rotation': array([-0.27444381, 45.38473129, -0.18280029]), + 'Velocity': array([ 0.45097154, 0.4217115 , -0.00211554]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31642914]), + 'frame': 25249, + 'frame_number': 25249, + 'framesequence': 101692, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.1968486495316, + 'timestamp_carla': 859196, + 'timestamp_device': 1729800, + 'timestamp_stream': 859.1968486495316, + 'transform': [array([-35.09139633, 68.05452728, -0.10174756]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01636753, 0.08093084, -0.54469764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.148526668548584, + 'FR_Wheel_Angle': -3.9874322414398193, + 'Location': array([-4.12174072e+01, 8.91384735e+01, 2.70525645e-02]), + 'Rotation': array([-0.2774286 , 45.25833893, -0.1895752 ]), + 'Velocity': array([ 0.4424299 , 0.41157579, -0.00182598]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31348419]), + 'frame': 25250, + 'frame_number': 25250, + 'framesequence': 101696, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.2303401492536, + 'timestamp_carla': 859229, + 'timestamp_device': 1729833, + 'timestamp_stream': 859.2303401492536, + 'transform': [array([-35.09139633, 68.05452728, -0.10174871]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.0189212 , 0.08532486, -0.52243292]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.1482415199279785, + 'FR_Wheel_Angle': -3.9883923530578613, + 'Location': array([-4.11408157e+01, 8.92105331e+01, 2.67367829e-02]), + 'Rotation': array([-0.28024265, 45.1487999 , -0.19647217]), + 'Velocity': array([ 0.43308657, 0.40120915, -0.00162219]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31534576]), + 'frame': 25251, + 'frame_number': 25251, + 'framesequence': 101700, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.2628959491849, + 'timestamp_carla': 859262, + 'timestamp_device': 1729866, + 'timestamp_stream': 859.2628959491849, + 'transform': [array([-35.09139633, 68.05452728, -0.10174288]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.00096518, 0.08667932, -0.20586072]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.149679660797119, + 'FR_Wheel_Angle': -3.9911530017852783, + 'Location': array([-4.10660477e+01, 8.92808838e+01, 2.63921637e-02]), + 'Rotation': array([-0.28524917, 45.02754211, -0.19973756]), + 'Velocity': array([ 0.4238075 , 0.39187998, -0.00192077]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31523132]), + 'frame': 25252, + 'frame_number': 25252, + 'framesequence': 101704, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.296705249697, + 'timestamp_carla': 859295, + 'timestamp_device': 1729900, + 'timestamp_stream': 859.296705249697, + 'transform': [array([-35.09139633, 68.05452728, -0.10174913]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.18200296, 0.01216858, -0.32737181]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.151856422424316, + 'FR_Wheel_Angle': -3.9901654720306396, + 'Location': array([-4.09931717e+01, 8.93492813e+01, 2.59465687e-02]), + 'Rotation': array([-0.29498219, 44.89209366, -0.19058223]), + 'Velocity': array([ 0.42070764, 0.38877052, -0.00414138]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31581116]), + 'frame': 25253, + 'frame_number': 25253, + 'framesequence': 101708, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.3305948488414, + 'timestamp_carla': 859329, + 'timestamp_device': 1729933, + 'timestamp_stream': 859.3305948488414, + 'transform': [array([-35.09139633, 68.05452728, -0.10175356]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.02837545, 0.06091306, -1.48346186]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.152589321136475, + 'FR_Wheel_Angle': -3.760538339614868, + 'Location': array([-4.09212799e+01, 8.94165421e+01, 2.54819766e-02]), + 'Rotation': array([-0.30423027, 44.72966766, -0.18566893]), + 'Velocity': array([ 0.41768843, 0.38014311, -0.00201435]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31518555]), + 'frame': 25254, + 'frame_number': 25254, + 'framesequence': 101712, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.3637708500028, + 'timestamp_carla': 859362, + 'timestamp_device': 1729966, + 'timestamp_stream': 859.3637708500028, + 'transform': [array([-35.09139633, 68.05452728, -0.10175073]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.46507695, -0.1185571 , -0.61595339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.6149321794509888, + 'FR_Wheel_Angle': 0.9418229460716248, + 'Location': array([-4.08372116e+01, 8.94966354e+01, 2.50260066e-02]), + 'Rotation': array([-0.31377888, 44.63253784, -0.18234254]), + 'Velocity': array([ 0.39044398, 0.39484358, -0.00627472]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31474304]), + 'frame': 25255, + 'frame_number': 25255, + 'framesequence': 101716, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.396485850215, + 'timestamp_carla': 859395, + 'timestamp_device': 1730000, + 'timestamp_stream': 859.396485850215, + 'transform': [array([-35.09139633, 68.05452728, -0.10174589]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.63661736, -0.15714417, 0.39686075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5527965426445007, + 'FR_Wheel_Angle': -0.13038218021392822, + 'Location': array([-4.07550049e+01, 8.95774918e+01, 2.34323014e-02]), + 'Rotation': array([-0.370729 , 44.6167717 , -0.07281492]), + 'Velocity': array([ 0.40560955, 0.39853668, -0.01098941]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31502533]), + 'frame': 25256, + 'frame_number': 25256, + 'framesequence': 101720, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.4301251508296, + 'timestamp_carla': 859429, + 'timestamp_device': 1730033, + 'timestamp_stream': 859.4301251508296, + 'transform': [array([-35.09139633, 68.05452728, -0.10175017]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03553835, 0.0855127 , 0.61261821]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.02027800865471363, + 'FR_Wheel_Angle': -0.17344048619270325, + 'Location': array([-4.06861610e+01, 8.96454926e+01, 2.20728200e-02]), + 'Rotation': array([-4.12809789e-01, 4.46017494e+01, -4.88281809e-03]), + 'Velocity': array([ 0.39126688, 0.38750082, -0.00381769]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31551361]), + 'frame': 25257, + 'frame_number': 25257, + 'framesequence': 101724, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.4635304510593, + 'timestamp_carla': 859462, + 'timestamp_device': 1730066, + 'timestamp_stream': 859.4635304510593, + 'transform': [array([-35.09139633, 68.05452728, -0.10175017]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.05388572, 0.05247649, 0.40038294]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.01648680679500103, + 'FR_Wheel_Angle': -0.04056937247514725, + 'Location': array([-4.06180382e+01, 8.97129211e+01, 2.18577087e-02]), + 'Rotation': array([-4.11553025e-01, 4.46065292e+01, -1.86462291e-02]), + 'Velocity': array([ 3.99100423e-01, 3.94839764e-01, -3.48443980e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31508636]), + 'frame': 25258, + 'frame_number': 25258, + 'framesequence': 101728, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.4967531524599, + 'timestamp_carla': 859495, + 'timestamp_device': 1730100, + 'timestamp_stream': 859.4967531524599, + 'transform': [array([-35.09139633, 68.05452728, -0.10175017]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.0497638 , 0.06225063, 0.19784231]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003805693006142974, + 'FR_Wheel_Angle': 0.0038054806645959616, + 'Location': array([-4.05385666e+01, 8.97917099e+01, 2.16667447e-02]), + 'Rotation': array([-4.13144469e-01, 4.46052284e+01, -2.87170224e-02]), + 'Velocity': array([ 0.36929503, 0.36541086, -0.0015801 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31508636]), + 'frame': 25259, + 'frame_number': 25259, + 'framesequence': 101732, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.530507851392, + 'timestamp_carla': 859529, + 'timestamp_device': 1730133, + 'timestamp_stream': 859.530507851392, + 'transform': [array([-35.09139633, 68.05452728, -0.10175375]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.0513519 , 0.05158977, 0.56860715]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003806563327088952, + 'FR_Wheel_Angle': 0.003806875552982092, + 'Location': array([-4.04609299e+01, 8.98685989e+01, 2.13035475e-02]), + 'Rotation': array([-4.18820351e-01, 4.46125565e+01, -2.98156645e-02]), + 'Velocity': array([ 0.36686844, 0.36382574, -0.00213359]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': True, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31508636]), + 'frame': 25260, + 'frame_number': 25260, + 'framesequence': 101736, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.5640374496579, + 'timestamp_carla': 859563, + 'timestamp_device': 1730166, + 'timestamp_stream': 859.5640374496579, + 'transform': [array([-35.09139633, 68.05452728, -0.10175375]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.05787923, 0.0635412 , -0.26842681]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038062501698732376, + 'FR_Wheel_Angle': 0.0038083093240857124, + 'Location': array([-4.03977051e+01, 8.99311295e+01, 2.09757891e-02]), + 'Rotation': array([-4.24441606e-01, 4.46098557e+01, -2.98767202e-02]), + 'Velocity': array([ 0.3519415 , 0.34761968, -0.00189415]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31472778]), + 'frame': 25261, + 'frame_number': 25261, + 'framesequence': 101740, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.5973595492542, + 'timestamp_carla': 859596, + 'timestamp_device': 1730200, + 'timestamp_stream': 859.5973595492542, + 'transform': [array([-35.09139633, 68.05452728, -0.1017523 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.04215258, 0.0128814 , 1.44926548]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003808405017480254, + 'FR_Wheel_Angle': 0.003809168469160795, + 'Location': array([-4.03345947e+01, 8.99934158e+01, 2.06295289e-02]), + 'Rotation': array([-4.29256886e-01, 4.46144333e+01, -3.00597847e-02]), + 'Velocity': array([ 0.37105358, 0.36620942, -0.00251637]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31472778]), + 'frame': 25262, + 'frame_number': 25262, + 'framesequence': 101744, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.6300600506365, + 'timestamp_carla': 859629, + 'timestamp_device': 1730233, + 'timestamp_stream': 859.6300600506365, + 'transform': [array([-35.09139633, 68.05452728, -0.101747 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03389873, 0.03950079, 0.59671658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.127657413482666, + 'FR_Wheel_Angle': 4.7145514488220215, + 'Location': array([-4.02740822e+01, 9.00534363e+01, 2.03407947e-02]), + 'Rotation': array([-4.35513318e-01, 4.46251678e+01, -3.07922345e-02]), + 'Velocity': array([ 0.34461692, 0.34898198, -0.00129101]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31487274]), + 'frame': 25263, + 'frame_number': 25263, + 'framesequence': 101748, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.6632083505392, + 'timestamp_carla': 859662, + 'timestamp_device': 1730266, + 'timestamp_stream': 859.6632083505392, + 'transform': [array([-35.09139633, 68.05452728, -0.101747 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.07469741, 0.00955181, 0.99667972]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9126737117767334, + 'FR_Wheel_Angle': 3.3809101581573486, + 'Location': array([-4.02058601e+01, 9.01256332e+01, 1.99730583e-02]), + 'Rotation': array([-4.41100419e-01, 4.47837868e+01, -3.23791504e-02]), + 'Velocity': array([ 0.32422563, 0.34755653, -0.00144709]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31539917]), + 'frame': 25264, + 'frame_number': 25264, + 'framesequence': 101752, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.6966476514935, + 'timestamp_carla': 859695, + 'timestamp_device': 1730300, + 'timestamp_stream': 859.6966476514935, + 'transform': [array([-35.09139633, 68.05452728, -0.10174955]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03882762, 0.01492881, 2.08763218]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.323977470397949, + 'FR_Wheel_Angle': 4.556490421295166, + 'Location': array([-4.01494827e+01, 9.01850662e+01, 1.96736809e-02]), + 'Rotation': array([-4.45014119e-01, 4.48923378e+01, -3.18908468e-02]), + 'Velocity': array([ 0.33523539, 0.36318401, -0.00208561]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31539917]), + 'frame': 25265, + 'frame_number': 25265, + 'framesequence': 101756, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.7302841506898, + 'timestamp_carla': 859729, + 'timestamp_device': 1730333, + 'timestamp_stream': 859.7302841506898, + 'transform': [array([-35.09139633, 68.05452728, -0.10175256]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.01152571, -0.00535432, 1.03203332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9761738777160645, + 'FR_Wheel_Angle': 4.243424415588379, + 'Location': array([-4.00944061e+01, 9.02441711e+01, 1.93616394e-02]), + 'Rotation': array([-4.48729753e-01, 4.49941330e+01, -3.44848298e-02]), + 'Velocity': array([ 0.33451101, 0.36556333, -0.00154788]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.3151474 ]), + 'frame': 25266, + 'frame_number': 25266, + 'framesequence': 101760, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.7635448500514, + 'timestamp_carla': 859762, + 'timestamp_device': 1730366, + 'timestamp_stream': 859.7635448500514, + 'transform': [array([-35.09139633, 68.05452728, -0.10175142]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.11964884, 0.03258101, 1.22960138]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.034031391143799, + 'FR_Wheel_Angle': 4.16741418838501, + 'Location': array([-4.00305099e+01, 9.03130722e+01, 1.90046597e-02]), + 'Rotation': array([-4.53667969e-01, 4.51033173e+01, -3.66516262e-02]), + 'Velocity': array([ 0.3221975 , 0.35262379, -0.0027392 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31484222]), + 'frame': 25267, + 'frame_number': 25267, + 'framesequence': 101764, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.7979658506811, + 'timestamp_carla': 859797, + 'timestamp_device': 1730400, + 'timestamp_stream': 859.7979658506811, + 'transform': [array([-35.09139633, 68.05452728, -0.10175958]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.03173374, 0.04132065, 0.99453485]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9831666946411133, + 'FR_Wheel_Angle': 4.143161296844482, + 'Location': array([-3.99668388e+01, 9.03816071e+01, 1.83135513e-02]), + 'Rotation': array([-0.44549224, 45.2303772 , -0.0566101 ]), + 'Velocity': array([ 0.30810899, 0.33348566, -0.00310074]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31495667]), + 'frame': 25268, + 'frame_number': 25268, + 'framesequence': 101768, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.830204449594, + 'timestamp_carla': 859829, + 'timestamp_device': 1730433, + 'timestamp_stream': 859.830204449594, + 'transform': [array([-35.09139633, 68.05452728, -0.10174799]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.01341709, 0.00482743, 1.34418046]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.986997127532959, + 'FR_Wheel_Angle': 4.146990776062012, + 'Location': array([-3.99135590e+01, 9.04389725e+01, 1.79311279e-02]), + 'Rotation': array([-0.44775301, 45.34204102, -0.06018065]), + 'Velocity': array([ 0.3186661 , 0.35227466, -0.00189805]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31414032]), + 'frame': 25269, + 'frame_number': 25269, + 'framesequence': 101771, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.8632232509553, + 'timestamp_carla': 859862, + 'timestamp_device': 1730458, + 'timestamp_stream': 859.8632232509553, + 'transform': [array([-35.09139633, 68.05452728, -0.10174677]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.18947023, 0.08932187, 0.40147972]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9842872619628906, + 'FR_Wheel_Angle': 4.1429572105407715, + 'Location': array([-3.98616982e+01, 9.04951859e+01, 1.76183991e-02]), + 'Rotation': array([-0.45019823, 45.44211578, -0.06365963]), + 'Velocity': array([ 0.3122887 , 0.34135267, -0.00325366]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31529999]), + 'frame': 25270, + 'frame_number': 25270, + 'framesequence': 101776, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.8962145522237, + 'timestamp_carla': 859895, + 'timestamp_device': 1730500, + 'timestamp_stream': 859.8962145522237, + 'transform': [array([-35.09139633, 68.05452728, -0.10174677]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.43893322, 0.12512164, 1.34557688]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.487120151519775, + 'FR_Wheel_Angle': 6.031064987182617, + 'Location': array([-3.97970200e+01, 9.05643463e+01, 1.61373038e-02]), + 'Rotation': array([-0.41342449, 45.60447311, -0.1294861 ]), + 'Velocity': array([ 0.31907701, 0.34492111, -0.00794914]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31542206]), + 'frame': 25271, + 'frame_number': 25271, + 'framesequence': 101779, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.9293892495334, + 'timestamp_carla': 859928, + 'timestamp_device': 1730525, + 'timestamp_stream': 859.9293892495334, + 'transform': [array([-35.09139633, 68.05452728, -0.10174791]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([0.48191726, 0.10530076, 2.37091923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.946582794189453, + 'FR_Wheel_Angle': 8.955215454101562, + 'Location': array([-3.97335129e+01, 9.06358185e+01, 1.43755246e-02]), + 'Rotation': array([-0.36266938, 45.87856674, -0.20733643]), + 'Velocity': array([ 0.28908369, 0.3484225 , -0.00758398]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31542206]), + 'frame': 25272, + 'frame_number': 25272, + 'framesequence': 101784, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.9646459519863, + 'timestamp_carla': 859963, + 'timestamp_device': 1730566, + 'timestamp_stream': 859.9646459519863, + 'transform': [array([-35.09139633, 68.05452728, -0.10176523]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.00221519, -0.06541537, 1.99506629]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.354649066925049, + 'FR_Wheel_Angle': 8.366086959838867, + 'Location': array([-3.96812935e+01, 9.06965637e+01, 1.31748104e-02]), + 'Rotation': array([-0.3276988 , 46.10922241, -0.24728392]), + 'Velocity': array([ 0.31592438, 0.38522291, -0.00214289]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31530762]), + 'frame': 25273, + 'frame_number': 25273, + 'framesequence': 101788, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 859.997172050178, + 'timestamp_carla': 859996, + 'timestamp_device': 1730600, + 'timestamp_stream': 859.997172050178, + 'transform': [array([-35.09139633, 68.05452728, -0.10175359]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.13967253, -0.00388064, 0.46747881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.553622722625732, + 'FR_Wheel_Angle': 8.213363647460938, + 'Location': array([-3.96307449e+01, 9.07569809e+01, 1.31078623e-02]), + 'Rotation': array([-0.33426261, 46.32404327, -0.23245241]), + 'Velocity': array([ 2.73303658e-01, 3.36773455e-01, -2.99367908e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31357574]), + 'frame': 25274, + 'frame_number': 25274, + 'framesequence': 101792, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 860.0342610515654, + 'timestamp_carla': 860033, + 'timestamp_device': 1730633, + 'timestamp_stream': 860.0342610515654, + 'transform': [array([-35.09139633, 68.05452728, -0.10178411]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.04478353, -0.01386298, 0.64351618]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.677807331085205, + 'FR_Wheel_Angle': 8.281746864318848, + 'Location': array([-3.95714340e+01, 9.08285141e+01, 1.30520910e-02]), + 'Rotation': array([-0.33700836, 46.56140518, -0.22125241]), + 'Velocity': array([ 0.28154358, 0.3501668 , -0.0010546 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31474304]), + 'frame': 25275, + 'frame_number': 25275, + 'framesequence': 101796, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 860.0664436519146, + 'timestamp_carla': 860065, + 'timestamp_device': 1730666, + 'timestamp_stream': 860.0664436519146, + 'transform': [array([-35.09139633, 68.05452728, -0.101761 ]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([-0.03560968, -0.00669111, -0.10690612]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.711743354797363, + 'FR_Wheel_Angle': 8.331356048583984, + 'Location': array([-3.95231552e+01, 9.08873215e+01, 1.28364079e-02]), + 'Rotation': array([-0.33577892, 46.75172806, -0.21685788]), + 'Velocity': array([ 0.27670556, 0.34630147, -0.00169475]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31169128]), + 'frame': 25276, + 'frame_number': 25276, + 'framesequence': 101800, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.019836727529764175, + 'timestamp': 860.0967079512775, + 'timestamp_carla': 860095, + 'timestamp_device': 1730700, + 'timestamp_stream': 860.0967079512775, + 'transform': [array([-35.09139633, 68.05452728, -0.10173555]), + array([-4.70599998e-03, -1.27822861e+02, 8.48992262e-03])]} +{'AngularVelocity': array([ 0.01827123, -0.0303646 , 0.66707766]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.72091817855835, + 'FR_Wheel_Angle': 8.338353157043457, + 'Location': array([-3.94761429e+01, 9.09448700e+01, 1.26270195e-02]), + 'Rotation': array([-0.3339211 , 46.94369888, -0.21295165]), + 'Velocity': array([ 0.28311932, 0.35875887, -0.00161547]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31400299]), + 'frame': 25277, + 'frame_number': 25277, + 'framesequence': 101803, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.051590751856565475, + 'timestamp': 860.1294918507338, + 'timestamp_carla': 860128, + 'timestamp_device': 1730725, + 'timestamp_stream': 860.1294918507338, + 'transform': [array([-35.09192657, 68.05374146, -0.10171345]), + array([-4.65818867e-03, -1.27826805e+02, 8.39430187e-03])]} +{'AngularVelocity': array([-0.04932133, 0.00361287, 1.19994676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.713708877563477, + 'FR_Wheel_Angle': 8.330364227294922, + 'Location': array([-3.94207306e+01, 9.10125275e+01, 1.23231793e-02]), + 'Rotation': array([-0.33169445, 47.17770004, -0.20886233]), + 'Velocity': array([ 0.24707322, 0.31642735, -0.00153716]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.903564453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.70703125, 10232.83496094, 123.31654358]), + 'frame': 25278, + 'frame_number': 25278, + 'framesequence': 101808, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.07142747938632965, + 'timestamp': 860.1628159508109, + 'timestamp_carla': 860162, + 'timestamp_device': 1730766, + 'timestamp_stream': 860.1628159508109, + 'transform': [array([-35.0917511 , 68.05363464, -0.10170972]), + array([-4.67867916e-03, -1.27826653e+02, 8.35332088e-03])]} +{'AngularVelocity': array([-0.0556641 , 0.01302446, 0.4378705 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.712582588195801, + 'FR_Wheel_Angle': 8.335606575012207, + 'Location': array([-3.93657265e+01, 9.10807800e+01, 1.20699210e-02]), + 'Rotation': array([-0.32812226, 47.41199875, -0.20477296]), + 'Velocity': array([ 0.24990232, 0.32374954, -0.00148448]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.573974609375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.26464844, 10232.8359375 , 123.30964661]), + 'frame': 25279, + 'frame_number': 25279, + 'framesequence': 101811, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.08729686588048935, + 'timestamp': 860.1959570497274, + 'timestamp_carla': 860195, + 'timestamp_device': 1730791, + 'timestamp_stream': 860.1959570497274, + 'transform': [array([-35.09157562, 68.05353546, -0.10171213]), + array([-4.68550948e-03, -1.27826515e+02, 8.35331995e-03])]} +{'AngularVelocity': array([-0.0242344 , 0.02343136, 1.17162907]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.869153022766113, + 'FR_Wheel_Angle': 13.750409126281738, + 'Location': array([-3.93205795e+01, 9.11378555e+01, 1.18293287e-02]), + 'Rotation': array([-0.32684502, 47.62100983, -0.20303345]), + 'Velocity': array([ 0.23507352, 0.32389709, -0.00132405]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.607177734375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.28222656, 10232.83496094, 123.30628204]), + 'frame': 25280, + 'frame_number': 25280, + 'framesequence': 101815, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.09919890016317368, + 'timestamp': 860.2297099493444, + 'timestamp_carla': 860228, + 'timestamp_device': 1730825, + 'timestamp_stream': 860.2297099493444, + 'transform': [array([-35.09143829, 68.05337524, -0.10172454]), + array([-4.67867916e-03, -1.27826645e+02, 8.38064123e-03])]} +{'AngularVelocity': array([-0.07165769, -0.0151289 , 1.72594583]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.861175537109375, + 'FR_Wheel_Angle': 11.584670066833496, + 'Location': array([-3.92791023e+01, 9.11939468e+01, 1.16278362e-02]), + 'Rotation': array([-0.32473451, 47.91012192, -0.20098877]), + 'Velocity': array([ 0.22160752, 0.31507632, -0.00115868]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.6416015625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.30078125, 10232.83496094, 123.30606842]), + 'frame': 25281, + 'frame_number': 25281, + 'framesequence': 101819, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.10713358968496323, + 'timestamp': 860.2622990496457, + 'timestamp_carla': 860261, + 'timestamp_device': 1730858, + 'timestamp_stream': 860.2622990496457, + 'transform': [array([-35.09133148, 68.05323792, -0.10173398]), + array([-4.67184931e-03, -1.27826805e+02, 8.44211318e-03])]} +{'AngularVelocity': array([-1.28211454e-03, 9.42362589e-04, 1.94197953e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.461788177490234, + 'FR_Wheel_Angle': 12.6421480178833, + 'Location': array([-3.92379074e+01, 9.12495804e+01, 1.14192106e-02]), + 'Rotation': array([-0.32183167, 48.19409943, -0.19781496]), + 'Velocity': array([ 0.22542238, 0.33352292, -0.00080936]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.650390625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.28515625, 10232.83496094, 123.30734253]), + 'frame': 25282, + 'frame_number': 25282, + 'framesequence': 101824, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1111009418964386, + 'timestamp': 860.2971613518894, + 'timestamp_carla': 860296, + 'timestamp_device': 1730900, + 'timestamp_stream': 860.2971613518894, + 'transform': [array([-35.09131622, 68.05300903, -0.10176281]), + array([-4.65135835e-03, -1.27827446e+02, 8.50358419e-03])]} +{'AngularVelocity': array([-0.07444236, -0.00927979, 1.58601224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.167725563049316, + 'FR_Wheel_Angle': 12.590091705322266, + 'Location': array([-3.91883430e+01, 9.13178177e+01, 1.11608030e-02]), + 'Rotation': array([-0.31857365, 48.54071808, -0.19403075]), + 'Velocity': array([ 0.22079673, 0.32074073, -0.00087206]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.656494140625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.27050781, 10232.83496094, 123.31209564]), + 'frame': 25283, + 'frame_number': 25283, + 'framesequence': 101827, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.11506828665733337, + 'timestamp': 860.3293403498828, + 'timestamp_carla': 860328, + 'timestamp_device': 1730925, + 'timestamp_stream': 860.3293403498828, + 'transform': [array([-35.09131622, 68.05288696, -0.10177491]), + array([-4.64452850e-03, -1.27827805e+02, 8.60603806e-03])]} +{'AngularVelocity': array([-0.06614989, -0.00444978, 1.67632449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.150975227355957, + 'FR_Wheel_Angle': 12.512439727783203, + 'Location': array([-3.91466599e+01, 9.13758698e+01, 1.09351631e-02]), + 'Rotation': array([-0.315705 , 48.83257675, -0.19131465]), + 'Velocity': array([ 0.22217049, 0.32791245, -0.0011524 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.6162109375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.19726562, 10232.83496094, 123.31486511]), + 'frame': 25284, + 'frame_number': 25284, + 'framesequence': 101831, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.13888761401176453, + 'timestamp': 860.3624190501869, + 'timestamp_carla': 860361, + 'timestamp_device': 1730958, + 'timestamp_stream': 860.3624190501869, + 'transform': [array([-35.09144974, 68.05273438, -0.10180158]), + array([-4.62403800e-03, -1.27828583e+02, 8.72214977e-03])]} +{'AngularVelocity': array([-0.02000188, 0.0118063 , 1.74231267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.167238235473633, + 'FR_Wheel_Angle': 12.498294830322266, + 'Location': array([-3.91052284e+01, 9.14341507e+01, 1.07503412e-02]), + 'Rotation': array([-0.31225574, 49.12861252, -0.19146724]), + 'Velocity': array([ 2.21453294e-01, 3.31555516e-01, -2.87284842e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.595703125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.15917969, 10232.83496094, 123.32316589]), + 'frame': 25285, + 'frame_number': 25285, + 'framesequence': 101835, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 860.3963198512793, + 'timestamp_carla': 860395, + 'timestamp_device': 1730991, + 'timestamp_stream': 860.3963198512793, + 'transform': [array([-35.09168625, 68.05260468, -0.10184252]), + array([-4.61720768e-03, -1.27829514e+02, 8.87241401e-03])]} +{'AngularVelocity': array([-0.02873309, 0.01002409, 1.77823281]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.166391372680664, + 'FR_Wheel_Angle': 12.498566627502441, + 'Location': array([-3.90639343e+01, 9.14927979e+01, 1.06040090e-02]), + 'Rotation': array([-0.30664134, 49.43471146, -0.19525146]), + 'Velocity': array([ 0.21858041, 0.33026341, -0.00061716]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.532470703125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.07666016, 10232.8359375 , 123.33125305]), + 'frame': 25286, + 'frame_number': 25286, + 'framesequence': 101839, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2222171425819397, + 'timestamp': 860.4297257512808, + 'timestamp_carla': 860428, + 'timestamp_device': 1731025, + 'timestamp_stream': 860.4297257512808, + 'transform': [array([-35.09208298, 68.0525589 , -0.10189828]), + array([-4.59671719e-03, -1.27830559e+02, 9.11147147e-03])]} +{'AngularVelocity': array([-0.05200221, -0.04399372, 1.459396 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.165281295776367, + 'FR_Wheel_Angle': 12.502655982971191, + 'Location': array([-3.90226250e+01, 9.15521469e+01, 1.04220482e-02]), + 'Rotation': array([-0.29964721, 49.73744202, -0.19650267]), + 'Velocity': array([ 0.21549335, 0.32894969, -0.00143575]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.44384765625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7601.97363281, 10232.83496094, 123.34108734]), + 'frame': 25287, + 'frame_number': 25287, + 'framesequence': 101844, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2380865216255188, + 'timestamp': 860.4626985490322, + 'timestamp_carla': 860461, + 'timestamp_device': 1731066, + 'timestamp_stream': 860.4626985490322, + 'transform': [array([-35.09272385, 68.05265045, -0.10197534]), + array([-4.58988687e-03, -1.27831749e+02, 9.45297908e-03])]} +{'AngularVelocity': array([-0.05526377, 0.03166923, 1.43173873]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.171850204467773, + 'FR_Wheel_Angle': 12.505939483642578, + 'Location': array([-3.89828568e+01, 9.16097641e+01, 1.02469921e-02]), + 'Rotation': array([-0.29531687, 50.01314545, -0.19918823]), + 'Velocity': array([1.98134899e-01, 3.02708626e-01, 1.98745722e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.329345703125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7601.86035156, 10232.83496094, 123.3576889 ]), + 'frame': 25288, + 'frame_number': 25288, + 'framesequence': 101848, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 860.4986280500889, + 'timestamp_carla': 860497, + 'timestamp_device': 1731099, + 'timestamp_stream': 860.4986280500889, + 'transform': [array([-35.09291458, 68.05400085, -0.10216302]), + array([-4.57622670e-03, -1.27827545e+02, 1.01564908e-02])]} +{'AngularVelocity': array([ 0.07767829, -0.02338645, 2.58869553]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.746928215026855, + 'FR_Wheel_Angle': 18.400917053222656, + 'Location': array([-3.89457397e+01, 9.16652527e+01, 1.00789927e-02]), + 'Rotation': array([-0.28778318, 50.32398987, -0.20269772]), + 'Velocity': array([ 0.20656443, 0.3582527 , -0.00154677]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.176513671875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7601.73144531, 10232.83496094, 123.3817215 ]), + 'frame': 25289, + 'frame_number': 25289, + 'framesequence': 101852, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 860.5330024510622, + 'timestamp_carla': 860532, + 'timestamp_device': 1731133, + 'timestamp_stream': 860.5330024510622, + 'transform': [array([-35.09778214, 68.0534668 , -0.10271585]), + array([-4.69916966e-03, -1.27841873e+02, 1.24855842e-02])]} +{'AngularVelocity': array([ 0.06810763, -0.03010255, 2.15291405]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.062332153320312, + 'FR_Wheel_Angle': 16.664262771606445, + 'Location': array([-3.89025192e+01, 9.17344284e+01, 9.64934286e-03]), + 'Rotation': array([-0.27252454, 50.76205826, -0.19107057]), + 'Velocity': array([ 0.2039122 , 0.35562301, -0.00099153]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4000.4482421875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7602.21679688, 10232.8359375 , 123.42845917]), + 'frame': 25290, + 'frame_number': 25290, + 'framesequence': 101856, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 860.5645818524063, + 'timestamp_carla': 860563, + 'timestamp_device': 1731166, + 'timestamp_stream': 860.5645818524063, + 'transform': [array([-35.09923172, 68.05812073, -0.10316037]), + array([-4.64452850e-03, -1.27829910e+02, 1.44595085e-02])]} +{'AngularVelocity': array([-3.31077874e-02, -7.87607802e-04, 2.08882689e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.366817474365234, + 'FR_Wheel_Angle': 16.44739532470703, + 'Location': array([-3.88616409e+01, 9.18006592e+01, 9.43507161e-03]), + 'Rotation': array([-0.26620662, 51.1699791 , -0.19259642]), + 'Velocity': array([ 0.17725338, 0.31504971, -0.00085989]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3998.8720703125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.59570312, 10232.83496094, 123.59012604]), + 'frame': 25291, + 'frame_number': 25291, + 'framesequence': 101859, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 860.5933991521597, + 'timestamp_carla': 860592, + 'timestamp_device': 1731191, + 'timestamp_stream': 860.5933991521597, + 'transform': [array([-35.10410309, 68.06110382, -0.10373633]), + array([-4.70599998e-03, -1.27832520e+02, 1.67339630e-02])]} +{'AngularVelocity': array([-0.0460508 , -0.00914385, 2.37021446]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.46578311920166, + 'FR_Wheel_Angle': 16.673160552978516, + 'Location': array([-3.88265953e+01, 9.18581848e+01, 9.28378105e-03]), + 'Rotation': array([-0.25961548, 51.55138397, -0.19436643]), + 'Velocity': array([ 0.1806495 , 0.32350668, -0.00051878]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3999.50927734375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7601.95654297, 10232.83496094, 123.72937012]), + 'frame': 25292, + 'frame_number': 25292, + 'framesequence': 101863, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 860.6287549510598, + 'timestamp_carla': 860627, + 'timestamp_device': 1731224, + 'timestamp_stream': 860.6287549510598, + 'transform': [array([-35.11143112, 68.06491852, -0.10408885]), + array([-4.82894341e-03, -1.27838799e+02, 1.82161108e-02])]} +{'AngularVelocity': array([-0.04755231, -0.0027708 , 2.07077098]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.408974647521973, + 'FR_Wheel_Angle': 16.67826271057129, + 'Location': array([-3.87919617e+01, 9.19156418e+01, 9.13081132e-03]), + 'Rotation': array([-0.25408986, 51.93805313, -0.19558717]), + 'Velocity': array([ 0.17693594, 0.32032573, -0.00086273]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3998.725830078125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7601.6640625 , 10232.83496094, 123.88349152]), + 'frame': 25293, + 'frame_number': 25293, + 'framesequence': 101868, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 860.6634205505252, + 'timestamp_carla': 860662, + 'timestamp_device': 1731266, + 'timestamp_stream': 860.6634205505252, + 'transform': [array([-35.1187706 , 68.06978607, -0.10417616]), + array([-4.80845291e-03, -1.27841530e+02, 1.86190922e-02])]} +{'AngularVelocity': array([ 0.00513389, -0.22306214, 1.73766041]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.410463333129883, + 'FR_Wheel_Angle': 16.681720733642578, + 'Location': array([-3.87505341e+01, 9.19848709e+01, 8.50027986e-03]), + 'Rotation': array([-0.22997929, 52.37741089, -0.17034909]), + 'Velocity': array([ 0.18960497, 0.34644929, -0.00384801]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3997.378173828125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.95507812, 10232.83496094, 123.98620605]), + 'frame': 25294, + 'frame_number': 25294, + 'framesequence': 101872, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 860.6979594491422, + 'timestamp_carla': 860697, + 'timestamp_device': 1731299, + 'timestamp_stream': 860.6979594491422, + 'transform': [array([-35.12744522, 68.07541656, -0.10439315]), + array([-4.93139634e-03, -1.27845314e+02, 1.95480008e-02])]} +{'AngularVelocity': array([-0.02448311, -0.24759978, 1.64828897]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.40405559539795, + 'FR_Wheel_Angle': 16.681976318359375, + 'Location': array([-3.87148056e+01, 9.20446854e+01, 7.56632769e-03]), + 'Rotation': array([-0.19753589, 52.75799942, -0.13372804]), + 'Velocity': array([ 0.18621758, 0.34807235, -0.00421993]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3996.26904296875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.65039062, 10232.83496094, 124.014534 ]), + 'frame': 25295, + 'frame_number': 25295, + 'framesequence': 101876, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21824978291988373, + 'timestamp': 860.7306419499218, + 'timestamp_carla': 860729, + 'timestamp_device': 1731333, + 'timestamp_stream': 860.7306419499218, + 'transform': [array([-35.13519287, 68.08259583, -0.10442854]), + array([-4.65818867e-03, -1.27841286e+02, 1.98007151e-02])]} +{'AngularVelocity': array([ 0.00314619, -0.23219429, 2.72769737]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.412026405334473, + 'FR_Wheel_Angle': 16.680362701416016, + 'Location': array([-3.86799393e+01, 9.21043320e+01, 6.54669758e-03]), + 'Rotation': array([-0.16274974, 53.13698959, -0.0895996 ]), + 'Velocity': array([ 0.17968288, 0.34611368, -0.00429478]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3994.910888671875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.21582031, 10232.83496094, 124.07922363]), + 'frame': 25296, + 'frame_number': 25296, + 'framesequence': 101880, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2063324898481369, + 'timestamp': 860.7634845487773, + 'timestamp_carla': 860762, + 'timestamp_device': 1731366, + 'timestamp_stream': 860.7634845487773, + 'transform': [array([-35.14529037, 68.08959961, -0.10456648]), + array([-4.52158507e-03, -1.27843842e+02, 2.04359256e-02])]} +{'AngularVelocity': array([-0.01494975, 0.04010641, 2.31094527]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.165353775024414, + 'FR_Wheel_Angle': 20.784807205200195, + 'Location': array([-3.86449890e+01, 9.21661148e+01, 5.81763266e-03]), + 'Rotation': array([-0.13751219, 53.53334808, -0.06683349]), + 'Velocity': array([ 0.17976435, 0.35854998, -0.00045895]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3994.210205078125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.67871094, 10232.83496094, 124.09801483]), + 'frame': 25297, + 'frame_number': 25297, + 'framesequence': 101884, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.19839780032634735, + 'timestamp': 860.7965143509209, + 'timestamp_carla': 860795, + 'timestamp_device': 1731399, + 'timestamp_stream': 860.7965143509209, + 'transform': [array([-35.15658951, 68.09729004, -0.10471138]), + array([-4.68550948e-03, -1.27847389e+02, 2.10438091e-02])]} +{'AngularVelocity': array([-0.00254285, 0.03155347, 2.50978923]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.959789276123047, + 'FR_Wheel_Angle': 19.88279914855957, + 'Location': array([-3.86059151e+01, 9.22423706e+01, 5.80534944e-03]), + 'Rotation': array([-0.13775808, 54.11127472, -0.07763671]), + 'Velocity': array([0.15995045, 0.35785151, 0.00072578]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3992.774658203125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.40136719, 10232.83496094, 124.14230347]), + 'frame': 25298, + 'frame_number': 25298, + 'framesequence': 101888, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 860.8297290503979, + 'timestamp_carla': 860828, + 'timestamp_device': 1731433, + 'timestamp_stream': 860.8297290503979, + 'transform': [array([-35.16759109, 68.10695648, -0.10479798]), + array([-4.77430178e-03, -1.27843620e+02, 2.13989820e-02])]} +{'AngularVelocity': array([-5.81750125e-02, -1.08023372e-03, 2.62992406e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.776897430419922, + 'FR_Wheel_Angle': 21.13906478881836, + 'Location': array([-3.85692139e+01, 9.23151627e+01, 5.71516994e-03]), + 'Rotation': array([-0.13415174, 54.63969803, -0.08322144]), + 'Velocity': array([ 0.14831781, 0.33783743, -0.0008809 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3991.109619140625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.00292969, 10232.83496094, 124.18427277]), + 'frame': 25299, + 'frame_number': 25299, + 'framesequence': 101891, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 860.863098051399, + 'timestamp_carla': 860862, + 'timestamp_device': 1731458, + 'timestamp_stream': 860.863098051399, + 'transform': [array([-35.18031311, 68.11690521, -0.10487357]), + array([-4.74698143e-03, -1.27843307e+02, 2.17131674e-02])]} +{'AngularVelocity': array([-2.67974846e-02, -1.44907797e-04, 2.76223993e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.497224807739258, + 'FR_Wheel_Angle': 20.92404556274414, + 'Location': array([-3.85378647e+01, 9.23796082e+01, 5.60210226e-03]), + 'Rotation': array([-0.12911789, 55.1287117 , -0.08721923]), + 'Velocity': array([1.51812792e-01, 3.52986455e-01, 6.36529876e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3989.97119140625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.42871094, 10232.83398438, 124.20851135]), + 'frame': 25300, + 'frame_number': 25300, + 'framesequence': 101896, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 860.897325951606, + 'timestamp_carla': 860896, + 'timestamp_device': 1731499, + 'timestamp_stream': 860.897325951606, + 'transform': [array([-35.19519043, 68.12656403, -0.10482602]), + array([-4.76747192e-03, -1.27849594e+02, 2.14741118e-02])]} +{'AngularVelocity': array([-1.11535918e-02, 1.07218954e-03, 2.03076315e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.45137596130371, + 'FR_Wheel_Angle': 20.86316680908203, + 'Location': array([-3.85037689e+01, 9.24508972e+01, 5.44718746e-03]), + 'Rotation': array([-0.12311415, 55.66466904, -0.08880614]), + 'Velocity': array([ 0.14776839, 0.35072234, -0.00099061]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3988.387939453125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7600.46777344, 10232.83496094, 124.22946167]), + 'frame': 25301, + 'frame_number': 25301, + 'framesequence': 101899, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 860.9293513521552, + 'timestamp_carla': 860928, + 'timestamp_device': 1731524, + 'timestamp_stream': 860.9293513521552, + 'transform': [array([-35.20947266, 68.13643646, -0.10473008]), + array([-4.79479274e-03, -1.27853706e+02, 2.11121123e-02])]} +{'AngularVelocity': array([ 0.03415456, -0.01372994, 3.3125217 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.45215606689453, + 'FR_Wheel_Angle': 20.846759796142578, + 'Location': array([-3.84766960e+01, 9.25081940e+01, 5.27014723e-03]), + 'Rotation': array([-0.11675525, 56.0901947 , -0.09014892]), + 'Velocity': array([ 0.15594564, 0.36865315, -0.00120725]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3986.084228515625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7599.76269531, 10232.83496094, 124.21121216]), + 'frame': 25302, + 'frame_number': 25302, + 'framesequence': 101903, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 860.9626343511045, + 'timestamp_carla': 860961, + 'timestamp_device': 1731558, + 'timestamp_stream': 860.9626343511045, + 'transform': [array([-35.22574997, 68.14712524, -0.10478152]), + array([-4.78796242e-03, -1.27860222e+02, 2.13170201e-02])]} +{'AngularVelocity': array([ 0.02107183, -0.01098551, 3.51591635]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.456369400024414, + 'FR_Wheel_Angle': 20.853118896484375, + 'Location': array([-3.84498940e+01, 9.25660934e+01, 5.10188099e-03]), + 'Rotation': array([-0.11093593, 56.51753235, -0.0909729 ]), + 'Velocity': array([ 0.15042722, 0.36455363, -0.00094053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3984.000244140625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7599.30175781, 10232.83496094, 124.18653107]), + 'frame': 25303, + 'frame_number': 25303, + 'framesequence': 101908, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.1904631108045578, + 'timestamp': 860.9959851503372, + 'timestamp_carla': 860995, + 'timestamp_device': 1731599, + 'timestamp_stream': 860.9959851503372, + 'transform': [array([-35.24356461, 68.15851593, -0.10491364]), + array([-4.80162259e-03, -1.27868378e+02, 2.18634289e-02])]} +{'AngularVelocity': array([0.08655643, 0.02372727, 3.38952994]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.467065811157227, + 'FR_Wheel_Angle': 20.86516761779785, + 'Location': array([-3.84178848e+01, 9.26368561e+01, 4.87875938e-03]), + 'Rotation': array([-0.10412623, 57.03882599, -0.09234618]), + 'Velocity': array([ 0.14595167, 0.37495366, -0.00065856]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3981.50341796875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7598.56835938, 10232.8359375 , 124.19946289]), + 'frame': 25304, + 'frame_number': 25304, + 'framesequence': 101911, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2380865216255188, + 'timestamp': 861.0287078507245, + 'timestamp_carla': 861027, + 'timestamp_device': 1731624, + 'timestamp_stream': 861.0287078507245, + 'transform': [array([-35.26052094, 68.17115784, -0.10484612]), + array([-4.84943390e-03, -1.27870201e+02, 2.15833969e-02])]} +{'AngularVelocity': array([0.0569656 , 0.00509615, 2.6726141 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.466875076293945, + 'FR_Wheel_Angle': 21.172691345214844, + 'Location': array([-3.83932037e+01, 9.26931686e+01, 4.73547913e-03]), + 'Rotation': array([-0.09942706, 57.44795227, -0.09237669]), + 'Velocity': array([ 0.13369709, 0.34409511, -0.00051282]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3978.699951171875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.64697266, 10232.83496094, 124.23590088]), + 'frame': 25305, + 'frame_number': 25305, + 'framesequence': 101915, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 861.0624372512102, + 'timestamp_carla': 861061, + 'timestamp_device': 1731658, + 'timestamp_stream': 861.0624372512102, + 'transform': [array([-35.27849197, 68.18532562, -0.10481313]), + array([-4.84260404e-03, -1.27869537e+02, 2.14194730e-02])]} +{'AngularVelocity': array([0.09795079, 0.04036755, 3.78383827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.497098922729492, + 'FR_Wheel_Angle': 26.72252082824707, + 'Location': array([-3.83700562e+01, 9.27491684e+01, 4.58598137e-03]), + 'Rotation': array([-0.09319793, 57.90889359, -0.09634399]), + 'Velocity': array([ 0.1169607 , 0.36573821, -0.00063029]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3976.4296875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.44335938, 10232.83496094, 124.21601105]), + 'frame': 25306, + 'frame_number': 25306, + 'framesequence': 101919, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 861.0954231508076, + 'timestamp_carla': 861094, + 'timestamp_device': 1731691, + 'timestamp_stream': 861.0954231508076, + 'transform': [array([-35.29684448, 68.19984436, -0.10474028]), + array([-4.78113210e-03, -1.27868675e+02, 2.11257748e-02])]} +{'AngularVelocity': array([-0.01023046, -0.07497366, 2.37810969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.750503540039062, + 'FR_Wheel_Angle': 24.534690856933594, + 'Location': array([-3.83481827e+01, 9.28065567e+01, 4.41897381e-03]), + 'Rotation': array([-0.08746057, 58.39166641, -0.09515381]), + 'Velocity': array([ 0.12309219, 0.34514838, -0.00098951]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3974.19775390625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.51757812, 10232.83496094, 124.20324707]), + 'frame': 25307, + 'frame_number': 25307, + 'framesequence': 101923, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 861.1286205500364, + 'timestamp_carla': 861127, + 'timestamp_device': 1731724, + 'timestamp_stream': 861.1286205500364, + 'transform': [array([-35.31713486, 68.21381378, -0.10466111]), + array([-4.75381128e-03, -1.27874641e+02, 2.07910892e-02])]} +{'AngularVelocity': array([ 0.04680716, -0.05324035, 3.54622245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.50884246826172, + 'FR_Wheel_Angle': 25.014543533325195, + 'Location': array([-3.83271523e+01, 9.28625565e+01, 4.27290890e-03]), + 'Rotation': array([-0.08251551, 58.87207413, -0.09564209]), + 'Velocity': array([ 0.12189456, 0.35764489, -0.00104444]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3971.93115234375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.6171875 , 10232.83496094, 124.18228912]), + 'frame': 25308, + 'frame_number': 25308, + 'framesequence': 101928, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 861.163986351341, + 'timestamp_carla': 861162, + 'timestamp_device': 1731766, + 'timestamp_stream': 861.163986351341, + 'transform': [array([-35.33862305, 68.23064423, -0.1046394 ]), + array([-4.67184931e-03, -1.27874138e+02, 2.06339974e-02])]} +{'AngularVelocity': array([0.11809502, 0.0035886 , 3.23572135]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.411012649536133, + 'FR_Wheel_Angle': 25.046024322509766, + 'Location': array([-3.83067513e+01, 9.29189453e+01, 4.13977634e-03]), + 'Rotation': array([-0.07696257, 59.34020996, -0.09725951]), + 'Velocity': array([ 0.1193966 , 0.3853347 , -0.00077525]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3968.964599609375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7596.94824219, 10232.83496094, 124.15803528]), + 'frame': 25309, + 'frame_number': 25309, + 'framesequence': 101931, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 861.1959633491933, + 'timestamp_carla': 861194, + 'timestamp_device': 1731791, + 'timestamp_stream': 861.1959633491933, + 'transform': [array([-35.35885239, 68.2469101 , -0.10468893]), + array([-4.69233980e-03, -1.27872253e+02, 2.09072083e-02])]} +{'AngularVelocity': array([0.10892274, 0.0033028 , 3.27095532]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.3645076751709, + 'FR_Wheel_Angle': 25.054847717285156, + 'Location': array([-3.82822342e+01, 9.29884338e+01, 3.96910636e-03]), + 'Rotation': array([-0.07040559, 59.93720245, -0.09826659]), + 'Velocity': array([ 0.11742958, 0.39106563, -0.00078058]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3966.28271484375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.01074219, 10232.83496094, 124.14440918]), + 'frame': 25310, + 'frame_number': 25310, + 'framesequence': 101935, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 861.228761550039, + 'timestamp_carla': 861227, + 'timestamp_device': 1731824, + 'timestamp_stream': 861.228761550039, + 'transform': [array([-35.38091278, 68.26393127, -0.10473078]), + array([-4.69916966e-03, -1.27872551e+02, 2.10984480e-02])]} +{'AngularVelocity': array([0.11455017, 0.0050585 , 3.33818173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.36321258544922, + 'FR_Wheel_Angle': 25.052169799804688, + 'Location': array([-3.82582054e+01, 9.30587845e+01, 3.79031175e-03]), + 'Rotation': array([-0.0642106 , 60.54039001, -0.09942625]), + 'Velocity': array([ 0.11458232, 0.39692584, -0.00087068]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3963.851318359375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.22753906, 10232.83496094, 124.16391754]), + 'frame': 25311, + 'frame_number': 25311, + 'framesequence': 101940, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.2539559006690979, + 'timestamp': 861.2633138522506, + 'timestamp_carla': 861262, + 'timestamp_device': 1731866, + 'timestamp_stream': 861.2633138522506, + 'transform': [array([-35.40522385, 68.28262329, -0.1047859 ]), + array([-4.70599998e-03, -1.27873169e+02, 2.12828629e-02])]} +{'AngularVelocity': array([0.1153722 , 0.00829424, 3.29988933]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.36208152770996, + 'FR_Wheel_Angle': 25.052528381347656, + 'Location': array([-3.82386284e+01, 9.31177597e+01, 3.64356022e-03]), + 'Rotation': array([-5.90196624e-02, 6.10488548e+01, -1.00341797e-01]), + 'Velocity': array([ 0.11112812, 0.39908162, -0.00060073]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3961.043701171875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.19726562, 10232.8359375 , 124.17640686]), + 'frame': 25312, + 'frame_number': 25312, + 'framesequence': 101944, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.23015183210372925, + 'timestamp': 861.2967118509114, + 'timestamp_carla': 861295, + 'timestamp_device': 1731899, + 'timestamp_stream': 861.2967118509114, + 'transform': [array([-35.42944717, 68.30180359, -0.10483987]), + array([-4.70599998e-03, -1.27871925e+02, 2.15219241e-02])]} +{'AngularVelocity': array([-0.06997591, -0.03837499, 2.72929811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.341997146606445, + 'FR_Wheel_Angle': 25.05152130126953, + 'Location': array([-3.82183380e+01, 9.31811295e+01, 3.54723912e-03]), + 'Rotation': array([-5.61236627e-02, 6.15873604e+01, -9.75952074e-02]), + 'Velocity': array([8.66885856e-02, 3.34358156e-01, 1.64327619e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3957.929443359375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.1328125, 10232.8359375, 124.1867981]), + 'frame': 25313, + 'frame_number': 25313, + 'framesequence': 101948, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.21824978291988373, + 'timestamp': 861.3291616514325, + 'timestamp_carla': 861328, + 'timestamp_device': 1731933, + 'timestamp_stream': 861.3291616514325, + 'transform': [array([-35.4541893 , 68.32109833, -0.10491372]), + array([-4.69916966e-03, -1.27871628e+02, 2.18702611e-02])]} +{'AngularVelocity': array([-0.06071556, -0.02299764, 2.90653563]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.05465316772461, + 'FR_Wheel_Angle': 29.217304229736328, + 'Location': array([-3.81979790e+01, 9.32476425e+01, 3.48414411e-03]), + 'Rotation': array([-5.40472828e-02, 6.21672783e+01, -9.42993015e-02]), + 'Velocity': array([7.52922446e-02, 3.33959907e-01, 1.01413723e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3954.94921875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.27685547, 10232.8359375 , 124.20236206]), + 'frame': 25314, + 'frame_number': 25314, + 'framesequence': 101951, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.006317331921309233, + 'throttle_input': 0.21031509339809418, + 'timestamp': 861.3624985516071, + 'timestamp_carla': 861361, + 'timestamp_device': 1731958, + 'timestamp_stream': 861.3624985516071, + 'transform': [array([-35.48112869, 68.34114838, -0.10497502]), + array([-5.07483026e-03, -1.27874863e+02, 2.20819972e-02])]} +{'AngularVelocity': array([-0.07702361, -0.05875618, 3.35012698]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.69304084777832, + 'FR_Wheel_Angle': 28.265581130981445, + 'Location': array([-3.81827888e+01, 9.33059616e+01, 3.44374659e-03]), + 'Rotation': array([-5.21553233e-02, 6.27573662e+01, -9.14916843e-02]), + 'Velocity': array([ 6.48296773e-02, 3.33681256e-01, -1.11117362e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3951.842041015625, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7597.31542969, 10232.8359375 , 124.22593689]), + 'frame': 25315, + 'frame_number': 25315, + 'framesequence': 101956, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.023364972323179245, + 'throttle_input': 0.2063324898481369, + 'timestamp': 861.396652251482, + 'timestamp_carla': 861395, + 'timestamp_device': 1731999, + 'timestamp_stream': 861.396652251482, + 'transform': [array([-35.51127243, 68.36077118, -0.10500872]), + array([-6.35207538e-03, -1.27889175e+02, 2.20546797e-02])]} +{'AngularVelocity': array([-0.06809763, -0.04018073, 3.33827686]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.374095916748047, + 'FR_Wheel_Angle': 29.483610153198242, + 'Location': array([-3.81646004e+01, 9.33774185e+01, 3.36005213e-03]), + 'Rotation': array([-4.95325290e-02, 6.34427605e+01, -8.64867941e-02]), + 'Velocity': array([6.07210808e-02, 3.34486157e-01, 1.65672303e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3948.202392578125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7596.94384766, 10232.8359375 , 124.23921967]), + 'frame': 25316, + 'frame_number': 25316, + 'framesequence': 101959, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04843287914991379, + 'throttle_input': 0.19839780032634735, + 'timestamp': 861.425413750112, + 'timestamp_carla': 861424, + 'timestamp_device': 1732024, + 'timestamp_stream': 861.425413750112, + 'transform': [array([-35.53969193, 68.37574768, -0.10514842]), + array([-8.33282992e-03, -1.27916092e+02, 2.22869068e-02])]} +{'AngularVelocity': array([-0.0924578 , -0.06187367, 3.15851402]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.03925895690918, + 'FR_Wheel_Angle': 29.216331481933594, + 'Location': array([-3.81501770e+01, 9.34372635e+01, 3.29428655e-03]), + 'Rotation': array([-4.70873229e-02, 6.40279999e+01, -8.29772800e-02]), + 'Velocity': array([ 0.05957403, 0.33334377, -0.00063807]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3943.365966796875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7595.29443359, 10232.8359375 , 124.23586273]), + 'frame': 25317, + 'frame_number': 25317, + 'framesequence': 101964, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07088229060173035, + 'throttle_input': 0.1904631108045578, + 'timestamp': 861.4632141515613, + 'timestamp_carla': 861462, + 'timestamp_device': 1732066, + 'timestamp_stream': 861.4632141515613, + 'transform': [array([-35.58054733, 68.39241028, -0.10506293]), + array([-1.11878496e-02, -1.27973396e+02, 2.15355884e-02])]} +{'AngularVelocity': array([-0.07545584, -0.04303873, 2.79261208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.09162139892578, + 'FR_Wheel_Angle': 29.20638656616211, + 'Location': array([-3.81365356e+01, 9.34963837e+01, 3.24053760e-03]), + 'Rotation': array([-4.54070941e-02, 6.45882568e+01, -7.95593113e-02]), + 'Velocity': array([ 5.36764339e-02, 3.30764890e-01, -1.47533414e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3937.84521484375, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7592.18847656, 10232.8359375 , 124.24794769]), + 'frame': 25318, + 'frame_number': 25318, + 'framesequence': 101967, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10234077274799347, + 'throttle_input': 0.1904631108045578, + 'timestamp': 861.4929065518081, + 'timestamp_carla': 861491, + 'timestamp_device': 1732091, + 'timestamp_stream': 861.4929065518081, + 'transform': [array([-35.61546326, 68.40299225, -0.10482121]), + array([-1.34418113e-02, -1.28036484e+02, 2.01832037e-02])]} +{'AngularVelocity': array([-0.06611229, -0.04517497, 3.15850687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.107542037963867, + 'FR_Wheel_Angle': 29.203189849853516, + 'Location': array([-3.81238136e+01, 9.35552139e+01, 3.18377488e-03]), + 'Rotation': array([-4.33033966e-02, 6.51394730e+01, -7.65380785e-02]), + 'Velocity': array([5.12104109e-02, 3.34290713e-01, 2.72846210e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3928.583251953125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7585.58007812, 10232.8359375 , 124.19371796]), + 'frame': 25319, + 'frame_number': 25319, + 'framesequence': 101971, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12691427767276764, + 'throttle_input': 0.1904631108045578, + 'timestamp': 861.52873454988, + 'timestamp_carla': 861527, + 'timestamp_device': 1732124, + 'timestamp_stream': 861.52873454988, + 'transform': [array([-35.6630249 , 68.41207886, -0.10473569]), + array([-1.65017359e-02, -1.28142624e+02, 1.95821524e-02])]} +{'AngularVelocity': array([-0.07281112, -0.04659931, 3.02103209]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.107749938964844, + 'FR_Wheel_Angle': 29.205522537231445, + 'Location': array([-3.81113625e+01, 9.36148605e+01, 3.12399864e-03]), + 'Rotation': array([-4.12953198e-02, 6.57070618e+01, -7.33337253e-02]), + 'Velocity': array([ 4.74436954e-02, 3.31397057e-01, -2.61011126e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3919.67236328125, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7578.31835938, 10232.83496094, 124.09825134]), + 'frame': 25320, + 'frame_number': 25320, + 'framesequence': 101975, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15582752227783203, + 'throttle_input': 0.1904631108045578, + 'timestamp': 861.5627163499594, + 'timestamp_carla': 861561, + 'timestamp_device': 1732158, + 'timestamp_stream': 861.5627163499594, + 'transform': [array([-35.71248627, 68.41780853, -0.10470698]), + array([-1.91996600e-02, -1.28267700e+02, 1.92884542e-02])]} +{'AngularVelocity': array([-0.091227 , -0.0605628 , 2.85098028]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.11114501953125, + 'FR_Wheel_Angle': 29.20799446105957, + 'Location': array([-3.80972290e+01, 9.36865768e+01, 3.04461480e-03]), + 'Rotation': array([-3.89389060e-02, 6.63868637e+01, -6.95190281e-02]), + 'Velocity': array([ 0.04319282, 0.32508877, -0.00041904]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3909.12451171875, + 'focus_actor_name': 'BP_Block05_71', + 'focus_actor_pt': array([-7568.49414062, 10234.65917969, 124.05863953]), + 'frame': 25321, + 'frame_number': 25321, + 'framesequence': 101979, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18415479362010956, + 'throttle_input': 0.1904631108045578, + 'timestamp': 861.5951633490622, + 'timestamp_carla': 861594, + 'timestamp_device': 1732191, + 'timestamp_stream': 861.5951633490622, + 'transform': [array([-35.76445389, 68.41997528, -0.10471795]), + array([-2.17609815e-02, -1.28414108e+02, 1.91723444e-02])]} +{'AngularVelocity': array([-0.0984389 , -0.06532673, 2.91080332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.110095977783203, + 'FR_Wheel_Angle': 29.757610321044922, + 'Location': array([-3.80839767e+01, 9.37579727e+01, 2.96973228e-03]), + 'Rotation': array([-3.65551710e-02, 6.70664825e+01, -6.57958835e-02]), + 'Velocity': array([ 0.03937621, 0.322135 , -0.00069689]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3891.171630859375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7551.93261719, 10232.83691406, 124.03784943]), + 'frame': 25322, + 'frame_number': 25322, + 'framesequence': 101983, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2133243829011917, + 'throttle_input': 0.1904631108045578, + 'timestamp': 861.6266316510737, + 'timestamp_carla': 861625, + 'timestamp_device': 1732224, + 'timestamp_stream': 861.6266316510737, + 'transform': [array([-35.81930542, 68.41896057, -0.10473653]), + array([-2.42676605e-02, -1.28581726e+02, 1.90698896e-02])]} +{'AngularVelocity': array([0.01198774, 0.04085151, 3.80552292]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.874568939208984, + 'FR_Wheel_Angle': 34.95204544067383, + 'Location': array([-3.80754967e+01, 9.38154297e+01, 2.94501288e-03]), + 'Rotation': array([-3.52437757e-02, 6.76381836e+01, -6.56127781e-02]), + 'Velocity': array([ 1.33182975e-02, 3.49302322e-01, -1.54409412e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3874.476806640625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7535.37402344, 10232.8359375 , 124.02938843]), + 'frame': 25323, + 'frame_number': 25323, + 'framesequence': 101988, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23899656534194946, + 'throttle_input': 0.18649576604366302, + 'timestamp': 861.6632375493646, + 'timestamp_carla': 861662, + 'timestamp_device': 1732266, + 'timestamp_stream': 861.6632375493646, + 'transform': [array([-35.88792038, 68.41421509, -0.1046873 ]), + array([-2.65147928e-02, -1.28805618e+02, 1.84961595e-02])]} +{'AngularVelocity': array([-0.0510065 , -0.03881812, 3.24132252]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.26757049560547, + 'FR_Wheel_Angle': 32.9675178527832, + 'Location': array([-3.80681000e+01, 9.38716278e+01, 2.88977614e-03]), + 'Rotation': array([-3.34542654e-02, 6.82474365e+01, -6.05468489e-02]), + 'Velocity': array([ 1.97133515e-02, 3.20531905e-01, -4.97055044e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3856.098388671875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7516.55957031, 10232.8359375 , 124.02072906]), + 'frame': 25324, + 'frame_number': 25324, + 'framesequence': 101991, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2709311246871948, + 'throttle_input': 0.18649576604366302, + 'timestamp': 861.6941943503916, + 'timestamp_carla': 861693, + 'timestamp_device': 1732291, + 'timestamp_stream': 861.6941943503916, + 'transform': [array([-35.95052338, 68.40692139, -0.1046406 ]), + array([-2.85980012e-02, -1.29021698e+02, 1.81819685e-02])]} +{'AngularVelocity': array([-0.08049645, -0.06017135, 2.87507105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.713375091552734, + 'FR_Wheel_Angle': 33.201263427734375, + 'Location': array([-3.80613708e+01, 9.39287872e+01, 2.84148217e-03]), + 'Rotation': array([-3.16442661e-02, 6.88472748e+01, -5.80139011e-02]), + 'Velocity': array([ 1.28834033e-02, 3.10283482e-01, -6.73580143e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3832.369384765625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7491.65429688, 10232.8359375 , 123.97373199]), + 'frame': 25325, + 'frame_number': 25325, + 'framesequence': 101995, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2968047261238098, + 'throttle_input': 0.18649576604366302, + 'timestamp': 861.7285778522491, + 'timestamp_carla': 861727, + 'timestamp_device': 1732324, + 'timestamp_stream': 861.7285778522491, + 'transform': [array([-36.02510834, 68.39511108, -0.1045832 ]), + array([-3.07016987e-02, -1.29292007e+02, 1.76697038e-02])]} +{'AngularVelocity': array([-0.03283592, 0.00426863, 3.03903174]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.79048728942871, + 'FR_Wheel_Angle': 33.36054992675781, + 'Location': array([-3.80544777e+01, 9.39956360e+01, 2.77178758e-03]), + 'Rotation': array([-2.98206042e-02, 6.95174789e+01, -5.38024753e-02]), + 'Velocity': array([ 0.00855547, 0.3107658 , -0.00064911]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3810.189453125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7467.86572266, 10232.8359375 , 123.95020294]), + 'frame': 25326, + 'frame_number': 25326, + 'framesequence': 102000, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.326084166765213, + 'throttle_input': 0.18649576604366302, + 'timestamp': 861.7631572522223, + 'timestamp_carla': 861762, + 'timestamp_device': 1732366, + 'timestamp_stream': 861.7631572522223, + 'transform': [array([-36.10543823, 68.37934113, -0.10450181]), + array([-3.25185284e-02, -1.29595490e+02, 1.70959700e-02])]} +{'AngularVelocity': array([-0.08301879, -0.06042203, 2.87731767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.76844596862793, + 'FR_Wheel_Angle': 33.401451110839844, + 'Location': array([-3.80487671e+01, 9.40497894e+01, 2.73520453e-03]), + 'Rotation': array([-2.75598112e-02, 7.00886078e+01, -5.21240160e-02]), + 'Velocity': array([ 0.00906166, 0.30355477, -0.000416 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3783.27099609375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7438.45117188, 10232.8359375 , 123.90886688]), + 'frame': 25327, + 'frame_number': 25327, + 'framesequence': 102003, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3562425673007965, + 'throttle_input': 0.18252842128276825, + 'timestamp': 861.7955621518195, + 'timestamp_carla': 861794, + 'timestamp_device': 1732391, + 'timestamp_stream': 861.7955621518195, + 'transform': [array([-36.18553925, 68.36125183, -0.10442755]), + array([-3.44036594e-02, -1.29908432e+02, 1.66246854e-02])]} +{'AngularVelocity': array([-0.08855671, -0.06879652, 2.93900609]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.77192497253418, + 'FR_Wheel_Angle': 33.40568542480469, + 'Location': array([-3.80439529e+01, 9.41044388e+01, 2.68759718e-03]), + 'Rotation': array([-2.63030566e-02, 7.06645355e+01, -4.94995043e-02]), + 'Velocity': array([ 0.00532953, 0.29398215, -0.00034835]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3753.943603515625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7405.86132812, 10232.8359375 , 123.86325836]), + 'frame': 25328, + 'frame_number': 25328, + 'framesequence': 102008, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.38392898440361023, + 'throttle_input': 0.18252842128276825, + 'timestamp': 861.8302934505045, + 'timestamp_carla': 861829, + 'timestamp_device': 1732433, + 'timestamp_stream': 861.8302934505045, + 'transform': [array([-36.27679062, 68.33804321, -0.10434005]), + array([-3.62000018e-02, -1.30276154e+02, 1.60099659e-02])]} +{'AngularVelocity': array([-0.08265559, -0.06364473, 2.56218362]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.778850555419922, + 'FR_Wheel_Angle': 33.41524124145508, + 'Location': array([-3.80401726e+01, 9.41572723e+01, 2.65246397e-03]), + 'Rotation': array([-2.52990201e-02, 7.11960068e+01, -4.68750037e-02]), + 'Velocity': array([ 0.00034679, 0.282426 , -0.00031516]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3724.534912109375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7372.71582031, 10232.8359375 , 123.82675934]), + 'frame': 25329, + 'frame_number': 25329, + 'framesequence': 102011, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4124943017959595, + 'throttle_input': 0.17856107652187347, + 'timestamp': 861.861907351762, + 'timestamp_carla': 861860, + 'timestamp_device': 1732458, + 'timestamp_stream': 861.861907351762, + 'transform': [array([-36.36468506, 68.31377411, -0.10426589]), + array([-3.79416980e-02, -1.30639145e+02, 1.55728338e-02])]} +{'AngularVelocity': array([-0.07423483, -0.0645762 , 2.9536798 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.780458450317383, + 'FR_Wheel_Angle': 33.41629409790039, + 'Location': array([-3.80363274e+01, 9.42186890e+01, 2.60115624e-03]), + 'Rotation': array([-2.35300008e-02, 7.18272705e+01, -4.39453162e-02]), + 'Velocity': array([-9.96705727e-04, 2.74124473e-01, -1.48086547e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3690.9658203125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7334.35791016, 10232.8359375 , 123.77804565]), + 'frame': 25330, + 'frame_number': 25330, + 'framesequence': 102016, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4401806890964508, + 'throttle_input': 0.17856107652187347, + 'timestamp': 861.8959043510258, + 'timestamp_carla': 861894, + 'timestamp_device': 1732499, + 'timestamp_stream': 861.8959043510258, + 'transform': [array([-36.46466064, 68.28404236, -0.10418095]), + array([-3.95877734e-02, -1.31061615e+02, 1.49991009e-02])]} +{'AngularVelocity': array([-0.06775032, -0.05181086, 3.03750801]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.221294403076172, + 'FR_Wheel_Angle': 35.45975875854492, + 'Location': array([-3.80334358e+01, 9.42687607e+01, 2.57433881e-03]), + 'Rotation': array([-2.18770951e-02, 7.23710022e+01, -4.22363319e-02]), + 'Velocity': array([-4.86706803e-03, 2.73621708e-01, 1.27520558e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3658.744873046875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7297.09130859, 10232.8359375 , 123.74436951]), + 'frame': 25331, + 'frame_number': 25331, + 'framesequence': 102019, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4687643349170685, + 'throttle_input': 0.17856107652187347, + 'timestamp': 861.9294714517891, + 'timestamp_carla': 861928, + 'timestamp_device': 1732524, + 'timestamp_stream': 861.9294714517891, + 'transform': [array([-36.56884766, 68.25117493, -0.10408553]), + array([-4.11450565e-02, -1.31510773e+02, 1.44185368e-02])]} +{'AngularVelocity': array([-0.06374013, -0.06034913, 3.3919096 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.18065643310547, + 'FR_Wheel_Angle': 38.112632751464844, + 'Location': array([-3.80326271e+01, 9.43178558e+01, 2.54111295e-03]), + 'Rotation': array([-2.08730567e-02, 7.29623718e+01, -4.20837365e-02]), + 'Velocity': array([-2.19456218e-02, 2.68014342e-01, 2.46047974e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3622.326171875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7254.45410156, 10232.8359375 , 123.69895935]), + 'frame': 25332, + 'frame_number': 25332, + 'framesequence': 102023, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4964873492717743, + 'throttle_input': 0.17856107652187347, + 'timestamp': 861.9614662490785, + 'timestamp_carla': 861960, + 'timestamp_device': 1732558, + 'timestamp_stream': 861.9614662490785, + 'transform': [array([-36.67333603, 68.21675873, -0.10400258]), + array([-4.27501500e-02, -1.31968765e+02, 1.39335943e-02])]} +{'AngularVelocity': array([0.02062629, 0.08028671, 3.93535924]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.131200790405273, + 'FR_Wheel_Angle': 37.730472564697266, + 'Location': array([-3.80322952e+01, 9.43669891e+01, 2.47042649e-03]), + 'Rotation': array([-1.91040374e-02, 7.35545197e+01, -3.93676758e-02]), + 'Velocity': array([-0.03117717, 0.29125416, -0.00081325]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3584.768798828125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7209.95214844, 10232.8359375 , 123.6541748 ]), + 'frame': 25333, + 'frame_number': 25333, + 'framesequence': 102028, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5258949995040894, + 'throttle_input': 0.17856107652187347, + 'timestamp': 861.9957505501807, + 'timestamp_carla': 861994, + 'timestamp_device': 1732599, + 'timestamp_stream': 861.9957505501807, + 'transform': [array([-36.79128647, 68.17625427, -0.10390601]), + array([-4.43210937e-02, -1.32494064e+02, 1.33052189e-02])]} +{'AngularVelocity': array([-0.05538913, -0.04736813, 3.54069805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.312137603759766, + 'FR_Wheel_Angle': 37.37601852416992, + 'Location': array([-3.80326653e+01, 9.44137650e+01, 2.45585432e-03]), + 'Rotation': array([-1.78267919e-02, 7.41185303e+01, -3.68041992e-02]), + 'Velocity': array([-2.38012355e-02, 2.64667362e-01, -1.48048392e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3580.939453125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7190.20556641, 10255.12207031, 123.62543488]), + 'frame': 25334, + 'frame_number': 25334, + 'framesequence': 102031, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5544419884681702, + 'throttle_input': 0.17856107652187347, + 'timestamp': 862.0279662497342, + 'timestamp_carla': 862027, + 'timestamp_device': 1732624, + 'timestamp_stream': 862.0279662497342, + 'transform': [array([-36.90774918, 68.13504791, -0.1038145 ]), + array([-4.59808297e-02, -1.33019699e+02, 1.27724642e-02])]} +{'AngularVelocity': array([-0.08462637, -0.08279543, 2.95010018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.386775970458984, + 'FR_Wheel_Angle': 37.58008575439453, + 'Location': array([-3.80332680e+01, 9.44602585e+01, 2.42587086e-03]), + 'Rotation': array([-1.68432463e-02, 7.46802979e+01, -3.44848596e-02]), + 'Velocity': array([-0.02297804, 0.24659246, -0.00036777]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3577.16259765625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7167.59375 , 10280.67285156, 123.58570862]), + 'frame': 25335, + 'frame_number': 25335, + 'framesequence': 102035, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.582165002822876, + 'throttle_input': 0.17856107652187347, + 'timestamp': 862.0622167512774, + 'timestamp_carla': 862061, + 'timestamp_device': 1732657, + 'timestamp_stream': 862.0622167512774, + 'transform': [array([-37.03776169, 68.087883 , -0.10371302]), + array([-4.75312844e-02, -1.33613525e+02, 1.21304244e-02])]} +{'AngularVelocity': array([-0.08098949, -0.07839472, 2.80002213]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.355104446411133, + 'FR_Wheel_Angle': 37.59901809692383, + 'Location': array([-3.80343895e+01, 9.45062485e+01, 2.39123334e-03]), + 'Rotation': array([-1.57504156e-02, 7.52382278e+01, -3.26538011e-02]), + 'Velocity': array([-2.54668854e-02, 2.42038012e-01, -1.68313971e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3610.198486328125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7171.47949219, 10330.94726562, 123.56227875]), + 'frame': 25336, + 'frame_number': 25336, + 'framesequence': 102039, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.17856107652187347, + 'timestamp': 862.0948644503951, + 'timestamp_carla': 862093, + 'timestamp_device': 1732691, + 'timestamp_stream': 862.0948644503951, + 'transform': [array([-37.16693878, 68.04064178, -0.10362361]), + array([-4.86172847e-02, -1.34208069e+02, 1.16591416e-02])]} +{'AngularVelocity': array([-0.06738693, -0.06528273, 3.02754474]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.35109519958496, + 'FR_Wheel_Angle': 37.598567962646484, + 'Location': array([-3.80359306e+01, 9.45517349e+01, 2.36159330e-03]), + 'Rotation': array([-1.45892836e-02, 7.57929382e+01, -3.09753399e-02]), + 'Velocity': array([-2.80727483e-02, 2.41788611e-01, 3.70883936e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3610.92138671875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7148.36474609, 10362.61328125, 123.52248383]), + 'frame': 25337, + 'frame_number': 25337, + 'framesequence': 102043, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.17856107652187347, + 'timestamp': 862.1284274496138, + 'timestamp_carla': 862127, + 'timestamp_device': 1732724, + 'timestamp_stream': 862.1284274496138, + 'transform': [array([-37.30300903, 67.99188232, -0.10356324]), + array([-4.80162278e-02, -1.34834518e+02, 1.14542339e-02])]} +{'AngularVelocity': array([-0.07188295, -0.07069416, 2.80424118]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.351280212402344, + 'FR_Wheel_Angle': 37.600467681884766, + 'Location': array([-3.80379181e+01, 9.45964432e+01, 2.33660685e-03]), + 'Rotation': array([-1.33393584e-02, 7.63360596e+01, -2.94189472e-02]), + 'Velocity': array([-3.00263818e-02, 2.39261866e-01, -2.71797171e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3612.26025390625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7125.18212891, 10394.37304688, 123.49477386]), + 'frame': 25338, + 'frame_number': 25338, + 'framesequence': 102047, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.589104950428009, + 'throttle_input': 0.17856107652187347, + 'timestamp': 862.1616850495338, + 'timestamp_carla': 862160, + 'timestamp_device': 1732757, + 'timestamp_stream': 862.1616850495338, + 'transform': [array([-37.43926239, 67.94521332, -0.10353776]), + array([-4.57144529e-02, -1.35458145e+02, 1.15976715e-02])]} +{'AngularVelocity': array([-0.08686497, -0.09022654, 2.68498254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.352609634399414, + 'FR_Wheel_Angle': 37.60590362548828, + 'Location': array([-3.80403442e+01, 9.46414566e+01, 2.28323927e-03]), + 'Rotation': array([-1.25129055e-02, 7.68792267e+01, -2.73742676e-02]), + 'Velocity': array([-0.03002626, 0.2261699 , -0.00044905]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3614.190673828125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7100.69970703, 10427.91210938, 123.48143768]), + 'frame': 25339, + 'frame_number': 25339, + 'framesequence': 102051, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5808466076850891, + 'throttle_input': 0.17062638700008392, + 'timestamp': 862.1956861503422, + 'timestamp_carla': 862194, + 'timestamp_device': 1732791, + 'timestamp_stream': 862.1956861503422, + 'transform': [array([-37.57950974, 67.89963531, -0.10352961]), + array([-4.25862260e-02, -1.36095261e+02, 1.18777063e-02])]} +{'AngularVelocity': array([-0.07830551, -0.08087046, 2.6802063 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.486095428466797, + 'FR_Wheel_Angle': 39.010902404785156, + 'Location': array([-3.80430984e+01, 9.46846161e+01, 2.26992602e-03]), + 'Rotation': array([-1.13517735e-02, 7.74048996e+01, -2.59704571e-02]), + 'Velocity': array([-3.27670984e-02, 2.27060735e-01, -1.69019695e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3616.529052734375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7076.26904297, 10461.38183594, 123.48889923]), + 'frame': 25340, + 'frame_number': 25340, + 'framesequence': 102056, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5844172835350037, + 'throttle_input': 0.16665904223918915, + 'timestamp': 862.230010651052, + 'timestamp_carla': 862229, + 'timestamp_device': 1732832, + 'timestamp_stream': 862.230010651052, + 'transform': [array([-37.72318268, 67.85477448, -0.10350995]), + array([-4.02229801e-02, -1.36745148e+02, 1.20279687e-02])]} +{'AngularVelocity': array([-0.06716999, -0.08007729, 2.93615723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.62755012512207, + 'FR_Wheel_Angle': 40.79582977294922, + 'Location': array([-3.80471687e+01, 9.47261963e+01, 2.25459086e-03]), + 'Rotation': array([-1.06209433e-02, 7.79541626e+01, -2.56347656e-02]), + 'Velocity': array([-4.36693914e-02, 2.23048434e-01, 3.46755987e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3591.7841796875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7032.1484375 , 10475.828125 , 123.49803162]), + 'frame': 25341, + 'frame_number': 25341, + 'framesequence': 102059, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5939207673072815, + 'throttle_input': 0.16665904223918915, + 'timestamp': 862.2621737495065, + 'timestamp_carla': 862261, + 'timestamp_device': 1732857, + 'timestamp_stream': 862.2621737495065, + 'transform': [array([-37.86064148, 67.81308746, -0.1034841 ]), + array([-3.93896997e-02, -1.37366333e+02, 1.20621230e-02])]} +{'AngularVelocity': array([-0.07033586, -0.08224297, 2.95569897]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.86259651184082, + 'FR_Wheel_Angle': 41.793182373046875, + 'Location': array([-3.80519142e+01, 9.47683105e+01, 2.21739756e-03]), + 'Rotation': array([-9.61690582e-03, 7.85213394e+01, -2.36206036e-02]), + 'Velocity': array([-4.53153662e-02, 2.17163727e-01, 8.58497588e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3594.4208984375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7006.29882812, 10510.16796875, 123.50536346]), + 'frame': 25342, + 'frame_number': 25342, + 'framesequence': 102063, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.16269169747829437, + 'timestamp': 862.2950374521315, + 'timestamp_carla': 862294, + 'timestamp_device': 1732891, + 'timestamp_stream': 862.2950374521315, + 'transform': [array([-38.00406647, 67.77078247, -0.10345063]), + array([-3.90618481e-02, -1.38014053e+02, 1.19664967e-02])]} +{'AngularVelocity': array([-0.07246624, -0.08521312, 2.78048992]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.86440086364746, + 'FR_Wheel_Angle': 41.79856491088867, + 'Location': array([-3.80582390e+01, 9.48177414e+01, 2.18344689e-03]), + 'Rotation': array([-8.48309416e-03, 7.91964264e+01, -2.15148889e-02]), + 'Velocity': array([-4.68433313e-02, 2.10983515e-01, 1.95026387e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3633.7568359375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7006.11621094, 10569.77929688, 123.51631165]), + 'frame': 25343, + 'frame_number': 25343, + 'framesequence': 102067, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.16269169747829437, + 'timestamp': 862.328002050519, + 'timestamp_carla': 862326, + 'timestamp_device': 1732924, + 'timestamp_stream': 862.328002050519, + 'transform': [array([-38.15027237, 67.72924805, -0.10340937]), + array([-3.85427549e-02, -1.38672943e+02, 1.18503859e-02])]} +{'AngularVelocity': array([-0.07444829, -0.09063932, 2.74409723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.864944458007812, + 'FR_Wheel_Angle': 41.80054473876953, + 'Location': array([-3.80638657e+01, 9.48581161e+01, 2.16265675e-03]), + 'Rotation': array([-7.50637753e-03, 7.97484055e+01, -2.00500451e-02]), + 'Velocity': array([-4.80168611e-02, 2.08046451e-01, -1.19104385e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3745.665283203125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7052.28417969, 10684.89355469, 123.53361511]), + 'frame': 25344, + 'frame_number': 25344, + 'framesequence': 102072, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.16269169747829437, + 'timestamp': 862.3622750490904, + 'timestamp_carla': 862361, + 'timestamp_device': 1732966, + 'timestamp_stream': 862.3622750490904, + 'transform': [array([-38.30438614, 67.68730927, -0.10336018]), + array([-3.76958102e-02, -1.39365433e+02, 1.16932886e-02])]} +{'AngularVelocity': array([-0.07917076, -0.09593429, 2.61081743]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.867862701416016, + 'FR_Wheel_Angle': 41.798858642578125, + 'Location': array([-3.80698433e+01, 9.48982925e+01, 2.12901109e-03]), + 'Rotation': array([-6.71407580e-03, 8.02978897e+01, -1.84936542e-02]), + 'Velocity': array([-4.85254414e-02, 2.01156706e-01, -1.68266299e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3794.03564453125, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7053.69335938, 10754.20117188, 123.53566742]), + 'frame': 25345, + 'frame_number': 25345, + 'framesequence': 102076, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.1587243527173996, + 'timestamp': 862.3963761515915, + 'timestamp_carla': 862395, + 'timestamp_device': 1732999, + 'timestamp_stream': 862.3963761515915, + 'transform': [array([-38.45965576, 67.64704895, -0.10330559]), + array([-3.68625298e-02, -1.40060898e+02, 1.15361968e-02])]} +{'AngularVelocity': array([-0.06332592, -0.0803172 , 3.07412863]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.855113983154297, + 'FR_Wheel_Angle': 41.779109954833984, + 'Location': array([-3.80776825e+01, 9.49470062e+01, 2.10532174e-03]), + 'Rotation': array([-4.63769818e-03, 8.09781952e+01, -1.86767541e-02]), + 'Velocity': array([-0.05853365, 0.22812 , -0.00028615]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3846.960693359375, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7055.21533203, 10829.02539062, 123.53439331]), + 'frame': 25346, + 'frame_number': 25346, + 'framesequence': 102079, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.15475699305534363, + 'timestamp': 862.4295234493911, + 'timestamp_carla': 862428, + 'timestamp_device': 1733024, + 'timestamp_stream': 862.4295234493911, + 'transform': [array([-38.61222076, 67.6095047 , -0.10325684]), + array([-3.62204909e-02, -1.40742126e+02, 1.14200842e-02])]} +{'AngularVelocity': array([-0.07428335, -0.09457059, 3.41540527]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.841007232666016, + 'FR_Wheel_Angle': 41.75911331176758, + 'Location': array([-3.80877075e+01, 9.50036621e+01, 2.03562737e-03]), + 'Rotation': array([-2.74573592e-03, 8.17605667e+01, -1.78833008e-02]), + 'Velocity': array([-0.06977565, 0.25625411, -0.00056002]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3902.36279296875, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7056.78808594, 10906.3203125 , 123.53394318]), + 'frame': 25347, + 'frame_number': 25347, + 'framesequence': 102084, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5983520150184631, + 'throttle_input': 0.14682230353355408, + 'timestamp': 862.4625942520797, + 'timestamp_carla': 862461, + 'timestamp_device': 1733066, + 'timestamp_stream': 862.4625942520797, + 'transform': [array([-38.76585388, 67.57378387, -0.10321339]), + array([-3.55579630e-02, -1.41425781e+02, 1.13244588e-02])]} +{'AngularVelocity': array([-0.04660998, -0.14233182, 3.40590215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.832483291625977, + 'FR_Wheel_Angle': 41.74504852294922, + 'Location': array([-3.80992126e+01, 9.50656586e+01, 2.03013420e-03]), + 'Rotation': array([-4.23471705e-04, 8.26023865e+01, -1.64489765e-02]), + 'Velocity': array([-7.72899538e-02, 3.18787932e-01, -1.07364649e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3958.93212890625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7058.37304688, 10984.25195312, 123.53727722]), + 'frame': 25348, + 'frame_number': 25348, + 'framesequence': 102088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.598370373249054, + 'throttle_input': 0.13888761401176453, + 'timestamp': 862.4967659525573, + 'timestamp_carla': 862495, + 'timestamp_device': 1733099, + 'timestamp_stream': 862.4967659525573, + 'transform': [array([-38.92620087, 67.53855133, -0.10315667]), + array([-3.48612852e-02, -1.42137177e+02, 1.11332126e-02])]} +{'AngularVelocity': array([-0.03088904, 0.02254217, 4.37308359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.834121704101562, + 'FR_Wheel_Angle': 41.74025344848633, + 'Location': array([-3.81102676e+01, 9.51205673e+01, 2.00366019e-03]), + 'Rotation': array([-1.03818870e-03, 8.33522873e+01, -1.38244601e-02]), + 'Velocity': array([-0.09802549, 0.31418374, -0.00034093]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3995.67919921875, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7046.03125 , 11047.25488281, 123.5377655 ]), + 'frame': 25349, + 'frame_number': 25349, + 'framesequence': 102091, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5994507074356079, + 'throttle_input': 0.12300297617912292, + 'timestamp': 862.5290917493403, + 'timestamp_carla': 862528, + 'timestamp_device': 1733124, + 'timestamp_stream': 862.5290917493403, + 'transform': [array([-39.07928848, 67.5068512 , -0.10309132]), + array([-3.45334336e-02, -1.42814682e+02, 1.09351370e-02])]} +{'AngularVelocity': array([-0.05090646, -0.04488888, 4.64575958]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.806049346923828, + 'FR_Wheel_Angle': 41.69414520263672, + 'Location': array([-3.81227455e+01, 9.51793747e+01, 1.97405810e-03]), + 'Rotation': array([ 9.35735879e-04, 8.41400681e+01, -1.34887677e-02]), + 'Velocity': array([-1.07091092e-01, 3.40740949e-01, -1.30939479e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3983.97265625, + 'focus_actor_name': 'BP_Block05_70', + 'focus_actor_pt': array([-7001.37109375, 11073.51269531, 123.52098846]), + 'frame': 25350, + 'frame_number': 25350, + 'framesequence': 102096, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.10713358968496323, + 'timestamp': 862.5627458505332, + 'timestamp_carla': 862561, + 'timestamp_device': 1733166, + 'timestamp_stream': 862.5627458505332, + 'transform': [array([-39.24008179, 67.47548676, -0.10301297]), + array([-3.40894721e-02, -1.43524750e+02, 1.06414389e-02])]} +{'AngularVelocity': array([-0.02461255, 0.03118325, 5.44782972]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.802579879760742, + 'FR_Wheel_Angle': 41.68885040283203, + 'Location': array([-3.81409225e+01, 9.52578812e+01, 1.92938803e-03]), + 'Rotation': array([ 2.39739637e-03, 8.52193680e+01, -1.15356436e-02]), + 'Velocity': array([-1.31817907e-01, 3.85861725e-01, -2.58388522e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4137.2880859375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7058.04736328, 11228.9453125 , 123.53726196]), + 'frame': 25351, + 'frame_number': 25351, + 'framesequence': 102100, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.09126421064138412, + 'timestamp': 862.5964332520962, + 'timestamp_carla': 862595, + 'timestamp_device': 1733199, + 'timestamp_stream': 862.5964332520962, + 'transform': [array([-39.40218735, 67.44584656, -0.10261048]), + array([-3.10158879e-02, -1.44239044e+02, 9.15928930e-03])]} +{'AngularVelocity': array([4.44295863e-03, 5.85731231e-02, 6.19318247e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.797286987304688, + 'FR_Wheel_Angle': 41.69124984741211, + 'Location': array([-3.81572571e+01, 9.53245773e+01, 1.92431442e-03]), + 'Rotation': array([ 2.90966034e-03, 8.61249619e+01, -9.36889648e-03]), + 'Velocity': array([-1.44064546e-01, 4.07612711e-01, 1.13396643e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4201.0341796875, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7056.28173828, 11315.76367188, 123.52735138]), + 'frame': 25352, + 'frame_number': 25352, + 'framesequence': 102104, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0634927898645401, + 'timestamp': 862.6304016523063, + 'timestamp_carla': 862629, + 'timestamp_device': 1733232, + 'timestamp_stream': 862.6304016523063, + 'transform': [array([-39.56644058, 67.41784668, -0.10204725]), + array([-2.69519258e-02, -1.44961334e+02, 7.03509944e-03])]} +{'AngularVelocity': array([-0.04490381, -0.09154557, 5.20793676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.792245864868164, + 'FR_Wheel_Angle': 41.68389129638672, + 'Location': array([-3.81754608e+01, 9.53927536e+01, 1.87087059e-03]), + 'Rotation': array([ 3.30581143e-03, 8.70508881e+01, -6.59179641e-03]), + 'Velocity': array([-1.36607602e-01, 3.83944780e-01, -7.78198228e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2675.840087890625, + 'focus_actor_name': 'AmericanLights_Town04_33_TrafficLight', + 'focus_actor_pt': array([-6123.96582031, 10113.86230469, 123.17004395]), + 'frame': 25353, + 'frame_number': 25353, + 'framesequence': 102108, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0476234070956707, + 'timestamp': 862.6657675504684, + 'timestamp_carla': 862664, + 'timestamp_device': 1733266, + 'timestamp_stream': 862.6657675504684, + 'transform': [array([-39.73809814, 67.39064026, -0.10136774]), + array([-2.21912842e-02, -1.45714828e+02, 4.40547522e-03])]} +{'AngularVelocity': array([-0.01884854, -0.10546219, 4.58583021]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.780912399291992, + 'FR_Wheel_Angle': 41.66733169555664, + 'Location': array([-3.81951027e+01, 9.54625931e+01, 1.84134475e-03]), + 'Rotation': array([ 5.38218860e-03, 8.79940643e+01, -5.21850539e-03]), + 'Velocity': array([-1.47178859e-01, 4.19086576e-01, -5.19466375e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4338.87646484375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7052.53564453, 11499.96875 , 123.26789856]), + 'frame': 25354, + 'frame_number': 25354, + 'framesequence': 102112, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.027771420776844025, + 'timestamp': 862.6995287500322, + 'timestamp_carla': 862698, + 'timestamp_device': 1733299, + 'timestamp_stream': 862.6995287500322, + 'transform': [array([-39.90201569, 67.366745 , -0.10067669]), + array([-1.76628679e-02, -1.46433075e+02, 1.77585136e-03])]} +{'AngularVelocity': array([-0.01676469, -0.08161145, 5.21257877]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.789060592651367, + 'FR_Wheel_Angle': 41.65376663208008, + 'Location': array([-3.82167892e+01, 9.55347214e+01, 1.80335040e-03]), + 'Rotation': array([ 5.90128312e-03, 8.89665451e+01, -3.35693313e-03]), + 'Velocity': array([-1.60122946e-01, 4.19900537e-01, -1.52282708e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4416.30224609375, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7050.47021484, 11601.53320312, 123.06507874]), + 'frame': 25355, + 'frame_number': 25355, + 'framesequence': 102116, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.7305326499045, + 'timestamp_carla': 862729, + 'timestamp_device': 1733332, + 'timestamp_stream': 862.7305326499045, + 'transform': [array([-40.05197525, 67.34682465, -0.10002948]), + array([-1.35920756e-02, -1.47089066e+02, -6.40866521e-04])]} +{'AngularVelocity': array([-1.48758711e-03, -1.76608972e-02, 6.35889673e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.771150588989258, + 'FR_Wheel_Angle': 41.64548873901367, + 'Location': array([-3.82400780e+01, 9.56085587e+01, 1.76558492e-03]), + 'Rotation': array([ 7.60883046e-03, 8.99836426e+01, -2.77709961e-03]), + 'Velocity': array([-1.80858299e-01, 4.49218243e-01, -2.41975780e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4417.12841796875, + 'focus_actor_name': 'BP_Block05_67', + 'focus_actor_pt': array([-7006.11669922, 11638.02929688, 122.85468292]), + 'frame': 25356, + 'frame_number': 25356, + 'framesequence': 102120, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.7643310502172, + 'timestamp_carla': 862763, + 'timestamp_device': 1733366, + 'timestamp_stream': 862.7643310502172, + 'transform': [array([-40.21509552, 67.32698822, -0.09932819]), + array([-8.84509459e-03, -1.47801727e+02, -3.35693220e-03])]} +{'AngularVelocity': array([-0.02990799, -0.12565909, 6.59902716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.770048141479492, + 'FR_Wheel_Angle': 41.63910675048828, + 'Location': array([-3.82663574e+01, 9.56866989e+01, 1.72518729e-03]), + 'Rotation': array([ 8.22354760e-03, 9.10694504e+01, -7.62939279e-04]), + 'Velocity': array([-0.18371251, 0.44151324, -0.00058952]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4835.1455078125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7191.91748047, 12021.1875 , 122.65802002]), + 'frame': 25357, + 'frame_number': 25357, + 'framesequence': 102124, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.7989531494677, + 'timestamp_carla': 862798, + 'timestamp_device': 1733399, + 'timestamp_stream': 862.7989531494677, + 'transform': [array([-40.38175201, 67.30856323, -0.09859834]), + array([-3.92735843e-03, -1.48529099e+02, -6.19506650e-03])]} +{'AngularVelocity': array([0.02479153, 0.06136113, 6.79000616]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.772014617919922, + 'FR_Wheel_Angle': 41.64365005493164, + 'Location': array([-3.82941856e+01, 9.57652130e+01, 1.72049517e-03]), + 'Rotation': array([ 9.85596236e-03, 9.21689072e+01, -2.74658290e-04]), + 'Velocity': array([-0.22605763, 0.49614802, 0.00062786]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4886.27099609375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7169.46582031, 12101.70507812, 122.41675568]), + 'frame': 25358, + 'frame_number': 25358, + 'framesequence': 102128, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.8299399502575, + 'timestamp_carla': 862829, + 'timestamp_device': 1733432, + 'timestamp_stream': 862.8299399502575, + 'transform': [array([-40.52974701, 67.29408264, -0.09796849]), + array([ 1.57094342e-04, -1.49174179e+02, -8.54492001e-03])]} +{'AngularVelocity': array([0.04636849, 0.08793803, 6.99372244]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78090476989746, + 'FR_Wheel_Angle': 41.65745544433594, + 'Location': array([-3.83245659e+01, 9.58450775e+01, 1.70836446e-03]), + 'Rotation': array([9.35052801e-03, 9.32751236e+01, 9.81509918e-04]), + 'Velocity': array([-2.38599822e-01, 5.03181636e-01, -2.11391438e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4907.44287109375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7128.76855469, 12157.45996094, 122.16213226]), + 'frame': 25359, + 'frame_number': 25359, + 'framesequence': 102132, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5998901724815369, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.8647254519165, + 'timestamp_carla': 862863, + 'timestamp_device': 1733466, + 'timestamp_stream': 862.8647254519165, + 'transform': [array([-40.69486618, 67.27976227, -0.09729559]), + array([ 4.97920765e-03, -1.49893311e+02, -1.11694336e-02])]} +{'AngularVelocity': array([0.04756214, 0.08377714, 7.03042126]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.77937126159668, + 'FR_Wheel_Angle': 41.65163040161133, + 'Location': array([-3.83567200e+01, 9.59235458e+01, 1.71957968e-03]), + 'Rotation': array([9.17977374e-03, 9.43484268e+01, 1.12615910e-03]), + 'Velocity': array([-2.49978960e-01, 5.01927078e-01, 1.67880062e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4927.103515625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7092.34423828, 12207.35742188, 121.95217896]), + 'frame': 25360, + 'frame_number': 25360, + 'framesequence': 102136, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5868343710899353, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.9017630517483, + 'timestamp_carla': 862900, + 'timestamp_device': 1733499, + 'timestamp_stream': 862.9017630517483, + 'transform': [array([-40.86794662, 67.26737976, -0.09660412]), + array([ 1.10785663e-02, -1.50644989e+02, -1.37939453e-02])]} +{'AngularVelocity': array([0.04668212, 0.08844916, 7.08944082]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.775175094604492, + 'FR_Wheel_Angle': 41.682044982910156, + 'Location': array([-3.83979645e+01, 9.60187607e+01, 1.71137811e-03]), + 'Rotation': array([9.17977374e-03, 9.56589203e+01, 1.24663161e-03]), + 'Velocity': array([-2.64030099e-01, 5.01940846e-01, 4.79888913e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4920.52978515625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7036.56054688, 12237.96484375, 121.71691132]), + 'frame': 25361, + 'frame_number': 25361, + 'framesequence': 102140, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.563304603099823, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.9367629513144, + 'timestamp_carla': 862935, + 'timestamp_device': 1733532, + 'timestamp_stream': 862.9367629513144, + 'transform': [array([-41.02615738, 67.25965881, -0.09600306]), + array([ 1.78541131e-02, -1.51327911e+02, -1.58081092e-02])]} +{'AngularVelocity': array([ 2.2703805 , -1.99899781, 4.85224104]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.843786239624023, + 'FR_Wheel_Angle': 41.72686767578125, + 'Location': array([-3.84052620e+01, 9.60883408e+01, 2.62131523e-02]), + 'Rotation': array([ 1.06975102, 96.37008667, 2.19757366]), + 'Velocity': array([-0.17193952, 0.3344636 , 0.09567077]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4971.1025390625, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7006.11230469, 12319.26660156, 121.46710968]), + 'frame': 25362, + 'frame_number': 25362, + 'framesequence': 102145, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5389508008956909, + 'throttle_input': 0.019836727529764175, + 'timestamp': 862.9715739488602, + 'timestamp_carla': 862970, + 'timestamp_device': 1733574, + 'timestamp_stream': 862.9715739488602, + 'transform': [array([-41.17713928, 67.25614166, -0.09546462]), + array([ 2.51760762e-02, -1.51974686e+02, -1.74865704e-02])]} +{'AngularVelocity': array([ 1.12501812, -1.98269308, 4.69027805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81569480895996, + 'FR_Wheel_Angle': 41.71343231201172, + 'Location': array([-3.84313583e+01, 9.61463623e+01, 3.41031663e-02]), + 'Rotation': array([ 1.31334972, 97.21387482, 2.65707064]), + 'Velocity': array([-0.18789816, 0.30626407, 0.0277985 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5177.162109375, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7053.92382812, 12533.69628906, 121.22470856]), + 'frame': 25363, + 'frame_number': 25363, + 'framesequence': 102149, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5169957876205444, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.0052182488143, + 'timestamp_carla': 863004, + 'timestamp_device': 1733607, + 'timestamp_stream': 863.0052182488143, + 'transform': [array([-41.31705475, 67.25644684, -0.0949904 ]), + array([ 3.23136225e-02, -1.52569458e+02, -1.88598689e-02])]} +{'AngularVelocity': array([-0.33691964, -0.13296154, 5.03690386]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.812118530273438, + 'FR_Wheel_Angle': 41.72050476074219, + 'Location': array([-3.84589386e+01, 9.62038422e+01, 3.40562090e-02]), + 'Rotation': array([ 1.30498266, 98.03152466, 2.63458419]), + 'Velocity': array([-0.17450321, 0.32284954, -0.01515721]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5287.5986328125, + 'focus_actor_name': 'BP_Block05_69', + 'focus_actor_pt': array([-7055.15478516, 12663.78710938, 121.02936554]), + 'frame': 25364, + 'frame_number': 25364, + 'framesequence': 102153, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5148167610168457, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.0393650494516, + 'timestamp_carla': 863038, + 'timestamp_device': 1733641, + 'timestamp_stream': 863.0393650494516, + 'transform': [array([-41.45573807, 67.25904846, -0.09441677]), + array([ 3.58584896e-02, -1.53156921e+02, -2.11486835e-02])]} +{'AngularVelocity': array([ 0.58366156, -0.71213686, 5.67842817]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81998634338379, + 'FR_Wheel_Angle': 41.71296310424805, + 'Location': array([-3.84938774e+01, 9.62751617e+01, 3.52505110e-02]), + 'Rotation': array([ 1.39987457, 99.07524109, 2.86871839]), + 'Velocity': array([-0.23487754, 0.37495416, 0.01221331]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3332.509521484375, + 'focus_actor_name': 'BP_StreetLight_doble12_42', + 'focus_actor_pt': array([-6106.67626953, 10958.72265625, 121.53701782]), + 'frame': 25365, + 'frame_number': 25365, + 'framesequence': 102156, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5239723324775696, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.0702726505697, + 'timestamp_carla': 863069, + 'timestamp_device': 1733666, + 'timestamp_stream': 863.0702726505697, + 'transform': [array([-41.58027267, 67.26249695, -0.09378424]), + array([ 3.52779254e-02, -1.53684830e+02, -2.41088886e-02])]} +{'AngularVelocity': array([ 0.08926719, -0.17033912, 6.56862259]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79218864440918, + 'FR_Wheel_Angle': 41.69110870361328, + 'Location': array([-3.85322227e+01, 9.63482895e+01, 3.64260487e-02]), + 'Rotation': array([ 1.44659305, 100.19265747, 2.96858692]), + 'Velocity': array([-0.25049841, 0.36269036, 0.00342116]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5410.85205078125, + 'focus_actor_name': 'BP_Block05_66', + 'focus_actor_pt': array([-7015.50488281, 12833.41113281, 120.62876129]), + 'frame': 25366, + 'frame_number': 25366, + 'framesequence': 102160, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5362957119941711, + 'throttle_input': 0.043656062334775925, + 'timestamp': 863.1025052517653, + 'timestamp_carla': 863101, + 'timestamp_device': 1733699, + 'timestamp_stream': 863.1025052517653, + 'transform': [array([-41.71062469, 67.26654816, -0.09308229]), + array([ 3.28327194e-02, -1.54239105e+02, -2.77099684e-02])]} +{'AngularVelocity': array([ 0.14298621, -0.13311617, 4.69432116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78974723815918, + 'FR_Wheel_Angle': 41.679935455322266, + 'Location': array([-3.85675468e+01, 9.64123535e+01, 3.67197059e-02]), + 'Rotation': array([ 1.46207702, 101.13331604, 3.00272775]), + 'Velocity': array([-0.25106749, 0.38607487, 0.00131947]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8842.5888671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8492.88476562, 15936.04785156, 118.90206146]), + 'frame': 25367, + 'frame_number': 25367, + 'framesequence': 102164, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.547465443611145, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.1327159516513, + 'timestamp_carla': 863131, + 'timestamp_device': 1733732, + 'timestamp_stream': 863.1327159516513, + 'transform': [array([-41.83350372, 67.27072906, -0.09240968]), + array([ 2.97591332e-02, -1.54763519e+02, -3.12194787e-02])]} +{'AngularVelocity': array([0.06071777, 0.02228111, 6.25894594]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79286766052246, + 'FR_Wheel_Angle': 41.66702651977539, + 'Location': array([-3.86049728e+01, 9.64782333e+01, 3.68216708e-02]), + 'Rotation': array([ 1.4661274 , 102.12343597, 3.01594949]), + 'Velocity': array([-2.82446027e-01, 4.13525581e-01, 3.37781908e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8808.701171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8401.90820312, 15947.44042969, 118.35766602]), + 'frame': 25368, + 'frame_number': 25368, + 'framesequence': 102168, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5522812604904175, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.1636919490993, + 'timestamp_carla': 863162, + 'timestamp_device': 1733766, + 'timestamp_stream': 863.1636919490993, + 'transform': [array([-41.95970535, 67.27566528, -0.091741 ]), + array([ 2.69177742e-02, -1.55303528e+02, -3.47595252e-02])]} +{'AngularVelocity': array([-0.07850579, 0.04731899, 6.65112543]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78928565979004, + 'FR_Wheel_Angle': 41.643123626708984, + 'Location': array([-3.86545944e+01, 9.65612106e+01, 3.68394479e-02]), + 'Rotation': array([ 1.46690595, 103.37245178, 3.02131081]), + 'Velocity': array([-2.88291246e-01, 3.81374389e-01, 9.05895213e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8733.13671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8297.41015625, 15917.8515625 , 117.85313416]), + 'frame': 25369, + 'frame_number': 25369, + 'framesequence': 102172, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5497360229492188, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.1965809501708, + 'timestamp_carla': 863195, + 'timestamp_device': 1733799, + 'timestamp_stream': 863.1965809501708, + 'transform': [array([-42.09326553, 67.28190613, -0.09105057]), + array([ 2.49916613e-02, -1.55875626e+02, -3.83911058e-02])]} +{'AngularVelocity': array([-0.06658959, -0.0348075 , 6.85365105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.788196563720703, + 'FR_Wheel_Angle': 41.674346923828125, + 'Location': array([-3.87039871e+01, 9.66400528e+01, 3.68519612e-02]), + 'Rotation': array([ 1.46557415, 104.58432007, 3.02454209]), + 'Velocity': array([-0.27576479, 0.37335697, -0.00038972]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8680.5087890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8201.24902344, 15908.89941406, 117.34099579]), + 'frame': 25370, + 'frame_number': 25370, + 'framesequence': 102175, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5442426800727844, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.2288906499743, + 'timestamp_carla': 863227, + 'timestamp_device': 1733824, + 'timestamp_stream': 863.2288906499743, + 'transform': [array([-42.22301483, 67.28942108, -0.09039942]), + array([ 2.39261519e-02, -1.56431335e+02, -4.17175330e-02])]} +{'AngularVelocity': array([0.07622924, 0.03641771, 5.31891441]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.796693801879883, + 'FR_Wheel_Angle': 41.68428039550781, + 'Location': array([-3.87458839e+01, 9.67035522e+01, 3.68456654e-02]), + 'Rotation': array([ 1.46690595, 105.55690002, 3.02474093]), + 'Velocity': array([-2.92987406e-01, 3.84181440e-01, -2.76794424e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8645.0947265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-8108.26806641, 15916.74121094, 116.80529022]), + 'frame': 25371, + 'frame_number': 25371, + 'framesequence': 102180, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538328230381012, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.2633374519646, + 'timestamp_carla': 863262, + 'timestamp_device': 1733866, + 'timestamp_stream': 863.2633374519646, + 'transform': [array([-42.35960007, 67.29896545, -0.08973259]), + array([ 2.34343782e-02, -1.57015869e+02, -4.51355129e-02])]} +{'AngularVelocity': array([-0.07146005, -0.06570968, 5.83567381]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.78034210205078, + 'FR_Wheel_Angle': 41.654693603515625, + 'Location': array([-3.87882614e+01, 9.67655716e+01, 3.68835479e-02]), + 'Rotation': array([ 1.46277368, 106.55368805, 3.02869344]), + 'Velocity': array([-0.27158895, 0.33398294, 0.00045691]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8562.921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7999.09082031, 15879.5625 , 116.35454559]), + 'frame': 25372, + 'frame_number': 25372, + 'framesequence': 102184, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5341715812683105, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.2966093495488, + 'timestamp_carla': 863295, + 'timestamp_device': 1733899, + 'timestamp_stream': 863.2966093495488, + 'transform': [array([-42.48971558, 67.30968475, -0.08910065]), + array([ 2.29494348e-02, -1.57572433e+02, -4.83093299e-02])]} +{'AngularVelocity': array([ 0.11471777, -0.09318916, 4.92104197]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.786495208740234, + 'FR_Wheel_Angle': 41.68529510498047, + 'Location': array([-3.88315964e+01, 9.68273010e+01, 3.68646272e-02]), + 'Rotation': array([ 1.46437883, 107.55088806, 3.02563167]), + 'Velocity': array([-2.79068857e-01, 3.57480586e-01, -3.23724729e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 9171.904296875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-8157. , 16479.21289062, 115.35319519]), + 'frame': 25373, + 'frame_number': 25373, + 'framesequence': 102187, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5354899764060974, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.3286731503904, + 'timestamp_carla': 863327, + 'timestamp_device': 1733924, + 'timestamp_stream': 863.3286731503904, + 'transform': [array([-42.61373138, 67.32130432, -0.08850718]), + array([ 2.20615100e-02, -1.58103180e+02, -5.13000526e-02])]} +{'AngularVelocity': array([ 0.06440548, -0.07891601, 6.13363647]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.800138473510742, + 'FR_Wheel_Angle': 41.69878005981445, + 'Location': array([-3.88758240e+01, 9.68873138e+01, 3.68618406e-02]), + 'Rotation': array([ 1.46521211, 108.53166962, 3.02492142]), + 'Velocity': array([-3.00617337e-01, 3.60601157e-01, -3.47232817e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8440.779296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7796.18847656, 15842.09667969, 115.45318604]), + 'frame': 25374, + 'frame_number': 25374, + 'framesequence': 102192, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538328230381012, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.3645173497498, + 'timestamp_carla': 863363, + 'timestamp_device': 1733966, + 'timestamp_stream': 863.3645173497498, + 'transform': [array([-42.7502861 , 67.33569336, -0.08783697]), + array([ 2.10301522e-02, -1.58688293e+02, -5.48095666e-02])]} +{'AngularVelocity': array([-0.06004764, 0.01040791, 6.22387457]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.791065216064453, + 'FR_Wheel_Angle': 41.67237091064453, + 'Location': array([-3.89198418e+01, 9.69451828e+01, 3.68634798e-02]), + 'Rotation': array([ 1.46547842, 109.48465729, 3.02577877]), + 'Velocity': array([-2.89701015e-01, 3.23512256e-01, 2.63681402e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8403.7451171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7710.23632812, 15841.3671875 , 115.03734589]), + 'frame': 25375, + 'frame_number': 25375, + 'framesequence': 102196, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5415875911712646, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.3967199511826, + 'timestamp_carla': 863395, + 'timestamp_device': 1733999, + 'timestamp_stream': 863.3967199511826, + 'transform': [array([-42.87321854, 67.34931183, -0.08722446]), + array([ 1.96163021e-02, -1.59216095e+02, -5.78918383e-02])]} +{'AngularVelocity': array([ 0.06905442, -0.10915697, 5.04915905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.795774459838867, + 'FR_Wheel_Angle': 41.69567108154297, + 'Location': array([-3.89645386e+01, 9.70021744e+01, 3.68534103e-02]), + 'Rotation': array([ 1.46784854, 110.41464996, 3.0271275 ]), + 'Velocity': array([-2.90674359e-01, 3.22305202e-01, -1.64985659e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8327.380859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7602.93701172, 15806.41503906, 114.58531952]), + 'frame': 25376, + 'frame_number': 25376, + 'framesequence': 102199, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5423017144203186, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.4296910502017, + 'timestamp_carla': 863428, + 'timestamp_device': 1734024, + 'timestamp_stream': 863.4296910502017, + 'transform': [array([-42.99883652, 67.36416626, -0.08662865]), + array([ 1.83117352e-02, -1.59756210e+02, -6.09435998e-02])]} +{'AngularVelocity': array([-0.08837032, -0.03000248, 6.15628576]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.814977645874023, + 'FR_Wheel_Angle': 41.704593658447266, + 'Location': array([-3.90078201e+01, 9.70557022e+01, 3.68388779e-02]), + 'Rotation': array([ 1.46487057, 111.33359528, 3.02649021]), + 'Velocity': array([-0.26799005, 0.28357503, -0.00065673]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8270.3193359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7511.27050781, 15784.70507812, 114.18856812]), + 'frame': 25377, + 'frame_number': 25377, + 'framesequence': 102204, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5411298274993896, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.4627002514899, + 'timestamp_carla': 863461, + 'timestamp_device': 1734066, + 'timestamp_stream': 863.4627002514899, + 'transform': [array([-43.12392426, 67.38007355, -0.08604844]), + array([ 1.72462258e-02, -1.60294693e+02, -6.39038086e-02])]} +{'AngularVelocity': array([0.02530218, 0.16139954, 5.87049007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.820964813232422, + 'FR_Wheel_Angle': 41.73974609375, + 'Location': array([-3.90502396e+01, 9.71065521e+01, 3.68482992e-02]), + 'Rotation': array([ 1.46769142, 112.18576813, 3.02511287]), + 'Velocity': array([-3.18944037e-01, 3.23544294e-01, 7.42530829e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8234.607421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7426.02978516, 15782.67773438, 113.778862 ]), + 'frame': 25378, + 'frame_number': 25378, + 'framesequence': 102208, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.539335310459137, + 'throttle_input': 0.0476234070956707, + 'timestamp': 863.4964610524476, + 'timestamp_carla': 863495, + 'timestamp_device': 1734099, + 'timestamp_stream': 863.4964610524476, + 'transform': [array([-43.25094604, 67.39744568, -0.08546216]), + array([ 1.64197739e-02, -1.60842010e+02, -6.68945238e-02])]} +{'AngularVelocity': array([-0.09157247, 0.05477728, 5.13278055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82968521118164, + 'FR_Wheel_Angle': 41.74742126464844, + 'Location': array([-3.90912323e+01, 9.71542969e+01, 3.68617661e-02]), + 'Rotation': array([ 1.46505499, 113.01931763, 3.02407765]), + 'Velocity': array([-2.68947691e-01, 2.55211085e-01, 5.81264467e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8140.88134765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7321.78320312, 15725.01757812, 113.45108795]), + 'frame': 25379, + 'frame_number': 25379, + 'framesequence': 102211, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.538694441318512, + 'throttle_input': 0.0238040741533041, + 'timestamp': 863.528758648783, + 'timestamp_carla': 863527, + 'timestamp_device': 1734124, + 'timestamp_stream': 863.528758648783, + 'transform': [array([-43.37135696, 67.41517639, -0.0849011 ]), + array([ 1.55933211e-02, -1.61361420e+02, -6.97021410e-02])]} +{'AngularVelocity': array([-0.02875632, -0.0722328 , 4.39728594]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.824655532836914, + 'FR_Wheel_Angle': 41.741390228271484, + 'Location': array([-3.91405640e+01, 9.72096558e+01, 3.68866362e-02]), + 'Rotation': array([ 1.46710408, 113.99791718, 3.0218935 ]), + 'Velocity': array([-2.38361165e-01, 2.30371207e-01, 1.01232523e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 15198.7802734375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-9564.72265625, 22422.10546875, 104.77748108]), + 'frame': 25380, + 'frame_number': 25380, + 'framesequence': 102215, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5393170118331909, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.5622536502779, + 'timestamp_carla': 863561, + 'timestamp_device': 1734157, + 'timestamp_stream': 863.5622536502779, + 'transform': [array([-43.49379349, 67.43482971, -0.08430857]), + array([ 1.48624908e-02, -1.61890411e+02, -7.26928711e-02])]} +{'AngularVelocity': array([-0.04390814, 0.22273126, 4.40920925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.835779190063477, + 'FR_Wheel_Angle': 41.769775390625, + 'Location': array([-3.91799698e+01, 9.72524261e+01, 3.69794108e-02]), + 'Rotation': array([ 1.47168028, 114.76301575, 3.01253581]), + 'Velocity': array([-0.25274 , 0.2325889, 0.0015999]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 8011.0947265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7137.22021484, 15660.02734375, 112.770401 ]), + 'frame': 25381, + 'frame_number': 25381, + 'framesequence': 102220, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.5970793515444, + 'timestamp_carla': 863596, + 'timestamp_device': 1734199, + 'timestamp_stream': 863.5970793515444, + 'transform': [array([-43.61941147, 67.45623016, -0.08365788]), + array([ 1.42819248e-02, -1.62434082e+02, -7.59582520e-02])]} +{'AngularVelocity': array([2.24761572e-03, 1.98003605e-01, 3.69501185e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.840877532958984, + 'FR_Wheel_Angle': 41.751583099365234, + 'Location': array([-3.92191315e+01, 9.72940826e+01, 3.72212604e-02]), + 'Rotation': array([ 1.48258805, 115.50145721, 2.99431872]), + 'Velocity': array([-0.25407559, 0.2279525 , 0.00194217]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7959.74267578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-7051.04882812, 15638.66113281, 112.40937805]), + 'frame': 25382, + 'frame_number': 25382, + 'framesequence': 102224, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5402691960334778, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.629694249481, + 'timestamp_carla': 863628, + 'timestamp_device': 1734232, + 'timestamp_stream': 863.629694249481, + 'transform': [array([-43.7366066 , 67.47692108, -0.08303662]), + array([ 1.36398869e-02, -1.62942184e+02, -7.89794847e-02])]} +{'AngularVelocity': array([0.03753551, 0.03238231, 4.56941652]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.84193992614746, + 'FR_Wheel_Angle': 41.76406478881836, + 'Location': array([-3.92661476e+01, 9.73424377e+01, 3.74809653e-02]), + 'Rotation': array([ 1.49257386, 116.39141846, 2.97394013]), + 'Velocity': array([-0.26304549, 0.23477954, 0.00161031]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7886.9091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6957.10644531, 15596.60351562, 112.04337311]), + 'frame': 25383, + 'frame_number': 25383, + 'framesequence': 102228, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401593446731567, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.666524451226, + 'timestamp_carla': 863665, + 'timestamp_device': 1734265, + 'timestamp_stream': 863.666524451226, + 'transform': [array([-43.86621094, 67.50141144, -0.08235493]), + array([ 1.32778874e-02, -1.63505096e+02, -8.24279711e-02])]} +{'AngularVelocity': array([ 0.05864137, -0.02944778, 4.00472641]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.854249954223633, + 'FR_Wheel_Angle': 41.776588439941406, + 'Location': array([-3.93051376e+01, 9.73814926e+01, 3.76527049e-02]), + 'Rotation': array([ 1.49939716, 117.11077118, 2.95995212]), + 'Velocity': array([-0.24267751, 0.21282655, 0.00091245]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7821.81884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6871.14355469, 15559.11816406, 111.71149445]), + 'frame': 25384, + 'frame_number': 25384, + 'framesequence': 102233, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.7048102505505, + 'timestamp_carla': 863703, + 'timestamp_device': 1734307, + 'timestamp_stream': 863.7048102505505, + 'transform': [array([-43.9981842 , 67.52780151, -0.08161923]), + array([ 1.30934715e-02, -1.64079437e+02, -8.60900581e-02])]} +{'AngularVelocity': array([-0.02147324, -0.03402086, 4.34767342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.835969924926758, + 'FR_Wheel_Angle': 41.760074615478516, + 'Location': array([-3.93427505e+01, 9.74181519e+01, 3.78387459e-02]), + 'Rotation': array([ 1.50378895, 117.81261444, 2.9462471 ]), + 'Velocity': array([-0.24031489, 0.19916646, 0.0010818 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19598.23046875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-10141.09960938, 26877.42578125, 94.29029846]), + 'frame': 25385, + 'frame_number': 25385, + 'framesequence': 102237, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.7403422519565, + 'timestamp_carla': 863739, + 'timestamp_device': 1734340, + 'timestamp_stream': 863.7403422519565, + 'transform': [array([-44.11872101, 67.55301666, -0.08092491]), + array([ 1.27587924e-02, -1.64605103e+02, -8.93859789e-02])]} +{'AngularVelocity': array([0.02946787, 0.1614351 , 4.46670914]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.645570755004883, + 'FR_Wheel_Angle': 36.38603210449219, + 'Location': array([-3.93904419e+01, 9.74638824e+01, 3.81673463e-02]), + 'Rotation': array([ 1.52057076, 118.68045807, 2.91333055]), + 'Velocity': array([-0.25139198, 0.22070527, 0.00367542]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7663.8896484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6678.60791016, 15460.18164062, 110.95610809]), + 'frame': 25386, + 'frame_number': 25386, + 'framesequence': 102241, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.7755975499749, + 'timestamp_carla': 863774, + 'timestamp_device': 1734374, + 'timestamp_stream': 863.7755975499749, + 'transform': [array([-44.23725891, 67.57866669, -0.08029073]), + array([ 1.22943399e-02, -1.65123032e+02, -9.24377441e-02])]} +{'AngularVelocity': array([0.12061717, 0.10857441, 2.97245622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.53894805908203, + 'FR_Wheel_Angle': 38.53205490112305, + 'Location': array([-3.94366684e+01, 9.75099945e+01, 3.86353321e-02]), + 'Rotation': array([ 1.54153943, 119.43450928, 2.87321305]), + 'Velocity': array([-0.23705415, 0.22115938, 0.00221395]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7589.474609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6590.92724609, 15411.50585938, 110.62475586]), + 'frame': 25387, + 'frame_number': 25387, + 'framesequence': 102245, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.8068390488625, + 'timestamp_carla': 863805, + 'timestamp_device': 1734407, + 'timestamp_stream': 863.8068390488625, + 'transform': [array([-44.3418045 , 67.60198212, -0.07976592]), + array([ 1.15635097e-02, -1.65580658e+02, -9.49096456e-02])]} +{'AngularVelocity': array([0.05762137, 0.19840799, 3.89732742]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.079458236694336, + 'FR_Wheel_Angle': 37.22805404663086, + 'Location': array([-3.94742317e+01, 9.75460815e+01, 3.90370563e-02]), + 'Rotation': array([ 1.55775428, 120.05450439, 2.83786678]), + 'Velocity': array([-0.24775794, 0.22150721, 0.00337935]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7520.978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6506.86376953, 15367.22070312, 110.32564545]), + 'frame': 25388, + 'frame_number': 25388, + 'framesequence': 102249, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.8391439504921, + 'timestamp_carla': 863838, + 'timestamp_device': 1734440, + 'timestamp_stream': 863.8391439504921, + 'transform': [array([-44.44787979, 67.62689209, -0.07927048]), + array([ 1.08668301e-02, -1.66045959e+02, -9.73510742e-02])]} +{'AngularVelocity': array([0.08141112, 0.02984404, 4.19827747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.444765090942383, + 'FR_Wheel_Angle': 37.61994171142578, + 'Location': array([-3.95114670e+01, 9.75812836e+01, 3.93424630e-02]), + 'Rotation': array([ 1.56918812, 120.67186737, 2.82421899]), + 'Velocity': array([-0.24859138, 0.21231835, 0.00135877]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7469.560546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6435.68798828, 15336.12109375, 110.0836792 ]), + 'frame': 25389, + 'frame_number': 25389, + 'framesequence': 102252, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.8689175508916, + 'timestamp_carla': 863867, + 'timestamp_device': 1734465, + 'timestamp_stream': 863.8689175508916, + 'transform': [array([-44.54380417, 67.65066528, -0.07897098]), + array([ 9.73984879e-03, -1.66467728e+02, -9.92431492e-02])]} +{'AngularVelocity': array([ 0.22842662, -0.03370976, 2.51498652]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.360475540161133, + 'FR_Wheel_Angle': 37.59075164794922, + 'Location': array([-3.95459709e+01, 9.76130066e+01, 3.97248864e-02]), + 'Rotation': array([ 1.58533466, 121.24075317, 2.83159351]), + 'Velocity': array([-0.214293 , 0.1845324, 0.0032587]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7425.06787109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6365.85644531, 15311.40820312, 109.83558655]), + 'frame': 25390, + 'frame_number': 25390, + 'framesequence': 102256, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.8999919518828, + 'timestamp_carla': 863898, + 'timestamp_device': 1734499, + 'timestamp_stream': 863.8999919518828, + 'transform': [array([-44.64153671, 67.67577362, -0.07842563]), + array([ 9.37101897e-03, -1.66898331e+02, -1.01745613e-01])]} +{'AngularVelocity': array([ 0.07690043, -0.03730409, 2.52042007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.371999740600586, + 'FR_Wheel_Angle': 37.651668548583984, + 'Location': array([-3.95853806e+01, 9.76479263e+01, 4.02208716e-02]), + 'Rotation': array([ 1.60637164, 121.88201141, 2.84625483]), + 'Velocity': array([-0.17167458, 0.13311709, 0.00233149]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7340.18115234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6292.609375 , 15245.16894531, 109.72718811]), + 'frame': 25391, + 'frame_number': 25391, + 'framesequence': 102260, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.9298895522952, + 'timestamp_carla': 863928, + 'timestamp_device': 1734532, + 'timestamp_stream': 863.9298895522952, + 'transform': [array([-44.73268509, 67.69989777, -0.07777882]), + array([ 1.02247922e-02, -1.67300735e+02, -1.04858384e-01])]} +{'AngularVelocity': array([ 0.45335644, -0.10469147, 0.80809629]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.412677764892578, + 'FR_Wheel_Angle': 37.67502212524414, + 'Location': array([-3.96115341e+01, 9.76700439e+01, 4.13550958e-02]), + 'Rotation': array([ 1.65969491, 122.27065277, 2.93626022]), + 'Velocity': array([-0.14005166, 0.09804426, 0.00765176]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7279.4228515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6224.83007812, 15202.08300781, 109.51234436]), + 'frame': 25392, + 'frame_number': 25392, + 'framesequence': 102263, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.9615473523736, + 'timestamp_carla': 863960, + 'timestamp_device': 1734557, + 'timestamp_stream': 863.9615473523736, + 'transform': [array([-44.829319 , 67.72598267, -0.07724879]), + array([ 9.73984879e-03, -1.67728058e+02, -1.07299797e-01])]} +{'AngularVelocity': array([ 2.65951335e-01, -1.50988530e-03, 2.74174595e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.42841148376465, + 'FR_Wheel_Angle': 37.74198913574219, + 'Location': array([-3.96344109e+01, 9.76896286e+01, 4.21207435e-02]), + 'Rotation': array([ 1.68903744, 122.64424896, 2.9725368 ]), + 'Velocity': array([-0.1726554 , 0.12742886, 0.00441588]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7223.8271484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6162.44189453, 15162.42382812, 109.20761108]), + 'frame': 25393, + 'frame_number': 25393, + 'framesequence': 102267, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 863.9956623502076, + 'timestamp_carla': 863994, + 'timestamp_device': 1734590, + 'timestamp_stream': 863.9956623502076, + 'transform': [array([-44.93312454, 67.7545166 , -0.07675729]), + array([ 9.15928278e-03, -1.68187927e+02, -1.09741189e-01])]} +{'AngularVelocity': array([ 0.02295722, -0.01196475, 2.00858951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.43758773803711, + 'FR_Wheel_Angle': 37.42655563354492, + 'Location': array([-3.96537819e+01, 9.77055664e+01, 4.25590873e-02]), + 'Rotation': array([ 1.7031008 , 122.94548798, 2.9934845 ]), + 'Velocity': array([-0.09366177, 0.04991025, 0.00219718]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7166.04833984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6097.1875 , 15120.94335938, 109.00534058]), + 'frame': 25394, + 'frame_number': 25394, + 'framesequence': 102272, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.0290128514171, + 'timestamp_carla': 864027, + 'timestamp_device': 1734632, + 'timestamp_stream': 864.0290128514171, + 'transform': [array([-45.03274155, 67.78289032, -0.07628857]), + array([ 8.57188739e-03, -1.68630341e+02, -1.12060532e-01])]} +{'AngularVelocity': array([ 0.23125605, -0.07444149, 1.83960915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.821170806884766, + 'FR_Wheel_Angle': 31.88193130493164, + 'Location': array([-3.96679344e+01, 9.77178574e+01, 4.28374857e-02]), + 'Rotation': array([ 1.71789491, 123.16936493, 3.00879431]), + 'Velocity': array([-0.10623002, 0.09301257, 0.00236892]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 7120.94775390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-6031.28125 , 15092.34375 , 108.78102875]), + 'frame': 25395, + 'frame_number': 25395, + 'framesequence': 102276, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.0621093511581, + 'timestamp_carla': 864061, + 'timestamp_device': 1734665, + 'timestamp_stream': 864.0621093511581, + 'transform': [array([-45.13010788, 67.81144714, -0.07583448]), + array([ 7.99815077e-03, -1.69063751e+02, -1.14318848e-01])]} +{'AngularVelocity': array([ 0.12447669, -0.04847037, 0.1068804 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.42749786376953, + 'FR_Wheel_Angle': 34.11298370361328, + 'Location': array([-3.96807632e+01, 9.77290421e+01, 4.30881493e-02]), + 'Rotation': array([ 1.72762108, 123.36022949, 3.0212698 ]), + 'Velocity': array([-0.0564805 , 0.05301553, 0.00107559]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 19342.69921875, + 'focus_actor_name': 'Landscape_0', + 'focus_actor_pt': array([-8386.35351562, 27088.6953125 , 84.58314514]), + 'frame': 25396, + 'frame_number': 25396, + 'framesequence': 102280, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.0949835516512, + 'timestamp_carla': 864093, + 'timestamp_device': 1734699, + 'timestamp_stream': 864.0949835516512, + 'transform': [array([-45.2254715 , 67.84018707, -0.07538711]), + array([ 7.44490558e-03, -1.69489227e+02, -1.16546609e-01])]} +{'AngularVelocity': array([ 0.10393484, -0.08519413, -0.63484001]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.71267318725586, + 'FR_Wheel_Angle': 33.57548904418945, + 'Location': array([-3.96901932e+01, 9.77369995e+01, 4.32476401e-02]), + 'Rotation': array([ 1.73505235, 123.50074005, 3.03006983]), + 'Velocity': array([-0.02814529, 0.0266026 , -0.00030342]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6993.296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5899.45849609, 14995.25 , 108.4557724 ]), + 'frame': 25397, + 'frame_number': 25397, + 'framesequence': 102284, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.1288163512945, + 'timestamp_carla': 864127, + 'timestamp_device': 1734732, + 'timestamp_stream': 864.1288163512945, + 'transform': [array([-45.32247543, 67.8700943 , -0.07494255]), + array([ 6.92581153e-03, -1.69922913e+02, -1.18804894e-01])]} +{'AngularVelocity': array([ 0.02099008, -0.02209281, 1.41383278]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.812715530395508, + 'FR_Wheel_Angle': 33.55063247680664, + 'Location': array([-3.96996536e+01, 9.77450333e+01, 4.34782393e-02]), + 'Rotation': array([ 1.74649298, 123.63935089, 3.04183674]), + 'Velocity': array([-0.06420367, 0.03511282, 0.00243522]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6962.5791015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5842.35791016, 14977.99414062, 108.24121094]), + 'frame': 25398, + 'frame_number': 25398, + 'framesequence': 102288, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.1622909493744, + 'timestamp_carla': 864161, + 'timestamp_device': 1734765, + 'timestamp_stream': 864.1622909493744, + 'transform': [array([-45.41716766, 67.90000153, -0.07450589]), + array([ 6.40671700e-03, -1.70347260e+02, -1.21002182e-01])]} +{'AngularVelocity': array([-0.02050085, 0.05311786, 1.46171832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.875991821289062, + 'FR_Wheel_Angle': 33.58696746826172, + 'Location': array([-3.97060089e+01, 9.77500763e+01, 4.36168648e-02]), + 'Rotation': array([ 1.75078917, 123.73508453, 3.0491569 ]), + 'Velocity': array([-0.03951313, 0.01963501, 0.00142813]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6865.0908203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5772.94238281, 14894.76074219, 108.16308594]), + 'frame': 25399, + 'frame_number': 25399, + 'framesequence': 102292, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.1952388510108, + 'timestamp_carla': 864194, + 'timestamp_device': 1734799, + 'timestamp_stream': 864.1952388510108, + 'transform': [array([-45.50901794, 67.92974091, -0.07407773]), + array([ 5.89445280e-03, -1.70759857e+02, -1.23138420e-01])]} +{'AngularVelocity': array([ 0.25015244, -0.15452105, 0.4828786 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.877574920654297, + 'FR_Wheel_Angle': 33.57597351074219, + 'Location': array([-3.97100716e+01, 9.77534027e+01, 4.36892696e-02]), + 'Rotation': array([ 1.75722313, 123.79650116, 3.05454326]), + 'Velocity': array([-0.0479816 , 0.04045434, 0.0015751 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6797.69970703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5711.03222656, 14840.28515625, 108.03697205]), + 'frame': 25400, + 'frame_number': 25400, + 'framesequence': 102296, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.2288279496133, + 'timestamp_carla': 864227, + 'timestamp_device': 1734832, + 'timestamp_stream': 864.2288279496133, + 'transform': [array([-45.59947586, 67.96031189, -0.07361591]), + array([ 5.52562252e-03, -1.71167664e+02, -1.25427216e-01])]} +{'AngularVelocity': array([ 0.24051733, -0.08802472, -0.08801018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.839889526367188, + 'FR_Wheel_Angle': 33.539520263671875, + 'Location': array([-3.97226181e+01, 9.77643509e+01, 4.39247899e-02]), + 'Rotation': array([ 1.77522075, 123.97792816, 3.06756592]), + 'Velocity': array([-0.09566018, 0.08342753, 0.00138924]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6733.67919921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5651.93798828, 14788.28515625, 107.91576385]), + 'frame': 25401, + 'frame_number': 25401, + 'framesequence': 102300, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.261645950377, + 'timestamp_carla': 864260, + 'timestamp_device': 1734865, + 'timestamp_stream': 864.261645950377, + 'transform': [array([-45.6855278 , 67.99031067, -0.0731573 ]), + array([ 5.21826418e-03, -1.71556763e+02, -1.27655044e-01])]} +{'AngularVelocity': array([ 0.16265526, -0.1299924 , 3.17952704]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.81508445739746, + 'FR_Wheel_Angle': 33.458740234375, + 'Location': array([-3.97455978e+01, 9.77843399e+01, 4.44948561e-02]), + 'Rotation': array([ 1.79909909, 124.30358887, 3.08999228]), + 'Velocity': array([-0.1613014 , 0.11983988, 0.00514038]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6676.59521484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5595.28515625, 14742.57324219, 107.76513672]), + 'frame': 25402, + 'frame_number': 25402, + 'framesequence': 102303, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.2943647503853, + 'timestamp_carla': 864293, + 'timestamp_device': 1734890, + 'timestamp_stream': 864.2943647503853, + 'transform': [array([-45.76962662, 68.02030182, -0.07271334]), + array([ 4.88358503e-03, -1.71937927e+02, -1.29821777e-01])]} +{'AngularVelocity': array([ 0.41251385, -0.03893279, 3.019557 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.446887969970703, + 'FR_Wheel_Angle': 31.63144874572754, + 'Location': array([-3.97874641e+01, 9.78205414e+01, 4.54994589e-02]), + 'Rotation': array([ 1.84177411, 124.89054871, 3.12892365]), + 'Velocity': array([-0.27743834, 0.20726664, 0.00792945]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6623.39892578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5542.09521484, 14699.80566406, 107.61998749]), + 'frame': 25403, + 'frame_number': 25403, + 'framesequence': 102307, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.3283751495183, + 'timestamp_carla': 864327, + 'timestamp_device': 1734924, + 'timestamp_stream': 864.3283751495183, + 'transform': [array([-45.85524368, 68.05151367, -0.07226634]), + array([ 4.57622670e-03, -1.72326965e+02, -1.32049546e-01])]} +{'AngularVelocity': array([ 1.22552454, -0.49640733, 1.20691919]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.16588592529297, + 'FR_Wheel_Angle': 28.568695068359375, + 'Location': array([-3.98261604e+01, 9.78540344e+01, 4.75350544e-02]), + 'Rotation': array([ 1.93295026, 125.36129761, 3.28791213]), + 'Velocity': array([-0.23613498, 0.18257962, 0.01874464]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6569.18310546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5490.31933594, 14655.43164062, 107.48682404]), + 'frame': 25404, + 'frame_number': 25404, + 'framesequence': 102311, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5401410460472107, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.3620595522225, + 'timestamp_carla': 864360, + 'timestamp_device': 1734957, + 'timestamp_stream': 864.3620595522225, + 'transform': [array([-45.93825912, 68.08240509, -0.07182555]), + array([ 4.27569821e-03, -1.72705170e+02, -1.34216309e-01])]} +{'AngularVelocity': array([ 0.55337989, -0.16447018, 3.74716115]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.046754837036133, + 'FR_Wheel_Angle': 28.76557159423828, + 'Location': array([-3.98706665e+01, 9.78929672e+01, 4.93504703e-02]), + 'Rotation': array([ 1.99845183, 125.91941071, 3.3654952 ]), + 'Velocity': array([-0.31292418, 0.24823414, 0.01041453]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6515.396484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5438.35498047, 14611.27246094, 107.34934998]), + 'frame': 25405, + 'frame_number': 25405, + 'framesequence': 102316, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.537540853023529, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.3959935493767, + 'timestamp_carla': 864394, + 'timestamp_device': 1734999, + 'timestamp_stream': 864.3959935493767, + 'transform': [array([-46.01993179, 68.11352539, -0.07140402]), + array([ 4.06396249e-03, -1.73078125e+02, -1.36291519e-01])]} +{'AngularVelocity': array([ 0.49955338, -0.01308207, 4.58299541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.133970260620117, + 'FR_Wheel_Angle': 29.09979820251465, + 'Location': array([-3.99379425e+01, 9.79514236e+01, 5.10004424e-02]), + 'Rotation': array([ 2.06326342, 126.76964569, 3.4254694 ]), + 'Velocity': array([-0.41401675, 0.3116622 , 0.01147715]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6437.6064453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5385.23583984, 14542.66503906, 107.27924347]), + 'frame': 25406, + 'frame_number': 25406, + 'framesequence': 102320, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5230017900466919, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.432137452066, + 'timestamp_carla': 864431, + 'timestamp_device': 1735032, + 'timestamp_stream': 864.432137452066, + 'transform': [array([-46.10352325, 68.14667511, -0.07098448]), + array([ 4.52158507e-03, -1.73460663e+02, -1.38366684e-01])]} +{'AngularVelocity': array([ 0.28158996, -0.04028165, 5.86385679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.051591873168945, + 'FR_Wheel_Angle': 29.06821060180664, + 'Location': array([-4.00209007e+01, 9.80210648e+01, 5.26319109e-02]), + 'Rotation': array([ 2.12334871, 127.77933502, 3.47054839]), + 'Velocity': array([-0.45244578, 0.33265159, 0.00872003]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6388.54443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5337.13134766, 14502.06542969, 107.15795898]), + 'frame': 25407, + 'frame_number': 25407, + 'framesequence': 102324, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4982818067073822, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.4656490497291, + 'timestamp_carla': 864464, + 'timestamp_device': 1735065, + 'timestamp_stream': 864.4656490497291, + 'transform': [array([-46.17683411, 68.17745209, -0.0705898 ]), + array([ 5.67588676e-03, -1.73796478e+02, -1.40106171e-01])]} +{'AngularVelocity': array([ 0.54651505, -0.1022046 , 4.60823536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.01778221130371, + 'FR_Wheel_Angle': 29.07117462158203, + 'Location': array([-4.00972366e+01, 9.80832672e+01, 5.40240481e-02]), + 'Rotation': array([ 2.17432237, 128.68734741, 3.51037264]), + 'Velocity': array([-0.48700312, 0.35091031, 0.01034818]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6325.9482421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5286.99511719, 14447.93261719, 107.06964874]), + 'frame': 25408, + 'frame_number': 25408, + 'framesequence': 102328, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4740562438964844, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.4987477511168, + 'timestamp_carla': 864497, + 'timestamp_device': 1735099, + 'timestamp_stream': 864.4987477511168, + 'transform': [array([-46.24469757, 68.20787048, -0.07023125]), + array([ 7.11022643e-03, -1.74107529e+02, -1.41662553e-01])]} +{'AngularVelocity': array([0.06348041, 0.30608794, 6.48156404]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.011634826660156, + 'FR_Wheel_Angle': 29.05277442932129, + 'Location': array([-4.01800537e+01, 9.81481323e+01, 5.55696487e-02]), + 'Rotation': array([ 2.23354006, 129.65075684, 3.55178237]), + 'Velocity': array([-0.56942081, 0.40214321, 0.00682636]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6270.4765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5243.57763672, 14399.70117188, 107.00721741]), + 'frame': 25409, + 'frame_number': 25409, + 'framesequence': 102332, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45607471466064453, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.5279140509665, + 'timestamp_carla': 864526, + 'timestamp_device': 1735132, + 'timestamp_stream': 864.5279140509665, + 'transform': [array([-46.30132294, 68.2350235 , -0.07013216]), + array([ 7.29464181e-03, -1.74367493e+02, -1.42425522e-01])]} +{'AngularVelocity': array([0.04047121, 0.30666348, 6.95508099]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.993667602539062, + 'FR_Wheel_Angle': 29.00874137878418, + 'Location': array([-4.02718964e+01, 9.82187805e+01, 5.63764945e-02]), + 'Rotation': array([ 2.2596519 , 130.73292542, 3.52276325]), + 'Velocity': array([-0.62151438, 0.4233824 , 0.00561087]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6220.66259765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5204.07861328, 14356.48144531, 106.95610046]), + 'frame': 25410, + 'frame_number': 25410, + 'framesequence': 102335, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4547196924686432, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.5605554506183, + 'timestamp_carla': 864559, + 'timestamp_device': 1735157, + 'timestamp_stream': 864.5605554506183, + 'transform': [array([-46.36227798, 68.26490021, -0.0697647 ]), + array([ 7.50637753e-03, -1.74647537e+02, -1.44073457e-01])]} +{'AngularVelocity': array([ 1.37138903, -8.04624557, 2.51650023]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.07799530029297, + 'FR_Wheel_Angle': 29.161056518554688, + 'Location': array([-4.03648224e+01, 9.82845688e+01, 6.55877292e-02]), + 'Rotation': array([ 1.93476021, 131.63568115, 4.08593512]), + 'Velocity': array([-0.41388914, 0.18190503, 0.08592536]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6179.5595703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5171.51074219, 14320.84570312, 106.96672058]), + 'frame': 25411, + 'frame_number': 25411, + 'framesequence': 102339, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.463856965303421, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.5947443507612, + 'timestamp_carla': 864593, + 'timestamp_device': 1735190, + 'timestamp_stream': 864.5947443507612, + 'transform': [array([-46.42559433, 68.29584503, -0.06938295]), + array([ 6.62528304e-03, -1.74938858e+02, -1.45996079e-01])]} +{'AngularVelocity': array([ 0.49315724, -4.66488361, 4.64009666]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.778547286987305, + 'FR_Wheel_Angle': 24.12118911743164, + 'Location': array([-4.04277153e+01, 9.83289108e+01, 8.41106772e-02]), + 'Rotation': array([ 1.31675792, 132.30184937, 4.98559093]), + 'Velocity': array([-0.49231601, 0.30355617, 0.07327973]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6161.755859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5139.29492188, 14308.66796875, 106.83084106]), + 'frame': 25412, + 'frame_number': 25412, + 'framesequence': 102343, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4787255525588989, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.6268568523228, + 'timestamp_carla': 864625, + 'timestamp_device': 1735224, + 'timestamp_stream': 864.6268568523228, + 'transform': [array([-46.4855423 , 68.32472992, -0.0690353 ]), + array([ 4.84943390e-03, -1.75215469e+02, -1.47796646e-01])]} +{'AngularVelocity': array([ 0.24835888, -1.59937012, 5.02368212]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.827285766601562, + 'FR_Wheel_Angle': 25.65453338623047, + 'Location': array([-4.05043411e+01, 9.83860321e+01, 9.40892026e-02]), + 'Rotation': array([ 1.02504742, 133.04406738, 5.38893843]), + 'Velocity': array([-0.54707772, 0.35124728, 0.02961067]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6098.64208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5102.01220703, 14251.36035156, 106.78168488]), + 'frame': 25413, + 'frame_number': 25413, + 'framesequence': 102347, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49024322628974915, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.6598527505994, + 'timestamp_carla': 864658, + 'timestamp_device': 1735257, + 'timestamp_stream': 864.6598527505994, + 'transform': [array([-46.54723358, 68.35411835, -0.06869159]), + array([ 2.90283025e-03, -1.75501038e+02, -1.49658188e-01])]} +{'AngularVelocity': array([ 0.10551678, -0.63280886, 4.35977411]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.213623046875, + 'FR_Wheel_Angle': 25.037538528442383, + 'Location': array([-4.06052017e+01, 9.84573746e+01, 9.64964256e-02]), + 'Rotation': array([ 0.90903664, 134.01008606, 5.42905903]), + 'Velocity': array([-0.53206593, 0.33882067, 0.00697041]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6049.783203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5068.09814453, 14207.69433594, 106.71542358]), + 'frame': 25414, + 'frame_number': 25414, + 'framesequence': 102351, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49324628710746765, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.6937921494246, + 'timestamp_carla': 864692, + 'timestamp_device': 1735290, + 'timestamp_stream': 864.6937921494246, + 'transform': [array([-4.66100121e+01, 6.83840408e+01, -6.83458000e-02]), + array([ 1.40701886e-03, -1.75792557e+02, -1.51519775e-01])]} +{'AngularVelocity': array([-12.20453262, 5.34176111, 4.24951124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.198299407958984, + 'FR_Wheel_Angle': 24.88388442993164, + 'Location': array([-4.07109146e+01, 9.85289688e+01, 9.67087150e-02]), + 'Rotation': array([ 0.79142761, 135.02882385, 5.25175285]), + 'Velocity': array([-0.54806864, 0.39776674, -0.10546257]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 6007.619140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5034.19873047, 14170.6015625 , 106.62567902]), + 'frame': 25415, + 'frame_number': 25415, + 'framesequence': 102355, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4887051284313202, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.7275706492364, + 'timestamp_carla': 864726, + 'timestamp_device': 1735324, + 'timestamp_stream': 864.7275706492364, + 'transform': [array([-4.66710358e+01, 6.84135590e+01, -6.80209175e-02]), + array([ 6.14717021e-04, -1.76076675e+02, -1.53198242e-01])]} +{'AngularVelocity': array([-4.13774347, 0.62464899, 4.75614882]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.25460433959961, + 'FR_Wheel_Angle': 24.879697799682617, + 'Location': array([-4.07957077e+01, 9.85855637e+01, 6.84743077e-02]), + 'Rotation': array([ -0.42444161, 135.69937134, 2.78207278]), + 'Velocity': array([-0.53098226, 0.37548378, -0.09887843]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5979.45947265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-5001.08789062, 14147.34960938, 106.50169373]), + 'frame': 25416, + 'frame_number': 25416, + 'framesequence': 102359, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48218634724617004, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.7596650496125, + 'timestamp_carla': 864758, + 'timestamp_device': 1735357, + 'timestamp_stream': 864.7596650496125, + 'transform': [array([-4.67274323e+01, 6.84414520e+01, -6.77250400e-02]), + array([ 3.07358510e-04, -1.76339859e+02, -1.54632553e-01])]} +{'AngularVelocity': array([-0.4033595 , 0.18956223, 6.2663393 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.237567901611328, + 'FR_Wheel_Angle': 24.8616886138916, + 'Location': array([-4.08900375e+01, 9.86482010e+01, 6.44987449e-02]), + 'Rotation': array([ -0.54009718, 136.62084961, 2.57147217]), + 'Velocity': array([-0.60169357, 0.3571614 , 0.00091345]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5910.3134765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4966.21435547, 14082.91796875, 106.50736237]), + 'frame': 25417, + 'frame_number': 25417, + 'framesequence': 102363, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47583240270614624, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.7942851521075, + 'timestamp_carla': 864793, + 'timestamp_device': 1735390, + 'timestamp_stream': 864.7942851521075, + 'transform': [array([-4.67855988e+01, 6.84711151e+01, -6.74107373e-02]), + array([ 3.34679266e-04, -1.76612137e+02, -1.56219468e-01])]} +{'AngularVelocity': array([-0.15493058, 0.13433391, 6.5490489 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.21372413635254, + 'FR_Wheel_Angle': 24.824478149414062, + 'Location': array([-4.09953003e+01, 9.87145615e+01, 6.54219389e-02]), + 'Rotation': array([ -0.53357434, 137.63078308, 2.49615455]), + 'Velocity': array([-0.66643804, 0.37714699, 0.00668378]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5880.9169921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4936.70898438, 14057.671875 , 106.43595123]), + 'frame': 25418, + 'frame_number': 25418, + 'framesequence': 102367, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4735618233680725, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.8280032500625, + 'timestamp_carla': 864826, + 'timestamp_device': 1735424, + 'timestamp_stream': 864.8280032500625, + 'transform': [array([-4.68414650e+01, 6.84997711e+01, -6.71231374e-02]), + array([ 1.57094342e-04, -1.76873856e+02, -1.57653794e-01])]} +{'AngularVelocity': array([-0.08848397, 0.06547028, 6.32649422]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.19928550720215, + 'FR_Wheel_Angle': 24.803302764892578, + 'Location': array([-4.11351318e+01, 9.87994766e+01, 6.60486966e-02]), + 'Rotation': array([ -0.53054857, 138.91134644, 2.46851087]), + 'Velocity': array([-0.75493443, 0.40561306, 0.00173514]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5859.453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4906.97705078, 14040.38671875, 106.32550049]), + 'frame': 25419, + 'frame_number': 25419, + 'framesequence': 102371, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4759972095489502, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.860978949815, + 'timestamp_carla': 864859, + 'timestamp_device': 1735457, + 'timestamp_stream': 864.860978949815, + 'transform': [array([-4.68953018e+01, 6.85276108e+01, -6.68576807e-02]), + array([-3.34679266e-04, -1.77126572e+02, -1.58996567e-01])]} +{'AngularVelocity': array([-0.02091258, -0.04824034, 7.5133605 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.162199020385742, + 'FR_Wheel_Angle': 23.95285415649414, + 'Location': array([-4.12632751e+01, 9.88731155e+01, 6.62929937e-02]), + 'Rotation': array([ -0.5319829 , 140.06991577, 2.45064306]), + 'Velocity': array([-0.78393823, 0.40031481, 0.00120749]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5797.5498046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4876.32861328, 13982.41210938, 106.34581757]), + 'frame': 25420, + 'frame_number': 25420, + 'framesequence': 102376, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47943970561027527, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.8953121490777, + 'timestamp_carla': 864894, + 'timestamp_device': 1735499, + 'timestamp_stream': 864.8953121490777, + 'transform': [array([-4.69504814e+01, 6.85562668e+01, -6.65874854e-02]), + array([-9.63056635e-04, -1.77386215e+02, -1.60430908e-01])]} +{'AngularVelocity': array([-0.01871339, 0.08213919, 5.98561668]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 16.404346466064453, + 'FR_Wheel_Angle': 20.265518188476562, + 'Location': array([-4.13965340e+01, 9.89504547e+01, 6.66048825e-02]), + 'Rotation': array([ -0.51702482, 141.14703369, 2.43168616]), + 'Velocity': array([-0.83047813, 0.45756993, 0.00242053]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5745.0791015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4847.62060547, 13933.57324219, 106.35221863]), + 'frame': 25421, + 'frame_number': 25421, + 'framesequence': 102379, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4824427366256714, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.9260699488223, + 'timestamp_carla': 864924, + 'timestamp_device': 1735524, + 'timestamp_stream': 864.9260699488223, + 'transform': [array([-4.69997063e+01, 6.85818863e+01, -6.63528740e-02]), + array([-1.72803772e-03, -1.77618301e+02, -1.61590546e-01])]} +{'AngularVelocity': array([-0.01337548, 0.07000182, 7.11390162]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.141239166259766, + 'FR_Wheel_Angle': 20.175416946411133, + 'Location': array([-4.15701256e+01, 9.90485840e+01, 6.69416413e-02]), + 'Rotation': array([ -0.49762022, 142.48880005, 2.39463854]), + 'Velocity': array([-0.91172969, 0.45653728, 0.00237633]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5701.7607421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4819.07714844, 13893.8125 , 106.32545471]), + 'frame': 25422, + 'frame_number': 25422, + 'framesequence': 102383, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4823145568370819, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.9605110511184, + 'timestamp_carla': 864959, + 'timestamp_device': 1735557, + 'timestamp_stream': 864.9605110511184, + 'transform': [array([-4.70526848e+01, 6.86100616e+01, -6.60767481e-02]), + array([-2.20615091e-03, -1.77869049e+02, -1.63055420e-01])]} +{'AngularVelocity': array([ 0.14052333, -0.34852174, 7.38694286]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.39684295654297, + 'FR_Wheel_Angle': 20.67091178894043, + 'Location': array([-4.17560921e+01, 9.91479187e+01, 6.77530244e-02]), + 'Rotation': array([ -0.49669817, 143.89016724, 2.39628482]), + 'Velocity': array([-0.97103435, 0.45578507, 0.00709143]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5685.79638671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4794.82568359, 13880.87109375, 106.25471497]), + 'frame': 25423, + 'frame_number': 25423, + 'framesequence': 102387, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4807763993740082, + 'throttle_input': 0.019836727529764175, + 'timestamp': 864.9953454509377, + 'timestamp_carla': 864994, + 'timestamp_device': 1735590, + 'timestamp_stream': 864.9953454509377, + 'transform': [array([-4.71050568e+01, 6.86380920e+01, -6.57864138e-02]), + array([-2.54766038e-03, -1.78117477e+02, -1.64550781e-01])]} +{'AngularVelocity': array([ 0.10951228, -0.8567552 , 7.40967989]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.277790069580078, + 'FR_Wheel_Angle': 20.61948013305664, + 'Location': array([-4.19196510e+01, 9.92300644e+01, 7.00511560e-02]), + 'Rotation': array([ -0.55685848, 145.09492493, 2.47776961]), + 'Velocity': array([-1.00441742, 0.44338512, 0.01669981]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5623.06689453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4767.05908203, 13821.35351562, 106.28263092]), + 'frame': 25424, + 'frame_number': 25424, + 'framesequence': 102391, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4789453148841858, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.0279333516955, + 'timestamp_carla': 865026, + 'timestamp_device': 1735624, + 'timestamp_stream': 865.0279333516955, + 'transform': [array([-4.71529961e+01, 6.86640396e+01, -6.55196384e-02]), + array([-2.83452845e-03, -1.78345337e+02, -1.65832490e-01])]} +{'AngularVelocity': array([ 0.18765831, -1.10078752, 7.53340292]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.2650089263916, + 'FR_Wheel_Angle': 20.582612991333008, + 'Location': array([-4.20847588e+01, 9.93083649e+01, 7.37162009e-02]), + 'Rotation': array([ -0.66457736, 146.29776001, 2.55697036]), + 'Velocity': array([-1.01844859, 0.42340586, 0.0198098 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5583.482421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4740.81640625, 13784.79882812, 106.24485779]), + 'frame': 25425, + 'frame_number': 25425, + 'framesequence': 102395, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47874388098716736, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.059019152075, + 'timestamp_carla': 865057, + 'timestamp_device': 1735657, + 'timestamp_stream': 865.059019152075, + 'transform': [array([-4.71983566e+01, 6.86886902e+01, -6.53055459e-02]), + array([-3.22384899e-03, -1.78561218e+02, -1.66870087e-01])]} +{'AngularVelocity': array([ 0.47179443, -1.08919656, 7.67139721]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.2607364654541, + 'FR_Wheel_Angle': 20.57577896118164, + 'Location': array([-4.22890701e+01, 9.93992462e+01, 7.82386735e-02]), + 'Rotation': array([ -0.79732895, 147.75666809, 2.70572805]), + 'Velocity': array([-1.04976845, 0.40268236, 0.01633895]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5572.25830078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4717.76269531, 13776.2421875 , 106.1506958 ]), + 'frame': 25426, + 'frame_number': 25426, + 'framesequence': 102399, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47953125834465027, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.0932391509414, + 'timestamp_carla': 865092, + 'timestamp_device': 1735690, + 'timestamp_stream': 865.0932391509414, + 'transform': [array([-4.72465706e+01, 6.87153473e+01, -6.50639012e-02]), + array([-3.53803788e-03, -1.78791428e+02, -1.68151855e-01])]} +{'AngularVelocity': array([ 0.44439888, -0.95220262, 7.68595362]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.255647659301758, + 'FR_Wheel_Angle': 20.567211151123047, + 'Location': array([-4.24633789e+01, 9.94721451e+01, 8.10906962e-02]), + 'Rotation': array([ -0.88705027, 148.97428894, 2.83714271]), + 'Velocity': array([-1.07881939, 0.39027405, 0.01267091]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5514.27978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4694.80810547, 13720.70898438, 106.21648407]), + 'frame': 25427, + 'frame_number': 25427, + 'framesequence': 102403, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48026371002197266, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.1257911510766, + 'timestamp_carla': 865124, + 'timestamp_device': 1735723, + 'timestamp_stream': 865.1257911510766, + 'transform': [array([-4.72903786e+01, 6.87403336e+01, -6.48170486e-02]), + array([-3.90686793e-03, -1.79001663e+02, -1.69372529e-01])]} +{'AngularVelocity': array([ 0.48857364, -0.9370113 , 7.50850773]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.260643005371094, + 'FR_Wheel_Angle': 20.5751953125, + 'Location': array([-4.26394577e+01, 9.95413055e+01, 8.19728449e-02]), + 'Rotation': array([ -0.91372901, 150.17984009, 2.87261677]), + 'Velocity': array([-1.05408072, 0.35751182, 0.00931931]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5479.091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4671.35791016, 13688.04296875, 106.19223022]), + 'frame': 25428, + 'frame_number': 25428, + 'framesequence': 102407, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4801538288593292, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.1589687503874, + 'timestamp_carla': 865157, + 'timestamp_device': 1735757, + 'timestamp_stream': 865.1589687503874, + 'transform': [array([-4.73354301e+01, 6.87657089e+01, -6.45932853e-02]), + array([-4.64452850e-03, -1.79217834e+02, -1.70562714e-01])]} +{'AngularVelocity': array([-2.62893915, 6.03692532, 6.2393508 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.986695289611816, + 'FR_Wheel_Angle': 14.860798835754395, + 'Location': array([-4.28498726e+01, 9.96198044e+01, 6.05543107e-02]), + 'Rotation': array([-9.40243825e-02, 1.51558823e+02, 1.56325662e+00]), + 'Velocity': array([-0.97510457, 0.3988122 , -0.10378049]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5453.52001953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4650.28271484, 13664.734375 , 106.14841461]), + 'frame': 25429, + 'frame_number': 25429, + 'framesequence': 102411, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4798242151737213, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.1934054493904, + 'timestamp_carla': 865192, + 'timestamp_device': 1735790, + 'timestamp_stream': 865.1934054493904, + 'transform': [array([-4.73815231e+01, 6.87916794e+01, -6.43707514e-02]), + array([-5.32754743e-03, -1.79439484e+02, -1.71783417e-01])]} +{'AngularVelocity': array([-1.06995749, 1.79190946, 6.41637564]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.794706344604492, + 'FR_Wheel_Angle': 17.347139358520508, + 'Location': array([-4.30210342e+01, 9.96876068e+01, 4.87615578e-02]), + 'Rotation': array([ 0.2662476 , 152.51911926, 1.05921638]), + 'Velocity': array([-1.02136505, 0.35966414, -0.02836106]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5402.80419921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4628.47851562, 13616.21679688, 106.18346405]), + 'frame': 25430, + 'frame_number': 25430, + 'framesequence': 102415, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.2262146510184, + 'timestamp_carla': 865225, + 'timestamp_device': 1735823, + 'timestamp_stream': 865.2262146510184, + 'transform': [array([-4.74248962e+01, 6.88161316e+01, -6.41406104e-02]), + array([-5.64173609e-03, -1.79648300e+02, -1.72912583e-01])]} +{'AngularVelocity': array([-0.51759291, 0.72173345, 6.28333282]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.049115180969238, + 'FR_Wheel_Angle': 16.421680450439453, + 'Location': array([-4.31955223e+01, 9.97511978e+01, 4.55806740e-02]), + 'Rotation': array([ 0.38155484, 153.54350281, 0.86282837]), + 'Velocity': array([-1.05802166, 0.35205516, -0.00769821]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5382.97705078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4606.82275391, 13598.53320312, 106.1237793 ]), + 'frame': 25431, + 'frame_number': 25431, + 'framesequence': 102419, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.2585666514933, + 'timestamp_carla': 865257, + 'timestamp_device': 1735857, + 'timestamp_stream': 865.2585666514933, + 'transform': [array([-4.74666748e+01, 6.88399048e+01, -6.39135912e-02]), + array([-5.86713199e-03, -1.79849823e+02, -1.74011230e-01])]} +{'AngularVelocity': array([-0.39626873, 0.21006729, 6.5421133 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.181595802307129, + 'FR_Wheel_Angle': 16.423982620239258, + 'Location': array([-4.34137878e+01, 9.98262177e+01, 4.45976257e-02]), + 'Rotation': array([ 0.43192065, 154.79496765, 0.75443298]), + 'Velocity': array([-1.10064220e+00, 3.31848294e-01, 1.02367398e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5339.41943359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4586.40820312, 13556.90039062, 106.14715576]), + 'frame': 25432, + 'frame_number': 25432, + 'framesequence': 102423, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.2932678498328, + 'timestamp_carla': 865292, + 'timestamp_device': 1735890, + 'timestamp_stream': 865.2932678498328, + 'transform': [array([-4.75103226e+01, 6.88650665e+01, -6.37146458e-02]), + array([-6.30426407e-03, 1.79938995e+02, -1.75109819e-01])]} +{'AngularVelocity': array([-0.40078032, -0.02232501, 6.32167387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.21635627746582, + 'FR_Wheel_Angle': 16.42839241027832, + 'Location': array([-4.36267509e+01, 9.98938522e+01, 4.52875905e-02]), + 'Rotation': array([ 0.41450366, 155.99118042, 0.66226786]), + 'Velocity': array([-1.12873816, 0.31444418, 0.00428488]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5317.34619140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4567.04980469, 13536.6171875 , 106.11023712]), + 'frame': 25433, + 'frame_number': 25433, + 'framesequence': 102427, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.3265795521438, + 'timestamp_carla': 865325, + 'timestamp_device': 1735923, + 'timestamp_stream': 865.3265795521438, + 'transform': [array([-4.75519829e+01, 6.88889160e+01, -6.33480921e-02]), + array([-5.54611348e-03, 1.79737518e+02, -1.76666215e-01])]} +{'AngularVelocity': array([-0.34716964, -0.05447853, 6.72624731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.215705871582031, + 'FR_Wheel_Angle': 16.421798706054688, + 'Location': array([-4.38554878e+01, 9.99609833e+01, 4.64957803e-02]), + 'Rotation': array([ 0.38324189, 157.25926208, 0.5875327 ]), + 'Velocity': array([-1.17170334, 0.29680461, 0.00450253]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5255.369140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4546.9609375 , 13476.45214844, 106.19275665]), + 'frame': 25434, + 'frame_number': 25434, + 'framesequence': 102431, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.3582199513912, + 'timestamp_carla': 865357, + 'timestamp_device': 1735957, + 'timestamp_stream': 865.3582199513912, + 'transform': [array([-4.75902824e+01, 6.89112091e+01, -6.31429628e-02]), + array([-5.92860393e-03, 1.79551575e+02, -1.77642807e-01])]} +{'AngularVelocity': array([-0.36221504, -0.08362681, 6.81532192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.210556983947754, + 'FR_Wheel_Angle': 16.414804458618164, + 'Location': array([-4.40536079e+01, 1.00014687e+02, 4.74195853e-02]), + 'Rotation': array([ 0.35441849, 158.34928894, 0.53109217]), + 'Velocity': array([-1.19960773, 0.27915409, 0.00471528]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5215.35302734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4528.13867188, 13438.06640625, 106.17169952]), + 'frame': 25435, + 'frame_number': 25435, + 'framesequence': 102435, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.3927922509611, + 'timestamp_carla': 865391, + 'timestamp_device': 1735990, + 'timestamp_stream': 865.3927922509611, + 'transform': [array([-4.76310005e+01, 6.89352493e+01, -6.30421564e-02]), + array([-7.67030194e-03, 1.79353210e+02, -1.78466767e-01])]} +{'AngularVelocity': array([-0.3370553 , -0.11373921, 6.87251329]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.205418586730957, + 'FR_Wheel_Angle': 16.408042907714844, + 'Location': array([-4.42560654e+01, 1.00065399e+02, 4.84131984e-02]), + 'Rotation': array([ 0.32057491, 159.44863892, 0.47515565]), + 'Velocity': array([-1.22762048, 0.26149163, 0.00463219]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5185.400390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4510.95214844, 13409.57421875, 106.17475128]), + 'frame': 25436, + 'frame_number': 25436, + 'framesequence': 102439, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.4245153516531, + 'timestamp_carla': 865423, + 'timestamp_device': 1736023, + 'timestamp_stream': 865.4245153516531, + 'transform': [array([-4.76681290e+01, 6.89570084e+01, -6.29061460e-02]), + array([-9.23441537e-03, 1.79172546e+02, -1.79290742e-01])]} +{'AngularVelocity': array([-0.32135943, -0.11778522, 7.04772472]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.367838859558105, + 'FR_Wheel_Angle': 13.947300910949707, + 'Location': array([-4.44634171e+01, 1.00113251e+02, 4.93668728e-02]), + 'Rotation': array([ 0.28647178, 160.57176208, 0.4226661 ]), + 'Velocity': array([-1.25532496, 0.24325262, 0.00474555]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5140.64892578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4492.96582031, 13366.33398438, 106.23622894]), + 'frame': 25437, + 'frame_number': 25437, + 'framesequence': 102443, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.459340352565, + 'timestamp_carla': 865458, + 'timestamp_device': 1736057, + 'timestamp_stream': 865.459340352565, + 'transform': [array([-4.77073631e+01, 6.89805069e+01, -6.29552528e-02]), + array([-1.04501890e-02, 1.78980743e+02, -1.79473862e-01])]} +{'AngularVelocity': array([-0.34976053, -0.12404504, 5.09587002]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.111159324645996, + 'FR_Wheel_Angle': 12.045856475830078, + 'Location': array([-4.47182884e+01, 1.00173462e+02, 5.04866391e-02]), + 'Rotation': array([ 0.24633075, 161.66168213, 0.36858147]), + 'Velocity': array([-1.27202296, 0.28132308, 0.00405749]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5122.09716796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4476.54052734, 13349.07617188, 106.21989441]), + 'frame': 25438, + 'frame_number': 25438, + 'framesequence': 102447, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.4921295493841, + 'timestamp_carla': 865490, + 'timestamp_device': 1736090, + 'timestamp_stream': 865.4921295493841, + 'transform': [array([-4.77441254e+01, 6.90024796e+01, -6.30446598e-02]), + array([-1.11810192e-02, 1.78800888e+02, -1.79351777e-01])]} +{'AngularVelocity': array([-0.28637913, -0.1262801 , 5.95433331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.18050765991211, + 'FR_Wheel_Angle': 12.075572967529297, + 'Location': array([-4.49342842e+01, 1.00221413e+02, 5.13842367e-02]), + 'Rotation': array([ 0.21456355, 162.58537292, 0.31411922]), + 'Velocity': array([-1.30176485, 0.24862228, 0.0038941 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5070.33154296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4459.78369141, 13298.66210938, 106.36058044]), + 'frame': 25439, + 'frame_number': 25439, + 'framesequence': 102451, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.5247949510813, + 'timestamp_carla': 865523, + 'timestamp_device': 1736123, + 'timestamp_stream': 865.5247949510813, + 'transform': [array([-4.77795677e+01, 6.90239105e+01, -6.31211102e-02]), + array([-1.15293590e-02, 1.78627151e+02, -1.79260209e-01])]} +{'AngularVelocity': array([-0.28943187, -0.12651193, 5.98042202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.10737133026123, + 'FR_Wheel_Angle': 12.427881240844727, + 'Location': array([-4.51552010e+01, 1.00267235e+02, 5.22257611e-02]), + 'Rotation': array([ 0.18459952, 163.49839783, 0.26797447]), + 'Velocity': array([-1.32543266, 0.23429064, 0.00363805]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5058.41943359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4443.62207031, 13287.94140625, 106.40517426]), + 'frame': 25440, + 'frame_number': 25440, + 'framesequence': 102455, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.5589757524431, + 'timestamp_carla': 865557, + 'timestamp_device': 1736157, + 'timestamp_stream': 865.5589757524431, + 'transform': [array([-4.78158531e+01, 6.90459137e+01, -6.31883964e-02]), + array([-1.14337364e-02, 1.78449265e+02, -1.79229721e-01])]} +{'AngularVelocity': array([-0.26912999, -0.12682721, 5.87003708]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.98436164855957, + 'FR_Wheel_Angle': 12.309429168701172, + 'Location': array([-4.53790474e+01, 1.00309715e+02, 5.30387871e-02]), + 'Rotation': array([1.55714646e-01, 1.64425858e+02, 2.23421246e-01]), + 'Velocity': array([-1.35029387, 0.21676305, 0.00371451]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5005.3779296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4429.0703125 , 13236.02734375, 106.57524109]), + 'frame': 25441, + 'frame_number': 25441, + 'framesequence': 102459, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.5928990505636, + 'timestamp_carla': 865591, + 'timestamp_device': 1736190, + 'timestamp_stream': 865.5928990505636, + 'transform': [array([-4.78510818e+01, 6.90676422e+01, -6.33527488e-02]), + array([-1.22533590e-02, 1.78275818e+02, -1.78863496e-01])]} +{'AngularVelocity': array([-0.2515755 , -0.12852606, 5.95379162]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.986761093139648, + 'FR_Wheel_Angle': 12.273816108703613, + 'Location': array([-4.56062012e+01, 1.00349060e+02, 5.38136661e-02]), + 'Rotation': array([1.28066033e-01, 1.65363647e+02, 1.80869102e-01]), + 'Velocity': array([-1.37348187, 0.19720714, 0.00353463]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4993.77099609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4413.34960938, 13225.51171875, 106.60758972]), + 'frame': 25442, + 'frame_number': 25442, + 'framesequence': 102463, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.6259112507105, + 'timestamp_carla': 865624, + 'timestamp_device': 1736223, + 'timestamp_stream': 865.6259112507105, + 'transform': [array([-4.78865166e+01, 6.90888977e+01, -6.35269061e-02]), + array([-1.29910195e-02, 1.78102066e+02, -1.78405732e-01])]} +{'AngularVelocity': array([-0.00710964, -0.04347534, 6.10119867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.982654571533203, + 'FR_Wheel_Angle': 12.269258499145508, + 'Location': array([-4.58369293e+01, 1.00385506e+02, 5.42119965e-02]), + 'Rotation': array([1.15184307e-01, 1.66318970e+02, 1.63092867e-01]), + 'Velocity': array([-1.39720774e+00, 1.77989110e-01, 4.07590851e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4942.4912109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4399.28515625, 13175.28417969, 106.79532623]), + 'frame': 25443, + 'frame_number': 25443, + 'framesequence': 102467, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.6585158519447, + 'timestamp_carla': 865657, + 'timestamp_device': 1736257, + 'timestamp_stream': 865.6585158519447, + 'transform': [array([-4.79191895e+01, 6.91093369e+01, -6.36515990e-02]), + array([-1.35852452e-02, 1.77940598e+02, -1.78131104e-01])]} +{'AngularVelocity': array([ 1.24907412e-03, -4.28994298e-02, 6.18931293e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.980234146118164, + 'FR_Wheel_Angle': 12.265965461730957, + 'Location': array([-4.61207428e+01, 1.00425148e+02, 5.42431995e-02]), + 'Rotation': array([1.12991810e-01, 1.67499786e+02, 1.59278736e-01]), + 'Velocity': array([-1.41469467e+00, 1.50744081e-01, -6.46400440e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4928.7666015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4384.27636719, 13162.4921875 , 106.87274933]), + 'frame': 25444, + 'frame_number': 25444, + 'framesequence': 102471, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.6924578510225, + 'timestamp_carla': 865691, + 'timestamp_device': 1736290, + 'timestamp_stream': 865.6924578510225, + 'transform': [array([-4.79526176e+01, 6.91304321e+01, -6.37990087e-02]), + array([-1.42546045e-02, 1.77774994e+02, -1.77825868e-01])]} +{'AngularVelocity': array([ 9.37740260e-04, -4.48907502e-02, 6.22360420e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.978753089904785, + 'FR_Wheel_Angle': 12.264747619628906, + 'Location': array([-4.63590775e+01, 1.00453865e+02, 5.42753600e-02]), + 'Rotation': array([1.10935926e-01, 1.68488937e+02, 1.56280696e-01]), + 'Velocity': array([-1.42507625e+00, 1.27104834e-01, 1.10826491e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4884.046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4371.53125 , 13118.68066406, 107.03123474]), + 'frame': 25445, + 'frame_number': 25445, + 'framesequence': 102475, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.7251066491008, + 'timestamp_carla': 865723, + 'timestamp_device': 1736323, + 'timestamp_stream': 865.7251066491008, + 'transform': [array([-4.79838791e+01, 6.91503983e+01, -6.38978779e-02]), + array([-1.47463772e-02, 1.77619614e+02, -1.77642807e-01])]} +{'AngularVelocity': array([-0.07013155, -0.08580177, 5.6338377 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.02182388305664, + 'FR_Wheel_Angle': 9.605511665344238, + 'Location': array([-4.65988655e+01, 1.00478416e+02, 5.45518100e-02]), + 'Rotation': array([1.00458413e-01, 1.69452057e+02, 1.40907735e-01]), + 'Velocity': array([-1.43343437, 0.11297957, 0.00187811]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4862.69873046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4357.76220703, 13098.21679688, 107.1183548 ]), + 'frame': 25446, + 'frame_number': 25446, + 'framesequence': 102479, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.7585699521005, + 'timestamp_carla': 865757, + 'timestamp_device': 1736357, + 'timestamp_stream': 865.7585699521005, + 'transform': [array([-4.80152969e+01, 6.91706161e+01, -6.39974400e-02]), + array([-1.52313206e-02, 1.77463226e+02, -1.77490175e-01])]} +{'AngularVelocity': array([-0.13960101, -0.07827016, 3.82145739]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.769157886505127, + 'FR_Wheel_Angle': 8.03266716003418, + 'Location': array([-4.68384056e+01, 1.00506119e+02, 5.49052805e-02]), + 'Rotation': array([8.81162658e-02, 1.70104233e+02, 1.30383417e-01]), + 'Velocity': array([-1.43240964, 0.15111434, 0.00177163]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4810.48046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4346.28808594, 13046.83105469, 107.29199982]), + 'frame': 25447, + 'frame_number': 25447, + 'framesequence': 102483, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.7927192524076, + 'timestamp_carla': 865791, + 'timestamp_device': 1736390, + 'timestamp_stream': 865.7927192524076, + 'transform': [array([-4.80462494e+01, 6.91908417e+01, -6.40778244e-02]), + array([-1.56616233e-02, 1.77308548e+02, -1.77429184e-01])]} +{'AngularVelocity': array([-0.08688343, -0.07603548, 4.36674309]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.70322847366333, + 'FR_Wheel_Angle': 7.957704544067383, + 'Location': array([-4.70785713e+01, 1.00530922e+02, 5.52395247e-02]), + 'Rotation': array([7.63068721e-02, 1.70791473e+02, 1.06521003e-01]), + 'Velocity': array([-1.43775475, 0.11710421, 0.00177135]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4784.3251953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4333.8515625 , 13021.46679688, 107.3814621 ]), + 'frame': 25448, + 'frame_number': 25448, + 'framesequence': 102487, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.825837649405, + 'timestamp_carla': 865824, + 'timestamp_device': 1736423, + 'timestamp_stream': 865.825837649405, + 'transform': [array([-4.80761375e+01, 6.92102356e+01, -6.41520172e-02]), + array([-1.60987545e-02, 1.77159271e+02, -1.77337646e-01])]} +{'AngularVelocity': array([-0.09700702, -0.07385322, 4.36242867]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.709573268890381, + 'FR_Wheel_Angle': 8.286909103393555, + 'Location': array([-4.73219185e+01, 1.00553696e+02, 5.55350855e-02]), + 'Rotation': array([6.55698106e-02, 1.71464096e+02, 9.01565105e-02]), + 'Velocity': array([-1.43728268, 0.10231432, 0.00148893]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4779.51708984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4320.69580078, 13017.40039062, 107.39577484]), + 'frame': 25449, + 'frame_number': 25449, + 'framesequence': 102491, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.8587229512632, + 'timestamp_carla': 865857, + 'timestamp_device': 1736457, + 'timestamp_stream': 865.8587229512632, + 'transform': [array([-4.81051559e+01, 6.92293243e+01, -6.42588586e-02]), + array([-1.67339630e-02, 1.77013809e+02, -1.77123994e-01])]} +{'AngularVelocity': array([-0.0746804 , -0.07798982, 4.33486748]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.589282989501953, + 'FR_Wheel_Angle': 8.20491886138916, + 'Location': array([-4.75625229e+01, 1.00573120e+02, 5.58037162e-02]), + 'Rotation': array([5.59187569e-02, 1.72129318e+02, 7.51785561e-02]), + 'Velocity': array([-1.43739891e+00, 8.68498385e-02, 1.08239171e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4742.32470703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4309.64111328, 12980.91210938, 107.51450348]), + 'frame': 25450, + 'frame_number': 25450, + 'framesequence': 102495, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.8942338488996, + 'timestamp_carla': 865893, + 'timestamp_device': 1736490, + 'timestamp_stream': 865.8942338488996, + 'transform': [array([-4.81352272e+01, 6.92493896e+01, -6.43325597e-02]), + array([-1.70891322e-02, 1.76862625e+02, -1.77124038e-01])]} +{'AngularVelocity': array([-0.06424565, -0.0712924 , 4.26544714]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.5658464431762695, + 'FR_Wheel_Angle': 8.16031551361084, + 'Location': array([-4.78027763e+01, 1.00589760e+02, 5.60554117e-02]), + 'Rotation': array([4.68346030e-02, 1.72795456e+02, 6.18857779e-02]), + 'Velocity': array([-1.43087721e+00, 6.97030351e-02, 1.29039760e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4713.76318359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4298.64941406, 12953.01464844, 107.61680603]), + 'frame': 25451, + 'frame_number': 25451, + 'framesequence': 102499, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47561267018318176, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.9276050515473, + 'timestamp_carla': 865926, + 'timestamp_device': 1736523, + 'timestamp_stream': 865.9276050515473, + 'transform': [array([-4.81630440e+01, 6.92679214e+01, -6.43713474e-02]), + array([-1.72257368e-02, 1.76722794e+02, -1.77124009e-01])]} +{'AngularVelocity': array([-0.08969563, -0.00958462, 3.56062365]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.574551105499268, + 'FR_Wheel_Angle': 8.169652938842773, + 'Location': array([-4.80613174e+01, 1.00604614e+02, 5.62591553e-02]), + 'Rotation': array([3.77026424e-02, 1.73515762e+02, 4.93006967e-02]), + 'Velocity': array([-1.43291688e+00, 4.96783331e-02, 6.41708379e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4677.12451171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4287.75439453, 12917.06542969, 107.72392273]), + 'frame': 25452, + 'frame_number': 25452, + 'framesequence': 102503, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4589312672615051, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.9587408490479, + 'timestamp_carla': 865957, + 'timestamp_device': 1736557, + 'timestamp_stream': 865.9587408490479, + 'transform': [array([-4.81873512e+01, 6.92848053e+01, -6.44118413e-02]), + array([-1.72189064e-02, 1.76599808e+02, -1.77032471e-01])]} +{'AngularVelocity': array([-7.83845112e-02, -1.48831087e-03, 3.59682655e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.577765941619873, + 'FR_Wheel_Angle': 8.17333698272705, + 'Location': array([-4.82917366e+01, 1.00615089e+02, 5.64841442e-02]), + 'Rotation': array([3.11661512e-02, 1.74160095e+02, 3.93145680e-02]), + 'Velocity': array([-1.41819990e+00, 3.30000222e-02, 1.19093887e-03]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4647.75, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4277.59130859, 12888.29101562, 107.81135559]), + 'frame': 25453, + 'frame_number': 25453, + 'framesequence': 102507, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4379284381866455, + 'throttle_input': 0.019836727529764175, + 'timestamp': 865.9920223504305, + 'timestamp_carla': 865990, + 'timestamp_device': 1736590, + 'timestamp_stream': 865.9920223504305, + 'transform': [array([-4.82124023e+01, 6.93025208e+01, -6.44847080e-02]), + array([-1.69320386e-02, 1.76473297e+02, -1.76879853e-01])]} +{'AngularVelocity': array([-0.04282027, 0.01898997, 3.67554879]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.5804762840271, + 'FR_Wheel_Angle': 8.178013801574707, + 'Location': array([-4.85671463e+01, 1.00624565e+02, 5.66040017e-02]), + 'Rotation': array([2.65489444e-02, 1.74951096e+02, 3.35163288e-02]), + 'Velocity': array([-1.38489830e+00, 1.46302329e-02, 4.66184603e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4650.8525390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4267.04345703, 12891.90527344, 107.80757141]), + 'frame': 25454, + 'frame_number': 25454, + 'framesequence': 102511, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41381269693374634, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.0261955522001, + 'timestamp_carla': 866025, + 'timestamp_device': 1736623, + 'timestamp_stream': 866.0261955522001, + 'transform': [array([-4.82359848e+01, 6.93201523e+01, -6.45519793e-02]), + array([-1.64812449e-02, 1.76353485e+02, -1.76757798e-01])]} +{'AngularVelocity': array([0.01780613, 0.01943136, 2.76097202]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 5.837608337402344, + 'FR_Wheel_Angle': 4.506757736206055, + 'Location': array([-4.87934303e+01, 1.00630028e+02, 5.66524491e-02]), + 'Rotation': array([2.40695849e-02, 1.75574142e+02, 3.26068960e-02]), + 'Velocity': array([-1.35097456e+00, 1.89051237e-02, 1.90963736e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4594.044921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4259.87695312, 12835.74609375, 107.99043274]), + 'frame': 25455, + 'frame_number': 25455, + 'framesequence': 102515, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3955748379230499, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.054016251117, + 'timestamp_carla': 866052, + 'timestamp_device': 1736657, + 'timestamp_stream': 866.054016251117, + 'transform': [array([-4.82514000e+01, 6.93337402e+01, -6.46466166e-02]), + array([-1.59553215e-02, 1.76272919e+02, -1.76544189e-01])]} +{'AngularVelocity': array([-0.07760973, 0.02361332, 1.38294661]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.349912643432617, + 'FR_Wheel_Angle': 4.983791828155518, + 'Location': array([-4.90121384e+01, 1.00640320e+02, 5.66989519e-02]), + 'Rotation': array([2.22459249e-02, 1.75891342e+02, 3.52946892e-02]), + 'Velocity': array([-1.31574953e+00, 5.01659587e-02, -6.21795652e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4583.3125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4250.56738281, 12825.61132812, 108.02849579]), + 'frame': 25456, + 'frame_number': 25456, + 'framesequence': 102519, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3947325348854065, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.0927939489484, + 'timestamp_carla': 866091, + 'timestamp_device': 1736690, + 'timestamp_stream': 866.0927939489484, + 'transform': [array([-4.82761116e+01, 6.93528976e+01, -6.47982508e-02]), + array([-1.65290572e-02, 1.76147232e+02, -1.76300004e-01])]} +{'AngularVelocity': array([-0.00915443, 0.0230473 , 1.38983309]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.5786502361297607, + 'FR_Wheel_Angle': 3.800323963165283, + 'Location': array([-4.92661514e+01, 1.00649239e+02, 5.67570850e-02]), + 'Rotation': array([2.01422274e-02, 1.76304398e+02, 2.82323025e-02]), + 'Velocity': array([-1.27243590e+00, 3.42541374e-02, 2.70833960e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4551.955078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4245.86328125, 12794.86621094, 108.13577271]), + 'frame': 25457, + 'frame_number': 25457, + 'framesequence': 102523, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4061220586299896, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.1209972500801, + 'timestamp_carla': 866119, + 'timestamp_device': 1736723, + 'timestamp_stream': 866.1209972500801, + 'transform': [array([-4.82933617e+01, 6.93661270e+01, -6.47153258e-02]), + array([-1.67681128e-02, 1.76059494e+02, -1.76818788e-01])]} +{'AngularVelocity': array([-0.02287993, 0.02277244, 1.49021769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.031965732574463, + 'FR_Wheel_Angle': 4.071949481964111, + 'Location': array([-4.94725418e+01, 1.00655693e+02, 5.67845888e-02]), + 'Rotation': array([1.85644533e-02, 1.76622467e+02, 2.50916258e-02]), + 'Velocity': array([-1.22840130e+00, 2.17667241e-02, 5.99765772e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4526.046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4237.21777344, 12769.64746094, 108.22698212]), + 'frame': 25458, + 'frame_number': 25458, + 'framesequence': 102527, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4165593385696411, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.1592412516475, + 'timestamp_carla': 866158, + 'timestamp_device': 1736757, + 'timestamp_stream': 866.1592412516475, + 'transform': [array([-4.83176346e+01, 6.93845367e+01, -6.48428798e-02]), + array([-1.81819629e-02, 1.75935959e+02, -1.76635697e-01])]} +{'AngularVelocity': array([-0.01976123, 0.02468499, 1.41541922]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9751477241516113, + 'FR_Wheel_Angle': 4.099352836608887, + 'Location': array([-4.96694183e+01, 1.00660606e+02, 5.68216294e-02]), + 'Rotation': array([1.70003399e-02, 1.76918076e+02, 2.34942660e-02]), + 'Velocity': array([-1.17856145e+00, 1.54531477e-02, 3.62205494e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4516.35888671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4230.67382812, 12760.39648438, 108.21289062]), + 'frame': 25459, + 'frame_number': 25459, + 'framesequence': 102531, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4299081563949585, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.1901464499533, + 'timestamp_carla': 866189, + 'timestamp_device': 1736790, + 'timestamp_stream': 866.1901464499533, + 'transform': [array([-4.83358231e+01, 6.93986206e+01, -6.47937655e-02]), + array([-1.87761895e-02, 1.75842590e+02, -1.76818818e-01])]} +{'AngularVelocity': array([-0.01742514, 0.02868751, 1.28391266]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.954197406768799, + 'FR_Wheel_Angle': 4.112238883972168, + 'Location': array([-4.98576050e+01, 1.00664391e+02, 5.68502806e-02]), + 'Rotation': array([1.59826409e-02, 1.77203049e+02, 2.21651625e-02]), + 'Velocity': array([-1.13148427e+00, 9.47582722e-03, -4.87327561e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4483.22265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4222.89892578, 12727.87890625, 108.32595825]), + 'frame': 25460, + 'frame_number': 25460, + 'framesequence': 102535, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4327280521392822, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.2254834510386, + 'timestamp_carla': 866224, + 'timestamp_device': 1736823, + 'timestamp_stream': 866.2254834510386, + 'transform': [array([-4.83563080e+01, 6.94143600e+01, -6.47878721e-02]), + array([-1.91859994e-02, 1.75737488e+02, -1.77032456e-01])]} +{'AngularVelocity': array([-0.00711131, 0.02568093, 1.37819827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.957474946975708, + 'FR_Wheel_Angle': 4.1152448654174805, + 'Location': array([-5.00383224e+01, 1.00667099e+02, 5.68653867e-02]), + 'Rotation': array([1.48898112e-02, 1.77483826e+02, 2.16402337e-02]), + 'Velocity': array([-1.08400166e+00, 2.74304929e-03, 1.09205241e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4464.5146484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4216.64306641, 12709.62890625, 108.37194061]), + 'frame': 25461, + 'frame_number': 25461, + 'framesequence': 102539, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4278390109539032, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.2594921514392, + 'timestamp_carla': 866258, + 'timestamp_device': 1736857, + 'timestamp_stream': 866.2594921514392, + 'transform': [array([-4.83754044e+01, 6.94288940e+01, -6.47347793e-02]), + array([-1.91040374e-02, 1.75639832e+02, -1.77337617e-01])]} +{'AngularVelocity': array([-0.00365862, 0.03102554, 1.34573853]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.95951509475708, + 'FR_Wheel_Angle': 4.117432594299316, + 'Location': array([-5.02188416e+01, 1.00668854e+02, 5.68325408e-02]), + 'Rotation': array([1.43433968e-02, 1.77772141e+02, 2.23897267e-02]), + 'Velocity': array([-1.06261098e+00, -2.81212083e-03, -2.19478607e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4450.23583984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4209.16992188, 12695.82421875, 108.39659119]), + 'frame': 25462, + 'frame_number': 25462, + 'framesequence': 102543, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4213935136795044, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.2930619493127, + 'timestamp_carla': 866291, + 'timestamp_device': 1736890, + 'timestamp_stream': 866.2930619493127, + 'transform': [array([-4.83936615e+01, 6.94426956e+01, -6.47041425e-02]), + array([-1.90357361e-02, 1.75546707e+02, -1.77551255e-01])]} +{'AngularVelocity': array([ 0.01530879, -0.04608642, 1.89160931]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9597105979919434, + 'FR_Wheel_Angle': 4.1178107261657715, + 'Location': array([-5.03846321e+01, 1.00669754e+02, 5.68444803e-02]), + 'Rotation': array([1.26016987e-02, 1.78049896e+02, 2.36508157e-02]), + 'Velocity': array([-9.85712886e-01, -6.33424334e-03, -1.50480264e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4452.6357421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4201.08886719, 12698.59472656, 108.36320496]), + 'frame': 25463, + 'frame_number': 25463, + 'framesequence': 102547, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4147648811340332, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.3252375498414, + 'timestamp_carla': 866324, + 'timestamp_device': 1736923, + 'timestamp_stream': 866.3252375498414, + 'transform': [array([-4.84103508e+01, 6.94553986e+01, -6.46904707e-02]), + array([-1.90767180e-02, 1.75461533e+02, -1.77673295e-01])]} +{'AngularVelocity': array([ 0.04183979, -0.03922356, 0.50349063]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.6660609245300293, + 'FR_Wheel_Angle': -1.550622582435608, + 'Location': array([-5.05817871e+01, 1.00671394e+02, 5.68531789e-02]), + 'Rotation': array([1.12083396e-02, 1.78270782e+02, 2.95609273e-02]), + 'Velocity': array([-9.43169832e-01, 2.71824133e-02, 2.18391415e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4406.34423828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4197.15527344, 12652.78125 , 108.4885788 ]), + 'frame': 25464, + 'frame_number': 25464, + 'framesequence': 102551, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41368451714515686, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.3605106510222, + 'timestamp_carla': 866359, + 'timestamp_device': 1736957, + 'timestamp_stream': 866.3605106510222, + 'transform': [array([-4.84276352e+01, 6.94687805e+01, -6.47249520e-02]), + array([-1.91859994e-02, 1.75373108e+02, -1.77734330e-01])]} +{'AngularVelocity': array([-0.02782939, -0.03974334, 0.82541835]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5278113484382629, + 'FR_Wheel_Angle': 0.047889769077301025, + 'Location': array([-5.07711449e+01, 1.00677750e+02, 5.68772107e-02]), + 'Rotation': array([1.11058867e-02, 1.78275330e+02, 2.44976468e-02]), + 'Velocity': array([-9.04678762e-01, 1.90276336e-02, 3.94930830e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4389.8935546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4191.63916016, 12636.69238281, 108.52828217]), + 'frame': 25465, + 'frame_number': 25465, + 'framesequence': 102555, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4163213074207306, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.3916417509317, + 'timestamp_carla': 866390, + 'timestamp_device': 1736990, + 'timestamp_stream': 866.3916417509317, + 'transform': [array([-4.84423332e+01, 6.94801254e+01, -6.47488683e-02]), + array([-1.96299627e-02, 1.75297806e+02, -1.77703843e-01])]} +{'AngularVelocity': array([-0.01812441, -0.04072687, 0.5700295 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.002521478570997715, + 'FR_Wheel_Angle': 0.17652666568756104, + 'Location': array([-5.09526863e+01, 1.00683090e+02, 5.68824001e-02]), + 'Rotation': array([1.11741889e-02, 1.78313538e+02, 2.34929882e-02]), + 'Velocity': array([-8.70496035e-01, 2.50984896e-02, 6.77299467e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4385.0322265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4184.9765625 , 12632.17480469, 108.53413391]), + 'frame': 25466, + 'frame_number': 25466, + 'framesequence': 102559, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.4249751493335, + 'timestamp_carla': 866423, + 'timestamp_device': 1737023, + 'timestamp_stream': 866.4249751493335, + 'transform': [array([-4.84575424e+01, 6.94919205e+01, -6.48041219e-02]), + array([-2.00261138e-02, 1.75219742e+02, -1.77642778e-01])]} +{'AngularVelocity': array([-0.00716335, -0.03804803, 0.53066969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.06307108700275421, + 'FR_Wheel_Angle': 0.020183779299259186, + 'Location': array([-5.10978699e+01, 1.00687286e+02, 5.69067746e-02]), + 'Rotation': array([1.10375853e-02, 1.78349228e+02, 2.20582150e-02]), + 'Velocity': array([-8.44752491e-01, 2.37071384e-02, 3.10115807e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4386.88134765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4178.82519531, 12634.28320312, 108.53034973]), + 'frame': 25467, + 'frame_number': 25467, + 'framesequence': 102563, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42241889238357544, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.4571209512651, + 'timestamp_carla': 866456, + 'timestamp_device': 1737057, + 'timestamp_stream': 866.4571209512651, + 'transform': [array([-4.84716988e+01, 6.95028381e+01, -6.48400709e-02]), + array([-2.03949437e-02, 1.75147079e+02, -1.77612290e-01])]} +{'AngularVelocity': array([-0.0061767 , -0.03732528, 0.58522236]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.015146322548389435, + 'FR_Wheel_Angle': -0.013884227722883224, + 'Location': array([-5.12399635e+01, 1.00691353e+02, 5.69136404e-02]), + 'Rotation': array([1.05458116e-02, 1.78383011e+02, 2.10070554e-02]), + 'Velocity': array([-8.11377823e-01, 2.19340157e-02, 1.10559464e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4343.806640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4176.19042969, 12591.62597656, 108.66638184]), + 'frame': 25468, + 'frame_number': 25468, + 'framesequence': 102567, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42219915986061096, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.4885146506131, + 'timestamp_carla': 866487, + 'timestamp_device': 1737090, + 'timestamp_stream': 866.4885146506131, + 'transform': [array([-4.84849701e+01, 6.95131073e+01, -6.48790151e-02]), + array([-2.07296237e-02, 1.75078812e+02, -1.77551255e-01])]} +{'AngularVelocity': array([-0.00568662, -0.03013571, 0.58833241]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.013893035240471363, + 'FR_Wheel_Angle': -0.01389261707663536, + 'Location': array([-5.13751945e+01, 1.00695114e+02, 5.69264591e-02]), + 'Rotation': array([1.01906415e-02, 1.78400864e+02, 2.02065464e-02]), + 'Velocity': array([-7.76557446e-01, 2.08467282e-02, 8.78238643e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4330.1455078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4171.60595703, 12578.25195312, 108.70919037]), + 'frame': 25469, + 'frame_number': 25469, + 'framesequence': 102571, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42077091336250305, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.5251032523811, + 'timestamp_carla': 866523, + 'timestamp_device': 1737123, + 'timestamp_stream': 866.5251032523811, + 'transform': [array([-4.84995728e+01, 6.95245667e+01, -6.49530813e-02]), + array([-2.08389051e-02, 1.75003555e+02, -1.77520737e-01])]} +{'AngularVelocity': array([-0.00527124, -0.02932486, 0.5700317 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.013900600373744965, + 'FR_Wheel_Angle': -0.013899723067879677, + 'Location': array([-5.15048637e+01, 1.00698692e+02, 5.69373704e-02]), + 'Rotation': array([1.03135854e-02, 1.78418991e+02, 1.94410905e-02]), + 'Velocity': array([-7.47774124e-01, 1.98454745e-02, 3.29256058e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4317.927734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4167.27978516, 12566.296875 , 108.75090027]), + 'frame': 25470, + 'frame_number': 25470, + 'framesequence': 102575, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41882991790771484, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.5544976517558, + 'timestamp_carla': 866553, + 'timestamp_device': 1737157, + 'timestamp_stream': 866.5544976517558, + 'transform': [array([-4.85115547e+01, 6.95339127e+01, -6.52099177e-02]), + array([-2.18087919e-02, 1.74941925e+02, -1.76788315e-01])]} +{'AngularVelocity': array([-0.00528717, -0.03595275, 0.57146388]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.013908347114920616, + 'FR_Wheel_Angle': -0.013908030465245247, + 'Location': array([-5.16301498e+01, 1.00702126e+02, 5.69451898e-02]), + 'Rotation': array([1.04160383e-02, 1.78436966e+02, 1.87317561e-02]), + 'Velocity': array([-7.17937171e-01, 1.88705809e-02, 1.31664274e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4319.7705078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4161.20458984, 12568.37988281, 108.74091339]), + 'frame': 25471, + 'frame_number': 25471, + 'framesequence': 102579, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4186285138130188, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.5934351496398, + 'timestamp_carla': 866592, + 'timestamp_device': 1737190, + 'timestamp_stream': 866.5934351496398, + 'transform': [array([-4.85252495e+01, 6.95447388e+01, -6.52302131e-02]), + array([-2.18702648e-02, 1.74871307e+02, -1.76910385e-01])]} +{'AngularVelocity': array([ 0.00467126, -0.04855364, -0.21989317]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.422893762588501, + 'FR_Wheel_Angle': -3.949907064437866, + 'Location': array([-5.17757149e+01, 1.00706100e+02, 5.69611713e-02]), + 'Rotation': array([1.03204157e-02, 1.78449890e+02, 1.83757115e-02]), + 'Velocity': array([-6.79264665e-01, 2.20245961e-02, 6.37893681e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4321.29443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4156.22900391, 12570.0859375 , 108.78606415]), + 'frame': 25472, + 'frame_number': 25472, + 'framesequence': 102583, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41970887780189514, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.622362550348, + 'timestamp_carla': 866621, + 'timestamp_device': 1737223, + 'timestamp_stream': 866.622362550348, + 'transform': [array([-4.85338173e+01, 6.95516357e+01, -6.50327280e-02]), + array([-2.09960006e-02, 1.74826874e+02, -1.77734360e-01])]} +{'AngularVelocity': array([-0.05988028, -0.05058528, -1.12951899]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.4429779052734375, + 'FR_Wheel_Angle': -3.537593364715576, + 'Location': array([-5.19140358e+01, 1.00714195e+02, 5.69982119e-02]), + 'Rotation': array([1.15771703e-02, 1.78247772e+02, 1.82015616e-02]), + 'Velocity': array([-6.53173268e-01, 4.78608645e-02, 3.41596606e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4279.03662109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4154.45458984, 12528.22070312, 108.902565 ]), + 'frame': 25473, + 'frame_number': 25473, + 'framesequence': 102587, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4203680753707886, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.6583501510322, + 'timestamp_carla': 866657, + 'timestamp_device': 1737256, + 'timestamp_stream': 866.6583501510322, + 'transform': [array([-4.85450859e+01, 6.95604630e+01, -6.50276393e-02]), + array([-2.12009065e-02, 1.74768814e+02, -1.77764863e-01])]} +{'AngularVelocity': array([-0.00726419, -0.06451928, -1.04778719]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.324012279510498, + 'FR_Wheel_Angle': -4.3211565017700195, + 'Location': array([-5.20272789e+01, 1.00720779e+02, 5.70104569e-02]), + 'Rotation': array([1.20826038e-02, 1.78091110e+02, 1.47754606e-02]), + 'Velocity': array([-6.35755837e-01, 4.55632918e-02, 7.80200935e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4270.8876953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4151.72363281, 12520.25390625, 108.86368561]), + 'frame': 25474, + 'frame_number': 25474, + 'framesequence': 102591, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42007508873939514, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.6875643506646, + 'timestamp_carla': 866686, + 'timestamp_device': 1737290, + 'timestamp_stream': 866.6875643506646, + 'transform': [array([-4.85548897e+01, 6.95679855e+01, -6.52952716e-02]), + array([-2.24235095e-02, 1.74718475e+02, -1.76879853e-01])]} +{'AngularVelocity': array([-0.01933124, -0.06053932, -0.90892911]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.11346435546875, + 'FR_Wheel_Angle': -4.039529323577881, + 'Location': array([-5.21354790e+01, 1.00727867e+02, 5.70249148e-02]), + 'Rotation': array([1.15566794e-02, 1.77931412e+02, 1.41001474e-02]), + 'Velocity': array([-6.12977028e-01, 4.51811403e-02, 6.14929158e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4260.318359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4148.17285156, 12509.89648438, 108.8944397 ]), + 'frame': 25475, + 'frame_number': 25475, + 'framesequence': 102595, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41967225074768066, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.7244358509779, + 'timestamp_carla': 866723, + 'timestamp_device': 1737323, + 'timestamp_stream': 866.7244358509779, + 'transform': [array([-4.85650787e+01, 6.95761185e+01, -6.53184503e-02]), + array([-2.26010941e-02, 1.74665771e+02, -1.76818818e-01])]} +{'AngularVelocity': array([-0.01674059, -0.06153685, -0.85482734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.1581268310546875, + 'FR_Wheel_Angle': -3.997616767883301, + 'Location': array([-5.22625427e+01, 1.00736626e+02, 5.70312478e-02]), + 'Rotation': array([1.12561509e-02, 1.77767365e+02, 1.34116439e-02]), + 'Velocity': array([-5.90158701e-01, 4.59157415e-02, 2.62169837e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4252.244140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4145.02099609, 12501.984375 , 108.98344421]), + 'frame': 25476, + 'frame_number': 25476, + 'framesequence': 102599, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4195989966392517, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.7543745525181, + 'timestamp_carla': 866753, + 'timestamp_device': 1737356, + 'timestamp_stream': 866.7543745525181, + 'transform': [array([-4.85713959e+01, 6.95814056e+01, -6.51200265e-02]), + array([-2.1624377e-02, 1.7463266e+02, -1.7767334e-01])]} +{'AngularVelocity': array([-0.00440981, -0.04168364, -1.36237359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.159557342529297, + 'FR_Wheel_Angle': -3.9986746311187744, + 'Location': array([-5.23669472e+01, 1.00744041e+02, 5.70164099e-02]), + 'Rotation': array([1.13859251e-02, 1.77605453e+02, 1.30839404e-02]), + 'Velocity': array([-5.87468565e-01, 4.90941815e-02, -2.17199326e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4253.5341796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4140.81787109, 12503.42578125, 108.98371887]), + 'frame': 25477, + 'frame_number': 25477, + 'framesequence': 102603, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.7932523488998, + 'timestamp_carla': 866792, + 'timestamp_device': 1737390, + 'timestamp_stream': 866.7932523488998, + 'transform': [array([-4.85803642e+01, 6.95886154e+01, -6.51481524e-02]), + array([-2.18361132e-02, 1.74586090e+02, -1.77642822e-01])]} +{'AngularVelocity': array([-0.004611 , -0.02913075, -0.25092763]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.162055969238281, + 'FR_Wheel_Angle': -4.000575542449951, + 'Location': array([-5.24661217e+01, 1.00751450e+02, 5.70356734e-02]), + 'Rotation': array([1.10853966e-02, 1.77483398e+02, 1.24718351e-02]), + 'Velocity': array([-5.76898038e-01, 4.87725660e-02, -1.30643835e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4254.328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4138.17041016, 12504.33203125, 108.91448975]), + 'frame': 25478, + 'frame_number': 25478, + 'framesequence': 102607, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.8239427506924, + 'timestamp_carla': 866822, + 'timestamp_device': 1737423, + 'timestamp_stream': 866.8239427506924, + 'transform': [array([-4.85865135e+01, 6.95938263e+01, -6.51525036e-02]), + array([-2.22527552e-02, 1.74553604e+02, -1.77459717e-01])]} +{'AngularVelocity': array([-0.00575345, -0.03435382, -0.42087224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.163329124450684, + 'FR_Wheel_Angle': -4.002161026000977, + 'Location': array([-5.25828896e+01, 1.00760216e+02, 5.70550524e-02]), + 'Rotation': array([1.07233962e-02, 1.77328522e+02, 1.17199896e-02]), + 'Velocity': array([-5.57382703e-01, 4.69512455e-02, 1.81131356e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4205.58935546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4139.15966797, 12455.94726562, 109.06672668]), + 'frame': 25479, + 'frame_number': 25479, + 'framesequence': 102611, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.8574638515711, + 'timestamp_carla': 866856, + 'timestamp_device': 1737456, + 'timestamp_stream': 866.8574638515711, + 'transform': [array([-4.85935745e+01, 6.95994415e+01, -6.52263165e-02]), + array([-2.25601140e-02, 1.74516937e+02, -1.77154526e-01])]} +{'AngularVelocity': array([-0.01857149, -0.06073425, -0.66092467]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.161458969116211, + 'FR_Wheel_Angle': -4.001735687255859, + 'Location': array([-5.26798859e+01, 1.00767731e+02, 5.70526496e-02]), + 'Rotation': array([1.11127170e-02, 1.77211044e+02, 1.12976870e-02]), + 'Velocity': array([-5.48712134e-01, 4.69271019e-02, 1.11494061e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4199.76416015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4137.20996094, 12450.25976562, 109.10357666]), + 'frame': 25480, + 'frame_number': 25480, + 'framesequence': 102615, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.8906196504831, + 'timestamp_carla': 866889, + 'timestamp_device': 1737490, + 'timestamp_stream': 866.8906196504831, + 'transform': [array([-4.85999069e+01, 6.96045837e+01, -6.52731434e-02]), + array([-2.27103774e-02, 1.74483978e+02, -1.76971421e-01])]} +{'AngularVelocity': array([ 0.00716102, -0.05165293, -1.20858657]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.296303749084473, + 'FR_Wheel_Angle': -8.883164405822754, + 'Location': array([-5.27779579e+01, 1.00776619e+02, 5.70647418e-02]), + 'Rotation': array([1.11468676e-02, 1.77059509e+02, 1.36607522e-02]), + 'Velocity': array([-5.59156418e-01, 7.09384531e-02, 1.89084996e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4197.37646484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4134.63232422, 12447.98242188, 109.13378143]), + 'frame': 25481, + 'frame_number': 25481, + 'framesequence': 102619, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.9248614497483, + 'timestamp_carla': 866923, + 'timestamp_device': 1737523, + 'timestamp_stream': 866.9248614497483, + 'transform': [array([-4.86058426e+01, 6.96094589e+01, -6.53199777e-02]), + array([-2.28538122e-02, 1.74452972e+02, -1.76849335e-01])]} +{'AngularVelocity': array([-0.01306408, 0.06122079, -1.64516497]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.434171199798584, + 'FR_Wheel_Angle': -7.165334224700928, + 'Location': array([-5.28781433e+01, 1.00789032e+02, 5.70042394e-02]), + 'Rotation': array([1.18025662e-02, 1.76789581e+02, 1.19084762e-02]), + 'Velocity': array([-0.63860184, 0.08274458, -0.00095945]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4196.55078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4132.18701172, 12447.25488281, 109.14994812]), + 'frame': 25482, + 'frame_number': 25482, + 'framesequence': 102623, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.9583835490048, + 'timestamp_carla': 866957, + 'timestamp_device': 1737556, + 'timestamp_stream': 866.9583835490048, + 'transform': [array([-4.86111641e+01, 6.96138535e+01, -6.53607324e-02]), + array([-2.30109058e-02, 1.74425110e+02, -1.76727295e-01])]} +{'AngularVelocity': array([ 0.0141399 , 0.05385594, -1.78478456]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.320931434631348, + 'FR_Wheel_Angle': -7.542535781860352, + 'Location': array([-5.30025024e+01, 1.00804062e+02, 5.70913665e-02]), + 'Rotation': array([1.15020378e-02, 1.76478439e+02, 1.06303757e-02]), + 'Velocity': array([-6.61293268e-01, 9.45518315e-02, 7.50637046e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4192.22900390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4130.22949219, 12443.046875 , 109.17093658]), + 'frame': 25483, + 'frame_number': 25483, + 'framesequence': 102627, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 866.9916059523821, + 'timestamp_carla': 866990, + 'timestamp_device': 1737590, + 'timestamp_stream': 866.9916059523821, + 'transform': [array([-4.86159668e+01, 6.96178589e+01, -6.54010251e-02]), + array([-2.31748298e-02, 1.74399963e+02, -1.76605210e-01])]} +{'AngularVelocity': array([ 0.01608396, 0.05165918, -1.79932702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.362812042236328, + 'FR_Wheel_Angle': -7.680110931396484, + 'Location': array([-5.31303215e+01, 1.00820557e+02, 5.71124628e-02]), + 'Rotation': array([1.07370568e-02, 1.76161331e+02, 8.72609019e-03]), + 'Velocity': array([-6.80467129e-01, 9.98169035e-02, 1.02434155e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4187.3017578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4128.57666016, 12438.22558594, 109.19393921]), + 'frame': 25484, + 'frame_number': 25484, + 'framesequence': 102631, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 867.0249510519207, + 'timestamp_carla': 867023, + 'timestamp_device': 1737623, + 'timestamp_stream': 867.0249510519207, + 'transform': [array([-4.86203842e+01, 6.96215515e+01, -6.54514804e-02]), + array([-2.33592466e-02, 1.74376740e+02, -1.76452622e-01])]} +{'AngularVelocity': array([ 0.01666546, 0.05057064, -1.9120661 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.326871871948242, + 'FR_Wheel_Angle': -7.700850963592529, + 'Location': array([-5.32395592e+01, 1.00835175e+02, 5.71268052e-02]), + 'Rotation': array([9.61690582e-03, 1.75883057e+02, 7.31563242e-03]), + 'Velocity': array([-6.87144458e-01, 1.03641920e-01, -1.25141145e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4172.580078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4128.08837891, 12423.65234375, 109.24817657]), + 'frame': 25485, + 'frame_number': 25485, + 'framesequence': 102635, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 867.0579802505672, + 'timestamp_carla': 867056, + 'timestamp_device': 1737656, + 'timestamp_stream': 867.0579802505672, + 'transform': [array([-4.86243935e+01, 6.96249313e+01, -6.54999837e-02]), + array([-2.35504918e-02, 1.74355621e+02, -1.76300034e-01])]} +{'AngularVelocity': array([ 0.02293766, 0.05043591, -1.86970353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.318315505981445, + 'FR_Wheel_Angle': -7.701731204986572, + 'Location': array([-5.33500824e+01, 1.00850525e+02, 5.71545772e-02]), + 'Rotation': array([8.87924526e-03, 1.75598068e+02, 6.23420672e-03]), + 'Velocity': array([-6.99515283e-01, 1.09656818e-01, 2.58393295e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.4921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4126.71875 , 12419.65625 , 109.27085114]), + 'frame': 25486, + 'frame_number': 25486, + 'framesequence': 102639, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 867.0909594520926, + 'timestamp_carla': 867089, + 'timestamp_device': 1737690, + 'timestamp_stream': 867.0909594520926, + 'transform': [array([-4.86281204e+01, 6.96280670e+01, -6.55563623e-02]), + array([-2.37485673e-02, 1.74336014e+02, -1.76116943e-01])]} +{'AngularVelocity': array([ 0.02896933, 0.0619846 , -1.82507217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.314332008361816, + 'FR_Wheel_Angle': -7.699413776397705, + 'Location': array([-5.34843788e+01, 1.00869957e+02, 5.71628176e-02]), + 'Rotation': array([8.96120816e-03, 1.75247314e+02, 6.19906234e-03]), + 'Velocity': array([-7.18203008e-01, 1.17265157e-01, 1.19543074e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4167.6484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4125.19091797, 12418.8828125 , 109.28373718]), + 'frame': 25487, + 'frame_number': 25487, + 'framesequence': 102643, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 867.1237917505205, + 'timestamp_carla': 867122, + 'timestamp_device': 1737723, + 'timestamp_stream': 867.1237917505205, + 'transform': [array([-4.86315765e+01, 6.96309891e+01, -6.56122789e-02]), + array([-2.39671320e-02, 1.74317810e+02, -1.75933838e-01])]} +{'AngularVelocity': array([ 0.02687703, 0.05734583, -1.95966446]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.313502311706543, + 'FR_Wheel_Angle': -7.697368144989014, + 'Location': array([-5.36000443e+01, 1.00887360e+02, 5.71528226e-02]), + 'Rotation': array([9.00901947e-03, 1.74942154e+02, 6.13701716e-03]), + 'Velocity': array([-7.28487313e-01, 1.22562416e-01, -8.91876189e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.11962890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4123.64941406, 12419.41210938, 109.29502869]), + 'frame': 25488, + 'frame_number': 25488, + 'framesequence': 102647, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 867.1576965488493, + 'timestamp_carla': 867156, + 'timestamp_device': 1737756, + 'timestamp_stream': 867.1576965488493, + 'transform': [array([-4.86349792e+01, 6.96338425e+01, -6.56845346e-02]), + array([-2.41993591e-02, 1.74299896e+02, -1.75720215e-01])]} +{'AngularVelocity': array([ 0.02849369, 0.05487704, -2.10672545]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.488359451293945, + 'FR_Wheel_Angle': -9.900322914123535, + 'Location': array([-5.37176323e+01, 1.00905571e+02, 5.71532063e-02]), + 'Rotation': array([9.26173571e-03, 1.74610825e+02, 6.35497039e-03]), + 'Velocity': array([-7.45740235e-01, 1.30625665e-01, 2.19440462e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.55517578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4122.21972656, 12419.90234375, 109.30601501]), + 'frame': 25489, + 'frame_number': 25489, + 'framesequence': 102651, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 867.1913135498762, + 'timestamp_carla': 867190, + 'timestamp_device': 1737790, + 'timestamp_stream': 867.1913135498762, + 'transform': [array([-4.86381302e+01, 6.96365051e+01, -6.57431334e-02]), + array([-2.44110953e-02, 1.74283325e+02, -1.75537109e-01])]} +{'AngularVelocity': array([ 0.01478012, 0.05201101, -3.27824497]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.577537536621094, + 'FR_Wheel_Angle': -10.560043334960938, + 'Location': array([-5.38606644e+01, 1.00932838e+02, 5.71630858e-02]), + 'Rotation': array([8.96120816e-03, 1.74051849e+02, 1.10427933e-02]), + 'Velocity': array([-7.51219451e-01, 1.75783724e-01, 2.98047060e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.9853515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4120.8125 , 12420.38476562, 109.3191452 ]), + 'frame': 25490, + 'frame_number': 25490, + 'framesequence': 102655, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.019836727529764175, + 'timestamp': 867.2259542495012, + 'timestamp_carla': 867224, + 'timestamp_device': 1737823, + 'timestamp_stream': 867.2259542495012, + 'transform': [array([-4.86412392e+01, 6.96391068e+01, -6.58157244e-02]), + array([-2.46296600e-02, 1.74266937e+02, -1.75323457e-01])]} +{'AngularVelocity': array([ 0.04366738, 0.04955585, -3.10259986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.733680725097656, + 'FR_Wheel_Angle': -11.435640335083008, + 'Location': array([-5.40088310e+01, 1.00963081e+02, 5.71469106e-02]), + 'Rotation': array([9.17294342e-03, 1.73483566e+02, 7.94269703e-03]), + 'Velocity': array([-7.71871388e-01, 1.82090521e-01, -2.04601281e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4172.12451171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4119.234375 , 12423.55664062, 109.32208252]), + 'frame': 25491, + 'frame_number': 25491, + 'framesequence': 102659, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.043656062334775925, + 'timestamp': 867.2582128494978, + 'timestamp_carla': 867257, + 'timestamp_device': 1737856, + 'timestamp_stream': 867.2582128494978, + 'transform': [array([-4.86438751e+01, 6.96413345e+01, -6.58494681e-02]), + array([-2.47935858e-02, 1.74253067e+02, -1.75170884e-01])]} +{'AngularVelocity': array([ 0.02925638, 0.05137851, -3.04508948]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.27264404296875, + 'FR_Wheel_Angle': -11.082792282104492, + 'Location': array([-5.41327438e+01, 1.00989990e+02, 5.71620166e-02]), + 'Rotation': array([9.04317014e-03, 1.73008652e+02, 7.17490073e-03]), + 'Velocity': array([-7.83924699e-01, 1.89233929e-01, 2.29268073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4170.93408203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4118.10498047, 12422.41992188, 109.33911133]), + 'frame': 25492, + 'frame_number': 25492, + 'framesequence': 102663, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.0476234070956707, + 'timestamp': 867.2915513515472, + 'timestamp_carla': 867290, + 'timestamp_device': 1737890, + 'timestamp_stream': 867.2915513515472, + 'transform': [array([-4.86465378e+01, 6.96435699e+01, -6.59041330e-02]), + array([-2.49916613e-02, 1.74239029e+02, -1.74987778e-01])]} +{'AngularVelocity': array([ 0.03267144, 0.03139409, -2.90322042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.427964210510254, + 'FR_Wheel_Angle': -11.127720832824707, + 'Location': array([-5.42621765e+01, 1.01018906e+02, 5.71322255e-02]), + 'Rotation': array([8.91339593e-03, 1.72484375e+02, 7.09851226e-03]), + 'Velocity': array([-7.83206224e-01, 1.98467731e-01, -4.52489854e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4167.951171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4117.34570312, 12419.49414062, 109.36042786]), + 'frame': 25493, + 'frame_number': 25493, + 'framesequence': 102667, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.051590751856565475, + 'timestamp': 867.3236715495586, + 'timestamp_carla': 867322, + 'timestamp_device': 1737923, + 'timestamp_stream': 867.3236715495586, + 'transform': [array([-4.86489182e+01, 6.96455841e+01, -6.59416392e-02]), + array([-2.51692459e-02, 1.74226425e+02, -1.74835205e-01])]} +{'AngularVelocity': array([ 0.03989343, 0.05360939, -3.34973383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.439337730407715, + 'FR_Wheel_Angle': -11.116800308227539, + 'Location': array([-5.44165421e+01, 1.01054863e+02, 5.71426004e-02]), + 'Rotation': array([8.85875523e-03, 1.71843445e+02, 7.14640366e-03]), + 'Velocity': array([-8.08741987e-01, 2.13349745e-01, -4.28857806e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.14501953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4116.25683594, 12419.7265625 , 109.37324524]), + 'frame': 25494, + 'frame_number': 25494, + 'framesequence': 102671, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.05555810034275055, + 'timestamp': 867.3606358505785, + 'timestamp_carla': 867359, + 'timestamp_device': 1737956, + 'timestamp_stream': 867.3606358505785, + 'transform': [array([-4.86518059e+01, 6.96480026e+01, -6.60462528e-02]), + array([-2.54014730e-02, 1.74211212e+02, -1.74591064e-01])]} +{'AngularVelocity': array([ 0.03785276, 0.05077468, -3.31150723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.436142921447754, + 'FR_Wheel_Angle': -11.11601734161377, + 'Location': array([-5.45461655e+01, 1.01086601e+02, 5.71559891e-02]), + 'Rotation': array([8.81094392e-03, 1.71315552e+02, 7.17543205e-03]), + 'Velocity': array([-8.16846550e-01, 2.23739430e-01, -3.54480726e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.31884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4115.27734375, 12419.93652344, 109.3840332 ]), + 'frame': 25495, + 'frame_number': 25495, + 'framesequence': 102675, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41992858052253723, + 'throttle_input': 0.05555810034275055, + 'timestamp': 867.3917339518666, + 'timestamp_carla': 867390, + 'timestamp_device': 1737990, + 'timestamp_stream': 867.3917339518666, + 'transform': [array([-4.86538620e+01, 6.96497726e+01, -6.60487264e-02]), + array([-2.55039241e-02, 1.74200272e+02, -1.74499512e-01])]} +{'AngularVelocity': array([ 0.04223393, 0.05123289, -3.49819112]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.432713508605957, + 'FR_Wheel_Angle': -11.112866401672363, + 'Location': array([-5.46799507e+01, 1.01120499e+02, 5.71479797e-02]), + 'Rotation': array([9.04317014e-03, 1.70743103e+02, 7.27799814e-03]), + 'Velocity': array([-8.31187189e-01, 2.36296669e-01, -8.61453955e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.52978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4114.09570312, 12420.18945312, 109.39681244]), + 'frame': 25496, + 'frame_number': 25496, + 'framesequence': 102679, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4194525182247162, + 'throttle_input': 0.059525445103645325, + 'timestamp': 867.4270057491958, + 'timestamp_carla': 867425, + 'timestamp_device': 1738023, + 'timestamp_stream': 867.4270057491958, + 'transform': [array([-4.86563721e+01, 6.96518707e+01, -6.61170781e-02]), + array([-2.57019997e-02, 1.74187073e+02, -1.74316406e-01])]} +{'AngularVelocity': array([ 0.04014703, 0.04997906, -3.71726274]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.430343627929688, + 'FR_Wheel_Angle': -11.110977172851562, + 'Location': array([-5.48144379e+01, 1.01155937e+02, 5.71555682e-02]), + 'Rotation': array([8.81777331e-03, 1.70159012e+02, 7.30473083e-03]), + 'Velocity': array([-8.37455809e-01, 2.46991903e-01, 1.95503235e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.6787109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4113.24804688, 12420.37011719, 109.40556335]), + 'frame': 25497, + 'frame_number': 25497, + 'framesequence': 102683, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4093264639377594, + 'throttle_input': 0.07142747938632965, + 'timestamp': 867.4599914513528, + 'timestamp_carla': 867458, + 'timestamp_device': 1738056, + 'timestamp_stream': 867.4599914513528, + 'transform': [array([-4.86584549e+01, 6.96537018e+01, -6.61432371e-02]), + array([-2.58112829e-02, 1.74175949e+02, -1.74194321e-01])]} +{'AngularVelocity': array([ 0.08580391, 0.03872108, -4.52693653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.930314064025879, + 'FR_Wheel_Angle': -15.134467124938965, + 'Location': array([-5.49496574e+01, 1.01194107e+02, 5.71569055e-02]), + 'Rotation': array([8.66751000e-03, 1.69539581e+02, 1.04503836e-02]), + 'Velocity': array([-8.36650372e-01, 2.81951904e-01, -2.23865500e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4168.8623046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4112.22216797, 12420.58886719, 109.41603088]), + 'frame': 25498, + 'frame_number': 25498, + 'framesequence': 102687, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3900265693664551, + 'throttle_input': 0.08729686588048935, + 'timestamp': 867.4923850521445, + 'timestamp_carla': 867491, + 'timestamp_device': 1738090, + 'timestamp_stream': 867.4923850521445, + 'transform': [array([-4.86603737e+01, 6.96554413e+01, -6.61688894e-02]), + array([-2.59000752e-02, 1.74165741e+02, -1.74072266e-01])]} +{'AngularVelocity': array([ 0.00956947, 0.05792609, -4.86154079]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.182598114013672, + 'FR_Wheel_Angle': -13.625913619995117, + 'Location': array([-5.50848083e+01, 1.01238136e+02, 5.71586229e-02]), + 'Rotation': array([8.87241494e-03, 1.68707870e+02, 1.08237369e-02]), + 'Velocity': array([-8.45899045e-01, 3.06898862e-01, 1.17015836e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4169.01171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4111.35693359, 12420.7734375 , 109.4256134 ]), + 'frame': 25499, + 'frame_number': 25499, + 'framesequence': 102691, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36653342843055725, + 'throttle_input': 0.10316624492406845, + 'timestamp': 867.5238829515874, + 'timestamp_carla': 867522, + 'timestamp_device': 1738123, + 'timestamp_stream': 867.5238829515874, + 'transform': [array([-4.86620941e+01, 6.96570892e+01, -6.61925599e-02]), + array([-2.59820390e-02, 1.74156525e+02, -1.73950195e-01])]} +{'AngularVelocity': array([ 0.06026864, 0.04342999, -5.07326365]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.95883560180664, + 'FR_Wheel_Angle': -14.57271671295166, + 'Location': array([-5.52232590e+01, 1.01284264e+02, 5.71530536e-02]), + 'Rotation': array([8.89290590e-03, 1.67916809e+02, 9.58576519e-03]), + 'Velocity': array([-8.51585627e-01, 3.25990289e-01, -1.41496654e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4169.1435546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4110.56445312, 12420.94335938, 109.43474579]), + 'frame': 25500, + 'frame_number': 25500, + 'framesequence': 102695, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.34434035420417786, + 'throttle_input': 0.11506828665733337, + 'timestamp': 867.5580214522779, + 'timestamp_carla': 867556, + 'timestamp_device': 1738156, + 'timestamp_stream': 867.5580214522779, + 'transform': [array([-4.86639557e+01, 6.96589508e+01, -6.62636757e-02]), + array([-2.61049811e-02, 1.74146515e+02, -1.73736557e-01])]} +{'AngularVelocity': array([ 0.05015404, 0.04666711, -5.01394415]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.422481536865234, + 'FR_Wheel_Angle': -14.309595108032227, + 'Location': array([-5.53624649e+01, 1.01333366e+02, 5.71490452e-02]), + 'Rotation': array([8.84509459e-03, 1.67105286e+02, 8.62460583e-03]), + 'Velocity': array([-8.59390676e-01, 3.39061588e-01, -1.42316814e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4169.25439453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4109.84667969, 12421.09765625, 109.44412994]), + 'frame': 25501, + 'frame_number': 25501, + 'framesequence': 102699, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33375653624534607, + 'throttle_input': 0.11903563141822815, + 'timestamp': 867.5913765504956, + 'timestamp_carla': 867590, + 'timestamp_device': 1738190, + 'timestamp_stream': 867.5913765504956, + 'transform': [array([-4.86657104e+01, 6.96607742e+01, -6.63094968e-02]), + array([-2.62484159e-02, 1.74137009e+02, -1.73583999e-01])]} +{'AngularVelocity': array([ 0.05084242, 0.0449499 , -5.07320309]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.510974884033203, + 'FR_Wheel_Angle': -14.313125610351562, + 'Location': array([-5.55022545e+01, 1.01384842e+02, 5.71521372e-02]), + 'Rotation': array([8.79728328e-03, 1.66294968e+02, 8.62148032e-03]), + 'Velocity': array([-8.64403427e-01, 3.56104463e-01, -4.58049763e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4169.369140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4109.06835938, 12421.26464844, 109.45697021]), + 'frame': 25502, + 'frame_number': 25502, + 'framesequence': 102703, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33968934416770935, + 'throttle_input': 0.11903563141822815, + 'timestamp': 867.6252039521933, + 'timestamp_carla': 867624, + 'timestamp_device': 1738223, + 'timestamp_stream': 867.6252039521933, + 'transform': [array([-4.86684265e+01, 6.96630859e+01, -6.64336681e-02]), + array([-2.67675091e-02, 1.74122925e+02, -1.73156738e-01])]} +{'AngularVelocity': array([ 0.05112536, 0.04309845, -5.02838278]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.549365997314453, + 'FR_Wheel_Angle': -14.310524940490723, + 'Location': array([-5.56423950e+01, 1.01438797e+02, 5.71596511e-02]), + 'Rotation': array([8.73581134e-03, 1.65486603e+02, 8.60915147e-03]), + 'Velocity': array([-8.67958128e-01, 3.72438490e-01, -1.51729582e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4169.47021484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4108.32910156, 12421.421875 , 109.46755219]), + 'frame': 25503, + 'frame_number': 25503, + 'framesequence': 102707, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35226908326148987, + 'throttle_input': 0.12300297617912292, + 'timestamp': 867.6580298505723, + 'timestamp_carla': 867656, + 'timestamp_device': 1738256, + 'timestamp_stream': 867.6580298505723, + 'transform': [array([-4.86719284e+01, 6.96665497e+01, -6.68298677e-02]), + array([-2.82838121e-02, 1.74104050e+02, -1.71661347e-01])]} +{'AngularVelocity': array([ 0.05369572, 0.04350532, -5.09021759]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.547475814819336, + 'FR_Wheel_Angle': -14.30859661102295, + 'Location': array([-5.57845802e+01, 1.01495888e+02, 5.71523272e-02]), + 'Rotation': array([8.57871678e-03, 1.64664536e+02, 8.52702931e-03]), + 'Velocity': array([-8.69606137e-01, 3.87937814e-01, -6.63471219e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4135.70166015625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4110.71777344, 12387.875 , 109.59975433]), + 'frame': 25504, + 'frame_number': 25504, + 'framesequence': 102711, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36547136306762695, + 'throttle_input': 0.12300297617912292, + 'timestamp': 867.6918394491076, + 'timestamp_carla': 867690, + 'timestamp_device': 1738290, + 'timestamp_stream': 867.6918394491076, + 'transform': [array([-4.86788330e+01, 6.96713257e+01, -6.71084598e-02]), + array([-2.90078111e-02, 1.74069839e+02, -1.70623779e-01])]} +{'AngularVelocity': array([ 0.05302846, 0.04197355, -5.13199282]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.54436683654785, + 'FR_Wheel_Angle': -14.34496021270752, + 'Location': array([-5.59262848e+01, 1.01555191e+02, 5.71550354e-02]), + 'Rotation': array([8.57188739e-03, 1.63844009e+02, 8.55228957e-03]), + 'Velocity': array([-8.71715784e-01, 4.03897911e-01, 1.10816953e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4131.09814453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4109.75830078, 12383.390625 , 109.722435 ]), + 'frame': 25505, + 'frame_number': 25505, + 'framesequence': 102715, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.37252116203308105, + 'throttle_input': 0.12300297617912292, + 'timestamp': 867.7250004522502, + 'timestamp_carla': 867723, + 'timestamp_device': 1738323, + 'timestamp_stream': 867.7250004522502, + 'transform': [array([-4.86844139e+01, 6.96760025e+01, -6.72001988e-02]), + array([-2.91922260e-02, 1.74040878e+02, -1.70288086e-01])]} +{'AngularVelocity': array([ 2.15670586, 3.94788337, -4.575912 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.604331970214844, + 'FR_Wheel_Angle': -14.352295875549316, + 'Location': array([-56.04727936, 101.6036911 , 0.10490174]), + 'Rotation': array([ 2.00588989, 163.28430176, -0.25299063]), + 'Velocity': array([-0.62135488, 0.29953501, 0.16890393]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4123.0380859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4108.04882812, 12375.39550781, 109.8196106 ]), + 'frame': 25506, + 'frame_number': 25506, + 'framesequence': 102719, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.37003085017204285, + 'throttle_input': 0.1269855797290802, + 'timestamp': 867.7588545493782, + 'timestamp_carla': 867757, + 'timestamp_device': 1738356, + 'timestamp_stream': 867.7588545493782, + 'transform': [array([-4.86930733e+01, 6.96821823e+01, -6.74597993e-02]), + array([-3.02099250e-02, 1.73997467e+02, -1.69372573e-01])]} +{'AngularVelocity': array([ 1.46963978, 1.89041376, -3.97280145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.525409698486328, + 'FR_Wheel_Angle': -17.678781509399414, + 'Location': array([-56.15797806, 101.65412903, 0.12061154]), + 'Rotation': array([ 2.57331467e+00, 1.62643219e+02, -1.42791748e-01]), + 'Velocity': array([-0.60415912, 0.31072411, 0.07071655]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4116.10546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4106.59228516, 12368.58203125, 109.86354828]), + 'frame': 25507, + 'frame_number': 25507, + 'framesequence': 102723, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36428114771842957, + 'throttle_input': 0.1269855797290802, + 'timestamp': 867.7921438515186, + 'timestamp_carla': 867790, + 'timestamp_device': 1738390, + 'timestamp_stream': 867.7921438515186, + 'transform': [array([-4.86986427e+01, 6.96888046e+01, -6.77807108e-02]), + array([-3.14871706e-02, 1.73965652e+02, -1.68212876e-01])]} +{'AngularVelocity': array([ 0.44332537, 0.58760905, -4.27749586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.77717399597168, + 'FR_Wheel_Angle': -16.880386352539062, + 'Location': array([-56.26532745, 101.70872498, 0.12582216]), + 'Rotation': array([ 2.79654574e+00, 1.61862030e+02, -5.74340448e-02]), + 'Velocity': array([-0.60071075, 0.33431849, 0.01928945]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4105.92919921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4104.43554688, 12358.5 , 109.95828247]), + 'frame': 25508, + 'frame_number': 25508, + 'framesequence': 102727, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35814693570137024, + 'throttle_input': 0.1269855797290802, + 'timestamp': 867.8262854516506, + 'timestamp_carla': 867825, + 'timestamp_device': 1738423, + 'timestamp_stream': 867.8262854516506, + 'transform': [array([-4.87094269e+01, 6.96969757e+01, -6.79156780e-02]), + array([-3.19379643e-02, 1.73910873e+02, -1.67785615e-01])]} +{'AngularVelocity': array([ 0.17017643, 0.17394452, -4.38535881]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.004541397094727, + 'FR_Wheel_Angle': -17.600940704345703, + 'Location': array([-56.37311554, 101.76423645, 0.12710522]), + 'Rotation': array([ 2.87559152e+00, 1.61105026e+02, -2.41393875e-02]), + 'Velocity': array([-0.5997178 , 0.34287432, 0.00508065]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4102.9794921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4102.3125 , 12355.80078125, 110.04944611]), + 'frame': 25509, + 'frame_number': 25509, + 'framesequence': 102731, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35428327322006226, + 'throttle_input': 0.1269855797290802, + 'timestamp': 867.8580175489187, + 'timestamp_carla': 867856, + 'timestamp_device': 1738456, + 'timestamp_stream': 867.8580175489187, + 'transform': [array([-4.87183876e+01, 6.97047729e+01, -6.79310337e-02]), + array([-3.15827914e-02, 1.73864197e+02, -1.67694047e-01])]} +{'AngularVelocity': array([ 2.57085916e-03, 4.58309129e-02, -4.27190685e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.60161018371582, + 'FR_Wheel_Angle': -17.340253829956055, + 'Location': array([-56.47999573, 101.82149506, 0.12738442]), + 'Rotation': array([ 2.90586281e+00, 1.60334305e+02, -9.70462337e-03]), + 'Velocity': array([-0.61543393, 0.36207062, 0.00121614]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4103.79345703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4098.15332031, 12356.69042969, 110.07541656]), + 'frame': 25510, + 'frame_number': 25510, + 'framesequence': 102735, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3554002642631531, + 'throttle_input': 0.13492026925086975, + 'timestamp': 867.89143865183, + 'timestamp_carla': 867890, + 'timestamp_device': 1738490, + 'timestamp_stream': 867.89143865183, + 'transform': [array([-4.87293053e+01, 6.97147293e+01, -6.82505518e-02]), + array([-3.28941904e-02, 1.73806488e+02, -1.66595474e-01])]} +{'AngularVelocity': array([-0.02598439, -0.01659933, -4.44534063]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.688520431518555, + 'FR_Wheel_Angle': -17.354515075683594, + 'Location': array([-56.58908463, 101.8819046 , 0.12743691]), + 'Rotation': array([ 2.91643596e+00, 1.59559586e+02, -6.19510794e-03]), + 'Velocity': array([-0.62399226, 0.37895083, 0.00082839]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4104.40966796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4094.59545898, 12357.45117188, 110.07983398]), + 'frame': 25511, + 'frame_number': 25511, + 'framesequence': 102739, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35838496685028076, + 'throttle_input': 0.13492026925086975, + 'timestamp': 867.9265663512051, + 'timestamp_carla': 867925, + 'timestamp_device': 1738523, + 'timestamp_stream': 867.9265663512051, + 'transform': [array([-4.87429008e+01, 6.97260437e+01, -6.82878196e-02]), + array([-3.27780768e-02, 1.73736450e+02, -1.66595444e-01])]} +{'AngularVelocity': array([-0.05061113, -0.0314117 , -4.48867512]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.706798553466797, + 'FR_Wheel_Angle': -17.352291107177734, + 'Location': array([-56.69902802, 101.94472504, 0.12744389]), + 'Rotation': array([ 2.92051363e+00, 1.58772827e+02, -4.57763625e-03]), + 'Velocity': array([-6.28881752e-01, 3.94160539e-01, 1.48973457e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4060.754150390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4094.97460938, 12314.2578125 , 110.28369904]), + 'frame': 25512, + 'frame_number': 25512, + 'framesequence': 102743, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36136966943740845, + 'throttle_input': 0.13492026925086975, + 'timestamp': 867.9589447490871, + 'timestamp_carla': 867957, + 'timestamp_device': 1738556, + 'timestamp_stream': 867.9589447490871, + 'transform': [array([-4.87547493e+01, 6.97365723e+01, -6.82690665e-02]), + array([-3.33040021e-02, 1.73674011e+02, -1.66778564e-01])]} +{'AngularVelocity': array([-0.06877567, -0.04711694, -4.53794193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.70242691040039, + 'FR_Wheel_Angle': -17.34978485107422, + 'Location': array([-56.83346558, 102.02430725, 0.12742768]), + 'Rotation': array([ 2.92226887e+00, 1.57801575e+02, -3.78420297e-03]), + 'Velocity': array([-6.30441546e-01, 4.10288066e-01, -2.84080510e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4044.559326171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4091.5703125, 12298.3359375, 110.3266449]), + 'frame': 25513, + 'frame_number': 25513, + 'framesequence': 102747, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3620838224887848, + 'throttle_input': 0.1428549587726593, + 'timestamp': 867.9919141493738, + 'timestamp_carla': 867990, + 'timestamp_device': 1738590, + 'timestamp_stream': 867.9919141493738, + 'transform': [array([-4.87672920e+01, 6.97474365e+01, -6.81485459e-02]), + array([-3.28668691e-02, 1.73608582e+02, -1.67327866e-01])]} +{'AngularVelocity': array([ 0.05622417, -0.0740628 , -5.22317314]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.6997127532959, + 'FR_Wheel_Angle': -17.34634780883789, + 'Location': array([-56.94461441, 102.09243011, 0.1274395 ]), + 'Rotation': array([ 2.92280173e+00, 1.56985016e+02, -2.31930497e-03]), + 'Velocity': array([-6.37504935e-01, 4.26098675e-01, 2.38347042e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4038.00830078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4087.67602539, 12292.0234375 , 110.33213043]), + 'frame': 25514, + 'frame_number': 25514, + 'framesequence': 102751, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3610217571258545, + 'throttle_input': 0.14682230353355408, + 'timestamp': 868.0241192504764, + 'timestamp_carla': 868022, + 'timestamp_device': 1738623, + 'timestamp_stream': 868.0241192504764, + 'transform': [array([-4.87798576e+01, 6.97590103e+01, -6.82644174e-02]), + array([-3.35567184e-02, 1.73541977e+02, -1.66992173e-01])]} +{'AngularVelocity': array([ 0.03930473, -0.0905175 , -5.42045927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.69327735900879, + 'FR_Wheel_Angle': -17.341209411621094, + 'Location': array([-57.05800247, 102.1636734 , 0.12742375]), + 'Rotation': array([2.92356658e+00, 1.56094589e+02, 9.41219088e-03]), + 'Velocity': array([-6.45198703e-01, 4.45908874e-01, -3.14044955e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4038.8818359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4082.75878906, 12293.07519531, 110.28881836]), + 'frame': 25515, + 'frame_number': 25515, + 'framesequence': 102755, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35935547947883606, + 'throttle_input': 0.15078964829444885, + 'timestamp': 868.0572875514627, + 'timestamp_carla': 868056, + 'timestamp_device': 1738656, + 'timestamp_stream': 868.0572875514627, + 'transform': [array([-4.87952194e+01, 6.97719345e+01, -6.83113933e-02]), + array([-3.39050554e-02, 1.73462296e+02, -1.66961670e-01])]} +{'AngularVelocity': array([ 0.09104444, -0.03159877, -6.41056776]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.08403968811035, + 'FR_Wheel_Angle': -21.31334114074707, + 'Location': array([-57.1725769 , 102.23934174, 0.12741609]), + 'Rotation': array([2.92581391e+00, 1.55138199e+02, 1.71485711e-02]), + 'Velocity': array([-6.40013695e-01, 4.82377201e-01, -2.01988209e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3999.919921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4082.21557617, 12254.59082031, 110.42458344]), + 'frame': 25516, + 'frame_number': 25516, + 'framesequence': 102759, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35875117778778076, + 'throttle_input': 0.15078964829444885, + 'timestamp': 868.0932320505381, + 'timestamp_carla': 868092, + 'timestamp_device': 1738690, + 'timestamp_stream': 868.0932320505381, + 'transform': [array([-4.88111496e+01, 6.97860260e+01, -6.82948008e-02]), + array([-3.36318500e-02, 1.73378860e+02, -1.67236298e-01])]} +{'AngularVelocity': array([ 0.010799 , -0.01519472, -6.41668701]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.988113403320312, + 'FR_Wheel_Angle': -19.758455276489258, + 'Location': array([-57.30528259, 102.33592224, 0.12740514]), + 'Rotation': array([2.92865515e+00, 1.53824661e+02, 1.84388030e-02]), + 'Velocity': array([-6.43239439e-01, 5.10230303e-01, 6.51359551e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3982.02197265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4078.45092773, 12236.99023438, 110.47631836]), + 'frame': 25517, + 'frame_number': 25517, + 'framesequence': 102763, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3597033619880676, + 'throttle_input': 0.15078964829444885, + 'timestamp': 868.1259486488998, + 'timestamp_carla': 868124, + 'timestamp_device': 1738723, + 'timestamp_stream': 868.1259486488998, + 'transform': [array([-4.88249092e+01, 6.97998123e+01, -6.84425235e-02]), + array([-3.41509432e-02, 1.73304520e+02, -1.66748047e-01])]} +{'AngularVelocity': array([-0.1159742 , -0.03410351, -6.16444683]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.05825424194336, + 'FR_Wheel_Angle': -20.227706909179688, + 'Location': array([-57.41849136, 102.4212265 , 0.12738861]), + 'Rotation': array([2.92978215e+00, 1.52717682e+02, 1.94388852e-02]), + 'Velocity': array([-6.27859592e-01, 5.31548619e-01, -3.04460526e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3972.8935546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4073.43725586, 12228.16015625, 110.47782135]), + 'frame': 25518, + 'frame_number': 25518, + 'framesequence': 102767, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3602893054485321, + 'throttle_input': 0.15475699305534363, + 'timestamp': 868.15860825032, + 'timestamp_carla': 868157, + 'timestamp_device': 1738756, + 'timestamp_stream': 868.15860825032, + 'transform': [array([-4.88434792e+01, 6.98152542e+01, -6.85765073e-02]), + array([-3.50252092e-02, 1.73208466e+02, -1.66381836e-01])]} +{'AngularVelocity': array([ 0.01388167, -0.08265787, -6.94326687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.836181640625, + 'FR_Wheel_Angle': -20.219985961914062, + 'Location': array([-57.53053665, 102.50918579, 0.12740827]), + 'Rotation': array([2.92762375e+00, 1.51564728e+02, 2.73407530e-02]), + 'Velocity': array([-6.37177467e-01, 5.56453824e-01, -6.74057010e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3973.75732421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4067.90429688, 12229.34375 , 110.50779724]), + 'frame': 25519, + 'frame_number': 25519, + 'framesequence': 102771, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36017945408821106, + 'throttle_input': 0.1587243527173996, + 'timestamp': 868.1912598498166, + 'timestamp_carla': 868190, + 'timestamp_device': 1738789, + 'timestamp_stream': 868.1912598498166, + 'transform': [array([-4.88582764e+01, 6.98306656e+01, -6.87228888e-02]), + array([-3.53189074e-02, 1.73127686e+02, -1.65924072e-01])]} +{'AngularVelocity': array([-0.08196135, -0.01943173, -6.70886946]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.79825210571289, + 'FR_Wheel_Angle': -20.188928604125977, + 'Location': array([-57.64293671, 102.60133362, 0.12744167]), + 'Rotation': array([2.92600513e+00, 1.50402618e+02, 2.69335192e-02]), + 'Velocity': array([-6.39999747e-01, 5.84399939e-01, 4.47831146e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3925.693115234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4066.64648438, 12181.78710938, 110.6710968 ]), + 'frame': 25520, + 'frame_number': 25520, + 'framesequence': 102775, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35994142293930054, + 'throttle_input': 0.1587243527173996, + 'timestamp': 868.2244871519506, + 'timestamp_carla': 868223, + 'timestamp_device': 1738823, + 'timestamp_stream': 868.2244871519506, + 'transform': [array([-4.88756905e+01, 6.98477783e+01, -6.88735172e-02]), + array([-3.62546407e-02, 1.73033554e+02, -1.65557846e-01])]} +{'AngularVelocity': array([-0.01304849, -0.06123242, -7.19736671]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.787147521972656, + 'FR_Wheel_Angle': -20.183061599731445, + 'Location': array([-57.75751495, 102.69920349, 0.12741452]), + 'Rotation': array([2.92560220e+00, 1.49188171e+02, 2.95618083e-02]), + 'Velocity': array([-6.41018510e-01, 6.08796656e-01, -2.42929455e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3907.82861328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4062.93554688, 12164.43457031, 110.75120544]), + 'frame': 25521, + 'frame_number': 25521, + 'framesequence': 102779, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.1587243527173996, + 'timestamp': 868.2587394490838, + 'timestamp_carla': 868257, + 'timestamp_device': 1738856, + 'timestamp_stream': 868.2587394490838, + 'transform': [array([-4.88961983e+01, 6.98666916e+01, -6.89789206e-02]), + array([-3.64458859e-02, 1.72924850e+02, -1.65344208e-01])]} +{'AngularVelocity': array([-0.0528398 , -0.04091004, -7.20715809]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.778539657592773, + 'FR_Wheel_Angle': -20.17681312561035, + 'Location': array([-57.87097549, 102.80039978, 0.12742169]), + 'Rotation': array([2.92507625e+00, 1.47966522e+02, 3.09020989e-02]), + 'Velocity': array([-6.42036200e-01, 6.37160540e-01, -6.88362124e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3907.90771484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4056.15673828, 12164.86425781, 110.77236176]), + 'frame': 25522, + 'frame_number': 25522, + 'framesequence': 102783, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.2915185503662, + 'timestamp_carla': 868290, + 'timestamp_device': 1738889, + 'timestamp_stream': 868.2915185503662, + 'transform': [array([-4.89166794e+01, 6.98858032e+01, -6.91001788e-02]), + array([-3.75318862e-02, 1.72815308e+02, -1.65100113e-01])]} +{'AngularVelocity': array([-0.04272862, -0.04716047, -7.39639616]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.768760681152344, + 'FR_Wheel_Angle': -20.170352935791016, + 'Location': array([-57.98672104, 102.90818024, 0.12741223]), + 'Rotation': array([2.92483711e+00, 1.46693878e+02, 3.20255198e-02]), + 'Velocity': array([-6.41131580e-01, 6.64635897e-01, -5.95092752e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3864.04443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4053.78417969, 12121.640625 , 110.90844727]), + 'frame': 25523, + 'frame_number': 25523, + 'framesequence': 102787, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.3250591494143, + 'timestamp_carla': 868323, + 'timestamp_device': 1738923, + 'timestamp_stream': 868.3250591494143, + 'transform': [array([-4.89370155e+01, 6.99059448e+01, -6.91887736e-02]), + array([-3.77709456e-02, 1.72705048e+02, -1.64947510e-01])]} +{'AngularVelocity': array([ 0.06477164, 0.02623117, -7.97324896]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.78911590576172, + 'FR_Wheel_Angle': -20.51331329345703, + 'Location': array([-58.12405777, 103.0426712 , 0.12739494]), + 'Rotation': array([2.92470050e+00, 1.45165741e+02, 2.95688342e-02]), + 'Velocity': array([-6.77609861e-01, 7.40626633e-01, 5.13305655e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3841.444091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4048.84619141, 12099.51953125, 110.98748779]), + 'frame': 25524, + 'frame_number': 25524, + 'framesequence': 102791, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.3581665493548, + 'timestamp_carla': 868356, + 'timestamp_device': 1738956, + 'timestamp_stream': 868.3581665493548, + 'transform': [array([-4.89615211e+01, 6.99277496e+01, -6.93214089e-02]), + array([-3.84061523e-02, 1.72575699e+02, -1.64642334e-01])]} +{'AngularVelocity': array([ 6.38982153, -6.42143011, -6.99786615]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.677967071533203, + 'FR_Wheel_Angle': -23.827360153198242, + 'Location': array([-58.23007202, 103.13585663, 0.15301356]), + 'Rotation': array([ 1.85495639, 143.87052917, -1.85311878]), + 'Velocity': array([-0.54086858, 0.59852093, 0.116631 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3842.776123046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4040.87768555, 12101.22363281, 110.9896698 ]), + 'frame': 25525, + 'frame_number': 25525, + 'framesequence': 102795, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.3914804495871, + 'timestamp_carla': 868390, + 'timestamp_device': 1738989, + 'timestamp_stream': 868.3914804495871, + 'transform': [array([-4.89837570e+01, 6.99503555e+01, -6.95682764e-02]), + array([-3.96014340e-02, 1.72453979e+02, -1.63940445e-01])]} +{'AngularVelocity': array([-2.35496759, 0.31432119, -7.75018549]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.61769676208496, + 'FR_Wheel_Angle': -23.01250648498535, + 'Location': array([-58.32159042, 103.23873901, 0.16408883]), + 'Rotation': array([ 1.64098704, 142.63645935, -1.9103092 ]), + 'Velocity': array([-0.51988918, 0.68669534, 0.03010982]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3790.982177734375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4038.48657227, 12050.10644531, 111.1546936 ]), + 'frame': 25526, + 'frame_number': 25526, + 'framesequence': 102799, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.4249267503619, + 'timestamp_carla': 868423, + 'timestamp_device': 1739023, + 'timestamp_stream': 868.4249267503619, + 'transform': [array([-4.90081635e+01, 6.99741974e+01, -6.96675405e-02]), + array([-4.02844548e-02, 1.72321594e+02, -1.63818330e-01])]} +{'AngularVelocity': array([-0.59085131, 0.15516587, -7.53148079]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.789453506469727, + 'FR_Wheel_Angle': -22.89026641845703, + 'Location': array([-58.42779541, 103.36688232, 0.16758005]), + 'Rotation': array([ 1.51699865, 141.18777466, -2.140167 ]), + 'Velocity': array([-0.51136994, 0.70538634, 0.0052608 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3776.569091796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4031.86376953, 12036.24414062, 111.23781586]), + 'frame': 25527, + 'frame_number': 25527, + 'framesequence': 102803, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.4574789516628, + 'timestamp_carla': 868456, + 'timestamp_device': 1739056, + 'timestamp_stream': 868.4574789516628, + 'transform': [array([-4.90318642e+01, 6.99980087e+01, -6.97103068e-02]), + array([-4.04415466e-02, 1.72191986e+02, -1.63848892e-01])]} +{'AngularVelocity': array([-1.42609194e-01, 7.49016926e-03, -7.87374926e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.934240341186523, + 'FR_Wheel_Angle': -22.960674285888672, + 'Location': array([-58.53026199, 103.49671936, 0.16827753]), + 'Rotation': array([ 1.48320282, 139.75378418, -2.21337914]), + 'Velocity': array([-0.48985985, 0.71058995, 0.00129746]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3739.1171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4027.6640625 , 11999.49609375, 111.3482666 ]), + 'frame': 25528, + 'frame_number': 25528, + 'framesequence': 102807, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.4907396510243, + 'timestamp_carla': 868489, + 'timestamp_device': 1739089, + 'timestamp_stream': 868.4907396510243, + 'transform': [array([-4.90585938e+01, 7.00239029e+01, -6.98083565e-02]), + array([-4.11928669e-02, 1.72047058e+02, -1.63757324e-01])]} +{'AngularVelocity': array([ 0.01359569, -0.06195627, -8.06776905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.985286712646484, + 'FR_Wheel_Angle': -22.963918685913086, + 'Location': array([-58.63031006, 103.63043976, 0.16842389]), + 'Rotation': array([ 1.47265697, 138.29974365, -2.23764086]), + 'Velocity': array([-4.73550260e-01, 7.27307320e-01, 4.41741926e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3713.15673828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4022.24829102, 11974.16992188, 111.41629028]), + 'frame': 25529, + 'frame_number': 25529, + 'framesequence': 102811, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.5233517512679, + 'timestamp_carla': 868522, + 'timestamp_device': 1739123, + 'timestamp_stream': 868.5233517512679, + 'transform': [array([-4.90843430e+01, 7.00501709e+01, -6.99434951e-02]), + array([-4.15548682e-02, 1.71905624e+02, -1.63452148e-01])]} +{'AngularVelocity': array([-0.15862906, 0.00874039, -6.91871977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.961992263793945, + 'FR_Wheel_Angle': -22.95452117919922, + 'Location': array([-58.71170425, 103.74456024, 0.16840543]), + 'Rotation': array([ 1.46907115, 137.08164978, -2.24606347]), + 'Velocity': array([-0.42632282, 0.68059742, -0.0010898 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3712.111328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4012.48730469, 11973.48046875, 111.41991425]), + 'frame': 25530, + 'frame_number': 25530, + 'framesequence': 102815, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.557983148843, + 'timestamp_carla': 868556, + 'timestamp_device': 1739156, + 'timestamp_stream': 868.557983148843, + 'transform': [array([-4.91139603e+01, 7.00791702e+01, -6.99892566e-02]), + array([-4.20944542e-02, 1.71744293e+02, -1.63635269e-01])]} +{'AngularVelocity': array([-0.4398632 , -0.09093777, -8.98729801]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.03150177001953, + 'FR_Wheel_Angle': -23.015201568603516, + 'Location': array([-58.79029083, 103.85971069, 0.16872263]), + 'Rotation': array([ 1.45438623, 135.8208313 , -2.23004174]), + 'Velocity': array([-0.3961713 , 0.64874864, 0.00289982]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3657.1025390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4010.54101562, 11919.42578125, 111.59203339]), + 'frame': 25531, + 'frame_number': 25531, + 'framesequence': 102819, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.5863736495376, + 'timestamp_carla': 868585, + 'timestamp_device': 1739189, + 'timestamp_stream': 868.5863736495376, + 'transform': [array([-4.91364555e+01, 7.01028366e+01, -6.99429885e-02]), + array([-4.19373587e-02, 1.71619202e+02, -1.64154068e-01])]} +{'AngularVelocity': array([ 1.35101056, -6.23082972, -6.12643528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.07240104675293, + 'FR_Wheel_Angle': -23.149791717529297, + 'Location': array([-58.85502243, 103.97291565, 0.18968007]), + 'Rotation': array([ 0.66967267, 134.39086914, -1.03683472]), + 'Velocity': array([-0.37987563, 0.59491813, 0.08677586]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3646.189208984375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4001.23681641, 11908.97851562, 111.60404205]), + 'frame': 25532, + 'frame_number': 25532, + 'framesequence': 102823, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.6238675490022, + 'timestamp_carla': 868622, + 'timestamp_device': 1739223, + 'timestamp_stream': 868.6238675490022, + 'transform': [array([-4.91703377e+01, 7.01359863e+01, -6.99362233e-02]), + array([-4.22242284e-02, 1.71434402e+02, -1.64581329e-01])]} +{'AngularVelocity': array([ 0.54098958, -2.39289069, -7.70177031]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.76145935058594, + 'FR_Wheel_Angle': -26.65665626525879, + 'Location': array([-58.92381287, 104.08866882, 0.20385739]), + 'Rotation': array([ 0.22136642, 133.13911438, -0.34289551]), + 'Velocity': array([-0.33373088, 0.66115189, 0.03277497]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3589.070068359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-4001.11279297, 11852.83886719, 111.72708893]), + 'frame': 25533, + 'frame_number': 25533, + 'framesequence': 102827, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.6539064496756, + 'timestamp_carla': 868652, + 'timestamp_device': 1739256, + 'timestamp_stream': 868.6539064496756, + 'transform': [array([-4.91975441e+01, 7.01631088e+01, -6.99129254e-02]), + array([-4.25725654e-02, 1.71285049e+02, -1.64764419e-01])]} +{'AngularVelocity': array([ 0.24195597, -1.20483351, -7.96020079]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.29312515258789, + 'FR_Wheel_Angle': -25.316120147705078, + 'Location': array([-58.97979736, 104.19177246, 0.20622277]), + 'Rotation': array([ 0.14337933, 131.90068054, -0.21798708]), + 'Velocity': array([-0.30881956, 0.63885808, 0.01014131]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3563.0703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3992.75976562, 11827.4765625 , 111.76651001]), + 'frame': 25534, + 'frame_number': 25534, + 'framesequence': 102830, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.6854802519083, + 'timestamp_carla': 868684, + 'timestamp_device': 1739281, + 'timestamp_stream': 868.6854802519083, + 'transform': [array([-4.92270050e+01, 7.01928024e+01, -7.00246617e-02]), + array([-4.32692468e-02, 1.71122711e+02, -1.64550796e-01])]} +{'AngularVelocity': array([ 0.06950786, -0.58668679, -8.19489288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.3798713684082, + 'FR_Wheel_Angle': -25.611400604248047, + 'Location': array([-59.03337097, 104.29584503, 0.208239 ]), + 'Rotation': array([ 6.25030547e-02, 1.30697418e+02, -8.36486816e-02]), + 'Velocity': array([-0.29279137, 0.66189551, 0.00671531]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3523.39990234375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3988.94580078, 11788.54980469, 111.8683548 ]), + 'frame': 25535, + 'frame_number': 25535, + 'framesequence': 102835, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.7196630500257, + 'timestamp_carla': 868718, + 'timestamp_device': 1739323, + 'timestamp_stream': 868.7196630500257, + 'transform': [array([-4.92593803e+01, 7.02259598e+01, -7.01643899e-02]), + array([-4.40000780e-02, 1.70943344e+02, -1.64367706e-01])]} +{'AngularVelocity': array([ 0.04769681, -0.25192893, -8.39699554]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.21183395385742, + 'FR_Wheel_Angle': -25.599559783935547, + 'Location': array([-59.08672714, 104.40528107, 0.20913035]), + 'Rotation': array([ 2.82428302e-02, 1.29450134e+02, -2.71606427e-02]), + 'Velocity': array([-0.28054011, 0.69035614, 0.00235855]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3495.34912109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3982.70605469, 11761.1484375 , 111.95814514]), + 'frame': 25536, + 'frame_number': 25536, + 'framesequence': 102838, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.7527133524418, + 'timestamp_carla': 868751, + 'timestamp_device': 1739348, + 'timestamp_stream': 868.7527133524418, + 'transform': [array([-4.92928200e+01, 7.02592697e+01, -7.02540800e-02]), + array([-4.46762666e-02, 1.70759201e+02, -1.64337188e-01])]} +{'AngularVelocity': array([ 0.03377629, -0.09957103, -8.60917854]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.1722412109375, + 'FR_Wheel_Angle': -25.623380661010742, + 'Location': array([-59.14831924, 104.53980255, 0.20944731]), + 'Rotation': array([ 1.41316606e-02, 1.27932526e+02, -2.44140625e-03]), + 'Velocity': array([-2.67091602e-01, 7.16739476e-01, 1.62038807e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3428.915283203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3981.56201172, 11695.89257812, 112.15278625]), + 'frame': 25537, + 'frame_number': 25537, + 'framesequence': 102842, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.7846485488117, + 'timestamp_carla': 868783, + 'timestamp_device': 1739381, + 'timestamp_stream': 868.7846485488117, + 'transform': [array([-49.32554626, 70.29234314, -0.07035279]), + array([-4.54002656e-02, 1.70578033e+02, -1.64245635e-01])]} +{'AngularVelocity': array([ 0.01258464, -0.03885741, -8.70912647]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.15439224243164, + 'FR_Wheel_Angle': -25.616897583007812, + 'Location': array([-59.19765854, 104.65486908, 0.20953226]), + 'Rotation': array([1.04433587e-02, 1.26649284e+02, 5.07298205e-03]), + 'Velocity': array([-2.57988423e-01, 7.38430619e-01, 4.27608495e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3362.518310546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3980.55541992, 11630.62988281, 112.33935547]), + 'frame': 25538, + 'frame_number': 25538, + 'framesequence': 102846, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.8179339505732, + 'timestamp_carla': 868816, + 'timestamp_device': 1739414, + 'timestamp_stream': 868.8179339505732, + 'transform': [array([-49.36035538, 70.32782745, -0.0704784 ]), + array([-4.61584143e-02, 1.70384583e+02, -1.64123550e-01])]} +{'AngularVelocity': array([ 0.0102061 , -0.02322268, -8.87761497]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.144134521484375, + 'FR_Wheel_Angle': -25.60979461669922, + 'Location': array([-59.2462616 , 104.77581787, 0.20955187]), + 'Rotation': array([8.91339593e-03, 1.25314796e+02, 8.13024119e-03]), + 'Velocity': array([-2.45166376e-01, 7.58908451e-01, 8.19683046e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3309.78173828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3977.9074707 , 11578.88964844, 112.49088287]), + 'frame': 25539, + 'frame_number': 25539, + 'framesequence': 102850, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.8516438491642, + 'timestamp_carla': 868850, + 'timestamp_device': 1739448, + 'timestamp_stream': 868.8516438491642, + 'transform': [array([-49.39652252, 70.36483765, -0.07060144]), + array([-4.69233952e-02, 1.70183105e+02, -1.64031997e-01])]} +{'AngularVelocity': array([ 6.17143558e-03, -1.25842141e-02, -9.01911449e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.136505126953125, + 'FR_Wheel_Angle': -25.60582160949707, + 'Location': array([-59.30265808, 104.92747498, 0.20953757]), + 'Rotation': array([8.02547205e-03, 1.23659515e+02, 9.40986723e-03]), + 'Velocity': array([-2.27097332e-01, 7.78399944e-01, 3.03888315e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3255.48193359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3975.10473633, 11525.65234375, 112.64601135]), + 'frame': 25540, + 'frame_number': 25540, + 'framesequence': 102854, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.8844743520021, + 'timestamp_carla': 868883, + 'timestamp_device': 1739481, + 'timestamp_stream': 868.8844743520021, + 'transform': [array([-49.43216324, 70.40182495, -0.07072294]), + array([-4.77020368e-02, 1.69983414e+02, -1.63909942e-01])]} +{'AngularVelocity': array([ 0.01372549, -0.03264064, -9.62681007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.8367805480957, + 'FR_Wheel_Angle': -28.17910385131836, + 'Location': array([-59.35506058, 105.08330536, 0.20957696]), + 'Rotation': array([7.59516982e-03, 1.21953499e+02, 1.16310166e-02]), + 'Velocity': array([-1.93100855e-01, 8.00672948e-01, 5.67240699e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3229.77294921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3967.31298828, 11500.61425781, 112.71710205]), + 'frame': 25541, + 'frame_number': 25541, + 'framesequence': 102858, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35990479588508606, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.9173544496298, + 'timestamp_carla': 868915, + 'timestamp_device': 1739514, + 'timestamp_stream': 868.9173544496298, + 'transform': [array([-49.46833801, 70.43985748, -0.07085609]), + array([-4.85216603e-02, 1.69779648e+02, -1.63757354e-01])]} +{'AngularVelocity': array([-9.29698721e-03, 2.57991366e-02, -1.02534990e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.6623420715332, + 'FR_Wheel_Angle': -27.6323184967041, + 'Location': array([-59.38998795, 105.21311951, 0.20957208]), + 'Rotation': array([6.97362283e-03, 1.20378441e+02, 1.38109839e-02]), + 'Velocity': array([-1.52930290e-01, 8.16013038e-01, 1.90062521e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3163.180419921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3966.90820312, 11435.3203125 , 112.90794373]), + 'frame': 25542, + 'frame_number': 25542, + 'framesequence': 102862, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35957521200180054, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.9527645520866, + 'timestamp_carla': 868951, + 'timestamp_device': 1739548, + 'timestamp_stream': 868.9527645520866, + 'transform': [array([-49.50878906, 70.48216248, -0.07100312]), + array([-4.93276231e-02, 1.69551819e+02, -1.63665801e-01])]} +{'AngularVelocity': array([ 1.02659669e-02, -1.87044851e-02, -1.04951458e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.62084197998047, + 'FR_Wheel_Angle': -28.261489868164062, + 'Location': array([-59.42911911, 105.37419891, 0.20954786]), + 'Rotation': array([7.30147166e-03, 1.18486565e+02, 1.18880309e-02]), + 'Velocity': array([-1.28077537e-01, 8.33121479e-01, -2.89049145e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3096.51318359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3966.73193359, 11370.01367188, 113.099823 ]), + 'frame': 25543, + 'frame_number': 25543, + 'framesequence': 102867, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3506760001182556, + 'throttle_input': 0.16269169747829437, + 'timestamp': 868.9871005490422, + 'timestamp_carla': 868985, + 'timestamp_device': 1739589, + 'timestamp_stream': 868.9871005490422, + 'transform': [array([-49.54785538, 70.52404022, -0.07112191]), + array([-4.97647561e-02, 1.69330154e+02, -1.63574234e-01])]} +{'AngularVelocity': array([ 3.63527471e-03, -7.61017948e-03, -1.04478750e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.21436309814453, + 'FR_Wheel_Angle': -28.160818099975586, + 'Location': array([-59.45747375, 105.50985718, 0.20955877]), + 'Rotation': array([7.35611329e-03, 1.16894341e+02, 1.10152801e-02]), + 'Velocity': array([-1.09815776e-01, 8.44562590e-01, -9.11903335e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 3039.28369140625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3963.96362305, 11314.03320312, 113.25867462]), + 'frame': 25544, + 'frame_number': 25544, + 'framesequence': 102870, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.33126622438430786, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.0188751518726, + 'timestamp_carla': 869017, + 'timestamp_device': 1739614, + 'timestamp_stream': 869.0188751518726, + 'transform': [array([-49.58256912, 70.56326294, -0.07125279]), + array([-4.96213213e-02, 1.69130432e+02, -1.63269073e-01])]} +{'AngularVelocity': array([-3.23678576e-03, 5.62029751e-03, -1.04459095e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.2446174621582, + 'FR_Wheel_Angle': -28.134899139404297, + 'Location': array([-59.48184586, 105.64447784, 0.20956799]), + 'Rotation': array([7.28781149e-03, 1.15325905e+02, 1.08582005e-02]), + 'Velocity': array([-8.90019909e-02, 8.54255497e-01, 1.09677312e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2948.152099609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3968.24755859, 11224.81347656, 113.51529694]), + 'frame': 25545, + 'frame_number': 25545, + 'framesequence': 102874, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30795618891716003, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.0535067506135, + 'timestamp_carla': 869052, + 'timestamp_device': 1739648, + 'timestamp_stream': 869.0535067506135, + 'transform': [array([-49.61828613, 70.60636902, -0.07140324]), + array([-4.87538874e-02, 1.68921707e+02, -1.62963882e-01])]} +{'AngularVelocity': array([-4.76570101e-03, 1.15392460e-02, -1.05409927e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.2401008605957, + 'FR_Wheel_Angle': -28.131704330444336, + 'Location': array([-59.50702667, 105.8130188 , 0.20955342]), + 'Rotation': array([7.15803774e-03, 1.13374039e+02, 1.07979830e-02]), + 'Velocity': array([-6.09233193e-02, 8.63429844e-01, 6.66904452e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2943.08837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3958.13574219, 11220.29882812, 113.53907013]), + 'frame': 25546, + 'frame_number': 25546, + 'framesequence': 102878, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.28457289934158325, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.0850524492562, + 'timestamp_carla': 869083, + 'timestamp_device': 1739681, + 'timestamp_stream': 869.0850524492562, + 'transform': [array([-49.64870834, 70.64587402, -0.07153283]), + array([-4.77840006e-02, 1.68740692e+02, -1.62597671e-01])]} +{'AngularVelocity': array([-6.34478871e-04, 4.83178347e-03, -1.06219225e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.23430633544922, + 'FR_Wheel_Angle': -28.129663467407227, + 'Location': array([-59.5235672 , 105.9533844 , 0.20957261]), + 'Rotation': array([7.26732099e-03, 1.11754379e+02, 1.09499237e-02]), + 'Velocity': array([-3.65773216e-02, 8.74889731e-01, 7.80343980e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2891.73828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3956.41015625, 11170.54492188, 113.69000244]), + 'frame': 25547, + 'frame_number': 25547, + 'framesequence': 102882, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2741355895996094, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.1146887503564, + 'timestamp_carla': 869113, + 'timestamp_device': 1739714, + 'timestamp_stream': 869.1146887503564, + 'transform': [array([-49.67832947, 70.68442535, -0.07185197]), + array([-4.78113219e-02, 1.68565094e+02, -1.61804214e-01])]} +{'AngularVelocity': array([-7.56976195e-03, 1.00963861e-02, -1.07960081e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.230655670166016, + 'FR_Wheel_Angle': -28.124916076660156, + 'Location': array([-59.53646851, 106.09846497, 0.2095529 ]), + 'Rotation': array([7.24683050e-03, 1.10086060e+02, 1.10154925e-02]), + 'Velocity': array([-1.12330113e-02, 8.79988313e-01, -5.93729026e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2875.558837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3949.6315918 , 11155.43066406, 113.74641418]), + 'frame': 25548, + 'frame_number': 25548, + 'framesequence': 102886, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2787865996360779, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.1461605504155, + 'timestamp_carla': 869144, + 'timestamp_device': 1739748, + 'timestamp_stream': 869.1461605504155, + 'transform': [array([-49.70882797, 70.72554779, -0.07197412]), + array([-4.83850576e-02, 1.68381927e+02, -1.61590621e-01])]} +{'AngularVelocity': array([ 5.51622768e-04, 4.69367049e-04, -1.08097458e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.224365234375, + 'FR_Wheel_Angle': -28.12722396850586, + 'Location': array([-59.54506302, 106.241745 , 0.20955938]), + 'Rotation': array([7.19901919e-03, 1.08441620e+02, 1.11210011e-02]), + 'Velocity': array([1.47671280e-02, 8.89728308e-01, 3.61099228e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2813.16259765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3952.43237305, 11094.99609375, 113.9493866 ]), + 'frame': 25549, + 'frame_number': 25549, + 'framesequence': 102890, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.290816992521286, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.1796449497342, + 'timestamp_carla': 869178, + 'timestamp_device': 1739781, + 'timestamp_stream': 869.1796449497342, + 'transform': [array([-49.74199295, 70.77028656, -0.07211488]), + array([-5.00789434e-02, 1.68181778e+02, -1.61560059e-01])]} +{'AngularVelocity': array([ 3.53272841e-03, -2.73784157e-02, -1.18416042e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.37191390991211, + 'FR_Wheel_Angle': -30.612871170043945, + 'Location': array([-59.547966 , 106.38548279, 0.20958501]), + 'Rotation': array([6.62528304e-03, 1.06724060e+02, 1.50272837e-02]), + 'Velocity': array([7.20885172e-02, 8.89493763e-01, 3.99112687e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2774.17919921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3950.46655273, 11057.65625 , 114.06445312]), + 'frame': 25550, + 'frame_number': 25550, + 'framesequence': 102894, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.303158700466156, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.2137356512249, + 'timestamp_carla': 869212, + 'timestamp_device': 1739814, + 'timestamp_stream': 869.2137356512249, + 'transform': [array([-49.77748489, 70.8171463 , -0.07225028]), + array([-5.23260757e-02, 1.67967697e+02, -1.61651626e-01])]} +{'AngularVelocity': array([-7.14034867e-03, 1.56754237e-02, -1.18805857e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.04194641113281, + 'FR_Wheel_Angle': -30.610034942626953, + 'Location': array([-59.54358673, 106.53336334, 0.20954931]), + 'Rotation': array([6.57747174e-03, 1.04859428e+02, 1.33329378e-02]), + 'Velocity': array([ 1.00522041e-01, 8.86664033e-01, -4.00753022e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2739.854248046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3946.90039062, 11024.94335938, 114.15505219]), + 'frame': 25551, + 'frame_number': 25551, + 'framesequence': 102898, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3120761811733246, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.2470592521131, + 'timestamp_carla': 869245, + 'timestamp_device': 1739848, + 'timestamp_stream': 869.2470592521131, + 'transform': [array([-49.81396866, 70.86434937, -0.07238469]), + array([-5.45390584e-02, 1.67748032e+02, -1.61712661e-01])]} +{'AngularVelocity': array([-4.85026930e-03, 1.74633805e-02, -1.20397215e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.36884689331055, + 'FR_Wheel_Angle': -30.607702255249023, + 'Location': array([-59.53406525, 106.67819977, 0.20955564]), + 'Rotation': array([6.67309435e-03, 1.03008018e+02, 1.29352519e-02]), + 'Velocity': array([ 1.34142950e-01, 8.88216615e-01, -2.99053179e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2689.554443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3946.19775391, 10976.57128906, 114.28475952]), + 'frame': 25552, + 'frame_number': 25552, + 'framesequence': 102902, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.31119728088378906, + 'throttle_input': 0.16269169747829437, + 'timestamp': 869.2812329493463, + 'timestamp_carla': 869279, + 'timestamp_device': 1739881, + 'timestamp_stream': 869.2812329493463, + 'transform': [array([-49.85221481, 70.91386414, -0.07252291]), + array([-5.61304912e-02, 1.67516861e+02, -1.61743224e-01])]} +{'AngularVelocity': array([ 3.14974179e-03, 2.99469754e-03, -1.20651789e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.36355209350586, + 'FR_Wheel_Angle': -30.605615615844727, + 'Location': array([-59.51944351, 106.82558441, 0.20956953]), + 'Rotation': array([6.77554728e-03, 1.01114441e+02, 1.22185629e-02]), + 'Velocity': array([1.65073410e-01, 8.90732884e-01, 5.37905667e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2671.81884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3938.68774414, 10959.97753906, 114.32469177]), + 'frame': 25553, + 'frame_number': 25553, + 'framesequence': 102906, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30524611473083496, + 'throttle_input': 0.1428549587726593, + 'timestamp': 869.3128839507699, + 'timestamp_carla': 869311, + 'timestamp_device': 1739914, + 'timestamp_stream': 869.3128839507699, + 'transform': [array([-49.88798141, 70.96077728, -0.07266965]), + array([-5.70593961e-02, 1.67299377e+02, -1.61560103e-01])]} +{'AngularVelocity': array([-7.35587673e-04, 7.73655437e-03, -1.21779814e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.35932540893555, + 'FR_Wheel_Angle': -30.60296058654785, + 'Location': array([-59.50003433, 106.97206879, 0.20956941]), + 'Rotation': array([6.96679251e-03, 9.92263947e+01, 1.21935057e-02]), + 'Velocity': array([ 1.95384175e-01, 8.91031086e-01, -1.56621929e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2604.037109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3941.5480957 , 10894.51171875, 114.5056839 ]), + 'frame': 25554, + 'frame_number': 25554, + 'framesequence': 102910, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299459844827652, + 'throttle_input': 0.13888761401176453, + 'timestamp': 869.3494562506676, + 'timestamp_carla': 869348, + 'timestamp_device': 1739948, + 'timestamp_stream': 869.3494562506676, + 'transform': [array([-49.92897797, 71.01564026, -0.07281372]), + array([-5.74282259e-02, 1.67048264e+02, -1.61590651e-01])]} +{'AngularVelocity': array([-2.26771939e-04, 3.01805791e-03, -1.22353210e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.354984283447266, + 'FR_Wheel_Angle': -30.601802825927734, + 'Location': array([-59.47595978, 107.11701965, 0.20956948]), + 'Rotation': array([6.92581153e-03, 9.73503265e+01, 1.20775970e-02]), + 'Velocity': array([2.26148307e-01, 8.89592290e-01, 1.63106917e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2562.68212890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3939.79077148, 10854.87207031, 114.6231308 ]), + 'frame': 25555, + 'frame_number': 25555, + 'framesequence': 102914, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2945341467857361, + 'throttle_input': 0.13888761401176453, + 'timestamp': 869.381734251976, + 'timestamp_carla': 869380, + 'timestamp_device': 1739981, + 'timestamp_stream': 869.381734251976, + 'transform': [array([-49.96498108, 71.06486511, -0.07292732]), + array([-5.77970594e-02, 1.66825821e+02, -1.61499098e-01])]} +{'AngularVelocity': array([ 9.19247337e-04, 2.05196976e-03, -1.22744226e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.35383224487305, + 'FR_Wheel_Angle': -30.60053253173828, + 'Location': array([-59.44615555, 107.26559448, 0.20955968]), + 'Rotation': array([6.76188711e-03, 9.54171066e+01, 1.18867941e-02]), + 'Velocity': array([2.56371021e-01, 8.83053422e-01, 1.58033363e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2535.899658203125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3933.43017578, 10829.62304688, 114.68360901]), + 'frame': 25556, + 'frame_number': 25556, + 'framesequence': 102918, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29502856731414795, + 'throttle_input': 0.13492026925086975, + 'timestamp': 869.4148332513869, + 'timestamp_carla': 869413, + 'timestamp_device': 1740014, + 'timestamp_stream': 869.4148332513869, + 'transform': [array([-50.00174713, 71.11605072, -0.07304888]), + array([-5.83707951e-02, 1.66596786e+02, -1.61468551e-01])]} +{'AngularVelocity': array([-1.26627297e-03, 9.78754926e-03, -1.23553104e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.348819732666016, + 'FR_Wheel_Angle': -30.59781837463379, + 'Location': array([-59.41250229, 107.40870667, 0.20956784]), + 'Rotation': array([6.97362283e-03, 9.35393524e+01, 1.22463750e-02]), + 'Velocity': array([ 2.87138849e-01, 8.81440580e-01, -2.71549216e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2385.051513671875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3956.9453125 , 10683.52734375, 115.10476685]), + 'frame': 25557, + 'frame_number': 25557, + 'framesequence': 102922, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2976653575897217, + 'throttle_input': 0.13492026925086975, + 'timestamp': 869.4507088512182, + 'timestamp_carla': 869449, + 'timestamp_device': 1740048, + 'timestamp_stream': 869.4507088512182, + 'transform': [array([-50.04237747, 71.17247009, -0.07316904]), + array([-5.92655465e-02, 1.66343262e+02, -1.61621168e-01])]} +{'AngularVelocity': array([ 3.90741508e-04, 2.75935628e-03, -1.24070520e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.34658432006836, + 'FR_Wheel_Angle': -30.595348358154297, + 'Location': array([-59.37312317, 107.55432129, 0.20956442]), + 'Rotation': array([6.83701877e-03, 9.16138382e+01, 1.21066319e-02]), + 'Velocity': array([3.18117738e-01, 8.74609709e-01, 6.73294053e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2377.9736328125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3947.97363281, 10677.578125 , 115.11669159]), + 'frame': 25558, + 'frame_number': 25558, + 'framesequence': 102926, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3008881211280823, + 'throttle_input': 0.1269855797290802, + 'timestamp': 869.4825062491, + 'timestamp_carla': 869481, + 'timestamp_device': 1740081, + 'timestamp_stream': 869.4825062491, + 'transform': [array([-50.07899857, 71.22343445, -0.07327352]), + array([-6.04266785e-02, 1.66113724e+02, -1.61651671e-01])]} +{'AngularVelocity': array([ 8.51042219e-04, 3.88813671e-03, -1.24528294e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.342498779296875, + 'FR_Wheel_Angle': -30.594276428222656, + 'Location': array([-59.31935501, 107.7275238 , 0.20957094]), + 'Rotation': array([6.85750972e-03, 8.92996826e+01, 1.22015709e-02]), + 'Velocity': array([ 3.54994953e-01, 8.65937471e-01, -2.01320636e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2382.77587890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3935.13647461, 10683.1953125 , 115.08438873]), + 'frame': 25559, + 'frame_number': 25559, + 'framesequence': 102930, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30220651626586914, + 'throttle_input': 0.1269855797290802, + 'timestamp': 869.5131468512118, + 'timestamp_carla': 869511, + 'timestamp_device': 1740114, + 'timestamp_stream': 869.5131468512118, + 'transform': [array([-50.115345 , 71.27367401, -0.07340623]), + array([-6.16014712e-02, 1.65885773e+02, -1.61560148e-01])]} +{'AngularVelocity': array([-4.32793167e-04, 7.20505230e-03, -1.24957867e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.34061050415039, + 'FR_Wheel_Angle': -30.5929012298584, + 'Location': array([-59.26857758, 107.87187958, 0.20956178]), + 'Rotation': array([6.81652827e-03, 8.73458405e+01, 1.22238062e-02]), + 'Velocity': array([ 3.85338634e-01, 8.55794966e-01, -6.37340563e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2333.716064453125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3936.2980957 , 10636.35546875, 115.21421051]), + 'frame': 25560, + 'frame_number': 25560, + 'framesequence': 102934, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3011810779571533, + 'throttle_input': 0.1269855797290802, + 'timestamp': 869.5474627502263, + 'timestamp_carla': 869546, + 'timestamp_device': 1740148, + 'timestamp_stream': 869.5474627502263, + 'transform': [array([-50.15637207, 71.33068848, -0.07354278]), + array([-6.25098869e-02, 1.65627396e+02, -1.61621183e-01])]} +{'AngularVelocity': array([ 1.43671338e-03, 2.08225218e-03, -1.25615311e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.33563995361328, + 'FR_Wheel_Angle': -30.59008026123047, + 'Location': array([-59.2131958 , 108.01372528, 0.20957173]), + 'Rotation': array([6.83701877e-03, 8.54020081e+01, 1.22833010e-02]), + 'Velocity': array([4.16501939e-01, 8.46914709e-01, 5.61714151e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2313.528076171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3930.88574219, 10617.51074219, 115.26766968]), + 'frame': 25561, + 'frame_number': 25561, + 'framesequence': 102938, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299368292093277, + 'throttle_input': 0.1269855797290802, + 'timestamp': 869.5813026502728, + 'timestamp_carla': 869580, + 'timestamp_device': 1740181, + 'timestamp_stream': 869.5813026502728, + 'transform': [array([-50.19649124, 71.38741302, -0.07365547]), + array([-6.32065684e-02, 1.65372467e+02, -1.61712691e-01])]} +{'AngularVelocity': array([ 6.93652721e-04, 3.81690660e-03, -1.25761442e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.33449935913086, + 'FR_Wheel_Angle': -30.589204788208008, + 'Location': array([-59.13953018, 108.18338013, 0.20956826]), + 'Rotation': array([6.72773598e-03, 8.30408936e+01, 1.21897440e-02]), + 'Velocity': array([4.52152967e-01, 8.31209004e-01, 3.89943103e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2307.748779296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3920.69726562, 10612.70410156, 115.26981354]), + 'frame': 25562, + 'frame_number': 25562, + 'framesequence': 102942, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29883724451065063, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.6145233511925, + 'timestamp_carla': 869613, + 'timestamp_device': 1740214, + 'timestamp_stream': 869.6145233511925, + 'transform': [array([-50.23575592, 71.44368744, -0.07376707]), + array([-6.38827533e-02, 1.65121063e+02, -1.61773741e-01])]} +{'AngularVelocity': array([ 1.49782238e-04, 5.96643239e-03, -1.26205950e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.33183288574219, + 'FR_Wheel_Angle': -30.588123321533203, + 'Location': array([-59.07282639, 108.32231903, 0.20956747]), + 'Rotation': array([6.75505679e-03, 8.10720215e+01, 1.22714266e-02]), + 'Velocity': array([4.82216507e-01, 8.18278491e-01, 4.11853776e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2312.7060546875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3907.98754883, 10618.26757812, 115.24092865]), + 'frame': 25563, + 'frame_number': 25563, + 'framesequence': 102946, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299551397562027, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.6476533524692, + 'timestamp_carla': 869646, + 'timestamp_device': 1740248, + 'timestamp_stream': 869.6476533524692, + 'transform': [array([-50.27572632, 71.5007782 , -0.07389642]), + array([-6.46750554e-02, 1.64864868e+02, -1.61773756e-01])]} +{'AngularVelocity': array([ 7.92289386e-04, 1.21865794e-02, -1.26959925e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.33074951171875, + 'FR_Wheel_Angle': -30.586252212524414, + 'Location': array([-59.00038528, 108.46076202, 0.20955437]), + 'Rotation': array([6.76188711e-03, 7.90771179e+01, 1.24098817e-02]), + 'Velocity': array([ 5.11397243e-01, 8.03290129e-01, -3.28626629e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2265.580078125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3908.75878906, 10573.43945312, 115.36125946]), + 'frame': 25564, + 'frame_number': 25564, + 'framesequence': 102950, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3003937005996704, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.6806720495224, + 'timestamp_carla': 869679, + 'timestamp_device': 1740281, + 'timestamp_stream': 869.6806720495224, + 'transform': [array([-50.31585693, 71.55847168, -0.0740361 ]), + array([-6.55834749e-02, 1.64606277e+02, -1.61743194e-01])]} +{'AngularVelocity': array([ 1.93970359e-03, 4.51993430e-03, -1.26666431e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.332061767578125, + 'FR_Wheel_Angle': -30.588491439819336, + 'Location': array([-58.92006683, 108.6018219 , 0.20954156]), + 'Rotation': array([6.48184912e-03, 7.70052338e+01, 1.20717147e-02]), + 'Velocity': array([5.39175153e-01, 7.82496154e-01, 3.12643038e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2248.57568359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3901.8762207 , 10557.71484375, 115.399086 ]), + 'frame': 25565, + 'frame_number': 25565, + 'framesequence': 102954, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3003021478652954, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.7129200510681, + 'timestamp_carla': 869711, + 'timestamp_device': 1740314, + 'timestamp_stream': 869.7129200510681, + 'transform': [array([-50.35503006, 71.615448 , -0.07417706]), + array([-6.64918870e-02, 1.64351990e+02, -1.61682189e-01])]} +{'AngularVelocity': array([ 2.73057213e-03, -2.07160320e-03, -1.27004671e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.32959747314453, + 'FR_Wheel_Angle': -30.58505630493164, + 'Location': array([-58.83460236, 108.74007416, 0.20956904]), + 'Rotation': array([6.63211336e-03, 7.49297638e+01, 1.22112958e-02]), + 'Velocity': array([5.69254160e-01, 7.65037954e-01, 2.68850330e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2237.644287109375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3893.42504883, 10547.83105469, 115.42111969]), + 'frame': 25566, + 'frame_number': 25566, + 'framesequence': 102958, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299826055765152, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.7471688501537, + 'timestamp_carla': 869745, + 'timestamp_device': 1740347, + 'timestamp_stream': 869.7471688501537, + 'transform': [array([-50.39657974, 71.67649078, -0.07431842]), + array([-6.72978535e-02, 1.64080429e+02, -1.61712706e-01])]} +{'AngularVelocity': array([ 1.45099987e-03, 9.05213470e-04, -1.27247448e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.327884674072266, + 'FR_Wheel_Angle': -30.585742950439453, + 'Location': array([-58.74634933, 108.87203979, 0.20956922]), + 'Rotation': array([6.69358484e-03, 7.29043121e+01, 1.23095736e-02]), + 'Velocity': array([5.97435832e-01, 7.46356785e-01, 1.77392954e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2242.681884765625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3880.94189453, 10553.29492188, 115.39975739]), + 'frame': 25567, + 'frame_number': 25567, + 'framesequence': 102962, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.7809523493052, + 'timestamp_carla': 869779, + 'timestamp_device': 1740381, + 'timestamp_stream': 869.7809523493052, + 'transform': [array([-50.43783188, 71.73744202, -0.07446435]), + array([-6.81038126e-02, 1.63809494e+02, -1.61682174e-01])]} +{'AngularVelocity': array([ 1.48580410e-03, 4.16459749e-03, -1.27711840e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.32561492919922, + 'FR_Wheel_Angle': -30.58331871032715, + 'Location': array([-58.65372086, 109.00049591, 0.20956647]), + 'Rotation': array([6.76188711e-03, 7.08824997e+01, 1.24689527e-02]), + 'Velocity': array([ 6.25493050e-01, 7.27391481e-01, -2.86769864e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2197.8544921875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3881.33227539, 10510.78125 , 115.51287842]), + 'frame': 25568, + 'frame_number': 25568, + 'framesequence': 102966, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.8131637498736, + 'timestamp_carla': 869811, + 'timestamp_device': 1740414, + 'timestamp_stream': 869.8131637498736, + 'transform': [array([-50.47692108, 71.79614258, -0.07461654]), + array([-6.89917356e-02, 1.63550308e+02, -1.61560133e-01])]} +{'AngularVelocity': array([ -1.94114304, 24.69079018, -10.39424038]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.35564041137695, + 'FR_Wheel_Angle': -30.60985565185547, + 'Location': array([-58.56739044, 109.11991119, 0.19487977]), + 'Rotation': array([-0.74578834, 69.05535126, -1.68563855]), + 'Velocity': array([ 0.71228856, 0.63401288, -0.29413524]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2180.802001953125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3874.41894531, 10494.98632812, 115.55120087]), + 'frame': 25569, + 'frame_number': 25569, + 'framesequence': 102970, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.848693151027, + 'timestamp_carla': 869847, + 'timestamp_device': 1740447, + 'timestamp_stream': 869.848693151027, + 'transform': [array([-50.51984406, 71.86129761, -0.07478043]), + array([-6.98318481e-02, 1.63263596e+02, -1.61560133e-01])]} +{'AngularVelocity': array([ -0.07257903, 1.08096528, -11.9677 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.35487747192383, + 'FR_Wheel_Angle': -30.599645614624023, + 'Location': array([-58.4765892 , 109.22628784, 0.17384237]), + 'Rotation': array([-1.45553374, 67.30351257, -2.92797923]), + 'Velocity': array([ 0.63824815, 0.62635678, -0.03541438]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2167.231201171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3867.15942383, 10482.51660156, 115.58454132]), + 'frame': 25570, + 'frame_number': 25570, + 'framesequence': 102974, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.8812809512019, + 'timestamp_carla': 869880, + 'timestamp_device': 1740481, + 'timestamp_stream': 869.8812809512019, + 'transform': [array([-50.55853271, 71.92142487, -0.07493206]), + array([-7.06992820e-02, 1.63001678e+02, -1.61438063e-01])]} +{'AngularVelocity': array([ 0.15186039, 0.26667482, -12.32771587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.340415954589844, + 'FR_Wheel_Angle': -30.591053009033203, + 'Location': array([-58.35654831, 109.36055756, 0.17320207]), + 'Rotation': array([-1.46224785, 64.96912384, -2.99487352]), + 'Velocity': array([0.67560065, 0.61905086, 0.00591293]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2172.97998046875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3853.28540039, 10488.58984375, 115.55484009]), + 'frame': 25571, + 'frame_number': 25571, + 'framesequence': 102978, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.913132648915, + 'timestamp_carla': 869911, + 'timestamp_device': 1740514, + 'timestamp_stream': 869.913132648915, + 'transform': [array([-50.59642029, 71.98084259, -0.07509664]), + array([-7.15872124e-02, 1.62743500e+02, -1.61254987e-01])]} +{'AngularVelocity': array([ 0.09983617, 0.20228873, -12.65824413]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.3257942199707, + 'FR_Wheel_Angle': -30.582061767578125, + 'Location': array([-58.24911499, 109.47213745, 0.17397268]), + 'Rotation': array([-1.45663333, 62.94826126, -3.01355004]), + 'Velocity': array([0.7127713, 0.6096589, 0.0033852]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2131.112548828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3854.31201172, 10449.04980469, 115.6681366 ]), + 'frame': 25572, + 'frame_number': 25572, + 'framesequence': 102982, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.9472977519035, + 'timestamp_carla': 869946, + 'timestamp_device': 1740547, + 'timestamp_stream': 869.9472977519035, + 'transform': [array([-50.63711929, 72.04514313, -0.07527571]), + array([-7.24204928e-02, 1.62464478e+02, -1.61132917e-01])]} +{'AngularVelocity': array([ -0.02800666, -0.1159199 , -11.75911999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.31650161743164, + 'FR_Wheel_Angle': -29.74165153503418, + 'Location': array([-58.15417862, 109.56454468, 0.17426088]), + 'Rotation': array([-1.45449555, 61.2273407 , -3.01962304]), + 'Velocity': array([0.75677115, 0.62108147, 0.00117852]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2115.594482421875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3848.04248047, 10434.72558594, 115.70927429]), + 'frame': 25573, + 'frame_number': 25573, + 'framesequence': 102986, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 869.9813558496535, + 'timestamp_carla': 869980, + 'timestamp_device': 1740581, + 'timestamp_stream': 869.9813558496535, + 'transform': [array([-50.67806625, 72.11000061, -0.07544953]), + array([-7.32606053e-02, 1.62182693e+02, -1.61010846e-01])]} +{'AngularVelocity': array([ 0.06989069, 0.14740558, -10.09545994]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.177837371826172, + 'FR_Wheel_Angle': -22.099056243896484, + 'Location': array([-57.97354889, 109.73707581, 0.17438665]), + 'Rotation': array([-1.45113504, 58.30512619, -3.03634739]), + 'Velocity': array([7.33330965e-01, 6.53790414e-01, 6.66637381e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2099.048828125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3841.3515625 , 10419.44042969, 115.74815369]), + 'frame': 25574, + 'frame_number': 25574, + 'framesequence': 102990, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.0138953514397, + 'timestamp_carla': 870012, + 'timestamp_device': 1740614, + 'timestamp_stream': 870.0138953514397, + 'transform': [array([-50.71697235, 72.17255402, -0.07562859]), + array([-7.41553605e-02, 1.61912384e+02, -1.60797223e-01])]} +{'AngularVelocity': array([ 0.0422721 , 0.12698069, -6.99247789]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.843090057373047, + 'FR_Wheel_Angle': -14.508803367614746, + 'Location': array([-57.8537674 , 109.86579895, 0.17440988]), + 'Rotation': array([-1.45052719, 56.94123077, -3.04443407]), + 'Velocity': array([6.91668928e-01, 7.23101079e-01, 4.69598774e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2101.79443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3828.81176758, 10422.49023438, 115.73352814]), + 'frame': 25575, + 'frame_number': 25575, + 'framesequence': 102994, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.0475684516132, + 'timestamp_carla': 870046, + 'timestamp_device': 1740647, + 'timestamp_stream': 870.0475684516132, + 'transform': [array([-50.7569046 , 72.23769379, -0.07582364]), + array([-7.50569478e-02, 1.61632248e+02, -1.60583615e-01])]} +{'AngularVelocity': array([ 0.01170615, 0.10421615, -3.91441703]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.495577335357666, + 'FR_Wheel_Angle': -4.347372531890869, + 'Location': array([-57.74334717, 109.99964905, 0.17441712]), + 'Rotation': array([-1.4516269 , 56.15087128, -3.04766941]), + 'Velocity': array([ 6.36557758e-01, 7.83956945e-01, -3.97634489e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 4361.43212890625, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-3116.01025391, 12570.82617188, 109.38993835]), + 'frame': 25576, + 'frame_number': 25576, + 'framesequence': 102998, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.0812950506806, + 'timestamp_carla': 870080, + 'timestamp_device': 1740681, + 'timestamp_stream': 870.0812950506806, + 'transform': [array([-50.79691696, 72.30355072, -0.0760178 ]), + array([-7.59448707e-02, 1.61349579e+02, -1.60369962e-01])]} +{'AngularVelocity': array([-0.05023638, 0.05226996, 0.01098716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5714122653007507, + 'FR_Wheel_Angle': 0.3143029510974884, + 'Location': array([-57.62301254, 110.1687851 , 0.17418382]), + 'Rotation': array([-1.46655762, 55.92596817, -3.02459788]), + 'Velocity': array([ 5.53791642e-01, 8.30645800e-01, -8.96358470e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2051.01318359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3821.90600586, 10375.01464844, 115.87007904]), + 'frame': 25577, + 'frame_number': 25577, + 'framesequence': 103002, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.1141294501722, + 'timestamp_carla': 870112, + 'timestamp_device': 1740714, + 'timestamp_stream': 870.1141294501722, + 'transform': [array([-50.83568573, 72.36823273, -0.07620963]), + array([-7.68464506e-02, 1.61073135e+02, -1.60125852e-01])]} +{'AngularVelocity': array([-25.63082886, -15.91151905, 2.10395908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0050352951511740685, + 'FR_Wheel_Angle': 0.005038027185946703, + 'Location': array([-57.49594116, 110.34925842, 0.16298276]), + 'Rotation': array([-2.0518229 , 55.97478867, -1.61993408]), + 'Velocity': array([ 0.41711283, 0.91138029, -0.31845638]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2035.101806640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3815.46582031, 10360.30175781, 115.91080475]), + 'frame': 25578, + 'frame_number': 25578, + 'framesequence': 103006, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.1478018499911, + 'timestamp_carla': 870146, + 'timestamp_device': 1740747, + 'timestamp_stream': 870.1478018499911, + 'transform': [array([-50.87519455, 72.43505096, -0.07641292]), + array([-7.77412057e-02, 1.60788757e+02, -1.59881711e-01])]} +{'AngularVelocity': array([-2.26336765, -1.16053152, 0.22922856]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00504082627594471, + 'FR_Wheel_Angle': 0.0050410255789756775, + 'Location': array([-57.40540314, 110.49055481, 0.14254931]), + 'Rotation': array([-2.75372028, 56.0018158 , -0.36767584]), + 'Velocity': array([ 0.50135779, 0.78149086, -0.047522 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2029.748779296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3805.99462891, 10355.56933594, 115.92436218]), + 'frame': 25579, + 'frame_number': 25579, + 'framesequence': 103010, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.181392852217, + 'timestamp_carla': 870180, + 'timestamp_device': 1740781, + 'timestamp_stream': 870.181392852217, + 'transform': [array([-50.91455841, 72.50229645, -0.07661422]), + array([-7.86427930e-02, 1.60503235e+02, -1.59637600e-01])]} +{'AngularVelocity': array([-0.82043028, -0.47217721, 0.1463345 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005039466079324484, + 'FR_Wheel_Angle': 0.005039524286985397, + 'Location': array([-57.31894302, 110.61960602, 0.13967061]), + 'Rotation': array([-2.85292888, 56.00690079, -0.14266965]), + 'Velocity': array([ 0.52232385, 0.78897047, -0.00793343]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 5775.76513671875, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-2561.84448242, 13893.26171875, 105.4682312 ]), + 'frame': 25580, + 'frame_number': 25580, + 'framesequence': 103014, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.2132852524519, + 'timestamp_carla': 870212, + 'timestamp_device': 1740814, + 'timestamp_stream': 870.2132852524519, + 'transform': [array([-50.95167542, 72.56666565, -0.07681971]), + array([-7.95648694e-02, 1.60231186e+02, -1.59301892e-01])]} +{'AngularVelocity': array([-0.37442049, -0.17777511, 0.10782661]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005038526374846697, + 'FR_Wheel_Angle': 0.005038658156991005, + 'Location': array([-57.23355484, 110.74668884, 0.13928209]), + 'Rotation': array([-2.88522196e+00, 5.60127335e+01, -5.53284027e-02]), + 'Velocity': array([ 0.53136367, 0.79524559, -0.00136965]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1988.6099853515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3796.65893555, 10317.33496094, 116.03302002]), + 'frame': 25581, + 'frame_number': 25581, + 'framesequence': 103018, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.2475931495428, + 'timestamp_carla': 870246, + 'timestamp_device': 1740847, + 'timestamp_stream': 870.2475931495428, + 'transform': [array([-50.99137115, 72.63635254, -0.07703415]), + array([-8.04527923e-02, 1.59937637e+02, -1.59057766e-01])]} +{'AngularVelocity': array([16.27550888, 7.24730587, -1.71474421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0050402614288032055, + 'FR_Wheel_Angle': 0.00504102511331439, + 'Location': array([-57.14735413, 110.88176727, 0.12326223]), + 'Rotation': array([-2.2586956 , 55.93154526, -1.12240601]), + 'Velocity': array([ 0.58024442, 0.70853317, -0.19642034]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1974.0186767578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3790.76000977, 10303.85839844, 116.0761261 ]), + 'frame': 25582, + 'frame_number': 25582, + 'framesequence': 103022, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.2808775492013, + 'timestamp_carla': 870279, + 'timestamp_device': 1740881, + 'timestamp_stream': 870.2808775492013, + 'transform': [array([-51.02996445, 72.70463562, -0.07723976]), + array([-8.13543797e-02, 1.59650314e+02, -1.58783078e-01])]} +{'AngularVelocity': array([ 0.75936443, 0.13097543, -0.2315224 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005043945740908384, + 'FR_Wheel_Angle': 0.005044165533035994, + 'Location': array([-5.70604515e+01, 1.11007545e+02, 9.75304618e-02]), + 'Rotation': array([-1.44091713, 55.89842987, -2.22686791]), + 'Velocity': array([ 0.50949514, 0.7368167 , -0.03184285]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1958.4644775390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3784.47265625, 10289.49414062, 116.11460114]), + 'frame': 25583, + 'frame_number': 25583, + 'framesequence': 103026, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.3152441494167, + 'timestamp_carla': 870314, + 'timestamp_device': 1740914, + 'timestamp_stream': 870.3152441494167, + 'transform': [array([-51.06954956, 72.77558136, -0.07745092]), + array([-8.22559670e-02, 1.59352737e+02, -1.58538982e-01])]} +{'AngularVelocity': array([-0.10542182, 0.11191251, -0.24547789]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005042431876063347, + 'FR_Wheel_Angle': 0.005042808596044779, + 'Location': array([-5.69777222e+01, 1.11129486e+02, 9.67173204e-02]), + 'Rotation': array([-1.43255019, 55.89416122, -2.24490356]), + 'Velocity': array([0.50992894, 0.75292403, 0.00516698]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1650.707763671875, + 'focus_actor_name': 'AmericanLights_Town04_30_TrafficLight', + 'focus_actor_pt': array([-3880.19873047, 10001.14453125, 116.96598053]), + 'frame': 25584, + 'frame_number': 25584, + 'framesequence': 103030, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.3490590490401, + 'timestamp_carla': 870347, + 'timestamp_device': 1740947, + 'timestamp_stream': 870.3490590490401, + 'transform': [array([-51.10839844, 72.84598541, -0.07766046]), + array([-8.31780359e-02, 1.59058105e+02, -1.58264309e-01])]} +{'AngularVelocity': array([-0.07852101, 0.08904257, -0.34923449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005042821168899536, + 'FR_Wheel_Angle': 0.005042909178882837, + 'Location': array([-5.68878174e+01, 1.11262497e+02, 9.76032019e-02]), + 'Rotation': array([-1.44454396, 55.88314438, -2.24603295]), + 'Velocity': array([0.50746572, 0.74974281, 0.00333811]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1639.8499755859375, + 'focus_actor_name': 'AmericanLights_Town04_30_TrafficLight', + 'focus_actor_pt': array([-3873.82177734, 9991.69140625, 116.9907608 ]), + 'frame': 25585, + 'frame_number': 25585, + 'framesequence': 103034, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.3804938495159, + 'timestamp_carla': 870379, + 'timestamp_device': 1740981, + 'timestamp_stream': 870.3804938495159, + 'transform': [array([-51.14412308, 72.91194916, -0.07787501]), + array([-8.41342658e-02, 1.58783707e+02, -1.57867566e-01])]} +{'AngularVelocity': array([-0.05381697, 0.0628861 , -0.24110927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005041340831667185, + 'FR_Wheel_Angle': 0.005041528958827257, + 'Location': array([-5.68029175e+01, 1.11387909e+02, 9.80499461e-02]), + 'Rotation': array([-1.44799316, 55.87799454, -2.24569702]), + 'Velocity': array([0.51683831, 0.76299673, 0.0012113 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1636.08447265625, + 'focus_actor_name': 'AmericanLights_Town04_30_TrafficLight', + 'focus_actor_pt': array([-3865.11474609, 9988.83789062, 116.99758911]), + 'frame': 25586, + 'frame_number': 25586, + 'framesequence': 103038, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.4152060523629, + 'timestamp_carla': 870414, + 'timestamp_device': 1741014, + 'timestamp_stream': 870.4152060523629, + 'transform': [array([-51.18330383, 72.98519135, -0.07810971]), + array([-8.50426778e-02, 1.58479919e+02, -1.57562390e-01])]} +{'AngularVelocity': array([-0.02052976, 0.00312118, 0.01034443]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005040990654379129, + 'FR_Wheel_Angle': 0.005040237680077553, + 'Location': array([-5.66952629e+01, 1.11546944e+02, 9.81356204e-02]), + 'Rotation': array([-1.44970763, 55.87129211, -2.24563551]), + 'Velocity': array([5.24664760e-01, 7.74805844e-01, 5.72185498e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1640.7078857421875, + 'focus_actor_name': 'AmericanLights_Town04_30_TrafficLight', + 'focus_actor_pt': array([-3854.0793457 , 9993.74707031, 116.98722839]), + 'frame': 25587, + 'frame_number': 25587, + 'framesequence': 103042, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29971620440483093, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.4478609524667, + 'timestamp_carla': 870446, + 'timestamp_device': 1741047, + 'timestamp_stream': 870.4478609524667, + 'transform': [array([-51.22019958, 73.05477142, -0.07833035]), + array([-8.59715864e-02, 1.58191620e+02, -1.57196179e-01])]} +{'AngularVelocity': array([-0.03901709, 0.05469466, -0.25747609]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005039755254983902, + 'FR_Wheel_Angle': 0.005040074232965708, + 'Location': array([-5.66105537e+01, 1.11672050e+02, 9.82323214e-02]), + 'Rotation': array([-1.44991243, 55.86606598, -2.24581885]), + 'Velocity': array([5.27068436e-01, 7.77663708e-01, 2.33530998e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1888.978515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3752.61450195, 10225.3125 , 116.30008698]), + 'frame': 25588, + 'frame_number': 25588, + 'framesequence': 103046, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299459844827652, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.4825276508927, + 'timestamp_carla': 870481, + 'timestamp_device': 1741081, + 'timestamp_stream': 870.4825276508927, + 'transform': [array([-51.25897217, 73.12902832, -0.07855437]), + array([-8.68595093e-02, 1.57885269e+02, -1.56921506e-01])]} +{'AngularVelocity': array([-0.04224499, 0.05758908, -0.26627523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.65245285e+01, 1.11799088e+02, 9.82325524e-02]), + 'Rotation': array([-1.45082772, 55.85873413, -2.24597192]), + 'Velocity': array([5.19643724e-01, 7.66802251e-01, 1.60722731e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1895.2099609375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3739.28271484, 10231.1484375 , 116.28458405]), + 'frame': 25589, + 'frame_number': 25589, + 'framesequence': 103050, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2897549271583557, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.514997150749, + 'timestamp_carla': 870513, + 'timestamp_device': 1741114, + 'timestamp_stream': 870.514997150749, + 'transform': [array([-51.29409409, 73.19863892, -0.07876337]), + array([-8.71600360e-02, 1.57602097e+02, -1.56524792e-01])]} +{'AngularVelocity': array([-0.01387563, 0.01436708, -0.0264104 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.64161797e+01, 1.11958855e+02, 9.81938690e-02]), + 'Rotation': array([-1.44879234, 55.85968018, -2.24569678]), + 'Velocity': array([ 5.56210577e-01, 8.20298612e-01, -5.30385936e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1855.0660400390625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3742.65063477, 10193.94726562, 116.39063263]), + 'frame': 25590, + 'frame_number': 25590, + 'framesequence': 103054, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.27140721678733826, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.5482212491333, + 'timestamp_carla': 870547, + 'timestamp_device': 1741147, + 'timestamp_stream': 870.5482212491333, + 'transform': [array([-51.32701492, 73.26888275, -0.07897268]), + array([-8.63950551e-02, 1.57326080e+02, -1.56067029e-01])]} +{'AngularVelocity': array([-0.0119141 , 0.01103104, -0.0190498 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.63268433e+01, 1.12090584e+02, 9.82302278e-02]), + 'Rotation': array([-1.4516542 , 55.85940933, -2.24588037]), + 'Velocity': array([ 5.25114954e-01, 7.74440765e-01, -3.78131845e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1841.387451171875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3737.15380859, 10181.38964844, 116.43041992]), + 'frame': 25591, + 'frame_number': 25591, + 'framesequence': 103058, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24668721854686737, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.5800375491381, + 'timestamp_carla': 870578, + 'timestamp_device': 1741181, + 'timestamp_stream': 870.5800375491381, + 'transform': [array([-51.35465622, 73.33470917, -0.0791668 ]), + array([-8.47079977e-02, 1.57080292e+02, -1.55517712e-01])]} +{'AngularVelocity': array([-0.00375366, 0.01054878, -0.06596242]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.62420692e+01, 1.12215607e+02, 9.82360244e-02]), + 'Rotation': array([-1.45325243, 55.85891342, -2.24597216]), + 'Velocity': array([4.90324050e-01, 7.23134518e-01, 1.18837357e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1827.9554443359375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3731.85302734, 10169.27929688, 116.46881866]), + 'frame': 25592, + 'frame_number': 25592, + 'framesequence': 103062, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22471390664577484, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.6162166520953, + 'timestamp_carla': 870615, + 'timestamp_device': 1741214, + 'timestamp_stream': 870.6162166520953, + 'transform': [array([-51.38152313, 73.40746307, -0.07935054]), + array([-8.23720768e-02, 1.56823929e+02, -1.55182049e-01])]} +{'AngularVelocity': array([-0.00051325, 0.00611583, -0.05099954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.61637154e+01, 1.12331123e+02, 9.82396454e-02]), + 'Rotation': array([-1.45377159, 55.85865402, -2.24597168]), + 'Velocity': array([4.57462937e-01, 6.74669087e-01, 3.10468662e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1817.1468505859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3726.64428711, 10159.86816406, 116.50314331]), + 'frame': 25593, + 'frame_number': 25593, + 'framesequence': 103066, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21381878852844238, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.6484813503921, + 'timestamp_carla': 870647, + 'timestamp_device': 1741247, + 'timestamp_stream': 870.6484813503921, + 'transform': [array([-51.40304565, 73.47155762, -0.07952294]), + array([-8.12792480e-02, 1.56606750e+02, -1.54785305e-01])]} +{'AngularVelocity': array([ 0.00120643, 0.0077833 , -0.07576793]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.60902100e+01, 1.12439545e+02, 9.82364044e-02]), + 'Rotation': array([-1.45381939, 55.85811996, -2.24597192]), + 'Velocity': array([4.26525027e-01, 6.29035950e-01, 7.48538951e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1821.71875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3714.89453125, 10165.01171875, 116.48303223]), + 'frame': 25594, + 'frame_number': 25594, + 'framesequence': 103070, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21978820860385895, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.6821843497455, + 'timestamp_carla': 870681, + 'timestamp_device': 1741281, + 'timestamp_stream': 870.6821843497455, + 'transform': [array([-51.4248085 , 73.53855133, -0.07972829]), + array([-8.20169076e-02, 1.56382004e+02, -1.54541180e-01])]} +{'AngularVelocity': array([ 0.00190782, 0.01217698, -0.11902805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.60213356e+01, 1.12541153e+02, 9.82280150e-02]), + 'Rotation': array([-1.45373738, 55.85770035, -2.24600244]), + 'Velocity': array([ 3.97525012e-01, 5.86273193e-01, -1.80559160e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 2733.052490234375, + 'focus_actor_name': 'InstancedFoliageActor_1', + 'focus_actor_pt': array([-3344.51318359, 11002.42382812, 114.021698 ]), + 'frame': 25595, + 'frame_number': 25595, + 'framesequence': 103074, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.232514426112175, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.7147661522031, + 'timestamp_carla': 870713, + 'timestamp_device': 1741314, + 'timestamp_stream': 870.7147661522031, + 'transform': [array([-51.4472847 , 73.60457611, -0.0799541 ]), + array([-8.43596607e-02, 1.56155151e+02, -1.54327512e-01])]} +{'AngularVelocity': array([ 0.00209315, 0.02623159, -0.06661927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.59585037e+01, 1.12632889e+02, 9.81665626e-02]), + 'Rotation': array([-1.45043159, 55.88663483, -2.24414086]), + 'Velocity': array([3.56203020e-01, 5.25633812e-01, 6.94847113e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1780.058837890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3714.1730957 , 10128.88769531, 116.59153748]), + 'frame': 25596, + 'frame_number': 25596, + 'framesequence': 103078, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24533221125602722, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.7474696524441, + 'timestamp_carla': 870746, + 'timestamp_device': 1741347, + 'timestamp_stream': 870.7474696524441, + 'transform': [array([-51.47170639, 73.67236328, -0.08019672]), + array([-8.74673948e-02, 1.55915283e+02, -1.54144421e-01])]} +{'AngularVelocity': array([-0.00291551, 0.00982467, -0.03233125]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.59011574e+01, 1.12717567e+02, 9.82159600e-02]), + 'Rotation': array([-1.45192742, 55.88637543, -2.24530029]), + 'Velocity': array([0.3327224 , 0.49117517, 0.00056824]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1768.7115478515625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3710.03613281, 10119.43652344, 116.61933899]), + 'frame': 25597, + 'frame_number': 25597, + 'framesequence': 103082, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25280311703681946, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.7807988524437, + 'timestamp_carla': 870779, + 'timestamp_device': 1741381, + 'timestamp_stream': 870.7807988524437, + 'transform': [array([-51.49808502, 73.74275208, -0.08043507]), + array([-9.03702304e-02, 1.55660736e+02, -1.53991863e-01])]} +{'AngularVelocity': array([ -0.81735373, -11.25481987, 1.09242749]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.58452759e+01, 1.12796181e+02, 9.41134468e-02]), + 'Rotation': array([-1.28109753, 55.93862152, -1.93792737]), + 'Velocity': array([ 0.28690678, 0.4869692 , -0.10096797]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1757.0523681640625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3705.70581055, 10109.54296875, 116.64685822]), + 'frame': 25598, + 'frame_number': 25598, + 'framesequence': 103086, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25100862979888916, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.8138626515865, + 'timestamp_carla': 870812, + 'timestamp_device': 1741414, + 'timestamp_stream': 870.8138626515865, + 'transform': [array([-51.52439499, 73.81316376, -0.08065695]), + array([-9.22348723e-02, 1.55405151e+02, -1.53778255e-01])]} +{'AngularVelocity': array([ 0.16862579, -1.46733475, -0.10323785]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.57864647e+01, 1.12883194e+02, 5.87178208e-02]), + 'Rotation': array([-0.05913578, 55.97242355, -0.14453124]), + 'Velocity': array([ 0.24885602, 0.38626677, -0.03878269]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1744.9761962890625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3701.15698242, 10099.15039062, 116.6736145 ]), + 'frame': 25599, + 'frame_number': 25599, + 'framesequence': 103090, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24502091109752655, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.8479206524789, + 'timestamp_carla': 870846, + 'timestamp_device': 1741447, + 'timestamp_stream': 870.8479206524789, + 'transform': [array([-51.55056 , 73.88562012, -0.08087105]), + array([-9.30476636e-02, 1.55144882e+02, -1.53534099e-01])]} +{'AngularVelocity': array([-0.09833114, -0.3139801 , -0.11402106]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.57445831e+01, 1.12945465e+02, 5.65966219e-02]), + 'Rotation': array([-6.16766047e-03, 5.59721527e+01, -5.08117639e-02]), + 'Velocity': array([2.40834340e-01, 3.61823946e-01, 2.33716957e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1650.7110595703125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3730.88452148, 10013.99023438, 116.92225647]), + 'frame': 25600, + 'frame_number': 25600, + 'framesequence': 103094, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23852047324180603, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.880200650543, + 'timestamp_carla': 870879, + 'timestamp_device': 1741481, + 'timestamp_stream': 870.880200650543, + 'transform': [array([-51.57412338, 73.95413208, -0.0810766 ]), + array([-9.32935476e-02, 1.54902710e+02, -1.53167889e-01])]} +{'AngularVelocity': array([-0.04848232, -0.11715301, -0.10658488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.57052765e+01, 1.13003838e+02, 5.68687618e-02]), + 'Rotation': array([ 1.89196225e-03, 5.59719391e+01, -1.73645020e-02]), + 'Velocity': array([0.22611097, 0.33733898, 0.00183264]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1643.1124267578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3724.75195312, 10007.85742188, 116.93678284]), + 'frame': 25601, + 'frame_number': 25601, + 'framesequence': 103098, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23416243493556976, + 'throttle_input': 0.12300297617912292, + 'timestamp': 870.9137835502625, + 'timestamp_carla': 870912, + 'timestamp_device': 1741514, + 'timestamp_stream': 870.9137835502625, + 'transform': [array([-51.59739304, 74.0251236 , -0.0812906 ]), + array([-9.34233218e-02, 1.54655609e+02, -1.52832225e-01])]} +{'AngularVelocity': array([-0.01687294, -0.03914554, -0.03040927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56624260e+01, 1.13067459e+02, 5.71073331e-02]), + 'Rotation': array([ 4.73332079e-03, 5.59719505e+01, -2.80761695e-03]), + 'Velocity': array([0.20867297, 0.31032279, 0.00075243]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1642.249755859375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3716.41723633, 10007.85742188, 116.93849182]), + 'frame': 25602, + 'frame_number': 25602, + 'framesequence': 103102, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23476670682430267, + 'throttle_input': 0.11506828665733337, + 'timestamp': 870.9475846514106, + 'timestamp_carla': 870946, + 'timestamp_device': 1741547, + 'timestamp_stream': 870.9475846514106, + 'transform': [array([-51.6204071 , 74.09681702, -0.08150844]), + array([-9.39697400e-02, 1.54407166e+02, -1.52527034e-01])]} +{'AngularVelocity': array([ 4.39085439e-02, -4.74058464e-02, -6.42767918e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.00512685114517808, + 'FR_Wheel_Angle': 0.005127104930579662, + 'Location': array([-5.56529007e+01, 1.13080597e+02, 5.72111309e-02]), + 'Rotation': array([-8.48309416e-03, 5.60014038e+01, 1.69811840e-03]), + 'Velocity': array([-2.73234546e-05, -3.47213390e-05, 5.41419955e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1686.1131591796875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3688.71484375, 10048.359375 , 116.81795502]), + 'frame': 25603, + 'frame_number': 25603, + 'framesequence': 103106, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2376781702041626, + 'throttle_input': 0.1111009418964386, + 'timestamp': 870.9808810502291, + 'timestamp_carla': 870979, + 'timestamp_device': 1741581, + 'timestamp_stream': 870.9808810502291, + 'transform': [array([-51.64317703, 74.16792297, -0.08172362]), + array([-9.49806049e-02, 1.54159912e+02, -1.52252391e-01])]} +{'AngularVelocity': array([ 3.01442686e-02, -2.83702500e-02, 8.39306949e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126852076500654, + 'FR_Wheel_Angle': 0.005127107258886099, + 'Location': array([-5.56528511e+01, 1.13080643e+02, 5.72134592e-02]), + 'Rotation': array([1.24992453e-03, 5.60012894e+01, 3.43412929e-03]), + 'Velocity': array([-1.59801384e-05, -2.36078486e-05, 1.32770539e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1676.62646484375, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3683.65771484, 10040.56835938, 116.83944702]), + 'frame': 25604, + 'frame_number': 25604, + 'framesequence': 103110, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24091921746730804, + 'throttle_input': 0.1111009418964386, + 'timestamp': 871.0156211517751, + 'timestamp_carla': 871014, + 'timestamp_device': 1741614, + 'timestamp_stream': 871.0156211517751, + 'transform': [array([-51.66723633, 74.24268341, -0.08194007]), + array([-9.62441936e-02, 1.53898361e+02, -1.52069300e-01])]} +{'AngularVelocity': array([ 9.64628998e-03, -9.37807932e-03, 1.28442565e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0051268539391458035, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([-5.56528244e+01, 1.13080673e+02, 5.71904555e-02]), + 'Rotation': array([5.91494329e-03, 5.60011215e+01, 4.21399949e-03]), + 'Velocity': array([-5.17779563e-06, -7.66337598e-06, -4.20856450e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1651.14404296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3685.7043457 , 10018.34179688, 116.90351868]), + 'frame': 25605, + 'frame_number': 25605, + 'framesequence': 103114, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24236580729484558, + 'throttle_input': 0.1111009418964386, + 'timestamp': 871.0468589514494, + 'timestamp_carla': 871045, + 'timestamp_device': 1741647, + 'timestamp_stream': 871.0468589514494, + 'transform': [array([-51.68898392, 74.31050873, -0.08214113]), + array([-9.74531323e-02, 1.53660278e+02, -1.51764095e-01])]} +{'AngularVelocity': array([ 3.48420441e-03, -3.56418546e-03, 4.49003146e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854404807091, + 'FR_Wheel_Angle': 0.005127109121531248, + 'Location': array([-5.56528168e+01, 1.13080673e+02, 5.71669564e-02]), + 'Rotation': array([6.80286810e-03, 5.60010529e+01, 4.37551551e-03]), + 'Velocity': array([-1.97681584e-06, -2.78068728e-06, -1.26056664e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1638.6904296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3681.73046875, 10007.85839844, 116.92866516]), + 'frame': 25606, + 'frame_number': 25606, + 'framesequence': 103118, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2413586974143982, + 'throttle_input': 0.1111009418964386, + 'timestamp': 871.0806078501046, + 'timestamp_carla': 871079, + 'timestamp_device': 1741681, + 'timestamp_stream': 871.0806078501046, + 'transform': [array([-51.7120285 , 74.38385773, -0.08236291]), + array([-9.83956978e-02, 1.53403549e+02, -1.51489481e-01])]} +{'AngularVelocity': array([ 1.14610419e-03, -1.07047288e-03, 5.90689453e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.005126854870468378, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71609661e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-5.69007966e-07, -9.22388040e-07, -3.91168578e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1638.0322265625, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3673.47802734, 10007.85839844, 116.93052673]), + 'frame': 25607, + 'frame_number': 25607, + 'framesequence': 103122, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23945434391498566, + 'throttle_input': 0.10316624492406845, + 'timestamp': 871.1142571493983, + 'timestamp_carla': 871113, + 'timestamp_device': 1741714, + 'timestamp_stream': 871.1142571493983, + 'transform': [array([-51.73459244, 74.45713043, -0.08256641]), + array([-9.90445688e-02, 1.53147934e+02, -1.51245326e-01])]} +{'AngularVelocity': array([ 3.76736280e-04, -3.63516388e-04, -6.67673419e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71618453e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-1.50349436e-07, -2.65834444e-07, 5.65171242e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1637.3514404296875, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3664.55834961, 10007.859375 , 116.92759705]), + 'frame': 25608, + 'frame_number': 25608, + 'framesequence': 103126, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23872189223766327, + 'throttle_input': 0.09126421064138412, + 'timestamp': 871.1479411497712, + 'timestamp_carla': 871146, + 'timestamp_device': 1741747, + 'timestamp_stream': 871.1479411497712, + 'transform': [array([-51.75670242, 74.53051758, -0.08275946]), + array([-9.96251330e-02, 1.52892883e+02, -1.51031718e-01])]} +{'AngularVelocity': array([ 7.15756541e-05, -1.68554252e-04, -1.37212099e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([-5.56528168e+01, 1.13080681e+02, 5.71639799e-02]), + 'Rotation': array([6.93947170e-03, 5.60010338e+01, 4.40178718e-03]), + 'Velocity': array([-3.51523965e-08, -1.05516087e-07, 5.80182066e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1636.702392578125, + 'focus_actor_name': 'BP_RepSpline109_14', + 'focus_actor_pt': array([-3655.66162109, 10007.859375 , 116.92370605]), + 'frame': 25609, + 'frame_number': 25609, + 'framesequence': 103130, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2394726574420929, + 'throttle_input': 0.08332952111959457, + 'timestamp': 871.1809071488678, + 'timestamp_carla': 871179, + 'timestamp_device': 1741781, + 'timestamp_stream': 871.1809071488678, + 'transform': [array([-51.7780571 , 74.6024704 , -0.08294611]), + array([-1.00301325e-01, 1.52643005e+02, -1.50818095e-01])]} \ No newline at end of file diff --git a/PythonAPI/data/vehicle_logs/forward_2.txt b/PythonAPI/data/vehicle_logs/forward_2.txt new file mode 100644 index 0000000..ab91ac8 --- /dev/null +++ b/PythonAPI/data/vehicle_logs/forward_2.txt @@ -0,0 +1,20351 @@ +{'AngularVelocity': array([9.33988815e-07, 4.47465891e-06, 3.80926446e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30171618]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([-7.53566809e-09, -4.12201162e-09, -7.50350955e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521240234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37534, + 'frame_number': 37534, + 'framesequence': 151369, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.059819597751, + 'timestamp_carla': 1274064, + 'timestamp_device': 2892621, + 'timestamp_stream': 1274.059819597751, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43183812e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([4.59717694e-06, 2.27627265e-06, 1.30427658e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30170527]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([-2.77870532e-10, -3.83192056e-09, 1.34935370e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5219116210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37535, + 'frame_number': 37535, + 'framesequence': 151373, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.0952307991683, + 'timestamp_carla': 1274100, + 'timestamp_device': 2892655, + 'timestamp_stream': 1274.0952307991683, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43203273e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 5.98433417e-06, -3.69792019e-06, 1.03580771e-08]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30169681]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 1.99696615e-08, 1.94847072e-09, -2.80179986e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5214233398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37536, + 'frame_number': 37536, + 'framesequence': 151377, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.1274137981236, + 'timestamp_carla': 1274132, + 'timestamp_device': 2892688, + 'timestamp_stream': 1274.1274137981236, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43189698e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 6.54246696e-06, -1.97451845e-06, -4.11240729e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30170375]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 1.77318960e-09, -3.57452867e-09, 3.43909254e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5175170898438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37537, + 'frame_number': 37537, + 'framesequence': 151381, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.1602874994278, + 'timestamp_carla': 1274165, + 'timestamp_device': 2892721, + 'timestamp_stream': 1274.1602874994278, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43186942e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([3.25535007e-06, 4.04006187e-06, 2.60573976e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30173343]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 9.45662326e-10, -2.88957147e-09, 4.86702920e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5202026367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37538, + 'frame_number': 37538, + 'framesequence': 151385, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.1957404986024, + 'timestamp_carla': 1274200, + 'timestamp_device': 2892755, + 'timestamp_stream': 1274.1957404986024, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43206254e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 5.83523888e-06, -2.14348916e-07, 4.31584324e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30171505]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([-7.58006102e-09, -6.53605303e-09, 1.48453706e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.520751953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37539, + 'frame_number': 37539, + 'framesequence': 151389, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.2291139997542, + 'timestamp_carla': 1274233, + 'timestamp_device': 2892788, + 'timestamp_stream': 1274.2291139997542, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43200457e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 6.23241294e-06, -6.62614070e-07, 7.99289940e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30167881]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 1.60607583e-09, -3.71464393e-09, -7.15408300e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5169067382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37540, + 'frame_number': 37540, + 'framesequence': 151393, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.262178298086, + 'timestamp_carla': 1274267, + 'timestamp_device': 2892821, + 'timestamp_stream': 1274.262178298086, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43194735e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 2.61278024e-06, 3.29181603e-06, -6.33422870e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30170467]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([-3.05171710e-08, -1.30210349e-08, 2.57115345e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51806640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37541, + 'frame_number': 37541, + 'framesequence': 151397, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.298437397927, + 'timestamp_carla': 1274303, + 'timestamp_device': 2892855, + 'timestamp_stream': 1274.298437397927, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43217549e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 2.78149196e-06, 3.09188954e-06, -5.36668376e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30169758]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 1.31404987e-09, -2.22752217e-09, 3.93238064e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5192260742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37542, + 'frame_number': 37542, + 'framesequence': 151401, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.3298644982278, + 'timestamp_carla': 1274334, + 'timestamp_device': 2892888, + 'timestamp_stream': 1274.3298644982278, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43193588e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 5.36255084e-06, -1.11010911e-06, 4.66932222e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30169985]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 1.29702260e-09, -3.09823234e-09, -1.87578204e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5146484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24023438, 30.00003052]), + 'frame': 37543, + 'frame_number': 37543, + 'framesequence': 151405, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.3615523986518, + 'timestamp_carla': 1274366, + 'timestamp_device': 2892921, + 'timestamp_stream': 1274.3615523986518, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43181145e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 4.07236848e-06, -5.23607059e-06, -9.52871254e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30170766]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 2.17140680e-10, -1.63052327e-09, 1.44920341e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5194702148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37544, + 'frame_number': 37544, + 'framesequence': 151409, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.3944880999625, + 'timestamp_carla': 1274399, + 'timestamp_device': 2892955, + 'timestamp_stream': 1274.3944880999625, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43183216e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 4.54643850e-06, -7.95295762e-07, 9.60646927e-12]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30169392]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 5.83718740e-10, -2.83738300e-09, 8.37521511e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5219116210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37545, + 'frame_number': 37545, + 'framesequence': 151413, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.4295271001756, + 'timestamp_carla': 1274434, + 'timestamp_device': 2892988, + 'timestamp_stream': 1274.4295271001756, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43201515e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 3.31617321e-06, -7.87907481e-07, 4.33600118e-12]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30170092]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 7.55461180e-11, -2.12186624e-09, -3.50503920e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37546, + 'frame_number': 37546, + 'framesequence': 151417, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.461801096797, + 'timestamp_carla': 1274466, + 'timestamp_device': 2893021, + 'timestamp_stream': 1274.461801096797, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43190920e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 5.78958088e-06, -4.77939284e-06, 7.11607551e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30170017]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([-4.91300778e-10, -3.16573834e-09, -3.88717657e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5178833007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37547, + 'frame_number': 37547, + 'framesequence': 151421, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.4964956976473, + 'timestamp_carla': 1274501, + 'timestamp_device': 2893055, + 'timestamp_stream': 1274.4964956976473, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43203199e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 5.58032798e-06, -8.84034671e-06, 7.72926223e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30171901]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([-7.66673058e-10, -2.20926943e-09, 2.91166303e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5199584960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37548, + 'frame_number': 37548, + 'framesequence': 151425, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.5290321968496, + 'timestamp_carla': 1274533, + 'timestamp_device': 2893088, + 'timestamp_stream': 1274.5290321968496, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43193737e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 5.26248414e-06, -2.67749897e-06, -1.17400090e-10]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30167171]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 1.11942089e-09, -2.71669109e-09, 5.95808029e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5175170898438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37549, + 'frame_number': 37549, + 'framesequence': 151429, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.559982497245, + 'timestamp_carla': 1274564, + 'timestamp_device': 2893121, + 'timestamp_stream': 1274.559982497245, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43178180e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 3.97750500e-06, -1.36084765e-07, 4.98596615e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30171245]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 7.36221639e-10, -2.53742205e-09, 8.45718387e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5194091796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37550, + 'frame_number': 37550, + 'framesequence': 151433, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.5927133001387, + 'timestamp_carla': 1274597, + 'timestamp_device': 2893155, + 'timestamp_stream': 1274.5927133001387, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43181458e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 4.84913244e-06, -8.78777428e-06, 7.94200643e-12]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30171138]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([-4.37705788e-10, -1.58682723e-09, 1.47314073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5225219726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23242188, 30.00003052]), + 'frame': 37551, + 'frame_number': 37551, + 'framesequence': 151437, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.626341599971, + 'timestamp_carla': 1274631, + 'timestamp_device': 2893188, + 'timestamp_stream': 1274.626341599971, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43190682e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-3.00088541e-05, 4.40336298e-05, 2.81212387e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30170888]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([3.69929190e-08, 2.38373605e-08, 2.75239930e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5217895507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37552, + 'frame_number': 37552, + 'framesequence': 151441, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.6598086990416, + 'timestamp_carla': 1274664, + 'timestamp_device': 2893221, + 'timestamp_stream': 1274.6598086990416, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43194959e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 6.76506352e-06, -6.21406434e-06, 3.99256357e-11]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([240.15190125, 167.00819397, 0.30171269]), + 'Rotation': array([-2.26693973e-02, -7.23946762e+01, -8.91113281e-03]), + 'Velocity': array([ 2.55517635e-10, -3.28679395e-09, 2.63977054e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37553, + 'frame_number': 37553, + 'framesequence': 151445, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.6953765004873, + 'timestamp_carla': 1274700, + 'timestamp_device': 2893255, + 'timestamp_stream': 1274.6953765004873, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43214330e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 2.41286922e-04, -1.50459050e-03, 1.23409009e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011534616351127625, + 'FR_Wheel_Angle': 0.011535963974893093, + 'Location': array([240.15194702, 167.00819397, 0.30170366]), + 'Rotation': array([-2.26693973e-02, -7.24006195e+01, -8.94165132e-03]), + 'Velocity': array([1.74398228e-04, 4.84026066e-04, 6.81972524e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5191650390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37554, + 'frame_number': 37554, + 'framesequence': 151450, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.735625397414, + 'timestamp_carla': 1274740, + 'timestamp_device': 2893296, + 'timestamp_stream': 1274.735625397414, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43196255e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-2.45972158e-04, -1.63174816e-03, 1.23888266e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011534009128808975, + 'FR_Wheel_Angle': 0.011535150930285454, + 'Location': array([240.1519928 , 167.00791931, 0.30170929]), + 'Rotation': array([-2.25259624e-02, -7.24011765e+01, -8.94165132e-03]), + 'Velocity': array([ 0.00137122, -0.00326041, -0.00013092]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5153198242188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37555, + 'frame_number': 37555, + 'framesequence': 151455, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.7736719995737, + 'timestamp_carla': 1274778, + 'timestamp_device': 2893338, + 'timestamp_stream': 1274.7736719995737, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43237382e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 1.78223054e-04, -1.58192159e-03, 1.25468111e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011532817967236042, + 'FR_Wheel_Angle': 0.011533941142261028, + 'Location': array([240.1525116 , 167.00645447, 0.30170816]), + 'Rotation': array([-2.23688688e-02, -7.24013824e+01, -8.91113188e-03]), + 'Velocity': array([ 0.00306533, -0.00876844, -0.00022208]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5189208984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37556, + 'frame_number': 37556, + 'framesequence': 151459, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.8125980980694, + 'timestamp_carla': 1274817, + 'timestamp_device': 2893371, + 'timestamp_stream': 1274.8125980980694, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43266067e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 6.03346853e-04, -1.40064606e-03, 1.31475925e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011531622149050236, + 'FR_Wheel_Angle': 0.011532757431268692, + 'Location': array([240.15339661, 167.00375366, 0.30169266]), + 'Rotation': array([-2.23073959e-02, -7.24017487e+01, -8.88061337e-03]), + 'Velocity': array([ 0.00478805, -0.01420977, -0.00042838]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5107421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.2421875 , 29.99996948]), + 'frame': 37557, + 'frame_number': 37557, + 'framesequence': 151463, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.8423193991184, + 'timestamp_carla': 1274847, + 'timestamp_device': 2893404, + 'timestamp_stream': 1274.8423193991184, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43281624e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 8.46743409e-04, -1.01073249e-03, 1.27217817e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011530004441738129, + 'FR_Wheel_Angle': 0.011531122028827667, + 'Location': array([240.15466309, 167.00007629, 0.30169517]), + 'Rotation': array([-2.22186036e-02, -7.24078293e+01, -8.91113468e-03]), + 'Velocity': array([ 6.87488914e-03, -2.08251923e-02, -9.34410054e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5049438476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86523438, 16591.24804688, 30. ]), + 'frame': 37558, + 'frame_number': 37558, + 'framesequence': 151466, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.8724055998027, + 'timestamp_carla': 1274877, + 'timestamp_device': 2893429, + 'timestamp_stream': 1274.8724055998027, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43219903e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 3.95712705e-04, -1.06017687e-03, 1.20690203e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.011528880335390568, + 'FR_Wheel_Angle': 0.011529998853802681, + 'Location': array([240.15632629, 166.99456787, 0.30171219]), + 'Rotation': array([-2.22186036e-02, -7.24074554e+01, -8.88061710e-03]), + 'Velocity': array([ 8.45076051e-03, -2.61966120e-02, 5.01489631e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5018920898438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86523438, 16591.25 , 30. ]), + 'frame': 37559, + 'frame_number': 37559, + 'framesequence': 151470, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.8995704986155, + 'timestamp_carla': 1274904, + 'timestamp_device': 2893463, + 'timestamp_stream': 1274.8995704986155, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43223494e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 1.59329556e-05, -1.07403577e-03, 1.22956800e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0115275327116251, + 'FR_Wheel_Angle': 0.011528619565069675, + 'Location': array([240.1585083 , 166.98773193, 0.30170211]), + 'Rotation': array([-2.22186036e-02, -7.24073639e+01, -8.88061523e-03]), + 'Velocity': array([ 1.02964491e-02, -3.21280956e-02, 5.58662396e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51416015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24023438, 30. ]), + 'frame': 37560, + 'frame_number': 37560, + 'framesequence': 151473, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.930031400174, + 'timestamp_carla': 1274934, + 'timestamp_device': 2893488, + 'timestamp_stream': 1274.930031400174, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43185720e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 2.34048188e-04, -4.00182209e-04, 1.24833655e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.5011268854141235, + 'FR_Wheel_Angle': -2.3983094692230225, + 'Location': array([240.16116333, 166.97935486, 0.30169386]), + 'Rotation': array([-2.22186036e-02, -7.24077301e+01, -8.85009859e-03]), + 'Velocity': array([ 1.19606471e-02, -3.82495895e-02, 4.42123419e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5134887695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24023438, 30. ]), + 'frame': 37561, + 'frame_number': 37561, + 'framesequence': 151477, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.9609554968774, + 'timestamp_carla': 1274965, + 'timestamp_device': 2893521, + 'timestamp_stream': 1274.9609554968774, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43166572e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([4.20676486e-04, 5.48809359e-04, 1.08072197e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.003713607788086, + 'FR_Wheel_Angle': -9.196328163146973, + 'Location': array([240.16381836, 166.96975708, 0.30171043]), + 'Rotation': array([-2.22800765e-02, -7.24219284e+01, -8.48388858e-03]), + 'Velocity': array([ 1.02158748e-02, -4.33805175e-02, 9.38796948e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5209350585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00006104]), + 'frame': 37562, + 'frame_number': 37562, + 'framesequence': 151481, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1274.9952276982367, + 'timestamp_carla': 1275000, + 'timestamp_device': 2893554, + 'timestamp_stream': 1274.9952276982367, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43180534e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-1.94422231e-04, 2.35064910e-03, 1.00380087e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.86518669128418, + 'FR_Wheel_Angle': -15.454400062561035, + 'Location': array([240.16595459, 166.95962524, 0.30169648]), + 'Rotation': array([-2.24303398e-02, -7.24619675e+01, -8.36181734e-03]), + 'Velocity': array([ 6.67177653e-03, -4.40535210e-02, -9.14001430e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5248413085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.87109375, 16591.23046875, 30. ]), + 'frame': 37563, + 'frame_number': 37563, + 'framesequence': 151485, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.0284669995308, + 'timestamp_carla': 1275033, + 'timestamp_device': 2893588, + 'timestamp_stream': 1275.0284669995308, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43181682e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.00184577, 0.00597474, 0.79303122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.824159622192383, + 'FR_Wheel_Angle': -20.98238182067871, + 'Location': array([240.16751099, 166.94943237, 0.30170387]), + 'Rotation': array([-2.24303398e-02, -7.25258331e+01, -8.33130069e-03]), + 'Velocity': array([ 0.00289368, -0.0442786 , 0.00030036]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5220336914062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37564, + 'frame_number': 37564, + 'framesequence': 151489, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.061930399388, + 'timestamp_carla': 1275066, + 'timestamp_device': 2893621, + 'timestamp_stream': 1275.061930399388, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43184960e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.00541897, 0.01100178, 0.56594253]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.77577590942383, + 'FR_Wheel_Angle': -26.07638931274414, + 'Location': array([240.16856384, 166.93786621, 0.30170575]), + 'Rotation': array([-2.22459249e-02, -7.26290359e+01, -8.11767485e-03]), + 'Velocity': array([-0.00124684, -0.04837473, 0.00061827]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5217895507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37565, + 'frame_number': 37565, + 'framesequence': 151493, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.0956550985575, + 'timestamp_carla': 1275100, + 'timestamp_device': 2893654, + 'timestamp_stream': 1275.0956550985575, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43189535e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.00203833, 0.01331531, 0.49601215]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.65179443359375, + 'FR_Wheel_Angle': -28.669113159179688, + 'Location': array([240.16882324, 166.92851257, 0.30171233]), + 'Rotation': array([-2.23415475e-02, -7.27338486e+01, -8.23974609e-03]), + 'Velocity': array([-0.00475329, -0.04665055, -0.00012218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5211791992188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37566, + 'frame_number': 37566, + 'framesequence': 151497, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.129192598164, + 'timestamp_carla': 1275133, + 'timestamp_device': 2893688, + 'timestamp_stream': 1275.129192598164, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43191293e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.00286257, 0.01371987, 0.51961011]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.00004959106445, + 'FR_Wheel_Angle': -28.552379608154297, + 'Location': array([240.16897583, 166.91770935, 0.30170351]), + 'Rotation': array([-2.23415475e-02, -7.28592377e+01, -8.66699219e-03]), + 'Velocity': array([-4.35671350e-03, -4.63861376e-02, -3.83663173e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5202026367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37567, + 'frame_number': 37567, + 'framesequence': 151501, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.1616556979716, + 'timestamp_carla': 1275166, + 'timestamp_device': 2893721, + 'timestamp_stream': 1275.1616556979716, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43184960e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.0515344 , 0.0188907 , -0.22549218]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.62916946411133, + 'FR_Wheel_Angle': -26.508190155029297, + 'Location': array([240.16918945, 166.90576172, 0.30169913]), + 'Rotation': array([-2.11462639e-02, -7.29970016e+01, -7.35473493e-03]), + 'Velocity': array([-0.00167785, -0.09254692, -0.00015308]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5198364257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37568, + 'frame_number': 37568, + 'framesequence': 151505, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.1934200972319, + 'timestamp_carla': 1275198, + 'timestamp_device': 2893754, + 'timestamp_stream': 1275.1934200972319, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43177181e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.0159868 , 0.08055443, -1.46731865]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.876346588134766, + 'FR_Wheel_Angle': -26.1634578704834, + 'Location': array([240.17007446, 166.883255 , 0.3017022 ]), + 'Rotation': array([-2.11735852e-02, -7.32497406e+01, -7.50732375e-03]), + 'Velocity': array([-0.0123665 , -0.10013738, 0.00032856]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5211791992188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37569, + 'frame_number': 37569, + 'framesequence': 151509, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.2270553000271, + 'timestamp_carla': 1275231, + 'timestamp_device': 2893788, + 'timestamp_stream': 1275.2270553000271, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43186867e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02386987, 0.01867052, -0.26051822]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.540958404541016, + 'FR_Wheel_Angle': -25.904985427856445, + 'Location': array([240.1706543 , 166.86329651, 0.30171406]), + 'Rotation': array([-2.24303398e-02, -7.34566193e+01, -8.88061523e-03]), + 'Velocity': array([-0.00756653, -0.0715212 , 0.00029325]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.522705078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.87109375, 16591.23242188, 30.00003052]), + 'frame': 37570, + 'frame_number': 37570, + 'framesequence': 151513, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.2627290003002, + 'timestamp_carla': 1275267, + 'timestamp_device': 2893821, + 'timestamp_stream': 1275.2627290003002, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43209606e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.11947065, 0.10172001, -2.5064249 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.53976821899414, + 'FR_Wheel_Angle': -25.675369262695312, + 'Location': array([240.17173767, 166.83789062, 0.30168265]), + 'Rotation': array([-1.90084148e-02, -7.37315292e+01, -5.34057617e-03]), + 'Velocity': array([-4.43281187e-03, -2.00625926e-01, -4.75692723e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208129882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37571, + 'frame_number': 37571, + 'framesequence': 151517, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.2955546975136, + 'timestamp_carla': 1275300, + 'timestamp_device': 2893854, + 'timestamp_stream': 1275.2955546975136, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43199608e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02129882, 0.06545867, -2.23153496]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.199987411499023, + 'FR_Wheel_Angle': -22.588592529296875, + 'Location': array([240.17314148, 166.79981995, 0.30169654]), + 'Rotation': array([-1.96163021e-02, -7.41209793e+01, -6.92748930e-03]), + 'Velocity': array([-0.00647002, -0.19547094, 0.00024258]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5161743164062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37572, + 'frame_number': 37572, + 'framesequence': 151521, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.3274243995547, + 'timestamp_carla': 1275332, + 'timestamp_device': 2893888, + 'timestamp_stream': 1275.3274243995547, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43187255e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.07986022, 0.05941921, -2.57344055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.187084197998047, + 'FR_Wheel_Angle': -23.007078170776367, + 'Location': array([240.17581177, 166.75001526, 0.3016946 ]), + 'Rotation': array([-1.95616614e-02, -7.45749054e+01, -6.50024414e-03]), + 'Velocity': array([-1.17452750e-04, -2.73740023e-01, 4.70194820e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5182495117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37573, + 'frame_number': 37573, + 'framesequence': 151525, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.3602486997843, + 'timestamp_carla': 1275365, + 'timestamp_device': 2893921, + 'timestamp_stream': 1275.3602486997843, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43187255e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02370917, -0.01730947, -2.56239462]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.180259704589844, + 'FR_Wheel_Angle': -23.129222869873047, + 'Location': array([240.17826843, 166.68881226, 0.30168307]), + 'Rotation': array([-1.91655103e-02, -7.51561737e+01, -5.64575242e-03]), + 'Velocity': array([-5.37883257e-03, -2.88294643e-01, 7.02857960e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206298828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37574, + 'frame_number': 37574, + 'framesequence': 151529, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.3971224986017, + 'timestamp_carla': 1275401, + 'timestamp_device': 2893954, + 'timestamp_stream': 1275.3971224986017, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43221200e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.061241 , 0.0237389 , -2.96818447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.717039108276367, + 'FR_Wheel_Angle': -20.791044235229492, + 'Location': array([240.1809845 , 166.60658264, 0.30169448]), + 'Rotation': array([-1.95889808e-02, -7.58876724e+01, -6.31713821e-03]), + 'Velocity': array([-3.26751941e-03, -3.69800687e-01, -8.58306862e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206298828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37575, + 'frame_number': 37575, + 'framesequence': 151533, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.427660498768, + 'timestamp_carla': 1275432, + 'timestamp_device': 2893988, + 'timestamp_stream': 1275.427660498768, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192142e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.06275734, 0.04219506, -3.34436131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.53059196472168, + 'FR_Wheel_Angle': -20.669654846191406, + 'Location': array([240.18431091, 166.53633118, 0.301698 ]), + 'Rotation': array([-1.95889808e-02, -7.64297333e+01, -7.08007859e-03]), + 'Velocity': array([ 1.26615458e-03, -4.06531543e-01, 2.50201207e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.513916015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24023438, 30. ]), + 'frame': 37576, + 'frame_number': 37576, + 'framesequence': 151537, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.4609397985041, + 'timestamp_carla': 1275465, + 'timestamp_device': 2894021, + 'timestamp_stream': 1275.4609397985041, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192142e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-1.66908407e-03, 1.30485622e-02, -3.29777384e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.08550453186035, + 'FR_Wheel_Angle': -20.38386344909668, + 'Location': array([240.18766785, 166.44700623, 0.30169541]), + 'Rotation': array([-2.06340011e-02, -7.71351089e+01, -6.98852679e-03]), + 'Velocity': array([-6.10145275e-03, -3.99894327e-01, 3.72962939e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37577, + 'frame_number': 37577, + 'framesequence': 151541, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.495633199811, + 'timestamp_carla': 1275500, + 'timestamp_device': 2894054, + 'timestamp_stream': 1275.495633199811, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43203810e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.06318972, -0.02937233, -3.45741034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.936113357543945, + 'FR_Wheel_Angle': -19.974882125854492, + 'Location': array([240.19026184, 166.34767151, 0.30167395]), + 'Rotation': array([-1.98348686e-02, -7.79130020e+01, -5.73730655e-03]), + 'Velocity': array([-1.43385027e-02, -4.24415529e-01, -2.98404688e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37578, + 'frame_number': 37578, + 'framesequence': 151545, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.5264755003154, + 'timestamp_carla': 1275531, + 'timestamp_device': 2894088, + 'timestamp_stream': 1275.5264755003154, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43183365e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.06124951, -0.02817345, -2.23346019]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -19.793691635131836, + 'FR_Wheel_Angle': -16.955249786376953, + 'Location': array([240.1932373 , 166.24093628, 0.30169111]), + 'Rotation': array([-2.05383785e-02, -7.87048645e+01, -9.03320219e-03]), + 'Velocity': array([-6.83796010e-04, -4.45309639e-01, -3.53288633e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.517333984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37579, + 'frame_number': 37579, + 'framesequence': 151549, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.5611476004124, + 'timestamp_carla': 1275565, + 'timestamp_device': 2894121, + 'timestamp_stream': 1275.5611476004124, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198997e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01063406, 0.00727165, -1.97320104]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.615123748779297, + 'FR_Wheel_Angle': -17.279130935668945, + 'Location': array([240.19708252, 166.12898254, 0.30168948]), + 'Rotation': array([-2.05725282e-02, -7.94507904e+01, -7.14111421e-03]), + 'Velocity': array([-8.33699293e-03, -4.93004173e-01, 8.64982576e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37580, + 'frame_number': 37580, + 'framesequence': 151553, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.5955596975982, + 'timestamp_carla': 1275600, + 'timestamp_device': 2894154, + 'timestamp_stream': 1275.5955596975982, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43205643e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.00783607, 0.01400512, -2.37695122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.780298233032227, + 'FR_Wheel_Angle': -17.43741798400879, + 'Location': array([240.19937134, 165.9962616 , 0.30170155]), + 'Rotation': array([-2.11462639e-02, -8.03010712e+01, -7.17163226e-03]), + 'Velocity': array([-1.49137806e-02, -5.18292308e-01, 2.06108089e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5183715820312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37581, + 'frame_number': 37581, + 'framesequence': 151557, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.6281076967716, + 'timestamp_carla': 1275632, + 'timestamp_device': 2894188, + 'timestamp_stream': 1275.6281076967716, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43195346e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.04846361, -0.06159398, -2.35556602]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.920700073242188, + 'FR_Wheel_Angle': -14.535018920898438, + 'Location': array([240.20030212, 165.87374878, 0.30169669]), + 'Rotation': array([-2.11735852e-02, -8.10607071e+01, -8.78906250e-03]), + 'Velocity': array([-6.18760148e-03, -5.15861750e-01, -3.68213659e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5170288085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37582, + 'frame_number': 37582, + 'framesequence': 151561, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.6607792973518, + 'timestamp_carla': 1275665, + 'timestamp_device': 2894221, + 'timestamp_stream': 1275.6607792973518, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43190309e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04349291, 0.04587406, -2.67242312]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.15578269958496, + 'FR_Wheel_Angle': -14.683823585510254, + 'Location': array([240.20298767, 165.75184631, 0.30170652]), + 'Rotation': array([-2.20956616e-02, -8.16755295e+01, -8.66699126e-03]), + 'Velocity': array([-9.55255795e-03, -5.43550193e-01, 5.06286626e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5191040039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37583, + 'frame_number': 37583, + 'framesequence': 151565, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.696604397148, + 'timestamp_carla': 1275701, + 'timestamp_device': 2894254, + 'timestamp_stream': 1275.696604397148, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43212587e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04353297, 0.03925659, -2.56422377]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.75047492980957, + 'FR_Wheel_Angle': -14.425179481506348, + 'Location': array([240.20462036, 165.63241577, 0.30171067]), + 'Rotation': array([-2.25259624e-02, -8.23140488e+01, -8.17871187e-03]), + 'Velocity': array([-1.38932383e-02, -5.32266021e-01, 3.20720661e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37584, + 'frame_number': 37584, + 'framesequence': 151569, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.7300879992545, + 'timestamp_carla': 1275734, + 'timestamp_device': 2894288, + 'timestamp_stream': 1275.7300879992545, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43205643e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.03437994, -0.03654926, -1.50588751]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.505290985107422, + 'FR_Wheel_Angle': -13.891525268554688, + 'Location': array([240.20469666, 165.51673889, 0.30171961]), + 'Rotation': array([-2.33114343e-02, -8.29280090e+01, -8.23974796e-03]), + 'Velocity': array([-1.53957037e-02, -4.71832424e-01, 1.84431075e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37585, + 'frame_number': 37585, + 'framesequence': 151573, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.761704698205, + 'timestamp_carla': 1275766, + 'timestamp_device': 2894321, + 'timestamp_stream': 1275.761704698205, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43188626e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03333755, 0.03127077, -1.37920403]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -11.532492637634277, + 'FR_Wheel_Angle': -10.79837703704834, + 'Location': array([240.20620728, 165.4006958 , 0.30170417]), + 'Rotation': array([-2.24303398e-02, -8.34419708e+01, -1.08947763e-02]), + 'Velocity': array([ 5.93699224e-04, -5.08333683e-01, -8.42571244e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5170288085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37586, + 'frame_number': 37586, + 'framesequence': 151577, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.7966643981636, + 'timestamp_carla': 1275801, + 'timestamp_device': 2894354, + 'timestamp_stream': 1275.7966643981636, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43203586e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03694338, 0.02792994, -1.45944655]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.25867748260498, + 'FR_Wheel_Angle': -11.033845901489258, + 'Location': array([240.20802307, 165.2877655 , 0.30169171]), + 'Rotation': array([-2.25259624e-02, -8.39080124e+01, -8.91113374e-03]), + 'Velocity': array([-6.24067197e-03, -4.97792184e-01, -1.67980194e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5203857421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37587, + 'frame_number': 37587, + 'framesequence': 151581, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.8259859979153, + 'timestamp_carla': 1275830, + 'timestamp_device': 2894388, + 'timestamp_stream': 1275.8259859979153, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43241882e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02477977, 0.02148058, -1.48100567]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.484390258789062, + 'FR_Wheel_Angle': -11.190508842468262, + 'Location': array([240.20858765, 165.17796326, 0.30171108]), + 'Rotation': array([-2.23688688e-02, -8.43439560e+01, -8.17870907e-03]), + 'Velocity': array([-1.18977018e-02, -4.85800207e-01, -8.41140718e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5174560546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37588, + 'frame_number': 37588, + 'framesequence': 151585, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.85912649706, + 'timestamp_carla': 1275863, + 'timestamp_device': 2894421, + 'timestamp_stream': 1275.85912649706, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43218234e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.01970295, -0.00508653, -0.91059381]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.260733604431152, + 'FR_Wheel_Angle': -7.576415061950684, + 'Location': array([240.2091217 , 165.06887817, 0.30170542]), + 'Rotation': array([-2.20615100e-02, -8.47546005e+01, -9.79614165e-03]), + 'Velocity': array([-8.94780562e-04, -4.81391162e-01, 8.63742825e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5098266601562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24414062, 29.99996948]), + 'frame': 37589, + 'frame_number': 37589, + 'framesequence': 151589, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.8920489996672, + 'timestamp_carla': 1275896, + 'timestamp_device': 2894454, + 'timestamp_stream': 1275.8920489996672, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43202439e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.04958493, -0.01653913, -0.81493551]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.83405590057373, + 'FR_Wheel_Angle': -7.9843010902404785, + 'Location': array([240.2117157 , 164.96237183, 0.30171522]), + 'Rotation': array([-2.30450574e-02, -8.50375061e+01, -9.12475493e-03]), + 'Velocity': array([ 5.53515158e-04, -4.23163533e-01, 7.23934136e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5145263671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24023438, 30. ]), + 'frame': 37590, + 'frame_number': 37590, + 'framesequence': 151593, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.9266605004668, + 'timestamp_carla': 1275931, + 'timestamp_device': 2894488, + 'timestamp_stream': 1275.9266605004668, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43205866e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.03386812, -0.01798137, -0.19505386]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.42619800567627, + 'FR_Wheel_Angle': -7.73516845703125, + 'Location': array([240.21359253, 164.85687256, 0.30170146]), + 'Rotation': array([-2.30450574e-02, -8.53248138e+01, -8.75854678e-03]), + 'Velocity': array([-1.60223226e-05, -4.18727905e-01, 2.15034481e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5177001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37591, + 'frame_number': 37591, + 'framesequence': 151597, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.9592278003693, + 'timestamp_carla': 1275964, + 'timestamp_device': 2894521, + 'timestamp_stream': 1275.9592278003693, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192589e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02989686, 0.01073012, -0.67387944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.063384056091309, + 'FR_Wheel_Angle': -6.878007888793945, + 'Location': array([240.21476746, 164.75511169, 0.30168724]), + 'Rotation': array([-2.27308683e-02, -8.55863571e+01, -8.75854492e-03]), + 'Velocity': array([-1.96112948e-03, -4.41376030e-01, -2.41193760e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5169677734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37592, + 'frame_number': 37592, + 'framesequence': 151601, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1275.9947641976178, + 'timestamp_carla': 1275999, + 'timestamp_device': 2894554, + 'timestamp_stream': 1275.9947641976178, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43208161e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.0370728 , 0.0164755 , -0.01309977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.3082289695739746, + 'FR_Wheel_Angle': -3.732835531234741, + 'Location': array([240.21835327, 164.65597534, 0.3017039 ]), + 'Rotation': array([-2.20615100e-02, -8.57660141e+01, -1.10473633e-02]), + 'Velocity': array([ 1.80314761e-02, -4.48417068e-01, -2.17962253e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37593, + 'frame_number': 37593, + 'framesequence': 151605, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.0301556997001, + 'timestamp_carla': 1276034, + 'timestamp_device': 2894588, + 'timestamp_stream': 1276.0301556997001, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43215328e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02624192, -0.00015875, -0.08514193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9496498107910156, + 'FR_Wheel_Angle': -3.8895440101623535, + 'Location': array([240.22227478, 164.55574036, 0.30170363]), + 'Rotation': array([-2.16721892e-02, -8.59160461e+01, -9.03320312e-03]), + 'Velocity': array([ 1.42118661e-02, -4.49868083e-01, 1.67312624e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5164794921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37594, + 'frame_number': 37594, + 'framesequence': 151609, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.0618613995612, + 'timestamp_carla': 1276066, + 'timestamp_device': 2894621, + 'timestamp_stream': 1276.0618613995612, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192142e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.00543033, -0.00796691, 0.4944047 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.175018787384033, + 'FR_Wheel_Angle': -4.027266502380371, + 'Location': array([240.22593689, 164.45544434, 0.30169296]), + 'Rotation': array([-2.23688688e-02, -8.60529709e+01, -8.69750883e-03]), + 'Velocity': array([ 1.14691211e-02, -4.20783371e-01, -1.88074104e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5150756835938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24023438, 30. ]), + 'frame': 37595, + 'frame_number': 37595, + 'framesequence': 151613, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.0965145975351, + 'timestamp_carla': 1276101, + 'timestamp_device': 2894654, + 'timestamp_stream': 1276.0965145975351, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43200144e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.00780154, -0.01253444, 1.01362681]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.5332612991333008, + 'FR_Wheel_Angle': 0.40330770611763, + 'Location': array([240.22991943, 164.36077881, 0.30171344]), + 'Rotation': array([-2.28606425e-02, -8.61525879e+01, -1.06506357e-02]), + 'Velocity': array([ 2.37969607e-02, -3.98629129e-01, -1.49345396e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37596, + 'frame_number': 37596, + 'framesequence': 151617, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.128041498363, + 'timestamp_carla': 1276132, + 'timestamp_device': 2894688, + 'timestamp_stream': 1276.128041498363, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43182606e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.0083315 , 0.01409678, -0.03377883]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.4212122857570648, + 'FR_Wheel_Angle': -0.20584005117416382, + 'Location': array([240.23513794, 164.28224182, 0.30171224]), + 'Rotation': array([-2.29221135e-02, -8.61349106e+01, -9.67407227e-03]), + 'Velocity': array([ 2.33147237e-02, -3.82161081e-01, 1.66053767e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5181274414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37597, + 'frame_number': 37597, + 'framesequence': 151621, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.1605567969382, + 'timestamp_carla': 1276165, + 'timestamp_device': 2894721, + 'timestamp_stream': 1276.1605567969382, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43179476e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02223414, -0.00466463, 0.06820557]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.06616726517677307, + 'FR_Wheel_Angle': 0.020356912165880203, + 'Location': array([240.24198914, 164.17877197, 0.3017008 ]), + 'Rotation': array([-2.18429435e-02, -8.61334229e+01, -9.33837891e-03]), + 'Velocity': array([ 2.74251439e-02, -3.81592780e-01, -8.15963722e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5216674804688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37598, + 'frame_number': 37598, + 'framesequence': 151625, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.1945642977953, + 'timestamp_carla': 1276199, + 'timestamp_device': 2894754, + 'timestamp_stream': 1276.1945642977953, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43189698e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 2.67468784e-02, 2.21143258e-04, -4.91347671e-01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.5342440009117126, + 'FR_Wheel_Angle': 1.3297723531723022, + 'Location': array([240.24829102, 164.08734131, 0.30170849]), + 'Rotation': array([-2.23073959e-02, -8.61253891e+01, -9.33837611e-03]), + 'Velocity': array([ 2.82350294e-02, -3.75787675e-01, 9.39845995e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5222778320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37599, + 'frame_number': 37599, + 'framesequence': 151629, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.2274548001587, + 'timestamp_carla': 1276232, + 'timestamp_device': 2894788, + 'timestamp_stream': 1276.2274548001587, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43187627e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.03902494, 0.00812612, -0.14790732]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.524725437164307, + 'FR_Wheel_Angle': 4.183084487915039, + 'Location': array([240.2552948, 164.0111084, 0.3017092]), + 'Rotation': array([-2.25464534e-02, -8.60437164e+01, -1.10473633e-02]), + 'Velocity': array([ 4.21562754e-02, -3.56883436e-01, 1.91483487e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5202026367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37600, + 'frame_number': 37600, + 'framesequence': 151633, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.2622328996658, + 'timestamp_carla': 1276267, + 'timestamp_device': 2894821, + 'timestamp_stream': 1276.2622328996658, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43201441e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.0451979 , 0.00497854, 0.83245122]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.176950454711914, + 'FR_Wheel_Angle': 4.221249580383301, + 'Location': array([240.26417542, 163.92233276, 0.30170229]), + 'Rotation': array([-2.19658874e-02, -8.59124756e+01, -9.55200288e-03]), + 'Velocity': array([ 4.11629900e-02, -3.58885139e-01, 2.27165219e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206298828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37601, + 'frame_number': 37601, + 'framesequence': 151637, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.2956295982003, + 'timestamp_carla': 1276300, + 'timestamp_device': 2894854, + 'timestamp_stream': 1276.2956295982003, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198386e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.05923386, 0.01435325, 0.4030914 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9706790447235107, + 'FR_Wheel_Angle': 4.153024196624756, + 'Location': array([240.27386475, 163.82969666, 0.30169982]), + 'Rotation': array([-2.17883028e-02, -8.57795715e+01, -9.15527344e-03]), + 'Velocity': array([ 4.20159772e-02, -3.65049303e-01, 1.38864518e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5178833007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37602, + 'frame_number': 37602, + 'framesequence': 151641, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.328443299979, + 'timestamp_carla': 1276333, + 'timestamp_device': 2894887, + 'timestamp_stream': 1276.328443299979, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192366e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01565038, -0.00837108, 0.10163929]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.64022970199585, + 'FR_Wheel_Angle': 9.141263961791992, + 'Location': array([240.28434753, 163.73791504, 0.3017104 ]), + 'Rotation': array([-2.23688688e-02, -8.56343307e+01, -1.04675302e-02]), + 'Velocity': array([ 5.58979698e-02, -3.81574482e-01, -2.05707547e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184326171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37603, + 'frame_number': 37603, + 'framesequence': 151645, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.3618481978774, + 'timestamp_carla': 1276366, + 'timestamp_device': 2894921, + 'timestamp_stream': 1276.3618481978774, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43193439e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.04715366, 0.0273477 , 1.18995786]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.416199207305908, + 'FR_Wheel_Angle': 8.2471284866333, + 'Location': array([240.29725647, 163.64683533, 0.30170378]), + 'Rotation': array([-2.21298113e-02, -8.53669968e+01, -9.94872954e-03]), + 'Velocity': array([ 5.83815426e-02, -3.63667667e-01, 1.53369896e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37604, + 'frame_number': 37604, + 'framesequence': 151649, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.3946943990886, + 'timestamp_carla': 1276399, + 'timestamp_device': 2894954, + 'timestamp_stream': 1276.3946943990886, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43190235e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.05494582, 0.0240731 , 0.97786683]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.666294574737549, + 'FR_Wheel_Angle': 8.352838516235352, + 'Location': array([240.31108093, 163.55360413, 0.30170539]), + 'Rotation': array([-2.20615100e-02, -8.51020508e+01, -9.46045015e-03]), + 'Velocity': array([ 6.21344931e-02, -3.68256092e-01, 1.93414686e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5194702148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37605, + 'frame_number': 37605, + 'framesequence': 151653, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.4282802976668, + 'timestamp_carla': 1276433, + 'timestamp_device': 2894987, + 'timestamp_stream': 1276.4282802976668, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43194050e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.06153439, 0.02136229, 1.07078242]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.467409133911133, + 'FR_Wheel_Angle': 10.111202239990234, + 'Location': array([240.32771301, 163.44589233, 0.30170166]), + 'Rotation': array([-2.21571326e-02, -8.47896042e+01, -9.58252046e-03]), + 'Velocity': array([ 6.71596974e-02, -3.69096667e-01, -5.47790514e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37606, + 'frame_number': 37606, + 'framesequence': 151657, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.4623987972736, + 'timestamp_carla': 1276467, + 'timestamp_device': 2895021, + 'timestamp_stream': 1276.4623987972736, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43200457e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.0539481 , 0.04955709, 1.8430897 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.390186309814453, + 'FR_Wheel_Angle': 12.268848419189453, + 'Location': array([240.34550476, 163.35166931, 0.30171207]), + 'Rotation': array([-2.23415475e-02, -8.43997116e+01, -1.08947763e-02]), + 'Velocity': array([ 8.31269622e-02, -3.67207915e-01, 3.13644414e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.519287109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37607, + 'frame_number': 37607, + 'framesequence': 151661, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.4929660968482, + 'timestamp_carla': 1276497, + 'timestamp_device': 2895054, + 'timestamp_stream': 1276.4929660968482, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43179923e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.06081146, 0.04074956, 1.46948349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.280776977539062, + 'FR_Wheel_Angle': 12.505242347717285, + 'Location': array([240.36419678, 163.2578125 , 0.30169314]), + 'Rotation': array([-2.23688688e-02, -8.40181885e+01, -9.67407320e-03]), + 'Velocity': array([ 0.08379038, -0.3613655 , -0.00036193]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51806640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37608, + 'frame_number': 37608, + 'framesequence': 151666, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.5318855978549, + 'timestamp_carla': 1276536, + 'timestamp_device': 2895096, + 'timestamp_stream': 1276.5318855978549, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43237919e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.05626469, -0.03245057, 1.89361537]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.145977020263672, + 'FR_Wheel_Angle': 12.492507934570312, + 'Location': array([240.38067627, 163.177948 , 0.30170876]), + 'Rotation': array([-2.14263014e-02, -8.36810455e+01, -9.70458891e-03]), + 'Velocity': array([ 1.02634974e-01, -4.40778494e-01, 1.35850903e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5221557617188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37609, + 'frame_number': 37609, + 'framesequence': 151669, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.563272897154, + 'timestamp_carla': 1276568, + 'timestamp_device': 2895121, + 'timestamp_stream': 1276.563272897154, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43206105e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.05500781, -0.05286538, 2.36119747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.48507022857666, + 'FR_Wheel_Angle': 17.66934585571289, + 'Location': array([240.4016571 , 163.08268738, 0.30170605]), + 'Rotation': array([-2.15765666e-02, -8.32519684e+01, -1.12304678e-02]), + 'Velocity': array([ 1.19338937e-01, -4.40900177e-01, -2.60572415e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5106201171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.2421875 , 29.99996948]), + 'frame': 37610, + 'frame_number': 37610, + 'framesequence': 151673, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.597247697413, + 'timestamp_carla': 1276601, + 'timestamp_device': 2895154, + 'timestamp_stream': 1276.597247697413, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43204644e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.05452401, -0.03479493, 2.41286612]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.231521606445312, + 'FR_Wheel_Angle': 16.6978702545166, + 'Location': array([240.42591858, 162.98815918, 0.30170366]), + 'Rotation': array([-2.17609815e-02, -8.27173004e+01, -1.01318359e-02]), + 'Velocity': array([ 1.25397921e-01, -4.36752498e-01, 6.86550120e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5169677734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37611, + 'frame_number': 37611, + 'framesequence': 151677, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.6280735991895, + 'timestamp_carla': 1276632, + 'timestamp_device': 2895187, + 'timestamp_stream': 1276.6280735991895, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43182367e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.03869043, 0.06090435, 1.50844145]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.382169723510742, + 'FR_Wheel_Angle': 16.709484100341797, + 'Location': array([240.45068359, 162.89442444, 0.30171183]), + 'Rotation': array([-2.27035470e-02, -8.21973495e+01, -9.03320312e-03]), + 'Velocity': array([ 1.08462058e-01, -3.67484540e-01, -3.69262671e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5171508789062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37612, + 'frame_number': 37612, + 'framesequence': 151681, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.6612323001027, + 'timestamp_carla': 1276666, + 'timestamp_device': 2895221, + 'timestamp_stream': 1276.6612323001027, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43185347e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.0474476 , 0.03173855, 2.46918678]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.202488899230957, + 'FR_Wheel_Angle': 18.694656372070312, + 'Location': array([240.47514343, 162.80445862, 0.30170989]), + 'Rotation': array([-2.24303398e-02, -8.17015305e+01, -9.21630953e-03]), + 'Velocity': array([ 1.12389095e-01, -3.55425507e-01, 2.05588338e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5216674804688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37613, + 'frame_number': 37613, + 'framesequence': 151685, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.6953663975, + 'timestamp_carla': 1276700, + 'timestamp_device': 2895254, + 'timestamp_stream': 1276.6953663975, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43195108e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.06848866, -0.07288322, 2.93399525]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.69257354736328, + 'FR_Wheel_Angle': 20.699644088745117, + 'Location': array([240.50498962, 162.7088623 , 0.30169663]), + 'Rotation': array([-2.16107182e-02, -8.10760727e+01, -1.16882343e-02]), + 'Velocity': array([ 1.54595733e-01, -4.14323181e-01, -3.06529982e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5211181640625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37614, + 'frame_number': 37614, + 'framesequence': 151689, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.7293849997222, + 'timestamp_carla': 1276734, + 'timestamp_device': 2895287, + 'timestamp_stream': 1276.7293849997222, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43199846e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02256056, 0.02692735, 3.15771317]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.538619995117188, + 'FR_Wheel_Angle': 20.82801055908203, + 'Location': array([240.53427124, 162.61979675, 0.30170044]), + 'Rotation': array([-2.17883028e-02, -8.04474945e+01, -9.64355562e-03]), + 'Velocity': array([ 1.40357822e-01, -3.87687266e-01, -2.31533049e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5191650390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37615, + 'frame_number': 37615, + 'framesequence': 151693, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.7608927972615, + 'timestamp_carla': 1276765, + 'timestamp_device': 2895321, + 'timestamp_stream': 1276.7608927972615, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43184960e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.05877389, -0.05740554, 2.98608971]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.45259666442871, + 'FR_Wheel_Angle': 20.851362228393555, + 'Location': array([240.56384277, 162.53308105, 0.30170867]), + 'Rotation': array([-2.14536227e-02, -7.98456268e+01, -1.02539072e-02]), + 'Velocity': array([ 1.60710275e-01, -4.11740780e-01, 2.84605019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5181274414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37616, + 'frame_number': 37616, + 'framesequence': 151697, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.793482400477, + 'timestamp_carla': 1276798, + 'timestamp_device': 2895354, + 'timestamp_stream': 1276.793482400477, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43183902e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04421807, -0.07334107, 3.53920865]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.55731201171875, + 'FR_Wheel_Angle': 26.063453674316406, + 'Location': array([240.59648132, 162.44432068, 0.30170548]), + 'Rotation': array([-2.15765666e-02, -7.91631317e+01, -1.20544434e-02]), + 'Velocity': array([ 1.81469247e-01, -4.03826237e-01, 1.20449067e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5211791992188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37617, + 'frame_number': 37617, + 'framesequence': 151701, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.8280775994062, + 'timestamp_carla': 1276832, + 'timestamp_device': 2895387, + 'timestamp_stream': 1276.8280775994062, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43199071e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04755594, -0.06541328, 3.36410689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.22418975830078, + 'FR_Wheel_Angle': 25.074024200439453, + 'Location': array([240.63198853, 162.35772705, 0.30170411]), + 'Rotation': array([-2.17883028e-02, -7.84303360e+01, -1.02539072e-02]), + 'Velocity': array([ 1.84007779e-01, -3.97939980e-01, 3.80134588e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213623046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37618, + 'frame_number': 37618, + 'framesequence': 151705, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.8628039993346, + 'timestamp_carla': 1276867, + 'timestamp_device': 2895421, + 'timestamp_stream': 1276.8628039993346, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43208534e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04184669, -0.06963273, 3.26514769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.3515567779541, + 'FR_Wheel_Angle': 25.07896614074707, + 'Location': array([240.66743469, 162.2727356 , 0.30170935]), + 'Rotation': array([-2.20615100e-02, -7.77182083e+01, -9.61303618e-03]), + 'Velocity': array([ 1.83779031e-01, -3.85071903e-01, 1.03454586e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5183715820312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37619, + 'frame_number': 37619, + 'framesequence': 151709, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.8978966996074, + 'timestamp_carla': 1276902, + 'timestamp_device': 2895454, + 'timestamp_stream': 1276.8978966996074, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43216327e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04551902, -0.07551865, 3.64985514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.20709991455078, + 'FR_Wheel_Angle': 27.36177635192871, + 'Location': array([240.70402527, 162.18890381, 0.30169821]), + 'Rotation': array([-2.13033594e-02, -7.69869156e+01, -1.08337412e-02]), + 'Velocity': array([ 1.98356166e-01, -3.91050756e-01, -2.45208736e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5164794921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37620, + 'frame_number': 37620, + 'framesequence': 151713, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.9317314997315, + 'timestamp_carla': 1276936, + 'timestamp_device': 2895487, + 'timestamp_stream': 1276.9317314997315, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43209994e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04594773, -0.05838108, 3.9961791 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.12564468383789, + 'FR_Wheel_Angle': 28.787742614746094, + 'Location': array([240.74472046, 162.10566711, 0.30170363]), + 'Rotation': array([-2.16107182e-02, -7.61349564e+01, -1.14440918e-02]), + 'Velocity': array([ 2.14368001e-01, -3.79678398e-01, 1.54647831e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5148315429688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24023438, 30.00006104]), + 'frame': 37621, + 'frame_number': 37621, + 'framesequence': 151718, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.9663148969412, + 'timestamp_carla': 1276971, + 'timestamp_device': 2895529, + 'timestamp_stream': 1276.9663148969412, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43211663e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03705062, -0.05898388, 3.78322244]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.126508712768555, + 'FR_Wheel_Angle': 29.136165618896484, + 'Location': array([240.78575134, 162.02461243, 0.30171484]), + 'Rotation': array([-2.23688688e-02, -7.52954559e+01, -9.27734282e-03]), + 'Velocity': array([ 2.06300959e-01, -3.58783036e-01, 3.52845178e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5161743164062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37622, + 'frame_number': 37622, + 'framesequence': 151721, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1276.9971238970757, + 'timestamp_carla': 1277001, + 'timestamp_device': 2895554, + 'timestamp_stream': 1276.9971238970757, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43186331e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.0390004 , -0.07049968, 3.85687304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.102327346801758, + 'FR_Wheel_Angle': 29.201833724975586, + 'Location': array([240.82843018, 161.94381714, 0.30170229]), + 'Rotation': array([-2.12692078e-02, -7.44602737e+01, -1.04064941e-02]), + 'Velocity': array([ 2.24798992e-01, -3.72713268e-01, -9.88388056e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5157470703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37623, + 'frame_number': 37623, + 'framesequence': 151725, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.029682599008, + 'timestamp_carla': 1277034, + 'timestamp_device': 2895587, + 'timestamp_stream': 1277.029682599008, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43182978e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03072189, -0.08669438, 4.51741743]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.252323150634766, + 'FR_Wheel_Angle': 34.450401306152344, + 'Location': array([240.87260437, 161.86557007, 0.30170378]), + 'Rotation': array([-2.21298113e-02, -7.35905304e+01, -1.16577148e-02]), + 'Velocity': array([ 2.35489309e-01, -3.46390992e-01, -1.61285396e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208740234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37624, + 'frame_number': 37624, + 'framesequence': 151729, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.06460679695, + 'timestamp_carla': 1277069, + 'timestamp_device': 2895621, + 'timestamp_stream': 1277.06460679695, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43199846e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03888743, -0.08238345, 4.32136917]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.69935417175293, + 'FR_Wheel_Angle': 33.515472412109375, + 'Location': array([240.91296387, 161.79989624, 0.30169171]), + 'Rotation': array([-2.16995105e-02, -7.27827835e+01, -1.05590830e-02]), + 'Velocity': array([ 2.42730454e-01, -3.49673182e-01, -3.14130768e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37625, + 'frame_number': 37625, + 'framesequence': 151734, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.0989753976464, + 'timestamp_carla': 1277103, + 'timestamp_device': 2895662, + 'timestamp_stream': 1277.0989753976464, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43204883e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04040467, 0.03027342, 4.52258348]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.78523063659668, + 'FR_Wheel_Angle': 33.421199798583984, + 'Location': array([240.95913696, 161.72589111, 0.30170277]), + 'Rotation': array([-2.16721892e-02, -7.18671799e+01, -9.70458891e-03]), + 'Velocity': array([ 2.26595968e-01, -3.29895288e-01, -1.29776003e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5181274414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37626, + 'frame_number': 37626, + 'framesequence': 151737, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.1290620975196, + 'timestamp_carla': 1277133, + 'timestamp_device': 2895687, + 'timestamp_stream': 1277.1290620975196, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43179014e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03171263, -0.09204902, 4.49586058]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.747018814086914, + 'FR_Wheel_Angle': 35.95296096801758, + 'Location': array([241.00582886, 161.65374756, 0.30170783]), + 'Rotation': array([-2.15150956e-02, -7.09592209e+01, -1.04064951e-02]), + 'Velocity': array([ 2.47819424e-01, -3.30860436e-01, 2.07233425e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5171508789062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37627, + 'frame_number': 37627, + 'framesequence': 151741, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.1641966998577, + 'timestamp_carla': 1277168, + 'timestamp_device': 2895721, + 'timestamp_stream': 1277.1641966998577, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43199921e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.0275571 , -0.07639303, 4.92319393]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.269699096679688, + 'FR_Wheel_Angle': 37.06035232543945, + 'Location': array([241.05754089, 161.58175659, 0.30170417]), + 'Rotation': array([-2.13921517e-02, -6.99093628e+01, -1.19934101e-02]), + 'Velocity': array([ 2.70878315e-01, -3.21175307e-01, 9.66739608e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5223388671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37628, + 'frame_number': 37628, + 'framesequence': 151745, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.1955218985677, + 'timestamp_carla': 1277200, + 'timestamp_device': 2895754, + 'timestamp_stream': 1277.1955218985677, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43183902e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03036486, -0.09611312, 4.94971085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.346399307250977, + 'FR_Wheel_Angle': 37.45341491699219, + 'Location': array([241.10940552, 161.51300049, 0.30170673]), + 'Rotation': array([-2.14877743e-02, -6.88948135e+01, -1.09863281e-02]), + 'Velocity': array([ 2.76676089e-01, -3.16715151e-01, -7.53402674e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5181274414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37629, + 'frame_number': 37629, + 'framesequence': 151749, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.229344200343, + 'timestamp_carla': 1277234, + 'timestamp_device': 2895787, + 'timestamp_stream': 1277.229344200343, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192515e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.03375171, 0.04090175, 4.66057491]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.32595443725586, + 'FR_Wheel_Angle': 37.622257232666016, + 'Location': array([241.1630249 , 161.44389343, 0.3017039 ]), + 'Rotation': array([-2.16107182e-02, -6.78787003e+01, -9.21630859e-03]), + 'Velocity': array([ 2.52659380e-01, -2.96974421e-01, 1.03635786e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213623046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37630, + 'frame_number': 37630, + 'framesequence': 151753, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.2607987001538, + 'timestamp_carla': 1277265, + 'timestamp_device': 2895821, + 'timestamp_stream': 1277.2607987001538, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43180996e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.01833228, -0.09906486, 5.31142616]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.84476661682129, + 'FR_Wheel_Angle': 41.76449966430664, + 'Location': array([241.22489929, 161.36920166, 0.30171156]), + 'Rotation': array([-2.20615100e-02, -6.66837921e+01, -1.16882343e-02]), + 'Velocity': array([ 2.86038935e-01, -2.83642888e-01, -3.66592394e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37631, + 'frame_number': 37631, + 'framesequence': 151757, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.2945868968964, + 'timestamp_carla': 1277299, + 'timestamp_device': 2895854, + 'timestamp_stream': 1277.2945868968964, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43191442e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01659282, -0.08976944, 5.63112783]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.842140197753906, + 'FR_Wheel_Angle': 41.758201599121094, + 'Location': array([241.28071594, 161.30741882, 0.30170432]), + 'Rotation': array([-2.22459249e-02, -6.55843735e+01, -1.04675302e-02]), + 'Velocity': array([ 2.78838605e-01, -2.52214074e-01, -1.82781208e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52197265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37632, + 'frame_number': 37632, + 'framesequence': 151761, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.3261811994016, + 'timestamp_carla': 1277330, + 'timestamp_device': 2895887, + 'timestamp_stream': 1277.3261811994016, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43181995e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01778606, -0.09303488, 5.7299366 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.84859275817871, + 'FR_Wheel_Angle': 41.754310607910156, + 'Location': array([241.32876587, 161.25613403, 0.30170271]), + 'Rotation': array([-2.18770951e-02, -6.46637650e+01, -1.01623526e-02]), + 'Velocity': array([ 2.82519728e-01, -2.49251992e-01, -2.70233140e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5198364257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37633, + 'frame_number': 37633, + 'framesequence': 151765, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.3612863980234, + 'timestamp_carla': 1277366, + 'timestamp_device': 2895921, + 'timestamp_stream': 1277.3612863980234, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43203497e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.01464613, 0.07756532, 4.91066027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82733917236328, + 'FR_Wheel_Angle': 41.73609924316406, + 'Location': array([241.39337158, 161.18972778, 0.3017087 ]), + 'Rotation': array([-2.16995105e-02, -6.34531364e+01, -9.30786133e-03]), + 'Velocity': array([ 2.57017910e-01, -2.31606901e-01, -2.76756273e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5217895507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37634, + 'frame_number': 37634, + 'framesequence': 151769, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.3955119997263, + 'timestamp_carla': 1277400, + 'timestamp_device': 2895954, + 'timestamp_stream': 1277.3955119997263, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43208012e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.02759679, 0.0558277 , 3.77214503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82337188720703, + 'FR_Wheel_Angle': 41.73012161254883, + 'Location': array([241.45124817, 161.13235474, 0.30171353]), + 'Rotation': array([-2.21571326e-02, -6.23928337e+01, -9.94872954e-03]), + 'Velocity': array([ 2.56352246e-01, -2.04445511e-01, -3.39794169e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5174560546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37635, + 'frame_number': 37635, + 'framesequence': 151773, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.4288065992296, + 'timestamp_carla': 1277433, + 'timestamp_device': 2895987, + 'timestamp_stream': 1277.4288065992296, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43202975e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.02002805, 0.08493715, 3.75165963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82332420349121, + 'FR_Wheel_Angle': 41.74681091308594, + 'Location': array([241.50968933, 161.076828 , 0.30170631]), + 'Rotation': array([-2.21912842e-02, -6.13254662e+01, -9.52148344e-03]), + 'Velocity': array([ 2.52789259e-01, -1.95896283e-01, -1.66587823e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5164794921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37636, + 'frame_number': 37636, + 'framesequence': 151777, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.4637520983815, + 'timestamp_carla': 1277468, + 'timestamp_device': 2896021, + 'timestamp_stream': 1277.4637520983815, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43212423e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02135365, -0.10230618, 4.45364809]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.839534759521484, + 'FR_Wheel_Angle': 41.75324630737305, + 'Location': array([241.5605011 , 161.03005981, 0.30169916]), + 'Rotation': array([-2.15492453e-02, -6.04232101e+01, -1.01623544e-02]), + 'Velocity': array([ 2.98055202e-01, -2.28903860e-01, -5.61618799e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.517578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37637, + 'frame_number': 37637, + 'framesequence': 151781, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.4934713989496, + 'timestamp_carla': 1277498, + 'timestamp_device': 2896054, + 'timestamp_stream': 1277.4934713989496, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43252403e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-4.12514480e-03, -1.04555264e-01, 5.02428341e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.851593017578125, + 'FR_Wheel_Angle': 41.77650451660156, + 'Location': array([241.62049866, 160.97691345, 0.30170593]), + 'Rotation': array([-2.17883028e-02, -5.93762665e+01, -9.88769438e-03]), + 'Velocity': array([ 3.05431008e-01, -2.31748044e-01, 6.14547680e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00006104]), + 'frame': 37638, + 'frame_number': 37638, + 'framesequence': 151785, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.5271865986288, + 'timestamp_carla': 1277531, + 'timestamp_device': 2896087, + 'timestamp_stream': 1277.5271865986288, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43228292e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02114798, -0.01379503, 3.72465396]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.85761833190918, + 'FR_Wheel_Angle': 41.77821731567383, + 'Location': array([241.68118286, 160.9254303 , 0.30170357]), + 'Rotation': array([-2.20341887e-02, -5.83366203e+01, -9.06372257e-03]), + 'Velocity': array([ 2.86854029e-01, -2.13529170e-01, -9.41562612e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5077514648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.24609375, 30. ]), + 'frame': 37639, + 'frame_number': 37639, + 'framesequence': 151789, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.5592525973916, + 'timestamp_carla': 1277564, + 'timestamp_device': 2896121, + 'timestamp_stream': 1277.5592525973916, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43202201e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 5.26369782e-04, -1.04203977e-01, 4.93189573e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.85407257080078, + 'FR_Wheel_Angle': 41.78314208984375, + 'Location': array([241.74302673, 160.87440491, 0.30169222]), + 'Rotation': array([-2.15492453e-02, -5.72959137e+01, -1.02233896e-02]), + 'Velocity': array([ 3.13857466e-01, -2.20260203e-01, -3.05824273e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5125732421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8671875 , 16591.2421875 , 29.99996948]), + 'frame': 37640, + 'frame_number': 37640, + 'framesequence': 151793, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.5938443988562, + 'timestamp_carla': 1277598, + 'timestamp_device': 2896154, + 'timestamp_stream': 1277.5938443988562, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43205106e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.06186214, 0.0410783 , 4.58870697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.847274780273438, + 'FR_Wheel_Angle': 41.78468704223633, + 'Location': array([241.80511475, 160.82571411, 0.30170393]), + 'Rotation': array([-2.15492453e-02, -5.62720718e+01, -9.42992978e-03]), + 'Velocity': array([ 2.93141097e-01, -2.12751016e-01, 9.05704510e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5177001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37641, + 'frame_number': 37641, + 'framesequence': 151797, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.6265818998218, + 'timestamp_carla': 1277631, + 'timestamp_device': 2896187, + 'timestamp_stream': 1277.6265818998218, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192977e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02512465, -0.0888031 , 5.05976439]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.852256774902344, + 'FR_Wheel_Angle': 41.79701614379883, + 'Location': array([241.866745 , 160.77908325, 0.30171087]), + 'Rotation': array([-2.23415475e-02, -5.52853851e+01, -9.03320312e-03]), + 'Velocity': array([ 2.96540231e-01, -1.87509283e-01, 1.26171115e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5171508789062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30. ]), + 'frame': 37642, + 'frame_number': 37642, + 'framesequence': 151801, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.65889229998, + 'timestamp_carla': 1277663, + 'timestamp_device': 2896221, + 'timestamp_stream': 1277.65889229998, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43183365e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.00983132, -0.10606496, 4.62483549]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.86339569091797, + 'FR_Wheel_Angle': 41.79798126220703, + 'Location': array([241.93597412, 160.72801208, 0.30170241]), + 'Rotation': array([-2.17609815e-02, -5.41721153e+01, -9.67407320e-03]), + 'Velocity': array([ 3.07734907e-01, -1.91713303e-01, -1.37243274e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37643, + 'frame_number': 37643, + 'framesequence': 151805, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.692946497351, + 'timestamp_carla': 1277697, + 'timestamp_device': 2896254, + 'timestamp_stream': 1277.692946497351, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43191293e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.0068281 , -0.1112835 , 4.79423523]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.86048698425293, + 'FR_Wheel_Angle': 41.79500961303711, + 'Location': array([241.99627686, 160.68585205, 0.30171189]), + 'Rotation': array([-2.14263014e-02, -5.32213821e+01, -1.00708008e-02]), + 'Velocity': array([ 3.13702166e-01, -1.88043267e-01, 1.57904622e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37644, + 'frame_number': 37644, + 'framesequence': 151809, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.7258311994374, + 'timestamp_carla': 1277730, + 'timestamp_device': 2896287, + 'timestamp_stream': 1277.7258311994374, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43187553e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.00885877, -0.1049557 , 4.85957623]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.859704971313477, + 'FR_Wheel_Angle': 41.78800582885742, + 'Location': array([242.05924988, 160.64292908, 0.30169746]), + 'Rotation': array([-2.11462639e-02, -5.22002754e+01, -1.03454590e-02]), + 'Velocity': array([ 3.21862608e-01, -1.85834706e-01, -8.53443125e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5198364257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37645, + 'frame_number': 37645, + 'framesequence': 151813, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.7602146975696, + 'timestamp_carla': 1277764, + 'timestamp_device': 2896321, + 'timestamp_stream': 1277.7602146975696, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43197253e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.00813272, -0.09883415, 4.67136526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.86326026916504, + 'FR_Wheel_Angle': 41.79072952270508, + 'Location': array([242.12399292, 160.60098267, 0.30169559]), + 'Rotation': array([-2.16995105e-02, -5.11995773e+01, -9.79614258e-03]), + 'Velocity': array([ 3.19488108e-01, -1.75893307e-01, -1.56202310e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206298828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37646, + 'frame_number': 37646, + 'framesequence': 151817, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.792559299618, + 'timestamp_carla': 1277797, + 'timestamp_device': 2896354, + 'timestamp_stream': 1277.792559299618, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43187940e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01006077, -0.10181577, 4.57241869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.861614227294922, + 'FR_Wheel_Angle': 41.80107498168945, + 'Location': array([242.17814636, 160.567276 , 0.30170426]), + 'Rotation': array([-2.16995105e-02, -5.03797150e+01, -9.64355562e-03]), + 'Velocity': array([ 3.18381131e-01, -1.69006139e-01, 1.20086668e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5186767578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37647, + 'frame_number': 37647, + 'framesequence': 151821, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.8269388973713, + 'timestamp_carla': 1277831, + 'timestamp_device': 2896387, + 'timestamp_stream': 1277.8269388973713, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198088e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01388458, -0.10865884, 4.89887953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.860366821289062, + 'FR_Wheel_Angle': 41.79285430908203, + 'Location': array([242.24226379, 160.52824402, 0.3017005 ]), + 'Rotation': array([-2.09960006e-02, -4.93844910e+01, -1.04370108e-02]), + 'Velocity': array([ 3.33106697e-01, -1.71157494e-01, -1.36642455e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205688476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37648, + 'frame_number': 37648, + 'framesequence': 151825, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.8605445995927, + 'timestamp_carla': 1277865, + 'timestamp_device': 2896420, + 'timestamp_stream': 1277.8605445995927, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198088e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01695097, -0.0997238 , 4.64503527]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.862897872924805, + 'FR_Wheel_Angle': 41.79547882080078, + 'Location': array([242.30775452, 160.49015808, 0.30170617]), + 'Rotation': array([-2.14877743e-02, -4.84083672e+01, -9.85717867e-03]), + 'Velocity': array([ 3.28096807e-01, -1.60791934e-01, -6.95037816e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5185546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37649, + 'frame_number': 37649, + 'framesequence': 151829, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.8924000002444, + 'timestamp_carla': 1277897, + 'timestamp_device': 2896454, + 'timestamp_stream': 1277.8924000002444, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43185809e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.0209432 , -0.1235563 , 4.69228315]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.862754821777344, + 'FR_Wheel_Angle': 41.79530715942383, + 'Location': array([242.37083435, 160.45465088, 0.30169585]), + 'Rotation': array([-2.20341887e-02, -4.74763603e+01, -9.27734282e-03]), + 'Velocity': array([ 0.31765217, -0.15028459, -0.0003583 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5185546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37650, + 'frame_number': 37650, + 'framesequence': 151833, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.9264355003834, + 'timestamp_carla': 1277931, + 'timestamp_device': 2896487, + 'timestamp_stream': 1277.9264355003834, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43194735e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.04342668, -0.07404102, 5.08750534]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.859561920166016, + 'FR_Wheel_Angle': 41.76447677612305, + 'Location': array([242.43302917, 160.42071533, 0.30171028]), + 'Rotation': array([-2.20615100e-02, -4.65326538e+01, -9.09423828e-03]), + 'Velocity': array([ 2.96413422e-01, -1.27368182e-01, 1.47695537e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5209350585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00006104]), + 'frame': 37651, + 'frame_number': 37651, + 'framesequence': 151837, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.9589258991182, + 'timestamp_carla': 1277963, + 'timestamp_device': 2896520, + 'timestamp_stream': 1277.9589258991182, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43188626e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.04539868, -0.00916277, 4.27626181]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.847551345825195, + 'FR_Wheel_Angle': 41.77214431762695, + 'Location': array([242.50762939, 160.38168335, 0.30170837]), + 'Rotation': array([-2.20341887e-02, -4.54448128e+01, -9.58251860e-03]), + 'Velocity': array([ 2.84727901e-01, -1.09882027e-01, -9.42039478e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5192260742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37652, + 'frame_number': 37652, + 'framesequence': 151841, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1277.9931312985718, + 'timestamp_carla': 1277997, + 'timestamp_device': 2896554, + 'timestamp_stream': 1277.9931312985718, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198162e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02224906, 0.09889866, 3.79113293]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.83462142944336, + 'FR_Wheel_Angle': 41.74539566040039, + 'Location': array([242.56306458, 160.35368347, 0.30169785]), + 'Rotation': array([-2.17883028e-02, -4.46184158e+01, -9.64355282e-03]), + 'Velocity': array([ 2.68797427e-01, -1.05637208e-01, 1.61657328e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5203857421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37653, + 'frame_number': 37653, + 'framesequence': 151845, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.026604797691, + 'timestamp_carla': 1278031, + 'timestamp_device': 2896587, + 'timestamp_stream': 1278.026604797691, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198162e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02396348, 0.1032776 , 3.90236259]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.830549240112305, + 'FR_Wheel_Angle': 41.738807678222656, + 'Location': array([242.63044739, 160.32141113, 0.30170295]), + 'Rotation': array([-2.14536227e-02, -4.36177597e+01, -9.79614165e-03]), + 'Velocity': array([ 2.79869199e-01, -1.04606003e-01, -2.57587435e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5185546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37654, + 'frame_number': 37654, + 'framesequence': 151849, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.0606212988496, + 'timestamp_carla': 1278065, + 'timestamp_device': 2896620, + 'timestamp_stream': 1278.0606212988496, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43202126e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02378611, 0.09915337, 3.93805623]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82759666442871, + 'FR_Wheel_Angle': 41.734249114990234, + 'Location': array([242.71003723, 160.28507996, 0.30170622]), + 'Rotation': array([-2.13921517e-02, -4.24470711e+01, -9.82665922e-03]), + 'Velocity': array([ 2.90851980e-01, -1.02151975e-01, 3.59535225e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5185546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37655, + 'frame_number': 37655, + 'framesequence': 151853, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.0934241972864, + 'timestamp_carla': 1278098, + 'timestamp_device': 2896654, + 'timestamp_stream': 1278.0934241972864, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43195257e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.0325702 , 0.00534705, 4.19686556]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.834712982177734, + 'FR_Wheel_Angle': 41.75370407104492, + 'Location': array([242.78208923, 160.2540741 , 0.30170539]), + 'Rotation': array([-2.15492453e-02, -4.14190788e+01, -1.01013193e-02]), + 'Velocity': array([ 3.15801620e-01, -9.77023616e-02, 1.61199569e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5177001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37656, + 'frame_number': 37656, + 'framesequence': 151857, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.126453898847, + 'timestamp_carla': 1278131, + 'timestamp_device': 2896687, + 'timestamp_stream': 1278.126453898847, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43192977e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.0258536 , 0.02862411, 3.86055636]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.834617614746094, + 'FR_Wheel_Angle': 41.73601150512695, + 'Location': array([242.84266663, 160.22895813, 0.30171019]), + 'Rotation': array([-2.19044164e-02, -4.05688705e+01, -8.72802734e-03]), + 'Velocity': array([ 2.99700171e-01, -9.12877843e-02, 1.36728282e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5191040039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37657, + 'frame_number': 37657, + 'framesequence': 151861, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.1608503982425, + 'timestamp_carla': 1278165, + 'timestamp_device': 2896720, + 'timestamp_stream': 1278.1608503982425, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43202201e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.07560106, -0.06602964, 4.91438341]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8369197845459, + 'FR_Wheel_Angle': 41.74269485473633, + 'Location': array([242.91400146, 160.20089722, 0.30171204]), + 'Rotation': array([-2.15765666e-02, -3.95837250e+01, -9.70458891e-03]), + 'Velocity': array([ 3.31123471e-01, -9.09620151e-02, 8.56161132e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37658, + 'frame_number': 37658, + 'framesequence': 151865, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.1930353976786, + 'timestamp_carla': 1278197, + 'timestamp_device': 2896754, + 'timestamp_stream': 1278.1930353976786, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43191144e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.04248008, -0.05641501, 5.42935514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.848939895629883, + 'FR_Wheel_Angle': 41.781517028808594, + 'Location': array([242.99737549, 160.1693573 , 0.30171028]), + 'Rotation': array([-2.12692078e-02, -3.83991165e+01, -1.01928720e-02]), + 'Velocity': array([ 0.34450996, -0.09409006, 0.00042408]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5177001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37659, + 'frame_number': 37659, + 'framesequence': 151869, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.2258590981364, + 'timestamp_carla': 1278230, + 'timestamp_device': 2896787, + 'timestamp_stream': 1278.2258590981364, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43189386e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.0416146 , -0.04834994, 5.01839304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.843772888183594, + 'FR_Wheel_Angle': 41.772972106933594, + 'Location': array([243.06755066, 160.14427185, 0.30170608]), + 'Rotation': array([-2.14877743e-02, -3.74207001e+01, -1.01013184e-02]), + 'Velocity': array([ 3.29733580e-01, -8.41227695e-02, -9.18865189e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5199584960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37660, + 'frame_number': 37660, + 'framesequence': 151873, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.2600533999503, + 'timestamp_carla': 1278264, + 'timestamp_device': 2896820, + 'timestamp_stream': 1278.2600533999503, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198922e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.02555892, 0.01249591, 5.5752449 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.829017639160156, + 'FR_Wheel_Angle': 41.759681701660156, + 'Location': array([243.14022827, 160.11952209, 0.30169937]), + 'Rotation': array([-2.08115857e-02, -3.64146042e+01, -1.00402823e-02]), + 'Velocity': array([ 3.35672647e-01, -9.12636518e-02, -5.60760491e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5202026367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37661, + 'frame_number': 37661, + 'framesequence': 151877, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.2947111986578, + 'timestamp_carla': 1278299, + 'timestamp_device': 2896854, + 'timestamp_stream': 1278.2947111986578, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43208012e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.04019001, 0.04739927, 4.85836697]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.85421371459961, + 'FR_Wheel_Angle': 41.788394927978516, + 'Location': array([243.21289062, 160.09632874, 0.3017031 ]), + 'Rotation': array([-2.24303398e-02, -3.53998146e+01, -8.42285249e-03]), + 'Velocity': array([ 3.00219029e-01, -7.27005675e-02, -2.26154327e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5183715820312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37662, + 'frame_number': 37662, + 'framesequence': 151881, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.327626299113, + 'timestamp_carla': 1278332, + 'timestamp_device': 2896887, + 'timestamp_stream': 1278.327626299113, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43199533e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.04484274, -0.00884154, 4.22523022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.84328842163086, + 'FR_Wheel_Angle': 41.159507751464844, + 'Location': array([243.28182983, 160.07583618, 0.30170813]), + 'Rotation': array([-2.16721892e-02, -3.44398918e+01, -9.58251860e-03]), + 'Velocity': array([ 0.30691466, -0.05655721, 0.00050023]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5164794921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37663, + 'frame_number': 37663, + 'framesequence': 151885, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.3590481989086, + 'timestamp_carla': 1278363, + 'timestamp_device': 2896920, + 'timestamp_stream': 1278.3590481989086, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43184587e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([0.03437853, 0.01250341, 4.16208458]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.76326560974121, + 'FR_Wheel_Angle': 37.13179016113281, + 'Location': array([243.35435486, 160.0537262 , 0.30170241]), + 'Rotation': array([-2.09960006e-02, -3.35207062e+01, -8.08715820e-03]), + 'Velocity': array([ 3.12066555e-01, -6.98221177e-02, 1.97048183e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5182495117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37664, + 'frame_number': 37664, + 'framesequence': 151889, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.3922773003578, + 'timestamp_carla': 1278397, + 'timestamp_device': 2896954, + 'timestamp_stream': 1278.3922773003578, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43188700e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.0336603 , 0.09127805, 3.50391579]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.17349624633789, + 'FR_Wheel_Angle': 37.37667465209961, + 'Location': array([243.41720581, 160.03494263, 0.30170333]), + 'Rotation': array([-2.11462639e-02, -3.27295990e+01, -9.42993164e-03]), + 'Velocity': array([ 3.00368249e-01, -6.38104603e-02, -9.19437371e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521240234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30. ]), + 'frame': 37665, + 'frame_number': 37665, + 'framesequence': 151893, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.4249549992383, + 'timestamp_carla': 1278429, + 'timestamp_device': 2896987, + 'timestamp_stream': 1278.4249549992383, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43187329e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.03712866, -0.0970805 , 4.63859367]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.32370376586914, + 'FR_Wheel_Angle': 37.619022369384766, + 'Location': array([243.5007019 , 160.01132202, 0.30170539]), + 'Rotation': array([-2.06954721e-02, -3.16902046e+01, -1.04064941e-02]), + 'Velocity': array([ 3.79886389e-01, -8.00717175e-02, -3.57131939e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5203857421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37666, + 'frame_number': 37666, + 'framesequence': 151897, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0, + 'timestamp': 1278.4591031968594, + 'timestamp_carla': 1278464, + 'timestamp_device': 2897020, + 'timestamp_stream': 1278.4591031968594, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198013e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02484316, -0.08817611, 4.22658825]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.338638305664062, + 'FR_Wheel_Angle': 33.256683349609375, + 'Location': array([243.57781982, 159.99058533, 0.30169827]), + 'Rotation': array([-2.06613205e-02, -3.07689285e+01, -9.09424014e-03]), + 'Velocity': array([ 3.80754530e-01, -8.41335207e-02, -1.72138207e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206298828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.234375 , 30.00003052]), + 'frame': 37667, + 'frame_number': 37667, + 'framesequence': 151901, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.01190203707665205, + 'timestamp': 1278.49371079728, + 'timestamp_carla': 1278498, + 'timestamp_device': 2897054, + 'timestamp_stream': 1278.49371079728, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43207699e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.0436804 , -0.09003072, 4.1809516 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.077167510986328, + 'FR_Wheel_Angle': 33.699214935302734, + 'Location': array([243.64544678, 159.97128296, 0.30170235]), + 'Rotation': array([-2.06954721e-02, -3.00309505e+01, -9.52148624e-03]), + 'Velocity': array([ 3.86153162e-01, -8.31874162e-02, 2.14471816e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5185546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30. ]), + 'frame': 37668, + 'frame_number': 37668, + 'framesequence': 151905, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.01190203707665205, + 'timestamp': 1278.5263870991766, + 'timestamp_carla': 1278531, + 'timestamp_device': 2897087, + 'timestamp_stream': 1278.5263870991766, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43198237e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.03638274, -0.08785229, 4.23806477]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.829336166381836, + 'FR_Wheel_Angle': 33.4266357421875, + 'Location': array([243.73765564, 159.94676208, 0.3017002 ]), + 'Rotation': array([-2.08457354e-02, -2.90175476e+01, -1.00402832e-02]), + 'Velocity': array([ 3.93721491e-01, -7.86228999e-02, -2.31361391e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5166015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23828125, 30.00003052]), + 'frame': 37669, + 'frame_number': 37669, + 'framesequence': 151909, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.019836727529764175, + 'timestamp': 1278.5592739991844, + 'timestamp_carla': 1278564, + 'timestamp_device': 2897120, + 'timestamp_stream': 1278.5592739991844, + 'transform': [array([ 1.89967972e+02, 3.00261078e+02, -1.43194124e-01]), + array([-8.91339593e-03, -1.62394623e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.03834565, -0.08382054, 4.2232585 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.503881454467773, + 'FR_Wheel_Angle': 32.21493148803711, + 'Location': array([243.80854797, 159.92895508, 0.30169284]), + 'Rotation': array([-2.08457354e-02, -2.82422447e+01, -9.88769438e-03]), + 'Velocity': array([ 3.96572113e-01, -7.49157891e-02, -1.55925751e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184326171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37670, + 'frame_number': 37670, + 'framesequence': 151913, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.027771420776844025, + 'timestamp': 1278.5932183973491, + 'timestamp_carla': 1278598, + 'timestamp_device': 2897154, + 'timestamp_stream': 1278.5932183973491, + 'transform': [array([ 1.89981796e+02, 3.00266296e+02, -1.43203497e-01]), + array([-8.94071721e-03, -1.62400543e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02643409, -0.08206763, 3.67519021]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.698118209838867, + 'FR_Wheel_Angle': 29.124929428100586, + 'Location': array([243.8910675 , 159.90791321, 0.30170459]), + 'Rotation': array([-2.05998495e-02, -2.74297028e+01, -8.05664062e-03]), + 'Velocity': array([ 4.02723104e-01, -8.84107575e-02, 2.01025003e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.519287109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86914062, 16591.23632812, 30.00003052]), + 'frame': 37671, + 'frame_number': 37671, + 'framesequence': 151917, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.035706110298633575, + 'timestamp': 1278.6259940974414, + 'timestamp_carla': 1278630, + 'timestamp_device': 2897187, + 'timestamp_stream': 1278.6259940974414, + 'transform': [array([ 1.89981796e+02, 3.00266296e+02, -1.43197820e-01]), + array([-8.94071721e-03, -1.62400543e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.02888835, -0.08051779, 3.82966852]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.000389099121094, + 'FR_Wheel_Angle': 29.1505184173584, + 'Location': array([243.9879303 , 159.88336182, 0.301707 ]), + 'Rotation': array([-2.07227934e-02, -2.65071239e+01, -9.64355376e-03]), + 'Velocity': array([ 4.10614580e-01, -8.04592967e-02, 2.76417733e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5181274414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86132812, 16591.24023438, 30. ]), + 'frame': 37672, + 'frame_number': 37672, + 'framesequence': 151921, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.03967345505952835, + 'timestamp': 1278.6598520986736, + 'timestamp_carla': 1278664, + 'timestamp_device': 2897220, + 'timestamp_stream': 1278.6598520986736, + 'transform': [array([ 1.89982040e+02, 3.00266357e+02, -1.43202931e-01]), + array([-8.94071721e-03, -1.62400665e+02, 2.26745512e-02])]} +{'AngularVelocity': array([ 0.03125522, -0.08010674, 3.88358307]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.12828826904297, + 'FR_Wheel_Angle': 29.230247497558594, + 'Location': array([244.07450867, 159.86274719, 0.3017047 ]), + 'Rotation': array([-2.07842644e-02, -2.56789951e+01, -1.00097656e-02]), + 'Velocity': array([ 4.15947795e-01, -7.44674131e-02, 1.30519868e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5193481445312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86328125, 16591.23828125, 29.99996948]), + 'frame': 37673, + 'frame_number': 37673, + 'framesequence': 151925, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0476234070956707, + 'timestamp': 1278.6929953992367, + 'timestamp_carla': 1278697, + 'timestamp_device': 2897254, + 'timestamp_stream': 1278.6929953992367, + 'transform': [array([ 1.89981827e+02, 3.00266296e+02, -1.43200338e-01]), + array([-8.94071721e-03, -1.62400558e+02, 2.26745531e-02])]} +{'AngularVelocity': array([ 0.01720731, -0.07851962, 3.64180493]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.55592918395996, + 'FR_Wheel_Angle': 24.38429069519043, + 'Location': array([244.14959717, 159.84542847, 0.30169231]), + 'Rotation': array([-2.05383785e-02, -2.49833450e+01, -8.85009766e-03]), + 'Velocity': array([ 0.42190653, -0.08159886, -0.00043406]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.518310546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86132812, 16591.2421875 , 29.99996948]), + 'frame': 37674, + 'frame_number': 37674, + 'framesequence': 151929, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0476234070956707, + 'timestamp': 1278.726629998535, + 'timestamp_carla': 1278731, + 'timestamp_device': 2897287, + 'timestamp_stream': 1278.726629998535, + 'transform': [array([ 1.89982101e+02, 3.00266388e+02, -1.43202513e-01]), + array([-8.94071721e-03, -1.62400696e+02, 2.26745494e-02])]} +{'AngularVelocity': array([ 0.03080795, -0.078911 , 3.46361303]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.627578735351562, + 'FR_Wheel_Angle': 25.191186904907227, + 'Location': array([244.25169373, 159.82060242, 0.30169547]), + 'Rotation': array([-2.07227934e-02, -2.41515617e+01, -9.46044922e-03]), + 'Velocity': array([ 4.25632954e-01, -7.98403248e-02, -2.39725108e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.518798828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86132812, 16591.2421875 , 29.99996948]), + 'frame': 37675, + 'frame_number': 37675, + 'framesequence': 151933, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0476234070956707, + 'timestamp': 1278.7619825005531, + 'timestamp_carla': 1278767, + 'timestamp_device': 2897320, + 'timestamp_stream': 1278.7619825005531, + 'transform': [array([ 1.89982971e+02, 3.00266724e+02, -1.43293187e-01]), + array([-8.94071721e-03, -1.62401062e+02, 2.26440355e-02])]} +{'AngularVelocity': array([ 0.02914747, -0.07844597, 3.47937751]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.4060115814209, + 'FR_Wheel_Angle': 25.013593673706055, + 'Location': array([244.34239197, 159.79985046, 0.30169684]), + 'Rotation': array([-2.06954721e-02, -2.34072666e+01, -9.64355469e-03]), + 'Velocity': array([ 4.31883544e-01, -7.69496784e-02, -2.17494962e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5183715820312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86328125, 16591.2421875 , 30. ]), + 'frame': 37676, + 'frame_number': 37676, + 'framesequence': 151937, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1278.795184597373, + 'timestamp_carla': 1278800, + 'timestamp_device': 2897354, + 'timestamp_stream': 1278.795184597373, + 'transform': [array([ 1.89982422e+02, 3.00266510e+02, -1.43359944e-01]), + array([-8.94071721e-03, -1.62400818e+02, 2.26135179e-02])]} +{'AngularVelocity': array([ 0.01903868, -0.07666532, 3.43060398]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.925365447998047, + 'FR_Wheel_Angle': 23.5631046295166, + 'Location': array([244.43254089, 159.78060913, 0.30170551]), + 'Rotation': array([-2.08115857e-02, -2.26975842e+01, -9.55200195e-03]), + 'Velocity': array([ 4.32670504e-01, -7.33801872e-02, -1.61581032e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5154418945312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86132812, 16591.2421875 , 30.00003052]), + 'frame': 37677, + 'frame_number': 37677, + 'framesequence': 151941, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1278.8266609981656, + 'timestamp_carla': 1278831, + 'timestamp_device': 2897387, + 'timestamp_stream': 1278.8266609981656, + 'transform': [array([ 1.89981827e+02, 3.00266235e+02, -1.43418804e-01]), + array([-8.94071721e-03, -1.62400558e+02, 2.25830004e-02])]} +{'AngularVelocity': array([ 0.02627417, -0.06590024, 2.73791075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.14282989501953, + 'FR_Wheel_Angle': 20.92041778564453, + 'Location': array([244.52359009, 159.75985718, 0.30171478]), + 'Rotation': array([-2.08730567e-02, -2.20759163e+01, -7.59887788e-03]), + 'Velocity': array([ 0.42510313, -0.08371225, 0.00075478]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.517333984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86132812, 16591.2421875 , 30. ]), + 'frame': 37678, + 'frame_number': 37678, + 'framesequence': 151945, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1278.8597398996353, + 'timestamp_carla': 1278864, + 'timestamp_device': 2897420, + 'timestamp_stream': 1278.8597398996353, + 'transform': [array([ 1.89982529e+02, 3.00266418e+02, -1.43496051e-01]), + array([-8.94071721e-03, -1.62400864e+02, 2.25524772e-02])]} +{'AngularVelocity': array([ 0.02147092, -0.07465862, 2.96432018]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.352706909179688, + 'FR_Wheel_Angle': 20.820640563964844, + 'Location': array([244.61526489, 159.73939514, 0.30169964]), + 'Rotation': array([-2.05725282e-02, -2.14456692e+01, -9.15527157e-03]), + 'Velocity': array([ 4.36903149e-01, -7.99128413e-02, 8.27884651e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206909179688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86328125, 16591.23632812, 30. ]), + 'frame': 37679, + 'frame_number': 37679, + 'framesequence': 151949, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1278.892118498683, + 'timestamp_carla': 1278897, + 'timestamp_device': 2897454, + 'timestamp_stream': 1278.892118498683, + 'transform': [array([ 1.89982529e+02, 3.00266327e+02, -1.43492356e-01]), + array([-8.94071721e-03, -1.62400864e+02, 2.25524772e-02])]} +{'AngularVelocity': array([ 0.02229017, -0.07502931, 2.96560216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.468017578125, + 'FR_Wheel_Angle': 20.880680084228516, + 'Location': array([244.70787048, 159.71972656, 0.30170366]), + 'Rotation': array([-2.05725282e-02, -2.08160343e+01, -9.67407320e-03]), + 'Velocity': array([ 4.44223523e-01, -7.53591731e-02, -1.15327835e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208129882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86132812, 16591.2265625 , 30. ]), + 'frame': 37680, + 'frame_number': 37680, + 'framesequence': 151953, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1278.9254633001983, + 'timestamp_carla': 1278930, + 'timestamp_device': 2897487, + 'timestamp_stream': 1278.9254633001983, + 'transform': [array([ 1.89983154e+02, 3.00266510e+02, -1.43573418e-01]), + array([-8.94071721e-03, -1.62401108e+02, 2.25219615e-02])]} +{'AngularVelocity': array([ 0.00464594, -0.07485715, 2.38832045]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.436203002929688, + 'FR_Wheel_Angle': 15.786919593811035, + 'Location': array([244.8000946 , 159.70022583, 0.30169499]), + 'Rotation': array([-2.11462639e-02, -2.02558556e+01, -7.41577055e-03]), + 'Velocity': array([ 4.29748476e-01, -8.46965015e-02, -2.82030087e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5215454101562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86132812, 16591.21875 , 30. ]), + 'frame': 37681, + 'frame_number': 37681, + 'framesequence': 151957, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1278.9612168967724, + 'timestamp_carla': 1278966, + 'timestamp_device': 2897520, + 'timestamp_stream': 1278.9612168967724, + 'transform': [array([ 1.89984299e+02, 3.00266724e+02, -1.43671945e-01]), + array([-8.94071721e-03, -1.62401581e+02, 2.24914439e-02])]} +{'AngularVelocity': array([-0.0309961 , -0.00907861, 2.7730155 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.645724296569824, + 'FR_Wheel_Angle': 16.72079086303711, + 'Location': array([244.89089966, 159.67971802, 0.30170652]), + 'Rotation': array([-2.16380376e-02, -1.97735271e+01, -8.20922945e-03]), + 'Velocity': array([ 3.97007316e-01, -7.91237354e-02, 1.02462764e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5204467773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.86523438, 16591.21289062, 30.00003052]), + 'frame': 37682, + 'frame_number': 37682, + 'framesequence': 151961, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1278.9931591972709, + 'timestamp_carla': 1278998, + 'timestamp_device': 2897554, + 'timestamp_stream': 1278.9931591972709, + 'transform': [array([ 1.89983002e+02, 3.00266083e+02, -1.43727154e-01]), + array([-8.91339593e-03, -1.62400986e+02, 2.24609263e-02])]} +{'AngularVelocity': array([ 0.02925872, -0.03028153, 2.94606543]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.436490058898926, + 'FR_Wheel_Angle': 16.640384674072266, + 'Location': array([244.96876526, 159.66281128, 0.30169731]), + 'Rotation': array([-2.13033594e-02, -1.93666115e+01, -8.97216797e-03]), + 'Velocity': array([ 4.00980175e-01, -6.99322447e-02, -4.16851035e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5159301757812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.87109375, 16591.20117188, 29.99996948]), + 'frame': 37683, + 'frame_number': 37683, + 'framesequence': 151965, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.030360199511, + 'timestamp_carla': 1279035, + 'timestamp_device': 2897587, + 'timestamp_stream': 1279.030360199511, + 'transform': [array([ 1.89985092e+02, 3.00266632e+02, -1.43839762e-01]), + array([-8.94071721e-03, -1.62401855e+02, 2.24304125e-02])]} +{'AngularVelocity': array([ 0.00666479, -0.01317096, 2.63966393]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.75986099243164, + 'FR_Wheel_Angle': 14.975485801696777, + 'Location': array([245.06730652, 159.64227295, 0.30171344]), + 'Rotation': array([-2.15492453e-02, -1.88464432e+01, -8.54492094e-03]), + 'Velocity': array([ 3.76775891e-01, -6.65344000e-02, 3.49330912e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.87890625, 16591.18164062, 29.99996948]), + 'frame': 37684, + 'frame_number': 37684, + 'framesequence': 151969, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.0612714998424, + 'timestamp_carla': 1279066, + 'timestamp_device': 2897620, + 'timestamp_stream': 1279.0612714998424, + 'transform': [array([ 1.89982880e+02, 3.00265594e+02, -1.43805087e-01]), + array([-8.91339593e-03, -1.62400864e+02, 2.24304087e-02])]} +{'AngularVelocity': array([-0.00990425, 0.04638229, 1.99756944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.932694435119629, + 'FR_Wheel_Angle': 12.696417808532715, + 'Location': array([245.14175415, 159.62495422, 0.30170912]), + 'Rotation': array([-2.13306788e-02, -1.85282040e+01, -6.68334868e-03]), + 'Velocity': array([ 3.49585325e-01, -7.70891830e-02, 1.98664668e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5128173828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.8828125 , 16591.16796875, 30.00003052]), + 'frame': 37685, + 'frame_number': 37685, + 'framesequence': 151973, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.0933525003493, + 'timestamp_carla': 1279098, + 'timestamp_device': 2897654, + 'timestamp_stream': 1279.0933525003493, + 'transform': [array([ 1.89983322e+02, 3.00265503e+02, -1.43869936e-01]), + array([-8.91339593e-03, -1.62401016e+02, 2.23998912e-02])]} +{'AngularVelocity': array([-8.49152493e-05, 1.43355811e-02, 1.22591364e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.0956392288208, + 'FR_Wheel_Angle': 12.530378341674805, + 'Location': array([245.23878479, 159.60282898, 0.30169758]), + 'Rotation': array([-2.12692078e-02, -1.81233006e+01, -8.36181547e-03]), + 'Velocity': array([ 3.58665764e-01, -7.22512677e-02, -1.20277400e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5189819335938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.89453125, 16591.14453125, 30.00003052]), + 'frame': 37686, + 'frame_number': 37686, + 'framesequence': 151977, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.125458497554, + 'timestamp_carla': 1279130, + 'timestamp_device': 2897687, + 'timestamp_stream': 1279.125458497554, + 'transform': [array([ 1.89983398e+02, 3.00265259e+02, -1.43864363e-01]), + array([-8.91339593e-03, -1.62401016e+02, 2.23998912e-02])]} +{'AngularVelocity': array([ 0.026896 , -0.03736786, 2.13516855]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.194809913635254, + 'FR_Wheel_Angle': 12.52926254272461, + 'Location': array([245.30950928, 159.58711243, 0.30170357]), + 'Rotation': array([-2.13033594e-02, -1.78276196e+01, -8.66699219e-03]), + 'Velocity': array([ 3.72447312e-01, -7.06371889e-02, 1.21383666e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.90429688, 16591.11914062, 30. ]), + 'frame': 37687, + 'frame_number': 37687, + 'framesequence': 151981, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.1591854989529, + 'timestamp_carla': 1279164, + 'timestamp_device': 2897720, + 'timestamp_stream': 1279.1591854989529, + 'transform': [array([ 1.89984177e+02, 3.00265198e+02, -1.43949166e-01]), + array([-8.91339593e-03, -1.62401321e+02, 2.23693736e-02])]} +{'AngularVelocity': array([-0.00851134, 0.06734503, 0.74472815]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.486117362976074, + 'FR_Wheel_Angle': 7.366000652313232, + 'Location': array([245.40516663, 159.56555176, 0.30169749]), + 'Rotation': array([-2.07227934e-02, -1.75007477e+01, -7.17163086e-03]), + 'Velocity': array([ 0.33407578, -0.07556476, -0.00036331]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5226440429688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.91210938, 16591.09570312, 29.99996948]), + 'frame': 37688, + 'frame_number': 37688, + 'framesequence': 151985, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.1928207986057, + 'timestamp_carla': 1279197, + 'timestamp_device': 2897754, + 'timestamp_stream': 1279.1928207986057, + 'transform': [array([ 1.89984253e+02, 3.00264862e+02, -1.43954203e-01]), + array([-8.91339593e-03, -1.62401321e+02, 2.23693736e-02])]} +{'AngularVelocity': array([-0.00139256, 0.06919701, 1.02230227]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.890848159790039, + 'FR_Wheel_Angle': 8.274248123168945, + 'Location': array([245.49206543, 159.54425049, 0.30170748]), + 'Rotation': array([-2.06613205e-02, -1.72560883e+01, -8.45336914e-03]), + 'Velocity': array([ 3.45397145e-01, -7.63236284e-02, -6.66522974e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208129882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.91796875, 16591.06640625, 30. ]), + 'frame': 37689, + 'frame_number': 37689, + 'framesequence': 151989, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.2260413989425, + 'timestamp_carla': 1279231, + 'timestamp_device': 2897787, + 'timestamp_stream': 1279.2260413989425, + 'transform': [array([ 1.89984329e+02, 3.00264557e+02, -1.43953696e-01]), + array([-8.91339593e-03, -1.62401321e+02, 2.23693736e-02])]} +{'AngularVelocity': array([-0.00112645, 0.06955912, 0.94576311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.6999382972717285, + 'FR_Wheel_Angle': 8.274231910705566, + 'Location': array([245.58143616, 159.52281189, 0.30169457]), + 'Rotation': array([-2.09960006e-02, -1.69978771e+01, -8.60595610e-03]), + 'Velocity': array([ 3.46118689e-01, -7.57343471e-02, -7.28321029e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5198364257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.92578125, 16591.03515625, 30. ]), + 'frame': 37690, + 'frame_number': 37690, + 'framesequence': 151993, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.2590500973165, + 'timestamp_carla': 1279264, + 'timestamp_device': 2897820, + 'timestamp_stream': 1279.2590500973165, + 'transform': [array([ 1.89984451e+02, 3.00264221e+02, -1.43952250e-01]), + array([-8.91339593e-03, -1.62401321e+02, 2.23693736e-02])]} +{'AngularVelocity': array([-0.00712122, 0.06570259, 0.79374552]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.568849563598633, + 'FR_Wheel_Angle': 6.121118068695068, + 'Location': array([245.67071533, 159.50180054, 0.30170444]), + 'Rotation': array([-2.09345277e-02, -1.67512646e+01, -8.17871094e-03]), + 'Velocity': array([ 3.53560090e-01, -7.97573850e-02, 2.61592868e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5199584960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.93359375, 16591.00390625, 30. ]), + 'frame': 37691, + 'frame_number': 37691, + 'framesequence': 151997, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.2937094978988, + 'timestamp_carla': 1279298, + 'timestamp_device': 2897854, + 'timestamp_stream': 1279.2937094978988, + 'transform': [array([ 1.89985229e+02, 3.00264069e+02, -1.43964082e-01]), + array([-8.91339593e-03, -1.62401611e+02, 2.23693736e-02])]} +{'AngularVelocity': array([0.02285244, 0.05780343, 0.93737787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.964064836502075, + 'FR_Wheel_Angle': 4.569637298583984, + 'Location': array([245.76060486, 159.47805786, 0.30170619]), + 'Rotation': array([-2.10301522e-02, -1.66048450e+01, -7.11059570e-03]), + 'Velocity': array([ 3.52958053e-01, -9.09265056e-02, 2.42657654e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5202026367188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.9453125 , 16590.96679688, 30. ]), + 'frame': 37692, + 'frame_number': 37692, + 'framesequence': 152001, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.051590751856565475, + 'timestamp': 1279.324374999851, + 'timestamp_carla': 1279329, + 'timestamp_device': 2897887, + 'timestamp_stream': 1279.324374999851, + 'transform': [array([ 1.89983856e+02, 3.00263092e+02, -1.44014701e-01]), + array([-8.87924526e-03, -1.62400955e+02, 2.23388541e-02])]} +{'AngularVelocity': array([0.00993214, 0.05903431, 0.57851481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9550890922546387, + 'FR_Wheel_Angle': 4.252324104309082, + 'Location': array([245.83830261, 159.45776367, 0.30170539]), + 'Rotation': array([-2.09072083e-02, -1.64917755e+01, -8.20922945e-03]), + 'Velocity': array([ 3.59207302e-01, -9.09619853e-02, 9.04178596e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5179443359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.9609375, 16590.9296875, 30. ]), + 'frame': 37693, + 'frame_number': 37693, + 'framesequence': 152005, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1279.3572985976934, + 'timestamp_carla': 1279362, + 'timestamp_device': 2897920, + 'timestamp_stream': 1279.3572985976934, + 'transform': [array([ 1.89984802e+02, 3.00262939e+02, -1.44093022e-01]), + array([-8.87924526e-03, -1.62401291e+02, 2.23083403e-02])]} +{'AngularVelocity': array([0.00967691, 0.08535759, 0.56114185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.015916347503662, + 'FR_Wheel_Angle': 4.144488334655762, + 'Location': array([245.92987061, 159.43392944, 0.30170378]), + 'Rotation': array([-2.13648304e-02, -1.63583546e+01, -8.54492281e-03]), + 'Velocity': array([ 3.43967587e-01, -8.57611075e-02, -1.48620602e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.522216796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.97265625, 16590.88671875, 30. ]), + 'frame': 37694, + 'frame_number': 37694, + 'framesequence': 152009, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1279.3924016989768, + 'timestamp_carla': 1279397, + 'timestamp_device': 2897953, + 'timestamp_stream': 1279.3924016989768, + 'transform': [array([ 1.89985916e+02, 3.00262817e+02, -1.44112170e-01]), + array([-8.87924526e-03, -1.62401688e+02, 2.23083384e-02])]} +{'AngularVelocity': array([0.00643522, 0.06799556, 0.0146068 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.6739062070846558, + 'FR_Wheel_Angle': -1.037139892578125, + 'Location': array([246.02104187, 159.40950012, 0.30170184]), + 'Rotation': array([-2.08115857e-02, -1.62705250e+01, -6.71386672e-03]), + 'Velocity': array([ 3.58091205e-01, -1.02917813e-01, -1.40161515e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5216064453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.99023438, 16590.83984375, 30.00003052]), + 'frame': 37695, + 'frame_number': 37695, + 'framesequence': 152014, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1279.4369224980474, + 'timestamp_carla': 1279442, + 'timestamp_device': 2897995, + 'timestamp_stream': 1279.4369224980474, + 'transform': [array([ 1.90014267e+02, 3.00272736e+02, -1.44128948e-01]), + array([-8.87924526e-03, -1.62413773e+02, 2.23083403e-02])]} +{'AngularVelocity': array([ 0.01936924, 0.05705801, -0.04653428]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.08891981095075607, + 'FR_Wheel_Angle': -0.17896686494350433, + 'Location': array([246.11288452, 159.38241577, 0.30170411]), + 'Rotation': array([-2.09345277e-02, -1.62854462e+01, -8.08715820e-03]), + 'Velocity': array([ 3.63786012e-01, -1.05301112e-01, 3.35979457e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5181884765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.00390625, 16590.79492188, 30. ]), + 'frame': 37696, + 'frame_number': 37696, + 'framesequence': 152017, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.059525445103645325, + 'timestamp': 1279.4585013985634, + 'timestamp_carla': 1279463, + 'timestamp_device': 2898020, + 'timestamp_stream': 1279.4585013985634, + 'transform': [array([ 1.89998672e+02, 3.00266479e+02, -1.44178241e-01]), + array([-8.91339593e-03, -1.62407028e+02, 2.22778190e-02])]} +{'AngularVelocity': array([ 0.01786177, 0.05967539, -0.0483468 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.05085663124918938, + 'FR_Wheel_Angle': -0.030503282323479652, + 'Location': array([246.20643616, 159.35487366, 0.30169666]), + 'Rotation': array([-2.10847929e-02, -1.62827950e+01, -8.30078218e-03]), + 'Velocity': array([ 3.63440663e-01, -1.06927291e-01, 1.01909638e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.514404296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.00390625, 16590.74023438, 30. ]), + 'frame': 37697, + 'frame_number': 37697, + 'framesequence': 152021, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.059525445103645325, + 'timestamp': 1279.4920063987374, + 'timestamp_carla': 1279497, + 'timestamp_device': 2898053, + 'timestamp_stream': 1279.4920063987374, + 'transform': [array([ 1.90000626e+02, 3.00266510e+02, -1.44332618e-01]), + array([-8.91339593e-03, -1.62407776e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.01017873, 0.05559406, -0.0748244 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.515357494354248, + 'FR_Wheel_Angle': -2.3565168380737305, + 'Location': array([246.31211853, 159.32368469, 0.30171111]), + 'Rotation': array([-2.08730567e-02, -1.63011036e+01, -7.72094727e-03]), + 'Velocity': array([ 3.70482892e-01, -1.14565939e-01, 7.90786726e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205688476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.02929688, 16590.69726562, 30. ]), + 'frame': 37698, + 'frame_number': 37698, + 'framesequence': 152025, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.5256882980466, + 'timestamp_carla': 1279530, + 'timestamp_device': 2898087, + 'timestamp_stream': 1279.5256882980466, + 'transform': [array([ 1.90000854e+02, 3.00265900e+02, -1.44335672e-01]), + array([-8.91339593e-03, -1.62407776e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.04233649, 0.05437661, -0.56478173]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.086945533752441, + 'FR_Wheel_Angle': -3.6000289916992188, + 'Location': array([246.391922 , 159.29733276, 0.30170649]), + 'Rotation': array([-2.09345277e-02, -1.64160938e+01, -6.34765625e-03]), + 'Velocity': array([ 3.64775091e-01, -1.27420783e-01, -7.42244738e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.520263671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.04882812, 16590.6328125 , 30. ]), + 'frame': 37699, + 'frame_number': 37699, + 'framesequence': 152029, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.5593206994236, + 'timestamp_carla': 1279564, + 'timestamp_device': 2898120, + 'timestamp_stream': 1279.5593206994236, + 'transform': [array([ 1.90001083e+02, 3.00265198e+02, -1.44337162e-01]), + array([-8.91339593e-03, -1.62407776e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.03210113, 0.0574108 , -0.4693768 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.138797283172607, + 'FR_Wheel_Angle': -3.918586015701294, + 'Location': array([246.49937439, 159.26139832, 0.30170193]), + 'Rotation': array([-2.09345277e-02, -1.65714283e+01, -8.05664062e-03]), + 'Velocity': array([ 3.68123382e-01, -1.27331913e-01, -7.52353662e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.07226562, 16590.57226562, 30. ]), + 'frame': 37700, + 'frame_number': 37700, + 'framesequence': 152033, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.5934008993208, + 'timestamp_carla': 1279598, + 'timestamp_device': 2898153, + 'timestamp_stream': 1279.5934008993208, + 'transform': [array([ 1.90001328e+02, 3.00264496e+02, -1.44340858e-01]), + array([-8.91339593e-03, -1.62407776e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.02778908, 0.05712859, -0.60361087]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.168022632598877, + 'FR_Wheel_Angle': -4.048569679260254, + 'Location': array([246.58007812, 159.23426819, 0.30170226]), + 'Rotation': array([-2.09960006e-02, -1.66982250e+01, -8.36181734e-03]), + 'Velocity': array([ 3.69067907e-01, -1.28514513e-01, -1.21870042e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5193481445312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.09570312, 16590.50195312, 30. ]), + 'frame': 37701, + 'frame_number': 37701, + 'framesequence': 152037, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.6248850002885, + 'timestamp_carla': 1279630, + 'timestamp_device': 2898187, + 'timestamp_stream': 1279.6248850002885, + 'transform': [array([ 1.90000488e+02, 3.00263367e+02, -1.44320905e-01]), + array([-8.87924526e-03, -1.62407318e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.03895568, 0.05924755, -1.22500288]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.218989372253418, + 'FR_Wheel_Angle': -8.530729293823242, + 'Location': array([246.68739319, 159.19592285, 0.30169928]), + 'Rotation': array([-2.09960006e-02, -1.69211273e+01, -5.82885696e-03]), + 'Velocity': array([ 3.61959785e-01, -1.47076577e-01, -2.26497650e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5186157226562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.11914062, 16590.43164062, 29.99996948]), + 'frame': 37702, + 'frame_number': 37702, + 'framesequence': 152041, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.6583572998643, + 'timestamp_carla': 1279663, + 'timestamp_device': 2898220, + 'timestamp_stream': 1279.6583572998643, + 'transform': [array([ 1.90001358e+02, 3.00262878e+02, -1.44325718e-01]), + array([-8.87924526e-03, -1.62407578e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.03533776, 0.04780598, -1.08548403]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.3019437789917, + 'FR_Wheel_Angle': -7.860723495483398, + 'Location': array([246.76690674, 159.16539001, 0.30171156]), + 'Rotation': array([-2.08730567e-02, -1.71576996e+01, -7.72094727e-03]), + 'Velocity': array([ 3.70985180e-01, -1.49141222e-01, 1.00789068e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5219116210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.14648438, 16590.35742188, 29.99996948]), + 'frame': 37703, + 'frame_number': 37703, + 'framesequence': 152045, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.6930186003447, + 'timestamp_carla': 1279698, + 'timestamp_device': 2898253, + 'timestamp_stream': 1279.6930186003447, + 'transform': [array([ 1.90002060e+02, 3.00262268e+02, -1.44337878e-01]), + array([-8.87924526e-03, -1.62407791e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.03669155, 0.05469445, -0.76593429]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.376459121704102, + 'FR_Wheel_Angle': -7.710216999053955, + 'Location': array([246.87487793, 159.12347412, 0.30170289]), + 'Rotation': array([-2.09960006e-02, -1.74734936e+01, -8.08715820e-03]), + 'Velocity': array([ 3.66148561e-01, -1.51063114e-01, 1.68437953e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5209350585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.16796875, 16590.28515625, 30. ]), + 'frame': 37704, + 'frame_number': 37704, + 'framesequence': 152049, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.7259895987809, + 'timestamp_carla': 1279731, + 'timestamp_device': 2898287, + 'timestamp_stream': 1279.7259895987809, + 'transform': [array([ 1.90001678e+02, 3.00261230e+02, -1.44331619e-01]), + array([-8.87924526e-03, -1.62407532e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.03054176, 0.05396704, -1.28484678]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.197863578796387, + 'FR_Wheel_Angle': -10.147516250610352, + 'Location': array([246.96862793, 159.08624268, 0.30171096]), + 'Rotation': array([-2.07842644e-02, -1.77648125e+01, -7.32421922e-03]), + 'Velocity': array([ 3.69415909e-01, -1.60873204e-01, -7.22312907e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184326171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.18945312, 16590.20898438, 30. ]), + 'frame': 37705, + 'frame_number': 37705, + 'framesequence': 152053, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.7578781992197, + 'timestamp_carla': 1279763, + 'timestamp_device': 2898320, + 'timestamp_stream': 1279.7578781992197, + 'transform': [array([ 1.90001480e+02, 3.00260284e+02, -1.44320592e-01]), + array([-8.87924526e-03, -1.62407349e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.04962919, 0.02654159, -2.03542304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.235215187072754, + 'FR_Wheel_Angle': -10.776002883911133, + 'Location': array([247.06202698, 159.04533386, 0.30170262]), + 'Rotation': array([-2.09345277e-02, -1.81761875e+01, -6.95800781e-03]), + 'Velocity': array([ 3.72099310e-01, -1.74802542e-01, 1.44319536e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5199584960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.21289062, 16590.13085938, 30. ]), + 'frame': 37706, + 'frame_number': 37706, + 'framesequence': 152056, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1279.790853999555, + 'timestamp_carla': 1279795, + 'timestamp_device': 2898345, + 'timestamp_stream': 1279.790853999555, + 'transform': [array([ 1.90002151e+02, 3.00259583e+02, -1.44321904e-01]), + array([-8.87924526e-03, -1.62407532e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.05404099, 0.05429276, -2.07088876]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.436075210571289, + 'FR_Wheel_Angle': -11.095010757446289, + 'Location': array([247.1534729 , 159.00453186, 0.30169752]), + 'Rotation': array([-2.15150956e-02, -1.85467892e+01, -8.08715820e-03]), + 'Velocity': array([ 0.34272769, -0.16437578, -0.00036911]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52197265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.24023438, 16590.04882812, 29.99996948]), + 'frame': 37707, + 'frame_number': 37707, + 'framesequence': 152060, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07142747938632965, + 'timestamp': 1279.8233537971973, + 'timestamp_carla': 1279828, + 'timestamp_device': 2898378, + 'timestamp_stream': 1279.8233537971973, + 'transform': [array([ 1.90002106e+02, 3.00258636e+02, -1.44319832e-01]), + array([-8.87924526e-03, -1.62407394e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.01968319, -0.01901945, -2.29095435]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.520284652709961, + 'FR_Wheel_Angle': -11.29686164855957, + 'Location': array([247.24017334, 158.96528625, 0.30169916]), + 'Rotation': array([-2.12077368e-02, -1.89318581e+01, -8.33129883e-03]), + 'Velocity': array([ 3.71931195e-01, -1.76536456e-01, -1.74903871e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5219116210938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.26171875, 16589.96484375, 30. ]), + 'frame': 37708, + 'frame_number': 37708, + 'framesequence': 152065, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1279.8571754992008, + 'timestamp_carla': 1279862, + 'timestamp_device': 2898420, + 'timestamp_stream': 1279.8571754992008, + 'transform': [array([ 1.90002762e+02, 3.00257843e+02, -1.44328684e-01]), + array([-8.87924526e-03, -1.62407547e+02, 2.22167838e-02])]} +{'AngularVelocity': array([-1.15689654e-04, -1.69920456e-02, -1.39053404e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.696836471557617, + 'FR_Wheel_Angle': -15.066455841064453, + 'Location': array([247.32337952, 158.92504883, 0.30171287]), + 'Rotation': array([-2.15765666e-02, -1.93586159e+01, -6.16455032e-03]), + 'Velocity': array([ 3.51746410e-01, -1.91867352e-01, -2.00576775e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5221557617188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.28710938, 16589.87695312, 29.99996948]), + 'frame': 37709, + 'frame_number': 37709, + 'framesequence': 152069, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1279.889972500503, + 'timestamp_carla': 1279895, + 'timestamp_device': 2898453, + 'timestamp_stream': 1279.889972500503, + 'transform': [array([ 1.90002594e+02, 3.00256775e+02, -1.44326314e-01]), + array([-8.87924526e-03, -1.62407349e+02, 2.22167857e-02])]} +{'AngularVelocity': array([-0.053903 , -0.04568579, -2.41129017]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.76744842529297, + 'FR_Wheel_Angle': -14.581385612487793, + 'Location': array([247.40681458, 158.88198853, 0.3017112 ]), + 'Rotation': array([-2.01422274e-02, -1.98555279e+01, -7.04956008e-03]), + 'Velocity': array([ 0.3885819 , -0.2161593 , 0.00059232]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.520263671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.31640625, 16589.79101562, 30. ]), + 'frame': 37710, + 'frame_number': 37710, + 'framesequence': 152073, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1279.9231898002326, + 'timestamp_carla': 1279928, + 'timestamp_device': 2898487, + 'timestamp_stream': 1279.9231898002326, + 'transform': [array([ 1.90002899e+02, 3.00255829e+02, -1.44327968e-01]), + array([-8.87924526e-03, -1.62407349e+02, 2.22167857e-02])]} +{'AngularVelocity': array([-0.06733882, -0.04453078, -2.37484384]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.734912872314453, + 'FR_Wheel_Angle': -14.407695770263672, + 'Location': array([247.49162292, 158.83763123, 0.30169287]), + 'Rotation': array([-2.08457354e-02, -2.03474407e+01, -8.20922945e-03]), + 'Velocity': array([ 3.78545612e-01, -2.11937308e-01, -2.97126768e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208129882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.34960938, 16589.69921875, 30. ]), + 'frame': 37711, + 'frame_number': 37711, + 'framesequence': 152077, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1279.9576139003038, + 'timestamp_carla': 1279962, + 'timestamp_device': 2898520, + 'timestamp_stream': 1279.9576139003038, + 'transform': [array([ 1.90003571e+02, 3.00254944e+02, -1.44338340e-01]), + array([-8.87924526e-03, -1.62407486e+02, 2.22167876e-02])]} +{'AngularVelocity': array([-0.03871324, 0.03324202, -2.57427526]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.85127067565918, + 'FR_Wheel_Angle': -16.728395462036133, + 'Location': array([247.57000732, 158.79576111, 0.30171692]), + 'Rotation': array([-2.10847929e-02, -2.08382816e+01, -7.04956101e-03]), + 'Velocity': array([ 3.23444813e-01, -2.01195121e-01, 8.25405077e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205688476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.38085938, 16589.60546875, 29.99993896]), + 'frame': 37712, + 'frame_number': 37712, + 'framesequence': 152081, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1279.991044100374, + 'timestamp_carla': 1279996, + 'timestamp_device': 2898553, + 'timestamp_stream': 1279.991044100374, + 'transform': [array([ 1.90003479e+02, 3.00253784e+02, -1.44336388e-01]), + array([-8.87924526e-03, -1.62407318e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.07244987, 0.03157158, -2.97794747]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.441360473632812, + 'FR_Wheel_Angle': -17.093395233154297, + 'Location': array([247.63876343, 158.75570679, 0.30171177]), + 'Rotation': array([-2.05383785e-02, -2.13925991e+01, -6.34765532e-03]), + 'Velocity': array([ 3.13359529e-01, -2.03771755e-01, 1.18336677e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5183715820312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.41015625, 16589.5078125 , 30. ]), + 'frame': 37713, + 'frame_number': 37713, + 'framesequence': 152085, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.0241278968751, + 'timestamp_carla': 1280029, + 'timestamp_device': 2898587, + 'timestamp_stream': 1280.0241278968751, + 'transform': [array([ 1.90003784e+02, 3.00252777e+02, -1.44332156e-01]), + array([-8.87924526e-03, -1.62407318e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.06934658, 0.03422348, -2.38767695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.75465202331543, + 'FR_Wheel_Angle': -17.36412811279297, + 'Location': array([247.71871948, 158.70773315, 0.30170193]), + 'Rotation': array([-2.03812830e-02, -2.20099983e+01, -7.17163086e-03]), + 'Velocity': array([ 3.13881099e-01, -2.09263250e-01, 1.48105619e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5187377929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.44335938, 16589.40429688, 30. ]), + 'frame': 37714, + 'frame_number': 37714, + 'framesequence': 152089, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.0572282001376, + 'timestamp_carla': 1280062, + 'timestamp_device': 2898620, + 'timestamp_stream': 1280.0572282001376, + 'transform': [array([ 1.90004105e+02, 3.00251709e+02, -1.44329906e-01]), + array([-8.87924526e-03, -1.62407318e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.08047345, 0.04524262, -2.14167142]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.853878021240234, + 'FR_Wheel_Angle': -17.642242431640625, + 'Location': array([247.79768372, 158.65921021, 0.3017081 ]), + 'Rotation': array([-2.17268299e-02, -2.26097584e+01, -8.45336914e-03]), + 'Velocity': array([ 2.86080003e-01, -1.94786072e-01, -1.46913531e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5195922851562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.47460938, 16589.30078125, 30. ]), + 'frame': 37715, + 'frame_number': 37715, + 'framesequence': 152093, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.0899815000594, + 'timestamp_carla': 1280095, + 'timestamp_device': 2898653, + 'timestamp_stream': 1280.0899815000594, + 'transform': [array([ 1.90004410e+02, 3.00250610e+02, -1.44326016e-01]), + array([-8.87924526e-03, -1.62407318e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.04981662, 0.02568302, -3.20550013]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.03457260131836, + 'FR_Wheel_Angle': -20.85016441345215, + 'Location': array([247.87417603, 158.61000061, 0.30169404]), + 'Rotation': array([-2.10847929e-02, -2.32695732e+01, -5.95092773e-03]), + 'Velocity': array([ 2.90436983e-01, -2.19528154e-01, -1.22108453e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.50585938, 16589.1953125 , 30. ]), + 'frame': 37716, + 'frame_number': 37716, + 'framesequence': 152097, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.1240690983832, + 'timestamp_carla': 1280129, + 'timestamp_device': 2898687, + 'timestamp_stream': 1280.1240690983832, + 'transform': [array([ 1.90005203e+02, 3.00249603e+02, -1.44333914e-01]), + array([-8.87924526e-03, -1.62407486e+02, 2.22167876e-02])]} +{'AngularVelocity': array([ 0.03234334, 0.02866855, -3.38943553]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.157888412475586, + 'FR_Wheel_Angle': -20.48843002319336, + 'Location': array([247.94618225, 158.56027222, 0.30171624]), + 'Rotation': array([-2.15765666e-02, -2.39646111e+01, -8.05664062e-03]), + 'Velocity': array([ 2.80136734e-01, -2.17665747e-01, 7.10153545e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208129882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.53710938, 16589.0859375 , 30. ]), + 'frame': 37717, + 'frame_number': 37717, + 'framesequence': 152101, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.1574504002929, + 'timestamp_carla': 1280162, + 'timestamp_device': 2898720, + 'timestamp_stream': 1280.1574504002929, + 'transform': [array([ 1.90005249e+02, 3.00248291e+02, -1.44332960e-01]), + array([-8.87924526e-03, -1.62407349e+02, 2.22167857e-02])]} +{'AngularVelocity': array([-0.00215562, 0.00202676, -1.73487604]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.075027465820312, + 'FR_Wheel_Angle': -20.348861694335938, + 'Location': array([248.01531982, 158.51133728, 0.30171496]), + 'Rotation': array([-2.16107182e-02, -2.46112461e+01, -8.57543759e-03]), + 'Velocity': array([ 2.81202793e-01, -2.20648170e-01, 9.13906042e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5192260742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.57617188, 16588.97070312, 30. ]), + 'frame': 37718, + 'frame_number': 37718, + 'framesequence': 152105, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.190605700016, + 'timestamp_carla': 1280195, + 'timestamp_device': 2898753, + 'timestamp_stream': 1280.190605700016, + 'transform': [array([ 1.90005646e+02, 3.00247131e+02, -1.44330829e-01]), + array([-8.87924526e-03, -1.62407349e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.10424417, 0.00778089, -1.91480207]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.43178939819336, + 'FR_Wheel_Angle': -22.578025817871094, + 'Location': array([248.08311462, 158.46235657, 0.30170143]), + 'Rotation': array([-2.09686793e-02, -2.52869987e+01, -7.81249953e-03]), + 'Velocity': array([ 2.59081841e-01, -2.07673579e-01, -1.42011646e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5194702148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.61523438, 16588.8515625 , 30. ]), + 'frame': 37719, + 'frame_number': 37719, + 'framesequence': 152109, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00016479995974805206, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.2256044968963, + 'timestamp_carla': 1280230, + 'timestamp_device': 2898787, + 'timestamp_stream': 1280.2256044968963, + 'transform': [array([ 1.90006760e+02, 3.00246155e+02, -1.44343749e-01]), + array([-8.87924526e-03, -1.62407639e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.09985285, 0.02349387, -3.21167541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.782129287719727, + 'FR_Wheel_Angle': -22.83026885986328, + 'Location': array([248.15097046, 158.40921021, 0.30170658]), + 'Rotation': array([-2.09345277e-02, -2.60725212e+01, -6.92748930e-03]), + 'Velocity': array([ 2.49132365e-01, -2.23473951e-01, 4.81605530e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.65429688, 16588.734375 , 29.99996948]), + 'frame': 37720, + 'frame_number': 37720, + 'framesequence': 152113, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.001647999626584351, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.2592685967684, + 'timestamp_carla': 1280264, + 'timestamp_device': 2898820, + 'timestamp_stream': 1280.2592685967684, + 'transform': [array([ 1.90006714e+02, 3.00244751e+02, -1.44339904e-01]), + array([-8.87924526e-03, -1.62407471e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.13141774, 0.01604408, -2.85583735]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.10222625732422, + 'FR_Wheel_Angle': -23.053749084472656, + 'Location': array([248.22622681, 158.3482666 , 0.30169666]), + 'Rotation': array([-2.07227934e-02, -2.69515533e+01, -7.69042969e-03]), + 'Velocity': array([ 2.44280353e-01, -2.22529590e-01, -1.69363018e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.517333984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.69335938, 16588.61328125, 30. ]), + 'frame': 37721, + 'frame_number': 37721, + 'framesequence': 152117, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.010180975310504436, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.2930441983044, + 'timestamp_carla': 1280298, + 'timestamp_device': 2898853, + 'timestamp_stream': 1280.2930441983044, + 'transform': [array([ 1.90007599e+02, 3.00243652e+02, -1.44334108e-01]), + array([-8.85192491e-03, -1.62407669e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.09501655, 0.02194561, -3.11275434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.209056854248047, + 'FR_Wheel_Angle': -23.386178970336914, + 'Location': array([248.282547 , 158.30075073, 0.30170467]), + 'Rotation': array([-2.05998495e-02, -2.76410713e+01, -7.50732375e-03]), + 'Velocity': array([ 2.46202424e-01, -2.35592663e-01, -2.17437744e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.518310546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.73242188, 16588.48828125, 30. ]), + 'frame': 37722, + 'frame_number': 37722, + 'framesequence': 152121, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.02146061696112156, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1280.3247961997986, + 'timestamp_carla': 1280329, + 'timestamp_device': 2898887, + 'timestamp_stream': 1280.3247961997986, + 'transform': [array([ 1.90008713e+02, 3.00242676e+02, -1.44386634e-01]), + array([-8.79045296e-03, -1.62407990e+02, 2.21862681e-02])]} +{'AngularVelocity': array([ 0.09796269, 0.01675093, -3.67254257]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.3380241394043, + 'FR_Wheel_Angle': -26.13661003112793, + 'Location': array([248.35604858, 158.23457336, 0.3017067 ]), + 'Rotation': array([-2.12692078e-02, -2.86354599e+01, -6.10351562e-03]), + 'Velocity': array([ 2.27045879e-01, -2.48533726e-01, -1.42955774e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184326171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.76953125, 16588.359375 , 30. ]), + 'frame': 37723, + 'frame_number': 37723, + 'framesequence': 152124, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03510238975286484, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.3573953993618, + 'timestamp_carla': 1280362, + 'timestamp_device': 2898912, + 'timestamp_stream': 1280.3573953993618, + 'transform': [array([ 1.90011795e+02, 3.00242371e+02, -1.44455642e-01]), + array([-8.76313262e-03, -1.62409149e+02, 2.21557524e-02])]} +{'AngularVelocity': array([ 0.08086304, 0.01511249, -3.91956234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.524383544921875, + 'FR_Wheel_Angle': -25.862672805786133, + 'Location': array([248.41770935, 158.17544556, 0.30170602]), + 'Rotation': array([-2.11462639e-02, -2.95520687e+01, -7.93457124e-03]), + 'Velocity': array([ 0.22613917, -0.25006124, 0.00042052]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5217895507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.80859375, 16588.23242188, 30. ]), + 'frame': 37724, + 'frame_number': 37724, + 'framesequence': 152129, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04914701357483864, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.3909700997174, + 'timestamp_carla': 1280396, + 'timestamp_device': 2898953, + 'timestamp_stream': 1280.3909700997174, + 'transform': [array([ 1.90016083e+02, 3.00242401e+02, -1.44453615e-01]), + array([-8.70166067e-03, -1.62410812e+02, 2.21557524e-02])]} +{'AngularVelocity': array([-0.03984745, 0.03150231, -3.78565359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.39515686035156, + 'FR_Wheel_Angle': -25.755218505859375, + 'Location': array([248.47772217, 158.11607361, 0.30171019]), + 'Rotation': array([-2.12077368e-02, -3.04208107e+01, -7.87353422e-03]), + 'Velocity': array([ 2.32215509e-01, -2.73324102e-01, 3.83281695e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.522705078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.84765625, 16588.09960938, 29.99996948]), + 'frame': 37725, + 'frame_number': 37725, + 'framesequence': 152133, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06526078283786774, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.4248287975788, + 'timestamp_carla': 1280429, + 'timestamp_device': 2898987, + 'timestamp_stream': 1280.4248287975788, + 'transform': [array([ 1.90021484e+02, 3.00242889e+02, -1.44375384e-01]), + array([-8.64018872e-03, -1.62412949e+02, 2.21862681e-02])]} +{'AngularVelocity': array([-1.04464740e-01, -3.56800784e-03, -4.40623331e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.1419677734375, + 'FR_Wheel_Angle': -28.094898223876953, + 'Location': array([248.53511047, 158.05708313, 0.30170602]), + 'Rotation': array([-2.08457354e-02, -3.13041515e+01, -6.62231538e-03]), + 'Velocity': array([ 2.48278186e-01, -3.01010400e-01, 2.84328446e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5216064453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.8828125, 16587.9609375, 30. ]), + 'frame': 37726, + 'frame_number': 37726, + 'framesequence': 152137, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.08168584853410721, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.4581802003086, + 'timestamp_carla': 1280463, + 'timestamp_device': 2899020, + 'timestamp_stream': 1280.4581802003086, + 'transform': [array([ 1.90027695e+02, 3.00243713e+02, -1.44290924e-01]), + array([-8.57188739e-03, -1.62415451e+02, 2.22167838e-02])]} +{'AngularVelocity': array([-0.08707901, -0.01403191, -4.25516224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.112648010253906, + 'FR_Wheel_Angle': -28.104679107666016, + 'Location': array([248.58813477, 157.99679565, 0.30170473]), + 'Rotation': array([-2.09345277e-02, -3.22443123e+01, -7.14111328e-03]), + 'Velocity': array([ 2.32249007e-01, -3.00279170e-01, -1.46989812e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.520263671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.91992188, 16587.82226562, 30.00003052]), + 'frame': 37727, + 'frame_number': 37727, + 'framesequence': 152141, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09717704355716705, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.4908547997475, + 'timestamp_carla': 1280495, + 'timestamp_device': 2899053, + 'timestamp_stream': 1280.4908547997475, + 'transform': [array([ 1.90034821e+02, 3.00244843e+02, -1.44201651e-01]), + array([-8.51041544e-03, -1.62418396e+02, 2.22473051e-02])]} +{'AngularVelocity': array([-0.10197783, -0.00868273, -4.39344645]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.50975036621094, + 'FR_Wheel_Angle': -28.313182830810547, + 'Location': array([248.63772583, 157.93850708, 0.30170745]), + 'Rotation': array([-2.08115857e-02, -3.31266632e+01, -7.87353422e-03]), + 'Velocity': array([ 2.22009614e-01, -2.96391189e-01, 1.17759701e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.95703125, 16587.68359375, 29.99996948]), + 'frame': 37728, + 'frame_number': 37728, + 'framesequence': 152145, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11224707961082458, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.5233572982252, + 'timestamp_carla': 1280528, + 'timestamp_device': 2899087, + 'timestamp_stream': 1280.5233572982252, + 'transform': [array([ 1.90043274e+02, 3.00246490e+02, -1.44117966e-01]), + array([-8.48309416e-03, -1.62421860e+02, 2.22778227e-02])]} +{'AngularVelocity': array([-9.25074071e-02, -2.54317140e-03, -4.10087252e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.7464714050293, + 'FR_Wheel_Angle': -28.77784538269043, + 'Location': array([248.686203 , 157.87988281, 0.30171257]), + 'Rotation': array([-2.07842644e-02, -3.40155182e+01, -7.87353516e-03]), + 'Velocity': array([ 0.21026008, -0.29301891, 0.00040704]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5217895507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.98242188, 16587.54296875, 29.99996948]), + 'frame': 37729, + 'frame_number': 37729, + 'framesequence': 152148, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12872707843780518, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.5565411001444, + 'timestamp_carla': 1280561, + 'timestamp_device': 2899112, + 'timestamp_stream': 1280.5565411001444, + 'transform': [array([ 1.90053467e+02, 3.00248779e+02, -1.44040868e-01]), + array([-8.45577382e-03, -1.62426102e+02, 2.23083403e-02])]} +{'AngularVelocity': array([-1.00310184e-01, 1.41656383e-05, -4.72444725e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.79648971557617, + 'FR_Wheel_Angle': -30.661998748779297, + 'Location': array([248.73091125, 157.82194519, 0.30170792]), + 'Rotation': array([-2.06340011e-02, -3.49531326e+01, -6.22558640e-03]), + 'Velocity': array([ 0.19305605, -0.30091292, 0.00051984]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5225219726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.00976562, 16587.40429688, 29.99996948]), + 'frame': 37730, + 'frame_number': 37730, + 'framesequence': 152153, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14419996738433838, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.5907390974462, + 'timestamp_carla': 1280595, + 'timestamp_device': 2899153, + 'timestamp_stream': 1280.5907390974462, + 'transform': [array([ 1.90065231e+02, 3.00251587e+02, -1.43970519e-01]), + array([-8.42162315e-03, -1.62431015e+02, 2.23388560e-02])]} +{'AngularVelocity': array([-1.07246570e-01, 4.39717760e-03, -4.74584484e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.798770904541016, + 'FR_Wheel_Angle': -30.86390495300293, + 'Location': array([248.77430725, 157.76235962, 0.3017031 ]), + 'Rotation': array([-2.03471333e-02, -3.59385948e+01, -6.95800781e-03]), + 'Velocity': array([ 1.89010203e-01, -3.05997223e-01, -3.80611418e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521728515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.03710938, 16587.26757812, 30. ]), + 'frame': 37731, + 'frame_number': 37731, + 'framesequence': 152157, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16040529310703278, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.6242761984468, + 'timestamp_carla': 1280629, + 'timestamp_device': 2899187, + 'timestamp_stream': 1280.6242761984468, + 'transform': [array([ 1.90077362e+02, 3.00254578e+02, -1.43890649e-01]), + array([-8.39430187e-03, -1.62436081e+02, 2.23693717e-02])]} +{'AngularVelocity': array([-0.10259352, 0.00542477, -4.70503092]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.797821044921875, + 'FR_Wheel_Angle': -30.865070343017578, + 'Location': array([248.81636047, 157.70210266, 0.30171096]), + 'Rotation': array([-2.02924907e-02, -3.69199638e+01, -7.14111328e-03]), + 'Velocity': array([ 1.83555812e-01, -3.09462070e-01, -7.92503306e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5201416015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.06054688, 16587.12304688, 29.99996948]), + 'frame': 37732, + 'frame_number': 37732, + 'framesequence': 152160, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1770867109298706, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.656844496727, + 'timestamp_carla': 1280661, + 'timestamp_device': 2899212, + 'timestamp_stream': 1280.656844496727, + 'transform': [array([ 1.90090134e+02, 3.00257843e+02, -1.43803790e-01]), + array([-8.36015120e-03, -1.62441452e+02, 2.23998912e-02])]} +{'AngularVelocity': array([-0.10749379, 0.00975812, -4.72354603]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.80031204223633, + 'FR_Wheel_Angle': -30.862716674804688, + 'Location': array([248.85751343, 157.64093018, 0.30170047]), + 'Rotation': array([-2.02651694e-02, -3.79072342e+01, -7.38525437e-03]), + 'Velocity': array([ 1.78333893e-01, -3.11862469e-01, -2.11286533e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.08398438, 16586.97851562, 30. ]), + 'frame': 37733, + 'frame_number': 37733, + 'framesequence': 152164, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1926511526107788, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.6897665970027, + 'timestamp_carla': 1280694, + 'timestamp_device': 2899245, + 'timestamp_stream': 1280.6897665970027, + 'transform': [array([ 1.90104767e+02, 3.00261841e+02, -1.43726379e-01]), + array([-8.36015120e-03, -1.62447632e+02, 2.24304087e-02])]} +{'AngularVelocity': array([-0.1040118 , 0.01113206, -4.70342159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.79962921142578, + 'FR_Wheel_Angle': -30.862972259521484, + 'Location': array([248.89181519, 157.58808899, 0.30170548]), + 'Rotation': array([-2.02651694e-02, -3.87491531e+01, -7.38525437e-03]), + 'Velocity': array([ 1.73299134e-01, -3.14245343e-01, 3.72982031e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213623046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.10351562, 16586.83984375, 30.00003052]), + 'frame': 37734, + 'frame_number': 37734, + 'framesequence': 152169, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.20896635949611664, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.723742198199, + 'timestamp_carla': 1280728, + 'timestamp_device': 2899287, + 'timestamp_stream': 1280.723742198199, + 'transform': [array([ 1.90121292e+02, 3.00266449e+02, -1.43733487e-01]), + array([-8.36015120e-03, -1.62454605e+02, 2.24304087e-02])]} +{'AngularVelocity': array([-0.10877096, 0.01005846, -4.74392366]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.79997253417969, + 'FR_Wheel_Angle': -30.863645553588867, + 'Location': array([248.93626404, 157.51687622, 0.30170333]), + 'Rotation': array([-2.03812830e-02, -3.98636971e+01, -7.44629046e-03]), + 'Velocity': array([ 1.66373864e-01, -3.16250265e-01, -1.08623499e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.521484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.11914062, 16586.70117188, 30.00003052]), + 'frame': 37735, + 'frame_number': 37735, + 'framesequence': 152173, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2256660759449005, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.7577113993466, + 'timestamp_carla': 1280762, + 'timestamp_device': 2899320, + 'timestamp_stream': 1280.7577113993466, + 'transform': [array([ 1.90138550e+02, 3.00271362e+02, -1.43737212e-01]), + array([-8.36015120e-03, -1.62461914e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.10663934, 0.01440734, -4.69394541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.79978561401367, + 'FR_Wheel_Angle': -30.866182327270508, + 'Location': array([248.96847534, 157.4634552 , 0.30170149]), + 'Rotation': array([-2.03471333e-02, -4.06956444e+01, -7.56835938e-03]), + 'Velocity': array([ 1.61182031e-01, -3.17199260e-01, -1.69754026e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.13085938, 16586.55859375, 30.00003052]), + 'frame': 37736, + 'frame_number': 37736, + 'framesequence': 152177, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24112065136432648, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.7909983992577, + 'timestamp_carla': 1280796, + 'timestamp_device': 2899353, + 'timestamp_stream': 1280.7909983992577, + 'transform': [array([ 1.90156326e+02, 3.00276428e+02, -1.43733785e-01]), + array([-8.36015120e-03, -1.62469437e+02, 2.24304069e-02])]} +{'AngularVelocity': array([-0.09906734, 0.01474291, -4.35609055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.81007385253906, + 'FR_Wheel_Angle': -30.871810913085938, + 'Location': array([249.00442505, 157.40107727, 0.30170757]), + 'Rotation': array([-2.08115857e-02, -4.16322441e+01, -7.99560640e-03]), + 'Velocity': array([ 1.49239227e-01, -3.08653802e-01, 1.10321045e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5194091796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.14453125, 16586.41601562, 30. ]), + 'frame': 37737, + 'frame_number': 37737, + 'framesequence': 152181, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25855281949043274, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.824144396931, + 'timestamp_carla': 1280829, + 'timestamp_device': 2899387, + 'timestamp_stream': 1280.824144396931, + 'transform': [array([ 1.90175308e+02, 3.00282013e+02, -1.43730849e-01]), + array([-8.36015120e-03, -1.62477509e+02, 2.24304125e-02])]} +{'AngularVelocity': array([-0.10468242, 0.01815983, -4.50603056]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.80887222290039, + 'FR_Wheel_Angle': -30.871688842773438, + 'Location': array([249.0385437 , 157.33998108, 0.30170411]), + 'Rotation': array([-2.04086043e-02, -4.25581818e+01, -7.72094727e-03]), + 'Velocity': array([ 1.45840660e-01, -3.11792940e-01, 1.53856279e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.16015625, 16586.2734375 , 29.99996948]), + 'frame': 37738, + 'frame_number': 37738, + 'framesequence': 152185, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.27426373958587646, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.8560228981078, + 'timestamp_carla': 1280861, + 'timestamp_device': 2899420, + 'timestamp_stream': 1280.8560228981078, + 'transform': [array([ 1.90194443e+02, 3.00287720e+02, -1.43716201e-01]), + array([-8.33282992e-03, -1.62485626e+02, 2.24304087e-02])]} +{'AngularVelocity': array([-0.10583911, 0.01924025, -4.61618137]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.809165954589844, + 'FR_Wheel_Angle': -30.870342254638672, + 'Location': array([249.07177734, 157.27819824, 0.30170643]), + 'Rotation': array([-2.02036984e-02, -4.34993210e+01, -7.41577148e-03]), + 'Velocity': array([ 1.42212585e-01, -3.16871822e-01, -1.69277191e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206298828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.16601562, 16586.12890625, 30.00003052]), + 'frame': 37739, + 'frame_number': 37739, + 'framesequence': 152189, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2893521189689636, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.8903724998236, + 'timestamp_carla': 1280895, + 'timestamp_device': 2899453, + 'timestamp_stream': 1280.8903724998236, + 'transform': [array([ 1.90217499e+02, 3.00294769e+02, -1.43728450e-01]), + array([-8.33282992e-03, -1.62495407e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.0975705 , 0.02022892, -4.22255611]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.814842224121094, + 'FR_Wheel_Angle': -30.871322631835938, + 'Location': array([249.10800171, 157.20751953, 0.30171534]), + 'Rotation': array([-2.08115857e-02, -4.45356522e+01, -7.96508696e-03]), + 'Velocity': array([ 0.12924805, -0.306611 , 0.00031278]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5228881835938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.17578125, 16585.99414062, 30. ]), + 'frame': 37740, + 'frame_number': 37740, + 'framesequence': 152193, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3062898516654968, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.9249547980726, + 'timestamp_carla': 1280929, + 'timestamp_device': 2899486, + 'timestamp_stream': 1280.9249547980726, + 'transform': [array([ 1.90240936e+02, 3.00301941e+02, -1.43737257e-01]), + array([-8.33282992e-03, -1.62505402e+02, 2.24304087e-02])]} +{'AngularVelocity': array([-0.10715988, 0.02119259, -4.36796761]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.82212829589844, + 'FR_Wheel_Angle': -30.874643325805664, + 'Location': array([249.1333313 , 157.15664673, 0.30171248]), + 'Rotation': array([-2.06613205e-02, -4.52890778e+01, -7.78198196e-03]), + 'Velocity': array([ 0.12483203, -0.304867 , 0.00035353]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5204467773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.1796875 , 16585.84960938, 30. ]), + 'frame': 37741, + 'frame_number': 37741, + 'framesequence': 152197, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3238135874271393, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.959069699049, + 'timestamp_carla': 1280964, + 'timestamp_device': 2899520, + 'timestamp_stream': 1280.959069699049, + 'transform': [array([ 1.90265076e+02, 3.00309448e+02, -1.43737823e-01]), + array([-8.33282992e-03, -1.62515686e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.10329685, 0.0232951 , -4.46670675]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.818397521972656, + 'FR_Wheel_Angle': -30.87456703186035, + 'Location': array([249.16270447, 157.09550476, 0.30171016]), + 'Rotation': array([-2.00534351e-02, -4.62058792e+01, -7.17163133e-03]), + 'Velocity': array([ 1.23320125e-01, -3.13998640e-01, -4.38976276e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5187377929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.18164062, 16585.70507812, 30. ]), + 'frame': 37742, + 'frame_number': 37742, + 'framesequence': 152201, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.34014710783958435, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1280.9915305003524, + 'timestamp_carla': 1280996, + 'timestamp_device': 2899553, + 'timestamp_stream': 1280.9915305003524, + 'transform': [array([ 1.90288742e+02, 3.00316833e+02, -1.43725812e-01]), + array([-8.33282992e-03, -1.62525772e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.10330166, 0.02618896, -4.48598528]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.81398010253906, + 'FR_Wheel_Angle': -30.872312545776367, + 'Location': array([249.19128418, 157.03338623, 0.30170801]), + 'Rotation': array([-2.00807545e-02, -4.71256218e+01, -7.23266555e-03]), + 'Velocity': array([ 1.18345752e-01, -3.16468716e-01, 1.21645928e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184936523438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.1796875 , 16585.56640625, 30. ]), + 'frame': 37743, + 'frame_number': 37743, + 'framesequence': 152205, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3549058735370636, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.0253112986684, + 'timestamp_carla': 1281030, + 'timestamp_device': 2899586, + 'timestamp_stream': 1281.0253112986684, + 'transform': [array([ 1.90315506e+02, 3.00325317e+02, -1.43728524e-01]), + array([-8.33282992e-03, -1.62537201e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.10369897, 0.02914691, -4.44543982]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.812957763671875, + 'FR_Wheel_Angle': -30.876384735107422, + 'Location': array([249.21920776, 156.97003174, 0.30169708]), + 'Rotation': array([-2.02036984e-02, -4.80545464e+01, -7.53784226e-03]), + 'Velocity': array([ 1.12586714e-01, -3.16181809e-01, 1.99279777e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208740234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.1796875 , 16585.43164062, 30. ]), + 'frame': 37744, + 'frame_number': 37744, + 'framesequence': 152210, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3713309168815613, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.0718967989087, + 'timestamp_carla': 1281076, + 'timestamp_device': 2899628, + 'timestamp_stream': 1281.0718967989087, + 'transform': [array([ 1.90382477e+02, 3.00348206e+02, -1.43776849e-01]), + array([-8.42162315e-03, -1.62565826e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.10314424, 0.03093123, -4.50504112]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.810089111328125, + 'FR_Wheel_Angle': -30.87215232849121, + 'Location': array([249.24609375, 156.90638733, 0.30170366]), + 'Rotation': array([-1.99578125e-02, -4.89869919e+01, -7.26318313e-03]), + 'Velocity': array([ 1.09153301e-01, -3.22918117e-01, -2.71987901e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.17578125, 16585.29101562, 29.99996948]), + 'frame': 37745, + 'frame_number': 37745, + 'framesequence': 152214, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.394879013299942, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.1018748991191, + 'timestamp_carla': 1281106, + 'timestamp_device': 2899661, + 'timestamp_stream': 1281.1018748991191, + 'transform': [array([ 1.90374878e+02, 3.00344055e+02, -1.43721387e-01]), + array([-8.33282992e-03, -1.62562546e+02, 2.24609282e-02])]} +{'AngularVelocity': array([ 0.06962246, -0.00418174, -3.16253042]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.773075103759766, + 'FR_Wheel_Angle': -30.845115661621094, + 'Location': array([249.27114868, 156.84411621, 0.3017025 ]), + 'Rotation': array([-2.09345277e-02, -4.98776932e+01, -8.14819336e-03]), + 'Velocity': array([ 7.26174340e-02, -2.53566474e-01, 2.38761902e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5128784179688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.15234375, 16585.11132812, 30.00003052]), + 'frame': 37746, + 'frame_number': 37746, + 'framesequence': 152218, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.40897855162620544, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.1313729994, + 'timestamp_carla': 1281136, + 'timestamp_device': 2899695, + 'timestamp_stream': 1281.1313729994, + 'transform': [array([ 1.90430939e+02, 3.00363678e+02, -1.43673703e-01]), + array([-8.45577382e-03, -1.62586533e+02, 2.24914439e-02])]} +{'AngularVelocity': array([ 0.105395 , -0.03633184, -3.55090213]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76316833496094, + 'FR_Wheel_Angle': -30.844472885131836, + 'Location': array([249.29556274, 156.78083801, 0.30170867]), + 'Rotation': array([-2.03812830e-02, -5.07968330e+01, -7.93456938e-03]), + 'Velocity': array([ 7.37396255e-02, -2.57901341e-01, -8.55541221e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5066528320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.15820312, 16584.98632812, 30. ]), + 'frame': 37747, + 'frame_number': 37747, + 'framesequence': 152221, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42289501428604126, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.161929398775, + 'timestamp_carla': 1281167, + 'timestamp_device': 2899720, + 'timestamp_stream': 1281.161929398775, + 'transform': [array([ 1.90461746e+02, 3.00373810e+02, -1.43762171e-01]), + array([-8.42162315e-03, -1.62599716e+02, 2.24304125e-02])]} +{'AngularVelocity': array([ 0.11171687, -0.03895197, -3.31800961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.766239166259766, + 'FR_Wheel_Angle': -30.84369468688965, + 'Location': array([249.31913757, 156.71630859, 0.30169725]), + 'Rotation': array([-2.06340011e-02, -5.17129364e+01, -8.30078032e-03]), + 'Velocity': array([ 6.79222345e-02, -2.53947854e-01, -1.34582515e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5038452148438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.1328125 , 16584.88085938, 30. ]), + 'frame': 37748, + 'frame_number': 37748, + 'framesequence': 152225, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4386425316333771, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.1906419992447, + 'timestamp_carla': 1281195, + 'timestamp_device': 2899753, + 'timestamp_stream': 1281.1906419992447, + 'transform': [array([ 1.90458359e+02, 3.00371307e+02, -1.43760875e-01]), + array([-8.27135891e-03, -1.62598251e+02, 2.24304087e-02])]} +{'AngularVelocity': array([ 0.10823485, -0.04007398, -3.38574576]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.764251708984375, + 'FR_Wheel_Angle': -30.844009399414062, + 'Location': array([249.34486389, 156.64233398, 0.30170107]), + 'Rotation': array([-2.06340011e-02, -5.27645988e+01, -8.27026367e-03]), + 'Velocity': array([ 6.37668148e-02, -2.57074416e-01, -7.20024109e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5158081054688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.11914062, 16584.74609375, 30. ]), + 'frame': 37749, + 'frame_number': 37749, + 'framesequence': 152229, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4518814980983734, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.224981598556, + 'timestamp_carla': 1281230, + 'timestamp_device': 2899786, + 'timestamp_stream': 1281.224981598556, + 'transform': [array([ 1.90494415e+02, 3.00383209e+02, -1.43955529e-01]), + array([-8.18256661e-03, -1.62613693e+02, 2.23388597e-02])]} +{'AngularVelocity': array([ 0.09403317, -0.03742232, -3.5700891 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.763370513916016, + 'FR_Wheel_Angle': -30.8421573638916, + 'Location': array([249.36610413, 156.57739258, 0.30171311]), + 'Rotation': array([-2.05383785e-02, -5.36795959e+01, -8.02612305e-03]), + 'Velocity': array([ 6.09193593e-02, -2.64315456e-01, 1.07374188e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.512451171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.12304688, 16584.625 , 30. ]), + 'frame': 37750, + 'frame_number': 37750, + 'framesequence': 152233, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46861782670021057, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.2574623003602, + 'timestamp_carla': 1281262, + 'timestamp_device': 2899820, + 'timestamp_stream': 1281.2574623003602, + 'transform': [array([ 1.90530106e+02, 3.00394928e+02, -1.44150272e-01]), + array([-8.12109467e-03, -1.62628983e+02, 2.22473014e-02])]} +{'AngularVelocity': array([ 0.11001925, -0.04769734, -3.42935252]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.762638092041016, + 'FR_Wheel_Angle': -30.84440803527832, + 'Location': array([249.3865509 , 156.51141357, 0.30169624]), + 'Rotation': array([-2.06613205e-02, -5.46021347e+01, -8.33130069e-03]), + 'Velocity': array([ 5.59869520e-02, -2.58879274e-01, -1.91097250e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5172119140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.10546875, 16584.4765625 , 30. ]), + 'frame': 37751, + 'frame_number': 37751, + 'framesequence': 152237, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4845667779445648, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.2908658981323, + 'timestamp_carla': 1281295, + 'timestamp_device': 2899853, + 'timestamp_stream': 1281.2908658981323, + 'transform': [array([ 1.90568787e+02, 3.00407623e+02, -1.44218907e-01]), + array([-8.12109467e-03, -1.62645554e+02, 2.22167857e-02])]} +{'AngularVelocity': array([ 0.10156003, -0.04498581, -3.4950161 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76203155517578, + 'FR_Wheel_Angle': -30.843175888061523, + 'Location': array([249.40586853, 156.44528198, 0.30170318]), + 'Rotation': array([-2.05998495e-02, -5.55296516e+01, -8.11767485e-03]), + 'Velocity': array([ 5.22769243e-02, -2.64176905e-01, 4.35829170e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5224609375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.08984375, 16584.328125 , 30. ]), + 'frame': 37752, + 'frame_number': 37752, + 'framesequence': 152241, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5009003281593323, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.3233345970511, + 'timestamp_carla': 1281328, + 'timestamp_device': 2899886, + 'timestamp_stream': 1281.3233345970511, + 'transform': [array([ 1.90606873e+02, 3.00420227e+02, -1.44208983e-01]), + array([-8.12109467e-03, -1.62661880e+02, 2.22167876e-02])]} +{'AngularVelocity': array([ 0.07812466, -0.03186513, -3.75360632]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76347351074219, + 'FR_Wheel_Angle': -30.840972900390625, + 'Location': array([249.42410278, 156.37879944, 0.30171385]), + 'Rotation': array([-2.06340011e-02, -5.64540596e+01, -7.99560454e-03]), + 'Velocity': array([ 0.04838656, -0.27175251, 0.00029071]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52392578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.0625 , 16584.17578125, 29.99996948]), + 'frame': 37753, + 'frame_number': 37753, + 'framesequence': 152244, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5167394280433655, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.3559964969754, + 'timestamp_carla': 1281361, + 'timestamp_device': 2899911, + 'timestamp_stream': 1281.3559964969754, + 'transform': [array([ 1.90646545e+02, 3.00433380e+02, -1.44133866e-01]), + array([-8.14841501e-03, -1.62678879e+02, 2.22473014e-02])]} +{'AngularVelocity': array([ 0.06652807, -0.02008009, -3.54755521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.763790130615234, + 'FR_Wheel_Angle': -30.840248107910156, + 'Location': array([249.44129944, 156.31192017, 0.30171347]), + 'Rotation': array([-2.06340011e-02, -5.73767204e+01, -7.87353609e-03]), + 'Velocity': array([ 0.04293168, -0.27423251, 0.00042361]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5258178710938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.0390625, 16584.03125 , 30. ]), + 'frame': 37754, + 'frame_number': 37754, + 'framesequence': 152249, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5328531861305237, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.3907335996628, + 'timestamp_carla': 1281395, + 'timestamp_device': 2899953, + 'timestamp_stream': 1281.3907335996628, + 'transform': [array([ 1.90690002e+02, 3.00447876e+02, -1.44077763e-01]), + array([-8.18256661e-03, -1.62697525e+02, 2.22778246e-02])]} +{'AngularVelocity': array([ 0.09235319, -0.04254343, -3.65434861]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76115417480469, + 'FR_Wheel_Angle': -30.84039878845215, + 'Location': array([249.45768738, 156.24415588, 0.30170867]), + 'Rotation': array([-2.05998495e-02, -5.83217239e+01, -8.08715820e-03]), + 'Velocity': array([ 4.03758846e-02, -2.71627128e-01, 1.23996739e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5265502929688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23985.01171875, 16583.88671875, 30. ]), + 'frame': 37755, + 'frame_number': 37755, + 'framesequence': 152253, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5494064688682556, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.423414800316, + 'timestamp_carla': 1281428, + 'timestamp_device': 2899986, + 'timestamp_stream': 1281.423414800316, + 'transform': [array([ 1.90730927e+02, 3.00461517e+02, -1.43999591e-01]), + array([-8.20988696e-03, -1.62715088e+02, 2.23083403e-02])]} +{'AngularVelocity': array([ 0.09467974, -0.04476059, -3.44736433]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.75871276855469, + 'FR_Wheel_Angle': -30.84193992614746, + 'Location': array([249.47302246, 156.175354 , 0.30170363]), + 'Rotation': array([-2.06613205e-02, -5.92665863e+01, -8.05664156e-03]), + 'Velocity': array([ 3.49625237e-02, -2.72383630e-01, -3.77750403e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5230712890625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.9765625 , 16583.73828125, 30. ]), + 'frame': 37756, + 'frame_number': 37756, + 'framesequence': 152257, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5559800863265991, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.4571017995477, + 'timestamp_carla': 1281462, + 'timestamp_device': 2900020, + 'timestamp_stream': 1281.4571017995477, + 'transform': [array([ 1.90774567e+02, 3.00476135e+02, -1.43932492e-01]), + array([-8.24403763e-03, -1.62733780e+02, 2.23388616e-02])]} +{'AngularVelocity': array([ 0.09368767, -0.0429669 , -2.98310614]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.77111053466797, + 'FR_Wheel_Angle': -30.84912872314453, + 'Location': array([249.48629761, 156.10853577, 0.30170891]), + 'Rotation': array([-2.13306788e-02, -6.01367645e+01, -8.85009766e-03]), + 'Velocity': array([ 2.69307438e-02, -2.56303102e-01, -6.24752065e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5244140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.94726562, 16583.59570312, 30. ]), + 'frame': 37757, + 'frame_number': 37757, + 'framesequence': 152261, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5526108741760254, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.4900319986045, + 'timestamp_carla': 1281495, + 'timestamp_device': 2900053, + 'timestamp_stream': 1281.4900319986045, + 'transform': [array([ 1.90816681e+02, 3.00490143e+02, -1.43938288e-01]), + array([-8.30550957e-03, -1.62751846e+02, 2.23388579e-02])]} +{'AngularVelocity': array([ 0.10729574, -0.06277221, -3.35315084]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76548385620117, + 'FR_Wheel_Angle': -30.84626007080078, + 'Location': array([249.49876404, 156.04278564, 0.30169499]), + 'Rotation': array([-2.06954721e-02, -6.10340805e+01, -8.45337007e-03]), + 'Velocity': array([ 0.02629364, -0.257617 , -0.00026305]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.523193359375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.9140625 , 16583.45117188, 29.99996948]), + 'frame': 37758, + 'frame_number': 37758, + 'framesequence': 152265, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5451033115386963, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.5232679992914, + 'timestamp_carla': 1281528, + 'timestamp_device': 2900086, + 'timestamp_stream': 1281.5232679992914, + 'transform': [array([ 1.90859131e+02, 3.00504303e+02, -1.43951878e-01]), + array([-8.39430187e-03, -1.62770050e+02, 2.23388579e-02])]} +{'AngularVelocity': array([ 0.09977013, -0.05957354, -3.42598486]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76337432861328, + 'FR_Wheel_Angle': -30.84459686279297, + 'Location': array([249.51048279, 155.97612 , 0.30170512]), + 'Rotation': array([-2.05725282e-02, -6.19518471e+01, -8.08715820e-03]), + 'Velocity': array([ 2.24817954e-02, -2.63921320e-01, -1.68132785e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5235595703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.88085938, 16583.31054688, 29.99996948]), + 'frame': 37759, + 'frame_number': 37759, + 'framesequence': 152269, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5370647311210632, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.5566393993795, + 'timestamp_carla': 1281561, + 'timestamp_device': 2900120, + 'timestamp_stream': 1281.5566393993795, + 'transform': [array([ 1.90900970e+02, 3.00518188e+02, -1.43966362e-01]), + array([-8.48309416e-03, -1.62787979e+02, 2.23388541e-02])]} +{'AngularVelocity': array([ 0.09735031, -0.06170469, -3.47583103]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.763065338134766, + 'FR_Wheel_Angle': -30.84372901916504, + 'Location': array([249.52102661, 155.90908813, 0.30170894]), + 'Rotation': array([-2.05383785e-02, -6.28591347e+01, -8.02612305e-03]), + 'Velocity': array([ 1.84964258e-02, -2.66048193e-01, -1.23634338e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5228881835938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.84765625, 16583.16601562, 30.00003052]), + 'frame': 37760, + 'frame_number': 37760, + 'framesequence': 152273, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5321390628814697, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.5893289968371, + 'timestamp_carla': 1281594, + 'timestamp_device': 2900153, + 'timestamp_stream': 1281.5893289968371, + 'transform': [array([ 1.90941422e+02, 3.00531555e+02, -1.43975183e-01]), + array([-8.57188739e-03, -1.62805328e+02, 2.23388579e-02])]} +{'AngularVelocity': array([ 0.09328472, -0.05732673, -3.45559645]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76459884643555, + 'FR_Wheel_Angle': -30.843801498413086, + 'Location': array([249.53063965, 155.84117126, 0.30170602]), + 'Rotation': array([-2.06613205e-02, -6.37786713e+01, -8.11767671e-03]), + 'Velocity': array([ 1.34864962e-02, -2.66409308e-01, 3.75938398e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5223388671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.81835938, 16583.0234375 , 29.99996948]), + 'frame': 37761, + 'frame_number': 37761, + 'framesequence': 152277, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5332010984420776, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.6239187978208, + 'timestamp_carla': 1281629, + 'timestamp_device': 2900186, + 'timestamp_stream': 1281.6239187978208, + 'transform': [array([ 1.90984665e+02, 3.00545837e+02, -1.43996581e-01]), + array([-8.64018872e-03, -1.62823853e+02, 2.23388579e-02])]} +{'AngularVelocity': array([ 0.09645738, -0.06448065, -3.05234909]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.83002471923828, + 'FR_Wheel_Angle': -29.738969802856445, + 'Location': array([249.53909302, 155.77354431, 0.30171454]), + 'Rotation': array([-2.09345277e-02, -6.46856613e+01, -8.66699312e-03]), + 'Velocity': array([ 0.0105192 , -0.25986183, 0.00039711]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52294921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.78710938, 16582.88085938, 29.99990845]), + 'frame': 37762, + 'frame_number': 37762, + 'framesequence': 152281, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5370464324951172, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.6569705978036, + 'timestamp_carla': 1281662, + 'timestamp_device': 2900220, + 'timestamp_stream': 1281.6569705978036, + 'transform': [array([ 1.91025146e+02, 3.00559235e+02, -1.43996194e-01]), + array([-8.66751000e-03, -1.62841202e+02, 2.23388560e-02])]} +{'AngularVelocity': array([ 0.10778825, -0.06017128, -2.76746225]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.34621047973633, + 'FR_Wheel_Angle': -28.56465721130371, + 'Location': array([249.54856873, 155.70666504, 0.30169404]), + 'Rotation': array([-2.06613205e-02, -6.54997330e+01, -9.73510556e-03]), + 'Velocity': array([ 0.01750862, -0.25012839, -0.00043529]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5199584960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.75195312, 16582.73046875, 30. ]), + 'frame': 37763, + 'frame_number': 37763, + 'framesequence': 152285, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5408551692962646, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.6905439980328, + 'timestamp_carla': 1281695, + 'timestamp_device': 2900253, + 'timestamp_stream': 1281.6905439980328, + 'transform': [array([ 1.91067123e+02, 3.00573090e+02, -1.43997461e-01]), + array([-8.66751000e-03, -1.62859192e+02, 2.23388523e-02])]} +{'AngularVelocity': array([ 0.1022054 , -0.0638321 , -2.79833055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.42921447753906, + 'FR_Wheel_Angle': -28.34563446044922, + 'Location': array([249.55700684, 155.64204407, 0.30169791]), + 'Rotation': array([-2.08730567e-02, -6.62845612e+01, -9.15527344e-03]), + 'Velocity': array([ 1.32347960e-02, -2.43908972e-01, -2.19745634e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206909179688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.72265625, 16582.58984375, 30. ]), + 'frame': 37764, + 'frame_number': 37764, + 'framesequence': 152289, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5432905554771423, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.7235735990107, + 'timestamp_carla': 1281728, + 'timestamp_device': 2900286, + 'timestamp_stream': 1281.7235735990107, + 'transform': [array([ 1.91108276e+02, 3.00586670e+02, -1.43994436e-01]), + array([-8.66751000e-03, -1.62876801e+02, 2.23388560e-02])]} +{'AngularVelocity': array([ 0.10294222, -0.06863204, -2.69542336]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.600955963134766, + 'FR_Wheel_Angle': -28.347394943237305, + 'Location': array([249.56448364, 155.57875061, 0.30170128]), + 'Rotation': array([-2.08730567e-02, -6.70548859e+01, -8.78906343e-03]), + 'Velocity': array([ 0.00925643, -0.23733163, -0.00041634]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5204467773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.68945312, 16582.4453125 , 30.00003052]), + 'frame': 37765, + 'frame_number': 37765, + 'framesequence': 152293, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5423383712768555, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.756667997688, + 'timestamp_carla': 1281761, + 'timestamp_device': 2900320, + 'timestamp_stream': 1281.756667997688, + 'transform': [array([ 1.91149658e+02, 3.00600311e+02, -1.43993139e-01]), + array([-8.66751000e-03, -1.62894531e+02, 2.23388560e-02])]} +{'AngularVelocity': array([ 0.07838669, -0.04815708, -2.50160432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.56353759765625, + 'FR_Wheel_Angle': -25.07179832458496, + 'Location': array([249.570755 , 155.52560425, 0.30171806]), + 'Rotation': array([-2.05998495e-02, -6.76749725e+01, -9.70458984e-03]), + 'Velocity': array([ 1.47260660e-02, -2.40685686e-01, 1.47542945e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5210571289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.65820312, 16582.30078125, 30.00003052]), + 'frame': 37766, + 'frame_number': 37766, + 'framesequence': 152297, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5403973460197449, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.7895723991096, + 'timestamp_carla': 1281794, + 'timestamp_device': 2900353, + 'timestamp_stream': 1281.7895723991096, + 'transform': [array([ 1.91190643e+02, 3.00613831e+02, -1.43995479e-01]), + array([-8.70166067e-03, -1.62912109e+02, 2.23388597e-02])]} +{'AngularVelocity': array([ 0.07302743, -0.03488518, -2.45981598]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.52599334716797, + 'FR_Wheel_Angle': -25.67790412902832, + 'Location': array([249.57879639, 155.463974 , 0.30171028]), + 'Rotation': array([-2.08457354e-02, -6.83404617e+01, -8.97216797e-03]), + 'Velocity': array([ 0.01134375, -0.23479721, 0.00029429]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213623046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.62695312, 16582.15625 , 29.99996948]), + 'frame': 37767, + 'frame_number': 37767, + 'framesequence': 152301, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5385845899581909, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.8238056972623, + 'timestamp_carla': 1281829, + 'timestamp_device': 2900386, + 'timestamp_stream': 1281.8238056972623, + 'transform': [array([ 1.91233551e+02, 3.00627991e+02, -1.44008711e-01]), + array([-8.72898102e-03, -1.62930466e+02, 2.23388597e-02])]} +{'AngularVelocity': array([ 0.0850636 , -0.04739177, -2.24544239]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.4124870300293, + 'FR_Wheel_Angle': -25.739696502685547, + 'Location': array([249.58590698, 155.40313721, 0.30171025]), + 'Rotation': array([-2.08457354e-02, -6.89996948e+01, -8.81958008e-03]), + 'Velocity': array([ 9.21999943e-03, -2.27022097e-01, 2.07996363e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5215454101562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.59570312, 16582.01367188, 30. ]), + 'frame': 37768, + 'frame_number': 37768, + 'framesequence': 152305, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.537907063961029, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.8586179986596, + 'timestamp_carla': 1281863, + 'timestamp_device': 2900420, + 'timestamp_stream': 1281.8586179986596, + 'transform': [array([ 1.91276596e+02, 3.00642090e+02, -1.44022554e-01]), + array([-8.76313262e-03, -1.62948914e+02, 2.23388523e-02])]} +{'AngularVelocity': array([ 0.07586135, -0.04450992, -2.20720029]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.502012252807617, + 'FR_Wheel_Angle': -23.906742095947266, + 'Location': array([249.59222412, 155.34390259, 0.30171084]), + 'Rotation': array([-2.08730567e-02, -6.96376266e+01, -9.03320219e-03]), + 'Velocity': array([ 0.00802664, -0.22166944, 0.00031214]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.56445312, 16581.87304688, 30. ]), + 'frame': 37769, + 'frame_number': 37769, + 'framesequence': 152309, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5329447388648987, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.889571197331, + 'timestamp_carla': 1281894, + 'timestamp_device': 2900453, + 'timestamp_stream': 1281.889571197331, + 'transform': [array([ 1.91339233e+02, 3.00663147e+02, -1.45238981e-01]), + array([-8.36015120e-03, -1.62975693e+02, 2.18200553e-02])]} +{'AngularVelocity': array([ 0.08407186, -0.04184236, -1.87983763]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.60651206970215, + 'FR_Wheel_Angle': -23.48529815673828, + 'Location': array([249.59953308, 155.2855072 , 0.30170411]), + 'Rotation': array([-2.05998495e-02, -7.02006836e+01, -9.64355469e-03]), + 'Velocity': array([ 1.45259816e-02, -2.15466574e-01, -8.33892773e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5177001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.53125 , 16581.72460938, 29.99996948]), + 'frame': 37770, + 'frame_number': 37770, + 'framesequence': 152313, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5228919386863708, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.9233147986233, + 'timestamp_carla': 1281928, + 'timestamp_device': 2900486, + 'timestamp_stream': 1281.9233147986233, + 'transform': [array([ 1.91388824e+02, 3.00678772e+02, -1.46783069e-01]), + array([-7.35611329e-03, -1.62996933e+02, 2.11486686e-02])]} +{'AngularVelocity': array([ 0.09739474, -0.05623089, -1.80549514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.269548416137695, + 'FR_Wheel_Angle': -23.200815200805664, + 'Location': array([249.60623169, 155.22793579, 0.3016969 ]), + 'Rotation': array([-2.07227934e-02, -7.07496262e+01, -9.06372163e-03]), + 'Velocity': array([ 0.01169373, -0.20657431, -0.00024776]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5238037109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.49023438, 16581.5546875 , 30. ]), + 'frame': 37771, + 'frame_number': 37771, + 'framesequence': 152316, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5098910927772522, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.9562800005078, + 'timestamp_carla': 1281961, + 'timestamp_device': 2900511, + 'timestamp_stream': 1281.9562800005078, + 'transform': [array([ 1.91492157e+02, 3.00713104e+02, -1.49289623e-01]), + array([-6.22913241e-03, -1.63041107e+02, 2.00805590e-02])]} +{'AngularVelocity': array([ 0.09150743, -0.05389029, -1.84551656]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.269699096679688, + 'FR_Wheel_Angle': -22.978979110717773, + 'Location': array([249.61227417, 155.17189026, 0.30170539]), + 'Rotation': array([-2.09072083e-02, -7.12800293e+01, -8.94165132e-03]), + 'Velocity': array([ 8.88541061e-03, -2.01551601e-01, -1.48057938e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5263671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.44921875, 16581.3203125 , 29.99996948]), + 'frame': 37772, + 'frame_number': 37772, + 'framesequence': 152321, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4949125647544861, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1281.9898723997176, + 'timestamp_carla': 1281995, + 'timestamp_device': 2900553, + 'timestamp_stream': 1281.9898723997176, + 'transform': [array([ 1.91569168e+02, 3.00737885e+02, -1.49305418e-01]), + array([-6.31109439e-03, -1.63074051e+02, 2.00805590e-02])]} +{'AngularVelocity': array([ 0.08330288, -0.04547776, -1.43416762]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.972049713134766, + 'FR_Wheel_Angle': -19.82254981994629, + 'Location': array([249.6184082 , 155.11740112, 0.30170584]), + 'Rotation': array([-2.07569432e-02, -7.17652359e+01, -1.00402832e-02]), + 'Velocity': array([ 1.55390371e-02, -1.96231022e-01, -4.41551219e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.531494140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.38476562, 16581.01757812, 30.00003052]), + 'frame': 37773, + 'frame_number': 37773, + 'framesequence': 152325, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47971436381340027, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1282.0241690985858, + 'timestamp_carla': 1282029, + 'timestamp_device': 2900586, + 'timestamp_stream': 1282.0241690985858, + 'transform': [array([ 1.91662338e+02, 3.00768188e+02, -1.49444729e-01]), + array([-6.16766047e-03, -1.63113876e+02, 2.00195275e-02])]} +{'AngularVelocity': array([ 0.0803332 , -0.04154808, -1.47291803]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.902833938598633, + 'FR_Wheel_Angle': -20.218584060668945, + 'Location': array([249.62486267, 155.06437683, 0.30171564]), + 'Rotation': array([-2.07842644e-02, -7.21938934e+01, -9.03320219e-03]), + 'Velocity': array([ 1.27296252e-02, -1.91825137e-01, 6.20174396e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5308227539062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.33007812, 16580.71875 , 30.00003052]), + 'frame': 37774, + 'frame_number': 37774, + 'framesequence': 152329, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46695151925086975, + 'throttle_input': 0.05555810034275055, + 'timestamp': 1282.0572335980833, + 'timestamp_carla': 1282062, + 'timestamp_device': 2900620, + 'timestamp_stream': 1282.0572335980833, + 'transform': [array([ 1.91737900e+02, 3.00792297e+02, -1.48680717e-01]), + array([-6.74822647e-03, -1.63146164e+02, 2.03552153e-02])]} +{'AngularVelocity': array([ 0.08597844, -0.04540308, -1.3560015 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.032285690307617, + 'FR_Wheel_Angle': -20.387893676757812, + 'Location': array([249.63082886, 155.01234436, 0.30170774]), + 'Rotation': array([-2.07842644e-02, -7.26165848e+01, -8.91113281e-03]), + 'Velocity': array([ 1.10372780e-02, -1.83205470e-01, 3.65257256e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5296630859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.26757812, 16580.39648438, 30. ]), + 'frame': 37775, + 'frame_number': 37775, + 'framesequence': 152333, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4646626114845276, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1282.0897205993533, + 'timestamp_carla': 1282094, + 'timestamp_device': 2900653, + 'timestamp_stream': 1282.0897205993533, + 'transform': [array([ 1.91809448e+02, 3.00815063e+02, -1.47610962e-01]), + array([-7.32879248e-03, -1.63176727e+02, 2.08129808e-02])]} +{'AngularVelocity': array([ 0.08235147, -0.04426737, -1.1737572 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -22.59356117248535, + 'FR_Wheel_Angle': -17.975797653198242, + 'Location': array([249.63713074, 154.95541382, 0.3017104 ]), + 'Rotation': array([-2.07569432e-02, -7.30740814e+01, -9.42993257e-03]), + 'Velocity': array([ 1.28117418e-02, -1.74665526e-01, 1.18064881e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5287475585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.21679688, 16580.09375 , 30. ]), + 'frame': 37776, + 'frame_number': 37776, + 'framesequence': 152337, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46971651911735535, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1282.1245019994676, + 'timestamp_carla': 1282129, + 'timestamp_device': 2900686, + 'timestamp_stream': 1282.1245019994676, + 'transform': [array([ 1.91904816e+02, 3.00846130e+02, -1.47308499e-01]), + array([-7.23316986e-03, -1.63217453e+02, 2.09350511e-02])]} +{'AngularVelocity': array([ 0.07240826, -0.02334524, -0.98930758]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.38896942138672, + 'FR_Wheel_Angle': -17.81971549987793, + 'Location': array([249.64268494, 154.91421509, 0.30171084]), + 'Rotation': array([-2.07569432e-02, -7.33535233e+01, -9.46044922e-03]), + 'Velocity': array([ 1.43875051e-02, -1.69087783e-01, 1.36032104e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52783203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.17382812, 16579.81054688, 30. ]), + 'frame': 37777, + 'frame_number': 37777, + 'framesequence': 152340, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4777916967868805, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1282.1565161980689, + 'timestamp_carla': 1282161, + 'timestamp_device': 2900711, + 'timestamp_stream': 1282.1565161980689, + 'transform': [array([ 1.91980270e+02, 3.00870178e+02, -1.46724313e-01]), + array([-7.50637753e-03, -1.63249680e+02, 2.11791918e-02])]} +{'AngularVelocity': array([ 0.09547215, -0.04452867, -0.949718 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.0072078704834, + 'FR_Wheel_Angle': -17.543882369995117, + 'Location': array([249.64872742, 154.86668396, 0.30169708]), + 'Rotation': array([-2.07227934e-02, -7.36805191e+01, -9.06372163e-03]), + 'Velocity': array([ 0.013213 , -0.15700802, -0.00038515]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5252075195312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.10742188, 16579.50585938, 30. ]), + 'frame': 37778, + 'frame_number': 37778, + 'framesequence': 152345, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4846949875354767, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1282.1903754994273, + 'timestamp_carla': 1282195, + 'timestamp_device': 2900753, + 'timestamp_stream': 1282.1903754994273, + 'transform': [array([ 1.92052612e+02, 3.00893066e+02, -1.45787388e-01]), + array([-7.84105714e-03, -1.63280579e+02, 2.15759166e-02])]} +{'AngularVelocity': array([ 0.06096022, -0.02231618, -0.80899662]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.847890853881836, + 'FR_Wheel_Angle': -17.123340606689453, + 'Location': array([249.65409851, 154.82173157, 0.3017126 ]), + 'Rotation': array([-2.07569432e-02, -7.39864273e+01, -8.75854399e-03]), + 'Velocity': array([ 0.01099606, -0.16094084, 0.00047503]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5264892578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.05664062, 16579.21484375, 30. ]), + 'frame': 37779, + 'frame_number': 37779, + 'framesequence': 152349, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.486873984336853, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1282.2231820970774, + 'timestamp_carla': 1282228, + 'timestamp_device': 2900786, + 'timestamp_stream': 1282.2231820970774, + 'transform': [array([ 1.92119598e+02, 3.00914276e+02, -1.44840389e-01]), + array([-8.18256661e-03, -1.63309189e+02, 2.19726432e-02])]} +{'AngularVelocity': array([ 0.08502094, -0.02895828, -0.71301478]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.661776542663574, + 'FR_Wheel_Angle': -13.958375930786133, + 'Location': array([249.66082764, 154.77078247, 0.30171433]), + 'Rotation': array([-2.02036984e-02, -7.42931290e+01, -9.70458984e-03]), + 'Velocity': array([ 1.85664855e-02, -1.53565437e-01, -7.24506390e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.524169921875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23984.00585938, 16578.9296875 , 29.99993896]), + 'frame': 37780, + 'frame_number': 37780, + 'framesequence': 152353, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48449355363845825, + 'throttle_input': 0.07539482414722443, + 'timestamp': 1282.256952200085, + 'timestamp_carla': 1282262, + 'timestamp_device': 2900820, + 'timestamp_stream': 1282.256952200085, + 'transform': [array([ 1.92194794e+02, 3.00938354e+02, -1.44397497e-01]), + array([-8.24403763e-03, -1.63341293e+02, 2.21557505e-02])]} +{'AngularVelocity': array([ 0.08032864, -0.02943846, -0.63664436]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.515396118164062, + 'FR_Wheel_Angle': -14.298381805419922, + 'Location': array([249.66685486, 154.72839355, 0.30170897]), + 'Rotation': array([-2.08457354e-02, -7.45298538e+01, -9.15527437e-03]), + 'Velocity': array([ 1.48620801e-02, -1.38850033e-01, -9.07897902e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5231323242188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.95507812, 16578.66601562, 29.99996948]), + 'frame': 37781, + 'frame_number': 37781, + 'framesequence': 152357, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4810144305229187, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.291175097227, + 'timestamp_carla': 1282296, + 'timestamp_device': 2900853, + 'timestamp_stream': 1282.291175097227, + 'transform': [array([ 1.92264725e+02, 3.00960388e+02, -1.44327730e-01]), + array([-8.24403763e-03, -1.63371140e+02, 2.21862700e-02])]} +{'AngularVelocity': array([ 0.06166569, -0.01776721, -0.47067353]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.71654510498047, + 'FR_Wheel_Angle': -14.473554611206055, + 'Location': array([249.67237854, 154.68858337, 0.30170813]), + 'Rotation': array([-2.07227934e-02, -7.47509613e+01, -8.81958008e-03]), + 'Velocity': array([ 0.01304458, -0.13682345, 0.00032598]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5217895507812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.90429688, 16578.40039062, 29.99996948]), + 'frame': 37782, + 'frame_number': 37782, + 'framesequence': 152361, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47764521837234497, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.3233533985913, + 'timestamp_carla': 1282328, + 'timestamp_device': 2900886, + 'timestamp_stream': 1282.3233533985913, + 'transform': [array([ 1.92329391e+02, 3.00980743e+02, -1.44128487e-01]), + array([-8.54456611e-03, -1.63398727e+02, 2.22778227e-02])]} +{'AngularVelocity': array([-0.0702344 , 0.01517628, -0.91210961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.925512313842773, + 'FR_Wheel_Angle': -11.436540603637695, + 'Location': array([249.67781067, 154.6496582 , 0.30171305]), + 'Rotation': array([-2.01149061e-02, -7.49639130e+01, -9.06372070e-03]), + 'Velocity': array([ 2.53711715e-02, -1.98519304e-01, 5.62667822e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5203247070312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.85546875, 16578.125 , 30.00003052]), + 'frame': 37783, + 'frame_number': 37783, + 'framesequence': 152365, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47702261805534363, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.3573134988546, + 'timestamp_carla': 1282362, + 'timestamp_device': 2900920, + 'timestamp_stream': 1282.3573134988546, + 'transform': [array([ 1.92399216e+02, 3.01002686e+02, -1.43871263e-01]), + array([-8.85192491e-03, -1.63428513e+02, 2.23998912e-02])]} +{'AngularVelocity': array([-0.07440597, 0.02247527, -0.8111186 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.104567527770996, + 'FR_Wheel_Angle': -11.540802001953125, + 'Location': array([249.68370056, 154.61346436, 0.30170986]), + 'Rotation': array([-2.00807545e-02, -7.51163101e+01, -8.78906343e-03]), + 'Velocity': array([ 2.57290956e-02, -1.90928489e-01, 7.48062084e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5218505859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.81054688, 16577.86523438, 30. ]), + 'frame': 37784, + 'frame_number': 37784, + 'framesequence': 152368, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47859737277030945, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.3891285993159, + 'timestamp_carla': 1282394, + 'timestamp_device': 2900945, + 'timestamp_stream': 1282.3891285993159, + 'transform': [array([ 1.92464951e+02, 3.01023346e+02, -1.43787801e-01]), + array([-8.87924526e-03, -1.63456558e+02, 2.24304069e-02])]} +{'AngularVelocity': array([-0.06893941, 0.01791331, -0.79005188]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.678389549255371, + 'FR_Wheel_Angle': -11.253588676452637, + 'Location': array([249.68934631, 154.57810974, 0.30170855]), + 'Rotation': array([-1.98348686e-02, -7.52689362e+01, -8.51440430e-03]), + 'Velocity': array([ 2.54854653e-02, -1.87153131e-01, -6.03294357e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5197143554688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.76367188, 16577.59960938, 30. ]), + 'frame': 37785, + 'frame_number': 37785, + 'framesequence': 152373, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800439774990082, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.4227232970297, + 'timestamp_carla': 1282427, + 'timestamp_device': 2900986, + 'timestamp_stream': 1282.4227232970297, + 'transform': [array([ 1.92533234e+02, 3.01044708e+02, -1.43865734e-01]), + array([-8.85192491e-03, -1.63485657e+02, 2.23998912e-02])]} +{'AngularVelocity': array([-0.07997858, 0.01639745, -0.86923021]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.43908977508545, + 'FR_Wheel_Angle': -10.669707298278809, + 'Location': array([249.69447327, 154.54574585, 0.30169478]), + 'Rotation': array([-2.00534351e-02, -7.54079056e+01, -8.51440523e-03]), + 'Velocity': array([ 2.40260232e-02, -1.77677929e-01, 8.36944528e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5218505859375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.71875 , 16577.34375 , 29.99996948]), + 'frame': 37786, + 'frame_number': 37786, + 'framesequence': 152377, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4811060130596161, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.4565557986498, + 'timestamp_carla': 1282461, + 'timestamp_device': 2901019, + 'timestamp_stream': 1282.4565557986498, + 'transform': [array([ 1.92605301e+02, 3.01067383e+02, -1.43795282e-01]), + array([-8.85192491e-03, -1.63516418e+02, 2.24304087e-02])]} +{'AngularVelocity': array([-0.04647894, -0.00548846, 0.2523852 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.434177398681641, + 'FR_Wheel_Angle': -7.318704605102539, + 'Location': array([249.70050049, 154.51234436, 0.301705 ]), + 'Rotation': array([-1.89469438e-02, -7.55068512e+01, -9.21630859e-03]), + 'Velocity': array([ 0.03491766, -0.18318096, 0.00021258]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208740234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.67382812, 16577.07421875, 29.99996948]), + 'frame': 37787, + 'frame_number': 37787, + 'framesequence': 152381, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4803186357021332, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.4903889968991, + 'timestamp_carla': 1282495, + 'timestamp_device': 2901053, + 'timestamp_stream': 1282.4903889968991, + 'transform': [array([ 1.92673706e+02, 3.01088776e+02, -1.43510744e-01]), + array([-8.97486787e-03, -1.63545563e+02, 2.25524791e-02])]} +{'AngularVelocity': array([-0.07199926, 0.007119 , -0.53540587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.176328659057617, + 'FR_Wheel_Angle': -7.628257751464844, + 'Location': array([249.70690918, 154.47753906, 0.30168724]), + 'Rotation': array([-2.04427559e-02, -7.56037598e+01, -8.85009766e-03]), + 'Velocity': array([ 0.02952462, -0.17101444, -0.00051114]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5195922851562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.625 , 16576.80664062, 29.99996948]), + 'frame': 37788, + 'frame_number': 37788, + 'framesequence': 152385, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4792199730873108, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.5231973975897, + 'timestamp_carla': 1282528, + 'timestamp_device': 2901086, + 'timestamp_stream': 1282.5231973975897, + 'transform': [array([ 1.92773056e+02, 3.01120789e+02, -1.44802898e-01]), + array([-8.45577382e-03, -1.63587875e+02, 2.20031627e-02])]} +{'AngularVelocity': array([-0.02740503, -0.01253057, -1.06539512]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.376070022583008, + 'FR_Wheel_Angle': -7.779658317565918, + 'Location': array([249.71205139, 154.44927979, 0.30170166]), + 'Rotation': array([-2.09345277e-02, -7.56865311e+01, -8.91113095e-03]), + 'Velocity': array([ 2.38509718e-02, -1.28616586e-01, -1.06983185e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184936523438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.58007812, 16576.546875 , 30. ]), + 'frame': 37789, + 'frame_number': 37789, + 'framesequence': 152389, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4792199730873108, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.557157497853, + 'timestamp_carla': 1282562, + 'timestamp_device': 2901119, + 'timestamp_stream': 1282.557157497853, + 'transform': [array([ 1.92848877e+02, 3.01143341e+02, -1.47237092e-01]), + array([-7.87520781e-03, -1.63620163e+02, 2.09960844e-02])]} +{'AngularVelocity': array([-0.03078431, -0.01069068, -0.9314543 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.325533866882324, + 'FR_Wheel_Angle': -4.120450019836426, + 'Location': array([249.71577454, 154.42980957, 0.30170855]), + 'Rotation': array([-2.11121142e-02, -7.57445831e+01, -9.15527251e-03]), + 'Velocity': array([ 2.15416681e-02, -1.06934018e-01, -9.12094110e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.522216796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.51953125, 16576.26367188, 29.99996948]), + 'frame': 37790, + 'frame_number': 37790, + 'framesequence': 152393, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4799524247646332, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.590183697641, + 'timestamp_carla': 1282595, + 'timestamp_device': 2901153, + 'timestamp_stream': 1282.590183697641, + 'transform': [array([ 1.92962143e+02, 3.01178833e+02, -1.48838237e-01]), + array([-6.22913241e-03, -1.63668442e+02, 2.02636626e-02])]} +{'AngularVelocity': array([-0.03205344, -0.00411105, -0.77504641]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.690958499908447, + 'FR_Wheel_Angle': -4.310428142547607, + 'Location': array([249.71980286, 154.41186523, 0.30171439]), + 'Rotation': array([-2.10301522e-02, -7.57747269e+01, -9.00268648e-03]), + 'Velocity': array([ 0.0184873 , -0.08537093, 0.00030543]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5245361328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.47265625, 16575.87109375, 29.99996948]), + 'frame': 37791, + 'frame_number': 37791, + 'framesequence': 152397, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48017215728759766, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.6238145977259, + 'timestamp_carla': 1282629, + 'timestamp_device': 2901186, + 'timestamp_stream': 1282.6238145977259, + 'transform': [array([ 1.93110275e+02, 3.01225281e+02, -1.51836321e-01]), + array([-5.34120761e-03, -1.63731461e+02, 1.90124437e-02])]} +{'AngularVelocity': array([-0.03160899, -0.00697953, -0.72740644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.2716288566589355, + 'FR_Wheel_Angle': -4.048073768615723, + 'Location': array([249.72329712, 154.39584351, 0.30171904]), + 'Rotation': array([-2.05383785e-02, -7.58013077e+01, -8.72802641e-03]), + 'Velocity': array([ 0.01552689, -0.07205275, 0.00037848]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.530517578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.39257812, 16575.45703125, 29.99996948]), + 'frame': 37792, + 'frame_number': 37792, + 'framesequence': 152401, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48008060455322266, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.6590588986874, + 'timestamp_carla': 1282664, + 'timestamp_device': 2901219, + 'timestamp_stream': 1282.6590588986874, + 'transform': [array([ 1.93252335e+02, 3.01269470e+02, -1.51562914e-01]), + array([-5.46415104e-03, -1.63791946e+02, 1.91345122e-02])]} +{'AngularVelocity': array([-0.03204395, -0.00794193, -0.76840734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.9749879837036133, + 'FR_Wheel_Angle': -3.2015039920806885, + 'Location': array([249.7256012 , 154.38539124, 0.30170318]), + 'Rotation': array([-2.02651694e-02, -7.58169861e+01, -8.66699219e-03]), + 'Velocity': array([ 1.45361172e-02, -6.73220083e-02, -2.93064113e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5347900390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.30859375, 16574.953125 , 29.99996948]), + 'frame': 37793, + 'frame_number': 37793, + 'framesequence': 152405, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4759605824947357, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.6907855980098, + 'timestamp_carla': 1282696, + 'timestamp_device': 2901253, + 'timestamp_stream': 1282.6907855980098, + 'transform': [array([ 1.93375580e+02, 3.01307526e+02, -1.50889322e-01]), + array([-5.67588676e-03, -1.63844406e+02, 1.94091741e-02])]} +{'AngularVelocity': array([-0.03097304, -0.0070524 , -0.65897536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.7958036661148071, + 'FR_Wheel_Angle': 0.2459692358970642, + 'Location': array([249.72819519, 154.37425232, 0.30170792]), + 'Rotation': array([-1.99919622e-02, -7.58235550e+01, -8.94165039e-03]), + 'Velocity': array([ 0.01602685, -0.06333729, 0.00020214]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5313110351562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.2109375 , 16574.45507812, 30. ]), + 'frame': 37794, + 'frame_number': 37794, + 'framesequence': 152409, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4669698178768158, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.72402529791, + 'timestamp_carla': 1282729, + 'timestamp_device': 2901286, + 'timestamp_stream': 1282.72402529791, + 'transform': [array([ 1.93511322e+02, 3.01349365e+02, -1.50517344e-01]), + array([-5.73735870e-03, -1.63902176e+02, 1.95617583e-02])]} +{'AngularVelocity': array([-0.03120648, -0.00727074, -0.69299012]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.22116774320602417, + 'FR_Wheel_Angle': 0.121710866689682, + 'Location': array([249.73078918, 154.36373901, 0.30170405]), + 'Rotation': array([-1.99578125e-02, -7.58236465e+01, -8.81958008e-03]), + 'Velocity': array([ 1.50956009e-02, -6.14840984e-02, -2.62165067e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5338134765625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.125 , 16573.99609375, 30. ]), + 'frame': 37795, + 'frame_number': 37795, + 'framesequence': 152412, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4540238678455353, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.7561058998108, + 'timestamp_carla': 1282761, + 'timestamp_device': 2901311, + 'timestamp_stream': 1282.7561058998108, + 'transform': [array([ 1.93628250e+02, 3.01384613e+02, -1.50046036e-01]), + array([-6.25645276e-03, -1.63951904e+02, 1.97753813e-02])]} +{'AngularVelocity': array([-0.03087293, -0.00726334, -0.68971854]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.015374117530882359, + 'FR_Wheel_Angle': -0.03073994815349579, + 'Location': array([249.73329163, 154.35365295, 0.30170745]), + 'Rotation': array([-1.99304912e-02, -7.58234940e+01, -8.81958008e-03]), + 'Velocity': array([ 1.47246048e-02, -6.01785034e-02, -3.65066517e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5335083007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23983.02734375, 16573.50585938, 30. ]), + 'frame': 37796, + 'frame_number': 37796, + 'framesequence': 152417, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.44056522846221924, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.7903858982027, + 'timestamp_carla': 1282795, + 'timestamp_device': 2901353, + 'timestamp_stream': 1282.7903858982027, + 'transform': [array([ 1.93751556e+02, 3.01421631e+02, -1.49230957e-01]), + array([-6.89849071e-03, -1.64004318e+02, 2.01415941e-02])]} +{'AngularVelocity': array([-0.0300308 , -0.00826154, -0.63291889]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.3916947841644287, + 'FR_Wheel_Angle': 4.56992244720459, + 'Location': array([249.73580933, 154.34382629, 0.30170891]), + 'Rotation': array([-1.99304912e-02, -7.58217773e+01, -8.94165039e-03]), + 'Velocity': array([ 0.01533544, -0.05868347, 0.00022218]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5335083007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.9453125 , 16573.01367188, 30. ]), + 'frame': 37797, + 'frame_number': 37797, + 'framesequence': 152421, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4247443974018097, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.8238325975835, + 'timestamp_carla': 1282829, + 'timestamp_device': 2901386, + 'timestamp_stream': 1282.8238325975835, + 'transform': [array([ 1.93874374e+02, 3.01458130e+02, -1.49343520e-01]), + array([-7.17169838e-03, -1.64056473e+02, 2.01110747e-02])]} +{'AngularVelocity': array([-0.03173153, -0.00584529, -0.64874464]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.617666244506836, + 'FR_Wheel_Angle': 3.9845399856567383, + 'Location': array([249.7384491 , 154.33425903, 0.30170211]), + 'Rotation': array([-1.98963396e-02, -7.58074493e+01, -8.91113095e-03]), + 'Velocity': array([ 1.58033650e-02, -5.82416616e-02, -8.48197888e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.529052734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.86328125, 16572.49804688, 30. ]), + 'frame': 37798, + 'frame_number': 37798, + 'framesequence': 152424, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4100589156150818, + 'throttle_input': 0.0793621763586998, + 'timestamp': 1282.8558715991676, + 'timestamp_carla': 1282861, + 'timestamp_device': 2901411, + 'timestamp_stream': 1282.8558715991676, + 'transform': [array([ 1.94026245e+02, 3.01503998e+02, -1.50516242e-01]), + array([-6.92581153e-03, -1.64120926e+02, 1.96227953e-02])]} +{'AngularVelocity': array([-0.03181134, -0.00744895, -0.63141209]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.961024045944214, + 'FR_Wheel_Angle': 4.208430290222168, + 'Location': array([249.74116516, 154.32432556, 0.30170414]), + 'Rotation': array([-1.97119247e-02, -7.57925186e+01, -8.88061523e-03]), + 'Velocity': array([ 0.01717751, -0.06258513, -0.00014692]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5283203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.79101562, 16571.95703125, 30. ]), + 'frame': 37799, + 'frame_number': 37799, + 'framesequence': 152428, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4043641686439514, + 'throttle_input': 0.08332952111959457, + 'timestamp': 1282.8882830999792, + 'timestamp_carla': 1282893, + 'timestamp_device': 2901444, + 'timestamp_stream': 1282.8882830999792, + 'transform': [array([ 1.94153046e+02, 3.01540955e+02, -1.50649175e-01]), + array([-6.80969842e-03, -1.64174713e+02, 1.95617583e-02])]} +{'AngularVelocity': array([-0.03056942, -0.00750271, -0.59485418]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.4604668617248535, + 'FR_Wheel_Angle': 5.4567179679870605, + 'Location': array([249.74429321, 154.31307983, 0.30170304]), + 'Rotation': array([-1.95889808e-02, -7.57758636e+01, -8.88061523e-03]), + 'Velocity': array([ 0.01893367, -0.06806441, 0.0002165 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5318603515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.70898438, 16571.38085938, 29.99996948]), + 'frame': 37800, + 'frame_number': 37800, + 'framesequence': 152432, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4074404537677765, + 'throttle_input': 0.08332952111959457, + 'timestamp': 1282.9219499975443, + 'timestamp_carla': 1282927, + 'timestamp_device': 2901478, + 'timestamp_stream': 1282.9219499975443, + 'transform': [array([ 1.94289520e+02, 3.01580292e+02, -1.51508182e-01]), + array([-6.92581153e-03, -1.64232529e+02, 1.92260649e-02])]} +{'AngularVelocity': array([-0.05013948, -0.01151354, 1.06648421]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.299931526184082, + 'FR_Wheel_Angle': 8.452741622924805, + 'Location': array([249.7490387 , 154.29756165, 0.30168754]), + 'Rotation': array([-1.74511317e-02, -7.57275543e+01, -9.97924805e-03]), + 'Velocity': array([ 4.11552526e-02, -1.24037214e-01, 7.66372686e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5328979492188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.64257812, 16570.78320312, 30. ]), + 'frame': 37801, + 'frame_number': 37801, + 'framesequence': 152437, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4149113595485687, + 'throttle_input': 0.08332952111959457, + 'timestamp': 1282.957287300378, + 'timestamp_carla': 1282962, + 'timestamp_device': 2901519, + 'timestamp_stream': 1282.957287300378, + 'transform': [array([ 1.94439911e+02, 3.01623810e+02, -1.51266515e-01]), + array([-6.68675499e-03, -1.64296280e+02, 1.93176195e-02])]} +{'AngularVelocity': array([0.06550948, 0.03608079, 0.05435758]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.9291534423828125, + 'FR_Wheel_Angle': 8.435717582702637, + 'Location': array([249.76036072, 154.26255798, 0.30167705]), + 'Rotation': array([-1.61738880e-02, -7.56288528e+01, -1.00097647e-02]), + 'Velocity': array([ 5.16778976e-02, -1.46834940e-01, -4.61673735e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5318603515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.57617188, 16570.11523438, 29.99996948]), + 'frame': 37802, + 'frame_number': 37802, + 'framesequence': 152441, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42293164134025574, + 'throttle_input': 0.08332952111959457, + 'timestamp': 1282.9911911971867, + 'timestamp_carla': 1282996, + 'timestamp_device': 2901553, + 'timestamp_stream': 1282.9911911971867, + 'transform': [array([ 1.94600693e+02, 3.01670959e+02, -1.50018185e-01]), + array([-7.02143414e-03, -1.64364426e+02, 1.98364165e-02])]} +{'AngularVelocity': array([0.0459808 , 0.04874907, 1.02475274]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.71439790725708, + 'FR_Wheel_Angle': 8.327266693115234, + 'Location': array([249.77592468, 154.2147522 , 0.30168623]), + 'Rotation': array([-1.73076987e-02, -7.54888382e+01, -9.55200195e-03]), + 'Velocity': array([ 6.57766387e-02, -1.96495906e-01, -1.71661370e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5284423828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.49609375, 16569.41210938, 30. ]), + 'frame': 37803, + 'frame_number': 37803, + 'framesequence': 152445, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4271431565284729, + 'throttle_input': 0.08332952111959457, + 'timestamp': 1283.0226914994419, + 'timestamp_carla': 1283028, + 'timestamp_device': 2901586, + 'timestamp_stream': 1283.0226914994419, + 'transform': [array([ 1.94756622e+02, 3.01716736e+02, -1.49464071e-01]), + array([-6.40671700e-03, -1.64430527e+02, 2.00195219e-02])]} +{'AngularVelocity': array([-0.01739548, -0.05203529, 1.78263974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.0656156539917, + 'FR_Wheel_Angle': 13.33194637298584, + 'Location': array([249.79649353, 154.15359497, 0.30168381]), + 'Rotation': array([-1.62080377e-02, -7.52922745e+01, -1.11389169e-02]), + 'Velocity': array([ 1.17249422e-01, -3.04796547e-01, 9.29832458e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5269775390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.40234375, 16568.73828125, 30. ]), + 'frame': 37804, + 'frame_number': 37804, + 'framesequence': 152449, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42569658160209656, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.0578569993377, + 'timestamp_carla': 1283063, + 'timestamp_device': 2901619, + 'timestamp_stream': 1283.0578569993377, + 'transform': [array([ 1.94933563e+02, 3.01768219e+02, -1.50192142e-01]), + array([-6.62528304e-03, -1.64505432e+02, 1.97448619e-02])]} +{'AngularVelocity': array([ 1.01989480e-02, -1.00632897e-03, 1.57941175e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.90625286102295, + 'FR_Wheel_Angle': 12.448230743408203, + 'Location': array([249.8240509 , 154.07940674, 0.30168003]), + 'Rotation': array([-1.64539255e-02, -7.49595566e+01, -1.10168448e-02]), + 'Velocity': array([ 1.37301102e-01, -3.40734422e-01, 9.61303704e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5315551757812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.3046875 , 16568.10546875, 30.00003052]), + 'frame': 37805, + 'frame_number': 37805, + 'framesequence': 152453, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4221808612346649, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.0893059968948, + 'timestamp_carla': 1283094, + 'timestamp_device': 2901653, + 'timestamp_stream': 1283.0893059968948, + 'transform': [array([ 1.95097580e+02, 3.01815582e+02, -1.50613517e-01]), + array([-6.50233962e-03, -1.64574844e+02, 1.95617583e-02])]} +{'AngularVelocity': array([0.04050293, 0.026487 , 1.42185521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.133012771606445, + 'FR_Wheel_Angle': 12.52688980102539, + 'Location': array([249.85696411, 153.99229431, 0.3016825 ]), + 'Rotation': array([-1.72120761e-02, -7.45839081e+01, -1.07116709e-02]), + 'Velocity': array([ 1.51926339e-01, -3.66596639e-01, -1.43280020e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5283813476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.20703125, 16567.375 , 30.00003052]), + 'frame': 37806, + 'frame_number': 37806, + 'framesequence': 152457, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41846370697021484, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.1229364983737, + 'timestamp_carla': 1283128, + 'timestamp_device': 2901686, + 'timestamp_stream': 1283.1229364983737, + 'transform': [array([ 1.95279724e+02, 3.01868011e+02, -1.50714189e-01]), + array([-6.07203785e-03, -1.64651962e+02, 1.95007250e-02])]} +{'AngularVelocity': array([0.05274897, 0.04224835, 1.69928849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.779972076416016, + 'FR_Wheel_Angle': 14.06961727142334, + 'Location': array([249.89491272, 153.89422607, 0.30169234]), + 'Rotation': array([-1.76423769e-02, -7.41632462e+01, -1.03454608e-02]), + 'Velocity': array([ 0.1691069 , -0.40258706, 0.00052141]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5326538085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.1171875, 16566.6796875, 30. ]), + 'frame': 37807, + 'frame_number': 37807, + 'framesequence': 152460, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4165593385696411, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.1559010967612, + 'timestamp_carla': 1283161, + 'timestamp_device': 2901711, + 'timestamp_stream': 1283.1559010967612, + 'transform': [array([ 1.95460068e+02, 3.01919617e+02, -1.50620311e-01]), + array([-5.95592475e-03, -1.64728287e+02, 1.95312425e-02])]} +{'AngularVelocity': array([-0.01358582, -0.03132809, 2.44056273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.634774208068848, + 'FR_Wheel_Angle': 16.454376220703125, + 'Location': array([249.93899536, 153.78945923, 0.30167717]), + 'Rotation': array([-1.78267919e-02, -7.36129074e+01, -1.31225595e-02]), + 'Velocity': array([ 2.25241765e-01, -4.65731889e-01, -3.89766683e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5328369140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23982.00585938, 16565.91796875, 29.99996948]), + 'frame': 37808, + 'frame_number': 37808, + 'framesequence': 152465, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.417511522769928, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.190718498081, + 'timestamp_carla': 1283196, + 'timestamp_device': 2901753, + 'timestamp_stream': 1283.190718498081, + 'transform': [array([ 1.95658783e+02, 3.01976562e+02, -1.49858668e-01]), + array([-6.40671700e-03, -1.64812302e+02, 1.98669359e-02])]} +{'AngularVelocity': array([-0.00965069, -0.04104016, 2.34976888]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.465508460998535, + 'FR_Wheel_Angle': 16.62952423095703, + 'Location': array([249.98747253, 153.6789856 , 0.30167082]), + 'Rotation': array([-1.85849443e-02, -7.29611359e+01, -1.10778809e-02]), + 'Velocity': array([ 0.23626883, -0.48297384, -0.00049849]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23981.89648438, 16565.15429688, 30.00003052]), + 'frame': 37809, + 'frame_number': 37809, + 'framesequence': 152469, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41956236958503723, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.225956197828, + 'timestamp_carla': 1283231, + 'timestamp_device': 2901786, + 'timestamp_stream': 1283.225956197828, + 'transform': [array([ 1.95864365e+02, 3.02035187e+02, -1.49629131e-01]), + array([-6.31109439e-03, -1.64899216e+02, 1.99584886e-02])]} +{'AngularVelocity': array([-0.00963091, -0.03827025, 2.49348092]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.354596138000488, + 'FR_Wheel_Angle': 16.623388290405273, + 'Location': array([250.04536438, 153.55114746, 0.30169952]), + 'Rotation': array([-1.89127922e-02, -7.21966476e+01, -1.05895987e-02]), + 'Velocity': array([ 2.50453591e-01, -4.96828377e-01, -6.07681250e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5288696289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23981.77539062, 16564.36328125, 30. ]), + 'frame': 37810, + 'frame_number': 37810, + 'framesequence': 152472, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.42113712430000305, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.2565178982913, + 'timestamp_carla': 1283261, + 'timestamp_device': 2901811, + 'timestamp_stream': 1283.2565178982913, + 'transform': [array([ 1.96043594e+02, 3.02085480e+02, -1.50216907e-01]), + array([-5.79883019e-03, -1.64974991e+02, 1.96838304e-02])]} +{'AngularVelocity': array([-0.00471164, -0.06033279, 3.1679759 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.51012420654297, + 'FR_Wheel_Angle': 21.73753547668457, + 'Location': array([250.09138489, 153.45443726, 0.30171353]), + 'Rotation': array([-1.98075473e-02, -7.15786285e+01, -1.20544434e-02]), + 'Velocity': array([ 2.67118990e-01, -4.83980447e-01, 2.59084685e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5269775390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23981.6484375 , 16563.54296875, 30. ]), + 'frame': 37811, + 'frame_number': 37811, + 'framesequence': 152477, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4208807647228241, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.2908580973744, + 'timestamp_carla': 1283296, + 'timestamp_device': 2901853, + 'timestamp_stream': 1283.2908580973744, + 'transform': [array([ 1.96271484e+02, 3.02149567e+02, -1.51597470e-01]), + array([-5.83298132e-03, -1.65071213e+02, 1.91345122e-02])]} +{'AngularVelocity': array([-0.01262177, -0.02883155, 3.13345027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.24565887451172, + 'FR_Wheel_Angle': 20.812381744384766, + 'Location': array([250.14860535, 153.34503174, 0.301705 ]), + 'Rotation': array([-1.98075473e-02, -7.07481308e+01, -1.11999512e-02]), + 'Velocity': array([ 2.75442272e-01, -4.74027216e-01, 7.47585291e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5342407226562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23981.53125 , 16562.76953125, 29.99996948]), + 'frame': 37812, + 'frame_number': 37812, + 'framesequence': 152481, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4194525182247162, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.3244247995317, + 'timestamp_carla': 1283329, + 'timestamp_device': 2901886, + 'timestamp_stream': 1283.3244247995317, + 'transform': [array([ 1.96472534e+02, 3.02204712e+02, -1.51497304e-01]), + array([-5.64856594e-03, -1.65156113e+02, 1.91650316e-02])]} +{'AngularVelocity': array([-0.01451333, -0.05325228, 3.31235695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.4072265625, + 'FR_Wheel_Angle': 20.839067459106445, + 'Location': array([250.20730591, 153.23634338, 0.30170339]), + 'Rotation': array([-2.00534351e-02, -6.99209290e+01, -1.04064941e-02]), + 'Velocity': array([ 2.82619327e-01, -4.67378527e-01, -1.75046924e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23981.39648438, 16561.84765625, 30.00003052]), + 'frame': 37813, + 'frame_number': 37813, + 'framesequence': 152485, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4189947545528412, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.3575566969812, + 'timestamp_carla': 1283362, + 'timestamp_device': 2901919, + 'timestamp_stream': 1283.3575566969812, + 'transform': [array([ 1.96671127e+02, 3.02259094e+02, -1.50347516e-01]), + array([-6.16766047e-03, -1.65239914e+02, 1.96533147e-02])]} +{'AngularVelocity': array([ 0.01238141, -0.02178133, 3.94990492]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.25400733947754, + 'FR_Wheel_Angle': 22.852102279663086, + 'Location': array([250.27462769, 153.11621094, 0.30165741]), + 'Rotation': array([-2.01149061e-02, -6.89960098e+01, -1.08642578e-02]), + 'Velocity': array([ 0.28049752, -0.43908426, -0.00126507]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.533447265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23981.26757812, 16560.921875 , 30.00003052]), + 'frame': 37814, + 'frame_number': 37814, + 'framesequence': 152489, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.41967225074768066, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.3908618986607, + 'timestamp_carla': 1283396, + 'timestamp_device': 2901953, + 'timestamp_stream': 1283.3908618986607, + 'transform': [array([ 1.96906128e+02, 3.02324402e+02, -1.49983406e-01]), + array([-6.29060389e-03, -1.65339035e+02, 1.98059008e-02])]} +{'AngularVelocity': array([-3.51690617e-03, -3.41014601e-02, 4.75906610e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.418895721435547, + 'FR_Wheel_Angle': 24.59807014465332, + 'Location': array([250.32913208, 153.02793884, 0.30171746]), + 'Rotation': array([-2.00807545e-02, -6.81889114e+01, -1.33361816e-02]), + 'Velocity': array([ 3.12020838e-01, -4.34016973e-01, 8.68129719e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5319213867188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23981.140625 , 16560.03515625, 30.00003052]), + 'frame': 37815, + 'frame_number': 37815, + 'framesequence': 152493, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4201849699020386, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.423692997545, + 'timestamp_carla': 1283429, + 'timestamp_device': 2901986, + 'timestamp_stream': 1283.423692997545, + 'transform': [array([ 1.97100388e+02, 3.02376373e+02, -1.50167733e-01]), + array([-6.56381156e-03, -1.65420914e+02, 1.97448637e-02])]} +{'AngularVelocity': array([-0.01604232, -0.07034542, 4.06950569]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.373931884765625, + 'FR_Wheel_Angle': 24.911890029907227, + 'Location': array([250.4052124 , 152.91088867, 0.30169746]), + 'Rotation': array([-2.00807545e-02, -6.71166534e+01, -1.08032217e-02]), + 'Velocity': array([ 0.32253388, -0.44006038, -0.00044083]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5316162109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.9921875 , 16559.12695312, 29.99996948]), + 'frame': 37816, + 'frame_number': 37816, + 'framesequence': 152497, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4202765226364136, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.458270996809, + 'timestamp_carla': 1283463, + 'timestamp_device': 2902019, + 'timestamp_stream': 1283.458270996809, + 'transform': [array([ 1.97316788e+02, 3.02434204e+02, -1.50151446e-01]), + array([-6.92581153e-03, -1.65512070e+02, 1.97753832e-02])]} +{'AngularVelocity': array([-0.01734084, -0.07251927, 4.18139696]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.303611755371094, + 'FR_Wheel_Angle': 24.97938346862793, + 'Location': array([250.47206116, 152.81109619, 0.30169907]), + 'Rotation': array([-1.99304912e-02, -6.61594391e+01, -1.04675284e-02]), + 'Velocity': array([ 3.28707308e-01, -4.35697287e-01, -2.67848955e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5317993164062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.87304688, 16558.20117188, 30.00003052]), + 'frame': 37817, + 'frame_number': 37817, + 'framesequence': 152501, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4179876446723938, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.490557897836, + 'timestamp_carla': 1283495, + 'timestamp_device': 2902053, + 'timestamp_stream': 1283.490557897836, + 'transform': [array([ 1.97548767e+02, 3.02496674e+02, -1.50963321e-01]), + array([-5.67588676e-03, -1.65609802e+02, 1.93786528e-02])]} +{'AngularVelocity': array([0.00445174, 0.06328987, 3.75379229]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.57035255432129, + 'FR_Wheel_Angle': 30.183887481689453, + 'Location': array([250.54147339, 152.71444702, 0.30171058]), + 'Rotation': array([-2.06340011e-02, -6.51629105e+01, -1.29394522e-02]), + 'Velocity': array([ 3.19872200e-01, -3.78388047e-01, 1.27840045e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.528564453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.74414062, 16557.2109375 , 30. ]), + 'frame': 37818, + 'frame_number': 37818, + 'framesequence': 152505, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.40994906425476074, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.5269046984613, + 'timestamp_carla': 1283532, + 'timestamp_device': 2902086, + 'timestamp_stream': 1283.5269046984613, + 'transform': [array([ 1.97790344e+02, 3.02560822e+02, -1.50042802e-01]), + array([-5.98324556e-03, -1.65711533e+02, 1.97753850e-02])]} +{'AngularVelocity': array([4.11249883e-03, 6.87527061e-02, 4.39747286e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.024198532104492, + 'FR_Wheel_Angle': 29.29834747314453, + 'Location': array([250.6129303 , 152.62252808, 0.30170631]), + 'Rotation': array([-2.05725282e-02, -6.41067581e+01, -1.03149414e-02]), + 'Velocity': array([ 3.15750122e-01, -3.64474028e-01, -7.40432733e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.534423828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.58984375, 16556.22851562, 30. ]), + 'frame': 37819, + 'frame_number': 37819, + 'framesequence': 152509, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.39462265372276306, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.5574605986476, + 'timestamp_carla': 1283562, + 'timestamp_device': 2902119, + 'timestamp_stream': 1283.5574605986476, + 'transform': [array([ 1.98007462e+02, 3.02618195e+02, -1.50665626e-01]), + array([-5.73735870e-03, -1.65802902e+02, 1.95007212e-02])]} +{'AngularVelocity': array([ 0.00906635, -0.02771271, 4.97065926]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.074899673461914, + 'FR_Wheel_Angle': 29.144330978393555, + 'Location': array([250.6759491 , 152.54367065, 0.30170017]), + 'Rotation': array([-1.97392460e-02, -6.31771355e+01, -1.08337412e-02]), + 'Velocity': array([ 3.47429305e-01, -3.81193310e-01, -2.04696655e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5276489257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.4296875 , 16555.16796875, 29.99996948]), + 'frame': 37820, + 'frame_number': 37820, + 'framesequence': 152513, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3836909234523773, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.590534698218, + 'timestamp_carla': 1283595, + 'timestamp_device': 2902153, + 'timestamp_stream': 1283.590534698218, + 'transform': [array([ 1.98208939e+02, 3.02669403e+02, -1.50513843e-01]), + array([-6.31109439e-03, -1.65887604e+02, 1.95922758e-02])]} +{'AngularVelocity': array([-1.71634339e-04, 5.51316626e-02, 4.71186638e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.135339736938477, + 'FR_Wheel_Angle': 31.773393630981445, + 'Location': array([250.75195312, 152.45196533, 0.30170432]), + 'Rotation': array([-1.98348686e-02, -6.20745659e+01, -1.08337393e-02]), + 'Velocity': array([ 3.44615638e-01, -3.67952198e-01, -5.50651530e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5344848632812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.29101562, 16554.21679688, 30. ]), + 'frame': 37821, + 'frame_number': 37821, + 'framesequence': 152517, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36893218755722046, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.6247035004199, + 'timestamp_carla': 1283629, + 'timestamp_device': 2902186, + 'timestamp_stream': 1283.6247035004199, + 'transform': [array([ 1.98418976e+02, 3.02722412e+02, -1.50426820e-01]), + array([-6.74822647e-03, -1.65975876e+02, 1.96533110e-02])]} +{'AngularVelocity': array([-0.0297582 , 0.11414581, 5.31153536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.577463150024414, + 'FR_Wheel_Angle': 32.739952087402344, + 'Location': array([250.83087158, 152.36524963, 0.30171204]), + 'Rotation': array([-2.04427559e-02, -6.08591003e+01, -1.23596182e-02]), + 'Velocity': array([ 3.55246991e-01, -3.41603309e-01, 3.40442639e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5328979492188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.16210938, 16553.17578125, 30.00003052]), + 'frame': 37822, + 'frame_number': 37822, + 'framesequence': 152521, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3536973297595978, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.6590139977634, + 'timestamp_carla': 1283664, + 'timestamp_device': 2902219, + 'timestamp_stream': 1283.6590139977634, + 'transform': [array([ 1.98646317e+02, 3.02779877e+02, -1.50868520e-01]), + array([-7.17169838e-03, -1.66071304e+02, 1.95007231e-02])]} +{'AngularVelocity': array([-2.61136983e-03, 5.43802828e-02, 5.11964750e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.702648162841797, + 'FR_Wheel_Angle': 33.164791107177734, + 'Location': array([250.91247559, 152.28010559, 0.3017036 ]), + 'Rotation': array([-2.05725282e-02, -5.96241684e+01, -1.07116699e-02]), + 'Velocity': array([ 3.63606721e-01, -3.31089824e-01, -1.27840045e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5300903320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23980.03710938, 16552.08398438, 30. ]), + 'frame': 37823, + 'frame_number': 37823, + 'framesequence': 152525, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3446882665157318, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.690053999424, + 'timestamp_carla': 1283695, + 'timestamp_device': 2902253, + 'timestamp_stream': 1283.690053999424, + 'transform': [array([ 1.98847305e+02, 3.02829926e+02, -1.50789335e-01]), + array([-7.87520781e-03, -1.66155579e+02, 1.95617583e-02])]} +{'AngularVelocity': array([-0.02100358, 0.09609159, 5.36900806]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.694665908813477, + 'FR_Wheel_Angle': 33.395042419433594, + 'Location': array([250.99528503, 152.1973114 , 0.30170798]), + 'Rotation': array([-2.01149061e-02, -5.83910637e+01, -1.05285635e-02]), + 'Velocity': array([ 0.37002552, -0.32842535, 0.00038376]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5284423828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.91210938, 16550.9609375 , 30. ]), + 'frame': 37824, + 'frame_number': 37824, + 'framesequence': 152529, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3461165130138397, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.724154599011, + 'timestamp_carla': 1283729, + 'timestamp_device': 2902286, + 'timestamp_stream': 1283.724154599011, + 'transform': [array([ 1.99047607e+02, 3.02878357e+02, -1.50479957e-01]), + array([-7.75226438e-03, -1.66239563e+02, 1.96838304e-02])]} +{'AngularVelocity': array([ 0.03414616, -0.08806147, 6.78021574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.906206130981445, + 'FR_Wheel_Angle': 38.4797477722168, + 'Location': array([251.08244324, 152.11624146, 0.30170864]), + 'Rotation': array([-2.07569432e-02, -5.70987015e+01, -1.33972168e-02]), + 'Velocity': array([ 4.20537800e-01, -3.12682003e-01, -1.77555077e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5305786132812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.8125 , 16549.92578125, 29.99996948]), + 'frame': 37825, + 'frame_number': 37825, + 'framesequence': 152533, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35355085134506226, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.7576083987951, + 'timestamp_carla': 1283762, + 'timestamp_device': 2902319, + 'timestamp_stream': 1283.7576083987951, + 'transform': [array([ 1.99255859e+02, 3.02928772e+02, -1.50385201e-01]), + array([-7.60200014e-03, -1.66326828e+02, 1.97143443e-02])]} +{'AngularVelocity': array([ 0.0320373 , -0.09530839, 6.64205027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.316516876220703, + 'FR_Wheel_Angle': 37.74160385131836, + 'Location': array([251.18182373, 152.03266907, 0.30170324]), + 'Rotation': array([-2.05725282e-02, -5.55945930e+01, -1.13525400e-02]), + 'Velocity': array([ 4.20557469e-01, -2.94990122e-01, -1.96180335e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5285034179688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.7109375 , 16548.78320312, 30.00006104]), + 'frame': 37826, + 'frame_number': 37826, + 'framesequence': 152537, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3613513708114624, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.7895261980593, + 'timestamp_carla': 1283794, + 'timestamp_device': 2902353, + 'timestamp_stream': 1283.7895261980593, + 'transform': [array([ 1.99501358e+02, 3.02990143e+02, -1.50610611e-01]), + array([-7.07607577e-03, -1.66429672e+02, 1.95922740e-02])]} +{'AngularVelocity': array([ 0.02652989, -0.06947958, 6.64040947]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.323678970336914, + 'FR_Wheel_Angle': 37.520118713378906, + 'Location': array([251.27050781, 151.96173096, 0.30170652]), + 'Rotation': array([-2.02651694e-02, -5.42813759e+01, -1.10778799e-02]), + 'Velocity': array([ 4.22391385e-01, -2.83083171e-01, 2.27980607e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5285034179688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.609375 , 16547.63476562, 30.00003052]), + 'frame': 37827, + 'frame_number': 37827, + 'framesequence': 152541, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3671376705169678, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.8234652988613, + 'timestamp_carla': 1283828, + 'timestamp_device': 2902386, + 'timestamp_stream': 1283.8234652988613, + 'transform': [array([ 1.99750549e+02, 3.03051544e+02, -1.49596751e-01]), + array([-7.39026442e-03, -1.66534042e+02, 2.00195219e-02])]} +{'AngularVelocity': array([ 0.03587699, -0.09020615, 6.76508951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.66936683654785, + 'FR_Wheel_Angle': 40.78397750854492, + 'Location': array([251.35780334, 151.89550781, 0.30170947]), + 'Rotation': array([-2.05725282e-02, -5.29992828e+01, -1.15356427e-02]), + 'Velocity': array([ 4.22281206e-01, -2.60751039e-01, 1.05981824e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.531982421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.48046875, 16546.51367188, 30. ]), + 'frame': 37828, + 'frame_number': 37828, + 'framesequence': 152545, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36666160821914673, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.8560165986419, + 'timestamp_carla': 1283861, + 'timestamp_device': 2902419, + 'timestamp_stream': 1283.8560165986419, + 'transform': [array([ 1.99986298e+02, 3.03108978e+02, -1.48892701e-01]), + array([-7.26732099e-03, -1.66632767e+02, 2.02941801e-02])]} +{'AngularVelocity': array([ 0.02858447, -0.08430308, 6.72831249]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.600954055786133, + 'FR_Wheel_Angle': 41.60912322998047, + 'Location': array([251.44523621, 151.83580017, 0.30170485]), + 'Rotation': array([-2.07842644e-02, -5.16411972e+01, -1.15356436e-02]), + 'Velocity': array([ 4.18729156e-01, -2.31845468e-01, -5.75637787e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.528564453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.33984375, 16545.33984375, 30. ]), + 'frame': 37829, + 'frame_number': 37829, + 'framesequence': 152548, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3632923364639282, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.888340599835, + 'timestamp_carla': 1283893, + 'timestamp_device': 2902444, + 'timestamp_stream': 1283.888340599835, + 'transform': [array([ 2.00224442e+02, 3.03166351e+02, -1.49124101e-01]), + array([-7.32879248e-03, -1.66732391e+02, 2.02026255e-02])]} +{'AngularVelocity': array([ 0.04231369, -0.08818677, 7.01229525]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79779624938965, + 'FR_Wheel_Angle': 41.695064544677734, + 'Location': array([251.53341675, 151.77911377, 0.30170006]), + 'Rotation': array([-2.02036984e-02, -5.02813301e+01, -1.15661621e-02]), + 'Velocity': array([ 0.42556757, -0.2183094 , -0.00044184]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5291137695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.20117188, 16544.20117188, 30. ]), + 'frame': 37830, + 'frame_number': 37830, + 'framesequence': 152552, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35920900106430054, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.921313598752, + 'timestamp_carla': 1283926, + 'timestamp_device': 2902478, + 'timestamp_stream': 1283.921313598752, + 'transform': [array([ 2.00460388e+02, 3.03221954e+02, -1.49797469e-01]), + array([-6.65260386e-03, -1.66831100e+02, 1.98974498e-02])]} +{'AngularVelocity': array([-0.04383299, 0.09352522, 6.18348169]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.783824920654297, + 'FR_Wheel_Angle': 41.661312103271484, + 'Location': array([251.62321472, 151.72363281, 0.3016988 ]), + 'Rotation': array([-2.01422274e-02, -4.89001923e+01, -1.01623526e-02]), + 'Velocity': array([ 3.94701630e-01, -2.06616223e-01, -2.23722454e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5300903320312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23979.06835938, 16543.0390625 , 30.00003052]), + 'frame': 37831, + 'frame_number': 37831, + 'framesequence': 152557, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35635244846343994, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.9562226980925, + 'timestamp_carla': 1283961, + 'timestamp_device': 2902519, + 'timestamp_stream': 1283.9562226980925, + 'transform': [array([ 2.00718536e+02, 3.03282837e+02, -1.49626613e-01]), + array([-6.37939619e-03, -1.66939041e+02, 1.99584868e-02])]} +{'AngularVelocity': array([-0.05134048, 0.10877967, 5.95580006]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.783876419067383, + 'FR_Wheel_Angle': 41.65852355957031, + 'Location': array([251.71542358, 151.66990662, 0.30171028]), + 'Rotation': array([-2.03198120e-02, -4.74980011e+01, -1.00707998e-02]), + 'Velocity': array([ 3.98644239e-01, -1.95670739e-01, 2.90441501e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.531982421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23978.93164062, 16541.80273438, 29.99996948]), + 'frame': 37832, + 'frame_number': 37832, + 'framesequence': 152561, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3571947515010834, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1283.9905417002738, + 'timestamp_carla': 1283995, + 'timestamp_device': 2902552, + 'timestamp_stream': 1283.9905417002738, + 'transform': [array([ 2.00971283e+02, 3.03342102e+02, -1.48604125e-01]), + array([-6.65260386e-03, -1.67044662e+02, 2.03857347e-02])]} +{'AngularVelocity': array([ 0.0508035 , -0.07582472, 7.00680208]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79694175720215, + 'FR_Wheel_Angle': 41.68580627441406, + 'Location': array([251.80966187, 151.6179657 , 0.30170387]), + 'Rotation': array([-1.99919622e-02, -4.60769806e+01, -1.09863281e-02]), + 'Velocity': array([ 4.43429291e-01, -1.90944195e-01, -1.20592114e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.529052734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23978.77929688, 16540.50976562, 29.99996948]), + 'frame': 37833, + 'frame_number': 37833, + 'framesequence': 152565, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35930055379867554, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.0225564986467, + 'timestamp_carla': 1284027, + 'timestamp_device': 2902586, + 'timestamp_stream': 1284.0225564986467, + 'transform': [array([ 2.01187668e+02, 3.03391357e+02, -1.48026198e-01]), + array([-6.98728301e-03, -1.67135040e+02, 2.06298735e-02])]} +{'AngularVelocity': array([ 0.05009092, -0.08308019, 6.93876076]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.801597595214844, + 'FR_Wheel_Angle': 41.68239974975586, + 'Location': array([251.90396118, 151.56954956, 0.30170172]), + 'Rotation': array([-2.05383785e-02, -4.47031059e+01, -1.05285635e-02]), + 'Velocity': array([ 4.39709514e-01, -1.75081879e-01, -6.12640360e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.526611328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23978.62890625, 16539.2578125 , 30.00003052]), + 'frame': 37834, + 'frame_number': 37834, + 'framesequence': 152568, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3611682653427124, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.0553482994437, + 'timestamp_carla': 1284060, + 'timestamp_device': 2902611, + 'timestamp_stream': 1284.0553482994437, + 'transform': [array([ 2.01429016e+02, 3.03446594e+02, -1.47970885e-01]), + array([-7.17169838e-03, -1.67235825e+02, 2.06603911e-02])]} +{'AngularVelocity': array([ 0.04534787, -0.07839533, 6.75566959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.800851821899414, + 'FR_Wheel_Angle': 41.69310760498047, + 'Location': array([251.99703979, 151.52441406, 0.30171072]), + 'Rotation': array([-2.00534351e-02, -4.33624954e+01, -1.08337393e-02]), + 'Velocity': array([ 4.44162220e-01, -1.66998714e-01, 2.88858399e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5281982421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23978.49804688, 16538.07421875, 30.00003052]), + 'frame': 37835, + 'frame_number': 37835, + 'framesequence': 152573, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3610400855541229, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.0896722003818, + 'timestamp_carla': 1284094, + 'timestamp_device': 2902652, + 'timestamp_stream': 1284.0896722003818, + 'transform': [array([ 2.01685089e+02, 3.03504517e+02, -1.48312107e-01]), + array([-6.80969842e-03, -1.67342712e+02, 2.05078050e-02])]} +{'AngularVelocity': array([ 0.04976972, -0.06715499, 6.89189434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80223274230957, + 'FR_Wheel_Angle': 41.70038604736328, + 'Location': array([252.07843018, 151.48716736, 0.30170688]), + 'Rotation': array([-1.97119247e-02, -4.22026863e+01, -1.11083975e-02]), + 'Velocity': array([ 4.47776049e-01, -1.57268003e-01, -9.91821253e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5284423828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23978.35546875, 16536.83203125, 30. ]), + 'frame': 37836, + 'frame_number': 37836, + 'framesequence': 152577, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3597033619880676, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.1225266978145, + 'timestamp_carla': 1284127, + 'timestamp_device': 2902686, + 'timestamp_stream': 1284.1225266978145, + 'transform': [array([ 2.01951981e+02, 3.03565582e+02, -1.48326531e-01]), + array([-6.95996219e-03, -1.67454056e+02, 2.05078013e-02])]} +{'AngularVelocity': array([-11.17396927, 26.84268188, 4.89320183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.798004150390625, + 'FR_Wheel_Angle': 41.7027473449707, + 'Location': array([252.15052795, 151.45053101, 0.26011813]), + 'Rotation': array([ -1.93618774, -41.23172379, 4.08118105]), + 'Velocity': array([ 0.45385161, -0.01697973, -0.39839315]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5275268554688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23978.19335938, 16535.49414062, 30.00003052]), + 'frame': 37837, + 'frame_number': 37837, + 'framesequence': 152581, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35887935757637024, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.1555668003857, + 'timestamp_carla': 1284160, + 'timestamp_device': 2902719, + 'timestamp_stream': 1284.1555668003857, + 'transform': [array([ 2.02194016e+02, 3.03619110e+02, -1.47885323e-01]), + array([-7.07607577e-03, -1.67554962e+02, 2.06909105e-02])]} +{'AngularVelocity': array([ 0.25839505, -1.06483459, 6.04252338]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79962730407715, + 'FR_Wheel_Angle': 41.68651580810547, + 'Location': array([2.52241211e+02, 1.51415482e+02, 2.41117626e-01]), + 'Rotation': array([ -2.42712116, -40.00914383, 4.87281227]), + 'Velocity': array([ 0.46211427, -0.14896607, 0.02272822]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5284423828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23978.03125 , 16534.22070312, 30. ]), + 'frame': 37838, + 'frame_number': 37838, + 'framesequence': 152584, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35957521200180054, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.1877976991236, + 'timestamp_carla': 1284192, + 'timestamp_device': 2902744, + 'timestamp_stream': 1284.1877976991236, + 'transform': [array([ 2.02454529e+02, 3.03676941e+02, -1.49000853e-01]), + array([-6.37939619e-03, -1.67663574e+02, 2.02026274e-02])]} +{'AngularVelocity': array([ 0.1535778 , -0.43146828, 6.50169849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79095458984375, + 'FR_Wheel_Angle': 41.65727996826172, + 'Location': array([2.52357071e+02, 1.51370880e+02, 2.45501086e-01]), + 'Rotation': array([ -2.33309007, -38.40507126, 4.77164507]), + 'Velocity': array([ 0.49420229, -0.13760827, 0.00900115]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5281372070312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23977.8828125 , 16532.93359375, 29.99996948]), + 'frame': 37839, + 'frame_number': 37839, + 'framesequence': 152589, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3602893054485321, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.2219986990094, + 'timestamp_carla': 1284227, + 'timestamp_device': 2902786, + 'timestamp_stream': 1284.2219986990094, + 'transform': [array([ 2.02744522e+02, 3.03741089e+02, -1.49571151e-01]), + array([-6.01056591e-03, -1.67784439e+02, 1.99584886e-02])]} +{'AngularVelocity': array([ 0.09498989, -0.20752472, 6.40006447]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.793169021606445, + 'FR_Wheel_Angle': 41.66118240356445, + 'Location': array([2.52448044e+02, 1.51338440e+02, 2.46419102e-01]), + 'Rotation': array([ -2.31853485, -37.15262985, 4.74544001]), + 'Velocity': array([ 0.49191847, -0.1253908 , 0.00242592]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5320434570312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23977.71484375, 16531.61328125, 30.00003052]), + 'frame': 37840, + 'frame_number': 37840, + 'framesequence': 152593, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.36017945408821106, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.2571282982826, + 'timestamp_carla': 1284262, + 'timestamp_device': 2902819, + 'timestamp_stream': 1284.2571282982826, + 'transform': [array([ 2.03053055e+02, 3.03808868e+02, -1.49852291e-01]), + array([-5.73735870e-03, -1.67912949e+02, 1.98364183e-02])]} +{'AngularVelocity': array([ 0.18761341, -0.23634188, 6.1023984 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.774839401245117, + 'FR_Wheel_Angle': 41.638240814208984, + 'Location': array([2.52555664e+02, 1.51302826e+02, 2.46609375e-01]), + 'Rotation': array([ -2.31188226, -35.66314697, 4.7403636 ]), + 'Velocity': array([ 5.03559351e-01, -1.16679847e-01, 1.88112259e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5311889648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23977.5234375, 16530.1875 , 30. ]), + 'frame': 37841, + 'frame_number': 37841, + 'framesequence': 152597, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35930055379867554, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.2904786989093, + 'timestamp_carla': 1284295, + 'timestamp_device': 2902852, + 'timestamp_stream': 1284.2904786989093, + 'transform': [array([ 2.03347931e+02, 3.03873108e+02, -1.49302408e-01]), + array([-6.22913241e-03, -1.68035675e+02, 2.00805608e-02])]} +{'AngularVelocity': array([ 0.16436599, -0.1581448 , 5.59331131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.790006637573242, + 'FR_Wheel_Angle': 41.658260345458984, + 'Location': array([2.52663803e+02, 1.51270264e+02, 2.46642753e-01]), + 'Rotation': array([ -2.30980587, -34.21626282, 4.73203564]), + 'Velocity': array([ 5.01867652e-01, -1.12718619e-01, 1.78718561e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5292358398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23977.31445312, 16528.6953125 , 30.00003052]), + 'frame': 37842, + 'frame_number': 37842, + 'framesequence': 152601, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.35270851850509644, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.322660498321, + 'timestamp_carla': 1284327, + 'timestamp_device': 2902886, + 'timestamp_stream': 1284.322660498321, + 'transform': [array([ 2.03621170e+02, 3.03931427e+02, -1.48742780e-01]), + array([-6.68675499e-03, -1.68149353e+02, 2.03246977e-02])]} +{'AngularVelocity': array([ 0.05386863, -0.09651516, 6.73903561]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.776748657226562, + 'FR_Wheel_Angle': 41.62947463989258, + 'Location': array([2.52789734e+02, 1.51236252e+02, 2.46650428e-01]), + 'Rotation': array([ -2.31057096, -32.52861023, 4.7322154 ]), + 'Velocity': array([ 5.33073664e-01, -9.76016596e-02, 1.06821055e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5291748046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23977.11914062, 16527.28515625, 29.99996948]), + 'frame': 37843, + 'frame_number': 37843, + 'framesequence': 152605, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3420697748661041, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.356261499226, + 'timestamp_carla': 1284361, + 'timestamp_device': 2902919, + 'timestamp_stream': 1284.356261499226, + 'transform': [array([ 2.03915970e+02, 3.03993927e+02, -1.48638114e-01]), + array([-7.02143414e-03, -1.68271912e+02, 2.03857291e-02])]} +{'AngularVelocity': array([-0.27204561, 0.20517735, 7.263134 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.768863677978516, + 'FR_Wheel_Angle': 41.68955612182617, + 'Location': array([2.52881210e+02, 1.51213791e+02, 2.46648207e-01]), + 'Rotation': array([ -2.31078959, -31.31107712, 4.73768377]), + 'Velocity': array([ 4.88722801e-01, -7.00101927e-02, 7.57217413e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5298461914062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23976.93554688, 16525.91796875, 30.00003052]), + 'frame': 37844, + 'frame_number': 37844, + 'framesequence': 152609, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.32776880264282227, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.3904084973037, + 'timestamp_carla': 1284395, + 'timestamp_device': 2902952, + 'timestamp_stream': 1284.3904084973037, + 'transform': [array([ 2.04196869e+02, 3.04052032e+02, -1.48164630e-01]), + array([-7.41758524e-03, -1.68388626e+02, 2.05993559e-02])]} +{'AngularVelocity': array([5.24775076, 0.59561819, 5.22001505]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.780179977416992, + 'FR_Wheel_Angle': 41.68674087524414, + 'Location': array([2.52986160e+02, 1.51193695e+02, 1.97234303e-01]), + 'Rotation': array([ -4.38000202, -29.93259239, 0.43476295]), + 'Velocity': array([ 0.42643669, -0.12506971, -0.14124852]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.528564453125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23976.74609375, 16524.47070312, 30.00006104]), + 'frame': 37845, + 'frame_number': 37845, + 'framesequence': 152613, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3124057948589325, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.425041899085, + 'timestamp_carla': 1284430, + 'timestamp_device': 2902986, + 'timestamp_stream': 1284.425041899085, + 'transform': [array([ 2.04470154e+02, 3.04107147e+02, -1.48144111e-01]), + array([-7.77958520e-03, -1.68502060e+02, 2.06298716e-02])]} +{'AngularVelocity': array([ 0.7576232 , -0.29291669, 5.81403494]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.805919647216797, + 'FR_Wheel_Angle': 41.70185852050781, + 'Location': array([2.53081573e+02, 1.51173264e+02, 1.90423012e-01]), + 'Rotation': array([ -4.56673956, -28.65035439, 0.09097391]), + 'Velocity': array([ 0.46422037, -0.05338877, 0.00150634]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5263061523438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23976.56835938, 16523.00976562, 29.99996948]), + 'frame': 37846, + 'frame_number': 37846, + 'framesequence': 152616, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2964751124382019, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.455477297306, + 'timestamp_carla': 1284460, + 'timestamp_device': 2903011, + 'timestamp_stream': 1284.455477297306, + 'transform': [array([ 2.04700363e+02, 3.04152496e+02, -1.47787899e-01]), + array([-8.72898102e-03, -1.68597534e+02, 2.08129752e-02])]} +{'AngularVelocity': array([ 0.39310798, -0.25902212, 5.65470886]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.806381225585938, + 'FR_Wheel_Angle': 41.68452453613281, + 'Location': array([2.53182510e+02, 1.51155365e+02, 1.91241682e-01]), + 'Rotation': array([-4.58429289e+00, -2.72997265e+01, 1.49151161e-02]), + 'Velocity': array([ 0.46343866, -0.03628271, 0.00215923]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5238647460938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23976.40234375, 16521.50390625, 29.99996948]), + 'frame': 37847, + 'frame_number': 37847, + 'framesequence': 152621, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2863490879535675, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.4901437982917, + 'timestamp_carla': 1284495, + 'timestamp_device': 2903052, + 'timestamp_stream': 1284.4901437982917, + 'transform': [array([ 2.04959335e+02, 3.04202240e+02, -1.48526385e-01]), + array([-9.03633982e-03, -1.68704819e+02, 2.05383208e-02])]} +{'AngularVelocity': array([-0.12581137, 0.13414887, 6.34688187]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.798534393310547, + 'FR_Wheel_Angle': 41.6953239440918, + 'Location': array([2.53285202e+02, 1.51139496e+02, 1.91563532e-01]), + 'Rotation': array([-4.59054279e+00, -2.59267673e+01, -5.76792099e-03]), + 'Velocity': array([ 0.47520053, -0.0397235 , 0.00058948]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5264892578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23976.27929688, 16520.17578125, 30. ]), + 'frame': 37848, + 'frame_number': 37848, + 'framesequence': 152625, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.28521379828453064, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.5225614979863, + 'timestamp_carla': 1284527, + 'timestamp_device': 2903086, + 'timestamp_stream': 1284.5225614979863, + 'transform': [array([ 2.05190430e+02, 3.04245789e+02, -1.47847250e-01]), + array([-9.70569812e-03, -1.68800461e+02, 2.08434947e-02])]} +{'AngularVelocity': array([0.1392505 , 0.0579573 , 4.84781599]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.778722763061523, + 'FR_Wheel_Angle': 41.65906524658203, + 'Location': array([2.53388855e+02, 1.51126434e+02, 1.91581041e-01]), + 'Rotation': array([-4.58642387e+00, -2.45540257e+01, -2.01111082e-02]), + 'Velocity': array([ 4.61204022e-01, -2.03854106e-02, 1.97420115e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5231323242188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23976.1484375 , 16518.61328125, 29.99996948]), + 'frame': 37849, + 'frame_number': 37849, + 'framesequence': 152628, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.290450781583786, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.5557635985315, + 'timestamp_carla': 1284560, + 'timestamp_device': 2903111, + 'timestamp_stream': 1284.5557635985315, + 'transform': [array([ 2.05453842e+02, 3.04296478e+02, -1.47644386e-01]), + array([-9.3027167e-03, -1.6890950e+02, 2.0904528e-02])]} +{'AngularVelocity': array([0.05617937, 0.08038605, 4.60230827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.795433044433594, + 'FR_Wheel_Angle': 41.68257522583008, + 'Location': array([2.53492294e+02, 1.51116302e+02, 1.91615552e-01]), + 'Rotation': array([-4.59124613e+00, -2.31997814e+01, -1.98058952e-02]), + 'Velocity': array([ 4.21335638e-01, -9.01727565e-03, -1.86767575e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5225219726562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23976.04296875, 16517.17382812, 30. ]), + 'frame': 37850, + 'frame_number': 37850, + 'framesequence': 152632, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29792168736457825, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.588250298053, + 'timestamp_carla': 1284593, + 'timestamp_device': 2903144, + 'timestamp_stream': 1284.588250298053, + 'transform': [array([ 2.05687653e+02, 3.04339722e+02, -1.46908790e-01]), + array([-8.94071721e-03, -1.69006271e+02, 2.11791899e-02])]} +{'AngularVelocity': array([0.00865388, 0.08943285, 4.77004242]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7919864654541, + 'FR_Wheel_Angle': 41.684661865234375, + 'Location': array([2.53593781e+02, 1.51108536e+02, 1.91627875e-01]), + 'Rotation': array([-4.59243441e+00, -2.18726997e+01, -2.13927981e-02]), + 'Velocity': array([4.31080818e-01, 1.03033893e-03, 1.55453672e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5232543945312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23975.9140625 , 16515.69140625, 30.00003052]), + 'frame': 37851, + 'frame_number': 37851, + 'framesequence': 152636, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3050813376903534, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.6221967972815, + 'timestamp_carla': 1284627, + 'timestamp_device': 2903177, + 'timestamp_stream': 1284.6221967972815, + 'transform': [array([ 2.05964523e+02, 3.04392029e+02, -1.47312731e-01]), + array([-8.48309416e-03, -1.69120850e+02, 2.09960844e-02])]} +{'AngularVelocity': array([ 0.15209854, -0.0276997 , 4.79254246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.791912078857422, + 'FR_Wheel_Angle': 41.67502212524414, + 'Location': array([2.53696671e+02, 1.51103226e+02, 1.91616774e-01]), + 'Rotation': array([ -4.5911231 , -20.5303936 , -0.02139281]), + 'Velocity': array([4.42110598e-01, 1.52108893e-02, 6.37817357e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5242309570312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23975.79101562, 16514.24023438, 30. ]), + 'frame': 37852, + 'frame_number': 37852, + 'framesequence': 152640, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3068941533565521, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.655562799424, + 'timestamp_carla': 1284660, + 'timestamp_device': 2903211, + 'timestamp_stream': 1284.655562799424, + 'transform': [array([ 2.06237549e+02, 3.04443085e+02, -1.47416875e-01]), + array([-8.12109467e-03, -1.69233780e+02, 2.09350493e-02])]} +{'AngularVelocity': array([0.07694976, 0.13455811, 4.53189039]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.791316986083984, + 'FR_Wheel_Angle': 41.676395416259766, + 'Location': array([2.53798523e+02, 1.51100372e+02, 1.91621542e-01]), + 'Rotation': array([ -4.59130764, -19.19742012, -0.02050782]), + 'Velocity': array([ 4.30841923e-01, 1.69603173e-02, -9.42516272e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5238647460938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23975.63476562, 16512.6875 , 29.99996948]), + 'frame': 37853, + 'frame_number': 37853, + 'framesequence': 152645, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3044953942298889, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.689513400197, + 'timestamp_carla': 1284694, + 'timestamp_device': 2903252, + 'timestamp_stream': 1284.689513400197, + 'transform': [array([ 2.06517609e+02, 3.04494873e+02, -1.47377312e-01]), + array([-7.77958520e-03, -1.69349579e+02, 2.09350474e-02])]} +{'AngularVelocity': array([0.0384351 , 0.12211904, 4.4248414 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.793739318847656, + 'FR_Wheel_Angle': 41.68272399902344, + 'Location': array([2.53899765e+02, 1.51099915e+02, 1.91617206e-01]), + 'Rotation': array([ -4.59231138, -17.87864113, -0.02407843]), + 'Velocity': array([ 4.18071270e-01, 2.83636898e-02, -3.54042044e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5247802734375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23975.48046875, 16511.15820312, 30. ]), + 'frame': 37854, + 'frame_number': 37854, + 'framesequence': 152649, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3007965683937073, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.7231058999896, + 'timestamp_carla': 1284728, + 'timestamp_device': 2903286, + 'timestamp_stream': 1284.7231058999896, + 'transform': [array([ 2.06762177e+02, 3.04537292e+02, -1.48203611e-01]), + array([-7.14437757e-03, -1.69450729e+02, 2.05688421e-02])]} +{'AngularVelocity': array([ 0.36347902, -0.11169957, 4.62733746]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.790576934814453, + 'FR_Wheel_Angle': 41.68305587768555, + 'Location': array([2.54002060e+02, 1.51101486e+02, 1.91601098e-01]), + 'Rotation': array([ -4.59057665, -16.54872322, -0.02487183]), + 'Velocity': array([ 4.56738889e-01, 4.92167361e-02, -3.66811757e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.524658203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23975.31835938, 16509.58984375, 30.00003052]), + 'frame': 37855, + 'frame_number': 37855, + 'framesequence': 152652, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29718926548957825, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.755543999374, + 'timestamp_carla': 1284760, + 'timestamp_device': 2903311, + 'timestamp_stream': 1284.755543999374, + 'transform': [array([ 2.07008453e+02, 3.04580566e+02, -1.47420123e-01]), + array([-7.60200014e-03, -1.69552490e+02, 2.09045336e-02])]} +{'AngularVelocity': array([ 0.28439322, -0.1176523 , 5.34235764]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.791215896606445, + 'FR_Wheel_Angle': 41.678062438964844, + 'Location': array([2.54091171e+02, 1.51104736e+02, 1.91599235e-01]), + 'Rotation': array([ -4.58816576, -15.38554859, -0.02096564]), + 'Velocity': array([4.68643546e-01, 6.17995672e-02, 1.64346697e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5266723632812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23975.1640625 , 16507.98632812, 30. ]), + 'frame': 37856, + 'frame_number': 37856, + 'framesequence': 152656, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29704275727272034, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.7886377982795, + 'timestamp_carla': 1284793, + 'timestamp_device': 2903344, + 'timestamp_stream': 1284.7886377982795, + 'transform': [array([ 2.07261551e+02, 3.04624481e+02, -1.47072598e-01]), + array([-7.84105714e-03, -1.69657013e+02, 2.10571177e-02])]} +{'AngularVelocity': array([ 0.30899149, -0.14559476, 5.94769478]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.802942276000977, + 'FR_Wheel_Angle': 41.69435501098633, + 'Location': array([2.54196289e+02, 1.51110931e+02, 1.91599160e-01]), + 'Rotation': array([ -4.58960009, -14.01164722, -0.02270506]), + 'Velocity': array([ 4.78128523e-01, 7.46840537e-02, -8.59832726e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5269775390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23975.01953125, 16506.47460938, 30. ]), + 'frame': 37857, + 'frame_number': 37857, + 'framesequence': 152660, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2986358404159546, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.8214889988303, + 'timestamp_carla': 1284826, + 'timestamp_device': 2903377, + 'timestamp_stream': 1284.8214889988303, + 'transform': [array([ 2.07517792e+02, 3.04668793e+02, -1.46659166e-01]), + array([-7.60200014e-03, -1.69762848e+02, 2.12097075e-02])]} +{'AngularVelocity': array([ 0.20393009, -0.09297898, 6.08815002]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.795644760131836, + 'FR_Wheel_Angle': 41.68439865112305, + 'Location': array([2.54299744e+02, 1.51119263e+02, 1.91607624e-01]), + 'Rotation': array([ -4.59100723, -12.64101124, -0.01431275]), + 'Velocity': array([ 4.81534719e-01, 8.42118263e-02, -3.50570685e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5260620117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23974.86914062, 16504.91796875, 30. ]), + 'frame': 37858, + 'frame_number': 37858, + 'framesequence': 152665, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3004302978515625, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.855097398162, + 'timestamp_carla': 1284860, + 'timestamp_device': 2903419, + 'timestamp_stream': 1284.855097398162, + 'transform': [array([ 2.07773590e+02, 3.04712036e+02, -1.46555975e-01]), + array([-7.35611329e-03, -1.69868484e+02, 2.12402251e-02])]} +{'AngularVelocity': array([ 0.32530236, -0.18694516, 6.03920221]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.794981002807617, + 'FR_Wheel_Angle': 41.68362808227539, + 'Location': array([2.54406769e+02, 1.51130539e+02, 1.91599041e-01]), + 'Rotation': array([ -4.58923101, -11.2181263 , -0.01510622]), + 'Velocity': array([ 4.83215213e-01, 1.02359958e-01, -1.57833092e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.526611328125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23974.703125 , 16503.37109375, 30.00003052]), + 'frame': 37859, + 'frame_number': 37859, + 'framesequence': 152668, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3011261522769928, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.8872045986354, + 'timestamp_carla': 1284892, + 'timestamp_device': 2903444, + 'timestamp_stream': 1284.8872045986354, + 'transform': [array([ 2.08024338e+02, 3.04754242e+02, -1.46699980e-01]), + array([-7.35611329e-03, -1.69971985e+02, 2.11791880e-02])]} +{'AngularVelocity': array([ 0.29916567, -0.14549325, 6.01929522]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79344940185547, + 'FR_Wheel_Angle': 41.678001403808594, + 'Location': array([2.54512665e+02, 1.51144180e+02, 1.91618726e-01]), + 'Rotation': array([-4.59087706, -9.80412006, -0.01043701]), + 'Velocity': array([ 4.80836183e-01, 1.12181820e-01, -6.10828356e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5260620117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23974.53710938, 16501.77929688, 30. ]), + 'frame': 37860, + 'frame_number': 37860, + 'framesequence': 152673, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.30008241534233093, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.9232307970524, + 'timestamp_carla': 1284928, + 'timestamp_device': 2903486, + 'timestamp_stream': 1284.9232307970524, + 'transform': [array([ 2.08312195e+02, 3.04802368e+02, -1.46846160e-01]), + array([-7.11022643e-03, -1.70090744e+02, 2.11181547e-02])]} +{'AngularVelocity': array([ 0.32215759, -0.16783701, 5.89969635]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 29.227771759033203, + 'FR_Wheel_Angle': 37.98491668701172, + 'Location': array([2.54619720e+02, 1.51160843e+02, 1.91593885e-01]), + 'Rotation': array([-4.58811092, -8.38434792, -0.01431272]), + 'Velocity': array([ 4.87286508e-01, 1.21938877e-01, -3.98883800e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5277709960938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23974.375 , 16500.24804688, 30. ]), + 'frame': 37861, + 'frame_number': 37861, + 'framesequence': 152676, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.299203485250473, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.9557322971523, + 'timestamp_carla': 1284960, + 'timestamp_device': 2903511, + 'timestamp_stream': 1284.9557322971523, + 'transform': [array([ 2.08571671e+02, 3.04845337e+02, -1.46521181e-01]), + array([-7.04875495e-03, -1.70197769e+02, 2.12402251e-02])]} +{'AngularVelocity': array([ 0.28703395, -0.10692834, 5.40832663]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.58669662475586, + 'FR_Wheel_Angle': 37.92611312866211, + 'Location': array([2.54728943e+02, 1.51176865e+02, 1.91606328e-01]), + 'Rotation': array([-4.58929968, -7.07550764, -0.0108032 ]), + 'Velocity': array([4.83037412e-01, 1.15098692e-01, 7.90500635e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5233764648438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23974.18359375, 16498.51757812, 29.99996948]), + 'frame': 37862, + 'frame_number': 37862, + 'framesequence': 152680, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29958799481391907, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1284.9881889000535, + 'timestamp_carla': 1284993, + 'timestamp_device': 2903544, + 'timestamp_stream': 1284.9881889000535, + 'transform': [array([ 2.08822098e+02, 3.04885529e+02, -1.46756589e-01]), + array([-7.17169838e-03, -1.70301010e+02, 2.11486742e-02])]} +{'AngularVelocity': array([ 0.26296803, -0.09058528, 5.57198477]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.336158752441406, + 'FR_Wheel_Angle': 37.58456802368164, + 'Location': array([2.54838516e+02, 1.51195343e+02, 1.91612273e-01]), + 'Rotation': array([-4.58978462, -5.75512981, -0.0126648 ]), + 'Velocity': array([0.49118122, 0.12772991, 0.00050488]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5256958007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23974.0078125 , 16496.96484375, 29.99996948]), + 'frame': 37863, + 'frame_number': 37863, + 'framesequence': 152684, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3003021478652954, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1285.020959097892, + 'timestamp_carla': 1285025, + 'timestamp_device': 2903577, + 'timestamp_stream': 1285.020959097892, + 'transform': [array([ 2.09091171e+02, 3.04929321e+02, -1.46310687e-01]), + array([-7.26732099e-03, -1.70411911e+02, 2.13317759e-02])]} +{'AngularVelocity': array([ 0.24592255, -0.09244614, 5.64201498]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 28.182010650634766, + 'FR_Wheel_Angle': 36.653038024902344, + 'Location': array([2.54949219e+02, 1.51216644e+02, 1.91597968e-01]), + 'Rotation': array([-4.58975029, -4.41998434, -0.01223753]), + 'Velocity': array([ 4.87848967e-01, 1.39805257e-01, -2.96478276e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5271606445312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23973.84179688, 16495.38671875, 30. ]), + 'frame': 37864, + 'frame_number': 37864, + 'framesequence': 152688, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.300283819437027, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1285.0557650998235, + 'timestamp_carla': 1285060, + 'timestamp_device': 2903611, + 'timestamp_stream': 1285.0557650998235, + 'transform': [array([ 2.09373428e+02, 3.04974213e+02, -1.46468967e-01]), + array([-7.20584905e-03, -1.70528214e+02, 2.12707426e-02])]} +{'AngularVelocity': array([0.19717531, 0.08274628, 3.82714558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.168336868286133, + 'FR_Wheel_Angle': 32.9439697265625, + 'Location': array([2.55075424e+02, 1.51241409e+02, 1.91608846e-01]), + 'Rotation': array([-4.58886909, -3.0080266 , -0.00833131]), + 'Velocity': array([4.68551159e-01, 1.16752915e-01, 1.03654857e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5269165039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23973.65820312, 16493.8125 , 30. ]), + 'frame': 37865, + 'frame_number': 37865, + 'framesequence': 152692, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2999359369277954, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1285.088622096926, + 'timestamp_carla': 1285093, + 'timestamp_device': 2903644, + 'timestamp_stream': 1285.088622096926, + 'transform': [array([ 2.09631699e+02, 3.05014069e+02, -1.46813542e-01]), + array([-6.98728301e-03, -1.70634628e+02, 2.11181547e-02])]} +{'AngularVelocity': array([0.12395144, 0.12322201, 3.76020813]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.5656681060791, + 'FR_Wheel_Angle': 33.15829849243164, + 'Location': array([2.55186707e+02, 1.51265015e+02, 1.91622198e-01]), + 'Rotation': array([-4.5917654 , -1.83804369, -0.0206604 ]), + 'Velocity': array([ 4.50753838e-01, 1.23996645e-01, -5.40733345e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.524658203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23973.45898438, 16492.10742188, 30. ]), + 'frame': 37866, + 'frame_number': 37866, + 'framesequence': 152697, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2959624230861664, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1285.1222025975585, + 'timestamp_carla': 1285127, + 'timestamp_device': 2903686, + 'timestamp_stream': 1285.1222025975585, + 'transform': [array([ 2.09906677e+02, 3.05056641e+02, -1.46750942e-01]), + array([-7.07607577e-03, -1.70747894e+02, 2.11486742e-02])]} +{'AngularVelocity': array([ 2.26268744, -33.07719421, 4.34062862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.752477645874023, + 'FR_Wheel_Angle': 33.39719009399414, + 'Location': array([2.55299149e+02, 1.51292038e+02, 1.19918287e-01]), + 'Rotation': array([-1.82030678, -0.68228155, 0.93519747]), + 'Velocity': array([ 0.32475355, 0.18771836, -0.67698395]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52685546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23973.2734375 , 16490.47851562, 29.99993896]), + 'frame': 37867, + 'frame_number': 37867, + 'framesequence': 152701, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.28600117564201355, + 'throttle_input': 0.08729686588048935, + 'timestamp': 1285.1543134972453, + 'timestamp_carla': 1285159, + 'timestamp_device': 2903719, + 'timestamp_stream': 1285.1543134972453, + 'transform': [array([ 2.10167999e+02, 3.05095978e+02, -1.47688061e-01]), + array([-7.35611329e-03, -1.70855423e+02, 2.07824595e-02])]} +{'AngularVelocity': array([-0.4028177 , -0.40925184, 2.47169304]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.686891555786133, + 'FR_Wheel_Angle': 29.04399871826172, + 'Location': array([2.55369110e+02, 1.51315994e+02, 6.31949306e-02]), + 'Rotation': array([-0.1937588 , 0.07663993, -0.0404663 ]), + 'Velocity': array([0.26509938, 0.08369296, 0.00271555]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5263671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23973.0703125 , 16488.8125 , 29.99996948]), + 'frame': 37868, + 'frame_number': 37868, + 'framesequence': 152704, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2723594009876251, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.1881383992732, + 'timestamp_carla': 1285193, + 'timestamp_device': 2903744, + 'timestamp_stream': 1285.1881383992732, + 'transform': [array([ 2.10430847e+02, 3.05134308e+02, -1.47391856e-01]), + array([-7.93667976e-03, -1.70963516e+02, 2.09350493e-02])]} +{'AngularVelocity': array([ 0.03108728, -0.2237552 , 1.66676581]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.44023895263672, + 'FR_Wheel_Angle': 29.5131778717041, + 'Location': array([2.55426300e+02, 1.51330292e+02, 6.39812201e-02]), + 'Rotation': array([-0.11077883, 0.60727865, -0.0168457 ]), + 'Velocity': array([0.2650643 , 0.07500456, 0.00385161]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5284423828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23972.88867188, 16487.16992188, 29.99996948]), + 'frame': 37869, + 'frame_number': 37869, + 'framesequence': 152708, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25855281949043274, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.2216451987624, + 'timestamp_carla': 1285226, + 'timestamp_device': 2903777, + 'timestamp_stream': 1285.2216451987624, + 'transform': [array([ 2.10667145e+02, 3.05166748e+02, -1.46898270e-01]), + array([-8.79045296e-03, -1.71060654e+02, 2.11791862e-02])]} +{'AngularVelocity': array([ 0.02288023, -0.10493944, 1.85181403]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.21129035949707, + 'FR_Wheel_Angle': 29.279069900512695, + 'Location': array([2.55483551e+02, 1.51344711e+02, 6.40554503e-02]), + 'Rotation': array([-0.07580143, 1.13229775, -0.0246582 ]), + 'Velocity': array([0.26068214, 0.07791277, 0.00041825]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5255737304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23972.7109375 , 16485.45507812, 30. ]), + 'frame': 37870, + 'frame_number': 37870, + 'framesequence': 152712, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24304331839084625, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.2551476992667, + 'timestamp_carla': 1285259, + 'timestamp_device': 2903811, + 'timestamp_stream': 1285.2551476992667, + 'transform': [array([ 2.10898514e+02, 3.05197937e+02, -1.46028668e-01]), + array([-9.67837777e-03, -1.71155655e+02, 2.15759184e-02])]} +{'AngularVelocity': array([ 0.04593566, -0.08845783, 2.20649838]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 22.898170471191406, + 'FR_Wheel_Angle': 28.149982452392578, + 'Location': array([2.55543533e+02, 1.51359985e+02, 6.37512654e-02]), + 'Rotation': array([-0.05440928, 1.70155275, -0.03115844]), + 'Velocity': array([ 0.26245639, 0.08396851, -0.00067446]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.522705078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23972.55664062, 16483.7578125 , 30. ]), + 'frame': 37871, + 'frame_number': 37871, + 'framesequence': 152717, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2289254516363144, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.2890163995326, + 'timestamp_carla': 1285293, + 'timestamp_device': 2903852, + 'timestamp_stream': 1285.2890163995326, + 'transform': [array([ 2.11109680e+02, 3.05224365e+02, -1.45284876e-01]), + array([-1.03477361e-02, -1.71242294e+02, 2.19116118e-02])]} +{'AngularVelocity': array([-1.87911571e-03, -1.25638947e-01, 2.55314827e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.94022560119629, + 'FR_Wheel_Angle': 24.96636962890625, + 'Location': array([2.55607468e+02, 1.51375183e+02, 6.34041652e-02]), + 'Rotation': array([-0.03839249, 2.24457645, -0.02911377]), + 'Velocity': array([ 0.30845156, 0.08378708, -0.00128916]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23972.41796875, 16482.078125 , 30. ]), + 'frame': 37872, + 'frame_number': 37872, + 'framesequence': 152721, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2243293672800064, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.3220345005393, + 'timestamp_carla': 1285326, + 'timestamp_device': 2903886, + 'timestamp_stream': 1285.3220345005393, + 'transform': [array([ 2.11305313e+02, 3.05247772e+02, -1.44788966e-01]), + array([-1.06550949e-02, -1.71322495e+02, 2.21252330e-02])]} +{'AngularVelocity': array([ 0.01635547, -0.10887189, 2.73596835]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.247272491455078, + 'FR_Wheel_Angle': 24.989099502563477, + 'Location': array([2.55673691e+02, 1.51391037e+02, 6.31272942e-02]), + 'Rotation': array([-0.02575664, 2.80773354, -0.0189209 ]), + 'Velocity': array([ 0.33013004, 0.09542082, -0.00080132]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5170288085938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23972.3046875 , 16480.37890625, 30. ]), + 'frame': 37873, + 'frame_number': 37873, + 'framesequence': 152724, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.22841274738311768, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.353936597705, + 'timestamp_carla': 1285358, + 'timestamp_device': 2903911, + 'timestamp_stream': 1285.353936597705, + 'transform': [array([ 2.11491592e+02, 3.05269470e+02, -1.44754410e-01]), + array([-1.04706790e-02, -1.71398895e+02, 2.21252330e-02])]} +{'AngularVelocity': array([ 0.04860664, -0.07158233, 2.94318366]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.381956100463867, + 'FR_Wheel_Angle': 25.093870162963867, + 'Location': array([2.55745575e+02, 1.51408905e+02, 6.29877523e-02]), + 'Rotation': array([-0.01937725, 3.41780663, -0.01296997]), + 'Velocity': array([ 3.54247510e-01, 1.06955536e-01, -1.88980091e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5166015625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23972.20703125, 16478.72851562, 30. ]), + 'frame': 37874, + 'frame_number': 37874, + 'framesequence': 152728, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23562730848789215, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.388322699815, + 'timestamp_carla': 1285393, + 'timestamp_device': 2903944, + 'timestamp_stream': 1285.388322699815, + 'transform': [array([ 2.11708099e+02, 3.05295837e+02, -1.44614860e-01]), + array([-9.89011303e-03, -1.71487656e+02, 2.21557505e-02])]} +{'AngularVelocity': array([ 0.03074594, -0.06014489, 2.68760324]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.785024642944336, + 'FR_Wheel_Angle': 20.322669982910156, + 'Location': array([2.55822723e+02, 1.51428497e+02, 6.29618168e-02]), + 'Rotation': array([-0.01782679, 4.02979422, -0.00973511]), + 'Velocity': array([3.76623541e-01, 1.05004698e-01, 3.42822081e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5193481445312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23972.10742188, 16477.11914062, 29.99993896]), + 'frame': 37875, + 'frame_number': 37875, + 'framesequence': 152733, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24355603754520416, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.4235128983855, + 'timestamp_carla': 1285428, + 'timestamp_device': 2903986, + 'timestamp_stream': 1285.4235128983855, + 'transform': [array([ 2.11948517e+02, 3.05326324e+02, -1.44811898e-01]), + array([-8.97486787e-03, -1.71586243e+02, 2.20336840e-02])]} +{'AngularVelocity': array([ 0.05825071, -0.05164708, 2.577425 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.76571273803711, + 'FR_Wheel_Angle': 21.019163131713867, + 'Location': array([2.55904099e+02, 1.51447525e+02, 6.29558638e-02]), + 'Rotation': array([-0.01840053, 4.5898037 , -0.00933838]), + 'Velocity': array([3.75901282e-01, 1.06030919e-01, 1.61724092e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5181274414062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.98828125, 16475.40234375, 29.99993896]), + 'frame': 37876, + 'frame_number': 37876, + 'framesequence': 152736, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24729149043560028, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.4550345987082, + 'timestamp_carla': 1285459, + 'timestamp_device': 2904011, + 'timestamp_stream': 1285.4550345987082, + 'transform': [array([ 2.12166183e+02, 3.05353729e+02, -1.44600376e-01]), + array([-8.66751000e-03, -1.71675476e+02, 2.20947135e-02])]} +{'AngularVelocity': array([ 0.05610221, -0.05135412, 2.62620997]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.515735626220703, + 'FR_Wheel_Angle': 20.844417572021484, + 'Location': array([2.55976395e+02, 1.51465408e+02, 6.29488081e-02]), + 'Rotation': array([-0.01785411, 5.08755493, -0.00976562]), + 'Velocity': array([3.96443754e-01, 1.15380526e-01, 7.09629021e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5174560546875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.84570312, 16473.65039062, 29.99993896]), + 'frame': 37877, + 'frame_number': 37877, + 'framesequence': 152740, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24569842219352722, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.4879982993007, + 'timestamp_carla': 1285492, + 'timestamp_device': 2904044, + 'timestamp_stream': 1285.4879982993007, + 'transform': [array([ 2.12398605e+02, 3.05383087e+02, -1.44207224e-01]), + array([-8.57188739e-03, -1.71770706e+02, 2.22473014e-02])]} +{'AngularVelocity': array([ 0.05183293, -0.02263097, 3.3871448 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 17.03904914855957, + 'FR_Wheel_Angle': 19.47339630126953, + 'Location': array([2.56062561e+02, 1.51487595e+02, 6.29486516e-02]), + 'Rotation': array([-0.01812049, 5.66489744, -0.00979614]), + 'Velocity': array([0.38820878, 0.12025295, 0.00045474]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52197265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.71484375, 16472.08398438, 30. ]), + 'frame': 37878, + 'frame_number': 37878, + 'framesequence': 152744, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2418714016675949, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.5210814997554, + 'timestamp_carla': 1285525, + 'timestamp_device': 2904077, + 'timestamp_stream': 1285.5210814997554, + 'transform': [array([ 2.12627029e+02, 3.05411163e+02, -1.44251138e-01]), + array([-8.33282992e-03, -1.71864319e+02, 2.22167857e-02])]} +{'AngularVelocity': array([-0.03544129, 0.05473587, 1.82105196]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.98421573638916, + 'FR_Wheel_Angle': 16.647994995117188, + 'Location': array([2.56152435e+02, 1.51509567e+02, 6.29444942e-02]), + 'Rotation': array([-0.01773117, 6.19197226, -0.00772095]), + 'Velocity': array([ 3.68796468e-01, 9.84644070e-02, -1.61008837e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5221557617188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.578125 , 16470.45898438, 29.99996948]), + 'frame': 37879, + 'frame_number': 37879, + 'framesequence': 152748, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23830074071884155, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.5541994981468, + 'timestamp_carla': 1285558, + 'timestamp_device': 2904110, + 'timestamp_stream': 1285.5541994981468, + 'transform': [array([ 2.12838379e+02, 3.05435699e+02, -1.43752247e-01]), + array([-8.57188739e-03, -1.71950897e+02, 2.24304069e-02])]} +{'AngularVelocity': array([-0.04311049, 0.06384696, 1.93723726]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.247326850891113, + 'FR_Wheel_Angle': 16.603225708007812, + 'Location': array([2.56248871e+02, 1.51533310e+02, 6.29460216e-02]), + 'Rotation': array([-0.01831174, 6.72092819, -0.0090332 ]), + 'Velocity': array([ 3.76428783e-01, 1.07588664e-01, -9.81903067e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5225830078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.43164062, 16468.82226562, 29.99996948]), + 'frame': 37880, + 'frame_number': 37880, + 'framesequence': 152753, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23657949268817902, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.5881883986294, + 'timestamp_carla': 1285592, + 'timestamp_device': 2904152, + 'timestamp_stream': 1285.5881883986294, + 'transform': [array([ 2.13061279e+02, 3.05461792e+02, -1.43387824e-01]), + array([-8.64018872e-03, -1.72042175e+02, 2.25829985e-02])]} +{'AngularVelocity': array([-0.04867317, 0.0330821 , 1.71417689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.391996383666992, + 'FR_Wheel_Angle': 16.706436157226562, + 'Location': array([2.56343933e+02, 1.51557404e+02, 6.29547983e-02]), + 'Rotation': array([-0.01934993, 7.22708511, -0.0088501 ]), + 'Velocity': array([3.79659027e-01, 1.08775966e-01, 1.21574398e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5214233398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.29882812, 16467.19921875, 30.00006104]), + 'frame': 37881, + 'frame_number': 37881, + 'framesequence': 152756, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23806269466876984, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.6212900988758, + 'timestamp_carla': 1285625, + 'timestamp_device': 2904177, + 'timestamp_stream': 1285.6212900988758, + 'transform': [array([ 2.13288895e+02, 3.05488678e+02, -1.43960342e-01]), + array([-8.39430187e-03, -1.72135361e+02, 2.23388560e-02])]} +{'AngularVelocity': array([-0.02442369, 0.04355178, 1.04493654]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.264860153198242, + 'FR_Wheel_Angle': 11.667388916015625, + 'Location': array([2.56452484e+02, 1.51585098e+02, 6.29430488e-02]), + 'Rotation': array([-1.91381890e-02, 7.77642775e+00, -6.95800735e-03]), + 'Velocity': array([ 3.75626087e-01, 1.00036383e-01, -2.82592780e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5195922851562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.16015625, 16465.54296875, 29.99996948]), + 'frame': 37882, + 'frame_number': 37882, + 'framesequence': 152760, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2401684671640396, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.6556068994105, + 'timestamp_carla': 1285660, + 'timestamp_device': 2904210, + 'timestamp_stream': 1285.6556068994105, + 'transform': [array([ 2.13514374e+02, 3.05514252e+02, -1.43876076e-01]), + array([-8.27135891e-03, -1.72227646e+02, 2.23693755e-02])]} +{'AngularVelocity': array([-0.02018956, 0.04656668, 1.95477438]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.423478126525879, + 'FR_Wheel_Angle': 12.573493957519531, + 'Location': array([2.56549164e+02, 1.51607803e+02, 6.29525483e-02]), + 'Rotation': array([-0.01788826, 8.18199158, -0.00930786]), + 'Velocity': array([ 4.03186411e-01, 1.11089930e-01, -3.05929163e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213012695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23971.01953125, 16463.91796875, 29.99996948]), + 'frame': 37883, + 'frame_number': 37883, + 'framesequence': 152764, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24139530956745148, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.6875854991376, + 'timestamp_carla': 1285692, + 'timestamp_device': 2904244, + 'timestamp_stream': 1285.6875854991376, + 'transform': [array([ 2.13725311e+02, 3.05538116e+02, -1.43471748e-01]), + array([-8.18256661e-03, -1.72313980e+02, 2.25219615e-02])]} +{'AngularVelocity': array([-0.01654162, 0.04710381, 1.85064161]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.186081886291504, + 'FR_Wheel_Angle': 12.446807861328125, + 'Location': array([2.56635468e+02, 1.51629074e+02, 6.29395396e-02]), + 'Rotation': array([-0.01843468, 8.53089809, -0.00933838]), + 'Velocity': array([ 0.40585244, 0.11386564, -0.00041399]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52001953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23970.875 , 16462.23632812, 30. ]), + 'frame': 37884, + 'frame_number': 37884, + 'framesequence': 152768, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24068118631839752, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.7211893983185, + 'timestamp_carla': 1285725, + 'timestamp_device': 2904277, + 'timestamp_stream': 1285.7211893983185, + 'transform': [array([ 2.13958664e+02, 3.05565002e+02, -1.43324092e-01]), + array([-8.18256661e-03, -1.72409470e+02, 2.25829966e-02])]} +{'AngularVelocity': array([-0.02057926, 0.04398739, 1.09893787]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 10.515684127807617, + 'FR_Wheel_Angle': 10.838391304016113, + 'Location': array([2.56738220e+02, 1.51654892e+02, 6.29444569e-02]), + 'Rotation': array([-0.01852347, 8.94858456, -0.00949097]), + 'Velocity': array([4.14154381e-01, 1.18460760e-01, 1.82981486e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5224609375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23970.73242188, 16460.69140625, 29.99996948]), + 'frame': 37885, + 'frame_number': 37885, + 'framesequence': 152773, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23934446275234222, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.7557613998652, + 'timestamp_carla': 1285760, + 'timestamp_device': 2904319, + 'timestamp_stream': 1285.7557613998652, + 'transform': [array([ 2.14184799e+02, 3.05589905e+02, -1.43030509e-01]), + array([-8.18256661e-03, -1.72501999e+02, 2.27050707e-02])]} +{'AngularVelocity': array([-0.01213056, 0.04997182, 1.66063643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.398035526275635, + 'FR_Wheel_Angle': 8.457747459411621, + 'Location': array([2.56841003e+02, 1.51679138e+02, 6.29531145e-02]), + 'Rotation': array([-1.90425664e-02, 9.27770233e+00, -6.65283203e-03]), + 'Velocity': array([ 4.12183136e-01, 9.97870788e-02, -4.50134257e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213012695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23970.58007812, 16459.06835938, 30.00006104]), + 'frame': 37886, + 'frame_number': 37886, + 'framesequence': 152777, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23936277627944946, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.787969198078, + 'timestamp_carla': 1285792, + 'timestamp_device': 2904352, + 'timestamp_stream': 1285.787969198078, + 'transform': [array([ 2.14408310e+02, 3.05615082e+02, -1.42878607e-01]), + array([-8.27135891e-03, -1.72593430e+02, 2.27661040e-02])]} +{'AngularVelocity': array([-0.03913423, 0.07018574, 1.24104524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.619759559631348, + 'FR_Wheel_Angle': 8.3350830078125, + 'Location': array([2.56957733e+02, 1.51706284e+02, 6.29596040e-02]), + 'Rotation': array([-1.92269813e-02, 9.60810089e+00, -8.42285156e-03]), + 'Velocity': array([3.95020485e-01, 9.96706858e-02, 2.76088704e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51904296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23970.421875 , 16457.421875 , 30.00003052]), + 'frame': 37887, + 'frame_number': 37887, + 'framesequence': 152780, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24018678069114685, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.8210003003478, + 'timestamp_carla': 1285825, + 'timestamp_device': 2904377, + 'timestamp_stream': 1285.8210003003478, + 'transform': [array([ 2.14617279e+02, 3.05636871e+02, -1.42641634e-01]), + array([-8.20988696e-03, -1.72678925e+02, 2.28576604e-02])]} +{'AngularVelocity': array([-0.02899013, 0.05303043, 1.43486619]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.722965240478516, + 'FR_Wheel_Angle': 8.342209815979004, + 'Location': array([2.57044891e+02, 1.51727020e+02, 6.29605949e-02]), + 'Rotation': array([-1.90084148e-02, 9.85368252e+00, -8.88061430e-03]), + 'Velocity': array([4.04227048e-01, 1.04511410e-01, 2.30641366e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213012695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23970.27148438, 16455.88671875, 30.00003052]), + 'frame': 37888, + 'frame_number': 37888, + 'framesequence': 152784, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2404431253671646, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.8553398996592, + 'timestamp_carla': 1285859, + 'timestamp_device': 2904410, + 'timestamp_stream': 1285.8553398996592, + 'transform': [array([ 2.14829803e+02, 3.05658539e+02, -1.42044023e-01]), + array([-8.20988696e-03, -1.72765869e+02, 2.31017992e-02])]} +{'AngularVelocity': array([-0.02957036, 0.04846358, 0.66631889]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.8107945919036865, + 'FR_Wheel_Angle': 3.225949287414551, + 'Location': array([2.57148193e+02, 1.51751434e+02, 6.29538447e-02]), + 'Rotation': array([-1.84346791e-02, 1.01066599e+01, -6.95800781e-03]), + 'Velocity': array([4.21373576e-01, 9.63218883e-02, 1.06287000e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213623046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23970.1171875 , 16454.30273438, 30. ]), + 'frame': 37889, + 'frame_number': 37889, + 'framesequence': 152788, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23991210758686066, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.8879650980234, + 'timestamp_carla': 1285892, + 'timestamp_device': 2904444, + 'timestamp_stream': 1285.8879650980234, + 'transform': [array([ 2.15023788e+02, 3.05677612e+02, -1.41584963e-01]), + array([-8.24403763e-03, -1.72845230e+02, 2.32849047e-02])]} +{'AngularVelocity': array([-0.01055152, 0.04818491, 0.85688782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 4.212514877319336, + 'FR_Wheel_Angle': 4.1214985847473145, + 'Location': array([2.57272186e+02, 1.51777756e+02, 6.29533082e-02]), + 'Rotation': array([-1.83117352e-02, 1.02695570e+01, -8.39233398e-03]), + 'Velocity': array([4.41509187e-01, 1.00083508e-01, 5.55992119e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5189208984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.95507812, 16452.68164062, 29.99996948]), + 'frame': 37890, + 'frame_number': 37890, + 'framesequence': 152792, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23793451488018036, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.920127697289, + 'timestamp_carla': 1285924, + 'timestamp_device': 2904477, + 'timestamp_stream': 1285.920127697289, + 'transform': [array([ 2.15226044e+02, 3.05698151e+02, -1.41501695e-01]), + array([-8.24403763e-03, -1.72927948e+02, 2.33154222e-02])]} +{'AngularVelocity': array([-0.00353773, 0.04338882, 0.1009258 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 3.9806771278381348, + 'FR_Wheel_Angle': 4.117893695831299, + 'Location': array([2.57366028e+02, 1.51797729e+02, 6.29556328e-02]), + 'Rotation': array([-1.86464153e-02, 1.03876390e+01, -8.54492188e-03]), + 'Velocity': array([4.45584029e-01, 1.00313127e-01, 1.13191600e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.80273438, 16451.15820312, 30. ]), + 'frame': 37891, + 'frame_number': 37891, + 'framesequence': 152797, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23057346045970917, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.95525649935, + 'timestamp_carla': 1285959, + 'timestamp_device': 2904519, + 'timestamp_stream': 1285.95525649935, + 'transform': [array([ 2.15447281e+02, 3.05719635e+02, -1.43382147e-01]), + array([-7.96400011e-03, -1.73018402e+02, 2.25524772e-02])]} +{'AngularVelocity': array([-0.00722234, 0.00670126, 0.31219655]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.874810218811035, + 'FR_Wheel_Angle': 1.9773913621902466, + 'Location': array([2.57491760e+02, 1.51824936e+02, 6.29508272e-02]), + 'Rotation': array([-1.87420379e-02, 1.05425777e+01, -8.30078125e-03]), + 'Velocity': array([ 4.64107692e-01, 1.01178937e-01, -2.45056144e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5214233398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.64257812, 16449.66015625, 30. ]), + 'frame': 37892, + 'frame_number': 37892, + 'framesequence': 152800, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2180120348930359, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1285.9874797984958, + 'timestamp_carla': 1285991, + 'timestamp_device': 2904544, + 'timestamp_stream': 1285.9874797984958, + 'transform': [array([ 2.15642868e+02, 3.05738007e+02, -1.43754229e-01]), + array([-8.57188739e-03, -1.73098282e+02, 2.24304087e-02])]} +{'AngularVelocity': array([ 0.0053383 , 0.03558373, -0.35217217]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.12318229675292969, + 'FR_Wheel_Angle': 0.2958836257457733, + 'Location': array([2.57583984e+02, 1.51842239e+02, 6.29534200e-02]), + 'Rotation': array([-1.88581515e-02, 1.05400057e+01, -6.04248047e-03]), + 'Velocity': array([ 4.51391757e-01, 7.86628202e-02, -1.57089235e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.4765625, 16447.96875 , 30. ]), + 'frame': 37893, + 'frame_number': 37893, + 'framesequence': 152804, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2036927491426468, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.021290998906, + 'timestamp_carla': 1286025, + 'timestamp_device': 2904577, + 'timestamp_stream': 1286.021290998906, + 'transform': [array([ 2.15834824e+02, 3.05754700e+02, -1.43863216e-01]), + array([-9.37101897e-03, -1.73176636e+02, 2.24304106e-02])]} +{'AngularVelocity': array([ 0.00167636, 0.0235336 , -0.95732397]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -0.06601881980895996, + 'FR_Wheel_Angle': 0.06348953396081924, + 'Location': array([2.57695160e+02, 1.51862625e+02, 6.29464388e-02]), + 'Rotation': array([-1.82775855e-02, 1.05190039e+01, -7.99560640e-03]), + 'Velocity': array([4.69671816e-01, 8.48373026e-02, 1.80692674e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5211791992188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.3359375 , 16446.43554688, 29.99996948]), + 'frame': 37894, + 'frame_number': 37894, + 'framesequence': 152808, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18944670259952545, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.053898498416, + 'timestamp_carla': 1286058, + 'timestamp_device': 2904610, + 'timestamp_stream': 1286.053898498416, + 'transform': [array([ 2.16021515e+02, 3.05770630e+02, -1.44688338e-01]), + array([-9.91743430e-03, -1.73252762e+02, 2.21252330e-02])]} +{'AngularVelocity': array([ 0.00063432, 0.02509516, -0.36115578]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.013970847241580486, + 'FR_Wheel_Angle': -0.015240960754454136, + 'Location': array([2.57807159e+02, 1.51883057e+02, 6.29617795e-02]), + 'Rotation': array([-1.85234714e-02, 1.05028400e+01, -8.45336914e-03]), + 'Velocity': array([0.46945822, 0.08516562, 0.00079296]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184936523438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.21289062, 16444.83203125, 30.00003052]), + 'frame': 37895, + 'frame_number': 37895, + 'framesequence': 152812, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1750175654888153, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.0871532969177, + 'timestamp_carla': 1286091, + 'timestamp_device': 2904644, + 'timestamp_stream': 1286.0871532969177, + 'transform': [array([ 2.16182236e+02, 3.05781677e+02, -1.44478217e-01]), + array([-1.06209433e-02, -1.73318253e+02, 2.22472996e-02])]} +{'AngularVelocity': array([-0.0047122 , 0.06947281, -0.65036184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.876332759857178, + 'FR_Wheel_Angle': -4.9267578125, + 'Location': array([2.57936829e+02, 1.51904953e+02, 6.29668906e-02]), + 'Rotation': array([-1.91996600e-02, 1.04153643e+01, -5.82885742e-03]), + 'Velocity': array([0.4460147 , 0.06015763, 0.00045409]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5191650390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.10351562, 16443.26757812, 30.00003052]), + 'frame': 37896, + 'frame_number': 37896, + 'framesequence': 152816, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16448867321014404, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.1203049980104, + 'timestamp_carla': 1286124, + 'timestamp_device': 2904677, + 'timestamp_stream': 1286.1203049980104, + 'transform': [array([ 2.16330460e+02, 3.05790680e+02, -1.44074738e-01]), + array([-1.10170944e-02, -1.73378586e+02, 2.24304087e-02])]} +{'AngularVelocity': array([ 0.00929226, -0.06347905, -0.52400953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.073366641998291, + 'FR_Wheel_Angle': -4.119034290313721, + 'Location': array([2.58033264e+02, 1.51918839e+02, 6.29383922e-02]), + 'Rotation': array([-1.86190940e-02, 1.02533970e+01, -7.78198382e-03]), + 'Velocity': array([ 5.15995920e-01, 7.17315003e-02, -2.05039978e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51708984375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23969.01953125, 16441.6796875 , 29.99996948]), + 'frame': 37897, + 'frame_number': 37897, + 'framesequence': 152820, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16615498065948486, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.1539246998727, + 'timestamp_carla': 1286158, + 'timestamp_device': 2904710, + 'timestamp_stream': 1286.1539246998727, + 'transform': [array([ 2.16486053e+02, 3.05800507e+02, -1.44062415e-01]), + array([-1.08941514e-02, -1.73441925e+02, 2.24304069e-02])]} +{'AngularVelocity': array([ 0.01391175, 0.05796082, -1.11014318]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -4.199058532714844, + 'FR_Wheel_Angle': -4.006664276123047, + 'Location': array([2.58145966e+02, 1.51934967e+02, 6.29509836e-02]), + 'Rotation': array([-1.81819629e-02, 1.00985088e+01, -8.39233492e-03]), + 'Velocity': array([ 4.66815442e-01, 6.47358671e-02, -7.13443733e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5157470703125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.953125 , 16440.11328125, 30. ]), + 'frame': 37898, + 'frame_number': 37898, + 'framesequence': 152824, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17349773645401, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.1865062974393, + 'timestamp_carla': 1286190, + 'timestamp_device': 2904744, + 'timestamp_stream': 1286.1865062974393, + 'transform': [array([ 2.16637070e+02, 3.05809967e+02, -1.44132301e-01]), + array([-1.03135854e-02, -1.73503372e+02, 2.23693736e-02])]} +{'AngularVelocity': array([-0.00992548, 0.02052113, -1.36150753]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -5.7549824714660645, + 'FR_Wheel_Angle': -6.292057514190674, + 'Location': array([2.58261322e+02, 1.51951508e+02, 6.29513636e-02]), + 'Rotation': array([-1.87078863e-02, 9.91879177e+00, -8.02612212e-03]), + 'Velocity': array([4.79560435e-01, 6.07745834e-02, 1.83773045e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5154418945312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.88085938, 16438.52148438, 30. ]), + 'frame': 37899, + 'frame_number': 37899, + 'framesequence': 152828, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1817377209663391, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.2208280973136, + 'timestamp_carla': 1286225, + 'timestamp_device': 2904777, + 'timestamp_stream': 1286.2208280973136, + 'transform': [array([ 2.16804062e+02, 3.05821198e+02, -1.43750414e-01]), + array([-9.64422617e-03, -1.73571381e+02, 2.24914439e-02])]} +{'AngularVelocity': array([ 0.00888168, -0.03972801, -1.88416326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.189839363098145, + 'FR_Wheel_Angle': -7.317119598388672, + 'Location': array([2.58377167e+02, 1.51964249e+02, 6.29414469e-02]), + 'Rotation': array([-1.86464153e-02, 9.61509228e+00, -5.64575195e-03]), + 'Velocity': array([5.17197490e-01, 4.13891487e-02, 2.12488172e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5177612304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.8125 , 16436.98242188, 30. ]), + 'frame': 37900, + 'frame_number': 37900, + 'framesequence': 152832, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18717612326145172, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.252756100148, + 'timestamp_carla': 1286257, + 'timestamp_device': 2904810, + 'timestamp_stream': 1286.252756100148, + 'transform': [array([ 2.16964981e+02, 3.05832520e+02, -1.43442646e-01]), + array([-9.12513211e-03, -1.73636917e+02, 2.25830022e-02])]} +{'AngularVelocity': array([ 0.00555871, 0.01114326, -1.2777915 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.303205490112305, + 'FR_Wheel_Angle': -7.617246627807617, + 'Location': array([2.58491119e+02, 1.51975372e+02, 6.29542992e-02]), + 'Rotation': array([-1.93499252e-02, 9.32891750e+00, -7.69042922e-03]), + 'Velocity': array([ 4.81793672e-01, 3.76552269e-02, -3.39431746e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5171508789062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.72460938, 16435.38476562, 29.99996948]), + 'frame': 37901, + 'frame_number': 37901, + 'framesequence': 152836, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18664512038230896, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.2874263003469, + 'timestamp_carla': 1286291, + 'timestamp_device': 2904844, + 'timestamp_stream': 1286.2874263003469, + 'transform': [array([ 2.17138275e+02, 3.05844391e+02, -1.43468007e-01]), + array([-8.64018872e-03, -1.73707520e+02, 2.25524791e-02])]} +{'AngularVelocity': array([ 0.01283004, 0.0363763 , -1.93331861]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.325942993164062, + 'FR_Wheel_Angle': -7.77453088760376, + 'Location': array([2.58604797e+02, 1.51986282e+02, 6.29509464e-02]), + 'Rotation': array([-1.85849443e-02, 9.00289536e+00, -8.14819243e-03]), + 'Velocity': array([4.76096421e-01, 3.70457284e-02, 1.50489805e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5203857421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.6328125 , 16433.90234375, 30. ]), + 'frame': 37902, + 'frame_number': 37902, + 'framesequence': 152840, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18305611610412598, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.319693800062, + 'timestamp_carla': 1286324, + 'timestamp_device': 2904877, + 'timestamp_stream': 1286.319693800062, + 'transform': [array([ 2.17300964e+02, 3.05855530e+02, -1.43381760e-01]), + array([-8.64018872e-03, -1.73773773e+02, 2.25829985e-02])]} +{'AngularVelocity': array([-0.04118599, -0.02117608, -2.67618799]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.4544095993042, + 'FR_Wheel_Angle': -11.92316722869873, + 'Location': array([2.58721283e+02, 1.51995453e+02, 6.29535392e-02]), + 'Rotation': array([-1.87693592e-02, 8.62069702e+00, -5.37109375e-03]), + 'Velocity': array([5.07473826e-01, 1.25587173e-02, 9.00840751e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5192260742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.52539062, 16432.30078125, 29.99996948]), + 'frame': 37903, + 'frame_number': 37903, + 'framesequence': 152844, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17911924421787262, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.3540578000247, + 'timestamp_carla': 1286358, + 'timestamp_device': 2904910, + 'timestamp_stream': 1286.3540578000247, + 'transform': [array([ 2.17475540e+02, 3.05867523e+02, -1.43411294e-01]), + array([-8.79045296e-03, -1.73844833e+02, 2.25830004e-02])]} +{'AngularVelocity': array([-0.02145472, -0.01083216, -2.58474183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.540699005126953, + 'FR_Wheel_Angle': -11.331178665161133, + 'Location': array([2.58852264e+02, 1.52001266e+02, 6.29598349e-02]), + 'Rotation': array([-1.91655103e-02, 8.11508751e+00, -7.41577148e-03]), + 'Velocity': array([4.90380704e-01, 7.55366078e-03, 4.25004953e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208740234375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.43164062, 16430.81445312, 29.99996948]), + 'frame': 37904, + 'frame_number': 37904, + 'framesequence': 152849, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1765739917755127, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.3887385986745, + 'timestamp_carla': 1286393, + 'timestamp_device': 2904952, + 'timestamp_stream': 1286.3887385986745, + 'transform': [array([ 2.17630615e+02, 3.05875885e+02, -1.43586963e-01]), + array([-8.91339593e-03, -1.73907959e+02, 2.25219615e-02])]} +{'AngularVelocity': array([-0.02042731, -0.02992059, -1.5200882 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.549665451049805, + 'FR_Wheel_Angle': -11.173657417297363, + 'Location': array([2.58948425e+02, 1.52005020e+02, 6.29577339e-02]), + 'Rotation': array([-0.01874204, 7.75044298, -0.00799561]), + 'Velocity': array([ 4.98926997e-01, 7.00366916e-03, -5.49888609e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5186767578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.328125 , 16429.25390625, 30. ]), + 'frame': 37905, + 'frame_number': 37905, + 'framesequence': 152852, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17765435576438904, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.4197667986155, + 'timestamp_carla': 1286424, + 'timestamp_device': 2904977, + 'timestamp_stream': 1286.4197667986155, + 'transform': [array([ 2.17776947e+02, 3.05884247e+02, -1.43988609e-01]), + array([-8.66751000e-03, -1.73967514e+02, 2.23388560e-02])]} +{'AngularVelocity': array([ 0.03005304, 0.05306406, -1.58668709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -14.48392105102539, + 'FR_Wheel_Angle': -13.492780685424805, + 'Location': array([2.59079834e+02, 1.52009171e+02, 6.29536137e-02]), + 'Rotation': array([-1.84346791e-02, 7.20435095e+00, -6.77490234e-03]), + 'Velocity': array([ 4.71784532e-01, -4.05779760e-03, -8.26930991e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5169067382812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.23828125, 16427.65234375, 30. ]), + 'frame': 37906, + 'frame_number': 37906, + 'framesequence': 152856, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17959532141685486, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.45370169729, + 'timestamp_carla': 1286458, + 'timestamp_device': 2905010, + 'timestamp_stream': 1286.45370169729, + 'transform': [array([ 2.17937088e+02, 3.05893524e+02, -1.43900186e-01]), + array([-8.51041544e-03, -1.74032715e+02, 2.23693755e-02])]} +{'AngularVelocity': array([-0.02485702, -0.04649735, -2.43587708]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.353254318237305, + 'FR_Wheel_Angle': -14.02643871307373, + 'Location': array([2.59176331e+02, 1.52008469e+02, 6.29560202e-02]), + 'Rotation': array([-1.88308302e-02, 6.69211817e+00, -5.88989258e-03]), + 'Velocity': array([ 5.10619521e-01, -2.45926324e-02, -2.14815140e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5223388671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.15039062, 16426.19726562, 29.99993896]), + 'frame': 37907, + 'frame_number': 37907, + 'framesequence': 152860, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1813715100288391, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.4873148985207, + 'timestamp_carla': 1286491, + 'timestamp_device': 2905044, + 'timestamp_stream': 1286.4873148985207, + 'transform': [array([ 2.18094604e+02, 3.05902344e+02, -1.43598437e-01]), + array([-8.51041544e-03, -1.74096832e+02, 2.24914439e-02])]} +{'AngularVelocity': array([-0.02423951, -0.0314372 , -2.41019082]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.584423065185547, + 'FR_Wheel_Angle': -14.321423530578613, + 'Location': array([2.59289276e+02, 1.52006897e+02, 6.29560575e-02]), + 'Rotation': array([-0.01858494, 6.08597565, -0.00726318]), + 'Velocity': array([ 5.04298568e-01, -2.71893311e-02, 4.64920973e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5210571289062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23968.046875 , 16424.64453125, 30. ]), + 'frame': 37908, + 'frame_number': 37908, + 'framesequence': 152864, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1810419112443924, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.5201910994947, + 'timestamp_carla': 1286524, + 'timestamp_device': 2905077, + 'timestamp_stream': 1286.5201910994947, + 'transform': [array([ 2.18245224e+02, 3.05910339e+02, -1.43270344e-01]), + array([-8.36015120e-03, -1.74158157e+02, 2.26135124e-02])]} +{'AngularVelocity': array([-0.03284121, -0.02595392, -2.28309536]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.660791397094727, + 'FR_Wheel_Angle': -14.572735786437988, + 'Location': array([2.59403900e+02, 1.52004044e+02, 6.29540309e-02]), + 'Rotation': array([-0.01855762, 5.47649479, -0.00759888]), + 'Velocity': array([ 5.05195558e-01, -3.28607969e-02, -1.25608436e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5204467773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.94921875, 16423.10351562, 30. ]), + 'frame': 37909, + 'frame_number': 37909, + 'framesequence': 152868, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1797967553138733, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.55403739959, + 'timestamp_carla': 1286558, + 'timestamp_device': 2905110, + 'timestamp_stream': 1286.55403739959, + 'transform': [array([ 2.18393738e+02, 3.05917267e+02, -1.43702269e-01]), + array([-8.14841501e-03, -1.74218643e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.05752717, -0.02894767, -3.00682616]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.827247619628906, + 'FR_Wheel_Angle': -17.97318458557129, + 'Location': array([2.59519165e+02, 1.51998596e+02, 6.29602522e-02]), + 'Rotation': array([-0.01861909, 4.78691816, -0.00509644]), + 'Velocity': array([ 5.10722756e-01, -6.00294434e-02, 3.15194135e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5214233398438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.84375 , 16421.59960938, 29.99996948]), + 'frame': 37910, + 'frame_number': 37910, + 'framesequence': 152872, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1792474240064621, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.5863543003798, + 'timestamp_carla': 1286590, + 'timestamp_device': 2905144, + 'timestamp_stream': 1286.5863543003798, + 'transform': [array([ 2.18546661e+02, 3.05925690e+02, -1.43330574e-01]), + array([-8.27135891e-03, -1.74280869e+02, 2.25829948e-02])]} +{'AngularVelocity': array([-0.04474859, -0.04723913, -3.14286709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.92810821533203, + 'FR_Wheel_Angle': -17.57634162902832, + 'Location': array([2.59633850e+02, 1.51989334e+02, 6.29514754e-02]), + 'Rotation': array([-0.01870789, 4.01739883, -0.00692749]), + 'Velocity': array([ 5.14043868e-01, -6.48132265e-02, -1.25646591e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213623046875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.73828125, 16420.03710938, 29.99996948]), + 'frame': 37911, + 'frame_number': 37911, + 'framesequence': 152876, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1798516809940338, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.6193489991128, + 'timestamp_carla': 1286623, + 'timestamp_device': 2905177, + 'timestamp_stream': 1286.6193489991128, + 'transform': [array([ 2.18701477e+02, 3.05933777e+02, -1.43850014e-01]), + array([-8.18256661e-03, -1.74343887e+02, 2.23693699e-02])]} +{'AngularVelocity': array([ 0.03020962, 0.02352739, -3.08402371]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.853504180908203, + 'FR_Wheel_Angle': -17.421833038330078, + 'Location': array([2.59748474e+02, 1.51978668e+02, 6.29558638e-02]), + 'Rotation': array([-0.01864642, 3.24530506, -0.00741577]), + 'Velocity': array([ 4.80163246e-01, -6.53304011e-02, 6.86550120e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5223999023438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.63476562, 16418.57421875, 29.99996948]), + 'frame': 37912, + 'frame_number': 37912, + 'framesequence': 152880, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1804010272026062, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.653093997389, + 'timestamp_carla': 1286657, + 'timestamp_device': 2905210, + 'timestamp_stream': 1286.653093997389, + 'transform': [array([ 2.18853348e+02, 3.05941193e+02, -1.43276587e-01]), + array([-8.39430187e-03, -1.74405701e+02, 2.26135142e-02])]} +{'AngularVelocity': array([ 0.0737242 , 0.0348819 , -2.78069139]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.246763229370117, + 'FR_Wheel_Angle': -19.800161361694336, + 'Location': array([2.59862152e+02, 1.51966202e+02, 6.29499480e-02]), + 'Rotation': array([-0.01870789, 2.48805285, -0.00704956]), + 'Velocity': array([ 4.72259581e-01, -7.22293854e-02, -2.36806867e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5231323242188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.52929688, 16417.0703125 , 29.99996948]), + 'frame': 37913, + 'frame_number': 37913, + 'framesequence': 152884, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1801629662513733, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.6867482997477, + 'timestamp_carla': 1286690, + 'timestamp_device': 2905244, + 'timestamp_stream': 1286.6867482997477, + 'transform': [array([ 2.19010971e+02, 3.05949341e+02, -1.43271446e-01]), + array([-8.33282992e-03, -1.74469833e+02, 2.26135179e-02])]} +{'AngularVelocity': array([ 0.03911998, 0.01054483, -2.94449425]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.51761245727539, + 'FR_Wheel_Angle': -20.015670776367188, + 'Location': array([2.59973206e+02, 1.51948868e+02, 6.29541874e-02]), + 'Rotation': array([-0.0193226 , 1.62313914, -0.00619507]), + 'Velocity': array([ 4.63596433e-01, -9.69454199e-02, 1.06525418e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5208129882812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.41992188, 16415.55664062, 30. ]), + 'frame': 37914, + 'frame_number': 37914, + 'framesequence': 152888, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1792474240064621, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.7207749970257, + 'timestamp_carla': 1286725, + 'timestamp_device': 2905277, + 'timestamp_stream': 1286.7207749970257, + 'transform': [array([ 2.19167923e+02, 3.05957214e+02, -1.42916143e-01]), + array([-8.48309416e-03, -1.74533691e+02, 2.27661040e-02])]} +{'AngularVelocity': array([-0.00875618, 0.03265312, -3.55402184]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.860864639282227, + 'FR_Wheel_Angle': -20.25769805908203, + 'Location': array([2.60084229e+02, 1.51929962e+02, 6.29383922e-02]), + 'Rotation': array([-0.01833906, 0.75507265, -0.00671387]), + 'Velocity': array([ 4.63078022e-01, -1.09233260e-01, -4.52470762e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5203857421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.31054688, 16414.05078125, 30. ]), + 'frame': 37915, + 'frame_number': 37915, + 'framesequence': 152892, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17276528477668762, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.7531171999872, + 'timestamp_carla': 1286757, + 'timestamp_device': 2905310, + 'timestamp_stream': 1286.7531171999872, + 'transform': [array([ 2.19324448e+02, 3.05965515e+02, -1.43305659e-01]), + array([-8.64018872e-03, -1.74597336e+02, 2.26135161e-02])]} +{'AngularVelocity': array([ 0.0946115 , 0.04893474, -3.95924091]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.01729965209961, + 'FR_Wheel_Angle': -20.645305633544922, + 'Location': array([2.60197235e+02, 1.51909241e+02, 6.29519373e-02]), + 'Rotation': array([-0.01843468, -0.15469362, -0.00738525]), + 'Velocity': array([ 4.59409565e-01, -1.05608344e-01, 2.82382953e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.518798828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.19726562, 16412.54296875, 30.00003052]), + 'frame': 37916, + 'frame_number': 37916, + 'framesequence': 152896, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.16159552335739136, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.786211296916, + 'timestamp_carla': 1286790, + 'timestamp_device': 2905344, + 'timestamp_stream': 1286.786211296916, + 'transform': [array([ 2.19461212e+02, 3.05970184e+02, -1.43509284e-01]), + array([-9.03633982e-03, -1.74652954e+02, 2.25524791e-02])]} +{'AngularVelocity': array([ 0.07742543, 0.03041334, -4.95171642]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.111358642578125, + 'FR_Wheel_Angle': -23.43290901184082, + 'Location': array([2.60324707e+02, 1.51881180e+02, 6.29532710e-02]), + 'Rotation': array([-0.01922698, -1.28585815, -0.00509644]), + 'Velocity': array([ 4.51852918e-01, -1.35968924e-01, -1.28278727e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52099609375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.09179688, 16411.09960938, 29.99996948]), + 'frame': 37917, + 'frame_number': 37917, + 'framesequence': 152900, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.14841152727603912, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.81996480003, + 'timestamp_carla': 1286824, + 'timestamp_device': 2905377, + 'timestamp_stream': 1286.81996480003, + 'transform': [array([ 2.19587891e+02, 3.05972626e+02, -1.45044431e-01]), + array([-9.12513211e-03, -1.74704422e+02, 2.19421275e-02])]} +{'AngularVelocity': array([ 0.0280613 , 0.01802246, -4.85595417]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.335323333740234, + 'FR_Wheel_Angle': -23.175931930541992, + 'Location': array([2.60434021e+02, 1.51853485e+02, 6.29548728e-02]), + 'Rotation': array([-0.01849615, -2.32168603, -0.00637817]), + 'Velocity': array([ 4.64629889e-01, -1.48552284e-01, 6.54602045e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.520263671875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23967.00195312, 16409.60546875, 30. ]), + 'frame': 37918, + 'frame_number': 37918, + 'framesequence': 152904, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13339640200138092, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.8528696000576, + 'timestamp_carla': 1286857, + 'timestamp_device': 2905410, + 'timestamp_stream': 1286.8528696000576, + 'transform': [array([ 2.19711395e+02, 3.05975220e+02, -1.44825593e-01]), + array([-9.79449041e-03, -1.74754547e+02, 2.20641941e-02])]} +{'AngularVelocity': array([ 0.0544572 , 0.01672345, -5.1622653 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.147871017456055, + 'FR_Wheel_Angle': -23.039213180541992, + 'Location': array([2.60545258e+02, 1.51823151e+02, 6.29534647e-02]), + 'Rotation': array([-0.01891279, -3.39087009, -0.0072937 ]), + 'Velocity': array([ 4.59367812e-01, -1.52638987e-01, 3.79228586e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.92382812, 16408.0390625 , 29.99996948]), + 'frame': 37919, + 'frame_number': 37919, + 'framesequence': 152908, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1176854819059372, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.8865812979639, + 'timestamp_carla': 1286890, + 'timestamp_device': 2905444, + 'timestamp_stream': 1286.8865812979639, + 'transform': [array([ 2.19821869e+02, 3.05975708e+02, -1.44242510e-01]), + array([-1.05321510e-02, -1.74799316e+02, 2.23388579e-02])]} +{'AngularVelocity': array([ 0.07400081, 0.03328719, -5.04163027]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.85760498046875, + 'FR_Wheel_Angle': -25.374191284179688, + 'Location': array([2.60654816e+02, 1.51790451e+02, 6.29572794e-02]), + 'Rotation': array([-0.01880351, -4.46273947, -0.00582886]), + 'Velocity': array([ 4.47241724e-01, -1.69168949e-01, 4.20856450e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5191650390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.859375 , 16406.54882812, 30. ]), + 'frame': 37920, + 'frame_number': 37920, + 'framesequence': 152912, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10607624053955078, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.9201371967793, + 'timestamp_carla': 1286924, + 'timestamp_device': 2905477, + 'timestamp_stream': 1286.9201371967793, + 'transform': [array([ 2.19921631e+02, 3.05974823e+02, -1.43632576e-01]), + array([-1.10785663e-02, -1.74839691e+02, 2.26135142e-02])]} +{'AngularVelocity': array([ 0.10277937, 0.0175901 , -4.97663927]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.80014419555664, + 'FR_Wheel_Angle': -25.455976486206055, + 'Location': array([2.60762695e+02, 1.51752441e+02, 6.29538819e-02]), + 'Rotation': array([-0.01855762, -5.66467619, -0.00616455]), + 'Velocity': array([ 4.49128449e-01, -1.85441390e-01, -1.17826457e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5164184570312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.81835938, 16405.04492188, 29.99996948]), + 'frame': 37921, + 'frame_number': 37921, + 'framesequence': 152916, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.10484939813613892, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.9539671987295, + 'timestamp_carla': 1286958, + 'timestamp_device': 2905510, + 'timestamp_stream': 1286.9539671987295, + 'transform': [array([ 2.20022461e+02, 3.05973785e+02, -1.43659204e-01]), + array([-1.12629812e-02, -1.74880432e+02, 2.26135161e-02])]} +{'AngularVelocity': array([ 0.08271658, 0.01510098, -5.51367712]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.191497802734375, + 'FR_Wheel_Angle': -25.664379119873047, + 'Location': array([2.60869354e+02, 1.51712357e+02, 6.29626513e-02]), + 'Rotation': array([-0.01907672, -6.84918785, -0.0071106 ]), + 'Velocity': array([ 4.37742174e-01, -1.94459110e-01, 2.36949913e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5142822265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.79296875, 16403.56445312, 30. ]), + 'frame': 37922, + 'frame_number': 37922, + 'framesequence': 152920, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11103855073451996, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1286.986542597413, + 'timestamp_carla': 1286990, + 'timestamp_device': 2905544, + 'timestamp_stream': 1286.986542597413, + 'transform': [array([ 2.20109207e+02, 3.05970978e+02, -1.44266352e-01]), + array([-1.07370568e-02, -1.74915527e+02, 2.23388560e-02])]} +{'AngularVelocity': array([-1.86400453e-03, -9.53129493e-03, -4.81735134e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.39430236816406, + 'FR_Wheel_Angle': -26.107236862182617, + 'Location': array([2.60975494e+02, 1.51669952e+02, 6.29597530e-02]), + 'Rotation': array([-1.86464153e-02, -8.04355717e+00, -6.50024414e-03]), + 'Velocity': array([ 4.55006659e-01, -2.18956545e-01, 1.26972198e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5134887695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.77929688, 16402.05859375, 29.99996948]), + 'frame': 37923, + 'frame_number': 37923, + 'framesequence': 152924, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11898557096719742, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.0201779976487, + 'timestamp_carla': 1287024, + 'timestamp_device': 2905577, + 'timestamp_stream': 1287.0201779976487, + 'transform': [array([ 2.20204193e+02, 3.05968811e+02, -1.44161105e-01]), + array([-9.91743430e-03, -1.74953995e+02, 2.23388560e-02])]} +{'AngularVelocity': array([-7.13305026e-02, -2.67364527e-03, -6.55810308e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -38.404815673828125, + 'FR_Wheel_Angle': -28.55409812927246, + 'Location': array([2.61079010e+02, 1.51623077e+02, 6.29538074e-02]), + 'Rotation': array([-1.99578125e-02, -9.32722187e+00, -4.82177781e-03]), + 'Velocity': array([ 4.21934724e-01, -2.48470232e-01, -1.52540204e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5166625976562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.76171875, 16400.57617188, 30. ]), + 'frame': 37924, + 'frame_number': 37924, + 'framesequence': 152928, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1261635273694992, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.0530643984675, + 'timestamp_carla': 1287057, + 'timestamp_device': 2905610, + 'timestamp_stream': 1287.0530643984675, + 'transform': [array([ 2.20307220e+02, 3.05968384e+02, -1.43322140e-01]), + array([-9.33686830e-03, -1.74995789e+02, 2.26440355e-02])]} +{'AngularVelocity': array([ 5.26307859e-02, -4.21576481e-03, -5.37357855e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.69240951538086, + 'FR_Wheel_Angle': -28.367918014526367, + 'Location': array([2.61163635e+02, 1.51581802e+02, 6.29504099e-02]), + 'Rotation': array([-1.93226039e-02, -1.04190826e+01, -6.98852539e-03]), + 'Velocity': array([ 4.10399795e-01, -2.34625712e-01, -1.14278788e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5180053710938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.72460938, 16399.04492188, 29.99996948]), + 'frame': 37925, + 'frame_number': 37925, + 'framesequence': 152932, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1272621899843216, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.0857909992337, + 'timestamp_carla': 1287090, + 'timestamp_device': 2905643, + 'timestamp_stream': 1287.0857909992337, + 'transform': [array([ 2.20409958e+02, 3.05968231e+02, -1.42304003e-01]), + array([-9.12513211e-03, -1.75037460e+02, 2.30407603e-02])]} +{'AngularVelocity': array([-0.09737781, -0.02533135, -5.85025311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -37.49879837036133, + 'FR_Wheel_Angle': -28.2873592376709, + 'Location': array([2.61261169e+02, 1.51531631e+02, 6.29568920e-02]), + 'Rotation': array([-1.83390565e-02, -1.17220030e+01, -6.01196242e-03]), + 'Velocity': array([ 4.37530667e-01, -2.71832108e-01, 7.44056670e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.519287109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.67773438, 16397.58789062, 30. ]), + 'frame': 37926, + 'frame_number': 37926, + 'framesequence': 152936, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12453383207321167, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.1201438978314, + 'timestamp_carla': 1287124, + 'timestamp_device': 2905677, + 'timestamp_stream': 1287.1201438978314, + 'transform': [array([ 2.20502609e+02, 3.05965454e+02, -1.43261641e-01]), + array([-8.82460363e-03, -1.75075012e+02, 2.26440355e-02])]} +{'AngularVelocity': array([-1.03564769e-01, 2.24013091e-03, -5.89575529e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.51896286010742, + 'FR_Wheel_Angle': -30.686532974243164, + 'Location': array([2.61359711e+02, 1.51477768e+02, 6.29541501e-02]), + 'Rotation': array([-1.84346791e-02, -1.30602312e+01, -5.03539946e-03]), + 'Velocity': array([ 4.21865076e-01, -2.89618105e-01, 1.17712021e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5196533203125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.625 , 16396.16796875, 29.99996948]), + 'frame': 37927, + 'frame_number': 37927, + 'framesequence': 152940, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12032227963209152, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.1529631987214, + 'timestamp_carla': 1287157, + 'timestamp_device': 2905710, + 'timestamp_stream': 1287.1529631987214, + 'transform': [array([ 2.20603577e+02, 3.05964722e+02, -1.43208310e-01]), + array([-9.03633982e-03, -1.75115906e+02, 2.26745512e-02])]} +{'AngularVelocity': array([-6.89836368e-02, 4.31789318e-04, -6.11323261e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.43820571899414, + 'FR_Wheel_Angle': -30.781953811645508, + 'Location': array([2.61468079e+02, 1.51410645e+02, 6.29542992e-02]), + 'Rotation': array([-1.87693592e-02, -1.47165413e+01, -5.18798828e-03]), + 'Velocity': array([ 4.01976436e-01, -3.05756003e-01, 7.20119424e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5188598632812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.58007812, 16394.6328125 , 29.99996948]), + 'frame': 37928, + 'frame_number': 37928, + 'framesequence': 152944, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11697134375572205, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.1863553002477, + 'timestamp_carla': 1287190, + 'timestamp_device': 2905743, + 'timestamp_stream': 1287.1863553002477, + 'transform': [array([ 2.20721542e+02, 3.05966003e+02, -1.43448830e-01]), + array([-9.12513211e-03, -1.75163696e+02, 2.25829985e-02])]} +{'AngularVelocity': array([-9.15505067e-02, 5.93860727e-03, -7.17483950e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67109298706055, + 'FR_Wheel_Angle': -30.78907012939453, + 'Location': array([2.61561707e+02, 1.51348450e+02, 6.29524663e-02]), + 'Rotation': array([-1.91040374e-02, -1.61824512e+01, -6.34765578e-03]), + 'Velocity': array([ 3.89041781e-01, -3.15816760e-01, 7.21168472e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.51953125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.53515625, 16393.19335938, 29.99996948]), + 'frame': 37929, + 'frame_number': 37929, + 'framesequence': 152948, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11706290394067764, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.2200667969882, + 'timestamp_carla': 1287224, + 'timestamp_device': 2905777, + 'timestamp_stream': 1287.2200667969882, + 'transform': [array([ 2.20827652e+02, 3.05965576e+02, -1.43467933e-01]), + array([-9.24807601e-03, -1.75206650e+02, 2.25829985e-02])]} +{'AngularVelocity': array([-8.42734054e-02, 4.25605103e-03, -7.06667948e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.678524017333984, + 'FR_Wheel_Angle': -30.795610427856445, + 'Location': array([2.61650513e+02, 1.51285675e+02, 6.29589558e-02]), + 'Rotation': array([-1.91996600e-02, -1.75957756e+01, -6.71386765e-03]), + 'Velocity': array([ 3.72337788e-01, -3.18467587e-01, 2.11129183e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.519287109375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.48632812, 16391.73828125, 30. ]), + 'frame': 37930, + 'frame_number': 37930, + 'framesequence': 152952, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11887570470571518, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.2538987994194, + 'timestamp_carla': 1287258, + 'timestamp_device': 2905810, + 'timestamp_stream': 1287.2538987994194, + 'transform': [array([ 2.20918121e+02, 3.05962799e+02, -1.43234521e-01]), + array([-9.18660406e-03, -1.75243286e+02, 2.26745531e-02])]} +{'AngularVelocity': array([-0.09393995, 0.00917319, -6.79285479]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.691864013671875, + 'FR_Wheel_Angle': -30.792587280273438, + 'Location': array([2.61735382e+02, 1.51222504e+02, 6.29584566e-02]), + 'Rotation': array([-1.95343401e-02, -1.89653072e+01, -7.32421922e-03]), + 'Velocity': array([ 3.50906581e-01, -3.17170471e-01, -1.42765042e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5182495117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.44335938, 16390.27734375, 29.99993896]), + 'frame': 37931, + 'frame_number': 37931, + 'framesequence': 152957, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12088992446660995, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.2889662981033, + 'timestamp_carla': 1287293, + 'timestamp_device': 2905852, + 'timestamp_stream': 1287.2889662981033, + 'transform': [array([ 2.21016052e+02, 3.05960785e+02, -1.42302275e-01]), + array([-8.94071721e-03, -1.75282990e+02, 2.30407584e-02])]} +{'AngularVelocity': array([-0.07857828, 0.01054713, -6.96122837]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68633270263672, + 'FR_Wheel_Angle': -30.801692962646484, + 'Location': array([2.61818695e+02, 1.51157394e+02, 6.29596040e-02]), + 'Rotation': array([-1.86805669e-02, -2.03377934e+01, -6.46972656e-03]), + 'Velocity': array([ 3.50355625e-01, -3.30134094e-01, 5.00679016e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.517822265625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.41015625, 16388.79882812, 30. ]), + 'frame': 37932, + 'frame_number': 37932, + 'framesequence': 152961, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12136600911617279, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.3221987001598, + 'timestamp_carla': 1287326, + 'timestamp_device': 2905885, + 'timestamp_stream': 1287.3221987001598, + 'transform': [array([ 2.21119171e+02, 3.05960236e+02, -1.42269671e-01]), + array([-8.76313262e-03, -1.75324753e+02, 2.30407622e-02])]} +{'AngularVelocity': array([-0.10529886, 0.0165004 , -6.71990538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69514846801758, + 'FR_Wheel_Angle': -30.80673599243164, + 'Location': array([2.61898773e+02, 1.51091827e+02, 6.29576594e-02]), + 'Rotation': array([-1.94113962e-02, -2.16539478e+01, -7.38525344e-03]), + 'Velocity': array([ 3.27651292e-01, -3.25446248e-01, -4.10079929e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5154418945312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.36328125, 16387.30859375, 30.00006104]), + 'frame': 37933, + 'frame_number': 37933, + 'framesequence': 152965, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12032227963209152, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.3548114970326, + 'timestamp_carla': 1287359, + 'timestamp_device': 2905918, + 'timestamp_stream': 1287.3548114970326, + 'transform': [array([ 2.21209610e+02, 3.05958008e+02, -1.42999187e-01]), + array([-8.60603806e-03, -1.75361420e+02, 2.27355864e-02])]} +{'AngularVelocity': array([-0.09313013, 0.01290757, -6.80010366]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.6893196105957, + 'FR_Wheel_Angle': -30.80782699584961, + 'Location': array([2.61975677e+02, 1.51025696e+02, 6.29502162e-02]), + 'Rotation': array([-1.84620004e-02, -2.29669018e+01, -6.16455032e-03]), + 'Velocity': array([ 3.27155322e-01, -3.39375973e-01, 8.94737241e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.517578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.31054688, 16385.89257812, 30. ]), + 'frame': 37934, + 'frame_number': 37934, + 'framesequence': 152968, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11935178935527802, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.386395599693, + 'timestamp_carla': 1287390, + 'timestamp_device': 2905943, + 'timestamp_stream': 1287.386395599693, + 'transform': [array([ 2.21303238e+02, 3.05956757e+02, -1.43222764e-01]), + array([-8.66751000e-03, -1.75399338e+02, 2.26440337e-02])]} +{'AngularVelocity': array([-0.08115759, 0.01655341, -6.48788071]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.703033447265625, + 'FR_Wheel_Angle': -30.810678482055664, + 'Location': array([2.62050598e+02, 1.50958282e+02, 6.29631504e-02]), + 'Rotation': array([-1.89810954e-02, -2.42723484e+01, -6.95800642e-03]), + 'Velocity': array([ 3.08306277e-01, -3.35138857e-01, 3.32221971e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5203857421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.26171875, 16384.48242188, 29.99996948]), + 'frame': 37935, + 'frame_number': 37935, + 'framesequence': 152972, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11946166306734085, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.4202733002603, + 'timestamp_carla': 1287424, + 'timestamp_device': 2905977, + 'timestamp_stream': 1287.4202733002603, + 'transform': [array([ 2.21395584e+02, 3.05954224e+02, -1.43092617e-01]), + array([-8.76313262e-03, -1.75436768e+02, 2.27050725e-02])]} +{'AngularVelocity': array([-0.07093566, 0.00943339, -6.51290607]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.701148986816406, + 'FR_Wheel_Angle': -30.808109283447266, + 'Location': array([2.62124298e+02, 1.50888947e+02, 6.29593357e-02]), + 'Rotation': array([-1.84346791e-02, -2.55782604e+01, -6.34765578e-03]), + 'Velocity': array([ 3.09479654e-01, -3.48103702e-01, 1.94420805e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5228271484375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.21679688, 16383.13574219, 30.00006104]), + 'frame': 37936, + 'frame_number': 37936, + 'framesequence': 152976, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12021241337060928, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.4530950970948, + 'timestamp_carla': 1287457, + 'timestamp_device': 2906010, + 'timestamp_stream': 1287.4530950970948, + 'transform': [array([ 2.21494858e+02, 3.05953125e+02, -1.42854795e-01]), + array([-8.70166067e-03, -1.75476990e+02, 2.27966215e-02])]} +{'AngularVelocity': array([ 0.01181603, -0.01685128, -6.67563725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67559051513672, + 'FR_Wheel_Angle': -30.80137825012207, + 'Location': array([2.62196564e+02, 1.50817810e+02, 6.29512891e-02]), + 'Rotation': array([-1.83732081e-02, -2.68895397e+01, -7.14111328e-03]), + 'Velocity': array([ 0.30181673, -0.34008861, 0.00052269]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205688476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.171875 , 16381.69140625, 30. ]), + 'frame': 37937, + 'frame_number': 37937, + 'framesequence': 152980, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12032227963209152, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.4869268983603, + 'timestamp_carla': 1287491, + 'timestamp_device': 2906043, + 'timestamp_stream': 1287.4869268983603, + 'transform': [array([ 2.21587189e+02, 3.05950958e+02, -1.42114177e-01]), + array([-8.79045296e-03, -1.75514404e+02, 2.31017955e-02])]} +{'AngularVelocity': array([ 0.03319399, -0.0185924 , -4.95338249]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67995834350586, + 'FR_Wheel_Angle': -30.804882049560547, + 'Location': array([2.62266235e+02, 1.50745926e+02, 6.29432723e-02]), + 'Rotation': array([-1.90425664e-02, -2.81978722e+01, -7.59887695e-03]), + 'Velocity': array([ 2.78861910e-01, -3.30970615e-01, 9.10568197e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.52099609375, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.11914062, 16380.30273438, 29.99996948]), + 'frame': 37938, + 'frame_number': 37938, + 'framesequence': 152984, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1200842335820198, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.5214024968445, + 'timestamp_carla': 1287525, + 'timestamp_device': 2906077, + 'timestamp_stream': 1287.5214024968445, + 'transform': [array([ 2.21673203e+02, 3.05947266e+02, -1.43157646e-01]), + array([-8.57188739e-03, -1.75549255e+02, 2.26745568e-02])]} +{'AngularVelocity': array([-0.09224202, 0.00891694, -5.99454308]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69984817504883, + 'FR_Wheel_Angle': -30.800100326538086, + 'Location': array([2.62335693e+02, 1.50671356e+02, 6.29499927e-02]), + 'Rotation': array([-1.82161126e-02, -2.95430317e+01, -6.34765578e-03]), + 'Velocity': array([ 2.92617023e-01, -3.73503596e-01, -1.28183368e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.518798828125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.0703125 , 16378.90136719, 30. ]), + 'frame': 37939, + 'frame_number': 37939, + 'framesequence': 152989, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11601916700601578, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.5566942989826, + 'timestamp_carla': 1287560, + 'timestamp_device': 2906118, + 'timestamp_stream': 1287.5566942989826, + 'transform': [array([ 2.21764648e+02, 3.05944183e+02, -1.43041223e-01]), + array([-8.76313262e-03, -1.75586304e+02, 2.27355845e-02])]} +{'AngularVelocity': array([-0.0355281 , 0.00950575, -5.6701827 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68390655517578, + 'FR_Wheel_Angle': -30.793697357177734, + 'Location': array([2.62404114e+02, 1.50594376e+02, 6.29471317e-02]), + 'Rotation': array([-1.84346791e-02, -3.09011326e+01, -6.50024461e-03]), + 'Velocity': array([ 2.76663542e-01, -3.70706052e-01, -6.82640093e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5184326171875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.02148438, 16377.4375 , 30. ]), + 'frame': 37940, + 'frame_number': 37940, + 'framesequence': 152993, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1060396209359169, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.5892248004675, + 'timestamp_carla': 1287593, + 'timestamp_device': 2906152, + 'timestamp_stream': 1287.5892248004675, + 'transform': [array([ 2.21861298e+02, 3.05942688e+02, -1.43968955e-01]), + array([-9.00218915e-03, -1.75625427e+02, 2.23693736e-02])]} +{'AngularVelocity': array([-0.09756398, 0.00776308, -6.23879862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69184112548828, + 'FR_Wheel_Angle': -30.794719696044922, + 'Location': array([2.62471313e+02, 1.50515091e+02, 6.29601777e-02]), + 'Rotation': array([-1.84620004e-02, -3.22667732e+01, -6.53076265e-03]), + 'Velocity': array([ 2.82836556e-01, -3.96294475e-01, 2.60395987e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.515869140625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23965.97265625, 16375.96972656, 29.99993896]), + 'frame': 37941, + 'frame_number': 37941, + 'framesequence': 152997, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09285561740398407, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.6213741004467, + 'timestamp_carla': 1287625, + 'timestamp_device': 2906185, + 'timestamp_stream': 1287.6213741004467, + 'transform': [array([ 2.21934509e+02, 3.05938232e+02, -1.44329265e-01]), + array([-9.52128321e-03, -1.75654999e+02, 2.22473014e-02])]} +{'AngularVelocity': array([ 0.12892275, -0.03230407, -4.84399986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66582489013672, + 'FR_Wheel_Angle': -30.789709091186523, + 'Location': array([2.62538727e+02, 1.50431396e+02, 6.29535019e-02]), + 'Rotation': array([-1.88581515e-02, -3.36679802e+01, -7.11059570e-03]), + 'Velocity': array([ 2.50076890e-01, -3.62832516e-01, -9.28783411e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5191040039062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23965.9296875 , 16374.6015625 , 30.00003052]), + 'frame': 37942, + 'frame_number': 37942, + 'framesequence': 153000, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07844477891921997, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.655792299658, + 'timestamp_carla': 1287659, + 'timestamp_device': 2906210, + 'timestamp_stream': 1287.655792299658, + 'transform': [array([ 2.22011124e+02, 3.05933105e+02, -1.44939229e-01]), + array([-1.00403773e-02, -1.75685913e+02, 2.20336802e-02])]} +{'AngularVelocity': array([ 0.06990395, -0.02375718, -4.80184937]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67165756225586, + 'FR_Wheel_Angle': -30.787626266479492, + 'Location': array([2.62601776e+02, 1.50348419e+02, 6.29579276e-02]), + 'Rotation': array([-1.90425664e-02, -3.50074234e+01, -7.08007859e-03]), + 'Velocity': array([ 2.41077036e-01, -3.72766823e-01, 1.46818158e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205078125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23965.91210938, 16373.23730469, 29.99996948]), + 'frame': 37943, + 'frame_number': 37943, + 'framesequence': 153004, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06403394043445587, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.6865213997662, + 'timestamp_carla': 1287690, + 'timestamp_device': 2906243, + 'timestamp_stream': 1287.6865213997662, + 'transform': [array([ 2.22061798e+02, 3.05926270e+02, -1.44836009e-01]), + array([-1.05594723e-02, -1.75706268e+02, 2.20947172e-02])]} +{'AngularVelocity': array([ 0.0889666 , -0.02735356, -4.81812572]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.663818359375, + 'FR_Wheel_Angle': -30.78610610961914, + 'Location': array([2.62664032e+02, 1.50262360e+02, 6.29600957e-02]), + 'Rotation': array([-1.86190940e-02, -3.63931847e+01, -6.71386719e-03]), + 'Velocity': array([ 2.34270930e-01, -3.83192658e-01, 2.85754184e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5177612304688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23965.90234375, 16371.77246094, 29.99996948]), + 'frame': 37944, + 'frame_number': 37944, + 'framesequence': 153008, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05000763013958931, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.7199852988124, + 'timestamp_carla': 1287724, + 'timestamp_device': 2906277, + 'timestamp_stream': 1287.7199852988124, + 'transform': [array([ 2.22113464e+02, 3.05918457e+02, -1.44911498e-01]), + array([-1.10785663e-02, -1.75726959e+02, 2.20947154e-02])]} +{'AngularVelocity': array([ 0.11920941, -0.04508198, -4.74413061]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66745376586914, + 'FR_Wheel_Angle': -30.7899112701416, + 'Location': array([2.62723206e+02, 1.50176285e+02, 6.29619658e-02]), + 'Rotation': array([-1.91381890e-02, -3.77433853e+01, -7.59887695e-03]), + 'Velocity': array([ 2.19638348e-01, -3.74142081e-01, -8.83388493e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5204467773438, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23965.91210938, 16370.46289062, 30. ]), + 'frame': 37945, + 'frame_number': 37945, + 'framesequence': 153012, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04403821378946304, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.7526829987764, + 'timestamp_carla': 1287756, + 'timestamp_device': 2906310, + 'timestamp_stream': 1287.7526829987764, + 'transform': [array([ 2.22161209e+02, 3.05910461e+02, -1.44946560e-01]), + array([-1.13517735e-02, -1.75746033e+02, 2.20947154e-02])]} +{'AngularVelocity': array([ 0.07683801, -0.03080321, -4.78964138]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.70757293701172, + 'FR_Wheel_Angle': -30.787790298461914, + 'Location': array([2.62771210e+02, 1.50103104e+02, 6.29505217e-02]), + 'Rotation': array([-1.93772465e-02, -3.88832741e+01, -7.96508789e-03]), + 'Velocity': array([ 2.07388625e-01, -3.72232854e-01, -1.23214719e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5178833007812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23965.94335938, 16369.04882812, 29.99996948]), + 'frame': 37946, + 'frame_number': 37946, + 'framesequence': 153016, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.04762718826532364, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.786627497524, + 'timestamp_carla': 1287790, + 'timestamp_device': 2906343, + 'timestamp_stream': 1287.786627497524, + 'transform': [array([ 2.22211044e+02, 3.05902191e+02, -1.44991562e-01]), + array([-1.10512450e-02, -1.75765961e+02, 2.20641941e-02])]} +{'AngularVelocity': array([-0.0771077 , 0.04100124, -6.89517784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69634246826172, + 'FR_Wheel_Angle': -30.80664825439453, + 'Location': array([2.62833405e+02, 1.50003662e+02, 6.29560575e-02]), + 'Rotation': array([-1.87693592e-02, -4.04160423e+01, -6.68335008e-03]), + 'Velocity': array([ 2.07641840e-01, -4.17116970e-01, -9.06181303e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5173950195312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23965.984375 , 16367.6640625 , 30.00003052]), + 'frame': 37947, + 'frame_number': 37947, + 'framesequence': 153020, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05573900416493416, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.8190521001816, + 'timestamp_carla': 1287823, + 'timestamp_device': 2906377, + 'timestamp_stream': 1287.8190521001816, + 'transform': [array([ 2.22259445e+02, 3.05894409e+02, -1.44773856e-01]), + array([-1.05936229e-02, -1.75785339e+02, 2.21252348e-02])]} +{'AngularVelocity': array([-0.08466869, 0.0372243 , -6.43214369]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.7026481628418, + 'FR_Wheel_Angle': -30.806846618652344, + 'Location': array([2.62884888e+02, 1.49916153e+02, 6.29596412e-02]), + 'Rotation': array([-1.89810954e-02, -4.17298393e+01, -7.20214797e-03]), + 'Velocity': array([ 1.97311878e-01, -4.17258799e-01, -8.53157035e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5162353515625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.02148438, 16366.23046875, 30.00003052]), + 'frame': 37948, + 'frame_number': 37948, + 'framesequence': 153024, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06342967599630356, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.8526376970112, + 'timestamp_carla': 1287856, + 'timestamp_device': 2906410, + 'timestamp_stream': 1287.8526376970112, + 'transform': [array([ 2.22313141e+02, 3.05886749e+02, -1.44622996e-01]), + array([-9.97890625e-03, -1.75806885e+02, 2.21557505e-02])]} +{'AngularVelocity': array([-0.09334461, 0.01511589, -6.03696775]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.699684143066406, + 'FR_Wheel_Angle': -30.81007957458496, + 'Location': array([2.62927094e+02, 1.49840805e+02, 6.29560202e-02]), + 'Rotation': array([-1.88308302e-02, -4.28499527e+01, -7.38525437e-03]), + 'Velocity': array([ 1.98269904e-01, -4.25283313e-01, 2.01044080e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5182495117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.05273438, 16364.86230469, 29.99996948]), + 'frame': 37949, + 'frame_number': 37949, + 'framesequence': 153028, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06751304864883423, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.886818498373, + 'timestamp_carla': 1287891, + 'timestamp_device': 2906443, + 'timestamp_stream': 1287.886818498373, + 'transform': [array([ 2.22370667e+02, 3.05879364e+02, -1.44402504e-01]), + array([-9.39833932e-03, -1.75829987e+02, 2.22167838e-02])]} +{'AngularVelocity': array([ 0.1044546 , -0.06420927, -3.67127728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.957481384277344, + 'FR_Wheel_Angle': -25.597450256347656, + 'Location': array([2.62981934e+02, 1.49740295e+02, 6.29830658e-02]), + 'Rotation': array([-1.85849443e-02, -4.42762833e+01, -1.11083975e-02]), + 'Velocity': array([ 1.91311091e-01, -3.69222969e-01, 2.10518832e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5186767578125, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.07421875, 16363.4453125 , 29.99996948]), + 'frame': 37950, + 'frame_number': 37950, + 'framesequence': 153032, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06575518101453781, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.9200654998422, + 'timestamp_carla': 1287924, + 'timestamp_device': 2906477, + 'timestamp_stream': 1287.9200654998422, + 'transform': [array([ 2.22437653e+02, 3.05873627e+02, -1.44291341e-01]), + array([-9.15928278e-03, -1.75856934e+02, 2.22473014e-02])]} +{'AngularVelocity': array([ 0.02683051, -0.01692159, -2.6631763 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.847166061401367, + 'FR_Wheel_Angle': -16.0802059173584, + 'Location': array([2.63037140e+02, 1.49655045e+02, 6.29534200e-02]), + 'Rotation': array([-1.74852833e-02, -4.51288261e+01, -1.53503409e-02]), + 'Velocity': array([ 2.45234638e-01, -3.68295670e-01, 1.23786922e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5180053710938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.0859375 , 16362.00683594, 30. ]), + 'frame': 37951, + 'frame_number': 37951, + 'framesequence': 153036, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06198309361934662, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.9530989974737, + 'timestamp_carla': 1287957, + 'timestamp_device': 2906510, + 'timestamp_stream': 1287.9530989974737, + 'transform': [array([ 2.22476974e+02, 3.05864197e+02, -1.44875035e-01]), + array([-9.00218915e-03, -1.75872681e+02, 2.20031627e-02])]} +{'AngularVelocity': array([ 0.00351962, 0.00096052, -0.07099938]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.786200046539307, + 'FR_Wheel_Angle': -4.372527599334717, + 'Location': array([2.63102814e+02, 1.49572189e+02, 6.29327446e-02]), + 'Rotation': array([-1.74511317e-02, -4.55739059e+01, -1.72424279e-02]), + 'Velocity': array([ 2.94686705e-01, -3.47842485e-01, -3.36799625e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5192260742188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.09570312, 16360.62207031, 29.99996948]), + 'frame': 37952, + 'frame_number': 37952, + 'framesequence': 153040, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05817438289523125, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1287.9869988001883, + 'timestamp_carla': 1287991, + 'timestamp_device': 2906543, + 'timestamp_stream': 1287.9869988001883, + 'transform': [array([ 2.22541595e+02, 3.05857574e+02, -1.45262942e-01]), + array([-9.03633982e-03, -1.75898651e+02, 2.18505766e-02])]} +{'AngularVelocity': array([-0.02293635, 0.02369103, 0.256585 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.34215831756591797, + 'FR_Wheel_Angle': 0.07753806561231613, + 'Location': array([2.63176392e+02, 1.49494659e+02, 6.29366785e-02]), + 'Rotation': array([-1.82434339e-02, -4.55994492e+01, -1.51062012e-02]), + 'Velocity': array([ 0.31859586, -0.32424724, -0.00035314]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5209350585938, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.1171875 , 16359.20507812, 30. ]), + 'frame': 37953, + 'frame_number': 37953, + 'framesequence': 153044, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05685598403215408, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.0196573995054, + 'timestamp_carla': 1288023, + 'timestamp_device': 2906577, + 'timestamp_stream': 1288.0196573995054, + 'transform': [array([ 2.22584885e+02, 3.05848602e+02, -1.45711660e-01]), + array([-9.03633982e-03, -1.75915985e+02, 2.16674674e-02])]} +{'AngularVelocity': array([-0.02306546, -0.00852327, -0.73081964]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038157689850777388, + 'FR_Wheel_Angle': 0.003815049771219492, + 'Location': array([2.63240631e+02, 1.49428970e+02, 6.29353821e-02]), + 'Rotation': array([-1.82434339e-02, -4.56032906e+01, -1.09863291e-02]), + 'Velocity': array([ 0.32929629, -0.33577242, -0.00063298]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5200805664062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.13085938, 16357.76171875, 29.99996948]), + 'frame': 37954, + 'frame_number': 37954, + 'framesequence': 153048, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05817438289523125, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.0518477968872, + 'timestamp_carla': 1288056, + 'timestamp_device': 2906610, + 'timestamp_stream': 1288.0518477968872, + 'transform': [array([ 2.22624924e+02, 3.05839569e+02, -1.45632848e-01]), + array([-9.06366017e-03, -1.75932007e+02, 2.16979850e-02])]} +{'AngularVelocity': array([-0.0368284 , -0.03135223, 0.04985339]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038140909746289253, + 'FR_Wheel_Angle': 0.003814256051555276, + 'Location': array([2.63328644e+02, 1.49338867e+02, 6.29560575e-02]), + 'Rotation': array([-1.76696982e-02, -4.56113129e+01, -9.21630859e-03]), + 'Velocity': array([ 0.35165825, -0.36138192, -0.00042823]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5220336914062, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.15234375, 16356.34960938, 29.99996948]), + 'frame': 37955, + 'frame_number': 37955, + 'framesequence': 153052, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06018860638141632, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.0857912003994, + 'timestamp_carla': 1288090, + 'timestamp_device': 2906643, + 'timestamp_stream': 1288.0857912003994, + 'transform': [array([ 2.22681396e+02, 3.05831970e+02, -1.45174250e-01]), + array([-8.97486787e-03, -1.75954651e+02, 2.18810923e-02])]} +{'AngularVelocity': array([-0.02435936, -0.02789594, 0.36060414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038131880573928356, + 'FR_Wheel_Angle': 0.0038134618662297726, + 'Location': array([2.63407379e+02, 1.49257980e+02, 6.29411042e-02]), + 'Rotation': array([-1.77038498e-02, -4.56223335e+01, -8.85009766e-03]), + 'Velocity': array([ 3.54031682e-01, -3.64516020e-01, -3.16085818e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5233154296875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.18359375, 16354.96679688, 30. ]), + 'frame': 37956, + 'frame_number': 37956, + 'framesequence': 153056, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.061415448784828186, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.1198922991753, + 'timestamp_carla': 1288124, + 'timestamp_device': 2906677, + 'timestamp_stream': 1288.1198922991753, + 'transform': [array([ 2.22746124e+02, 3.05825378e+02, -1.44649312e-01]), + array([-8.97486787e-03, -1.75980652e+02, 2.20947172e-02])]} +{'AngularVelocity': array([-0.03446549, -0.03526819, -0.02935127]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038135468494147062, + 'FR_Wheel_Angle': 0.003813887480646372, + 'Location': array([2.63486237e+02, 1.49176834e+02, 6.29536882e-02]), + 'Rotation': array([-1.81204900e-02, -4.56220627e+01, -9.09423735e-03]), + 'Velocity': array([ 3.57459068e-01, -3.65635514e-01, 6.61849990e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5213012695312, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.20117188, 16353.53613281, 30. ]), + 'frame': 37957, + 'frame_number': 37957, + 'framesequence': 153060, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06079287454485893, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.153150100261, + 'timestamp_carla': 1288157, + 'timestamp_device': 2906710, + 'timestamp_stream': 1288.153150100261, + 'transform': [array([ 2.22797882e+02, 3.05817596e+02, -1.44090921e-01]), + array([-8.79045296e-03, -1.76001419e+02, 2.23083403e-02])]} +{'AngularVelocity': array([-0.04606832, -0.04823671, 0.05933679]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038124523125588894, + 'FR_Wheel_Angle': 0.003811321221292019, + 'Location': array([2.63565399e+02, 1.49095413e+02, 6.29476234e-02]), + 'Rotation': array([-1.75126046e-02, -4.56139793e+01, -9.06371977e-03]), + 'Velocity': array([ 3.71417373e-01, -3.79444718e-01, -7.78293615e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5194091796875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.22070312, 16352.11035156, 30.00006104]), + 'frame': 37958, + 'frame_number': 37958, + 'framesequence': 153064, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05951109528541565, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.1858040988445, + 'timestamp_carla': 1288190, + 'timestamp_device': 2906743, + 'timestamp_stream': 1288.1858040988445, + 'transform': [array([ 2.22846375e+02, 3.05809784e+02, -1.43241763e-01]), + array([-8.72898102e-03, -1.76020905e+02, 2.26440318e-02])]} +{'AngularVelocity': array([-0.04813835, -0.04788925, 0.11407491]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0038057826459407806, + 'FR_Wheel_Angle': 0.003804990788921714, + 'Location': array([2.63653809e+02, 1.49004486e+02, 6.29344285e-02]), + 'Rotation': array([-1.40428683e-02, -4.55659981e+01, -8.88061523e-03]), + 'Velocity': array([ 0.4412165 , -0.45181933, 0.00058477]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5198364257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.234375 , 16350.71679688, 30. ]), + 'frame': 37959, + 'frame_number': 37959, + 'framesequence': 153068, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05936460569500923, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.219877999276, + 'timestamp_carla': 1288224, + 'timestamp_device': 2906777, + 'timestamp_stream': 1288.219877999276, + 'transform': [array([ 2.22877579e+02, 3.05798950e+02, -1.43768117e-01]), + array([-8.64018872e-03, -1.76033371e+02, 2.24304106e-02])]} +{'AngularVelocity': array([-0.04419771, -0.04471682, 0.20032431]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003793777897953987, + 'FR_Wheel_Angle': 0.0037915839347988367, + 'Location': array([2.63764130e+02, 1.48891174e+02, 6.29131421e-02]), + 'Rotation': array([-1.01633212e-02, -4.55408249e+01, -8.88061523e-03]), + 'Velocity': array([ 5.56962132e-01, -5.70352256e-01, 2.85148622e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5206909179688, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.24414062, 16349.36132812, 30. ]), + 'frame': 37960, + 'frame_number': 37960, + 'framesequence': 153073, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.06009704992175102, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.2545240968466, + 'timestamp_carla': 1288258, + 'timestamp_device': 2906818, + 'timestamp_stream': 1288.2545240968466, + 'transform': [array([ 2.22926239e+02, 3.05790070e+02, -1.43936351e-01]), + array([-8.70166067e-03, -1.76052917e+02, 2.23693717e-02])]} +{'AngularVelocity': array([-0.03539607, -0.03389724, -0.01092713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003782858606427908, + 'FR_Wheel_Angle': 0.0037817200645804405, + 'Location': array([2.63904358e+02, 1.48747482e+02, 6.29093274e-02]), + 'Rotation': array([-9.45981126e-03, -4.55172310e+01, -9.03320219e-03]), + 'Velocity': array([ 6.75117493e-01, -6.89569592e-01, 2.45475767e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5198364257812, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.26757812, 16347.9140625 , 30. ]), + 'frame': 37961, + 'frame_number': 37961, + 'framesequence': 153076, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0603167861700058, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.2867185994983, + 'timestamp_carla': 1288291, + 'timestamp_device': 2906843, + 'timestamp_stream': 1288.2867185994983, + 'transform': [array([ 2.22969131e+02, 3.05781647e+02, -1.43778905e-01]), + array([-8.76313262e-03, -1.76070129e+02, 2.24304069e-02])]} +{'AngularVelocity': array([-0.04252832, -0.04107096, 0.00134298]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003769859904423356, + 'FR_Wheel_Angle': 0.0037681518588215113, + 'Location': array([2.64046448e+02, 1.48602325e+02, 6.28944859e-02]), + 'Rotation': array([-8.85192491e-03, -4.55173531e+01, -8.91113095e-03]), + 'Velocity': array([ 7.84174323e-01, -8.01016748e-01, -1.51767730e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5182495117188, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.28125 , 16346.45703125, 29.99996948]), + 'frame': 37962, + 'frame_number': 37962, + 'framesequence': 153080, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0602252297103405, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.3201714977622, + 'timestamp_carla': 1288324, + 'timestamp_device': 2906877, + 'timestamp_stream': 1288.3201714977622, + 'transform': [array([ 2.23025391e+02, 3.05774567e+02, -1.43408313e-01]), + array([-8.82460363e-03, -1.76092697e+02, 2.25830004e-02])]} +{'AngularVelocity': array([-0.02982506, -0.02916336, 0.00154786]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003757600672543049, + 'FR_Wheel_Angle': 0.003756608348339796, + 'Location': array([2.64242371e+02, 1.48402176e+02, 6.28883094e-02]), + 'Rotation': array([-8.39430187e-03, -4.55173264e+01, -8.91113188e-03]), + 'Velocity': array([ 9.13459659e-01, -9.33070838e-01, 1.60055162e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.5205688476562, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.296875 , 16345.11035156, 29.99996948]), + 'frame': 37963, + 'frame_number': 37963, + 'framesequence': 153084, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.05806451663374901, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.3531477972865, + 'timestamp_carla': 1288357, + 'timestamp_device': 2906910, + 'timestamp_stream': 1288.3531477972865, + 'transform': [array([ 2.23072021e+02, 3.05766663e+02, -1.42890081e-01]), + array([-8.94071721e-03, -1.76111420e+02, 2.27966197e-02])]} +{'AngularVelocity': array([-0.02628747, -0.02573743, 0.00169179]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.003751270705834031, + 'FR_Wheel_Angle': 0.0037509489338845015, + 'Location': array([2.64458984e+02, 1.48180908e+02, 6.29176423e-02]), + 'Rotation': array([-1.16591323e-02, -4.55171738e+01, -8.91113281e-03]), + 'Velocity': array([ 9.81866181e-01, -1.00293267e+00, 1.86686506e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.519775390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.31054688, 16343.7421875 , 30. ]), + 'frame': 37964, + 'frame_number': 37964, + 'framesequence': 153088, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.050392165780067444, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.3873707987368, + 'timestamp_carla': 1288391, + 'timestamp_device': 2906943, + 'timestamp_stream': 1288.3873707987368, + 'transform': [array([ 2.23099686e+02, 3.05756378e+02, -1.41651690e-01]), + array([-9.27539635e-03, -1.76122421e+02, 2.33154166e-02])]} +{'AngularVelocity': array([1.85732648e-03, 2.05014367e-03, 9.74678987e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.64686707e+02, 1.47948242e+02, 6.29412532e-02]), + 'Rotation': array([-1.55660007e-02, -4.55170517e+01, -8.91113281e-03]), + 'Velocity': array([ 9.86599147e-01, -1.00781822e+00, 9.05990601e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.519775390625, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.32617188, 16342.41113281, 29.99996948]), + 'frame': 37965, + 'frame_number': 37965, + 'framesequence': 153092, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03706168010830879, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.4202512986958, + 'timestamp_carla': 1288424, + 'timestamp_device': 2906977, + 'timestamp_stream': 1288.4202512986958, + 'transform': [array([ 2.23152161e+02, 3.05749207e+02, -1.42892718e-01]), + array([-9.52128321e-03, -1.76143463e+02, 2.28271373e-02])]} +{'AngularVelocity': array([1.73946396e-02, 1.70088820e-02, 1.82437434e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.64913055e+02, 1.47716965e+02, 6.29574284e-02]), + 'Rotation': array([-2.05042269e-02, -4.55172920e+01, -8.91113374e-03]), + 'Velocity': array([ 9.33919728e-01, -9.54015315e-01, -3.78179539e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.516357421875, + 'focus_actor_name': 'Road_Grass_Town02_1', + 'focus_actor_pt': array([23966.359375 , 16341.0703125, 30. ]), + 'frame': 37966, + 'frame_number': 37966, + 'framesequence': 153096, + 'gaze_dir': array([1., 0., 0.]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': False, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([1., 0., 0.]), + 'left_gaze_origin': array([0., 0., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': -1.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([1., 0., 0.]), + 'right_gaze_origin': array([0., 0., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': -1.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.023346660658717155, + 'throttle_input': 0.0634927898645401, + 'timestamp': 1288.4529037997127, + 'timestamp_carla': 1288457, + 'timestamp_device': 2907010, + 'timestamp_stream': 1288.4529037997127, + 'transform': [array([ 2.23173401e+02, 3.05738281e+02, -1.43571392e-01]), + array([-1.01018492e-02, -1.76151779e+02, 2.25829966e-02])]} \ No newline at end of file diff --git a/PythonAPI/data/vehicle_logs/log_auto_fw.txt b/PythonAPI/data/vehicle_logs/log_auto_fw.txt new file mode 100644 index 0000000..ccba15d --- /dev/null +++ b/PythonAPI/data/vehicle_logs/log_auto_fw.txt @@ -0,0 +1,36190 @@ +{'AngularVelocity': array([-8.08959448e-05, 6.30066506e-06, 7.39372519e-09]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.34057335e-07, -7.79086751e-09, 1.77524565e-03]), + 'Rotation': array([0., 0., 0.]), + 'Velocity': array([ 4.52360416e-09, 6.54449721e-08, -2.34441759e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 666.8662109375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 98.21051025, -128.25932312, 0. ]), + 'frame': 294, + 'frame_number': 294, + 'framesequence': 292, + 'gaze_dir': array([ 0.98058069, -0.19281359, 0.03583925]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19281359, 0.03583925]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19281359, 0.03583925]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.773549977689981, + 'timestamp_carla': 9773, + 'timestamp_device': 9241, + 'timestamp_stream': 9.773549977689981, + 'transform': [array([ 5.34057335e-07, -7.79086751e-09, 1.77524565e-03]), + array([0., 0., 0.])]} +{'AngularVelocity': array([-3.65893757e-05, 1.68257691e-02, 1.33457497e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.31059676e-01, -2.52764281e-08, 1.83998107e-03]), + 'Rotation': array([-8.94071721e-03, 4.43064300e-06, 5.50866162e-07]), + 'Velocity': array([ 7.77964830e-01, 9.99791965e-08, -9.11235747e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 663.7180786132812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 94.64599609, -127.97387695, 0. ]), + 'frame': 295, + 'frame_number': 295, + 'framesequence': 293, + 'gaze_dir': array([ 0.98058069, -0.19329642, 0.03313645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19329642, 0.03313645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19329642, 0.03313645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.78651337698102, + 'timestamp_carla': 9786, + 'timestamp_device': 9255, + 'timestamp_stream': 9.78651337698102, + 'transform': [array([ 1.24076838e-02, -1.47432040e-08, 1.78333279e-03]), + array([-7.64981145e-04, 6.71640521e-07, 4.77729031e-07])]} +{'AngularVelocity': array([ 2.39564888e-05, -1.18012941e-02, 1.04681012e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.70238250e-01, -3.32112862e-08, 1.84772490e-03]), + 'Rotation': array([-9.85596236e-03, 6.05057676e-06, 3.43326434e-07]), + 'Velocity': array([ 8.82668674e-01, 1.04242623e-07, -1.42202378e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 660.351806640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 9.08345947e+01, -1.27643646e+02, -3.05175781e-05]), + 'frame': 296, + 'frame_number': 296, + 'framesequence': 294, + 'gaze_dir': array([ 0.98058069, -0.19364925, 0.0310081 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19364925, 0.0310081 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19364925, 0.0310081 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.79864577949047, + 'timestamp_carla': 9798, + 'timestamp_device': 9266, + 'timestamp_stream': 9.79864577949047, + 'transform': [array([ 2.36977004e-02, -9.81646497e-09, 1.79527281e-03]), + array([-1.70754723e-03, 1.25066583e-06, 0.00000000e+00])]} +{'AngularVelocity': array([-4.06287763e-05, -1.23470062e-02, 9.51989477e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.20025170e-01, -2.68131135e-08, 1.81144709e-03]), + 'Rotation': array([-8.82460363e-03, 7.05565435e-06, 1.66886764e-06]), + 'Velocity': array([ 9.14052546e-01, 1.63275701e-07, -2.49910343e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 657.7247924804688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 89.10095215, -127.36791229, 0. ]), + 'frame': 297, + 'frame_number': 297, + 'framesequence': 295, + 'gaze_dir': array([ 0.98058069, -0.19403596, 0.0284882 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19403596, 0.0284882 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19403596, 0.0284882 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.811158277094364, + 'timestamp_carla': 9811, + 'timestamp_device': 9279, + 'timestamp_stream': 9.811158277094364, + 'transform': [array([ 3.50446701e-02, -1.29969315e-08, 1.80496217e-03]), + array([-2.77988683e-03, 1.77729510e-06, 8.15368395e-08])]} +{'AngularVelocity': array([ 2.43498034e-05, -9.10079665e-03, 8.82799213e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.71604371e-01, -1.52227653e-08, 1.82460784e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.17423844e-01, 1.78937327e-07, 2.73847581e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 654.641845703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.67393494e+01, -1.27024078e+02, -3.05175781e-05]), + 'frame': 298, + 'frame_number': 298, + 'framesequence': 296, + 'gaze_dir': array([ 0.98058069, -0.19438991, 0.0259633 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19438991, 0.0259633 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19438991, 0.0259633 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.823726877570152, + 'timestamp_carla': 9823, + 'timestamp_device': 9292, + 'timestamp_stream': 9.823726877570152, + 'transform': [array([ 4.61775213e-02, -1.95394971e-08, 1.81362149e-03]), + array([-3.84539622e-03, 2.23525331e-06, 8.21704589e-07])]} +{'AngularVelocity': array([ 1.74583383e-05, -5.84562263e-03, 8.96232268e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([7.15008140e-01, 4.13476275e-09, 1.79550168e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.23584044e-01, 2.90088082e-07, 1.04813575e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 651.5808715820312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 84.40844727, -126.66074371, 0. ]), + 'frame': 299, + 'frame_number': 299, + 'framesequence': 297, + 'gaze_dir': array([ 0.98058069, -0.19468747, 0.0236288 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19468747, 0.0236288 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19468747, 0.0236288 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.83635187894106, + 'timestamp_carla': 9836, + 'timestamp_device': 9304, + 'timestamp_stream': 9.83635187894106, + 'transform': [array([ 5.71245961e-02, -2.09923545e-08, 1.82106008e-03]), + array([-4.84943390e-03, 2.63468883e-06, 6.28860448e-07])]} +{'AngularVelocity': array([-3.69942900e-05, -4.58486052e-03, 8.89504554e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([8.63060832e-01, 1.44864174e-08, 1.81480404e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.22575593e-01, 1.81518715e-07, 2.28028293e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 648.7759399414062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 82.3460083 , -126.30854797, 0. ]), + 'frame': 300, + 'frame_number': 300, + 'framesequence': 298, + 'gaze_dir': array([ 0.98058069, -0.19497818, 0.02109602]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19497818, 0.02109602]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19497818, 0.02109602]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.849095277488232, + 'timestamp_carla': 9849, + 'timestamp_device': 9317, + 'timestamp_stream': 9.849095277488232, + 'transform': [array([ 6.79620355e-02, -2.50948293e-08, 1.82697293e-03]), + array([-5.79883019e-03, 2.98796772e-06, 7.05605942e-07])]} +{'AngularVelocity': array([-3.01775417e-05, -3.60754272e-03, 8.83545090e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([1.02426958e+00, 6.64496014e-08, 1.82136532e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.21799362e-01, 4.60455283e-07, 1.83501237e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 645.760498046875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 80.02658081, -125.90920258, 0. ]), + 'frame': 301, + 'frame_number': 301, + 'framesequence': 299, + 'gaze_dir': array([ 0.98058069, -0.19525442, 0.01836436]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19525442, 0.01836436]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19525442, 0.01836436]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.863213676959276, + 'timestamp_carla': 9863, + 'timestamp_device': 9331, + 'timestamp_stream': 9.863213676959276, + 'transform': [array([ 7.97436535e-02, -2.41169325e-08, 1.82445522e-03]), + array([-6.68675499e-03, 3.32984496e-06, 4.68422286e-07])]} +{'AngularVelocity': array([-3.24010325e-05, -3.47735570e-03, 8.71654356e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([1.19230258e+00, 1.07590736e-07, 1.81285851e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.19087112e-01, 4.13229031e-07, 2.13613501e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 642.5398559570312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 77.46380615, -125.45874023, 0. ]), + 'frame': 302, + 'frame_number': 302, + 'framesequence': 300, + 'gaze_dir': array([ 0.98058069, -0.19547664, 0.01582448]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19547664, 0.01582448]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19547664, 0.01582448]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.876516479998827, + 'timestamp_carla': 9876, + 'timestamp_device': 9344, + 'timestamp_stream': 9.876516479998827, + 'transform': [array([ 9.06602070e-02, -2.44848000e-08, 1.82720181e-03]), + array([-7.39026442e-03, 3.61082880e-06, 3.42576925e-07])]} +{'AngularVelocity': array([-4.54950205e-05, -3.15418816e-03, 8.86948874e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([1.33632779e+00, 1.39400058e-07, 1.81446073e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.23984885e-01, 4.77537469e-07, -3.01971420e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 639.5720825195312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.52821655e+01, -1.25021393e+02, -3.05175781e-05]), + 'frame': 303, + 'frame_number': 303, + 'framesequence': 301, + 'gaze_dir': array([ 0.98058069, -0.19566584, 0.01328211]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19566584, 0.01328211]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19566584, 0.01328211]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.88927497714758, + 'timestamp_carla': 9889, + 'timestamp_device': 9357, + 'timestamp_stream': 9.88927497714758, + 'transform': [array([ 1.00979075e-01, -2.68317368e-08, 1.83193199e-03]), + array([-7.93667976e-03, 3.85040494e-06, 4.98235295e-07])]} +{'AngularVelocity': array([-3.24451503e-05, -3.49172275e-03, 8.80331390e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([1.48608124e+00, 1.68727439e-07, 1.83174131e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.21987593e-01, 2.43638681e-07, 9.96065137e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 636.630615234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 73.04333496, -124.56686401, 0. ]), + 'frame': 304, + 'frame_number': 304, + 'framesequence': 302, + 'gaze_dir': array([ 0.98058069, -0.19582197, 0.01073731]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19582197, 0.01073731]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19582197, 0.01073731]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.901480577886105, + 'timestamp_carla': 9901, + 'timestamp_device': 9370, + 'timestamp_stream': 9.901480577886105, + 'transform': [array([ 1.10725708e-01, -2.33252901e-08, 1.83803553e-03]), + array([-8.36015120e-03, 4.05652600e-06, 1.34771811e-08])]} +{'AngularVelocity': array([ 2.87634357e-05, -3.23059084e-03, 8.86361522e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([1.64847791e+00, 2.20802420e-07, 1.81629171e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.20926094e-01, 4.01636782e-07, -1.93009371e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 633.7144775390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 70.77313232, -124.09520721, 0. ]), + 'frame': 305, + 'frame_number': 305, + 'framesequence': 303, + 'gaze_dir': array([ 0.98058069, -0.19593669, 0.0083869 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19593669, 0.0083869 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19593669, 0.0083869 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.914556577801704, + 'timestamp_carla': 9914, + 'timestamp_device': 9382, + 'timestamp_stream': 9.914556577801704, + 'transform': [array([ 1.21040568e-01, -2.25616077e-08, 1.83864590e-03]), + array([-8.70166067e-03, 4.25472354e-06, 8.47694679e-08])]} +{'AngularVelocity': array([-1.65058664e-05, -2.90716998e-03, 8.96998245e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([1.80383027e+00, 2.72313827e-07, 1.82449340e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.23920572e-01, 5.61210072e-07, -3.63349909e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 631.0450439453125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 68.7250061 , -123.64488983, 0. ]), + 'frame': 306, + 'frame_number': 306, + 'framesequence': 304, + 'gaze_dir': array([ 0.98058069, -0.19602917, 0.00583899]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19602917, 0.00583899]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19602917, 0.00583899]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.927402276545763, + 'timestamp_carla': 9927, + 'timestamp_device': 9395, + 'timestamp_stream': 9.927402276545763, + 'transform': [array([ 1.31059676e-01, -2.52764281e-08, 1.83998107e-03]), + array([-8.94071721e-03, 4.43064300e-06, 5.50866162e-07])]} +{'AngularVelocity': array([-3.70240086e-05, -3.27709643e-03, 8.93588276e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([1.94953072e+00, 3.33511053e-07, 1.81465142e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.23765779e-01, 5.77399362e-07, 6.61659215e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 628.1759643554688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 66.50772095, -123.14081573, 0. ]), + 'frame': 307, + 'frame_number': 307, + 'framesequence': 305, + 'gaze_dir': array([ 0.98058069, -0.19608854, 0.00329028]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19608854, 0.00329028]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19608854, 0.00329028]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.940006077289581, + 'timestamp_carla': 9940, + 'timestamp_device': 9408, + 'timestamp_stream': 9.940006077289581, + 'transform': [array([ 1.43467322e-01, -2.78003132e-08, 1.84291834e-03]), + array([-9.24807601e-03, 4.74753506e-06, 6.32283331e-07])]} +{'AngularVelocity': array([-3.40113147e-05, -3.24880425e-03, 8.85211102e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.09423757e+00, 3.87909665e-07, 1.81114196e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.24360633e-01, 3.96547222e-07, -2.32071878e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 625.3322143554688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.42894287e+01, -1.22620468e+02, -3.05175781e-05]), + 'frame': 308, + 'frame_number': 308, + 'framesequence': 306, + 'gaze_dir': array([ 9.80580688e-01, -1.96113884e-01, 9.37016681e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, -1.96113884e-01, 9.37016681e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, -1.96113884e-01, 9.37016681e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.952147778123617, + 'timestamp_carla': 9952, + 'timestamp_device': 9420, + 'timestamp_stream': 9.952147778123617, + 'transform': [array([ 1.55262336e-01, -2.67246243e-08, 1.84738159e-03]), + array([-9.52128321e-03, 5.03335514e-06, 3.41544734e-07])]} +{'AngularVelocity': array([ 3.52113748e-05, -3.30870575e-03, 8.86503221e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.25733733e+00, 4.41288449e-07, 1.79779052e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.20858145e-01, 4.98373026e-07, 4.25357808e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 622.7295532226562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.25830383e+01, -1.22125923e+02, 3.05175781e-05]), + 'frame': 309, + 'frame_number': 309, + 'framesequence': 307, + 'gaze_dir': array([ 0.98058069, -0.19611101, -0.00141638]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19611101, -0.00141638]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19611101, -0.00141638]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.964556276798248, + 'timestamp_carla': 9964, + 'timestamp_device': 9432, + 'timestamp_stream': 9.964556276798248, + 'transform': [array([ 1.67167932e-01, -2.94301277e-08, 1.84986112e-03]), + array([-9.76717006e-03, 5.29950466e-06, 6.88421608e-07])]} +{'AngularVelocity': array([-6.92120302e-05, -3.44186742e-03, 8.83171379e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.41129518e+00, 5.05996695e-07, 1.79294578e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.19785619e-01, 6.23607662e-07, 5.06343844e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 620.1488647460938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.08401184e+01, -1.21618034e+02, -3.05175781e-05]), + 'frame': 310, + 'frame_number': 310, + 'framesequence': 308, + 'gaze_dir': array([ 0.98058069, -0.19607604, -0.00396573]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19607604, -0.00396573]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19607604, -0.00396573]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.977162979543209, + 'timestamp_carla': 9977, + 'timestamp_device': 9445, + 'timestamp_stream': 9.977162979543209, + 'transform': [array([ 1.79123715e-01, -3.37840866e-08, 1.85073854e-03]), + array([-9.97890625e-03, 5.54491908e-06, 1.42852480e-06])]} +{'AngularVelocity': array([ 7.45957950e-05, -3.25806788e-03, 8.74763555e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.56046462e+00, 5.82486223e-07, 1.78726192e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.21861529e-01, 5.96407745e-07, 1.29222870e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 617.3770141601562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.88917542e+01, -1.21052834e+02, -3.05175781e-05]), + 'frame': 311, + 'frame_number': 311, + 'framesequence': 309, + 'gaze_dir': array([ 0.98058069, -0.19600791, -0.00651422]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19600791, -0.00651422]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19600791, -0.00651422]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 9.990179978311062, + 'timestamp_carla': 9990, + 'timestamp_device': 9458, + 'timestamp_stream': 9.990179978311062, + 'transform': [array([ 1.91332698e-01, -3.07526093e-08, 1.84913632e-03]), + array([-1.01359999e-02, 5.77412220e-06, 8.51507082e-07])]} +{'AngularVelocity': array([ 2.93836747e-05, -3.23300622e-03, 8.88515569e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.70755720e+00, 6.55930307e-07, 1.80351257e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.23016250e-01, 6.45733394e-07, 1.04360581e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 614.6302490234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.69770508e+01, -1.20472397e+02, 3.05175781e-05]), + 'frame': 312, + 'frame_number': 312, + 'framesequence': 310, + 'gaze_dir': array([ 0.98058069, -0.19591562, -0.0088658 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19591562, -0.0088658 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19591562, -0.0088658 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.002389676868916, + 'timestamp_carla': 10002, + 'timestamp_device': 9470, + 'timestamp_stream': 10.002389676868916, + 'transform': [array([ 2.02671662e-01, -3.32764927e-08, 1.85150141e-03]), + array([-1.01359999e-02, 5.77412220e-06, 8.51507082e-07])]} +{'AngularVelocity': array([ 3.07686387e-05, -3.17104417e-03, 8.96918937e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([2.85233259e+00, 7.37099754e-07, 1.81144709e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.24224854e-01, 6.91480295e-07, 2.74858467e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 612.1171264648438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.53522339e+01, -1.19923309e+02, 3.05175781e-05]), + 'frame': 313, + 'frame_number': 313, + 'framesequence': 311, + 'gaze_dir': array([ 0.98058069, -0.19577232, -0.01160765]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19577232, -0.01160765]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19577232, -0.01160765]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.015696879476309, + 'timestamp_carla': 10015, + 'timestamp_device': 9484, + 'timestamp_stream': 10.015696879476309, + 'transform': [array([ 2.14910433e-01, -3.61775641e-08, 1.84749602e-03]), + array([-1.01359999e-02, 5.77412220e-06, 8.51507082e-07])]} +{'AngularVelocity': array([ 1.50156138e-05, -2.80897180e-03, 8.99841871e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([3.00179076e+00, 8.14082853e-07, 1.78241730e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.26800132e-01, 5.76808588e-07, -4.00238030e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.2138671875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.31983643e+01, -1.19267220e+02, -3.05175781e-05]), + 'frame': 314, + 'frame_number': 314, + 'framesequence': 312, + 'gaze_dir': array([ 0.98058069, -0.19561894, -0.01395604]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19561894, -0.01395604]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19561894, -0.01395604]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.027655579149723, + 'timestamp_carla': 10027, + 'timestamp_device': 9496, + 'timestamp_stream': 10.027655579149723, + 'transform': [array([ 2.25814551e-01, -3.50134002e-08, 1.85047148e-03]), + array([-1.01359999e-02, 5.77412220e-06, 8.51507082e-07])]} +{'AngularVelocity': array([-2.11102015e-05, -3.49307945e-03, 8.74464149e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([3.16917014e+00, 8.89561932e-07, 1.79267884e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.19677556e-01, 5.29515603e-07, -6.35132776e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 606.7476806640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.16297607e+01, -1.18691338e+02, 3.05175781e-05]), + 'frame': 315, + 'frame_number': 315, + 'framesequence': 313, + 'gaze_dir': array([ 0.98058069, -0.19543737, -0.01630243]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19543737, -0.01630243]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19543737, -0.01630243]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.040006279945374, + 'timestamp_carla': 10040, + 'timestamp_device': 9508, + 'timestamp_stream': 10.040006279945374, + 'transform': [array([ 2.36984938e-01, -3.34860211e-08, 1.85085298e-03]), + array([-1.01359999e-02, 5.77412220e-06, 8.51507082e-07])]} +{'AngularVelocity': array([-1.79920389e-05, -3.13226134e-03, 8.88155955e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([3.31500936e+00, 9.69636972e-07, 1.81869499e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.23340738e-01, 7.84822873e-07, 4.98371141e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 604.3050537109375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 4.99539490e+01, -1.18103806e+02, -3.05175781e-05]), + 'frame': 316, + 'frame_number': 316, + 'framesequence': 314, + 'gaze_dir': array([ 0.98058069, -0.1952277 , -0.01864646]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1952277 , -0.01864646]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1952277 , -0.01864646]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.052041176706553, + 'timestamp_carla': 10052, + 'timestamp_device': 9520, + 'timestamp_stream': 10.052041176706553, + 'transform': [array([ 2.47786820e-01, -3.80402092e-08, 1.85218803e-03]), + array([-1.01359999e-02, 5.77412220e-06, 8.51507082e-07])]} +{'AngularVelocity': array([ 1.93187716e-05, -3.55089945e-03, 8.77389903e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([3.46924591e+00, 1.06427331e-06, 1.80141442e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.19941783e-01, 7.31997034e-07, -1.18470191e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 601.8837890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 48.32919312, -117.50439453, 0. ]), + 'frame': 317, + 'frame_number': 317, + 'framesequence': 315, + 'gaze_dir': array([ 0.98058069, -0.19498987, -0.02098781]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19498987, -0.02098781]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19498987, -0.02098781]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.06460027769208, + 'timestamp_carla': 10064, + 'timestamp_device': 9532, + 'timestamp_stream': 10.06460027769208, + 'transform': [array([ 2.58975148e-01, -3.29411982e-08, 1.85043330e-03]), + array([-1.00062266e-02, 5.91542175e-06, 2.69081227e-07])]} +{'AngularVelocity': array([ 4.39717369e-05, -2.68014404e-03, 9.16468889e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([3.60466862e+00, 1.13573378e-06, 1.78855890e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.28173065e-01, 7.05772720e-07, 4.80999937e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 599.4848022460938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 4.66927185e+01, -1.16893478e+02, -3.05175781e-05]), + 'frame': 318, + 'frame_number': 318, + 'framesequence': 316, + 'gaze_dir': array([ 0.98058069, -0.19470057, -0.02352074]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19470057, -0.02352074]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19470057, -0.02352074]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.077336378395557, + 'timestamp_carla': 10077, + 'timestamp_device': 9545, + 'timestamp_stream': 10.077336378395557, + 'transform': [array([ 2.70238250e-01, -3.32112862e-08, 1.84772490e-03]), + array([-9.85596236e-03, 6.05057676e-06, 3.43326434e-07])]} +{'AngularVelocity': array([-5.79270200e-05, -3.68198380e-03, 8.68014467e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([3.77673244e+00, 1.23253074e-06, 1.80603028e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.17768776e-01, 6.83887833e-07, -1.30653382e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 596.910400390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 4.48963623e+01, -1.16218796e+02, -3.05175781e-05]), + 'frame': 319, + 'frame_number': 319, + 'framesequence': 317, + 'gaze_dir': array([ 0.98058069, -0.19437835, -0.02604989]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19437835, -0.02604989]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19437835, -0.02604989]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.089880779385567, + 'timestamp_carla': 10089, + 'timestamp_device': 9558, + 'timestamp_stream': 10.089880779385567, + 'transform': [array([ 2.81254500e-01, -3.56839607e-08, 1.84608460e-03]), + array([-9.70569812e-03, 6.17777005e-06, 7.89477554e-07])]} +{'AngularVelocity': array([ 8.54572572e-05, -3.14660091e-03, 8.96336587e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([3.92430115e+00, 1.33565607e-06, 1.79489132e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.22371864e-01, 7.73945317e-07, -2.50248908e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 594.3616333007812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 43.1366272 , -115.53104401, 0. ]), + 'frame': 320, + 'frame_number': 320, + 'framesequence': 318, + 'gaze_dir': array([ 0.98058069, -0.19405176, -0.02838051]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19405176, -0.02838051]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19405176, -0.02838051]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.10218257829547, + 'timestamp_carla': 10102, + 'timestamp_device': 9570, + 'timestamp_stream': 10.10218257829547, + 'transform': [array([ 2.93439865e-01, -3.50040885e-08, 1.84661860e-03]), + array([-9.70569812e-03, 6.17777005e-06, 7.89477554e-07])]} +{'AngularVelocity': array([-2.52079044e-05, -3.23868939e-03, 8.89563125e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([4.08814335e+00, 1.45682577e-06, 1.77944184e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.20498550e-01, 9.40313896e-07, -7.70568840e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 592.0322265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 41.60049438, -114.8848877 , 0. ]), + 'frame': 321, + 'frame_number': 321, + 'framesequence': 319, + 'gaze_dir': array([ 0.98058069, -0.19366644, -0.03090063]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19366644, -0.03090063]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19366644, -0.03090063]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.11482597887516, + 'timestamp_carla': 10114, + 'timestamp_device': 9583, + 'timestamp_stream': 10.11482597887516, + 'transform': [array([ 3.05849671e-01, -3.24336185e-08, 1.84532162e-03]), + array([-9.70569812e-03, 6.17777005e-06, 7.89477554e-07])]} +{'AngularVelocity': array([ 3.47922396e-05, -3.32963187e-03, 8.70891745e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([4.25708389e+00, 1.58978139e-06, 1.76715851e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.18225288e-01, 6.85208590e-07, 1.07417101e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 589.5343017578125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 3.99903870e+01, -1.14173004e+02, -3.05175781e-05]), + 'frame': 322, + 'frame_number': 322, + 'framesequence': 320, + 'gaze_dir': array([ 0.98058069, -0.19324836, -0.0334157 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19324836, -0.0334157 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19324836, -0.0334157 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.127978678792715, + 'timestamp_carla': 10127, + 'timestamp_device': 9596, + 'timestamp_stream': 10.127978678792715, + 'transform': [array([ 3.18644017e-01, -3.36210562e-08, 1.84139248e-03]), + array([-9.70569812e-03, 6.17777005e-06, 7.89477554e-07])]} +{'AngularVelocity': array([ 8.71209995e-05, -3.06699751e-03, 8.93999459e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([4.40191650e+00, 1.68479028e-06, 1.81915273e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.23505545e-01, 7.50608933e-07, 4.82931122e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 587.0619506835938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 38.43173218, -113.44875336, 0. ]), + 'frame': 323, + 'frame_number': 323, + 'framesequence': 321, + 'gaze_dir': array([ 0.98058069, -0.19279768, -0.03592495]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19279768, -0.03592495]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19279768, -0.03592495]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.140689779073, + 'timestamp_carla': 10140, + 'timestamp_device': 9609, + 'timestamp_stream': 10.140689779073, + 'transform': [array([ 3.30905944e-01, -3.04918011e-08, 1.84036256e-03]), + array([-9.70569812e-03, 6.17777005e-06, 7.89477554e-07])]} +{'AngularVelocity': array([ 3.79611338e-05, -2.73381476e-03, 9.09869868e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([4.54954290e+00, 1.80044196e-06, 1.79450982e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.27352667e-01, 7.91561831e-07, -1.57518385e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 584.6152954101562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 36.94091797, -112.71247864, 0. ]), + 'frame': 324, + 'frame_number': 324, + 'framesequence': 322, + 'gaze_dir': array([ 0.98058069, -0.19231434, -0.0384283 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19231434, -0.0384283 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19231434, -0.0384283 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.154009379446507, + 'timestamp_carla': 10154, + 'timestamp_device': 9622, + 'timestamp_stream': 10.154009379446507, + 'transform': [array([ 3.43650728e-01, -3.21123146e-08, 1.83601375e-03]), + array([-9.70569812e-03, 6.17777005e-06, 7.89477554e-07])]} +{'AngularVelocity': array([ 2.44014373e-05, -3.27056600e-03, 8.90193314e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([4.70880127e+00, 1.93015649e-06, 1.80408475e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.22856748e-01, 9.66279913e-07, 1.19123455e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 582.1951904296875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 35.42669678, -111.9644928 , 0. ]), + 'frame': 325, + 'frame_number': 325, + 'framesequence': 323, + 'gaze_dir': array([ 0.98058069, -0.19175752, -0.04111684]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19175752, -0.04111684]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19175752, -0.04111684]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.167990278452635, + 'timestamp_carla': 10167, + 'timestamp_device': 9636, + 'timestamp_stream': 10.167990278452635, + 'transform': [array([ 3.56919974e-01, -2.90808444e-08, 1.82830810e-03]), + array([-9.58275516e-03, 6.34731441e-06, 4.24942186e-07])]} +{'AngularVelocity': array([-2.67072355e-05, -3.22014769e-03, 8.91243235e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([4.85375547e+00, 2.06870482e-06, 1.81140890e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.24123824e-01, 1.16405806e-06, 1.55739777e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 579.6177978515625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 33.78277588, -111.14606476, 0. ]), + 'frame': 326, + 'frame_number': 326, + 'framesequence': 324, + 'gaze_dir': array([ 0.98058069, -0.19120684, -0.04360605]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19120684, -0.04360605]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19120684, -0.04360605]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.181000478565693, + 'timestamp_carla': 10181, + 'timestamp_device': 9649, + 'timestamp_stream': 10.181000478565693, + 'transform': [array([ 3.69175971e-01, -2.69993361e-08, 1.82762137e-03]), + array([-9.45981126e-03, 6.49583626e-06, 3.87272422e-07])]} +{'AngularVelocity': array([ 3.10428222e-05, -3.45112616e-03, 8.76938793e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([5.00405455e+00, 2.20781180e-06, 1.80023187e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.21867728e-01, 9.94042466e-07, 1.67365070e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 577.2509765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 3.24299927e+01, -1.10374336e+02, 3.05175781e-05]), + 'frame': 327, + 'frame_number': 327, + 'framesequence': 325, + 'gaze_dir': array([ 0.98058069, -0.19057764, -0.04627857]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19057764, -0.04627857]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19057764, -0.04627857]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.194788377732038, + 'timestamp_carla': 10194, + 'timestamp_device': 9663, + 'timestamp_stream': 10.194788377732038, + 'transform': [array([ 3.82069081e-01, -2.87222992e-08, 1.82243343e-03]), + array([-9.33686830e-03, 6.64603385e-06, 8.79798904e-07])]} +{'AngularVelocity': array([ 1.15803496e-05, -3.19085899e-03, 8.89642706e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([5.15022564e+00, 2.36210849e-06, 1.80648803e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.23523784e-01, 1.12374983e-06, 1.26013751e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 574.732666015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 30.80392456, -109.53120422, 0. ]), + 'frame': 328, + 'frame_number': 328, + 'framesequence': 326, + 'gaze_dir': array([ 0.98058069, -0.18995991, -0.0487522 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18995991, -0.0487522 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18995991, -0.0487522 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.208050578832626, + 'timestamp_carla': 10208, + 'timestamp_device': 9676, + 'timestamp_stream': 10.208050578832626, + 'transform': [array([ 3.94383729e-01, -2.69807288e-08, 1.82109827e-03]), + array([-9.18660406e-03, 6.78281458e-06, 9.77078003e-07])]} +{'AngularVelocity': array([ 3.77974939e-05, -3.11337016e-03, 9.00699433e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([5.29296017e+00, 2.48513152e-06, 1.78203580e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.25219119e-01, 8.67326889e-07, -7.89947517e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 572.4203491210938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 29.47512817, -108.73693085, 0. ]), + 'frame': 329, + 'frame_number': 329, + 'framesequence': 327, + 'gaze_dir': array([ 0.98058069, -0.18925878, -0.05140676]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18925878, -0.05140676]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18925878, -0.05140676]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.221950277686119, + 'timestamp_carla': 10221, + 'timestamp_device': 9690, + 'timestamp_stream': 10.221950277686119, + 'transform': [array([ 4.07200396e-01, -2.49411372e-08, 1.81617728e-03]), + array([-9.00218915e-03, 6.92132062e-06, 1.10337032e-06])]} +{'AngularVelocity': array([-7.12899491e-05, -3.60474805e-03, 8.66292794e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([5.46588326e+00, 2.65669973e-06, 1.77860260e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.16779220e-01, 1.21145138e-06, 2.30493533e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 569.9603881835938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 27.92108154, -107.87001038, 0. ]), + 'frame': 330, + 'frame_number': 330, + 'framesequence': 328, + 'gaze_dir': array([ 0.98058069, -0.18852058, -0.05405125]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18852058, -0.05405125]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18852058, -0.05405125]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.235955577343702, + 'timestamp_carla': 10235, + 'timestamp_device': 9704, + 'timestamp_stream': 10.235955577343702, + 'transform': [array([ 4.20025170e-01, -2.68131135e-08, 1.81144709e-03]), + array([-8.82460363e-03, 7.05565435e-06, 1.66886764e-06])]} +{'AngularVelocity': array([ 2.91326469e-05, -3.65971169e-03, 8.66137452e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([5.62909222e+00, 2.83710619e-06, 1.77543634e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.15163875e-01, 1.22255756e-06, -3.69400979e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 567.5299072265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 26.45077515, -106.99105835, 0. ]), + 'frame': 331, + 'frame_number': 331, + 'framesequence': 329, + 'gaze_dir': array([ 0.98058069, -0.18780203, -0.05649729]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18780203, -0.05649729]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18780203, -0.05649729]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.249513078480959, + 'timestamp_carla': 10249, + 'timestamp_device': 9717, + 'timestamp_stream': 10.249513078480959, + 'transform': [array([ 4.33470041e-01, -2.41448586e-08, 1.81354524e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([-2.34457293e-05, -3.46414396e-03, 8.90185675e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([5.78820372e+00, 2.99899330e-06, 1.78005209e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.16741848e-01, 1.01703108e-06, -1.38254167e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 565.2999877929688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 25.20849609, -106.16448212, 0. ]), + 'frame': 332, + 'frame_number': 332, + 'framesequence': 330, + 'gaze_dir': array([ 0.98058069, -0.18705168, -0.05893396]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18705168, -0.05893396]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18705168, -0.05893396]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.26265637949109, + 'timestamp_carla': 10262, + 'timestamp_device': 9730, + 'timestamp_stream': 10.26265637949109, + 'transform': [array([ 4.46398139e-01, -2.48386982e-08, 1.81739801e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([-6.38012425e-05, -3.39333760e-03, 8.74318812e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([5.94267273e+00, 3.15147417e-06, 1.83818815e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.18984830e-01, 9.73660576e-07, 1.53684614e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 563.0974731445312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 24.05877686, -105.32832336, 0. ]), + 'frame': 333, + 'frame_number': 333, + 'framesequence': 331, + 'gaze_dir': array([ 0.98058069, -0.18620831, -0.06154681]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18620831, -0.06154681]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18620831, -0.06154681]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.276173278689384, + 'timestamp_carla': 10276, + 'timestamp_device': 9744, + 'timestamp_stream': 10.276173278689384, + 'transform': [array([ 4.59588319e-01, -2.56396380e-08, 1.81842805e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([-1.83501015e-05, -3.17216502e-03, 8.88577597e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([6.08949995e+00, 3.30933790e-06, 1.82758330e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([ 9.22746539e-01, 1.26663406e-06, -2.68006319e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 560.7548828125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.26986389e+01, -1.04417206e+02, 3.05175781e-05]), + 'frame': 334, + 'frame_number': 334, + 'framesequence': 332, + 'gaze_dir': array([ 0.98058069, -0.18539245, -0.06396235]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18539245, -0.06396235]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18539245, -0.06396235]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.28927667811513, + 'timestamp_carla': 10289, + 'timestamp_device': 9757, + 'timestamp_stream': 10.28927667811513, + 'transform': [array([ 4.72279340e-01, -2.93882234e-08, 1.82128907e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([-6.30895229e-05, -3.39203887e-03, 8.79885556e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([6.23942614e+00, 3.46288039e-06, 1.82689668e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.21791673e-01, 8.73159706e-07, 1.67427061e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 558.60595703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 21.58428955, -103.5613327 , 0. ]), + 'frame': 335, + 'frame_number': 335, + 'framesequence': 333, + 'gaze_dir': array([ 0.98058069, -0.18454534, -0.06636689]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18454534, -0.06636689]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18454534, -0.06636689]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.30211427807808, + 'timestamp_carla': 10302, + 'timestamp_device': 9770, + 'timestamp_stream': 10.30211427807808, + 'transform': [array([ 4.84625548e-01, -2.58631516e-08, 1.82472228e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([-2.22485687e-05, -3.31585854e-03, 8.88701652e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([6.38852787e+00, 3.64720313e-06, 1.81625364e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.22141790e-01, 1.38025666e-06, 2.48751632e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 556.4835815429688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 20.44985962, -102.69644928, 0. ]), + 'frame': 336, + 'frame_number': 336, + 'framesequence': 334, + 'gaze_dir': array([ 0.98058069, -0.18359816, -0.06894393]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18359816, -0.06894393]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18359816, -0.06894393]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.316065579652786, + 'timestamp_carla': 10316, + 'timestamp_device': 9784, + 'timestamp_stream': 10.316065579652786, + 'transform': [array([ 4.97946322e-01, -1.98048671e-08, 1.82113645e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([ 1.82691711e-05, -3.33411898e-03, 8.75424394e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([6.53774595e+00, 3.82704138e-06, 1.80732727e-03]), + 'Rotation': array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06]), + 'Velocity': array([9.22124982e-01, 1.23813379e-06, 2.09236132e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 554.2268676757812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 19.1288147 , -101.75502014, 0. ]), + 'frame': 337, + 'frame_number': 337, + 'framesequence': 335, + 'gaze_dir': array([ 0.98058069, -0.18268636, -0.0713249 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18268636, -0.0713249 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18268636, -0.0713249 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.32942657917738, + 'timestamp_carla': 10329, + 'timestamp_device': 9797, + 'timestamp_stream': 10.32942657917738, + 'transform': [array([ 5.10615468e-01, -1.97583017e-08, 1.82147976e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([-0.06178558, -0.00298484, -0.54560375]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -2.0129647254943848, + 'FR_Wheel_Angle': -2.6565792560577393, + 'Location': array([ 6.68877745e+00, -2.08999671e-04, 1.80335995e-03]), + 'Rotation': array([-0.00818257, -0.01000976, 0.00132092]), + 'Velocity': array([ 9.20937121e-01, -1.48275718e-02, 1.93557731e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 552.1566772460938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.81169434e+01, -1.00871490e+02, 3.05175781e-05]), + 'frame': 338, + 'frame_number': 338, + 'framesequence': 336, + 'gaze_dir': array([ 0.98058069, -0.18166994, -0.07387542]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18166994, -0.07387542]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18166994, -0.07387542]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.342804476618767, + 'timestamp_carla': 10342, + 'timestamp_device': 9811, + 'timestamp_stream': 10.342804476618767, + 'transform': [array([ 5.23216248e-01, -1.97815915e-08, 1.82140351e-03]), + array([-8.72898102e-03, 7.24878782e-06, 1.20780646e-06])]} +{'AngularVelocity': array([-3.46826203e-02, -3.34475189e-04, -3.11734295e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.895675659179688, + 'FR_Wheel_Angle': -10.513089179992676, + 'Location': array([ 6.83836460e+00, -7.54454639e-03, 1.80526730e-03]), + 'Rotation': array([-0.00854457, -0.31625366, 0.0138156 ]), + 'Velocity': array([ 9.12871003e-01, -9.66454372e-02, 2.66089424e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 549.9571533203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.68930969e+01, -9.99106903e+01, -3.05175781e-05]), + 'frame': 339, + 'frame_number': 339, + 'framesequence': 337, + 'gaze_dir': array([ 0.98058069, -0.18069428, -0.07623073]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18069428, -0.07623073]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18069428, -0.07623073]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.35593357682228, + 'timestamp_carla': 10355, + 'timestamp_device': 9824, + 'timestamp_stream': 10.35593357682228, + 'transform': [array([ 5.35503626e-01, -2.13555413e-08, 1.82243343e-03]), + array([-8.60603806e-03, 7.37685104e-06, 1.68698443e-06])]} +{'AngularVelocity': array([ 5.10501228e-02, -2.26074271e-03, -5.57467175e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.0197811126709, + 'FR_Wheel_Angle': -17.429332733154297, + 'Location': array([ 6.98528194e+00, -2.51979791e-02, 1.80324551e-03]), + 'Rotation': array([-0.00958276, -1.03152454, 0.02975964]), + 'Velocity': array([ 8.90337944e-01, -1.81799725e-01, 3.78847108e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 547.941162109375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 15.87036133, -99.00984192, 0. ]), + 'frame': 340, + 'frame_number': 340, + 'framesequence': 338, + 'gaze_dir': array([ 0.98058069, -0.17968799, -0.07857335]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17968799, -0.07857335]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17968799, -0.07857335]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.369565177708864, + 'timestamp_carla': 10369, + 'timestamp_device': 9837, + 'timestamp_stream': 10.369565177708864, + 'transform': [array([ 5.48179269e-01, -2.14952429e-08, 1.82022096e-03]), + array([-8.48309416e-03, 7.50602294e-06, 1.77112474e-06])]} +{'AngularVelocity': array([ 0.13791955, -0.01026644, -7.79518795]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -29.558074951171875, + 'FR_Wheel_Angle': -23.824689865112305, + 'Location': array([ 7.12005186e+00, -5.14027327e-02, 1.81262963e-03]), + 'Rotation': array([-0.01153619, -2.06060815, 0.04797195]), + 'Velocity': array([ 8.55536878e-01, -2.63586432e-01, 1.40943521e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 545.9511108398438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.48454590e+01, -9.81008606e+01, -3.05175781e-05]), + 'frame': 341, + 'frame_number': 341, + 'framesequence': 339, + 'gaze_dir': array([ 0.98058069, -0.17865144, -0.0809025 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17865144, -0.0809025 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17865144, -0.0809025 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.381876576691866, + 'timestamp_carla': 10381, + 'timestamp_device': 9850, + 'timestamp_stream': 10.381876576691866, + 'transform': [array([ 5.59559643e-01, -2.22496190e-08, 1.82487478e-03]), + array([-8.36015120e-03, 7.61881256e-06, 1.93064466e-06])]} +{'AngularVelocity': array([ 0.22954674, -0.03022967, -10.09665012]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -39.84505081176758, + 'FR_Wheel_Angle': -30.047929763793945, + 'Location': array([ 7.26633406e+00, -9.31300074e-02, 1.83887477e-03]), + 'Rotation': array([-0.01443219, -3.63272119, 0.06421001]), + 'Velocity': array([ 7.87101567e-01, -3.52751166e-01, 3.91197209e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 543.9856567382812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 13.88769531, -97.18384552, 0. ]), + 'frame': 342, + 'frame_number': 342, + 'framesequence': 340, + 'gaze_dir': array([ 0.98058057, -0.17758459, -0.08321814]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17758459, -0.08321814]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17758459, -0.08321814]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.394984778016806, + 'timestamp_carla': 10394, + 'timestamp_device': 9863, + 'timestamp_stream': 10.394984778016806, + 'transform': [array([ 5.71604371e-01, -1.52227653e-08, 1.82460784e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.36789191, -0.08008779, -10.12191582]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.29708480834961, + 'FR_Wheel_Angle': -30.00827407836914, + 'Location': array([ 7.40547085e+00, -1.44035384e-01, 1.84017175e-03]), + 'Rotation': array([-0.01675445, -5.47003508, 0.07222808]), + 'Velocity': array([ 7.41412163e-01, -3.77973288e-01, 1.48410792e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 542.0470581054688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.28302002e+01, -9.62592163e+01, 3.05175781e-05]), + 'frame': 343, + 'frame_number': 343, + 'framesequence': 341, + 'gaze_dir': array([ 0.98058069, -0.17657328, -0.08534297]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17657328, -0.08534297]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17657328, -0.08534297]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.407633479684591, + 'timestamp_carla': 10407, + 'timestamp_device': 9875, + 'timestamp_stream': 10.407633479684591, + 'transform': [array([ 5.84158480e-01, -1.53810937e-08, 1.82647700e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39512643, -0.0995606 , -10.22749996]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.42605209350586, + 'FR_Wheel_Angle': -30.566730499267578, + 'Location': array([ 7.53081226e+00, -1.93875536e-01, 1.84314721e-03]), + 'Rotation': array([-0.01803853, -7.15863752, 0.07969996]), + 'Velocity': array([ 7.12404072e-01, -4.00909960e-01, -4.68935963e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 540.279541015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 12.03329468, -95.39892578, 0. ]), + 'frame': 344, + 'frame_number': 344, + 'framesequence': 342, + 'gaze_dir': array([ 0.98058069, -0.17544889, -0.08763123]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17544889, -0.08763123]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17544889, -0.08763123]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.420288980007172, + 'timestamp_carla': 10420, + 'timestamp_device': 9888, + 'timestamp_stream': 10.420288980007172, + 'transform': [array([ 5.96625447e-01, -1.61028861e-08, 1.82792661e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42898265, -0.1203741 , -10.08754349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.433902740478516, + 'FR_Wheel_Angle': -30.567161560058594, + 'Location': array([ 7.64591599e+00, -2.42795825e-01, 1.87061308e-03]), + 'Rotation': array([-0.01943872, -8.72663403, 0.08971504]), + 'Velocity': array([ 6.91519916e-01, -4.14757460e-01, -2.45785719e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 538.3893432617188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.11481934e+01, -9.44598236e+01, 3.05175781e-05]), + 'frame': 345, + 'frame_number': 345, + 'framesequence': 343, + 'gaze_dir': array([ 0.98058069, -0.17429493, -0.08990452]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17429493, -0.08990452]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17429493, -0.08990452]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.433242578059435, + 'timestamp_carla': 10433, + 'timestamp_device': 9901, + 'timestamp_stream': 10.433242578059435, + 'transform': [array([ 6.09292388e-01, -1.32530271e-08, 1.82746886e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.46370718, -0.14448772, -9.93459225]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44287872314453, + 'FR_Wheel_Angle': -30.57173728942871, + 'Location': array([ 7.75798130e+00, -2.93522805e-01, 1.88415521e-03]), + 'Rotation': array([ -0.02044276, -10.26960754, 0.09720033]), + 'Velocity': array([ 6.69318318e-01, -4.26991999e-01, -1.09238623e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 536.524658203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 10.28326416, -93.51352692, 0. ]), + 'frame': 346, + 'frame_number': 346, + 'framesequence': 344, + 'gaze_dir': array([ 0.98058069, -0.17301916, -0.09233591]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17301916, -0.09233591]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17301916, -0.09233591]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.446638576686382, + 'timestamp_carla': 10446, + 'timestamp_device': 9915, + 'timestamp_stream': 10.446638576686382, + 'transform': [array([ 6.22296453e-01, -8.68953531e-09, 1.82453147e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49073806, -0.16748188, -9.77436638]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.45198440551758, + 'FR_Wheel_Angle': -30.573240280151367, + 'Location': array([ 7.86700726e+00, -3.46000671e-01, 1.88724510e-03]), + 'Rotation': array([ -0.02117359, -11.7859354 , 0.10308683]), + 'Velocity': array([ 6.46879435e-01, -4.37655330e-01, -4.23798541e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 534.5440063476562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 9.30712891e+00, -9.24863510e+01, -3.05175781e-05]), + 'frame': 347, + 'frame_number': 347, + 'framesequence': 345, + 'gaze_dir': array([ 0.98058069, -0.17180425, -0.09457721]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17180425, -0.09457721]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17180425, -0.09457721]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.460328478366137, + 'timestamp_carla': 10460, + 'timestamp_device': 9928, + 'timestamp_stream': 10.460328478366137, + 'transform': [array([ 6.35490119e-01, -9.04345132e-09, 1.82033540e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50009036, -0.18757406, -9.58023071]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.463314056396484, + 'FR_Wheel_Angle': -30.57454490661621, + 'Location': array([ 7.97791290e+00, -4.02803183e-01, 1.91364286e-03]), + 'Rotation': array([ -0.02126921, -13.34764481, 0.10434102]), + 'Velocity': array([ 6.21738017e-01, -4.46270555e-01, 1.49774551e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 532.7305908203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.55432129e+00, -9.15253906e+01, 3.05175781e-05]), + 'frame': 348, + 'frame_number': 348, + 'framesequence': 346, + 'gaze_dir': array([ 0.98058069, -0.1702691 , -0.09731382]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1702691 , -0.09731382]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1702691 , -0.09731382]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.475603479892015, + 'timestamp_carla': 10475, + 'timestamp_device': 9944, + 'timestamp_stream': 10.475603479892015, + 'transform': [array([ 6.50099397e-01, -7.87464582e-09, 1.80587766e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50484794, -0.2052063 , -9.39248848]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.47398376464844, + 'FR_Wheel_Angle': -30.577484130859375, + 'Location': array([ 8.08677673e+00, -4.61749762e-01, 1.89014431e-03]), + 'Rotation': array([ -0.02139215, -14.897542 , 0.10605991]), + 'Velocity': array([ 5.97202420e-01, -4.53970224e-01, 4.35972215e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 530.5331420898438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.38562012, -90.33340454, 0. ]), + 'frame': 349, + 'frame_number': 349, + 'framesequence': 347, + 'gaze_dir': array([ 0.98058069, -0.16898963, -0.0995191 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16898963, -0.0995191 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16898963, -0.0995191 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.488773878663778, + 'timestamp_carla': 10488, + 'timestamp_device': 9957, + 'timestamp_stream': 10.488773878663778, + 'transform': [array([ 6.62609935e-01, -4.41477832e-09, 1.80809014e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.53347331, -0.22897272, -9.25236988]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.48160171508789, + 'FR_Wheel_Angle': -30.581586837768555, + 'Location': array([ 8.18529701e+00, -5.17172277e-01, 1.87557214e-03]), + 'Rotation': array([ -0.02249181, -16.30744934, 0.11566126]), + 'Velocity': array([ 0.57693833, -0.46175292, -0.00107286]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 528.7734985351562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.85479736e+00, -8.93572464e+01, -3.05175781e-05]), + 'frame': 350, + 'frame_number': 350, + 'framesequence': 348, + 'gaze_dir': array([ 0.98058069, -0.16747795, -0.10204256]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16747795, -0.10204256]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16747795, -0.10204256]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.501716379076242, + 'timestamp_carla': 10501, + 'timestamp_device': 9972, + 'timestamp_stream': 10.501716379076242, + 'transform': [array([ 6.74826443e-01, -2.97588487e-09, 1.81091309e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.59360653, -0.27547789, -8.07744026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -36.380741119384766, + 'FR_Wheel_Angle': -27.10396385192871, + 'Location': array([ 8.28363705e+00, -5.73927879e-01, 1.92703248e-03]), + 'Rotation': array([ -0.02246449, -17.66416168, 0.11737742]), + 'Velocity': array([ 5.79564631e-01, -4.44540590e-01, 3.01923748e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 526.7774658203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.8454895 , -88.22361755, 0. ]), + 'frame': 351, + 'frame_number': 351, + 'framesequence': 349, + 'gaze_dir': array([ 0.98058057, -0.16624139, -0.10404491]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16624139, -0.10404491]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16624139, -0.10404491]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.515709578990936, + 'timestamp_carla': 10515, + 'timestamp_device': 9984, + 'timestamp_stream': 10.515709578990936, + 'transform': [array([ 6.87948227e-01, -2.69649258e-09, 1.80728908e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52776927, -0.24866471, -7.16696072]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.13467025756836, + 'FR_Wheel_Angle': -25.191022872924805, + 'Location': array([ 8.38492870e+00, -6.28785968e-01, 1.88907620e-03]), + 'Rotation': array([ -0.02078426, -18.79678917, 0.11676424]), + 'Velocity': array([ 6.04587138e-01, -4.36625123e-01, 7.89117767e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 525.2044677734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.2857666 , -87.31074524, 0. ]), + 'frame': 352, + 'frame_number': 352, + 'framesequence': 350, + 'gaze_dir': array([ 0.98058057, -0.16466203, -0.10652678]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16466203, -0.10652678]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16466203, -0.10652678]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.531099878251553, + 'timestamp_carla': 10531, + 'timestamp_device': 9999, + 'timestamp_stream': 10.531099878251553, + 'transform': [array([7.02278793e-01, 1.71798320e-09, 1.79447175e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52923739, -0.26055863, -7.42334986]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.21834182739258, + 'FR_Wheel_Angle': -25.45351791381836, + 'Location': array([ 8.49975014e+00, -6.96299791e-01, 1.88125612e-03]), + 'Rotation': array([-1.92884523e-02, -2.01398258e+01, 1.11364655e-01]), + 'Velocity': array([ 5.80157280e-01, -4.54423815e-01, -1.62830343e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 523.2666015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 4.40374756, -86.16215515, 0. ]), + 'frame': 353, + 'frame_number': 353, + 'framesequence': 351, + 'gaze_dir': array([ 0.98058069, -0.16315459, -0.10882153]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16315459, -0.10882153]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16315459, -0.10882153]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.54486007988453, + 'timestamp_carla': 10544, + 'timestamp_device': 10013, + 'timestamp_stream': 10.54486007988453, + 'transform': [array([7.15008140e-01, 4.13476275e-09, 1.79550168e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52797759, -0.26724884, -7.37726402]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.3985710144043, + 'FR_Wheel_Angle': -25.699281692504883, + 'Location': array([ 8.59765244e+00, -7.54570961e-01, 1.88426964e-03]), + 'Rotation': array([-1.96504537e-02, -2.12679348e+01, 1.20307036e-01]), + 'Velocity': array([ 5.66912591e-01, -4.62163031e-01, 6.13498705e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 521.4859619140625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 3.82119751e+00, -8.50828323e+01, -3.05175781e-05]), + 'frame': 354, + 'frame_number': 354, + 'framesequence': 352, + 'gaze_dir': array([ 0.98058057, -0.16172621, -0.11093321]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16172621, -0.11093321]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16172621, -0.11093321]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.557799078524113, + 'timestamp_carla': 10557, + 'timestamp_device': 10026, + 'timestamp_stream': 10.557799078524113, + 'transform': [array([7.27851450e-01, 3.08702042e-09, 1.79977412e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52376103, -0.28223071, -7.1686306 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.165401458740234, + 'FR_Wheel_Angle': -25.574445724487305, + 'Location': array([ 8.70750332e+00, -8.24338198e-01, 1.85752870e-03]), + 'Rotation': array([-1.90084148e-02, -2.25699940e+01, 1.15219600e-01]), + 'Velocity': array([ 5.43534338e-01, -4.63128448e-01, -8.60404980e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 519.860107421875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 3.25299072, -84.07501984, 0. ]), + 'frame': 355, + 'frame_number': 355, + 'framesequence': 353, + 'gaze_dir': array([ 0.98058057, -0.16027039, -0.1130263 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16027039, -0.1130263 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16027039, -0.1130263 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.571015376597643, + 'timestamp_carla': 10571, + 'timestamp_device': 10039, + 'timestamp_stream': 10.571015376597643, + 'transform': [array([7.40870416e-01, 3.94384392e-09, 1.80202478e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.54591632, -0.30504826, -7.0881424 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.19817352294922, + 'FR_Wheel_Angle': -25.573680877685547, + 'Location': array([ 8.80099201e+00, -8.84853363e-01, 1.87046034e-03]), + 'Rotation': array([-1.97733957e-02, -2.36778965e+01, 1.24732159e-01]), + 'Velocity': array([ 5.27766347e-01, -4.68187898e-01, 9.54151110e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 518.2591552734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.72421265, -83.06161499, 0. ]), + 'frame': 356, + 'frame_number': 356, + 'framesequence': 354, + 'gaze_dir': array([ 0.98058069, -0.15890257, -0.11494137]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15890257, -0.11494137]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15890257, -0.11494137]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.583529777824879, + 'timestamp_carla': 10583, + 'timestamp_device': 10051, + 'timestamp_stream': 10.583529777824879, + 'transform': [array([7.53110588e-01, 4.37401004e-10, 1.80728908e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5362519 , -0.31724653, -6.9320159 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.206275939941406, + 'FR_Wheel_Angle': -25.577009201049805, + 'Location': array([ 8.90504837e+00, -9.56305683e-01, 1.85806246e-03]), + 'Rotation': array([-1.91996600e-02, -2.49378147e+01, 1.20139167e-01]), + 'Velocity': array([ 5.05448997e-01, -4.69105661e-01, -1.89013474e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 516.802734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.3767395 , -82.12129211, 0. ]), + 'frame': 357, + 'frame_number': 357, + 'framesequence': 355, + 'gaze_dir': array([ 0.98058069, -0.15727788, -0.11715466]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15727788, -0.11715466]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15727788, -0.11715466]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.596740879118443, + 'timestamp_carla': 10596, + 'timestamp_device': 10065, + 'timestamp_stream': 10.596740879118443, + 'transform': [array([ 7.65941381e-01, -4.52191884e-09, 1.80824276e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55545676, -0.34060922, -6.83604383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.21187210083008, + 'FR_Wheel_Angle': -25.580087661743164, + 'Location': array([ 8.99415588e+00, -1.01829529e+00, 1.86634017e-03]), + 'Rotation': array([-2.00192835e-02, -2.60160923e+01, 1.29548490e-01]), + 'Velocity': array([ 4.89463598e-01, -4.72074926e-01, 1.60574913e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 515.1300048828125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.70635986e+00, -8.10185623e+01, 3.05175781e-05]), + 'frame': 358, + 'frame_number': 358, + 'framesequence': 356, + 'gaze_dir': array([ 0.98058069, -0.15586074, -0.11903354]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15586074, -0.11903354]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15586074, -0.11903354]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.609198078513145, + 'timestamp_carla': 10609, + 'timestamp_device': 10077, + 'timestamp_stream': 10.609198078513145, + 'transform': [array([ 7.77960181e-01, -3.07370551e-09, 1.81262963e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5799045 , -0.37007719, -6.7255497 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.218284606933594, + 'FR_Wheel_Angle': -25.58346939086914, + 'Location': array([ 9.08006668e+00, -1.07985651e+00, 1.86862878e-03]), + 'Rotation': array([-2.06613205e-02, -2.70649261e+01, 1.36633694e-01]), + 'Velocity': array([ 4.72668290e-01, -4.73421514e-01, -7.82728166e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 513.7179565429688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.39044189, -80.06847382, 0. ]), + 'frame': 359, + 'frame_number': 359, + 'framesequence': 357, + 'gaze_dir': array([ 0.98058069, -0.15430021, -0.12104953]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15430021, -0.12104953]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15430021, -0.12104953]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.621873278170824, + 'timestamp_carla': 10621, + 'timestamp_device': 10090, + 'timestamp_stream': 10.621873278170824, + 'transform': [array([7.90111005e-01, 5.49157442e-10, 1.81514735e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.58149493, -0.38832423, -6.59114313]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.226139068603516, + 'FR_Wheel_Angle': -25.58816146850586, + 'Location': array([ 9.16683197e+00, -1.14449227e+00, 1.85779494e-03]), + 'Rotation': array([-2.05725282e-02, -2.81392708e+01, 1.36615962e-01]), + 'Velocity': array([ 4.54124093e-01, -4.72682059e-01, 2.13127132e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 512.2120361328125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 0.8868103 , -79.03443909, 0. ]), + 'frame': 360, + 'frame_number': 360, + 'framesequence': 358, + 'gaze_dir': array([ 0.98058069, -0.15283655, -0.12289239]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15283655, -0.12289239]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15283655, -0.12289239]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.634079679846764, + 'timestamp_carla': 10634, + 'timestamp_device': 10102, + 'timestamp_stream': 10.634079679846764, + 'transform': [array([8.01740944e-01, 4.65631045e-09, 1.81919092e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.56364661, -0.39446241, -6.44060326]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.23495864868164, + 'FR_Wheel_Angle': -25.593093872070312, + 'Location': array([ 9.25555325e+00, -1.21360254e+00, 1.86721690e-03]), + 'Rotation': array([-1.98963396e-02, -2.92571106e+01, 1.31118074e-01]), + 'Velocity': array([ 4.34395015e-01, -4.70441848e-01, 8.33606682e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 510.84283447265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.51269531e-01, -7.80754700e+01, 3.05175781e-05]), + 'frame': 361, + 'frame_number': 361, + 'framesequence': 359, + 'gaze_dir': array([ 0.98058069, -0.15122601, -0.1248689 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15122601, -0.1248689 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15122601, -0.1248689 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.647509779781103, + 'timestamp_carla': 10647, + 'timestamp_device': 10115, + 'timestamp_stream': 10.647509779781103, + 'transform': [array([8.14455450e-01, 9.39676248e-09, 1.81625364e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5714761 , -0.41213346, -6.3393693 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.24296188354492, + 'FR_Wheel_Angle': -25.59381103515625, + 'Location': array([ 9.33610344e+00, -1.27751696e+00, 1.87187060e-03]), + 'Rotation': array([-2.04427559e-02, -3.02750034e+01, 1.38312638e-01]), + 'Velocity': array([ 4.19143051e-01, -4.70647156e-01, 8.50200668e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 509.38275146484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.06689453e-02, -7.70319290e+01, 3.05175781e-05]), + 'frame': 362, + 'frame_number': 362, + 'framesequence': 360, + 'gaze_dir': array([ 0.98058069, -0.14959005, -0.12682416]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14959005, -0.12682416]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14959005, -0.12682416]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.660284079611301, + 'timestamp_carla': 10660, + 'timestamp_device': 10128, + 'timestamp_stream': 10.660284079611301, + 'transform': [array([8.26474845e-01, 8.41420622e-09, 1.81724539e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.58389789, -0.43938723, -5.80179548]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -30.062467575073242, + 'FR_Wheel_Angle': -23.094642639160156, + 'Location': array([ 9.42111588e+00, -1.34738696e+00, 1.85558165e-03]), + 'Rotation': array([-2.02036984e-02, -3.13509998e+01, 1.36911303e-01]), + 'Velocity': array([ 4.11849380e-01, -4.61508393e-01, 4.10046574e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 507.9454345703125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -0.29528809, -75.98358917, 0. ]), + 'frame': 363, + 'frame_number': 363, + 'framesequence': 361, + 'gaze_dir': array([ 0.98058069, -0.14779991, -0.12890592]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14779991, -0.12890592]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14779991, -0.12890592]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.673709478229284, + 'timestamp_carla': 10673, + 'timestamp_device': 10142, + 'timestamp_stream': 10.673709478229284, + 'transform': [array([8.39028537e-01, 1.38112268e-08, 1.81446073e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55972731, -0.42673272, -4.45894957]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.124170303344727, + 'FR_Wheel_Angle': -19.237152099609375, + 'Location': array([ 9.50852013e+00, -1.41529799e+00, 1.85756513e-03]), + 'Rotation': array([-1.86464153e-02, -3.22155685e+01, 1.34013221e-01]), + 'Velocity': array([ 4.48976249e-01, -4.47129995e-01, 2.12702740e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 506.4246520996094, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -0.81546021, -74.84952545, 0. ]), + 'frame': 364, + 'frame_number': 364, + 'framesequence': 362, + 'gaze_dir': array([ 0.98058069, -0.14611162, -0.13081644]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14611162, -0.13081644]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14611162, -0.13081644]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.687133979052305, + 'timestamp_carla': 10687, + 'timestamp_device': 10155, + 'timestamp_stream': 10.687133979052305, + 'transform': [array([8.51503789e-01, 1.63723612e-08, 1.81213371e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.53575754, -0.41419894, -4.96428728]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.26246452331543, + 'FR_Wheel_Angle': -20.29668426513672, + 'Location': array([ 9.60335827e+00, -1.49177563e+00, 1.84520544e-03]), + 'Rotation': array([-1.68159250e-02, -3.31323166e+01, 1.28262207e-01]), + 'Velocity': array([ 4.37296897e-01, -4.69327688e-01, 2.04815864e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 505.0362243652344, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-1.13214111e+00, -7.37916718e+01, 3.05175781e-05]), + 'frame': 365, + 'frame_number': 365, + 'framesequence': 363, + 'gaze_dir': array([ 0.98058069, -0.14453134, -0.13256033]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14453134, -0.13256033]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14453134, -0.13256033]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.699642676860094, + 'timestamp_carla': 10699, + 'timestamp_device': 10167, + 'timestamp_stream': 10.699642676860094, + 'transform': [array([8.63060832e-01, 1.44864174e-08, 1.81480404e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52750152, -0.41731811, -4.84214258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.05854606628418, + 'FR_Wheel_Angle': -20.36088752746582, + 'Location': array([ 9.68989372e+00, -1.56190848e+00, 1.84222974e-03]), + 'Rotation': array([-1.64197739e-02, -3.39644661e+01, 1.30507305e-01]), + 'Velocity': array([ 4.25395370e-01, -4.67430830e-01, 1.11641879e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 503.7757873535156, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-1.31179810e+00, -7.28114014e+01, -3.05175781e-05]), + 'frame': 366, + 'frame_number': 366, + 'framesequence': 364, + 'gaze_dir': array([ 0.98058069, -0.14266139, -0.1345707 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14266139, -0.1345707 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14266139, -0.1345707 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.71336917951703, + 'timestamp_carla': 10713, + 'timestamp_device': 10181, + 'timestamp_stream': 10.71336917951703, + 'transform': [array([8.75666559e-01, 2.26727739e-08, 1.81041716e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5618695 , -0.452961 , -4.75503159]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.836868286132812, + 'FR_Wheel_Angle': -20.190256118774414, + 'Location': array([ 9.76749039e+00, -1.62533152e+00, 1.84451824e-03]), + 'Rotation': array([-1.71232838e-02, -3.47168045e+01, 1.43054128e-01]), + 'Velocity': array([ 4.15578067e-01, -4.67717081e-01, -2.76937470e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 502.3312072753906, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -1.79202271, -71.6632843 , 0. ]), + 'frame': 367, + 'frame_number': 367, + 'framesequence': 365, + 'gaze_dir': array([ 0.98058069, -0.14090003, -0.13641381]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14090003, -0.13641381]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14090003, -0.13641381]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.726178776472807, + 'timestamp_carla': 10726, + 'timestamp_device': 10194, + 'timestamp_stream': 10.726178776472807, + 'transform': [array([8.88379872e-01, 2.58392809e-08, 1.81522360e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57051533, -0.47358999, -4.69632387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.92396354675293, + 'FR_Wheel_Angle': -20.23171615600586, + 'Location': array([ 9.84616280e+00, -1.69161177e+00, 1.84867601e-03]), + 'Rotation': array([-1.71232838e-02, -3.54884453e+01, 1.45267919e-01]), + 'Velocity': array([ 4.02669281e-01, -4.66665179e-01, 4.43844794e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 501.0129699707031, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -2.0239563 , -70.59275055, 0. ]), + 'frame': 368, + 'frame_number': 368, + 'framesequence': 366, + 'gaze_dir': array([ 0.98058069, -0.13911474, -0.138234 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13911474, -0.138234 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13911474, -0.138234 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.73946537822485, + 'timestamp_carla': 10739, + 'timestamp_device': 10207, + 'timestamp_stream': 10.73946537822485, + 'transform': [array([9.01465356e-01, 2.45028051e-08, 1.81674957e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.54115111, -0.46378806, -4.60892916]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.944307327270508, + 'FR_Wheel_Angle': -20.238332748413086, + 'Location': array([ 9.93199825e+00, -1.76729286e+00, 1.86679547e-03]), + 'Rotation': array([-1.63924526e-02, -3.63492699e+01, 1.37388840e-01]), + 'Velocity': array([ 3.87431175e-01, -4.63209212e-01, 1.77345268e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 499.7195129394531, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.21762085e+00, -6.95183563e+01, -6.10351562e-05]), + 'frame': 369, + 'frame_number': 369, + 'framesequence': 367, + 'gaze_dir': array([ 0.98058069, -0.13730606, -0.1400307 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13730606, -0.1400307 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13730606, -0.1400307 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.752133578062057, + 'timestamp_carla': 10752, + 'timestamp_device': 10220, + 'timestamp_stream': 10.752133578062057, + 'transform': [array([9.13851738e-01, 3.26844933e-08, 1.82090758e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.54392004, -0.47910589, -4.53609276]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.94856071472168, + 'FR_Wheel_Angle': -20.24081039428711, + 'Location': array([ 1.00098553e+01, -1.83637047e+00, 1.85210863e-03]), + 'Rotation': array([-1.64812449e-02, -3.71296539e+01, 1.39303669e-01]), + 'Velocity': array([ 3.74859184e-01, -4.61118013e-01, 6.25133471e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 498.4486389160156, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.34820557e+00, -6.84400253e+01, -3.05175781e-05]), + 'frame': 370, + 'frame_number': 370, + 'framesequence': 368, + 'gaze_dir': array([ 0.98058057, -0.13561581, -0.14166825]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.13561581, -0.14166825]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.13561581, -0.14166825]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.764488779008389, + 'timestamp_carla': 10764, + 'timestamp_device': 10232, + 'timestamp_stream': 10.764488779008389, + 'transform': [array([9.25850570e-01, 3.51059306e-08, 1.82556151e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.56743681, -0.50888979, -4.49232244]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.95107650756836, + 'FR_Wheel_Angle': -20.242815017700195, + 'Location': array([ 1.00800219e+01, -1.89852655e+00, 1.85157428e-03]), + 'Rotation': array([-1.73691697e-02, -3.78290787e+01, 1.52277291e-01]), + 'Velocity': array([ 3.65479082e-01, -4.61337149e-01, -1.51062004e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 497.29638671875, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -2.41461182, -67.44126129, 0. ]), + 'frame': 371, + 'frame_number': 371, + 'framesequence': 369, + 'gaze_dir': array([ 0.98058069, -0.13361926, -0.14355291]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13361926, -0.14355291]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13361926, -0.14355291]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.777740079909563, + 'timestamp_carla': 10777, + 'timestamp_device': 10246, + 'timestamp_stream': 10.777740079909563, + 'transform': [array([9.38631594e-01, 3.79930256e-08, 1.82476034e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57974935, -0.53478003, -4.4183526 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.955446243286133, + 'FR_Wheel_Angle': -20.24517822265625, + 'Location': array([ 1.01507807e+01, -1.96290982e+00, 1.84741593e-03]), + 'Rotation': array([-1.75809059e-02, -3.85436783e+01, 1.54945686e-01]), + 'Velocity': array([ 3.53437006e-01, -4.58367407e-01, 2.68549920e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 495.97686767578125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -2.70916748, -66.27207184, 0. ]), + 'frame': 372, + 'frame_number': 372, + 'framesequence': 370, + 'gaze_dir': array([ 0.98058069, -0.13188703, -0.14514598]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13188703, -0.14514598]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13188703, -0.14514598]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.79015427827835, + 'timestamp_carla': 10790, + 'timestamp_device': 10258, + 'timestamp_stream': 10.79015427827835, + 'transform': [array([9.50528026e-01, 3.95203905e-08, 1.82804104e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.58482784, -0.55178028, -4.35656261]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.959077835083008, + 'FR_Wheel_Angle': -20.24770164489746, + 'Location': array([ 1.02186012e+01, -2.02533245e+00, 1.84478355e-03]), + 'Rotation': array([-1.78267919e-02, -3.92306366e+01, 1.59709126e-01]), + 'Velocity': array([ 3.42867553e-01, -4.56190556e-01, 3.48043424e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 494.8661193847656, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -2.68878174, -65.26643372, 0. ]), + 'frame': 373, + 'frame_number': 373, + 'framesequence': 371, + 'gaze_dir': array([ 0.98058069, -0.12984213, -0.14697812]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12984213, -0.14697812]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12984213, -0.14697812]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.804139576852322, + 'timestamp_carla': 10804, + 'timestamp_device': 10272, + 'timestamp_stream': 10.804139576852322, + 'transform': [array([9.63839531e-01, 4.47078676e-08, 1.82197569e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57736802, -0.5603444 , -4.27598143]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.96379280090332, + 'FR_Wheel_Angle': -20.25002670288086, + 'Location': array([ 1.02876673e+01, -2.09099507e+00, 1.83089776e-03]), + 'Rotation': array([-1.74852833e-02, -3.99421234e+01, 1.56223908e-01]), + 'Velocity': array([ 3.30718309e-01, -4.51934010e-01, 4.39858413e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 493.5956115722656, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.93801880e+00, -6.40895157e+01, 3.05175781e-05]), + 'frame': 374, + 'frame_number': 374, + 'framesequence': 372, + 'gaze_dir': array([ 0.98058069, -0.12806909, -0.14852561]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12806909, -0.14852561]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12806909, -0.14852561]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.816446878015995, + 'timestamp_carla': 10816, + 'timestamp_device': 10284, + 'timestamp_stream': 10.816446878015995, + 'transform': [array([9.75481451e-01, 4.51269422e-08, 1.82582845e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.58714586, -0.5828234 , -4.02883768]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -23.717639923095703, + 'FR_Wheel_Angle': -18.967092514038086, + 'Location': array([ 1.03536530e+01, -2.15413117e+00, 1.82452716e-03]), + 'Rotation': array([-1.75467543e-02, -4.06173058e+01, 1.58492923e-01]), + 'Velocity': array([ 3.25245798e-01, -4.46545780e-01, 2.75516504e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 492.5261535644531, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.81753540e+00, -6.30773811e+01, -3.05175781e-05]), + 'frame': 375, + 'frame_number': 375, + 'framesequence': 373, + 'gaze_dir': array([ 0.98058069, -0.12597726, -0.15030396]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12597726, -0.15030396]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12597726, -0.15030396]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.829592879861593, + 'timestamp_carla': 10829, + 'timestamp_device': 10298, + 'timestamp_stream': 10.829592879861593, + 'transform': [array([9.87840176e-01, 5.27079287e-08, 1.82460784e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.60286057, -0.60490596, -2.70497346]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.289543151855469, + 'FR_Wheel_Angle': -12.942172050476074, + 'Location': array([ 1.04208860e+01, -2.21523929e+00, 1.83799304e-03]), + 'Rotation': array([-1.68159250e-02, -4.11486893e+01, 1.58135474e-01]), + 'Velocity': array([ 3.59760672e-01, -4.31094527e-01, 1.28250118e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 491.3046569824219, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-3.03680420e+00, -6.18932152e+01, -3.05175781e-05]), + 'frame': 376, + 'frame_number': 376, + 'framesequence': 374, + 'gaze_dir': array([ 0.98058069, -0.12416457, -0.15180483]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12416457, -0.15180483]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12416457, -0.15180483]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.84218817949295, + 'timestamp_carla': 10842, + 'timestamp_device': 10310, + 'timestamp_stream': 10.84218817949295, + 'transform': [array([9.99610603e-01, 5.93948428e-08, 1.82620995e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55596834, -0.55167586, -3.24171519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.55988311767578, + 'FR_Wheel_Angle': -15.048985481262207, + 'Location': array([ 1.04936199e+01, -2.28131413e+00, 1.82086509e-03]), + 'Rotation': array([-1.48351705e-02, -4.16255989e+01, 1.58126295e-01]), + 'Velocity': array([ 3.69188160e-01, -4.65535909e-01, 7.45391808e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 490.2775573730469, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -2.96386719, -60.87511063, 0. ]), + 'frame': 377, + 'frame_number': 377, + 'framesequence': 375, + 'gaze_dir': array([ 0.98058057, -0.1220272 , -0.15352818]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.1220272 , -0.15352818]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.1220272 , -0.15352818]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.85623037815094, + 'timestamp_carla': 10856, + 'timestamp_device': 10324, + 'timestamp_stream': 10.85623037815094, + 'transform': [array([1.01265037e+00, 6.24914875e-08, 1.81915273e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57067508, -0.57490766, -2.93695712]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.205341339111328, + 'FR_Wheel_Angle': -14.084733009338379, + 'Location': array([ 1.05641747e+01, -2.34656525e+00, 1.81579159e-03]), + 'Rotation': array([-1.43433968e-02, -4.21204987e+01, 1.57860085e-01]), + 'Velocity': array([ 3.61760288e-01, -4.53850418e-01, 4.96864322e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 489.10400390625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-3.11584473e+00, -5.96840057e+01, 3.05175781e-05]), + 'frame': 378, + 'frame_number': 378, + 'framesequence': 376, + 'gaze_dir': array([ 0.98058069, -0.12002102, -0.1551016 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12002102, -0.1551016 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12002102, -0.1551016 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.868816878646612, + 'timestamp_carla': 10868, + 'timestamp_device': 10337, + 'timestamp_stream': 10.868816878646612, + 'transform': [array([1.02426958e+00, 6.64496014e-08, 1.82136532e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.54989618, -0.56227899, -2.98434877]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.583415985107422, + 'FR_Wheel_Angle': -14.272906303405762, + 'Location': array([ 1.06383038e+01, -2.41723347e+00, 1.83101220e-03]), + 'Rotation': array([-1.35237742e-02, -4.26428413e+01, 1.49728224e-01]), + 'Velocity': array([ 3.53566080e-01, -4.55252647e-01, 7.28321029e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 488.0362243652344, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-3.02056885e+00, -5.85746155e+01, -3.05175781e-05]), + 'frame': 379, + 'frame_number': 379, + 'framesequence': 377, + 'gaze_dir': array([ 0.98058057, -0.11768117, -0.15688431]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11768117, -0.15688431]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11768117, -0.15688431]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.884105280041695, + 'timestamp_carla': 10884, + 'timestamp_device': 10352, + 'timestamp_stream': 10.884105280041695, + 'transform': [array([1.03829026e+00, 7.07243615e-08, 1.80591585e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.56087691, -0.57650983, -2.99096394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.618900299072266, + 'FR_Wheel_Angle': -14.325190544128418, + 'Location': array([ 1.07020721e+01, -2.47643995e+00, 1.81941548e-03]), + 'Rotation': array([-1.41931325e-02, -4.30838089e+01, 1.66557014e-01]), + 'Velocity': array([ 0.34967509, -0.4577238 , 0.00050637]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 486.8335266113281, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -3.22070312, -57.29115295, 0. ]), + 'frame': 380, + 'frame_number': 380, + 'framesequence': 378, + 'gaze_dir': array([ 0.98058069, -0.11531471, -0.15863186]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11531471, -0.15863186]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11531471, -0.15863186]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.898739278316498, + 'timestamp_carla': 10898, + 'timestamp_device': 10367, + 'timestamp_stream': 10.898739278316498, + 'transform': [array([1.05279958e+00, 6.84658872e-08, 1.81056967e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55969948, -0.58774489, -2.94179416]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.643430709838867, + 'FR_Wheel_Angle': -14.352416038513184, + 'Location': array([ 1.07745876e+01, -2.54741693e+00, 1.83536089e-03]), + 'Rotation': array([-1.38243018e-02, -4.36011353e+01, 1.59886688e-01]), + 'Velocity': array([ 3.39700967e-01, -4.53511387e-01, -9.30786118e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 485.6575622558594, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -3.14935303, -56.00347137, 0. ]), + 'frame': 381, + 'frame_number': 381, + 'framesequence': 379, + 'gaze_dir': array([ 0.98058069, -0.11308263, -0.16023067]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11308263, -0.16023067]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11308263, -0.16023067]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.912839077413082, + 'timestamp_carla': 10912, + 'timestamp_device': 10381, + 'timestamp_stream': 10.912839077413082, + 'transform': [array([1.06666458e+00, 6.88058108e-08, 1.81713095e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57067305, -0.60843223, -2.91363454]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.646129608154297, + 'FR_Wheel_Angle': -14.353280067443848, + 'Location': array([ 1.08395529e+01, -2.61028743e+00, 1.84638542e-03]), + 'Rotation': array([-1.40428683e-02, -4.40604057e+01, 1.65152565e-01]), + 'Velocity': array([ 3.32652777e-01, -4.51963097e-01, -1.94511405e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 484.589599609375, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -2.9079895 , -54.79867172, 0. ]), + 'frame': 382, + 'frame_number': 382, + 'framesequence': 380, + 'gaze_dir': array([ 0.98058069, -0.11082841, -0.16179806]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11082841, -0.16179806]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11082841, -0.16179806]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.9266655780375, + 'timestamp_carla': 10926, + 'timestamp_device': 10395, + 'timestamp_stream': 10.9266655780375, + 'transform': [array([1.08015525e+00, 7.78070728e-08, 1.82350155e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55367029, -0.60061997, -2.87763333]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.648202896118164, + 'FR_Wheel_Angle': -14.354779243469238, + 'Location': array([ 1.09087877e+01, -2.67937255e+00, 1.83448370e-03]), + 'Rotation': array([-1.37901511e-02, -4.45578346e+01, 1.61832407e-01]), + 'Velocity': array([ 3.24633628e-01, -4.49136943e-01, -1.42393110e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 483.54742431640625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.70202637e+00, -5.35907974e+01, 3.05175781e-05]), + 'frame': 383, + 'frame_number': 383, + 'framesequence': 381, + 'gaze_dir': array([ 0.98058057, -0.10855246, -0.16333373]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.10855246, -0.16333373]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.10855246, -0.16333373]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.940706979483366, + 'timestamp_carla': 10940, + 'timestamp_device': 10409, + 'timestamp_stream': 10.940706979483366, + 'transform': [array([1.09375238e+00, 7.77232430e-08, 1.82693475e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52106887, -0.57837266, -2.82561874]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.650230407714844, + 'FR_Wheel_Angle': -14.356285095214844, + 'Location': array([ 1.09816761e+01, -2.75445366e+00, 1.81754655e-03]), + 'Rotation': array([-1.31207928e-02, -4.50913200e+01, 1.49305403e-01]), + 'Velocity': array([ 3.14603657e-01, -4.43822801e-01, 1.72996515e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 482.5308532714844, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -2.5045166 , -52.37992096, 0. ]), + 'frame': 384, + 'frame_number': 384, + 'framesequence': 382, + 'gaze_dir': array([ 0.98058069, -0.10609028, -0.16494364]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10609028, -0.16494364]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10609028, -0.16494364]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.955976080149412, + 'timestamp_carla': 10955, + 'timestamp_device': 10424, + 'timestamp_stream': 10.955976080149412, + 'transform': [array([1.10842395e+00, 8.28408702e-08, 1.82094565e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5372985 , -0.60370111, -2.80659509]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.65241241455078, + 'FR_Wheel_Angle': -14.358757972717285, + 'Location': array([ 1.10448589e+01, -2.81818509e+00, 1.80213538e-03]), + 'Rotation': array([-1.34896226e-02, -4.55468369e+01, 1.58377811e-01]), + 'Velocity': array([ 0.3088308 , -0.44342566, -0.00047194]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 481.4690856933594, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.34729004e+00, -5.10791931e+01, -3.05175781e-05]), + 'frame': 385, + 'frame_number': 385, + 'framesequence': 383, + 'gaze_dir': array([ 0.98058069, -0.10343775, -0.16661987]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10343775, -0.16661987]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10343775, -0.16661987]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.971792377531528, + 'timestamp_carla': 10971, + 'timestamp_device': 10440, + 'timestamp_stream': 10.971792377531528, + 'transform': [array([1.12350130e+00, 8.38932337e-08, 1.81148527e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52326703, -0.59843129, -2.77118444]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.65330696105957, + 'FR_Wheel_Angle': -14.359845161437988, + 'Location': array([ 1.11121912e+01, -2.88913870e+00, 1.80068589e-03]), + 'Rotation': array([-1.33666797e-02, -4.60449028e+01, 1.56465068e-01]), + 'Velocity': array([ 3.01081955e-01, -4.40405756e-01, -3.52001189e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 480.3670349121094, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.12768555e+00, -4.96880951e+01, -3.05175781e-05]), + 'frame': 386, + 'frame_number': 386, + 'framesequence': 384, + 'gaze_dir': array([ 0.98058069, -0.10059037, -0.16835417]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10059037, -0.16835417]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10059037, -0.16835417]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 10.988820876926184, + 'timestamp_carla': 10988, + 'timestamp_device': 10457, + 'timestamp_stream': 10.988820876926184, + 'transform': [array([1.13960207e+00, 9.65359774e-08, 1.79298397e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5481708 , -0.63632315, -2.74538374]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.64838218688965, + 'FR_Wheel_Angle': -14.268978118896484, + 'Location': array([ 1.11720953e+01, -2.95131254e+00, 1.81747077e-03]), + 'Rotation': array([-1.37628308e-02, -4.64827309e+01, 1.65017188e-01]), + 'Velocity': array([ 0.29476032, -0.43891796, -0.00075045]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 479.2315673828125, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -1.9052124 , -48.20608521, 0. ]), + 'frame': 387, + 'frame_number': 387, + 'framesequence': 385, + 'gaze_dir': array([ 0.98058069, -0.09805394, -0.16984396]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09805394, -0.16984396]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09805394, -0.16984396]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.003233477473259, + 'timestamp_carla': 11003, + 'timestamp_device': 10472, + 'timestamp_stream': 11.003233477473259, + 'transform': [array([1.15313172e+00, 9.75837011e-08, 1.79889670e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55430174, -0.65451699, -1.58000004]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.376687049865723, + 'FR_Wheel_Angle': -6.857905387878418, + 'Location': array([ 1.12363634e+01, -3.01733303e+00, 1.81258807e-03]), + 'Rotation': array([-1.30934715e-02, -4.68642120e+01, 1.55308321e-01]), + 'Velocity': array([ 0.3173801 , -0.41770077, 0.00057183]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 478.25885009765625, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-1.39550781e+00, -4.68951721e+01, -3.05175781e-05]), + 'frame': 388, + 'frame_number': 388, + 'framesequence': 386, + 'gaze_dir': array([ 0.98058069, -0.09583766, -0.17110433]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09583766, -0.17110433]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09583766, -0.17110433]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.017157778143883, + 'timestamp_carla': 11017, + 'timestamp_device': 10485, + 'timestamp_stream': 11.017157778143883, + 'transform': [array([1.16611731e+00, 1.03777012e-07, 1.80610653e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49084976, -0.56448293, -1.60406733]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.13427734375, + 'FR_Wheel_Angle': -8.524758338928223, + 'Location': array([ 1.13092403e+01, -3.08869815e+00, 1.86259893e-03]), + 'Rotation': array([-1.07985288e-02, -4.71015472e+01, 1.55051947e-01]), + 'Velocity': array([ 3.49756956e-01, -4.54589248e-01, 1.75023073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 477.4424743652344, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-9.67407227e-01, -4.57569656e+01, -3.05175781e-05]), + 'frame': 389, + 'frame_number': 389, + 'framesequence': 387, + 'gaze_dir': array([ 0.98058069, -0.0934329 , -0.17242923]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0934329 , -0.17242923]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0934329 , -0.17242923]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.031372878700495, + 'timestamp_carla': 11031, + 'timestamp_device': 10499, + 'timestamp_stream': 11.031372878700495, + 'transform': [array([1.17928803e+00, 1.03292692e-07, 1.80984498e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52406752, -0.60574412, -1.42224085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.823084831237793, + 'FR_Wheel_Angle': -7.29660701751709, + 'Location': array([ 1.13795824e+01, -3.15830684e+00, 1.83074630e-03]), + 'Rotation': array([-1.04365284e-02, -4.73708916e+01, 1.58317536e-01]), + 'Velocity': array([ 3.45602304e-01, -4.47112679e-01, -9.69553003e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 476.5872497558594, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([ -0.63766479, -44.52892685, 0. ]), + 'frame': 390, + 'frame_number': 390, + 'framesequence': 388, + 'gaze_dir': array([ 0.98058069, -0.09100983, -0.17372034]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09100983, -0.17372034]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09100983, -0.17372034]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.045510079711676, + 'timestamp_carla': 11045, + 'timestamp_device': 10513, + 'timestamp_stream': 11.045510079711676, + 'transform': [array([1.19230258e+00, 1.07590736e-07, 1.81285851e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.54683936, -0.63231671, -1.54699981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.443922996520996, + 'FR_Wheel_Angle': -7.747354030609131, + 'Location': array([ 1.14437485e+01, -3.22077990e+00, 1.83360756e-03]), + 'Rotation': array([-1.02589438e-02, -4.76027946e+01, 1.68429822e-01]), + 'Velocity': array([ 3.44630271e-01, -4.55251157e-01, -5.66148738e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 475.7563781738281, + 'focus_actor_name': 'Road_Road_Town05_165', + 'focus_actor_pt': array([-2.61657715e-01, -4.32985115e+01, -3.05175781e-05]), + 'frame': 391, + 'frame_number': 391, + 'framesequence': 389, + 'gaze_dir': array([ 0.98058069, -0.08839381, -0.17506593]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08839381, -0.17506593]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08839381, -0.17506593]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.060578476637602, + 'timestamp_carla': 11060, + 'timestamp_device': 10528, + 'timestamp_stream': 11.060578476637602, + 'transform': [array([1.20724106e+00, 1.03711756e-07, 1.80648803e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55759197, -0.64949638, -1.5189507 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.352542877197266, + 'FR_Wheel_Angle': -7.701129913330078, + 'Location': array([ 1.15082531e+01, -3.28395653e+00, 1.81892107e-03]), + 'Rotation': array([-1.01018492e-02, -4.78388214e+01, 1.71314254e-01]), + 'Velocity': array([ 3.40232462e-01, -4.52854097e-01, 9.87958920e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 474.8932800292969, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 0.06234741, -41.97763443, 0. ]), + 'frame': 392, + 'frame_number': 392, + 'framesequence': 390, + 'gaze_dir': array([ 0.98058057, -0.08593432, -0.17628622]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08593432, -0.17628622]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08593432, -0.17628622]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.073630478233099, + 'timestamp_carla': 11073, + 'timestamp_device': 10542, + 'timestamp_stream': 11.073630478233099, + 'transform': [array([1.22008038e+00, 1.08242652e-07, 1.81339262e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52775538, -0.62104577, -1.4951005 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.32123851776123, + 'FR_Wheel_Angle': -7.692922592163086, + 'Location': array([ 1.15810633e+01, -3.35822034e+00, 1.81937905e-03]), + 'Rotation': array([-9.64422617e-03, -4.81117058e+01, 1.57863319e-01]), + 'Velocity': array([ 3.34539801e-01, -4.49158132e-01, -2.21352573e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 474.11187744140625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.71722412e-01, -4.07424927e+01, 3.05175781e-05]), + 'frame': 393, + 'frame_number': 393, + 'framesequence': 391, + 'gaze_dir': array([ 0.98058069, -0.08363549, -0.17738843]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08363549, -0.17738843]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08363549, -0.17738843]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.086902879178524, + 'timestamp_carla': 11086, + 'timestamp_device': 10555, + 'timestamp_stream': 11.086902879178524, + 'transform': [array([1.23304033e+00, 1.08889921e-07, 1.81774131e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.53960645, -0.63820225, -1.49561822]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.321215629577637, + 'FR_Wheel_Angle': -7.693119049072266, + 'Location': array([ 1.16435442e+01, -3.41997957e+00, 1.82536826e-03]), + 'Rotation': array([-9.89011303e-03, -4.83413544e+01, 1.68932885e-01]), + 'Velocity': array([ 3.32829326e-01, -4.50703621e-01, 9.41848702e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 473.41033935546875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.16085815e+00, -3.95939102e+01, 3.05175781e-05]), + 'frame': 394, + 'frame_number': 394, + 'framesequence': 392, + 'gaze_dir': array([ 0.98058069, -0.0809653 , -0.17862298]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0809653 , -0.17862298]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0809653 , -0.17862298]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.10152917727828, + 'timestamp_carla': 11101, + 'timestamp_device': 10570, + 'timestamp_stream': 11.10152917727828, + 'transform': [array([1.24721277e+00, 1.10803803e-07, 1.81297294e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.54987544, -0.65684026, -1.48418856]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.321846961975098, + 'FR_Wheel_Angle': -7.693828582763672, + 'Location': array([ 1.17078943e+01, -3.48455644e+00, 1.79248571e-03]), + 'Rotation': array([-9.91743430e-03, -4.85800972e+01, 1.68814525e-01]), + 'Velocity': array([ 3.28181416e-01, -4.48760331e-01, -1.64422992e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 472.62646484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.56900024, -38.26634979, 0. ]), + 'frame': 395, + 'frame_number': 395, + 'framesequence': 393, + 'gaze_dir': array([ 0.98058069, -0.07881602, -0.17958169]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07881602, -0.17958169]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07881602, -0.17958169]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.114006977528334, + 'timestamp_carla': 11114, + 'timestamp_device': 10582, + 'timestamp_stream': 11.114006977528334, + 'transform': [array([1.25922167e+00, 1.13551202e-07, 1.82071677e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55855888, -0.67138141, -1.48151481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.322579383850098, + 'FR_Wheel_Angle': -7.694432258605957, + 'Location': array([ 1.17685423e+01, -3.54535413e+00, 1.79435499e-03]), + 'Rotation': array([-1.01018492e-02, -4.88047333e+01, 1.76174715e-01]), + 'Velocity': array([ 3.25790882e-01, -4.49276865e-01, -3.20224761e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 472.018310546875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.29782104, -37.20261002, 0. ]), + 'frame': 396, + 'frame_number': 396, + 'framesequence': 394, + 'gaze_dir': array([ 0.98058069, -0.07629425, -0.18066746]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07629425, -0.18066746]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07629425, -0.18066746]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.127765979617834, + 'timestamp_carla': 11127, + 'timestamp_device': 10596, + 'timestamp_stream': 11.127765979617834, + 'transform': [array([1.27237403e+00, 1.16005225e-07, 1.82025903e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.51926142, -0.63221526, -1.4607569 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.323201179504395, + 'FR_Wheel_Angle': -7.694725036621094, + 'Location': array([ 1.18398762e+01, -3.62100458e+00, 1.81384827e-03]), + 'Rotation': array([-9.61690582e-03, -4.90781212e+01, 1.58376068e-01]), + 'Velocity': array([ 3.19175839e-01, -4.44313496e-01, 2.98609724e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 471.33343505859375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.72271729e+00, -3.59600372e+01, -3.05175781e-05]), + 'frame': 397, + 'frame_number': 397, + 'framesequence': 395, + 'gaze_dir': array([ 0.98058057, -0.07393927, -0.18164395]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07393927, -0.18164395]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07393927, -0.18164395]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.14108957722783, + 'timestamp_carla': 11141, + 'timestamp_device': 10609, + 'timestamp_stream': 11.14108957722783, + 'transform': [array([1.28502595e+00, 1.26226524e-07, 1.82209013e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50664777, -0.62244052, -1.45094121]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.323758125305176, + 'FR_Wheel_Angle': -7.695143222808838, + 'Location': array([ 1.19059210e+01, -3.69002867e+00, 1.77936361e-03]), + 'Rotation': array([-9.55543388e-03, -4.93287315e+01, 1.55574739e-01]), + 'Velocity': array([ 0.31511626, -0.44264427, 0.00049891]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.7179870605469, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 3.34106445, -34.80455399, 0. ]), + 'frame': 398, + 'frame_number': 398, + 'framesequence': 396, + 'gaze_dir': array([ 0.98058069, -0.07157163, -0.18258983]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07157163, -0.18258983]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07157163, -0.18258983]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.154460679739714, + 'timestamp_carla': 11154, + 'timestamp_device': 10622, + 'timestamp_stream': 11.154460679739714, + 'transform': [array([1.29764140e+00, 1.27264940e-07, 1.82296743e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52336198, -0.64662552, -1.45094562]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.32426643371582, + 'FR_Wheel_Angle': -7.695210933685303, + 'Location': array([ 1.19669466e+01, -3.75287914e+00, 1.80702028e-03]), + 'Rotation': array([-9.76717006e-03, -4.95580406e+01, 1.66115120e-01]), + 'Velocity': array([ 3.13273847e-01, -4.43990380e-01, 2.28080738e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.12384033203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 3.93328857e+00, -3.36475334e+01, -3.05175781e-05]), + 'frame': 399, + 'frame_number': 399, + 'framesequence': 397, + 'gaze_dir': array([ 0.98058069, -0.06919207, -0.18350478]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06919207, -0.18350478]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06919207, -0.18350478]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.16734317690134, + 'timestamp_carla': 11167, + 'timestamp_device': 10635, + 'timestamp_stream': 11.16734317690134, + 'transform': [array([1.30972135e+00, 1.32512938e-07, 1.82590482e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.53335434, -0.66561437, -0.71350074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -3.948901414871216, + 'FR_Wheel_Angle': -3.05328369140625, + 'Location': array([ 1.20356073e+01, -3.82460475e+00, 1.80274795e-03]), + 'Rotation': array([-9.49396286e-03, -4.97831192e+01, 1.56224519e-01]), + 'Velocity': array([ 3.25629145e-01, -4.28790241e-01, -2.15530395e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 469.5502624511719, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 4.54534912, -32.48915482, 0. ]), + 'frame': 400, + 'frame_number': 400, + 'framesequence': 398, + 'gaze_dir': array([ 0.98058069, -0.06643176, -0.18452199]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06643176, -0.18452199]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06643176, -0.18452199]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.181731976568699, + 'timestamp_carla': 11181, + 'timestamp_device': 10650, + 'timestamp_stream': 11.181731976568699, + 'transform': [array([1.32312584e+00, 1.36885504e-07, 1.81922910e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52016133, -0.6373356 , 0.34063378]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 1.3830119371414185, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.21011438e+01, -3.88552094e+00, 1.79984898e-03]), + 'Rotation': array([-8.30550957e-03, -4.97896194e+01, 1.63492247e-01]), + 'Velocity': array([ 3.73810261e-01, -4.35561210e-01, 1.23867983e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.91455078125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.03329468, -31.15082169, 0. ]), + 'frame': 401, + 'frame_number': 401, + 'framesequence': 399, + 'gaze_dir': array([ 0.98058069, -0.06384204, -0.18543392]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06384204, -0.18543392]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06384204, -0.18543392]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.195996679365635, + 'timestamp_carla': 11196, + 'timestamp_device': 10664, + 'timestamp_stream': 11.195996679365635, + 'transform': [array([1.33632779e+00, 1.39400058e-07, 1.81446073e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 5.08122265e-01, -6.12634242e-01, -2.43346062e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.21760798e+01, -3.95811296e+00, 1.79244857e-03]), + 'Rotation': array([-7.02143414e-03, -4.97795753e+01, 1.58256635e-01]), + 'Velocity': array([ 3.77185673e-01, -4.55008954e-01, 2.98743253e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.3447265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.72891235, -29.90008354, 0. ]), + 'frame': 402, + 'frame_number': 402, + 'framesequence': 400, + 'gaze_dir': array([ 0.98058069, -0.06105338, -0.18637067]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06105338, -0.18637067]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06105338, -0.18637067]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.210338078439236, + 'timestamp_carla': 11210, + 'timestamp_device': 10679, + 'timestamp_stream': 11.210338078439236, + 'transform': [array([1.35055351e+00, 1.39819150e-07, 1.81400299e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 3.66647631e-01, -4.40864354e-01, -1.75674613e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.22799654e+01, -4.06544590e+00, 1.78642140e-03]), + 'Rotation': array([-6.04471704e-03, -4.97785110e+01, 1.04298614e-01]), + 'Velocity': array([ 0.36734179, -0.44110972, 0.00074287]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.7611389160156, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.38848877e+00, -2.85584030e+01, 3.05175781e-05]), + 'frame': 403, + 'frame_number': 403, + 'framesequence': 401, + 'gaze_dir': array([ 0.98058069, -0.05712644, -0.18761161]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05712644, -0.18761161]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05712644, -0.18761161]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.23148087784648, + 'timestamp_carla': 11231, + 'timestamp_device': 10700, + 'timestamp_stream': 11.23148087784648, + 'transform': [array([1.37131584e+00, 1.43442008e-07, 1.81529997e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.38490450e-01, -5.21486580e-01, 5.81407403e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.23492479e+01, -4.13164806e+00, 1.72706484e-03]), + 'Rotation': array([-6.04471704e-03, -4.97779007e+01, 1.37311295e-01]), + 'Velocity': array([ 0.37939417, -0.45620257, -0.00068635]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.9912414550781, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.93927002e+00, -2.66775513e+01, -3.05175781e-05]), + 'frame': 404, + 'frame_number': 404, + 'framesequence': 402, + 'gaze_dir': array([ 0.98058069, -0.05449438, -0.18839295]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05449438, -0.18839295]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05449438, -0.18839295]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.245930276811123, + 'timestamp_carla': 11245, + 'timestamp_device': 10714, + 'timestamp_stream': 11.245930276811123, + 'transform': [array([1.38536739e+00, 1.45076484e-07, 1.81346887e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 2.28304267e-01, -2.74557233e-01, -2.64672781e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.24784851e+01, -4.26990366e+00, 1.81087374e-03]), + 'Rotation': array([-5.52562252e-03, -4.97745132e+01, 6.38317987e-02]), + 'Velocity': array([ 0.3559998 , -0.42511368, 0.00043934]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.5079345703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.46817017, -25.42206192, 0. ]), + 'frame': 405, + 'frame_number': 405, + 'framesequence': 403, + 'gaze_dir': array([ 0.98058057, -0.05185163, -0.18913737]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.05185163, -0.18913737]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.05185163, -0.18913737]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.259946778416634, + 'timestamp_carla': 11259, + 'timestamp_device': 10728, + 'timestamp_stream': 11.259946778416634, + 'transform': [array([1.39889741e+00, 1.44168425e-07, 1.81446073e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 3.72395307e-01, -4.40790087e-01, 8.09594258e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.25467682e+01, -4.33500957e+00, 1.77711411e-03]), + 'Rotation': array([-5.92177361e-03, -4.97738342e+01, 1.20899744e-01]), + 'Velocity': array([ 3.78658295e-01, -4.54021990e-01, 1.59115792e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.04791259765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 9.35250854e+00, -2.41653500e+01, 3.05175781e-05]), + 'frame': 406, + 'frame_number': 406, + 'framesequence': 404, + 'gaze_dir': array([ 0.98058069, -0.04919873, -0.18984474]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04919873, -0.18984474]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04919873, -0.18984474]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.274302776902914, + 'timestamp_carla': 11274, + 'timestamp_device': 10742, + 'timestamp_stream': 11.274302776902914, + 'transform': [array([1.41265500e+00, 1.42189350e-07, 1.81289669e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.65867370e-01, -5.53999722e-01, -6.33689581e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.26180468e+01, -4.40352440e+00, 1.77810609e-03]), + 'Rotation': array([-6.04471704e-03, -4.97733498e+01, 1.42412856e-01]), + 'Velocity': array([ 0.37908411, -0.45634279, -0.00081193]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.6120910644531, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.02119751e+01, -2.29075260e+01, 3.05175781e-05]), + 'frame': 407, + 'frame_number': 407, + 'framesequence': 405, + 'gaze_dir': array([ 0.98058069, -0.04653618, -0.19051489]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04653618, -0.19051489]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04653618, -0.19051489]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.28819327801466, + 'timestamp_carla': 11288, + 'timestamp_device': 10756, + 'timestamp_stream': 11.28819327801466, + 'transform': [array([1.42587471e+00, 1.48345421e-07, 1.81419367e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.78000849e-01, -5.68959713e-01, -9.84893722e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.26940584e+01, -4.47804356e+00, 1.81991525e-03]), + 'Rotation': array([-6.04471704e-03, -4.97727737e+01, 1.41680464e-01]), + 'Velocity': array([ 3.77344280e-01, -4.54628617e-01, -4.10308829e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.19964599609375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.11207275e+01, -2.16486187e+01, -3.05175781e-05]), + 'frame': 408, + 'frame_number': 408, + 'framesequence': 406, + 'gaze_dir': array([ 0.98058069, -0.04405572, -0.19110373]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04405572, -0.19110373]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04405572, -0.19110373]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.30116617679596, + 'timestamp_carla': 11301, + 'timestamp_device': 10769, + 'timestamp_stream': 11.30116617679596, + 'transform': [array([1.43814266e+00, 1.54943862e-07, 1.81983947e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.99704897e-01, -5.93644977e-01, 7.45193859e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.27640343e+01, -4.54463720e+00, 1.79992639e-03]), + 'Rotation': array([-6.10618899e-03, -4.97720985e+01, 1.53622344e-01]), + 'Velocity': array([ 0.38014773, -0.45813274, -0.00088644]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.8381042480469, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.20332642e+01, -2.04787769e+01, 3.05175781e-05]), + 'frame': 409, + 'frame_number': 409, + 'framesequence': 407, + 'gaze_dir': array([ 0.98058069, -0.04175934, -0.19161862]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04175934, -0.19161862]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04175934, -0.19161862]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.313547477126122, + 'timestamp_carla': 11313, + 'timestamp_device': 10781, + 'timestamp_stream': 11.313547477126122, + 'transform': [array([1.44978178e+00, 1.57216292e-07, 1.82678213e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 5.01976252e-01, -5.96786678e-01, -8.57319719e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.28376856e+01, -4.61610842e+00, 1.80839514e-03]), + 'Rotation': array([-6.13350933e-03, -4.97715149e+01, 1.51273802e-01]), + 'Velocity': array([ 3.78575653e-01, -4.56432879e-01, 3.22055821e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.523193359375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 12.90313721, -19.39818192, 0. ]), + 'frame': 410, + 'frame_number': 410, + 'framesequence': 408, + 'gaze_dir': array([ 0.98058069, -0.03907268, -0.19218446]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03907268, -0.19218446]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03907268, -0.19218446]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.326988577842712, + 'timestamp_carla': 11326, + 'timestamp_device': 10795, + 'timestamp_stream': 11.326988577842712, + 'transform': [array([1.46233976e+00, 1.61840305e-07, 1.82693475e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.84616667e-01, -5.75968564e-01, -6.77263733e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.29165010e+01, -4.69312572e+00, 1.79191586e-03]), + 'Rotation': array([-6.13350933e-03, -4.97709961e+01, 1.46093667e-01]), + 'Velocity': array([ 3.78472060e-01, -4.55968350e-01, -1.77822105e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.17779541015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 13.67550659, -18.13667297, 0. ]), + 'frame': 411, + 'frame_number': 411, + 'framesequence': 409, + 'gaze_dir': array([ 0.98058069, -0.0367637 , -0.19263949]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0367637 , -0.19263949]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0367637 , -0.19263949]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.33966537937522, + 'timestamp_carla': 11339, + 'timestamp_device': 10807, + 'timestamp_stream': 11.33966537937522, + 'transform': [array([1.47411358e+00, 1.65351395e-07, 1.83055876e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5355286 , -0.6319229 , 1.42243648]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.005901336669922, + 'FR_Wheel_Angle': 8.310186386108398, + 'Location': array([ 1.29870100e+01, -4.75680590e+00, 1.79679878e-03]), + 'Rotation': array([-6.13350933e-03, -4.96690063e+01, 1.52734861e-01]), + 'Velocity': array([ 4.13035154e-01, -4.30876255e-01, -2.52718921e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.8995361328125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.46162109e+01, -1.70546627e+01, -3.05175781e-05]), + 'frame': 412, + 'frame_number': 412, + 'framesequence': 410, + 'gaze_dir': array([ 0.98058069, -0.03425625, -0.19310112]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03425625, -0.19310112]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03425625, -0.19310112]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.352626278996468, + 'timestamp_carla': 11352, + 'timestamp_device': 10820, + 'timestamp_stream': 11.352626278996468, + 'transform': [array([1.48608124e+00, 1.68727439e-07, 1.83174131e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.464892 , -0.5386849 , 2.07635021]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.947379112243652, + 'FR_Wheel_Angle': 7.61146354675293, + 'Location': array([ 1.30456581e+01, -4.80271769e+00, 1.79367082e-03]), + 'Rotation': array([-4.08445299e-03, -4.94448242e+01, 1.85660437e-01]), + 'Velocity': array([ 4.72104073e-01, -4.62271601e-01, -4.31814173e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.6180419921875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 15.47463989, -15.88181591, 0. ]), + 'frame': 413, + 'frame_number': 413, + 'framesequence': 411, + 'gaze_dir': array([ 0.98058069, -0.03154958, -0.19356178]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03154958, -0.19356178]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03154958, -0.19356178]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.36556937918067, + 'timestamp_carla': 11365, + 'timestamp_device': 10834, + 'timestamp_stream': 11.36556937918067, + 'transform': [array([1.49796319e+00, 1.69439872e-07, 1.83242792e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4937585 , -0.55355424, 1.75435829]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.9776811599731445, + 'FR_Wheel_Angle': 8.781123161315918, + 'Location': array([ 1.31451740e+01, -4.89302683e+00, 1.77577999e-03]), + 'Rotation': array([-3.84539622e-03, -4.91015015e+01, 1.32605657e-01]), + 'Velocity': array([ 4.50141072e-01, -4.48216200e-01, -9.32264302e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.337158203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.63532715e+01, -1.46180935e+01, 3.05175781e-05]), + 'frame': 414, + 'frame_number': 414, + 'framesequence': 412, + 'gaze_dir': array([ 0.98058069, -0.02903077, -0.19395554]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02903077, -0.19395554]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02903077, -0.19395554]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.379578176885843, + 'timestamp_carla': 11379, + 'timestamp_device': 10847, + 'timestamp_stream': 11.379578176885843, + 'transform': [array([1.51185787e+00, 1.74022006e-07, 1.82613370e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.47683847, -0.52534753, 1.70757008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.482423305511475, + 'FR_Wheel_Angle': 8.093021392822266, + 'Location': array([ 1.32251129e+01, -4.96061707e+00, 1.79462472e-03]), + 'Rotation': array([-3.17603769e-03, -4.88159370e+01, 1.43390805e-01]), + 'Velocity': array([ 4.67272103e-01, -4.64064449e-01, -1.21569632e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.0972595214844, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.72698364e+01, -1.34440746e+01, 3.05175781e-05]), + 'frame': 415, + 'frame_number': 415, + 'framesequence': 413, + 'gaze_dir': array([ 0.98058069, -0.02650687, -0.19431655]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02650687, -0.19431655]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02650687, -0.19431655]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.392129678279161, + 'timestamp_carla': 11392, + 'timestamp_device': 10860, + 'timestamp_stream': 11.392129678279161, + 'transform': [array([1.52421439e+00, 1.76671620e-07, 1.82895653e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49425796, -0.53812099, 1.75785756]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.681779384613037, + 'FR_Wheel_Angle': 8.250764846801758, + 'Location': array([ 1.33074751e+01, -5.03008556e+00, 1.77879387e-03]), + 'Rotation': array([-3.05309449e-03, -4.85271683e+01, 1.45449147e-01]), + 'Velocity': array([ 4.70850050e-01, -4.61147726e-01, 4.17356496e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.87652587890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 18.40966797, -12.26940918, 0. ]), + 'frame': 416, + 'frame_number': 416, + 'framesequence': 414, + 'gaze_dir': array([ 0.98058069, -0.02397868, -0.19464469]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02397868, -0.19464469]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02397868, -0.19464469]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.405370078980923, + 'timestamp_carla': 11405, + 'timestamp_device': 10873, + 'timestamp_stream': 11.405370078980923, + 'transform': [array([1.53715348e+00, 1.81728709e-07, 1.82762137e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50570774, -0.54435468, 1.7674067 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.675728797912598, + 'FR_Wheel_Angle': 8.277987480163574, + 'Location': array([ 1.33896027e+01, -5.09856510e+00, 1.75712653e-03]), + 'Rotation': array([-2.96430197e-03, -4.82405281e+01, 1.47352785e-01]), + 'Velocity': array([ 4.76318240e-01, -4.62046146e-01, -1.02872844e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.67742919921875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 19.41964722, -11.09439278, 0. ]), + 'frame': 417, + 'frame_number': 417, + 'framesequence': 415, + 'gaze_dir': array([ 0.98058069, -0.02144625, -0.19493997]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02144625, -0.19493997]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02144625, -0.19493997]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.41778988018632, + 'timestamp_carla': 11417, + 'timestamp_device': 10886, + 'timestamp_stream': 11.41778988018632, + 'transform': [array([1.54920793e+00, 1.82073293e-07, 1.83040614e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.51135892, -0.54455006, 1.77538538]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.671996593475342, + 'FR_Wheel_Angle': 8.2813081741333, + 'Location': array([ 1.34722786e+01, -5.16699123e+00, 1.76277244e-03]), + 'Rotation': array([-2.90283025e-03, -4.79528313e+01, 1.47930518e-01]), + 'Velocity': array([ 4.81182247e-01, -4.62201059e-01, -1.07178683e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.49774169921875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.05101929e+01, -9.91884136e+00, -3.05175781e-05]), + 'frame': 418, + 'frame_number': 418, + 'framesequence': 416, + 'gaze_dir': array([ 0.98058069, -0.01891038, -0.19520231]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01891038, -0.19520231]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01891038, -0.19520231]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.431268576532602, + 'timestamp_carla': 11431, + 'timestamp_device': 10899, + 'timestamp_stream': 11.431268576532602, + 'transform': [array([1.56219935e+00, 1.87325966e-07, 1.82701112e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.51286709, -0.54055101, 1.78430235]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.671568393707275, + 'FR_Wheel_Angle': 8.280716896057129, + 'Location': array([ 1.35555096e+01, -5.23521233e+00, 1.77127926e-03]), + 'Rotation': array([-2.93015107e-03, -4.76642265e+01, 1.48047358e-01]), + 'Velocity': array([ 4.85990286e-01, -4.62082714e-01, 1.09138484e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.33880615234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.15355225e+01, -8.74300194e+00, 3.05175781e-05]), + 'frame': 419, + 'frame_number': 419, + 'framesequence': 417, + 'gaze_dir': array([ 0.98058069, -0.01637113, -0.19543163]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01637113, -0.19543163]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01637113, -0.19543163]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.443909280002117, + 'timestamp_carla': 11443, + 'timestamp_device': 10912, + 'timestamp_stream': 11.443909280002117, + 'transform': [array([1.57430339e+00, 1.89323657e-07, 1.82846060e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50828803, -0.53006893, 1.78867543]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.67134428024292, + 'FR_Wheel_Angle': 8.280109405517578, + 'Location': array([ 1.36418066e+01, -5.30575085e+00, 1.75869069e-03]), + 'Rotation': array([-3.02577368e-03, -4.73654900e+01, 1.43977225e-01]), + 'Velocity': array([ 4.89645064e-01, -4.60651428e-01, 9.31882823e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.1991271972656, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([22.67669678, -7.56672001, 0. ]), + 'frame': 420, + 'frame_number': 420, + 'framesequence': 418, + 'gaze_dir': array([ 0.98058069, -0.01402481, -0.19561401]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01402481, -0.19561401]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01402481, -0.19561401]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.456261578947306, + 'timestamp_carla': 11456, + 'timestamp_device': 10924, + 'timestamp_stream': 11.456261578947306, + 'transform': [array([1.58605862e+00, 1.96061791e-07, 1.83071138e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.48542845, -0.50054783, 1.78751481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.671410083770752, + 'FR_Wheel_Angle': 8.279563903808594, + 'Location': array([ 1.37343731e+01, -5.38161898e+00, 1.76773162e-03]), + 'Rotation': array([-3.32630193e-03, -4.70448494e+01, 1.33547798e-01]), + 'Velocity': array([ 4.92038190e-01, -4.57477212e-01, 1.27115243e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.088623046875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.37619324e+01, -6.48070383e+00, 3.05175781e-05]), + 'frame': 421, + 'frame_number': 421, + 'framesequence': 419, + 'gaze_dir': array([ 0.98058069, -0.0114808 , -0.1957798 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0114808 , -0.1957798 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0114808 , -0.1957798 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.468990579247475, + 'timestamp_carla': 11468, + 'timestamp_device': 10937, + 'timestamp_stream': 11.468990579247475, + 'transform': [array([1.59809792e+00, 2.01435540e-07, 1.83059683e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.31707764, -0.36031443, -0.9942674 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.701300144195557, + 'FR_Wheel_Angle': 8.283597946166992, + 'Location': array([ 1.38131828e+01, -5.44782114e+00, 2.71411985e-03]), + 'Rotation': array([ 0.0479206 , -46.90971756, 0.31893638]), + 'Velocity': array([ 0.27114981, -0.32660472, 0.00687156]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.988525390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.48239136e+01, -5.30399847e+00, 3.05175781e-05]), + 'frame': 422, + 'frame_number': 422, + 'framesequence': 420, + 'gaze_dir': array([ 0.98058069, -0.00873886, -0.19592133]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00873886, -0.19592133]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00873886, -0.19592133]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.4833830781281, + 'timestamp_carla': 11483, + 'timestamp_device': 10951, + 'timestamp_stream': 11.4833830781281, + 'transform': [array([1.61162031e+00, 2.01095588e-07, 1.82029721e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.02615047, 0.76184654, 1.38761401]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.689453125, + 'FR_Wheel_Angle': 8.279336929321289, + 'Location': array([13.89365578, -5.53234625, 0.03017136]), + 'Rotation': array([ 1.15635777, -46.62166595, 2.50224471]), + 'Velocity': array([ 0.41132101, -0.34549755, 0.06166707]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.9027404785156, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([25.93075562, -4.03650379, 0. ]), + 'frame': 423, + 'frame_number': 423, + 'framesequence': 421, + 'gaze_dir': array([ 0.98058069, -0.00599521, -0.19602446]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00599521, -0.19602446]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00599521, -0.19602446]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.496720779687166, + 'timestamp_carla': 11496, + 'timestamp_device': 10965, + 'timestamp_stream': 11.496720779687166, + 'transform': [array([1.62407196e+00, 2.07251645e-07, 1.81846612e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.93079656, 0.09286851, 1.8518573 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.169961929321289, + 'FR_Wheel_Angle': 9.430900573730469, + 'Location': array([13.99139595, -5.61184788, 0.03348316]), + 'Rotation': array([ 1.34939945, -46.28846359, 2.90515757]), + 'Velocity': array([ 0.49623302, -0.43180609, 0.02263737]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.8387451171875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.72110596e+01, -2.76881862e+00, -3.05175781e-05]), + 'frame': 424, + 'frame_number': 424, + 'framesequence': 422, + 'gaze_dir': array([ 0.98058069, -0.00364252, -0.19608229]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00364252, -0.19608229]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00364252, -0.19608229]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.509590979665518, + 'timestamp_carla': 11509, + 'timestamp_device': 10977, + 'timestamp_stream': 11.509590979665518, + 'transform': [array([1.63601530e+00, 2.13812825e-07, 1.81926729e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.96173966, 0.11031666, 3.4233892 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.210869789123535, + 'FR_Wheel_Angle': 18.30222511291504, + 'Location': array([14.08038521, -5.67768717, 0.03264629]), + 'Rotation': array([ 1.32406628, -45.87366867, 2.86965489]), + 'Velocity': array([ 0.50354511, -0.36594906, 0.02012121]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.8034362792969, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.84163513e+01, -1.68212807e+00, -3.05175781e-05]), + 'frame': 425, + 'frame_number': 425, + 'framesequence': 423, + 'gaze_dir': array([ 9.80580688e-01, -8.97115620e-04, -1.96114078e-01]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, -8.97115620e-04, -1.96114078e-01]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, -8.97115620e-04, -1.96114078e-01]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.523102577775717, + 'timestamp_carla': 11523, + 'timestamp_device': 10991, + 'timestamp_stream': 11.523102577775717, + 'transform': [array([1.64847791e+00, 2.20802420e-07, 1.81629171e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.20913659, -0.1878804 , 3.52584815]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.515769958496094, + 'FR_Wheel_Angle': 15.55728530883789, + 'Location': array([14.18553925, -5.75107908, 0.03459072]), + 'Rotation': array([ 1.39973104, -45.18001175, 3.03147054]), + 'Velocity': array([ 0.57788086, -0.43321767, 0.01479753]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.7842102050781, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 2.95888672e+01, -4.14271712e-01, -3.05175781e-05]), + 'frame': 426, + 'frame_number': 426, + 'framesequence': 424, + 'gaze_dir': array([ 0.98058069, 0.00165247, -0.19610916]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00165247, -0.19610916]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00165247, -0.19610916]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.536083977669477, + 'timestamp_carla': 11536, + 'timestamp_device': 11004, + 'timestamp_stream': 11.536083977669477, + 'transform': [array([1.66038084e+00, 2.23479958e-07, 1.81663514e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.19133022, -0.34603524, 3.94295025]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.629948616027832, + 'FR_Wheel_Angle': 16.853376388549805, + 'Location': array([14.27976608, -5.8148694 , 0.03544663]), + 'Rotation': array([ 1.42627323, -44.58768082, 3.100003 ]), + 'Velocity': array([ 0.59816492, -0.4302294 , 0.00760925]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.786865234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.08382568e+01, 7.63090372e-01, -3.05175781e-05]), + 'frame': 427, + 'frame_number': 427, + 'framesequence': 425, + 'gaze_dir': array([ 0.98058069, 0.00400562, -0.19607522]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00400562, -0.19607522]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00400562, -0.19607522]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.548472378402948, + 'timestamp_carla': 11548, + 'timestamp_device': 11016, + 'timestamp_stream': 11.548472378402948, + 'transform': [array([1.67267787e+00, 2.25277418e-07, 1.81949616e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.35451829, -0.3888599 , 3.8862102 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.314668655395508, + 'FR_Wheel_Angle': 16.61676788330078, + 'Location': array([14.39028549, -5.88947487, 0.03605961]), + 'Rotation': array([ 1.43716049, -43.88637924, 3.12098384]), + 'Velocity': array([ 0.60946202, -0.43296531, 0.00449199]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.807373046875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.20518799e+01, 1.84982729e+00, -3.05175781e-05]), + 'frame': 428, + 'frame_number': 428, + 'framesequence': 426, + 'gaze_dir': array([ 0.98058069, 0.00655409, -0.19600657]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00655409, -0.19600657]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00655409, -0.19600657]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.560945477336645, + 'timestamp_carla': 11560, + 'timestamp_device': 11029, + 'timestamp_stream': 11.560945477336645, + 'transform': [array([1.68496871e+00, 2.28783847e-07, 1.82147976e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42618427, -0.41315314, 3.91516614]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.279725074768066, + 'FR_Wheel_Angle': 16.53257942199707, + 'Location': array([14.49254704, -5.95626307, 0.03631951]), + 'Rotation': array([ 1.43981063, -43.2428627 , 3.1301589 ]), + 'Velocity': array([ 0.61957538, -0.43063322, 0.00199429]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.849365234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([3.33289185e+01, 3.02700758e+00, 3.05175781e-05]), + 'frame': 429, + 'frame_number': 429, + 'framesequence': 427, + 'gaze_dir': array([ 0.98058069, 0.00890566, -0.19591382]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00890566, -0.19591382]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00890566, -0.19591382]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.573195978999138, + 'timestamp_carla': 11573, + 'timestamp_device': 11041, + 'timestamp_stream': 11.573195978999138, + 'transform': [array([1.69695568e+00, 2.33324045e-07, 1.82403566e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44552457, -0.40771335, 3.94012427]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.319210052490234, + 'FR_Wheel_Angle': 16.56561851501465, + 'Location': array([14.60196114, -6.02659225, 0.03651512]), + 'Rotation': array([ 1.43990624, -42.55989075, 3.12577343]), + 'Velocity': array([ 0.6269381 , -0.42451462, 0.00120656]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.9059143066406, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.46219482e+01, 4.11358166e+00, -3.05175781e-05]), + 'frame': 430, + 'frame_number': 430, + 'framesequence': 428, + 'gaze_dir': array([ 0.98058069, 0.01145181, -0.19578148]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.01145181, -0.19578148]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.01145181, -0.19578148]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.586160778999329, + 'timestamp_carla': 11586, + 'timestamp_device': 11054, + 'timestamp_stream': 11.586160778999329, + 'transform': [array([1.70955300e+00, 2.36085413e-07, 1.82258605e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44243217, -0.38981727, 3.9705472 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.330426216125488, + 'FR_Wheel_Angle': 16.57254981994629, + 'Location': array([14.71415138, -6.09713411, 0.03657204]), + 'Rotation': array([ 1.43888855, -41.86421204, 3.11940575]), + 'Velocity': array([ 0.6365363 , -0.41952944, 0.00070726]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.9864807128906, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([35.91171265, 5.29058695, 0. ]), + 'frame': 431, + 'frame_number': 431, + 'framesequence': 429, + 'gaze_dir': array([ 0.98058069, 0.01399584, -0.19561608]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.01399584, -0.19561608]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.01399584, -0.19561608]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.59891627728939, + 'timestamp_carla': 11598, + 'timestamp_device': 11067, + 'timestamp_stream': 11.59891627728939, + 'transform': [array([1.72186291e+00, 2.34897954e-07, 1.82239525e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39861226, -0.34007603, 3.95334196]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.332247734069824, + 'FR_Wheel_Angle': 16.569618225097656, + 'Location': array([14.84441948, -6.17832136, 0.03660046]), + 'Rotation': array([ 1.43729031, -41.05999756, 3.09948015]), + 'Velocity': array([ 0.64008039, -0.40863165, 0.00085191]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.0865478515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([37.28485107, 6.46729422, 0. ]), + 'frame': 432, + 'frame_number': 432, + 'framesequence': 430, + 'gaze_dir': array([ 0.98058069, 0.01634219, -0.19543405]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.01634219, -0.19543405]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.01634219, -0.19543405]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.611264377832413, + 'timestamp_carla': 11611, + 'timestamp_device': 11079, + 'timestamp_stream': 11.611264377832413, + 'transform': [array([1.73370361e+00, 2.40448628e-07, 1.82407373e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39911771, -0.32882649, 4.03080225]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.327695846557617, + 'FR_Wheel_Angle': 16.567384719848633, + 'Location': array([14.96779633, -6.25239468, 0.03658009]), + 'Rotation': array([ 1.43548715, -40.30653763, 3.09943414]), + 'Velocity': array([ 6.58416629e-01, -4.08039510e-01, 3.37586389e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.1969299316406, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([3.86408081e+01, 7.55331230e+00, 3.05175781e-05]), + 'frame': 433, + 'frame_number': 433, + 'framesequence': 431, + 'gaze_dir': array([ 0.98058069, 0.01868618, -0.19522387]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.01868618, -0.19522387]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.01868618, -0.19522387]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.623678978532553, + 'timestamp_carla': 11623, + 'timestamp_device': 11091, + 'timestamp_stream': 11.623678978532553, + 'transform': [array([1.74553418e+00, 2.46157640e-07, 1.82498933e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42361435, -0.34176782, 4.07412624]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.325791358947754, + 'FR_Wheel_Angle': 16.564939498901367, + 'Location': array([15.07181072, -6.31203842, 0.03655583]), + 'Rotation': array([ 1.43400502, -39.67716599, 3.10968828]), + 'Velocity': array([ 6.70323074e-01, -4.04514760e-01, -1.19905468e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.3247375488281, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([39.96951294, 8.63908768, 0. ]), + 'frame': 434, + 'frame_number': 434, + 'framesequence': 432, + 'gaze_dir': array([ 0.98058069, 0.02122235, -0.19496447]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.02122235, -0.19496447]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.02122235, -0.19496447]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.636065479367971, + 'timestamp_carla': 11636, + 'timestamp_device': 11104, + 'timestamp_stream': 11.636065479367971, + 'transform': [array([1.75726640e+00, 2.53808480e-07, 1.82571402e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42895737, -0.33794877, 4.10485411]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.324468612670898, + 'FR_Wheel_Angle': 16.56291389465332, + 'Location': array([15.19771576, -6.38396454, 0.03652977]), + 'Rotation': array([ 1.43235886, -38.91708755, 3.09892201]), + 'Velocity': array([ 6.80375636e-01, -3.99372220e-01, 3.26700218e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.482421875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([41.33108521, 9.81496811, 0. ]), + 'frame': 435, + 'frame_number': 435, + 'framesequence': 433, + 'gaze_dir': array([ 0.98058069, 0.02356035, -0.19469577]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.02356035, -0.19469577]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.02356035, -0.19469577]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.648442678153515, + 'timestamp_carla': 11648, + 'timestamp_device': 11116, + 'timestamp_stream': 11.648442678153515, + 'transform': [array([1.76892030e+00, 2.55456911e-07, 1.82620995e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44152346, -0.33929369, 4.15809345]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.323312759399414, + 'FR_Wheel_Angle': 16.56048011779785, + 'Location': array([15.30654049, -6.44350576, 0.03648098]), + 'Rotation': array([ 1.43091774, -38.26636505, 3.10180616]), + 'Velocity': array([ 6.93875551e-01, -3.96747589e-01, 2.46000272e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.6458435058594, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.26893005e+01, 1.09001064e+01, -3.05175781e-05]), + 'frame': 436, + 'frame_number': 436, + 'framesequence': 434, + 'gaze_dir': array([ 0.98058069, 0.02589497, -0.19439904]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.02589497, -0.19439904]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.02589497, -0.19439904]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.660645179450512, + 'timestamp_carla': 11660, + 'timestamp_device': 11128, + 'timestamp_stream': 11.660645179450512, + 'transform': [array([1.78034329e+00, 2.57878327e-07, 1.82723999e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.45745632, -0.34493896, 5.43553495]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 18.42687225341797, + 'FR_Wheel_Angle': 23.04446029663086, + 'Location': array([15.43581867, -6.51155663, 0.03645855]), + 'Rotation': array([ 1.42950392, -37.4249115 , 3.08589625]), + 'Velocity': array([ 7.14527249e-01, -3.51468474e-01, 3.28798284e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.8263854980469, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([44.05911255, 11.98487854, 0. ]), + 'frame': 437, + 'frame_number': 437, + 'framesequence': 435, + 'gaze_dir': array([ 0.98058069, 0.02861392, -0.19401745]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.02861392, -0.19401745]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.02861392, -0.19401745]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.673498678952456, + 'timestamp_carla': 11673, + 'timestamp_device': 11142, + 'timestamp_stream': 11.673498678952456, + 'transform': [array([1.79230475e+00, 2.68351073e-07, 1.82472228e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.35324252, -0.25208864, 6.43081999]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.525108337402344, + 'FR_Wheel_Angle': 24.822813034057617, + 'Location': array([15.5656023 , -6.56943512, 0.03642922]), + 'Rotation': array([ 1.4282949 , -36.30241776, 3.07260489]), + 'Velocity': array([ 7.55979359e-01, -3.23037446e-01, 4.16746130e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.05877685546875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([45.46453857, 13.24993134, 0. ]), + 'frame': 438, + 'frame_number': 438, + 'framesequence': 436, + 'gaze_dir': array([ 0.98058069, 0.03094003, -0.19366014]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03094003, -0.19366014]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03094003, -0.19366014]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.685955077409744, + 'timestamp_carla': 11685, + 'timestamp_device': 11154, + 'timestamp_stream': 11.685955077409744, + 'transform': [array([1.80383027e+00, 2.72313827e-07, 1.82449340e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.38511506, -0.26463941, 6.43497849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.375072479248047, + 'FR_Wheel_Angle': 25.227783203125, + 'Location': array([15.68713379, -6.62228441, 0.03638676]), + 'Rotation': array([ 1.427086 , -35.29797363, 3.0718236 ]), + 'Velocity': array([ 7.79340446e-01, -3.23481590e-01, -1.81636802e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.2761535644531, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([46.90692139, 14.3337841 , 0. ]), + 'frame': 439, + 'frame_number': 439, + 'framesequence': 437, + 'gaze_dir': array([ 0.98058069, 0.03326168, -0.19327493]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03326168, -0.19327493]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03326168, -0.19327493]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.698028579354286, + 'timestamp_carla': 11698, + 'timestamp_device': 11166, + 'timestamp_stream': 11.698028579354286, + 'transform': [array([1.81581962e+00, 2.77138099e-07, 1.82620995e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.35357463, -0.23184735, 6.54662991]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.08759117126465, + 'FR_Wheel_Angle': 24.578609466552734, + 'Location': array([15.80829048, -6.67175293, 0.03638519]), + 'Rotation': array([ 1.4261229 , -34.2763176 , 3.07216525]), + 'Velocity': array([ 8.01501155e-01, -3.15726608e-01, -2.28815072e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.510986328125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([4.83254395e+01, 1.54171619e+01, 6.10351562e-05]), + 'frame': 440, + 'frame_number': 440, + 'framesequence': 438, + 'gaze_dir': array([ 0.98058069, 0.03577147, -0.19282618]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03577147, -0.19282618]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03577147, -0.19282618]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.710725277662277, + 'timestamp_carla': 11710, + 'timestamp_device': 11179, + 'timestamp_stream': 11.710725277662277, + 'transform': [array([1.82833648e+00, 2.78032161e-07, 1.82476034e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.30831474, -0.1955215 , 6.40910864]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.172748565673828, + 'FR_Wheel_Angle': 24.745023727416992, + 'Location': array([15.97417927, -6.73783636, 0.03637112]), + 'Rotation': array([ 1.42492759, -32.89930725, 3.0449264 ]), + 'Velocity': array([ 7.89214373e-01, -2.88383961e-01, -1.25384322e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.78533935546875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.98348999e+01, 1.65902882e+01, -3.05175781e-05]), + 'frame': 441, + 'frame_number': 441, + 'framesequence': 439, + 'gaze_dir': array([ 0.98058069, 0.03808277, -0.19238305]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03808277, -0.19238305]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03808277, -0.19238305]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.722823977470398, + 'timestamp_carla': 11722, + 'timestamp_device': 11191, + 'timestamp_stream': 11.722823977470398, + 'transform': [array([1.84018159e+00, 2.80192808e-07, 1.82628632e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.30321065, -0.18174869, 6.56417847]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.2019100189209, + 'FR_Wheel_Angle': 24.814186096191406, + 'Location': array([16.11062241, -6.78825855, 0.03637303]), + 'Rotation': array([ 1.4238075 , -31.77846146, 3.04457736]), + 'Velocity': array([ 8.13577473e-01, -2.79036075e-01, -6.70003865e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.055908203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([51.39312744, 17.67254257, 0. ]), + 'frame': 442, + 'frame_number': 442, + 'framesequence': 440, + 'gaze_dir': array([ 0.98058069, 0.0403884 , -0.19191223]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.0403884 , -0.19191223]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.0403884 , -0.19191223]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.735567279160023, + 'timestamp_carla': 11735, + 'timestamp_device': 11203, + 'timestamp_stream': 11.735567279160023, + 'transform': [array([1.85257304e+00, 2.86320926e-07, 1.82445522e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.00773673, -0.17447658, 6.64059401]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.215166091918945, + 'FR_Wheel_Angle': 24.81791877746582, + 'Location': array([16.25881004, -6.84009552, 0.03679623]), + 'Rotation': array([ 1.44429123, -30.56848526, 3.08802962]), + 'Velocity': array([ 0.82799566, -0.26063401, 0.00530601]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.3443603515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([52.90411377, 18.75413132, 0. ]), + 'frame': 443, + 'frame_number': 443, + 'framesequence': 441, + 'gaze_dir': array([ 0.98058069, 0.04287987, -0.19137098]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.04287987, -0.19137098]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.04287987, -0.19137098]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.748280879110098, + 'timestamp_carla': 11748, + 'timestamp_device': 11216, + 'timestamp_stream': 11.748280879110098, + 'transform': [array([1.86485326e+00, 2.94972921e-07, 1.82300562e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.27851334, -0.1490075 , 6.63800812]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.214920043945312, + 'FR_Wheel_Angle': 24.814735412597656, + 'Location': array([16.4106617 , -6.89005852, 0.03683727]), + 'Rotation': array([ 1.44879913, -29.33493423, 3.08654547]), + 'Velocity': array([ 8.32681000e-01, -2.45784029e-01, 7.13024114e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.6757507324219, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 5.45187073e+01, 1.99252472e+01, -3.05175781e-05]), + 'frame': 444, + 'frame_number': 444, + 'framesequence': 442, + 'gaze_dir': array([ 0.98058069, 0.04536391, -0.19079739]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.04536391, -0.19079739]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.04536391, -0.19079739]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.760904777795076, + 'timestamp_carla': 11760, + 'timestamp_device': 11229, + 'timestamp_stream': 11.760904777795076, + 'transform': [array([1.87696838e+00, 2.99163872e-07, 1.82220456e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.26558211, -0.13721301, 6.72005796]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.21331787109375, + 'FR_Wheel_Angle': 24.810771942138672, + 'Location': array([16.55195808, -6.93319798, 0.03685757]), + 'Rotation': array([ 1.44765854, -28.19661522, 3.08498764]), + 'Velocity': array([ 8.48030984e-01, -2.31975988e-01, 6.96659088e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.027587890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([56.14520264, 21.09547997, 0. ]), + 'frame': 445, + 'frame_number': 445, + 'framesequence': 443, + 'gaze_dir': array([ 0.98058069, 0.04784046, -0.19019154]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.04784046, -0.19019154]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.04784046, -0.19019154]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.774354979395866, + 'timestamp_carla': 11774, + 'timestamp_device': 11242, + 'timestamp_stream': 11.774354979395866, + 'transform': [array([1.88979173e+00, 3.04160409e-07, 1.81697845e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.24850422, -0.12443841, 6.76825666]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.209671020507812, + 'FR_Wheel_Angle': 24.807329177856445, + 'Location': array([16.70400047, -6.97671843, 0.03688606]), + 'Rotation': array([ 1.44705057, -26.97904778, 3.08106399]), + 'Velocity': array([ 8.59102488e-01, -2.15343431e-01, 4.13632370e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.3998718261719, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([57.77832031, 22.26495743, 0. ]), + 'frame': 446, + 'frame_number': 446, + 'framesequence': 444, + 'gaze_dir': array([ 0.98058069, 0.05030876, -0.18955359]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.05030876, -0.18955359]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.05030876, -0.18955359]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.787377279251814, + 'timestamp_carla': 11787, + 'timestamp_device': 11255, + 'timestamp_stream': 11.787377279251814, + 'transform': [array([1.90212798e+00, 3.10428220e-07, 1.81510916e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.24317275, -0.11727809, 6.81150961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.207904815673828, + 'FR_Wheel_Angle': 24.80352210998535, + 'Location': array([16.84496307, -7.01396894, 0.03689827]), + 'Rotation': array([ 1.44678426, -25.85663795, 3.07918859]), + 'Velocity': array([ 8.68804693e-01, -1.99739829e-01, 3.61251805e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.7918701171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([59.50482178, 23.433424 , 0. ]), + 'frame': 447, + 'frame_number': 447, + 'framesequence': 445, + 'gaze_dir': array([ 0.98058069, 0.05276873, -0.18888353]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.05276873, -0.18888353]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.05276873, -0.18888353]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.799697678536177, + 'timestamp_carla': 11799, + 'timestamp_device': 11268, + 'timestamp_stream': 11.799697678536177, + 'transform': [array([1.91373003e+00, 3.15862479e-07, 1.81697845e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.69002795, 6.16271067, 3.35613513]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.31753158569336, + 'FR_Wheel_Angle': 24.813459396362305, + 'Location': array([16.95601463, -7.04061937, 0.04462857]), + 'Rotation': array([ 1.13249993, -25.01917076, 3.61120415]), + 'Velocity': array([ 0.55605996, -0.07138229, 0.08093807]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.204833984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([61.20617676, 24.60104752, 0. ]), + 'frame': 448, + 'frame_number': 448, + 'framesequence': 446, + 'gaze_dir': array([ 0.98058069, 0.0552196 , -0.18818162]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.0552196 , -0.18818162]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.0552196 , -0.18818162]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.812694478780031, + 'timestamp_carla': 11812, + 'timestamp_device': 11281, + 'timestamp_stream': 11.812694478780031, + 'transform': [array([1.92589545e+00, 3.19611047e-07, 1.81510916e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-2.0684936 , 3.89692187, 6.49283648]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 21.68039321899414, + 'FR_Wheel_Angle': 27.76700210571289, + 'Location': array([17.09327698, -7.07023287, 0.06198227]), + 'Rotation': array([ 0.43610755, -24.02289772, 4.63492537]), + 'Velocity': array([ 0.80272681, -0.1186267 , 0.07609735]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.6387939453125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.28576965e+01, 2.57676201e+01, -3.05175781e-05]), + 'frame': 449, + 'frame_number': 449, + 'framesequence': 447, + 'gaze_dir': array([ 0.98058069, 0.05747376, -0.18750547]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.05747376, -0.18750547]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.05747376, -0.18750547]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.825590778142214, + 'timestamp_carla': 11825, + 'timestamp_device': 11293, + 'timestamp_stream': 11.825590778142214, + 'transform': [array([1.93789518e+00, 3.27257226e-07, 1.81400299e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.83164978, 1.40585542, 9.20837116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.825952529907227, + 'FR_Wheel_Angle': 34.78520584106445, + 'Location': array([17.24650002, -7.09524965, 0.07026035]), + 'Rotation': array([ 0.14396672, -22.50956917, 5.0329752 ]), + 'Velocity': array([ 0.869488 , -0.05238925, 0.03913236]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.05712890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([64.54803467, 26.84354591, 0. ]), + 'frame': 450, + 'frame_number': 450, + 'framesequence': 448, + 'gaze_dir': array([ 0.98058069, 0.0599065 , -0.18674245]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.0599065 , -0.18674245]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.0599065 , -0.18674245]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.838168278336525, + 'timestamp_carla': 11838, + 'timestamp_device': 11306, + 'timestamp_stream': 11.838168278336525, + 'transform': [array([1.94953072e+00, 3.33511053e-07, 1.81465142e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.54853094, 0.71788114, 8.60353374]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.17010498046875, + 'FR_Wheel_Angle': 32.65713119506836, + 'Location': array([17.4006691 , -7.11526108, 0.07308907]), + 'Rotation': array([ 0.08149781, -20.91136932, 5.13106251]), + 'Velocity': array([ 0.87302715, -0.05260469, 0.02120985]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.5301208496094, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([66.28372192, 28.00811005, 0. ]), + 'frame': 451, + 'frame_number': 451, + 'framesequence': 449, + 'gaze_dir': array([ 0.98058069, 0.06214306, -0.18601012]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.06214306, -0.18601012]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.06214306, -0.18601012]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.850210279226303, + 'timestamp_carla': 11850, + 'timestamp_device': 11318, + 'timestamp_stream': 11.850210279226303, + 'transform': [array([1.96148920e+00, 3.34954592e-07, 1.81713095e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.21128924, 0.28027406, 9.07546234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.509977340698242, + 'FR_Wheel_Angle': 32.834388732910156, + 'Location': array([17.56206512, -7.13112783, 0.07560929]), + 'Rotation': array([ 0.02396713, -19.25491714, 5.22648859]), + 'Velocity': array([ 0.90178245, -0.02531192, 0.01282363]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.9853210449219, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([67.96264648, 29.08205223, 0. ]), + 'frame': 452, + 'frame_number': 452, + 'framesequence': 450, + 'gaze_dir': array([ 0.98058069, 0.06437067, -0.18525104]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.06437067, -0.18525104]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.06437067, -0.18525104]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.862157378345728, + 'timestamp_carla': 11862, + 'timestamp_device': 11330, + 'timestamp_stream': 11.862157378345728, + 'transform': [array([1.97327125e+00, 3.41613600e-07, 1.81961060e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.06910174, 0.10149854, 9.29383945]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.61322021484375, + 'FR_Wheel_Angle': 33.079322814941406, + 'Location': array([17.70148087, -7.14154959, 0.0765815 ]), + 'Rotation': array([ 5.40267956e-03, -1.78394547e+01, 5.25766945e+00]), + 'Velocity': array([ 0.91866511, -0.00329334, 0.00692379]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.4584045410156, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([69.69406128, 30.15499496, 0. ]), + 'frame': 453, + 'frame_number': 453, + 'framesequence': 451, + 'gaze_dir': array([ 0.98058069, 0.06658901, -0.18446526]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.06658901, -0.18446526]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.06658901, -0.18446526]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.874667577445507, + 'timestamp_carla': 11874, + 'timestamp_device': 11342, + 'timestamp_stream': 11.874667577445507, + 'transform': [array([1.98552334e+00, 3.45045521e-07, 1.81919092e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.02289811, 0.02540203, 9.24921894]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.56949806213379, + 'FR_Wheel_Angle': 33.0118293762207, + 'Location': array([17.86586189, -7.14958429, 0.07722824]), + 'Rotation': array([-2.22664163e-03, -1.61674061e+01, 5.26842690e+00]), + 'Velocity': array([0.91565937, 0.0224581 , 0.00332794]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.94903564453125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([71.42776489, 31.22687149, 0. ]), + 'frame': 454, + 'frame_number': 454, + 'framesequence': 452, + 'gaze_dir': array([ 0.98058069, 0.0691649 , -0.18351497]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.0691649 , -0.18351497]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.0691649 , -0.18351497]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.887768879532814, + 'timestamp_carla': 11887, + 'timestamp_device': 11356, + 'timestamp_stream': 11.887768879532814, + 'transform': [array([1.99826455e+00, 3.50614812e-07, 1.81579590e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-1.89834274e-02, 4.23839083e-03, 9.28722286e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.552072525024414, + 'FR_Wheel_Angle': 33.00642395019531, + 'Location': array([18.0097065 , -7.15296316, 0.07748631]), + 'Rotation': array([-4.33716970e-03, -1.47082720e+01, 5.26820469e+00]), + 'Velocity': array([0.91924131, 0.04568492, 0.0020445 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 469.5433349609375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([73.32589722, 32.47592926, 0. ]), + 'frame': 455, + 'frame_number': 455, + 'framesequence': 453, + 'gaze_dir': array([ 0.98058069, 0.0715446 , -0.18260039]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.0715446 , -0.18260039]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.0715446 , -0.18260039]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.90068008005619, + 'timestamp_carla': 11900, + 'timestamp_device': 11369, + 'timestamp_stream': 11.90068008005619, + 'transform': [array([2.01073599e+00, 3.56044438e-07, 1.81407924e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.13376077e-02, -3.36380489e-03, 9.24300098e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.5537166595459, + 'FR_Wheel_Angle': 33.00334548950195, + 'Location': array([18.16355324, -7.15274954, 0.07764454]), + 'Rotation': array([-4.81528323e-03, -1.31482143e+01, 5.26449966e+00]), + 'Velocity': array([9.13160384e-01, 7.04822540e-02, 8.12826154e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.11614990234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([75.24890137, 33.63428879, 0. ]), + 'frame': 456, + 'frame_number': 456, + 'framesequence': 454, + 'gaze_dir': array([ 0.98058069, 0.07373062, -0.18172871]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.07373062, -0.18172871]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.07373062, -0.18172871]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.913683880120516, + 'timestamp_carla': 11913, + 'timestamp_device': 11381, + 'timestamp_stream': 11.913683880120516, + 'transform': [array([2.02321386e+00, 3.66763999e-07, 1.81221007e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-5.24359345e-02, -4.68246033e-03, 9.22822857e+00]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.554126739501953, + 'FR_Wheel_Angle': 33.0058479309082, + 'Location': array([18.31623459, -7.14870644, 0.07770187]), + 'Rotation': array([-4.84943390e-03, -1.16013050e+01, 5.25894165e+00]), + 'Velocity': array([ 9.09433484e-01, 9.51238424e-02, -4.82754695e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.6637268066406, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([77.1161499 , 34.70234299, 0. ]), + 'frame': 457, + 'frame_number': 457, + 'framesequence': 455, + 'gaze_dir': array([ 0.98058069, 0.07608688, -0.18075486]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.07608688, -0.18075486]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.07608688, -0.18075486]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.925955578684807, + 'timestamp_carla': 11925, + 'timestamp_device': 11394, + 'timestamp_stream': 11.925955578684807, + 'transform': [array([2.03491664e+00, 3.68980551e-07, 1.81423186e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.27225348, -0.04560638, 8.59118271]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.5776424407959, + 'FR_Wheel_Angle': 33.004329681396484, + 'Location': array([18.45135307, -7.14203787, 0.07728047]), + 'Rotation': array([ -0.02047691, -10.25312805, 5.21518707]), + 'Velocity': array([0.84295148, 0.11042194, 0.00106773]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 471.27691650390625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([79.05844116, 35.85800934, 0. ]), + 'frame': 458, + 'frame_number': 458, + 'framesequence': 456, + 'gaze_dir': array([ 0.98058069, 0.07825025, -0.17982888]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.07825025, -0.17982888]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.07825025, -0.17982888]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.93807227909565, + 'timestamp_carla': 11938, + 'timestamp_device': 11406, + 'timestamp_stream': 11.93807227909565, + 'transform': [array([2.04640341e+00, 3.74200596e-07, 1.81652070e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([13.64346886, 5.23070478, 7.71362066]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.570842742919922, + 'FR_Wheel_Angle': 33.000526428222656, + 'Location': array([18.58793831, -7.13056421, 0.05282108]), + 'Rotation': array([-1.14150894, -8.95170212, 2.73580718]), + 'Velocity': array([ 0.84493625, -0.01524359, -0.23549081]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 471.8620910644531, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([80.89123535, 36.92334366, 0. ]), + 'frame': 459, + 'frame_number': 459, + 'framesequence': 457, + 'gaze_dir': array([ 0.98058069, 0.08058143, -0.17879641]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08058143, -0.17879641]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08058143, -0.17879641]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.950692277401686, + 'timestamp_carla': 11950, + 'timestamp_device': 11419, + 'timestamp_stream': 11.950692277401686, + 'transform': [array([2.05829644e+00, 3.78228577e-07, 1.81602477e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([0.31158912, 0.10101305, 8.82361317]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.566558837890625, + 'FR_Wheel_Angle': 33.00038528442383, + 'Location': array([18.74906158, -7.11566353, 0.04788609]), + 'Rotation': array([-1.46810806, -7.31738853, 2.29981565]), + 'Velocity': array([ 0.86507916, 0.15506861, -0.02761631]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 472.51629638671875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([82.78060913, 38.07605743, 0. ]), + 'frame': 460, + 'frame_number': 460, + 'framesequence': 458, + 'gaze_dir': array([ 0.98058069, 0.08272116, -0.17781658]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08272116, -0.17781658]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08272116, -0.17781658]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.963349979370832, + 'timestamp_carla': 11963, + 'timestamp_device': 11431, + 'timestamp_stream': 11.963349979370832, + 'transform': [array([2.07015443e+00, 3.80524284e-07, 1.81537622e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.03311984, -0.04035 , 9.19229889]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.44642448425293, + 'FR_Wheel_Angle': 35.06907653808594, + 'Location': array([18.89486122, -7.09792709, 0.04568646]), + 'Rotation': array([-1.4741528 , -5.82675552, 2.25301814]), + 'Velocity': array([ 0.87424403, 0.1885429 , -0.01552473]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 473.1383972167969, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.46743774e+01, 3.91385765e+01, -3.05175781e-05]), + 'frame': 461, + 'frame_number': 461, + 'framesequence': 459, + 'gaze_dir': array([ 0.98058069, 0.08502564, -0.17672625]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08502564, -0.17672625]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08502564, -0.17672625]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.97605487704277, + 'timestamp_carla': 11976, + 'timestamp_device': 11444, + 'timestamp_stream': 11.97605487704277, + 'transform': [array([2.08198690e+00, 3.83909651e-07, 1.81461335e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.12198445, -0.03329858, 11.05840302]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.61707305908203, + 'FR_Wheel_Angle': 41.27707290649414, + 'Location': array([19.05030632, -7.06876802, 0.04436318]), + 'Rotation': array([-1.47686446, -3.9676528 , 2.2213819 ]), + 'Velocity': array([ 0.83668 , 0.27653822, -0.00787668]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 473.83258056640625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.66462402e+01, 4.02879333e+01, 3.05175781e-05]), + 'frame': 462, + 'frame_number': 462, + 'framesequence': 460, + 'gaze_dir': array([ 0.98058069, 0.08731592, -0.17560597]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08731592, -0.17560597]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08731592, -0.17560597]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 11.98928777873516, + 'timestamp_carla': 11989, + 'timestamp_device': 11457, + 'timestamp_stream': 11.98928777873516, + 'transform': [array([2.09423757e+00, 3.87909665e-07, 1.81114196e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.20987757, -0.05337029, 10.952878 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.610082626342773, + 'FR_Wheel_Angle': 41.280494689941406, + 'Location': array([19.188591 , -7.03672552, 0.04372807]), + 'Rotation': array([-1.47933698, -2.19131494, 2.20814538]), + 'Velocity': array([ 0.82096541, 0.29984874, -0.00509545]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 474.5478515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.86394958e+01, 4.14355965e+01, 3.05175781e-05]), + 'frame': 463, + 'frame_number': 463, + 'framesequence': 461, + 'gaze_dir': array([ 0.98058069, 0.08976575, -0.17436638]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08976575, -0.17436638]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08976575, -0.17436638]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.002068877220154, + 'timestamp_carla': 12002, + 'timestamp_device': 11471, + 'timestamp_stream': 12.002068877220154, + 'transform': [array([2.10600114e+00, 3.93511584e-07, 1.81068422e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.27621609, -0.07537358, 10.85981274]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.624210357666016, + 'FR_Wheel_Angle': 41.28181838989258, + 'Location': array([19.32362938, -7.00073433, 0.04341843]), + 'Rotation': array([-1.48122895, -0.41436765, 2.19944763]), + 'Velocity': array([ 0.80208242, 0.32339698, -0.00289531]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 475.34161376953125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([90.7635498 , 42.66941452, 0. ]), + 'frame': 464, + 'frame_number': 464, + 'framesequence': 462, + 'gaze_dir': array([ 0.98058069, 0.09185165, -0.17327666]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09185165, -0.17327666]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09185165, -0.17327666]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.014714676886797, + 'timestamp_carla': 12014, + 'timestamp_device': 11483, + 'timestamp_stream': 12.014714676886797, + 'transform': [array([2.11855364e+00, 3.97269446e-07, 1.81144709e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.30474496, -0.09178257, 10.73561668]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.62855339050293, + 'FR_Wheel_Angle': 41.2818603515625, + 'Location': array([19.45648575, -6.96135807, 0.04324112]), + 'Rotation': array([-1.48260176, 1.34752202, 2.19328666]), + 'Velocity': array([ 0.78240228, 0.34418082, -0.0014225 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 476.04180908203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([92.73287964, 43.72525024, 0. ]), + 'frame': 465, + 'frame_number': 465, + 'framesequence': 463, + 'gaze_dir': array([ 0.98058069, 0.09409634, -0.17206803]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09409634, -0.17206803]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09409634, -0.17206803]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.028029076755047, + 'timestamp_carla': 12028, + 'timestamp_device': 11496, + 'timestamp_stream': 12.028029076755047, + 'transform': [array([2.13166904e+00, 4.02531441e-07, 1.80870050e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.33477882, -0.10643847, 10.65704441]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.63321304321289, + 'FR_Wheel_Angle': 41.283607482910156, + 'Location': array([19.57721329, -6.92258263, 0.04312268]), + 'Rotation': array([-1.48501277, 2.95791674, 2.18376565]), + 'Velocity': array([ 7.66606748e-01, 3.63510311e-01, -4.07085405e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 476.8211669921875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([94.87060547, 44.86714935, 0. ]), + 'frame': 466, + 'frame_number': 466, + 'framesequence': 464, + 'gaze_dir': array([ 0.98058069, 0.09615435, -0.17092651]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09615435, -0.17092651]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09615435, -0.17092651]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.04020307958126, + 'timestamp_carla': 12040, + 'timestamp_device': 11508, + 'timestamp_stream': 12.04020307958126, + 'transform': [array([2.14357734e+00, 4.06186871e-07, 1.81217189e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.35765558, -0.12593155, 10.50646114]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.636281967163086, + 'FR_Wheel_Angle': 41.28839111328125, + 'Location': array([19.70675278, -6.87679005, 0.04305901]), + 'Rotation': array([-1.48613977, 4.70430899, 2.17913795]), + 'Velocity': array([ 7.44151294e-01, 3.81464124e-01, -5.72242716e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 477.5591125488281, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.70179138e+01, 4.59194069e+01, -3.05175781e-05]), + 'frame': 467, + 'frame_number': 467, + 'framesequence': 465, + 'gaze_dir': array([ 0.98058069, 0.09836829, -0.16966204]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09836829, -0.16966204]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09836829, -0.16966204]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.052722178399563, + 'timestamp_carla': 12052, + 'timestamp_device': 11521, + 'timestamp_stream': 12.052722178399563, + 'transform': [array([2.15574050e+00, 4.07742192e-07, 1.81354524e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38473845, -0.15012333, 10.35075569]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.641551971435547, + 'FR_Wheel_Angle': 41.29071807861328, + 'Location': array([19.82752228, -6.83074713, 0.04302521]), + 'Rotation': array([-1.48743069, 6.34698486, 2.17445993]), + 'Velocity': array([ 7.21622467e-01, 3.96948725e-01, -6.19487721e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 478.3800048828125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([99.13809204, 47.05744934, 0. ]), + 'frame': 468, + 'frame_number': 468, + 'framesequence': 466, + 'gaze_dir': array([ 0.98058069, 0.10056544, -0.168369 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10056544, -0.168369 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10056544, -0.168369 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.06526267901063, + 'timestamp_carla': 12065, + 'timestamp_device': 11534, + 'timestamp_stream': 12.06526267901063, + 'transform': [array([2.16784477e+00, 4.09567576e-07, 1.81453698e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40024349, -0.16925055, 10.19786549]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.646808624267578, + 'FR_Wheel_Angle': 41.29804229736328, + 'Location': array([19.94557571, -6.78242731, 0.04302865]), + 'Rotation': array([-1.48861229, 7.96784735, 2.1699791 ]), + 'Velocity': array([ 6.99292719e-01, 4.11195666e-01, -1.52549736e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 479.2222595214844, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.01308075e+02, 4.81932220e+01, -3.05175781e-05]), + 'frame': 469, + 'frame_number': 469, + 'framesequence': 467, + 'gaze_dir': array([ 0.98058069, 0.10241133, -0.16725264]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10241133, -0.16725264]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10241133, -0.16725264]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.07731917873025, + 'timestamp_carla': 12077, + 'timestamp_device': 11545, + 'timestamp_stream': 12.07731917873025, + 'transform': [array([2.17940950e+00, 4.12915682e-07, 1.81751244e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.39744681, -0.1883231 , 9.96933651]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.654586791992188, + 'FR_Wheel_Angle': 41.30526351928711, + 'Location': array([20.07243347, -6.72554111, 0.04302021]), + 'Rotation': array([-1.48763561, 9.73777962, 2.17303109]), + 'Velocity': array([ 6.70399129e-01, 4.23047632e-01, -2.11548802e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 479.9515686035156, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([1.03344299e+02, 4.91525002e+01, 6.10351562e-05]), + 'frame': 470, + 'frame_number': 470, + 'framesequence': 468, + 'gaze_dir': array([ 0.98058069, 0.10490856, -0.16569768]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10490856, -0.16569768]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10490856, -0.16569768]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.091986179351807, + 'timestamp_carla': 12091, + 'timestamp_device': 11560, + 'timestamp_stream': 12.091986179351807, + 'transform': [array([2.19338036e+00, 4.14997174e-07, 1.80496217e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.71617877, -0.18714784, 9.33703709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67597007751465, + 'FR_Wheel_Angle': 41.31072998046875, + 'Location': array([20.1836319 , -6.67156792, 0.04146626]), + 'Rotation': array([-1.43133438, 11.25887871, 2.08649778]), + 'Velocity': array([ 0.61579275, 0.4143624 , -0.001253 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 480.97161865234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([105.65570068, 50.45806122, 0. ]), + 'frame': 471, + 'frame_number': 471, + 'framesequence': 469, + 'gaze_dir': array([ 0.98058069, 0.10754614, -0.16399802]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10754614, -0.16399802]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10754614, -0.16399802]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.107791177928448, + 'timestamp_carla': 12107, + 'timestamp_device': 11576, + 'timestamp_stream': 12.107791177928448, + 'transform': [array([2.20832205e+00, 4.25726057e-07, 1.78623199e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.65523958, -0.11201791, 9.57527637]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.667369842529297, + 'FR_Wheel_Angle': 41.315059661865234, + 'Location': array([20.29580116, -6.61525393, 0.04219712]), + 'Rotation': array([-1.46276009, 12.84664726, 2.12707257]), + 'Velocity': array([0.62086594, 0.44234172, 0.00316546]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 482.0890197753906, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.08318817e+02, 5.18468399e+01, -3.05175781e-05]), + 'frame': 472, + 'frame_number': 472, + 'framesequence': 470, + 'gaze_dir': array([ 0.98058069, 0.1098315 , -0.16247636]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1098315 , -0.16247636]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1098315 , -0.16247636]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.121593479067087, + 'timestamp_carla': 12121, + 'timestamp_device': 11590, + 'timestamp_stream': 12.121593479067087, + 'transform': [array([2.22128224e+00, 4.26908827e-07, 1.78611756e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 6.4715395 , -3.34826899, 8.92944813]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.70328712463379, + 'FR_Wheel_Angle': 41.31730651855469, + 'Location': array([ 2.04063511e+01, -6.55454206e+00, 1.86891221e-02]), + 'Rotation': array([-0.56753403, 14.42428684, 0.70018482]), + 'Velocity': array([ 0.54701698, 0.36858356, -0.11979112]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 483.09259033203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.10950470e+02, 5.30588074e+01, -3.05175781e-05]), + 'frame': 473, + 'frame_number': 473, + 'framesequence': 471, + 'gaze_dir': array([ 0.98058069, 0.11177327, -0.1611467 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11177327, -0.1611467 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11177327, -0.1611467 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.134534478187561, + 'timestamp_carla': 12134, + 'timestamp_device': 11602, + 'timestamp_stream': 12.134534478187561, + 'transform': [array([2.23335910e+00, 4.31951946e-07, 1.79069513e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 1.42865229, -0.79706353, 9.27898216]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.679500579833984, + 'FR_Wheel_Angle': 41.32545471191406, + 'Location': array([ 2.05189247e+01, -6.49084282e+00, 1.00721028e-02]), + 'Rotation': array([-0.18927136, 16.0124855 , 0.20027708]), + 'Velocity': array([ 0.57604384, 0.44511783, -0.04125938]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 483.9754943847656, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([1.13246277e+02, 5.40955505e+01, 3.05175781e-05]), + 'frame': 474, + 'frame_number': 474, + 'framesequence': 472, + 'gaze_dir': array([ 0.98058069, 0.11401829, -0.15956615]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11401829, -0.15956615]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11401829, -0.15956615]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.147899478673935, + 'timestamp_carla': 12147, + 'timestamp_device': 11616, + 'timestamp_stream': 12.147899478673935, + 'transform': [array([2.24575567e+00, 4.37656297e-07, 1.79241179e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3138195, -0.4117648, 9.1655817]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.68279266357422, + 'FR_Wheel_Angle': 41.33293533325195, + 'Location': array([ 2.06162796e+01, -6.43381834e+00, 6.44482113e-03]), + 'Rotation': array([-0.08902468, 17.41382408, 0.01899224]), + 'Velocity': array([ 0.56100339, 0.46198505, -0.02374229]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 485.0300598144531, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([115.64785767, 55.30231857, 0. ]), + 'frame': 475, + 'frame_number': 475, + 'framesequence': 473, + 'gaze_dir': array([ 0.98058069, 0.11608303, -0.15807042]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11608303, -0.15807042]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11608303, -0.15807042]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.160458378493786, + 'timestamp_carla': 12160, + 'timestamp_device': 11629, + 'timestamp_stream': 12.160458378493786, + 'transform': [array([2.25733733e+00, 4.41288449e-07, 1.79779052e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.20409125, -0.29934856, 8.92372799]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.689937591552734, + 'FR_Wheel_Angle': 41.34153366088867, + 'Location': array([ 2.07221851e+01, -6.36714172e+00, 4.16042795e-03]), + 'Rotation': array([-0.04596034, 18.97694778, -0.06271361]), + 'Velocity': array([ 0.53421384, 0.4684816 , -0.01207555]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 486.0318298339844, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([118.02175903, 56.42007446, 0. ]), + 'frame': 476, + 'frame_number': 476, + 'framesequence': 474, + 'gaze_dir': array([ 0.98058069, 0.11828456, -0.15642983]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11828456, -0.15642983]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11828456, -0.15642983]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.174669779837132, + 'timestamp_carla': 12174, + 'timestamp_device': 11643, + 'timestamp_stream': 12.174669779837132, + 'transform': [array([2.27143335e+00, 4.44888030e-07, 1.78844447e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40642408, -0.28414163, 8.70842552]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.696828842163086, + 'FR_Wheel_Angle': 41.35123825073242, + 'Location': array([ 2.08231754e+01, -6.30035830e+00, 3.03471088e-03]), + 'Rotation': array([-0.03131641, 20.48701477, -0.09750365]), + 'Velocity': array([ 0.50899589, 0.47232935, -0.0060805 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 487.13604736328125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.20429947e+02, 5.76206894e+01, -3.05175781e-05]), + 'frame': 477, + 'frame_number': 477, + 'framesequence': 475, + 'gaze_dir': array([ 0.98058069, 0.12015317, -0.15499917]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12015317, -0.15499917]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12015317, -0.15499917]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.187527779489756, + 'timestamp_carla': 12187, + 'timestamp_device': 11655, + 'timestamp_stream': 12.187527779489756, + 'transform': [array([2.28409052e+00, 4.47439817e-07, 1.78928371e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.48911399, -0.2978949 , 8.48460007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.702350616455078, + 'FR_Wheel_Angle': 41.359004974365234, + 'Location': array([ 2.09225044e+01, -6.23111725e+00, 2.43275170e-03]), + 'Rotation': array([-0.02597521, 21.99654007, -0.11090088]), + 'Velocity': array([ 0.48327908, 0.4738113 , -0.00350564]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 488.10064697265625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.22932434e+02, 5.86468658e+01, -3.05175781e-05]), + 'frame': 478, + 'frame_number': 478, + 'framesequence': 476, + 'gaze_dir': array([ 0.98058069, 0.12215788, -0.15342417]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12215788, -0.15342417]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12215788, -0.15342417]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.200322978198528, + 'timestamp_carla': 12200, + 'timestamp_device': 11668, + 'timestamp_stream': 12.200322978198528, + 'transform': [array([2.29659653e+00, 4.54750676e-07, 1.79061887e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.51525819, -0.31679058, 8.24905872]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.710351943969727, + 'FR_Wheel_Angle': 41.36564254760742, + 'Location': array([ 2.10175076e+01, -6.16181946e+00, 2.16637133e-03]), + 'Rotation': array([-0.02377589, 23.46067238, -0.11312865]), + 'Velocity': array([ 0.45749518, 0.47285101, -0.00163879]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 489.1687927246094, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.25407684e+02, 5.97558517e+01, -3.05175781e-05]), + 'frame': 479, + 'frame_number': 479, + 'framesequence': 477, + 'gaze_dir': array([ 0.98058069, 0.12414209, -0.15182315]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12414209, -0.15182315]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12414209, -0.15182315]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.213019479066133, + 'timestamp_carla': 12213, + 'timestamp_device': 11681, + 'timestamp_stream': 12.213019479066133, + 'transform': [array([2.30892062e+00, 4.60860150e-07, 1.79244985e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.54437715, -0.34068716, 8.09183693]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.717315673828125, + 'FR_Wheel_Angle': 41.370269775390625, + 'Location': array([ 2.11011543e+01, -6.09957981e+00, 2.03815941e-03]), + 'Rotation': array([-2.44179256e-02, 2.47501888e+01, -1.25915542e-01]), + 'Velocity': array([ 0.4380326 , 0.47406131, -0.0005563 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 490.2595520019531, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([127.89329529, 60.86186981, 0. ]), + 'frame': 480, + 'frame_number': 480, + 'framesequence': 478, + 'gaze_dir': array([ 0.98058069, 0.1264053 , -0.14994408]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1264053 , -0.14994408]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1264053 , -0.14994408]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.227802477777004, + 'timestamp_carla': 12227, + 'timestamp_device': 11696, + 'timestamp_stream': 12.227802477777004, + 'transform': [array([2.32316375e+00, 4.67412008e-07, 1.78169250e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.53707111, -0.3557891 , 7.8502717 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7237606048584, + 'FR_Wheel_Angle': 41.379486083984375, + 'Location': array([ 2.11936245e+01, -6.02600813e+00, 1.95290090e-03]), + 'Rotation': array([-2.34616976e-02, 2.62185497e+01, -1.22039773e-01]), + 'Velocity': array([ 4.12631303e-01, 4.70741302e-01, -4.57320217e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 491.54595947265625, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([130.58233643, 62.13404083, 0. ]), + 'frame': 481, + 'frame_number': 481, + 'framesequence': 479, + 'gaze_dir': array([ 0.98058069, 0.12849219, -0.14815965]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12849219, -0.14815965]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12849219, -0.14815965]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.241601277142763, + 'timestamp_carla': 12241, + 'timestamp_device': 11710, + 'timestamp_stream': 12.241601277142763, + 'transform': [array([2.33636475e+00, 4.73065143e-07, 1.78005209e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.54332298, -0.37806839, 7.64643908]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.73061752319336, + 'FR_Wheel_Angle': 41.38976287841797, + 'Location': array([ 2.12765961e+01, -5.95822620e+00, 1.91551680e-03]), + 'Rotation': array([-2.35573202e-02, 2.75435848e+01, -1.24694832e-01]), + 'Velocity': array([ 3.90855312e-01, 4.67842937e-01, -2.33035084e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 492.7718505859375, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([133.39543152, 63.31736755, 0. ]), + 'frame': 482, + 'frame_number': 482, + 'framesequence': 480, + 'gaze_dir': array([ 0.98058069, 0.13069995, -0.14621575]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13069995, -0.14621575]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13069995, -0.14621575]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.256635576486588, + 'timestamp_carla': 12256, + 'timestamp_device': 11725, + 'timestamp_stream': 12.256635576486588, + 'transform': [array([2.35064363e+00, 4.79039556e-07, 1.77089684e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.54474455, -0.39727533, 7.44485044]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.737407684326172, + 'FR_Wheel_Angle': 41.39759063720703, + 'Location': array([ 2.13564453e+01, -5.89054775e+00, 1.90128793e-03]), + 'Rotation': array([-2.37144157e-02, 2.88354015e+01, -1.26983643e-01]), + 'Velocity': array([3.69875342e-01, 4.64081943e-01, 1.61647790e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 494.115966796875, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([1.36237671e+02, 6.45809555e+01, 3.05175781e-05]), + 'frame': 483, + 'frame_number': 483, + 'framesequence': 481, + 'gaze_dir': array([ 0.98058069, 0.13258974, -0.14450428]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13258974, -0.14450428]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13258974, -0.14450428]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.27049557864666, + 'timestamp_carla': 12270, + 'timestamp_device': 11738, + 'timestamp_stream': 12.27049557864666, + 'transform': [array([2.36371779e+00, 4.84566954e-07, 1.77181244e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.551624 , -0.41988239, 7.2539382 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.743806838989258, + 'FR_Wheel_Angle': 41.40345001220703, + 'Location': array([ 2.14321022e+01, -5.82453823e+00, 1.88908097e-03]), + 'Rotation': array([-2.41652075e-02, 3.00704422e+01, -1.31286606e-01]), + 'Velocity': array([ 3.50248218e-01, 4.59989458e-01, -6.65235493e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 495.30413818359375, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([1.39011536e+02, 6.56722717e+01, 6.10351562e-05]), + 'frame': 484, + 'frame_number': 484, + 'framesequence': 482, + 'gaze_dir': array([ 0.98058069, 0.13445698, -0.14276852]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13445698, -0.14276852]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13445698, -0.14276852]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.283196177333593, + 'timestamp_carla': 12283, + 'timestamp_device': 11751, + 'timestamp_stream': 12.283196177333593, + 'transform': [array([2.37562513e+00, 4.87477337e-07, 1.77883147e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55563152, -0.44173861, 7.05959463]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.750329971313477, + 'FR_Wheel_Angle': 41.410404205322266, + 'Location': array([ 2.15049992e+01, -5.75892544e+00, 1.88858504e-03]), + 'Rotation': array([-2.45067179e-02, 3.12745628e+01, -1.34216309e-01]), + 'Velocity': array([ 3.31061244e-01, 4.54861909e-01, -4.39643873e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 496.516845703125, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 1.41692093e+02, 6.67601852e+01, -3.05175781e-05]), + 'frame': 485, + 'frame_number': 485, + 'framesequence': 483, + 'gaze_dir': array([ 0.98058069, 0.13630161, -0.1410085 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13630161, -0.1410085 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13630161, -0.1410085 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.296509377658367, + 'timestamp_carla': 12296, + 'timestamp_device': 11764, + 'timestamp_stream': 12.296509377658367, + 'transform': [array([2.38803077e+00, 4.94131655e-07, 1.78176875e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55684656, -0.46142289, 6.86875486]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.756763458251953, + 'FR_Wheel_Angle': 41.4181022644043, + 'Location': array([ 2.15748863e+01, -5.69419050e+00, 1.89720630e-03]), + 'Rotation': array([-2.48072464e-02, 3.24408722e+01, -1.37237549e-01]), + 'Velocity': array([3.12745363e-01, 4.49137956e-01, 2.81310087e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 497.7533264160156, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([1.44282623e+02, 6.78446121e+01, 3.05175781e-05]), + 'frame': 486, + 'frame_number': 486, + 'framesequence': 484, + 'gaze_dir': array([ 0.98058069, 0.1381231 , -0.13922477]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1381231 , -0.13922477]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1381231 , -0.13922477]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.309344477951527, + 'timestamp_carla': 12309, + 'timestamp_device': 11777, + 'timestamp_stream': 12.309344477951527, + 'transform': [array([2.39991975e+00, 5.00627664e-07, 1.78665156e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.58448541, -0.49691799, 6.71843958]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.761646270751953, + 'FR_Wheel_Angle': 41.42597961425781, + 'Location': array([ 2.16372986e+01, -5.63631296e+00, 1.87611103e-03]), + 'Rotation': array([-2.64260005e-02, 3.34733505e+01, -1.50573745e-01]), + 'Velocity': array([ 0.2976808 , 0.44500971, -0.0005959 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 499.01226806640625, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([146.94859314, 68.92515564, 0. ]), + 'frame': 487, + 'frame_number': 487, + 'framesequence': 485, + 'gaze_dir': array([ 0.98058069, 0.13992137, -0.13741739]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13992137, -0.13741739]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13992137, -0.13741739]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.321694277226925, + 'timestamp_carla': 12321, + 'timestamp_device': 11790, + 'timestamp_stream': 12.321694277226925, + 'transform': [array([2.41129518e+00, 5.05996695e-07, 1.79294578e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.60670441, -0.53379422, 6.55963516]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76841163635254, + 'FR_Wheel_Angle': 41.435787200927734, + 'Location': array([ 2.16965904e+01, -5.58033848e+00, 1.92303176e-03]), + 'Rotation': array([-2.77032461e-02, 3.44584389e+01, -1.60705566e-01]), + 'Velocity': array([2.82751501e-01, 4.39684242e-01, 2.73704518e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 500.2947082519531, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 1.49589371e+02, 7.00019608e+01, -3.05175781e-05]), + 'frame': 488, + 'frame_number': 488, + 'framesequence': 486, + 'gaze_dir': array([ 0.98058069, 0.14156027, -0.13572846]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14156027, -0.13572846]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14156027, -0.13572846]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.334429379552603, + 'timestamp_carla': 12334, + 'timestamp_device': 11802, + 'timestamp_stream': 12.334429379552603, + 'transform': [array([2.42393613e+00, 5.10406551e-07, 1.79122924e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.57612592, -0.53239024, 6.34192514]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.774394989013672, + 'FR_Wheel_Angle': 41.44142532348633, + 'Location': array([ 2.17622547e+01, -5.51365995e+00, 1.91593647e-03]), + 'Rotation': array([-2.62074340e-02, 3.55986290e+01, -1.50146499e-01]), + 'Velocity': array([2.64544129e-01, 4.30396974e-01, 4.27532177e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 501.499267578125, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 1.52090591e+02, 7.09924088e+01, -6.10351562e-05]), + 'frame': 489, + 'frame_number': 489, + 'framesequence': 487, + 'gaze_dir': array([ 0.98058069, 0.14344652, -0.13373339]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14344652, -0.13373339]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14344652, -0.13373339]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.348222978413105, + 'timestamp_carla': 12348, + 'timestamp_device': 11816, + 'timestamp_stream': 12.348222978413105, + 'transform': [array([2.43752050e+00, 5.12306372e-07, 1.78432465e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.59234101, -0.55996674, 6.19743586]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.780447006225586, + 'FR_Wheel_Angle': 41.45214080810547, + 'Location': array([ 2.18172798e+01, -5.45933723e+00, 1.90773478e-03]), + 'Rotation': array([-2.77032461e-02, 3.65249062e+01, -1.62475571e-01]), + 'Velocity': array([2.51489520e-01, 4.24900055e-01, 8.21924186e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 502.9281311035156, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([1.54972748e+02, 7.21433182e+01, 3.05175781e-05]), + 'frame': 490, + 'frame_number': 490, + 'framesequence': 488, + 'gaze_dir': array([ 0.98058069, 0.14517283, -0.13185741]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14517283, -0.13185741]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14517283, -0.13185741]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.361226979643106, + 'timestamp_carla': 12361, + 'timestamp_device': 11829, + 'timestamp_stream': 12.361226979643106, + 'transform': [array([2.45023251e+00, 5.18252875e-07, 1.78375235e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.58501679, -0.5727433 , 6.01910591]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7863826751709, + 'FR_Wheel_Angle': 41.458248138427734, + 'Location': array([ 2.18746777e+01, -5.39955568e+00, 1.91261759e-03]), + 'Rotation': array([-2.76486035e-02, 3.75222549e+01, -1.63024917e-01]), + 'Velocity': array([2.36765489e-01, 4.16937321e-01, 1.25832550e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 504.27825927734375, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([1.57860519e+02, 7.32075424e+01, 3.05175781e-05]), + 'frame': 491, + 'frame_number': 491, + 'framesequence': 489, + 'gaze_dir': array([ 0.98058069, 0.14687473, -0.129959 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14687473, -0.129959 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14687473, -0.129959 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.373772878199816, + 'timestamp_carla': 12373, + 'timestamp_device': 11842, + 'timestamp_stream': 12.373772878199816, + 'transform': [array([2.46241260e+00, 5.24609163e-07, 1.78592675e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55259877, -0.56821954, 5.80625105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.792301177978516, + 'FR_Wheel_Angle': 41.4633674621582, + 'Location': array([ 2.1934248e+01, -5.3342576e+00, 1.9151353e-03]), + 'Rotation': array([-2.59410571e-02, 3.85909996e+01, -1.50573745e-01]), + 'Velocity': array([2.20543310e-01, 4.06327546e-01, 3.00855638e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 505.653076171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([160.68850708, 74.26769257, 0. ]), + 'frame': 492, + 'frame_number': 492, + 'framesequence': 490, + 'gaze_dir': array([ 0.98058069, 0.14842351, -0.12818733]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14842351, -0.12818733]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14842351, -0.12818733]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.386434279382229, + 'timestamp_carla': 12386, + 'timestamp_device': 11854, + 'timestamp_stream': 12.386434279382229, + 'transform': [array([2.47462416e+00, 5.33494017e-07, 1.78752898e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55705029, -0.58914977, 5.64708519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.797590255737305, + 'FR_Wheel_Angle': 41.473716735839844, + 'Location': array([ 2.19864273e+01, -5.27829933e+00, 1.90266129e-03]), + 'Rotation': array([-2.65489444e-02, 3.95024223e+01, -1.55822769e-01]), + 'Velocity': array([2.07911700e-01, 3.98695320e-01, 1.10230445e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 506.9434509277344, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.63367584e+02, 7.52423630e+01, -6.10351562e-05]), + 'frame': 493, + 'frame_number': 493, + 'framesequence': 491, + 'gaze_dir': array([ 0.98058069, 0.15007742, -0.12624696]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15007742, -0.12624696]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15007742, -0.12624696]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.39885587990284, + 'timestamp_carla': 12398, + 'timestamp_device': 11867, + 'timestamp_stream': 12.39885587990284, + 'transform': [array([2.48652864e+00, 5.34262369e-07, 1.79019920e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.57634664, -0.62141311, 5.51480007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.803020477294922, + 'FR_Wheel_Angle': 41.47856140136719, + 'Location': array([ 2.20337257e+01, -5.22817755e+00, 1.90792559e-03]), + 'Rotation': array([-2.82633211e-02, 4.03130455e+01, -1.70043916e-01]), + 'Velocity': array([1.97284698e-01, 3.92404974e-01, 3.78394121e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 508.3639831542969, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.66197159e+02, 7.62939835e+01, -3.05175781e-05]), + 'frame': 494, + 'frame_number': 494, + 'framesequence': 492, + 'gaze_dir': array([ 0.98058069, 0.15170585, -0.12428541]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15170585, -0.12428541]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15170585, -0.12428541]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.411762077361345, + 'timestamp_carla': 12411, + 'timestamp_device': 11880, + 'timestamp_stream': 12.411762077361345, + 'transform': [array([2.49881864e+00, 5.43226349e-07, 1.79027556e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.5611918 , -0.63007265, 5.33261204]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.809120178222656, + 'FR_Wheel_Angle': 41.48713302612305, + 'Location': array([ 2.20849361e+01, -5.17007303e+00, 1.89888477e-03]), + 'Rotation': array([-2.72797737e-02, 4.12349663e+01, -1.62841797e-01]), + 'Velocity': array([1.84280887e-01, 3.82519722e-01, 9.78898970e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 509.8084411621094, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.69023102e+02, 7.73409500e+01, -6.10351562e-05]), + 'frame': 495, + 'frame_number': 495, + 'framesequence': 493, + 'gaze_dir': array([ 0.98058069, 0.15318632, -0.12245603]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15318632, -0.12245603]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15318632, -0.12245603]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.424392778426409, + 'timestamp_carla': 12424, + 'timestamp_device': 11892, + 'timestamp_stream': 12.424392778426409, + 'transform': [array([2.51077223e+00, 5.52101824e-07, 1.79191586e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55366182, -0.6344353 , 5.18337154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81405258178711, + 'FR_Wheel_Angle': 41.496097564697266, + 'Location': array([ 2.21323109e+01, -5.11648321e+00, 1.89808360e-03]), + 'Rotation': array([-2.77988687e-02, 4.20777283e+01, -1.68395981e-01]), + 'Velocity': array([ 1.73564151e-01, 3.74451905e-01, -6.64758700e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 511.1623840332031, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.71785309e+02, 7.83031158e+01, -3.05175781e-05]), + 'frame': 496, + 'frame_number': 496, + 'framesequence': 494, + 'gaze_dir': array([ 0.98058069, 0.15488562, -0.1202995 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15488562, -0.1202995 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15488562, -0.1202995 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.43779867887497, + 'timestamp_carla': 12437, + 'timestamp_device': 11906, + 'timestamp_stream': 12.43779867887497, + 'transform': [array([2.52338028e+00, 5.59659497e-07, 1.78943633e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.53409255, -0.63899255, 5.00324488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81903076171875, + 'FR_Wheel_Angle': 41.502933502197266, + 'Location': array([ 2.21808434e+01, -5.05885744e+00, 1.89747324e-03]), + 'Rotation': array([-2.66445670e-02, 4.29701691e+01, -1.59545884e-01]), + 'Velocity': array([1.61518663e-01, 3.64031255e-01, 1.73316002e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 512.7680053710938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([1.74798767e+02, 7.94204330e+01, 6.10351562e-05]), + 'frame': 497, + 'frame_number': 497, + 'framesequence': 495, + 'gaze_dir': array([ 0.98058069, 0.15643644, -0.11827579]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15643644, -0.11827579]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15643644, -0.11827579]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.451040476560593, + 'timestamp_carla': 12451, + 'timestamp_device': 11919, + 'timestamp_stream': 12.451040476560593, + 'transform': [array([2.53575659e+00, 5.60250896e-07, 1.78859709e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55907303, -0.67883712, 4.88132334]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.82297134399414, + 'FR_Wheel_Angle': 41.51242446899414, + 'Location': array([ 2.22222137e+01, -5.01264191e+00, 1.89651956e-03]), + 'Rotation': array([-2.84067560e-02, 4.36851044e+01, -1.74072236e-01]), + 'Velocity': array([ 0.15285856, 0.3573769 , -0.00080334]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 514.283447265625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.77775726e+02, 8.04527206e+01, -3.05175781e-05]), + 'frame': 498, + 'frame_number': 498, + 'framesequence': 496, + 'gaze_dir': array([ 0.98058069, 0.15807693, -0.11607417]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15807693, -0.11607417]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15807693, -0.11607417]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.464695677161217, + 'timestamp_carla': 12464, + 'timestamp_device': 11933, + 'timestamp_stream': 12.464695677161217, + 'transform': [array([2.54843950e+00, 5.73340628e-07, 1.78581232e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55931437, -0.70387703, 4.73615503]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.827964782714844, + 'FR_Wheel_Angle': 41.51224136352539, + 'Location': array([ 2.22636967e+01, -4.96431494e+00, 1.95698254e-03]), + 'Rotation': array([-2.84682270e-02, 4.44222908e+01, -1.73736542e-01]), + 'Velocity': array([1.43381074e-01, 3.48779261e-01, 1.81469906e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 515.9424438476562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([1.80891983e+02, 8.15586395e+01, 3.05175781e-05]), + 'frame': 499, + 'frame_number': 499, + 'framesequence': 497, + 'gaze_dir': array([ 0.98058069, 0.15957244, -0.1140095 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15957244, -0.1140095 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15957244, -0.1140095 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.477720476686954, + 'timestamp_carla': 12477, + 'timestamp_device': 11946, + 'timestamp_stream': 12.477720476686954, + 'transform': [array([2.56046462e+00, 5.82486223e-07, 1.78726192e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55689293, -0.71687734, 4.60124731]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8323974609375, + 'FR_Wheel_Angle': 41.52054214477539, + 'Location': array([ 2.23037910e+01, -4.91805887e+00, 1.93226337e-03]), + 'Rotation': array([-2.86253206e-02, 4.51242943e+01, -1.76116899e-01]), + 'Velocity': array([ 1.34917840e-01, 3.40636641e-01, -3.10854899e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 517.5078125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.83933044e+02, 8.25800323e+01, -3.05175781e-05]), + 'frame': 500, + 'frame_number': 500, + 'framesequence': 498, + 'gaze_dir': array([ 0.98058069, 0.16092902, -0.11208645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16092902, -0.11208645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16092902, -0.11208645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.490181479603052, + 'timestamp_carla': 12490, + 'timestamp_device': 11958, + 'timestamp_stream': 12.490181479603052, + 'transform': [array([2.57283616e+00, 5.85988005e-07, 1.79023738e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.55093729, -0.72752339, 4.46905088]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.83681297302246, + 'FR_Wheel_Angle': 41.52772521972656, + 'Location': array([ 2.23426991e+01, -4.87263107e+00, 1.93268294e-03]), + 'Rotation': array([-2.87141129e-02, 4.58078995e+01, -1.77185029e-01]), + 'Velocity': array([ 1.26830563e-01, 3.32477868e-01, -2.43186951e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 518.9750366210938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([186.79690552, 83.51818848, 0. ]), + 'frame': 501, + 'frame_number': 501, + 'framesequence': 499, + 'gaze_dir': array([ 0.98058069, 0.16237256, -0.10998489]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16237256, -0.10998489]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16237256, -0.10998489]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.502828978002071, + 'timestamp_carla': 12502, + 'timestamp_device': 11971, + 'timestamp_stream': 12.502828978002071, + 'transform': [array([2.58530116e+00, 5.87920510e-07, 1.79214473e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.51896238, -0.71059334, 4.31712961]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.841909408569336, + 'FR_Wheel_Angle': 41.53218078613281, + 'Location': array([ 2.23824749e+01, -4.82381535e+00, 1.92314619e-03]), + 'Rotation': array([-2.71226801e-02, 4.65327835e+01, -1.65313721e-01]), + 'Velocity': array([1.18284412e-01, 3.22625726e-01, 2.60829926e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 520.5881958007812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([189.86056519, 84.52927399, 0. ]), + 'frame': 502, + 'frame_number': 502, + 'framesequence': 500, + 'gaze_dir': array([ 0.98058069, 0.16378857, -0.10786488]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16378857, -0.10786488]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16378857, -0.10786488]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.515701476484537, + 'timestamp_carla': 12515, + 'timestamp_device': 11984, + 'timestamp_stream': 12.515701476484537, + 'transform': [array([2.59789634e+00, 5.92064907e-07, 1.79290771e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.5022524 , -0.70279628, 4.18328094]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.84632110595703, + 'FR_Wheel_Angle': 41.53709030151367, + 'Location': array([ 2.24205418e+01, -4.77740383e+00, 1.90678111e-03]), + 'Rotation': array([-2.68563032e-02, 4.72161064e+01, -1.63757280e-01]), + 'Velocity': array([1.10782541e-01, 3.13973367e-01, 1.72471991e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 522.2255249023438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.92961029e+02, 8.55346222e+01, -3.05175781e-05]), + 'frame': 503, + 'frame_number': 503, + 'framesequence': 501, + 'gaze_dir': array([ 0.98058069, 0.16517697, -0.1057265 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16517697, -0.1057265 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16517697, -0.1057265 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.529262077063322, + 'timestamp_carla': 12529, + 'timestamp_device': 11997, + 'timestamp_stream': 12.529262077063322, + 'transform': [array([2.61106968e+00, 6.00041687e-07, 1.79008476e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.48755744, -0.70073825, 4.04985952]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.850753784179688, + 'FR_Wheel_Angle': 41.543758392333984, + 'Location': array([ 2.24577103e+01, -4.73138189e+00, 1.89644331e-03]), + 'Rotation': array([-2.65216231e-02, 4.78875580e+01, -1.61437988e-01]), + 'Velocity': array([0.10351149, 0.30521971, 0.00046225]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 523.8873291015625, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 1.96102295e+02, 8.65341721e+01, -6.10351562e-05]), + 'frame': 504, + 'frame_number': 504, + 'framesequence': 502, + 'gaze_dir': array([ 0.98058069, 0.16653737, -0.10357041]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16653737, -0.10357041]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16653737, -0.10357041]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.542068779468536, + 'timestamp_carla': 12542, + 'timestamp_device': 12010, + 'timestamp_stream': 12.542068779468536, + 'transform': [array([2.62342548e+00, 6.03543413e-07, 1.79210654e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.51296598, -0.73827946, 3.95632529]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.85377311706543, + 'FR_Wheel_Angle': 41.54718017578125, + 'Location': array([ 2.24910355e+01, -4.69338560e+00, 1.92165852e-03]), + 'Rotation': array([-2.90556233e-02, 4.84406433e+01, -1.82006836e-01]), + 'Velocity': array([9.80423987e-02, 2.99399555e-01, 1.59707066e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 525.5729370117188, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([199.32849121, 87.52757263, 0. ]), + 'frame': 505, + 'frame_number': 505, + 'framesequence': 503, + 'gaze_dir': array([ 0.98058069, 0.16786975, -0.10139664]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16786975, -0.10139664]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16786975, -0.10139664]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.555485777556896, + 'timestamp_carla': 12555, + 'timestamp_device': 12023, + 'timestamp_stream': 12.555485777556896, + 'transform': [array([2.63628340e+00, 6.12488805e-07, 1.79080956e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.51591742, -0.77148122, 3.83026624]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.858028411865234, + 'FR_Wheel_Angle': 41.558738708496094, + 'Location': array([ 2.25254517e+01, -4.65181255e+00, 1.91376207e-03]), + 'Rotation': array([-2.86253206e-02, 4.90404129e+01, -1.77551270e-01]), + 'Velocity': array([9.13086906e-02, 2.91017234e-01, 1.08880995e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 527.2843017578125, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([2.02501892e+02, 8.85151215e+01, 3.05175781e-05]), + 'frame': 506, + 'frame_number': 506, + 'framesequence': 504, + 'gaze_dir': array([ 0.98058069, 0.16917363, -0.09920591]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16917363, -0.09920591]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16917363, -0.09920591]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.568390376865864, + 'timestamp_carla': 12568, + 'timestamp_device': 12036, + 'timestamp_stream': 12.568390376865864, + 'transform': [array([2.64857078e+00, 6.21466711e-07, 1.79264066e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.50477755, -0.77044821, 3.71512079]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.86182975769043, + 'FR_Wheel_Angle': 41.56089782714844, + 'Location': array([ 2.25586338e+01, -4.61167431e+00, 1.92299357e-03]), + 'Rotation': array([-2.83589438e-02, 4.96142807e+01, -1.76727280e-01]), + 'Velocity': array([8.55768248e-02, 2.83192486e-01, 3.08513631e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 529.0197143554688, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 2.05752899e+02, 8.94962387e+01, -3.05175781e-05]), + 'frame': 507, + 'frame_number': 507, + 'framesequence': 505, + 'gaze_dir': array([ 0.98058069, 0.17044902, -0.09699824]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17044902, -0.09699824]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17044902, -0.09699824]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.581178579479456, + 'timestamp_carla': 12581, + 'timestamp_device': 12049, + 'timestamp_stream': 12.581178579479456, + 'transform': [array([2.66067195e+00, 6.25410905e-07, 1.79485313e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.51313365, -0.79036272, 3.61999154]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.865568161010742, + 'FR_Wheel_Angle': 41.5635986328125, + 'Location': array([ 2.25897999e+01, -4.57576609e+00, 1.93096639e-03]), + 'Rotation': array([-2.96703409e-02, 5.01254463e+01, -1.88049272e-01]), + 'Velocity': array([8.07498321e-02, 2.76836604e-01, 2.78902044e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 530.7807006835938, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([208.97564697, 90.47109985, 0. ]), + 'frame': 508, + 'frame_number': 508, + 'framesequence': 506, + 'gaze_dir': array([ 0.98058069, 0.1716955 , -0.09477435]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1716955 , -0.09477435]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1716955 , -0.09477435]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.593684580177069, + 'timestamp_carla': 12593, + 'timestamp_device': 12062, + 'timestamp_stream': 12.593684580177069, + 'transform': [array([2.67243505e+00, 6.33317825e-07, 1.79809565e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.50747859, -0.79523635, 3.51446533]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.727506637573242, + 'FR_Wheel_Angle': 41.66121292114258, + 'Location': array([ 2.26212883e+01, -4.53809261e+00, 1.94279186e-03]), + 'Rotation': array([-2.99640391e-02, 5.06573601e+01, -1.91009492e-01]), + 'Velocity': array([7.57289603e-02, 2.69566506e-01, 9.77802265e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 532.5665893554688, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([212.20785522, 91.4393158 , 0. ]), + 'frame': 509, + 'frame_number': 509, + 'framesequence': 507, + 'gaze_dir': array([ 0.98058069, 0.17282043, -0.09270722]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17282043, -0.09270722]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17282043, -0.09270722]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.605875078588724, + 'timestamp_carla': 12605, + 'timestamp_device': 12074, + 'timestamp_stream': 12.605875078588724, + 'transform': [array([2.68383574e+00, 6.40516930e-07, 1.80221559e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.47799805, -0.78417057, 3.38727832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8726863861084, + 'FR_Wheel_Angle': 41.57949447631836, + 'Location': array([ 2.26535072e+01, -4.49765682e+00, 1.87424175e-03]), + 'Rotation': array([-2.75598112e-02, 5.12248383e+01, -1.71508789e-01]), + 'Velocity': array([7.00570419e-02, 2.60477126e-01, 1.37290946e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 534.23779296875, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 2.15276367e+02, 9.23272476e+01, -6.10351562e-05]), + 'frame': 510, + 'frame_number': 510, + 'framesequence': 508, + 'gaze_dir': array([ 0.98058069, 0.17401104, -0.09045269]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17401104, -0.09045269]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17401104, -0.09045269]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.618764076381922, + 'timestamp_carla': 12618, + 'timestamp_device': 12087, + 'timestamp_stream': 12.618764076381922, + 'transform': [array([2.69581962e+00, 6.46998956e-07, 1.80240627e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.49187008, -0.80049288, 3.30807567]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.875802993774414, + 'FR_Wheel_Angle': 41.58115005493164, + 'Location': array([ 2.26820889e+01, -4.46545744e+00, 1.94481364e-03]), + 'Rotation': array([-2.97318120e-02, 5.16721420e+01, -1.90368623e-01]), + 'Velocity': array([ 6.64283633e-02, 2.55098999e-01, -4.52661516e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 536.0721435546875, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([218.49343872, 93.28253174, 0. ]), + 'frame': 511, + 'frame_number': 511, + 'framesequence': 509, + 'gaze_dir': array([ 0.98058069, 0.17508391, -0.08835809]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17508391, -0.08835809]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17508391, -0.08835809]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.631462179124355, + 'timestamp_carla': 12631, + 'timestamp_device': 12099, + 'timestamp_stream': 12.631462179124355, + 'transform': [array([2.70755720e+00, 6.55930307e-07, 1.80351257e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.49210775, -0.81678641, 3.2124145 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.878929138183594, + 'FR_Wheel_Angle': 41.58671951293945, + 'Location': array([ 2.27113838e+01, -4.43091154e+00, 1.94984907e-03]), + 'Rotation': array([-3.02440766e-02, 5.21496162e+01, -1.94122270e-01]), + 'Velocity': array([6.21577501e-02, 2.48374254e-01, 1.44171718e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 537.7874145507812, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 2.21634155e+02, 9.41579819e+01, -3.05175781e-05]), + 'frame': 512, + 'frame_number': 512, + 'framesequence': 510, + 'gaze_dir': array([ 0.98058069, 0.17621771, -0.08607467]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17621771, -0.08607467]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17621771, -0.08607467]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.64437297731638, + 'timestamp_carla': 12644, + 'timestamp_device': 12112, + 'timestamp_stream': 12.64437297731638, + 'transform': [array([2.72037268e+00, 6.59758086e-07, 1.80259696e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.47360763, -0.81430566, 3.10138917]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.88211441040039, + 'FR_Wheel_Angle': 41.596595764160156, + 'Location': array([ 2.27412720e+01, -4.39377451e+00, 1.91372389e-03]), + 'Rotation': array([-2.85911709e-02, 5.26596146e+01, -1.80877656e-01]), + 'Velocity': array([ 5.75373843e-02, 2.40339279e-01, -1.45754806e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 539.669921875, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([224.93948364, 95.09944916, 0. ]), + 'frame': 513, + 'frame_number': 513, + 'framesequence': 511, + 'gaze_dir': array([ 0.98058069, 0.17723788, -0.0839539 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17723788, -0.0839539 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17723788, -0.0839539 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.656408879905939, + 'timestamp_carla': 12656, + 'timestamp_device': 12124, + 'timestamp_stream': 12.656408879905939, + 'transform': [array([2.73223543e+00, 6.63893161e-07, 1.80610653e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.48340118, -0.83199441, 3.02687073]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.885082244873047, + 'FR_Wheel_Angle': 41.601165771484375, + 'Location': array([ 2.27678738e+01, -4.36417580e+00, 1.92005630e-03]), + 'Rotation': array([-3.04899625e-02, 5.30612488e+01, -1.96411103e-01]), + 'Velocity': array([0.05440401, 0.23511259, 0.00024529]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 541.4296875, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([2.28213806e+02, 9.59619064e+01, 3.05175781e-05]), + 'frame': 514, + 'frame_number': 514, + 'framesequence': 512, + 'gaze_dir': array([ 0.98058069, 0.17831433, -0.08164269]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17831433, -0.08164269]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17831433, -0.08164269]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.668878179043531, + 'timestamp_carla': 12668, + 'timestamp_device': 12137, + 'timestamp_stream': 12.668878179043531, + 'transform': [array([2.74444032e+00, 6.71045711e-07, 1.80725090e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.45968547, -0.8196705 , 2.91962409]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.888093948364258, + 'FR_Wheel_Angle': 41.60843276977539, + 'Location': array([ 2.27963123e+01, -4.32807255e+00, 1.91902637e-03]), + 'Rotation': array([-2.84409057e-02, 5.35490990e+01, -1.80175737e-01]), + 'Velocity': array([ 5.02649359e-02, 2.27209583e-01, -9.57870434e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 543.3615112304688, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([231.58746338, 96.88920593, 0. ]), + 'frame': 515, + 'frame_number': 515, + 'framesequence': 513, + 'gaze_dir': array([ 0.98058069, 0.1792811 , -0.07949725]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1792811 , -0.07949725]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1792811 , -0.07949725]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.681071877479553, + 'timestamp_carla': 12681, + 'timestamp_device': 12149, + 'timestamp_stream': 12.681071877479553, + 'transform': [array([2.75629663e+00, 6.80917708e-07, 1.80953974e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.47154349, -0.84166354, 2.84821558]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.890975952148438, + 'FR_Wheel_Angle': 41.61213684082031, + 'Location': array([ 2.28219070e+01, -4.29967928e+00, 1.93470472e-03]), + 'Rotation': array([-3.02440766e-02, 5.39277916e+01, -1.95068344e-01]), + 'Velocity': array([ 4.74150553e-02, 2.22150385e-01, -8.38661144e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 545.166748046875, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([234.8520813 , 97.73815918, 0. ]), + 'frame': 516, + 'frame_number': 516, + 'framesequence': 514, + 'gaze_dir': array([ 0.98058069, 0.18029943, -0.07715985]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18029943, -0.07715985]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18029943, -0.07715985]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.69383767992258, + 'timestamp_carla': 12693, + 'timestamp_device': 12162, + 'timestamp_stream': 12.69383767992258, + 'transform': [array([2.76862693e+00, 6.84712859e-07, 1.80877687e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44152099, -0.81783807, 2.74377346]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8939208984375, + 'FR_Wheel_Angle': 41.608314514160156, + 'Location': array([ 2.28492908e+01, -4.26441050e+00, 1.97983254e-03]), + 'Rotation': array([-2.78603397e-02, 5.43972626e+01, -1.76147446e-01]), + 'Velocity': array([ 0.04370195, 0.21431231, -0.00033366]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 547.1474609375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([238.28045654, 98.6504364 , 0. ]), + 'frame': 517, + 'frame_number': 517, + 'framesequence': 515, + 'gaze_dir': array([ 0.98058069, 0.18128721, -0.07480959]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18128721, -0.07480959]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18128721, -0.07480959]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.70683427900076, + 'timestamp_carla': 12706, + 'timestamp_device': 12175, + 'timestamp_stream': 12.70683427900076, + 'transform': [array([2.78109789e+00, 6.92270532e-07, 1.80706021e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44143134, -0.82601702, 2.66593599]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8964786529541, + 'FR_Wheel_Angle': 41.61375427246094, + 'Location': array([ 2.28751335e+01, -4.23507547e+00, 1.96495536e-03]), + 'Rotation': array([-2.85023786e-02, 5.47849312e+01, -1.81457505e-01]), + 'Velocity': array([ 0.04086642, 0.20862181, -0.00028047]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 549.153076171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([241.78463745, 99.55448914, 0. ]), + 'frame': 518, + 'frame_number': 518, + 'framesequence': 516, + 'gaze_dir': array([ 0.98058069, 0.18224442, -0.07244652]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18224442, -0.07244652]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18224442, -0.07244652]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.720203079283237, + 'timestamp_carla': 12720, + 'timestamp_device': 12188, + 'timestamp_stream': 12.720203079283237, + 'transform': [array([2.79384184e+00, 6.99567465e-07, 1.80370326e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44485003, -0.8449074 , 2.59112573]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.898958206176758, + 'FR_Wheel_Angle': 41.6168212890625, + 'Location': array([ 2.29003067e+01, -4.20688248e+00, 1.96560379e-03]), + 'Rotation': array([-2.90897749e-02, 5.51540184e+01, -1.86096191e-01]), + 'Velocity': array([3.81315276e-02, 2.03155667e-01, 3.27587122e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 551.184326171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([245.33190918, 100.45032501, 0. ]), + 'frame': 519, + 'frame_number': 519, + 'framesequence': 517, + 'gaze_dir': array([ 0.98058069, 0.18317078, -0.07007137]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18317078, -0.07007137]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18317078, -0.07007137]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.732966277748346, + 'timestamp_carla': 12732, + 'timestamp_device': 12201, + 'timestamp_stream': 12.732966277748346, + 'transform': [array([2.80593204e+00, 7.06272942e-07, 1.80427544e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.45888031, -0.871553 , 2.52998519]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.901344299316406, + 'FR_Wheel_Angle': 41.62211990356445, + 'Location': array([ 2.29244423e+01, -4.18216372e+00, 1.96144567e-03]), + 'Rotation': array([-3.11320014e-02, 5.54748268e+01, -2.02392548e-01]), + 'Velocity': array([3.59263346e-02, 1.98759034e-01, 1.56769747e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 553.2407836914062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([248.93518066, 101.33760834, 0. ]), + 'frame': 520, + 'frame_number': 520, + 'framesequence': 518, + 'gaze_dir': array([ 0.98058069, 0.18406624, -0.0676842 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18406624, -0.0676842 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18406624, -0.0676842 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.745943676680326, + 'timestamp_carla': 12745, + 'timestamp_device': 12214, + 'timestamp_stream': 12.745943676680326, + 'transform': [array([2.81814957e+00, 7.10836446e-07, 1.80374144e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44689763, -0.87372154, 2.44785953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.903675079345703, + 'FR_Wheel_Angle': 41.63002014160156, + 'Location': array([ 2.29495850e+01, -4.15322685e+00, 1.95683003e-03]), + 'Rotation': array([-2.97932830e-02, 5.58501816e+01, -1.91619828e-01]), + 'Velocity': array([ 3.31626534e-02, 1.92584485e-01, -1.07188222e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 555.323974609375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 2.52503113e+02, 1.02216461e+02, -3.05175781e-05]), + 'frame': 521, + 'frame_number': 521, + 'framesequence': 519, + 'gaze_dir': array([ 0.98058069, 0.18486518, -0.06547057]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18486518, -0.06547057]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18486518, -0.06547057]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.75811617821455, + 'timestamp_carla': 12758, + 'timestamp_device': 12226, + 'timestamp_stream': 12.75811617821455, + 'transform': [array([2.82954359e+00, 7.19819070e-07, 1.80709839e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36333081, -0.74859625, 2.27332425]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.120330810546875, + 'FR_Wheel_Angle': 39.55210494995117, + 'Location': array([ 2.29754410e+01, -4.11867571e+00, 1.85333728e-03]), + 'Rotation': array([-2.39876229e-02, 5.62965660e+01, -1.47796646e-01]), + 'Velocity': array([ 3.30037847e-02, 1.83882028e-01, -1.91402432e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 557.2695922851562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([255.92807007, 103.01981354, 0. ]), + 'frame': 522, + 'frame_number': 522, + 'framesequence': 520, + 'gaze_dir': array([ 0.98058069, 0.18563749, -0.06324751]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18563749, -0.06324751]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18563749, -0.06324751]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.770653378218412, + 'timestamp_carla': 12770, + 'timestamp_device': 12238, + 'timestamp_stream': 12.770653378218412, + 'transform': [array([2.84121180e+00, 7.28815621e-07, 1.80824276e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38257569, -0.76716053, 1.94910109]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.60390853881836, + 'FR_Wheel_Angle': 31.530132293701172, + 'Location': array([ 2.30006561e+01, -4.08873081e+00, 1.84231275e-03]), + 'Rotation': array([-2.45681889e-02, 5.66268425e+01, -1.61224335e-01]), + 'Velocity': array([0.05169568, 0.19675073, 0.00140849]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 559.2378540039062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([259.29611206, 103.81558228, 0. ]), + 'frame': 523, + 'frame_number': 523, + 'framesequence': 521, + 'gaze_dir': array([ 0.98058069, 0.18644398, -0.06082904]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18644398, -0.06082904]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18644398, -0.06082904]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.782669179141521, + 'timestamp_carla': 12782, + 'timestamp_device': 12251, + 'timestamp_stream': 12.782669179141521, + 'transform': [array([2.85233259e+00, 7.37099754e-07, 1.81144709e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.22268963, -0.45908159, 2.39606833]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.816150665283203, + 'FR_Wheel_Angle': 33.42655563354492, + 'Location': array([ 2.30379734e+01, -4.02385855e+00, 1.80687418e-03]), + 'Rotation': array([-1.40428683e-02, 5.73140945e+01, -8.94470215e-02]), + 'Velocity': array([0.0572599 , 0.22928035, 0.00078207]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 561.3947143554688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([262.9052124 , 104.66873932, 0. ]), + 'frame': 524, + 'frame_number': 524, + 'framesequence': 522, + 'gaze_dir': array([ 0.98058069, 0.18716049, -0.05858736]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18716049, -0.05858736]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18716049, -0.05858736]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.794834978878498, + 'timestamp_carla': 12794, + 'timestamp_device': 12263, + 'timestamp_stream': 12.794834978878498, + 'transform': [array([2.86353087e+00, 7.44135889e-07, 1.81346887e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.3011525 , -0.6042468 , 2.34078932]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.787689208984375, + 'FR_Wheel_Angle': 33.308876037597656, + 'Location': array([ 2.30667305e+01, -3.98253703e+00, 1.87233440e-03]), + 'Rotation': array([-1.77311692e-02, 5.77627144e+01, -1.27716050e-01]), + 'Velocity': array([0.05342097, 0.22586749, 0.00031651]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 563.4090576171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([2.66298096e+02, 1.05447983e+02, 3.05175781e-05]), + 'frame': 525, + 'frame_number': 525, + 'framesequence': 523, + 'gaze_dir': array([ 0.98058069, 0.18790632, -0.05614931]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18790632, -0.05614931]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18790632, -0.05614931]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.807414580136538, + 'timestamp_carla': 12807, + 'timestamp_device': 12276, + 'timestamp_stream': 12.807414580136538, + 'transform': [array([2.87601805e+00, 7.43586384e-07, 1.81156152e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36842418, -0.74368453, 2.3179903 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.820980072021484, + 'FR_Wheel_Angle': 33.32821273803711, + 'Location': array([ 2.30928535e+01, -3.94982719e+00, 1.90124987e-03]), + 'Rotation': array([-2.10506413e-02, 5.81177368e+01, -1.60949677e-01]), + 'Velocity': array([ 0.05033419, 0.22424155, -0.00059607]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 565.6160888671875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([2.69917023e+02, 1.06282913e+02, 3.05175781e-05]), + 'frame': 526, + 'frame_number': 526, + 'framesequence': 524, + 'gaze_dir': array([ 0.98058069, 0.18856652, -0.0538906 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18856652, -0.0538906 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18856652, -0.0538906 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.819961477071047, + 'timestamp_carla': 12819, + 'timestamp_device': 12288, + 'timestamp_stream': 12.819961477071047, + 'transform': [array([2.88838220e+00, 7.51465393e-07, 1.81037898e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38095501, -0.78408998, 2.26177573]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.82178497314453, + 'FR_Wheel_Angle': 33.328243255615234, + 'Location': array([ 2.31198921e+01, -3.91476679e+00, 1.90559856e-03]), + 'Rotation': array([-2.19044164e-02, 5.84981766e+01, -1.69677705e-01]), + 'Velocity': array([0.04718982, 0.21927541, 0.00035411]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 567.6756591796875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([273.49801636, 107.04468536, 0. ]), + 'frame': 527, + 'frame_number': 527, + 'framesequence': 525, + 'gaze_dir': array([ 0.98058069, 0.18919961, -0.05162397]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18919961, -0.05162397]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18919961, -0.05162397]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.832001280039549, + 'timestamp_carla': 12832, + 'timestamp_device': 12300, + 'timestamp_stream': 12.832001280039549, + 'transform': [array([2.90016532e+00, 7.55032374e-07, 1.81190483e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41556475, -0.85992885, 2.21920753]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.82370948791504, + 'FR_Wheel_Angle': 33.33308029174805, + 'Location': array([ 2.31448536e+01, -3.88593173e+00, 1.88030710e-03]), + 'Rotation': array([-2.38373596e-02, 5.88107109e+01, -1.89666748e-01]), + 'Velocity': array([ 0.04455678, 0.21572401, -0.00073355]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 569.7576904296875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([277.09216309, 107.79801178, 0. ]), + 'frame': 528, + 'frame_number': 528, + 'framesequence': 526, + 'gaze_dir': array([ 0.98058069, 0.18980548, -0.04934989]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18980548, -0.04934989]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18980548, -0.04934989]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.844494078308344, + 'timestamp_carla': 12844, + 'timestamp_device': 12312, + 'timestamp_stream': 12.844494078308344, + 'transform': [array([2.91230941e+00, 7.66259461e-07, 1.81114196e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40986976, -0.86421812, 2.16204572]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.82571792602539, + 'FR_Wheel_Angle': 33.33170700073242, + 'Location': array([ 2.31703663e+01, -3.85409141e+00, 1.90189830e-03]), + 'Rotation': array([-2.37758867e-02, 5.91536560e+01, -1.89788818e-01]), + 'Velocity': array([0.04194448, 0.21047559, 0.00061126]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 571.862548828125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 2.80653778e+02, 1.08542702e+02, -3.05175781e-05]), + 'frame': 529, + 'frame_number': 529, + 'framesequence': 527, + 'gaze_dir': array([ 0.98058069, 0.190431 , -0.04687823]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.190431 , -0.04687823]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.190431 , -0.04687823]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.85691287741065, + 'timestamp_carla': 12856, + 'timestamp_device': 12325, + 'timestamp_stream': 12.85691287741065, + 'transform': [array([2.92430329e+00, 7.74492321e-07, 1.81102753e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40997937, -0.8767665 , 2.10830331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.827253341674805, + 'FR_Wheel_Angle': 33.335025787353516, + 'Location': array([ 2.31957169e+01, -3.82355452e+00, 1.90029619e-03]), + 'Rotation': array([-2.38373596e-02, 5.94821625e+01, -1.91101074e-01]), + 'Velocity': array([ 3.94715555e-02, 2.05572635e-01, -7.07626305e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 574.1673583984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([284.47821045, 109.33934021, 0. ]), + 'frame': 530, + 'frame_number': 530, + 'framesequence': 528, + 'gaze_dir': array([ 0.98058069, 0.19097981, -0.04458972]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19097981, -0.04458972]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19097981, -0.04458972]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.869171876460314, + 'timestamp_carla': 12869, + 'timestamp_device': 12337, + 'timestamp_stream': 12.869171876460314, + 'transform': [array([2.93606734e+00, 7.78213007e-07, 1.81171414e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41807342, -0.90807229, 2.06030345]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.828981399536133, + 'FR_Wheel_Angle': 33.338863372802734, + 'Location': array([ 2.32200069e+01, -3.79595852e+00, 1.90922257e-03]), + 'Rotation': array([-2.44179256e-02, 5.97776756e+01, -1.96777329e-01]), + 'Velocity': array([3.71514894e-02, 2.01236606e-01, 1.21655459e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 576.318115234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([2.88113007e+02, 1.10065193e+02, 3.05175781e-05]), + 'frame': 531, + 'frame_number': 531, + 'framesequence': 529, + 'gaze_dir': array([ 0.98058069, 0.19158533, -0.04191173]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19158533, -0.04191173]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19158533, -0.04191173]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.88278827816248, + 'timestamp_carla': 12882, + 'timestamp_device': 12351, + 'timestamp_stream': 12.88278827816248, + 'transform': [array([2.94904828e+00, 7.82566929e-07, 1.80515286e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41884542, -0.9148466 , 2.01975584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.83076286315918, + 'FR_Wheel_Angle': 33.34170913696289, + 'Location': array([ 2.32435493e+01, -3.77062988e+00, 1.84017653e-03]), + 'Rotation': array([-2.54219621e-02, 6.00474281e+01, -2.07855195e-01]), + 'Velocity': array([0.03545717, 0.19750978, 0.00143637]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 578.8558349609375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([292.16296387, 110.90034485, 0. ]), + 'frame': 532, + 'frame_number': 532, + 'framesequence': 530, + 'gaze_dir': array([ 0.98058069, 0.1921533 , -0.03922553]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1921533 , -0.03922553]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1921533 , -0.03922553]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.897032778710127, + 'timestamp_carla': 12897, + 'timestamp_device': 12365, + 'timestamp_stream': 12.897032778710127, + 'transform': [array([2.96253538e+00, 7.90939509e-07, 1.79599761e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.4005768 , -0.90072739, 1.95864844]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.832599639892578, + 'FR_Wheel_Angle': 33.347015380859375, + 'Location': array([ 2.32682743e+01, -3.74004436e+00, 1.84044358e-03]), + 'Rotation': array([-2.35914718e-02, 6.03717804e+01, -1.89117402e-01]), + 'Velocity': array([0.03299477, 0.19172548, 0.00021716]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 581.4221801757812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([2.96367584e+02, 1.11722260e+02, 3.05175781e-05]), + 'frame': 533, + 'frame_number': 533, + 'framesequence': 531, + 'gaze_dir': array([ 0.98058069, 0.19268361, -0.03653163]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19268361, -0.03653163]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19268361, -0.03653163]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.910950876772404, + 'timestamp_carla': 12910, + 'timestamp_device': 12379, + 'timestamp_stream': 12.910950876772404, + 'transform': [array([2.97562551e+00, 8.00648536e-07, 1.79107662e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40719143, -0.91951609, 1.76145399]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.93137550354004, + 'FR_Wheel_Angle': 29.712133407592773, + 'Location': array([ 2.32914124e+01, -3.71455455e+00, 1.87782757e-03]), + 'Rotation': array([-2.42608301e-02, 6.06338615e+01, -1.97357193e-01]), + 'Velocity': array([0.03635846, 0.18771739, 0.00058143]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 584.0186157226562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([300.65692139, 112.53089142, 0. ]), + 'frame': 534, + 'frame_number': 534, + 'framesequence': 532, + 'gaze_dir': array([ 0.98058069, 0.19314221, -0.03402383]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19314221, -0.03402383]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19314221, -0.03402383]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.924602378159761, + 'timestamp_carla': 12924, + 'timestamp_device': 12392, + 'timestamp_stream': 12.924602378159761, + 'transform': [array([2.98838282e+00, 8.09905885e-07, 1.78886415e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41121227, -0.92707658, 1.54757094]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.08776092529297, + 'FR_Wheel_Angle': 23.274246215820312, + 'Location': array([ 2.33174477e+01, -3.68447804e+00, 1.86779490e-03]), + 'Rotation': array([-2.27035470e-02, 6.08850555e+01, -1.95007280e-01]), + 'Velocity': array([ 5.56895249e-02, 2.10926563e-01, -6.80541998e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 586.4573364257812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.04727722e+02, 1.13269737e+02, -3.05175781e-05]), + 'frame': 535, + 'frame_number': 535, + 'framesequence': 533, + 'gaze_dir': array([ 0.98058069, 0.19363081, -0.0311229 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19363081, -0.0311229 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19363081, -0.0311229 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.93904547765851, + 'timestamp_carla': 12939, + 'timestamp_device': 12407, + 'timestamp_stream': 12.93904547765851, + 'transform': [array([3.00179076e+00, 8.14082853e-07, 1.78241730e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41550839, -0.91921473, 1.99053383]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.945829391479492, + 'FR_Wheel_Angle': 25.643108367919922, + 'Location': array([ 2.33446693e+01, -3.64948058e+00, 1.88473216e-03]), + 'Rotation': array([-2.06613205e-02, 6.11754341e+01, -1.96533188e-01]), + 'Velocity': array([ 5.83329573e-02, 2.45438665e-01, -1.51348113e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 589.3043823242188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([309.22753906, 114.10756683, 0. ]), + 'frame': 536, + 'frame_number': 536, + 'framesequence': 534, + 'gaze_dir': array([ 0.98058069, 0.19404756, -0.02840912]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19404756, -0.02840912]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19404756, -0.02840912]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.953334778547287, + 'timestamp_carla': 12953, + 'timestamp_device': 12421, + 'timestamp_stream': 12.953334778547287, + 'transform': [array([3.01497030e+00, 8.15563681e-07, 1.77856442e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.42094553, -0.93202037, 1.84851551]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.238067626953125, + 'FR_Wheel_Angle': 24.879783630371094, + 'Location': array([ 2.33707962e+01, -3.61813378e+00, 1.87695026e-03]), + 'Rotation': array([-2.06613205e-02, 6.14429321e+01, -2.05810547e-01]), + 'Velocity': array([5.73801398e-02, 2.37097681e-01, 9.82999773e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 591.9921264648438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([3.13612244e+02, 1.14874702e+02, 3.05175781e-05]), + 'frame': 537, + 'frame_number': 537, + 'framesequence': 535, + 'gaze_dir': array([ 0.98058069, 0.19442627, -0.02568978]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19442627, -0.02568978]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19442627, -0.02568978]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.966721776872873, + 'timestamp_carla': 12966, + 'timestamp_device': 12435, + 'timestamp_stream': 12.966721776872873, + 'transform': [array([3.02825403e+00, 8.25039876e-07, 1.78405759e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41821298, -0.93955201, 1.83981085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.324302673339844, + 'FR_Wheel_Angle': 24.888826370239258, + 'Location': array([ 2.33973751e+01, -3.58416343e+00, 1.87717914e-03]), + 'Rotation': array([-1.97392460e-02, 6.17306786e+01, -1.98730499e-01]), + 'Velocity': array([5.50757535e-02, 2.35138446e-01, 1.25489227e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 594.7106323242188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([318.00875854, 115.62745667, 0. ]), + 'frame': 538, + 'frame_number': 538, + 'framesequence': 536, + 'gaze_dir': array([ 0.98058069, 0.1947438 , -0.02316004]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1947438 , -0.02316004]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1947438 , -0.02316004]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.979734778404236, + 'timestamp_carla': 12979, + 'timestamp_device': 12448, + 'timestamp_stream': 12.979734778404236, + 'transform': [array([3.04106927e+00, 8.29901410e-07, 1.79058069e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41052821, -0.92881238, 1.82067418]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.376989364624023, + 'FR_Wheel_Angle': 24.966938018798828, + 'Location': array([ 2.34236698e+01, -3.55161500e+00, 1.87702652e-03]), + 'Rotation': array([-1.94387175e-02, 6.20064621e+01, -1.99432373e-01]), + 'Velocity': array([0.05312278, 0.23232898, 0.00027573]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 597.263916015625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.22228088e+02, 1.16313530e+02, -3.05175781e-05]), + 'frame': 539, + 'frame_number': 539, + 'framesequence': 537, + 'gaze_dir': array([ 0.98058069, 0.19502841, -0.02062657]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19502841, -0.02062657]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19502841, -0.02062657]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 12.992306377738714, + 'timestamp_carla': 12992, + 'timestamp_device': 12461, + 'timestamp_stream': 12.992306377738714, + 'transform': [array([3.05336237e+00, 8.33552178e-07, 1.79805746e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40690792, -0.93214649, 1.78587031]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.3843994140625, + 'FR_Wheel_Angle': 24.993335723876953, + 'Location': array([ 2.34495811e+01, -3.51935053e+00, 1.87294476e-03]), + 'Rotation': array([-1.92884523e-02, 6.22795601e+01, -1.98913589e-01]), + 'Velocity': array([0.05083447, 0.22812928, 0.00027714]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 599.8431396484375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([326.42984009, 116.98652649, 0. ]), + 'frame': 540, + 'frame_number': 540, + 'framesequence': 538, + 'gaze_dir': array([ 0.98058069, 0.19528008, -0.01808944]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19528008, -0.01808944]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19528008, -0.01808944]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.005971278995275, + 'timestamp_carla': 13005, + 'timestamp_device': 12474, + 'timestamp_stream': 13.005971278995275, + 'transform': [array([3.06662774e+00, 8.37524283e-07, 1.79870601e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41606352, -0.94311708, 1.77292907]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.38483238220215, + 'FR_Wheel_Angle': 24.994665145874023, + 'Location': array([ 2.34733524e+01, -3.49407864e+00, 1.88255787e-03]), + 'Rotation': array([-2.13306788e-02, 6.24947166e+01, -2.29125962e-01]), + 'Velocity': array([0.04986662, 0.22671367, 0.00023313]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 602.44873046875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([330.60925293, 117.64631653, 0. ]), + 'frame': 541, + 'frame_number': 541, + 'framesequence': 539, + 'gaze_dir': array([ 0.98058069, 0.19548309, -0.01574481]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19548309, -0.01574481]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19548309, -0.01574481]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.018581978976727, + 'timestamp_carla': 13018, + 'timestamp_device': 12486, + 'timestamp_stream': 13.018581978976727, + 'transform': [array([3.07878780e+00, 8.44453325e-07, 1.80461875e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36856771, -0.88222951, 1.70309126]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.387659072875977, + 'FR_Wheel_Angle': 24.997270584106445, + 'Location': array([ 2.35003929e+01, -3.45447326e+00, 1.86703203e-03]), + 'Rotation': array([-1.74238123e-02, 6.28248215e+01, -1.74804688e-01]), + 'Velocity': array([0.04630206, 0.2179078 , 0.00049959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 604.8756713867188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.34683899e+02, 1.18243042e+02, -6.10351562e-05]), + 'frame': 542, + 'frame_number': 542, + 'framesequence': 540, + 'gaze_dir': array([ 0.98058069, 0.19568434, -0.01300661]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19568434, -0.01300661]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19568434, -0.01300661]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.031679976731539, + 'timestamp_carla': 13031, + 'timestamp_device': 12500, + 'timestamp_stream': 13.031679976731539, + 'transform': [array([3.09133482e+00, 8.48956233e-07, 1.80706021e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37567261, -0.88932365, 1.68625307]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.388254165649414, + 'FR_Wheel_Angle': 24.99867820739746, + 'Location': array([ 2.35251598e+01, -3.42458582e+00, 1.86653610e-03]), + 'Rotation': array([-1.84005294e-02, 6.30747108e+01, -1.90765366e-01]), + 'Velocity': array([ 4.49964479e-02, 2.16027394e-01, -1.68347353e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 607.735595703125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([339.13812256, 118.92442322, 0. ]), + 'frame': 543, + 'frame_number': 543, + 'framesequence': 541, + 'gaze_dir': array([ 0.98058069, 0.19584726, -0.01026585]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19584726, -0.01026585]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19584726, -0.01026585]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.045687079429626, + 'timestamp_carla': 13045, + 'timestamp_device': 12514, + 'timestamp_stream': 13.045687079429626, + 'transform': [array([3.10466146e+00, 8.60197304e-07, 1.80385588e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38732475, -0.92981142, 1.65807676]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.38936996459961, + 'FR_Wheel_Angle': 25.00119400024414, + 'Location': array([ 2.35496902e+01, -3.39514375e+00, 1.88385486e-03]), + 'Rotation': array([-1.90425664e-02, 6.33209991e+01, -1.98913589e-01]), + 'Velocity': array([4.29237820e-02, 2.12752506e-01, 1.03955266e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 610.6248168945312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([343.66436768, 119.58927917, 0. ]), + 'frame': 544, + 'frame_number': 544, + 'framesequence': 542, + 'gaze_dir': array([ 0.98058069, 0.19596414, -0.00771913]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19596414, -0.00771913]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19596414, -0.00771913]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.05921607837081, + 'timestamp_carla': 13059, + 'timestamp_device': 12527, + 'timestamp_stream': 13.05921607837081, + 'transform': [array([3.11744833e+00, 8.65799223e-07, 1.80404657e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.39113253, -0.95087916, 1.6293807 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.390825271606445, + 'FR_Wheel_Angle': 25.002182006835938, + 'Location': array([ 2.35738735e+01, -3.36632347e+00, 1.88412180e-03]), + 'Rotation': array([-1.93499252e-02, 6.35613289e+01, -2.03247085e-01]), + 'Velocity': array([4.10422981e-02, 2.09337860e-01, 1.77993774e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 613.3334350585938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.48064240e+02, 1.20191429e+02, -6.10351562e-05]), + 'frame': 545, + 'frame_number': 545, + 'framesequence': 543, + 'gaze_dir': array([ 0.98058069, 0.19604793, -0.00517092]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19604793, -0.00517092]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19604793, -0.00517092]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.072063878178596, + 'timestamp_carla': 13072, + 'timestamp_device': 12540, + 'timestamp_stream': 13.072063878178596, + 'transform': [array([3.12951660e+00, 8.69813221e-07, 1.80770864e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38473764, -0.93986875, 1.60309255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.391834259033203, + 'FR_Wheel_Angle': 25.004985809326172, + 'Location': array([ 2.35980663e+01, -3.33730006e+00, 1.87344069e-03]), + 'Rotation': array([-1.96163021e-02, 6.38024483e+01, -2.08435073e-01]), + 'Velocity': array([0.03957393, 0.20613152, 0.00021801]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 616.068115234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.52439667e+02, 1.20778961e+02, -3.05175781e-05]), + 'frame': 546, + 'frame_number': 546, + 'framesequence': 544, + 'gaze_dir': array([ 0.98058069, 0.19610113, -0.00242585]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19610113, -0.00242585]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19610113, -0.00242585]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.085725877434015, + 'timestamp_carla': 13085, + 'timestamp_device': 12554, + 'timestamp_stream': 13.085725877434015, + 'transform': [array([3.14226961e+00, 8.74413956e-07, 1.80625916e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37593478, -0.94139743, 1.46637332]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.21744155883789, + 'FR_Wheel_Angle': 22.613977432250977, + 'Location': array([ 2.36227436e+01, -3.30546498e+00, 1.86352246e-03]), + 'Rotation': array([-1.85849443e-02, 6.40625229e+01, -1.94183335e-01]), + 'Velocity': array([4.03968021e-02, 2.01004788e-01, 4.43839999e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 619.0422973632812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.57014099e+02, 1.21394966e+02, -3.05175781e-05]), + 'frame': 547, + 'frame_number': 547, + 'framesequence': 545, + 'gaze_dir': array([9.80580688e-01, 1.96115851e-01, 3.19704297e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([9.80580688e-01, 1.96115851e-01, 3.19704297e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([9.80580688e-01, 1.96115851e-01, 3.19704297e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.09967827796936, + 'timestamp_carla': 13099, + 'timestamp_device': 12568, + 'timestamp_stream': 13.09967827796936, + 'transform': [array([3.15521026e+00, 8.81552523e-07, 1.80328370e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37983015, -0.94587141, 1.05194104]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.120746612548828, + 'FR_Wheel_Angle': 14.7471284866333, + 'Location': array([ 2.36485558e+01, -3.27469110e+00, 1.87057967e-03]), + 'Rotation': array([-1.77038498e-02, 6.42575302e+01, -1.96166992e-01]), + 'Velocity': array([6.04164265e-02, 2.15488121e-01, 1.33519163e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 622.0447998046875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([361.68948364, 121.99291992, 0. ]), + 'frame': 548, + 'frame_number': 548, + 'framesequence': 546, + 'gaze_dir': array([0.98058069, 0.19608901, 0.00326118]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19608901, 0.00326118]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19608901, 0.00326118]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.114830676466227, + 'timestamp_carla': 13114, + 'timestamp_device': 12583, + 'timestamp_stream': 13.114830676466227, + 'transform': [array([3.16917014e+00, 8.89561932e-07, 1.79267884e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38884628, -0.94058061, 1.48655713]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 15.18167781829834, + 'FR_Wheel_Angle': 17.556795120239258, + 'Location': array([ 2.36763706e+01, -3.23853993e+00, 1.86584948e-03]), + 'Rotation': array([-1.57162640e-02, 6.44592056e+01, -2.03826904e-01]), + 'Velocity': array([6.74055889e-02, 2.61722475e-01, 5.36632542e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 625.293701171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([3.66662750e+02, 1.22613304e+02, 3.05175781e-05]), + 'frame': 549, + 'frame_number': 549, + 'framesequence': 547, + 'gaze_dir': array([0.98058069, 0.19602413, 0.006006 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19602413, 0.006006 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19602413, 0.006006 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.129119977355003, + 'timestamp_carla': 13129, + 'timestamp_device': 12597, + 'timestamp_stream': 13.129119977355003, + 'transform': [array([3.18334222e+00, 8.91443165e-07, 1.79859158e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38882661, -0.94106072, 1.314417 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.193062782287598, + 'FR_Wheel_Angle': 16.46358871459961, + 'Location': array([ 2.37036953e+01, -3.20353222e+00, 1.86035631e-03]), + 'Rotation': array([-1.54772075e-02, 6.46686096e+01, -2.10815430e-01]), + 'Velocity': array([0.06658392, 0.25000209, 0.00025319]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 628.3546752929688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.71525482e+02, 1.23172775e+02, -3.05175781e-05]), + 'frame': 550, + 'frame_number': 550, + 'framesequence': 548, + 'gaze_dir': array([0.98058069, 0.19592951, 0.00855383]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19592951, 0.00855383]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19592951, 0.00855383]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.14228317886591, + 'timestamp_carla': 13142, + 'timestamp_device': 12610, + 'timestamp_stream': 13.14228317886591, + 'transform': [array([3.19629693e+00, 8.93915853e-07, 1.80908199e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.32400134, -0.80510014, 1.31376755]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.380634307861328, + 'FR_Wheel_Angle': 16.626619338989258, + 'Location': array([ 2.37354755e+01, -3.15394616e+00, 1.82407850e-03]), + 'Rotation': array([-1.22670187e-02, 6.49543686e+01, -1.58142090e-01]), + 'Velocity': array([0.06403453, 0.24560942, 0.00037546]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 631.22607421875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([376.19384766, 123.67591095, 0. ]), + 'frame': 551, + 'frame_number': 551, + 'framesequence': 549, + 'gaze_dir': array([0.98058069, 0.19579054, 0.0112959 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19579054, 0.0112959 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19579054, 0.0112959 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.155700478702784, + 'timestamp_carla': 13155, + 'timestamp_device': 12624, + 'timestamp_stream': 13.155700478702784, + 'transform': [array([3.20940399e+00, 8.98013639e-07, 1.81610102e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.33962041, -0.83191681, 1.32362342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.419734001159668, + 'FR_Wheel_Angle': 16.667200088500977, + 'Location': array([ 2.37626553e+01, -3.11795712e+00, 1.84319017e-03]), + 'Rotation': array([-1.34008303e-02, 6.51644363e+01, -1.85394242e-01]), + 'Velocity': array([0.06333347, 0.24687253, 0.00034248]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 634.3468627929688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([381.02252197, 124.19918823, 0. ]), + 'frame': 552, + 'frame_number': 552, + 'framesequence': 550, + 'gaze_dir': array([0.98058069, 0.19562717, 0.01384025]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19562717, 0.01384025]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19562717, 0.01384025]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.169382579624653, + 'timestamp_carla': 13169, + 'timestamp_device': 12637, + 'timestamp_stream': 13.169382579624653, + 'transform': [array([3.22267175e+00, 9.10390952e-07, 1.82006834e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.35005549, -0.87587398, 1.30276525]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.45118522644043, + 'FR_Wheel_Angle': 16.693267822265625, + 'Location': array([ 2.37908688e+01, -3.07831931e+00, 1.84990407e-03]), + 'Rotation': array([-1.32778874e-02, 6.53950806e+01, -1.82067841e-01]), + 'Velocity': array([6.04801737e-02, 2.42718488e-01, 1.50203705e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 637.2697143554688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.85642609e+02, 1.24667366e+02, -6.10351562e-05]), + 'frame': 553, + 'frame_number': 553, + 'framesequence': 551, + 'gaze_dir': array([0.98058069, 0.19539756, 0.01677287]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19539756, 0.01677287]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19539756, 0.01677287]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.18399227783084, + 'timestamp_carla': 13183, + 'timestamp_device': 12652, + 'timestamp_stream': 13.18399227783084, + 'transform': [array([3.23673344e+00, 9.15909027e-07, 1.81720732e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36465961, -0.9174394 , 1.29145205]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.451666831970215, + 'FR_Wheel_Angle': 16.694257736206055, + 'Location': array([ 2.38170509e+01, -3.04477859e+00, 1.84776774e-03]), + 'Rotation': array([-1.39813963e-02, 6.55919189e+01, -1.95892334e-01]), + 'Velocity': array([5.88455871e-02, 2.40945384e-01, 9.37843288e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 640.6712036132812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([390.82089233, 125.18565369, 0. ]), + 'frame': 554, + 'frame_number': 554, + 'framesequence': 552, + 'gaze_dir': array([0.98058069, 0.1951436 , 0.01950669]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1951436 , 0.01950669]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1951436 , 0.01950669]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.197820778936148, + 'timestamp_carla': 13197, + 'timestamp_device': 12666, + 'timestamp_stream': 13.197820778936148, + 'transform': [array([3.24994922e+00, 9.24416668e-07, 1.81945798e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37648696, -0.95662534, 1.27685678]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.452592849731445, + 'FR_Wheel_Angle': 16.695301055908203, + 'Location': array([ 2.38429585e+01, -3.01193905e+00, 1.85066694e-03]), + 'Rotation': array([-1.44048678e-02, 6.57846603e+01, -2.03887910e-01]), + 'Velocity': array([ 5.70264421e-02, 2.38545418e-01, -1.79529179e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 643.8736572265625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 3.95853638e+02, 1.25647911e+02, -3.05175781e-05]), + 'frame': 555, + 'frame_number': 555, + 'framesequence': 553, + 'gaze_dir': array([0.98058069, 0.19487354, 0.02204194]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19487354, 0.02204194]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19487354, 0.02204194]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.210880279541016, + 'timestamp_carla': 13210, + 'timestamp_device': 12679, + 'timestamp_stream': 13.210880279541016, + 'transform': [array([3.26234913e+00, 9.31741511e-07, 1.82495115e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36763784, -0.94363433, 1.25962305]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.45305347442627, + 'FR_Wheel_Angle': 16.69610595703125, + 'Location': array([ 2.38694019e+01, -2.97666407e+00, 1.85093400e-03]), + 'Rotation': array([-1.42204529e-02, 6.59901428e+01, -2.01721162e-01]), + 'Velocity': array([0.05542233, 0.23550735, 0.0002824 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 646.873291015625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.00571716e+02, 1.26058571e+02, -3.05175781e-05]), + 'frame': 556, + 'frame_number': 556, + 'framesequence': 554, + 'gaze_dir': array([0.98058069, 0.19454587, 0.0247679 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19454587, 0.0247679 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19454587, 0.0247679 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.224941179156303, + 'timestamp_carla': 13224, + 'timestamp_device': 12693, + 'timestamp_stream': 13.224941179156303, + 'transform': [array([3.27561116e+00, 9.41646135e-07, 1.82346336e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37592548, -0.97447765, 1.24513686]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.453676223754883, + 'FR_Wheel_Angle': 16.696937561035156, + 'Location': array([ 2.38947659e+01, -2.94476986e+00, 1.84563152e-03]), + 'Rotation': array([-1.45892836e-02, 6.61768265e+01, -2.07580581e-01]), + 'Velocity': array([5.37239388e-02, 2.33081102e-01, 8.69941723e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 650.1305541992188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.05499817e+02, 1.26480286e+02, -3.05175781e-05]), + 'frame': 557, + 'frame_number': 557, + 'framesequence': 555, + 'gaze_dir': array([0.98058069, 0.19418006, 0.02748902]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19418006, 0.02748902]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19418006, 0.02748902]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.239557579159737, + 'timestamp_carla': 13239, + 'timestamp_device': 12707, + 'timestamp_stream': 13.239557579159737, + 'transform': [array([3.28930378e+00, 9.53450638e-07, 1.81827543e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.378672 , -0.99167246, 1.22955382]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.454632759094238, + 'FR_Wheel_Angle': 16.69771385192871, + 'Location': array([ 2.39200535e+01, -2.91300797e+00, 1.83857442e-03]), + 'Rotation': array([-1.46166040e-02, 6.63624573e+01, -2.09075943e-01]), + 'Velocity': array([ 0.05208733, 0.23040462, -0.00033959]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 653.4132690429688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([410.54342651, 126.87991333, 0. ]), + 'frame': 558, + 'frame_number': 558, + 'framesequence': 556, + 'gaze_dir': array([0.98058057, 0.19374587, 0.03039858]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.19374587, 0.03039858]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.19374587, 0.03039858]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.254426077008247, + 'timestamp_carla': 13254, + 'timestamp_device': 12722, + 'timestamp_stream': 13.254426077008247, + 'transform': [array([3.30313706e+00, 9.58917440e-07, 1.81209564e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.3630825 , -0.95993716, 1.21290255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.455068588256836, + 'FR_Wheel_Angle': 16.698741912841797, + 'Location': array([ 2.39458694e+01, -2.87894034e+00, 1.84277049e-03]), + 'Rotation': array([-1.43160755e-02, 6.65601883e+01, -2.04284638e-01]), + 'Velocity': array([5.07424660e-02, 2.27391601e-01, 1.54228212e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 656.9595336914062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([415.92868042, 127.28331757, 0. ]), + 'frame': 559, + 'frame_number': 559, + 'framesequence': 557, + 'gaze_dir': array([0.98058069, 0.19333436, 0.03291455]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19333436, 0.03291455]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19333436, 0.03291455]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.267264977097511, + 'timestamp_carla': 13267, + 'timestamp_device': 12735, + 'timestamp_stream': 13.267264977097511, + 'transform': [array([3.31500936e+00, 9.69636972e-07, 1.81869499e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36103123, -0.96525818, 0.96218085]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 11.715132713317871, + 'FR_Wheel_Angle': 12.491487503051758, + 'Location': array([ 2.39709663e+01, -2.84760714e+00, 1.77425856e-03]), + 'Rotation': array([-1.43433968e-02, 6.67290268e+01, -2.05291718e-01]), + 'Velocity': array([0.05635486, 0.22352879, 0.00208225]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 660.0570068359375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.20819824e+02, 1.27611794e+02, -3.05175781e-05]), + 'frame': 560, + 'frame_number': 560, + 'framesequence': 558, + 'gaze_dir': array([0.98058069, 0.19285461, 0.03561791]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19285461, 0.03561791]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19285461, 0.03561791]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.280435379594564, + 'timestamp_carla': 13280, + 'timestamp_device': 12749, + 'timestamp_stream': 13.280435379594564, + 'transform': [array([3.32808137e+00, 9.73031661e-07, 1.81682582e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.3702603 , -0.97580409, 0.55138195]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.136844158172607, + 'FR_Wheel_Angle': 6.768786430358887, + 'Location': array([ 2.39991589e+01, -2.81180882e+00, 1.77784439e-03]), + 'Rotation': array([-1.28202643e-02, 6.68437119e+01, -2.02514619e-01]), + 'Velocity': array([8.03584158e-02, 2.49384433e-01, 1.32498739e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 663.4205932617188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([425.81546021, 127.94381714, 0. ]), + 'frame': 561, + 'frame_number': 561, + 'framesequence': 559, + 'gaze_dir': array([0.98058069, 0.19237529, 0.03812203]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19237529, 0.03812203]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19237529, 0.03812203]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.294179677963257, + 'timestamp_carla': 13294, + 'timestamp_device': 12762, + 'timestamp_stream': 13.294179677963257, + 'transform': [array([3.34161592e+00, 9.82824531e-07, 1.81205745e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37591085, -0.96586221, 0.86037409]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.356039047241211, + 'FR_Wheel_Angle': 8.897926330566406, + 'Location': array([ 2.40286560e+01, -2.77139926e+00, 1.80492876e-03]), + 'Rotation': array([-1.07712075e-02, 6.69664078e+01, -2.03674302e-01]), + 'Velocity': array([8.42923224e-02, 2.83649802e-01, 1.30724904e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 666.5654296875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.30683929e+02, 1.28230804e+02, -6.10351562e-05]), + 'frame': 562, + 'frame_number': 562, + 'framesequence': 560, + 'gaze_dir': array([0.98058069, 0.19182275, 0.04081145]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19182275, 0.04081145]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19182275, 0.04081145]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.30741697922349, + 'timestamp_carla': 13307, + 'timestamp_device': 12776, + 'timestamp_stream': 13.30741697922349, + 'transform': [array([3.35455441e+00, 9.90298417e-07, 1.81118003e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37401196, -0.96061271, 0.75977385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.616065979003906, + 'FR_Wheel_Angle': 8.297148704528809, + 'Location': array([ 2.40579529e+01, -2.73192906e+00, 1.81274884e-03]), + 'Rotation': array([-1.01018492e-02, 6.70879440e+01, -2.02484116e-01]), + 'Velocity': array([8.38494673e-02, 2.76230067e-01, 8.50200668e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 669.9755859375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.35899200e+02, 1.28516663e+02, -3.05175781e-05]), + 'frame': 563, + 'frame_number': 563, + 'framesequence': 561, + 'gaze_dir': array([0.98058069, 0.19127603, 0.04330153]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19127603, 0.04330153]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19127603, 0.04330153]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.321312978863716, + 'timestamp_carla': 13321, + 'timestamp_device': 12789, + 'timestamp_stream': 13.321312978863716, + 'transform': [array([3.36803699e+00, 9.99560370e-07, 1.80671690e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37453929, -0.96184605, 0.76653987]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.658751964569092, + 'FR_Wheel_Angle': 8.247748374938965, + 'Location': array([ 2.40870934e+01, -2.69264698e+00, 1.82247639e-03]), + 'Rotation': array([-9.76717006e-03, 6.72100143e+01, -2.03369126e-01]), + 'Velocity': array([0.08320577, 0.27688143, 0.00028673]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 673.1650390625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([4.40804749e+02, 1.28760437e+02, 3.05175781e-05]), + 'frame': 564, + 'frame_number': 564, + 'framesequence': 562, + 'gaze_dir': array([0.98058069, 0.19065109, 0.04597506]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19065109, 0.04597506]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19065109, 0.04597506]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.334832679480314, + 'timestamp_carla': 13334, + 'timestamp_device': 12803, + 'timestamp_stream': 13.334832679480314, + 'transform': [array([3.38106251e+00, 1.01015883e-06, 1.80534355e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37884498, -0.97427422, 0.77186191]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.702737808227539, + 'FR_Wheel_Angle': 8.313185691833496, + 'Location': array([ 2.41153831e+01, -2.65511417e+00, 1.80031301e-03]), + 'Rotation': array([-9.73984879e-03, 6.73261337e+01, -2.10113555e-01]), + 'Velocity': array([8.25056508e-02, 2.77221113e-01, 2.05445278e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 676.622802734375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.46068726e+02, 1.28998978e+02, -3.05175781e-05]), + 'frame': 565, + 'frame_number': 565, + 'framesequence': 563, + 'gaze_dir': array([0.98058069, 0.18998878, 0.04863957]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18998878, 0.04863957]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18998878, 0.04863957]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.348510779440403, + 'timestamp_carla': 13348, + 'timestamp_device': 12817, + 'timestamp_stream': 13.348510779440403, + 'transform': [array([3.39415002e+00, 1.02112983e-06, 1.80339813e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36709508, -0.95035779, 0.76644391]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.732647895812988, + 'FR_Wheel_Angle': 8.34140396118164, + 'Location': array([ 2.41452484e+01, -2.61291218e+00, 1.81972980e-03]), + 'Rotation': array([-9.45981126e-03, 6.74553757e+01, -2.01843262e-01]), + 'Velocity': array([0.08107394, 0.27463156, 0.00036732]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 680.1051025390625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.51314636e+02, 1.29212433e+02, -3.05175781e-05]), + 'frame': 566, + 'frame_number': 566, + 'framesequence': 564, + 'gaze_dir': array([0.98058069, 0.1893404 , 0.05110534]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1893404 , 0.05110534]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1893404 , 0.05110534]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.36169207841158, + 'timestamp_carla': 13361, + 'timestamp_device': 12830, + 'timestamp_stream': 13.36169207841158, + 'transform': [array([3.40667987e+00, 1.03143498e-06, 1.80454249e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36008471, -0.93708122, 0.76133204]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.73268461227417, + 'FR_Wheel_Angle': 8.341456413269043, + 'Location': array([ 2.41748142e+01, -2.57151747e+00, 1.83220382e-03]), + 'Rotation': array([-9.37101897e-03, 6.75823746e+01, -2.00134262e-01]), + 'Velocity': array([8.00055861e-02, 2.72944897e-01, 1.12428665e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 683.3594360351562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([456.30862427, 129.38764954, 0. ]), + 'frame': 567, + 'frame_number': 567, + 'framesequence': 565, + 'gaze_dir': array([0.98058069, 0.18866007, 0.05356228]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18866007, 0.05356228]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18866007, 0.05356228]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.374841678887606, + 'timestamp_carla': 13374, + 'timestamp_device': 12843, + 'timestamp_stream': 13.374841678887606, + 'transform': [array([3.41910052e+00, 1.03886225e-06, 1.80564879e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36205524, -0.95045406, 0.7541582 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.73303747177124, + 'FR_Wheel_Angle': 8.341851234436035, + 'Location': array([ 2.42039757e+01, -2.53168797e+00, 1.83166971e-03]), + 'Rotation': array([-9.30271670e-03, 6.77051086e+01, -1.97448701e-01]), + 'Velocity': array([7.84403011e-02, 2.70600557e-01, 3.79800804e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 686.6340942382812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.61269684e+02, 1.29540543e+02, -3.05175781e-05]), + 'frame': 568, + 'frame_number': 568, + 'framesequence': 566, + 'gaze_dir': array([0.98058069, 0.18794781, 0.05601037]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18794781, 0.05601037]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18794781, 0.05601037]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.387628678232431, + 'timestamp_carla': 13387, + 'timestamp_device': 12856, + 'timestamp_stream': 13.387628678232431, + 'transform': [array([3.43110561e+00, 1.04493449e-06, 1.80831901e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.3663398 , -0.96491712, 0.75234807]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.733116626739502, + 'FR_Wheel_Angle': 8.342153549194336, + 'Location': array([ 2.42320328e+01, -2.49480891e+00, 1.82468886e-03]), + 'Rotation': array([-9.55543388e-03, 6.78192673e+01, -2.06298843e-01]), + 'Velocity': array([ 7.76758417e-02, 2.70136625e-01, -7.14969647e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 689.92822265625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([466.24185181, 129.67060852, 0. ]), + 'frame': 569, + 'frame_number': 569, + 'framesequence': 567, + 'gaze_dir': array([0.98058069, 0.18714529, 0.05863605]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18714529, 0.05863605]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18714529, 0.05863605]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.401582978665829, + 'timestamp_carla': 13401, + 'timestamp_device': 12870, + 'timestamp_stream': 13.401582978665829, + 'transform': [array([3.44412327e+00, 1.05121626e-06, 1.80397031e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37272161, -0.98789889, 0.74783862]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.733538627624512, + 'FR_Wheel_Angle': 8.342558860778809, + 'Location': array([ 2.42599277e+01, -2.45803285e+00, 1.82995317e-03]), + 'Rotation': array([-9.67837777e-03, 6.79328766e+01, -2.10510254e-01]), + 'Velocity': array([7.64652267e-02, 2.68739432e-01, 7.27176666e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 693.496826171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([4.71483246e+02, 1.29784790e+02, 6.10351562e-05]), + 'frame': 570, + 'frame_number': 570, + 'framesequence': 568, + 'gaze_dir': array([0.98058069, 0.18636726, 0.06106383]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18636726, 0.06106383]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18636726, 0.06106383]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.415040377527475, + 'timestamp_carla': 13415, + 'timestamp_device': 12883, + 'timestamp_stream': 13.415040377527475, + 'transform': [array([3.45659971e+00, 1.05630590e-06, 1.80339813e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36066616, -0.96216398, 0.74224555]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.73361349105835, + 'FR_Wheel_Angle': 8.342723846435547, + 'Location': array([ 2.42888107e+01, -2.41808987e+00, 1.82201853e-03]), + 'Rotation': array([-9.55543388e-03, 6.80552902e+01, -2.05505371e-01]), + 'Velocity': array([7.54612461e-02, 2.66827643e-01, 2.58593558e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 696.828369140625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.76557709e+02, 1.29866089e+02, -3.05175781e-05]), + 'frame': 571, + 'frame_number': 571, + 'framesequence': 569, + 'gaze_dir': array([0.98058069, 0.18549414, 0.06366689]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18549414, 0.06366689]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18549414, 0.06366689]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.428765378892422, + 'timestamp_carla': 13428, + 'timestamp_device': 12897, + 'timestamp_stream': 13.428765378892422, + 'transform': [array([3.46924591e+00, 1.06427331e-06, 1.80141442e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36905926, -0.99057287, 0.73804116]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.733809947967529, + 'FR_Wheel_Angle': 8.34302043914795, + 'Location': array([ 2.43164082e+01, -2.38169789e+00, 1.81622023e-03]), + 'Rotation': array([-9.67837777e-03, 6.81675797e+01, -2.10083008e-01]), + 'Velocity': array([ 7.42682815e-02, 2.65548110e-01, -1.86915393e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 700.4367065429688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.81891418e+02, 1.29927017e+02, -3.05175781e-05]), + 'frame': 572, + 'frame_number': 572, + 'framesequence': 570, + 'gaze_dir': array([0.98058069, 0.18465076, 0.06607295]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18465076, 0.06607295]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18465076, 0.06607295]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.442004278302193, + 'timestamp_carla': 13442, + 'timestamp_device': 12910, + 'timestamp_stream': 13.442004278302193, + 'transform': [array([3.48238373e+00, 1.06890207e-06, 1.80419919e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36551291, -0.98936319, 0.58813721]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.2180986404418945, + 'FR_Wheel_Angle': 6.022465705871582, + 'Location': array([ 2.43445282e+01, -2.34349370e+00, 1.81972980e-03]), + 'Rotation': array([-9.52128321e-03, 6.82808151e+01, -2.03613251e-01]), + 'Velocity': array([0.0769569 , 0.26208332, 0.00046439]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 703.80517578125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 4.86970490e+02, 1.29958282e+02, -3.05175781e-05]), + 'frame': 573, + 'frame_number': 573, + 'framesequence': 571, + 'gaze_dir': array([0.98058069, 0.18377627, 0.06846768]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18377627, 0.06846768]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18377627, 0.06846768]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.455409478396177, + 'timestamp_carla': 13455, + 'timestamp_device': 12923, + 'timestamp_stream': 13.455409478396177, + 'transform': [array([3.49558377e+00, 1.06976347e-06, 1.80564879e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37153095, -0.99199432, -0.12314621]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.5172218084335327, + 'FR_Wheel_Angle': -1.8322216272354126, + 'Location': array([ 2.43746166e+01, -2.30523252e+00, 1.81122299e-03]), + 'Rotation': array([-8.64018872e-03, 6.83158798e+01, -2.05841064e-01]), + 'Velocity': array([1.04557768e-01, 2.74651855e-01, 1.37796393e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 707.1911010742188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([492.11819458, 129.96505737, 0. ]), + 'frame': 574, + 'frame_number': 574, + 'framesequence': 572, + 'gaze_dir': array([0.98058069, 0.18279977, 0.07103374]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18279977, 0.07103374]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18279977, 0.07103374]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.468984078615904, + 'timestamp_carla': 13468, + 'timestamp_device': 12937, + 'timestamp_stream': 13.468984078615904, + 'transform': [array([3.50885010e+00, 1.07227811e-06, 1.80591585e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.75488430e-01, -9.66066360e-01, 7.32202125e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.44083099e+01, -2.25967956e+00, 1.79096696e-03]), + 'Rotation': array([-6.07203785e-03, 6.83056946e+01, -2.06420913e-01]), + 'Velocity': array([ 1.21332183e-01, 3.25210303e-01, -1.45435333e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 710.8552856445312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([497.58737183, 129.94430542, 0. ]), + 'frame': 575, + 'frame_number': 575, + 'framesequence': 573, + 'gaze_dir': array([0.98058069, 0.18178742, 0.07358588]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18178742, 0.07358588]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18178742, 0.07358588]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.482725378125906, + 'timestamp_carla': 13482, + 'timestamp_device': 12951, + 'timestamp_stream': 13.482725378125906, + 'transform': [array([3.52218008e+00, 1.07908602e-06, 1.80522911e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.66525024e-01, -9.33138907e-01, 7.07747449e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.44431801e+01, -2.21046209e+00, 1.78959360e-03]), + 'Rotation': array([-5.19094337e-03, 6.83049850e+01, -1.98944092e-01]), + 'Velocity': array([1.19319513e-01, 3.19500118e-01, 7.06386563e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 714.5372924804688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([503.08343506, 129.89401245, 0. ]), + 'frame': 576, + 'frame_number': 576, + 'framesequence': 574, + 'gaze_dir': array([0.98058069, 0.18073943, 0.0761236 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18073943, 0.0761236 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18073943, 0.0761236 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.497377879917622, + 'timestamp_carla': 13497, + 'timestamp_device': 12965, + 'timestamp_stream': 13.497377879917622, + 'transform': [array([3.53628778e+00, 1.08905590e-06, 1.79885863e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.77845109e-01, -9.56122935e-01, 5.12738188e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.44764175e+01, -2.16533113e+00, 1.78299425e-03]), + 'Rotation': array([-4.79479274e-03, 6.83042679e+01, -2.01812714e-01]), + 'Velocity': array([ 0.11934264, 0.32006347, -0.00080864]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 718.236083984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([508.6048584 , 129.81370544, 0. ]), + 'frame': 577, + 'frame_number': 577, + 'framesequence': 575, + 'gaze_dir': array([0.98058069, 0.17957728, 0.07882608]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17957728, 0.07882608]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17957728, 0.07882608]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.511588878929615, + 'timestamp_carla': 13511, + 'timestamp_device': 12980, + 'timestamp_stream': 13.511588878929615, + 'transform': [array([3.54987216e+00, 1.09886730e-06, 1.79679866e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.80281866e-01, -9.59430337e-01, 5.56007933e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.45088062e+01, -2.12213111e+00, 1.80424214e-03]), + 'Rotation': array([-4.69916966e-03, 6.83034439e+01, -2.09411621e-01]), + 'Velocity': array([1.19811140e-01, 3.21117610e-01, 1.60889627e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 722.2162475585938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([5.14523010e+02, 1.29693741e+02, 3.05175781e-05]), + 'frame': 578, + 'frame_number': 578, + 'framesequence': 576, + 'gaze_dir': array([0.98058069, 0.17837468, 0.08151083]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17837468, 0.08151083]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17837468, 0.08151083]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.527245879173279, + 'timestamp_carla': 13527, + 'timestamp_device': 12995, + 'timestamp_stream': 13.527245879173279, + 'transform': [array([3.56472659e+00, 1.10948906e-06, 1.78482046e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.53094995e-01, -8.90704036e-01, 1.92240987e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.45456982e+01, -2.06658936e+00, 1.81507587e-03]), + 'Rotation': array([-4.63769818e-03, 6.83027115e+01, -1.82800248e-01]), + 'Velocity': array([ 1.18823342e-01, 3.17617595e-01, -6.57558412e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 726.2151489257812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([520.40979004, 129.53851318, 0. ]), + 'frame': 579, + 'frame_number': 579, + 'framesequence': 577, + 'gaze_dir': array([0.98058069, 0.17713206, 0.08417708]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17713206, 0.08417708]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17713206, 0.08417708]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.542344577610493, + 'timestamp_carla': 13542, + 'timestamp_device': 13010, + 'timestamp_stream': 13.542344577610493, + 'transform': [array([3.57894707e+00, 1.11706538e-06, 1.77993765e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.41554433e-01, -8.61299694e-01, 1.81755240e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.45808487e+01, -2.01550412e+00, 1.79844373e-03]), + 'Rotation': array([-4.63769818e-03, 6.83018799e+01, -1.76666230e-01]), + 'Velocity': array([1.18896946e-01, 3.17148328e-01, 1.15938186e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 730.2283325195312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 5.26440308e+02, 1.29346970e+02, -3.05175781e-05]), + 'frame': 580, + 'frame_number': 580, + 'framesequence': 578, + 'gaze_dir': array([0.98058069, 0.17584948, 0.08682455]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17584948, 0.08682455]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17584948, 0.08682455]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.556568779051304, + 'timestamp_carla': 13556, + 'timestamp_device': 13025, + 'timestamp_stream': 13.556568779051304, + 'transform': [array([3.59225345e+00, 1.12751945e-06, 1.78203580e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.41070026e-01, -8.59693468e-01, 1.65119363e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.46154041e+01, -1.96585226e+00, 1.79714675e-03]), + 'Rotation': array([-4.63769818e-03, 6.83012390e+01, -1.78375229e-01]), + 'Velocity': array([1.19172961e-01, 3.17739874e-01, 2.85487156e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 734.2587890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([5.32426636e+02, 1.29119156e+02, 3.05175781e-05]), + 'frame': 581, + 'frame_number': 581, + 'framesequence': 579, + 'gaze_dir': array([0.98058069, 0.17470591, 0.08910328]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17470591, 0.08910328]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17470591, 0.08910328]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.569923777133226, + 'timestamp_carla': 13569, + 'timestamp_device': 13038, + 'timestamp_stream': 13.569923777133226, + 'transform': [array([3.60466862e+00, 1.13573378e-06, 1.78855890e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.56599510e-01, -8.98070037e-01, 6.59992975e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.46484509e+01, -1.92073309e+00, 1.80286879e-03]), + 'Rotation': array([-4.63769818e-03, 6.83004837e+01, -1.92626953e-01]), + 'Velocity': array([1.19812742e-01, 3.19916755e-01, 3.70502471e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 737.7654418945312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([537.72796631, 128.89212036, 0. ]), + 'frame': 582, + 'frame_number': 582, + 'framesequence': 580, + 'gaze_dir': array([0.98058069, 0.17334981, 0.09171364]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17334981, 0.09171364]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17334981, 0.09171364]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.584329679608345, + 'timestamp_carla': 13584, + 'timestamp_device': 13053, + 'timestamp_stream': 13.584329679608345, + 'transform': [array([3.61797428e+00, 1.14697480e-06, 1.78783410e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.61514062e-01, -9.10209417e-01, 8.34986224e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.46827259e+01, -1.87316489e+00, 1.79710856e-03]), + 'Rotation': array([-4.63769818e-03, 6.82997971e+01, -1.97845444e-01]), + 'Velocity': array([1.20023906e-01, 3.20563316e-01, 6.21557192e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 741.8247680664062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 5.43565796e+02, 1.28595337e+02, -3.05175781e-05]), + 'frame': 583, + 'frame_number': 583, + 'framesequence': 581, + 'gaze_dir': array([0.98058069, 0.17195462, 0.09430353]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17195462, 0.09430353]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17195462, 0.09430353]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.600336279720068, + 'timestamp_carla': 13600, + 'timestamp_device': 13068, + 'timestamp_stream': 13.600336279720068, + 'transform': [array([3.63383746e+00, 1.14909358e-06, 1.77635194e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.70378673e-01, -9.33043063e-01, 1.19250335e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.47163944e+01, -1.82634246e+00, 1.78608415e-03]), + 'Rotation': array([-4.63769818e-03, 6.82990952e+01, -1.96624741e-01]), + 'Velocity': array([1.19340971e-01, 3.19565624e-01, 1.81555748e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 745.8946533203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([549.50500488, 128.26017761, 0. ]), + 'frame': 584, + 'frame_number': 584, + 'framesequence': 582, + 'gaze_dir': array([0.98058069, 0.17061757, 0.09670156]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17061757, 0.09670156]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17061757, 0.09670156]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.614060278981924, + 'timestamp_carla': 13614, + 'timestamp_device': 13082, + 'timestamp_stream': 13.614060278981924, + 'transform': [array([3.64732909e+00, 1.15182695e-06, 1.78325654e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.73195052e-01, -9.39809620e-01, 6.10106599e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 2.47495499e+01, -1.78149319e+00, 1.79195881e-03]), + 'Rotation': array([-4.63769818e-03, 6.82983398e+01, -2.01721162e-01]), + 'Velocity': array([1.19670272e-01, 3.20383102e-01, 2.15997687e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 749.7006225585938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([555.40185547, 127.9122467 , 0. ]), + 'frame': 585, + 'frame_number': 585, + 'framesequence': 583, + 'gaze_dir': array([0.98058069, 0.16924708, 0.09908064]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16924708, 0.09908064]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16924708, 0.09908064]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.6276751793921, + 'timestamp_carla': 13627, + 'timestamp_device': 13096, + 'timestamp_stream': 13.6276751793921, + 'transform': [array([3.66061282e+00, 1.16276533e-06, 1.78947439e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37275222, -0.93635589, -0.64294207]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.602888107299805, + 'FR_Wheel_Angle': -6.794281005859375, + 'Location': array([ 2.47854309e+01, -1.73126435e+00, 1.80279254e-03]), + 'Rotation': array([-4.63769818e-03, 6.82623978e+01, -1.90826401e-01]), + 'Velocity': array([1.36934906e-01, 3.11799288e-01, 1.19895929e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 753.5198364257812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 5.61075195e+02, 1.27531158e+02, -6.10351562e-05]), + 'frame': 586, + 'frame_number': 586, + 'framesequence': 584, + 'gaze_dir': array([0.98058069, 0.16794482, 0.10127234]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16794482, 0.10127234]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16794482, 0.10127234]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.64055997878313, + 'timestamp_carla': 13640, + 'timestamp_device': 13109, + 'timestamp_stream': 13.64055997878313, + 'transform': [array([3.67309713e+00, 1.16944761e-06, 1.79813383e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.34608892, -0.83356804, -1.09180915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.562438011169434, + 'FR_Wheel_Angle': -7.5641350746154785, + 'Location': array([ 2.48288364e+01, -1.67284966e+00, 1.78810593e-03]), + 'Rotation': array([-2.58864160e-03, 6.80603180e+01, -1.78100571e-01]), + 'Velocity': array([ 1.71726793e-01, 3.55635643e-01, -6.09207127e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 757.0724487304688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([566.42614746, 127.14651489, 0. ]), + 'frame': 587, + 'frame_number': 587, + 'framesequence': 585, + 'gaze_dir': array([0.98058069, 0.16651049, 0.10361371]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16651049, 0.10361371]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16651049, 0.10361371]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.654948078095913, + 'timestamp_carla': 13654, + 'timestamp_device': 13123, + 'timestamp_stream': 13.654948078095913, + 'transform': [array([3.68693686e+00, 1.17827187e-06, 1.79687492e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36890727, -0.86662424, -1.11288273]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.576089859008789, + 'FR_Wheel_Angle': -8.061517715454102, + 'Location': array([ 2.48696766e+01, -1.61856699e+00, 1.75808428e-03]), + 'Rotation': array([-1.46849058e-03, 6.78886871e+01, -1.83013901e-01]), + 'Velocity': array([ 1.76765442e-01, 3.64621729e-01, -4.97341125e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 760.9052124023438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([5.72014282e+02, 1.26698845e+02, 6.10351562e-05]), + 'frame': 588, + 'frame_number': 588, + 'framesequence': 586, + 'gaze_dir': array([0.98058057, 0.16504362, 0.10593461]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.16504362, 0.10593461]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.16504362, 0.10593461]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.668658178299665, + 'timestamp_carla': 13668, + 'timestamp_device': 13137, + 'timestamp_stream': 13.668658178299665, + 'transform': [array([3.70003343e+00, 1.18258390e-06, 1.79988856e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37538624, -0.86493677, -1.08622074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.135896682739258, + 'FR_Wheel_Angle': -7.595957279205322, + 'Location': array([ 2.49111595e+01, -1.56354880e+00, 1.73866749e-03]), + 'Rotation': array([-6.42037718e-04, 6.77020340e+01, -1.86096177e-01]), + 'Velocity': array([ 1.81504056e-01, 3.74451548e-01, -1.03998180e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 764.7407836914062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([577.74157715, 126.21575928, 0. ]), + 'frame': 589, + 'frame_number': 589, + 'framesequence': 587, + 'gaze_dir': array([0.98058069, 0.16376068, 0.10790733]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16376068, 0.10790733]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16376068, 0.10790733]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.681078277528286, + 'timestamp_carla': 13681, + 'timestamp_device': 13149, + 'timestamp_stream': 13.681078277528286, + 'transform': [array([3.71182370e+00, 1.19052811e-06, 1.80847163e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.36245477, -0.82366014, -1.10626769]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.285726547241211, + 'FR_Wheel_Angle': -7.668701171875, + 'Location': array([ 2.49563103e+01, -1.50057065e+00, 1.74679281e-03]), + 'Rotation': array([-7.03509431e-04, 6.74950180e+01, -1.75201371e-01]), + 'Velocity': array([0.18334863, 0.37270617, 0.00041657]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 768.032470703125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([5.82778503e+02, 1.25773666e+02, 6.10351562e-05]), + 'frame': 590, + 'frame_number': 590, + 'framesequence': 588, + 'gaze_dir': array([0.98058069, 0.16223387, 0.11018948]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16223387, 0.11018948]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16223387, 0.11018948]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.695459477603436, + 'timestamp_carla': 13695, + 'timestamp_device': 13163, + 'timestamp_stream': 13.695459477603436, + 'transform': [array([3.72538495e+00, 1.19742458e-06, 1.80484762e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37518623, -0.84427601, -1.12250721]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.324514389038086, + 'FR_Wheel_Angle': -7.709845542907715, + 'Location': array([ 2.49981709e+01, -1.44493604e+00, 1.74641132e-03]), + 'Rotation': array([-4.91773593e-04, 6.73091660e+01, -1.81701660e-01]), + 'Velocity': array([1.86505795e-01, 3.75900000e-01, 3.32593918e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 771.8773803710938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 5.88310791e+02, 1.25224800e+02, -3.05175781e-05]), + 'frame': 591, + 'frame_number': 591, + 'framesequence': 589, + 'gaze_dir': array([0.98058069, 0.16056292, 0.11261039]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.16056292, 0.11261039]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.16056292, 0.11261039]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.710349079221487, + 'timestamp_carla': 13710, + 'timestamp_device': 13178, + 'timestamp_stream': 13.710349079221487, + 'transform': [array([3.73932886e+00, 1.21409528e-06, 1.79840089e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.38663158, -0.86171198, -1.13072157]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.32406234741211, + 'FR_Wheel_Angle': -7.709792613983154, + 'Location': array([ 2.50403805e+01, -1.38916337e+00, 1.78734295e-03]), + 'Rotation': array([-3.34679266e-04, 6.71223679e+01, -1.85119644e-01]), + 'Velocity': array([ 1.89036980e-01, 3.78131479e-01, -2.70414348e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 775.9949951171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([594.32983398, 124.59616089, 0. ]), + 'frame': 592, + 'frame_number': 592, + 'framesequence': 590, + 'gaze_dir': array([0.98058057, 0.15897068, 0.11484715]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.15897068, 0.11484715]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.15897068, 0.11484715]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.723635576665401, + 'timestamp_carla': 13723, + 'timestamp_device': 13192, + 'timestamp_stream': 13.723635576665401, + 'transform': [array([3.75169277e+00, 1.21923620e-06, 1.80297846e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.39022619, -0.86167622, -1.13740849]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.323694229125977, + 'FR_Wheel_Angle': -7.7093987464904785, + 'Location': array([ 2.50836811e+01, -1.33290756e+00, 1.79413310e-03]), + 'Rotation': array([-3.34679266e-04, 6.69330597e+01, -1.85302749e-01]), + 'Velocity': array([1.91436321e-01, 3.79750133e-01, 3.52382654e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 779.8378295898438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([600.07617188, 123.97151184, 0. ]), + 'frame': 593, + 'frame_number': 593, + 'framesequence': 591, + 'gaze_dir': array([0.98058057, 0.15746422, 0.11690408]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.15746422, 0.11690408]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.15746422, 0.11690408]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.73695807904005, + 'timestamp_carla': 13736, + 'timestamp_device': 13205, + 'timestamp_stream': 13.73695807904005, + 'transform': [array([3.76401520e+00, 1.22735730e-06, 1.80633541e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.39380407, -0.86217153, -1.1457969 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.323209762573242, + 'FR_Wheel_Angle': -7.709023952484131, + 'Location': array([ 2.51268177e+01, -1.27724504e+00, 1.77170278e-03]), + 'Rotation': array([-3.07358510e-04, 6.67453003e+01, -1.87347427e-01]), + 'Velocity': array([1.94168866e-01, 3.81907761e-01, 1.69816019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 783.408203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([605.35522461, 123.35891724, 0. ]), + 'frame': 594, + 'frame_number': 594, + 'framesequence': 592, + 'gaze_dir': array([0.98058069, 0.1558122 , 0.11909705]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1558122 , 0.11909705]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1558122 , 0.11909705]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.750793177634478, + 'timestamp_carla': 13750, + 'timestamp_device': 13219, + 'timestamp_stream': 13.750793177634478, + 'transform': [array([3.77673244e+00, 1.23253074e-06, 1.80603028e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40536112, -0.88043499, -1.15536022]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.322639465332031, + 'FR_Wheel_Angle': -7.708537578582764, + 'Location': array([ 2.51695385e+01, -1.22302735e+00, 1.75922865e-03]), + 'Rotation': array([-2.18566041e-04, 6.65612869e+01, -1.92169160e-01]), + 'Velocity': array([ 0.19697367, 0.38451022, -0.00057463]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 787.2505493164062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.10938232e+02, 1.22663391e+02, -3.05175781e-05]), + 'frame': 595, + 'frame_number': 595, + 'framesequence': 593, + 'gaze_dir': array([0.98058057, 0.15425086, 0.1211124 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.15425086, 0.1211124 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.15425086, 0.1211124 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.764388676732779, + 'timestamp_carla': 13764, + 'timestamp_device': 13232, + 'timestamp_stream': 13.764388676732779, + 'transform': [array([3.79022050e+00, 1.24080088e-06, 1.80744170e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40449479, -0.87009996, -1.15950859]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.322430610656738, + 'FR_Wheel_Angle': -7.708188056945801, + 'Location': array([ 2.52135620e+01, -1.16630590e+00, 1.78440567e-03]), + 'Rotation': array([-2.73207552e-04, 6.63695374e+01, -1.88964814e-01]), + 'Velocity': array([1.99025229e-01, 3.85227412e-01, 3.07092647e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 790.81396484375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([616.24511719, 121.98390198, 0. ]), + 'frame': 596, + 'frame_number': 596, + 'framesequence': 594, + 'gaze_dir': array([0.98058057, 0.15254024, 0.12325997]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.15254024, 0.12325997]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.15254024, 0.12325997]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.777724876999855, + 'timestamp_carla': 13777, + 'timestamp_device': 13246, + 'timestamp_stream': 13.777724876999855, + 'transform': [array([3.80334902e+00, 1.25301983e-06, 1.80995942e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.40753338, -0.86966568, -1.16916597]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.322261810302734, + 'FR_Wheel_Angle': -7.707758903503418, + 'Location': array([ 2.52570381e+01, -1.11128426e+00, 1.76712510e-03]), + 'Rotation': array([-2.45886797e-04, 6.61825943e+01, -1.91741928e-01]), + 'Velocity': array([2.02024937e-01, 3.87770653e-01, 1.77206995e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 794.6475219726562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([6.21934814e+02, 1.21215874e+02, 3.05175781e-05]), + 'frame': 597, + 'frame_number': 597, + 'framesequence': 595, + 'gaze_dir': array([0.98058069, 0.15092497, 0.12523261]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.15092497, 0.12523261]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.15092497, 0.12523261]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.79146657884121, + 'timestamp_carla': 13791, + 'timestamp_device': 13259, + 'timestamp_stream': 13.79146657884121, + 'transform': [array([3.81677318e+00, 1.26220266e-06, 1.80973054e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41220039, -0.87253916, -1.31322622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -9.94567584991455, + 'FR_Wheel_Angle': -9.636736869812012, + 'Location': array([ 2.53019180e+01, -1.05404556e+00, 1.74438953e-03]), + 'Rotation': array([-2.45886797e-04, 6.59855194e+01, -1.93603516e-01]), + 'Velocity': array([ 2.08679542e-01, 3.88668388e-01, -3.79676814e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 798.201904296875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([6.27272400e+02, 1.20468750e+02, 3.05175781e-05]), + 'frame': 598, + 'frame_number': 598, + 'framesequence': 596, + 'gaze_dir': array([0.98058069, 0.14902966, 0.12748222]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14902966, 0.12748222]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14902966, 0.12748222]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.806050579994917, + 'timestamp_carla': 13806, + 'timestamp_device': 13274, + 'timestamp_stream': 13.806050579994917, + 'transform': [array([3.83091021e+00, 1.26666373e-06, 1.80419919e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41378176, -0.85076594, -2.60212851]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.559648513793945, + 'FR_Wheel_Angle': -15.824577331542969, + 'Location': array([ 2.53531494e+01, -9.91383672e-01, 1.76022050e-03]), + 'Rotation': array([ 6.83018879e-06, 6.56350403e+01, -1.78649887e-01]), + 'Velocity': array([2.51143128e-01, 3.82555038e-01, 2.90608412e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 802.2936401367188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([633.24829102, 119.56571198, 0. ]), + 'frame': 599, + 'frame_number': 599, + 'framesequence': 597, + 'gaze_dir': array([0.98058069, 0.14723024, 0.12955621]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14723024, 0.12955621]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14723024, 0.12955621]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.81975457817316, + 'timestamp_carla': 13819, + 'timestamp_device': 13288, + 'timestamp_stream': 13.81975457817316, + 'transform': [array([3.84409881e+00, 1.27019348e-06, 1.80522911e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.39158219, -0.76966071, -2.50435686]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -15.620421409606934, + 'FR_Wheel_Angle': -13.707662582397461, + 'Location': array([ 2.54094982e+01, -9.24384356e-01, 1.75072195e-03]), + 'Rotation': array([ 1.95343397e-03, 6.51652451e+01, -1.74499512e-01]), + 'Velocity': array([ 2.75378197e-01, 4.30478573e-01, -2.92539589e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 806.1018676757812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([638.97460938, 118.68273926, 0. ]), + 'frame': 600, + 'frame_number': 600, + 'framesequence': 598, + 'gaze_dir': array([0.98058069, 0.14540209, 0.13160464]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14540209, 0.13160464]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14540209, 0.13160464]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.833919178694487, + 'timestamp_carla': 13833, + 'timestamp_device': 13302, + 'timestamp_stream': 13.833919178694487, + 'transform': [array([3.85763335e+00, 1.28259398e-06, 1.80328370e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.41197768, -0.78877473, -2.6949985 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.984601974487305, + 'FR_Wheel_Angle': -14.587193489074707, + 'Location': array([ 2.54636574e+01, -8.61575842e-01, 1.74725056e-03]), + 'Rotation': array([ 2.48618866e-03, 6.47299805e+01, -1.74530029e-01]), + 'Velocity': array([ 2.81674623e-01, 4.21997696e-01, -1.60317417e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 809.9005737304688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.44594971e+02, 1.17761406e+02, -3.05175781e-05]), + 'frame': 601, + 'frame_number': 601, + 'framesequence': 599, + 'gaze_dir': array([0.98058069, 0.14354545, 0.13362731]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14354545, 0.13362731]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14354545, 0.13362731]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.848137877881527, + 'timestamp_carla': 13848, + 'timestamp_device': 13316, + 'timestamp_stream': 13.848137877881527, + 'transform': [array([3.87112498e+00, 1.29170235e-06, 1.80133816e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.42519033, -0.79656076, -2.70749021]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.665027618408203, + 'FR_Wheel_Angle': -14.449180603027344, + 'Location': array([ 2.55160465e+01, -8.02223027e-01, 1.74019334e-03]), + 'Rotation': array([ 3.27849062e-03, 6.43134689e+01, -1.83441147e-01]), + 'Velocity': array([2.91147113e-01, 4.32549208e-01, 3.14235695e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 813.6859130859375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([650.23486328, 116.80106354, 0. ]), + 'frame': 602, + 'frame_number': 602, + 'framesequence': 600, + 'gaze_dir': array([0.98058069, 0.14166066, 0.13562377]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.14166066, 0.13562377]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.14166066, 0.13562377]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.86227247864008, + 'timestamp_carla': 13862, + 'timestamp_device': 13330, + 'timestamp_stream': 13.86227247864008, + 'transform': [array([3.88444638e+00, 1.30448007e-06, 1.80023187e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.42778921, -0.78511465, -2.74406362]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.638858795166016, + 'FR_Wheel_Angle': -14.409555435180664, + 'Location': array([ 2.55722828e+01, -7.37985671e-01, 1.74328324e-03]), + 'Rotation': array([ 3.44924536e-03, 6.38629150e+01, -1.83898866e-01]), + 'Velocity': array([2.98635691e-01, 4.35807377e-01, 4.01496873e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 817.4570922851562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([655.85449219, 115.80166626, 0. ]), + 'frame': 603, + 'frame_number': 603, + 'framesequence': 601, + 'gaze_dir': array([0.98058069, 0.13961054, 0.13773325]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13961054, 0.13773325]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13961054, 0.13773325]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.876697678118944, + 'timestamp_carla': 13876, + 'timestamp_device': 13345, + 'timestamp_stream': 13.876697678118944, + 'transform': [array([3.89794946e+00, 1.31270360e-06, 1.79740903e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.43059051, -0.77405012, -2.77801847]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.643890380859375, + 'FR_Wheel_Angle': -14.395480155944824, + 'Location': array([ 2.56301575e+01, -6.72385097e-01, 1.74526684e-03]), + 'Rotation': array([ 3.41509446e-03, 6.34013023e+01, -1.81854233e-01]), + 'Velocity': array([3.05440485e-01, 4.37631339e-01, 4.14395327e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 821.480224609375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([661.74237061, 114.68745422, 0. ]), + 'frame': 604, + 'frame_number': 604, + 'framesequence': 602, + 'gaze_dir': array([0.98058069, 0.13780819, 0.13953657]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13780819, 0.13953657]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13780819, 0.13953657]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.890477579087019, + 'timestamp_carla': 13890, + 'timestamp_device': 13358, + 'timestamp_stream': 13.890477579087019, + 'transform': [array([3.91076565e+00, 1.32149069e-06, 1.79908751e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44352522, -0.77980024, -2.79386258]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.651939392089844, + 'FR_Wheel_Angle': -14.399869918823242, + 'Location': array([ 2.56885223e+01, -6.06999934e-01, 1.74007891e-03]), + 'Rotation': array([ 3.16237751e-03, 6.29380569e+01, -1.75567627e-01]), + 'Velocity': array([3.10453147e-01, 4.37430799e-01, 3.21722036e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 824.9506225585938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([667.02258301, 113.68509674, 0. ]), + 'frame': 605, + 'frame_number': 605, + 'framesequence': 603, + 'gaze_dir': array([0.98058069, 0.13569966, 0.14158796]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.13569966, 0.14158796]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.13569966, 0.14158796]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.905127476900816, + 'timestamp_carla': 13905, + 'timestamp_device': 13373, + 'timestamp_stream': 13.905127476900816, + 'transform': [array([3.92430115e+00, 1.33565607e-06, 1.79489132e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44197962, -0.76332319, -2.82818055]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.650928497314453, + 'FR_Wheel_Angle': -14.3980073928833, + 'Location': array([ 2.57469101e+01, -5.42851448e-01, 1.75163744e-03]), + 'Rotation': array([ 3.08724539e-03, 6.24799042e+01, -1.74804688e-01]), + 'Velocity': array([3.18017811e-01, 4.40213323e-01, 1.57761577e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 828.935302734375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([672.81628418, 112.48640442, 0. ]), + 'frame': 606, + 'frame_number': 606, + 'framesequence': 604, + 'gaze_dir': array([0.98058057, 0.1337042 , 0.1434738 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.1337042 , 0.1434738 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.1337042 , 0.1434738 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.918849878013134, + 'timestamp_carla': 13918, + 'timestamp_device': 13387, + 'timestamp_stream': 13.918849878013134, + 'transform': [array([3.93689990e+00, 1.34753975e-06, 1.79729459e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.43127912, -0.73024982, -2.8574574 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.649248123168945, + 'FR_Wheel_Angle': -14.396087646484375, + 'Location': array([ 2.58106289e+01, -4.72059250e-01, 1.75304885e-03]), + 'Rotation': array([ 2.68426421e-03, 6.19772415e+01, -1.67572051e-01]), + 'Velocity': array([ 3.25496852e-01, 4.41825241e-01, -5.74111937e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 832.6310424804688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([678.3550415 , 111.32644653, 0. ]), + 'frame': 607, + 'frame_number': 607, + 'framesequence': 605, + 'gaze_dir': array([0.98058057, 0.13153723, 0.14546306]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.13153723, 0.14546306]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.13153723, 0.14546306]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.933396376669407, + 'timestamp_carla': 13933, + 'timestamp_device': 13402, + 'timestamp_stream': 13.933396376669407, + 'transform': [array([3.95132399e+00, 1.34706477e-06, 1.79225917e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.42862627, -0.71288157, -2.89744139]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.645906448364258, + 'FR_Wheel_Angle': -14.39348030090332, + 'Location': array([ 2.58738060e+01, -4.03233439e-01, 1.73626421e-03]), + 'Rotation': array([ 2.64328299e-03, 6.14842682e+01, -1.68273896e-01]), + 'Velocity': array([3.34143817e-01, 4.45074350e-01, 1.94110864e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 836.5671997070312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.84072021e+02, 1.10039917e+02, -3.05175781e-05]), + 'frame': 608, + 'frame_number': 608, + 'framesequence': 606, + 'gaze_dir': array([0.98058057, 0.12963507, 0.14716077]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.12963507, 0.14716077]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.12963507, 0.14716077]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.947351276874542, + 'timestamp_carla': 13947, + 'timestamp_device': 13415, + 'timestamp_stream': 13.947351276874542, + 'transform': [array([3.96504903e+00, 1.35499499e-06, 1.79229735e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44083387, -0.71681511, -2.91181207]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.645042419433594, + 'FR_Wheel_Angle': -14.393050193786621, + 'Location': array([ 2.59380016e+01, -3.33580196e-01, 1.74454204e-03]), + 'Rotation': array([ 2.37690564e-03, 6.09832878e+01, -1.62139878e-01]), + 'Velocity': array([ 3.39584559e-01, 4.44470048e-01, -2.03390111e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 839.9541625976562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.89349976e+02, 1.08887703e+02, -3.05175781e-05]), + 'frame': 609, + 'frame_number': 609, + 'framesequence': 607, + 'gaze_dir': array([0.98058069, 0.12756221, 0.14896119]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12756221, 0.14896119]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12756221, 0.14896119]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.961370676755905, + 'timestamp_carla': 13961, + 'timestamp_device': 13429, + 'timestamp_stream': 13.961370676755905, + 'transform': [array([3.97872972e+00, 1.36831761e-06, 1.79210654e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44498843, -0.71148479, -2.95528102]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.642534255981445, + 'FR_Wheel_Angle': -14.391088485717773, + 'Location': array([ 2.60006313e+01, -2.67879397e-01, 1.76525593e-03]), + 'Rotation': array([ 2.48618866e-03, 6.05038872e+01, -1.65893540e-01]), + 'Velocity': array([ 3.48599702e-01, 4.48166370e-01, -2.25119584e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 843.5775756835938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.94825439e+02, 1.07608780e+02, -3.05175781e-05]), + 'frame': 610, + 'frame_number': 610, + 'framesequence': 608, + 'gaze_dir': array([0.98058069, 0.12546432, 0.1507324 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12546432, 0.1507324 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12546432, 0.1507324 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.97489507868886, + 'timestamp_carla': 13974, + 'timestamp_device': 13443, + 'timestamp_stream': 13.97489507868886, + 'transform': [array([3.99183035e+00, 1.37928384e-06, 1.79492950e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.46649757, -0.72725916, -3.63746738]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -21.518054962158203, + 'FR_Wheel_Angle': -18.487363815307617, + 'Location': array([ 2.60672112e+01, -1.99049681e-01, 1.76548481e-03]), + 'Rotation': array([ 2.06954731e-03, 5.99668159e+01, -1.58782929e-01]), + 'Velocity': array([3.69258106e-01, 4.34136748e-01, 1.65166857e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 847.1726684570312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.00264587e+02, 1.06290115e+02, -3.05175781e-05]), + 'frame': 611, + 'frame_number': 611, + 'framesequence': 609, + 'gaze_dir': array([0.98058069, 0.12334185, 0.15247406]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.12334185, 0.15247406]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.12334185, 0.15247406]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 13.98923097923398, + 'timestamp_carla': 13989, + 'timestamp_device': 13457, + 'timestamp_stream': 13.98923097923398, + 'transform': [array([4.00561523e+00, 1.39209885e-06, 1.79248804e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.4255684 , -0.63946825, -4.97535181]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.105710983276367, + 'FR_Wheel_Angle': -20.823711395263672, + 'Location': array([ 2.61400146e+01, -1.31170452e-01, 1.77483074e-03]), + 'Rotation': array([ 2.89600017e-03, 5.92014809e+01, -1.55883789e-01]), + 'Velocity': array([ 4.28727418e-01, 4.37881500e-01, -2.83684727e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 850.73876953125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.05612671e+02, 1.04931877e+02, -3.05175781e-05]), + 'frame': 612, + 'frame_number': 612, + 'framesequence': 610, + 'gaze_dir': array([0.98058057, 0.12104089, 0.15430699]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.12104089, 0.15430699]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.12104089, 0.15430699]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.003769677132368, + 'timestamp_carla': 14003, + 'timestamp_device': 13472, + 'timestamp_stream': 14.003769677132368, + 'transform': [array([4.01949358e+00, 1.39931194e-06, 1.78935996e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.4336516 , -0.61666483, -4.82321835]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.66417694091797, + 'FR_Wheel_Angle': -20.265945434570312, + 'Location': array([ 2.62229977e+01, -5.36014549e-02, 1.75491802e-03]), + 'Rotation': array([ 3.57901887e-03, 5.83190002e+01, -1.45172134e-01]), + 'Velocity': array([4.45350021e-01, 4.56688643e-01, 4.90665434e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 854.5226440429688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([711.27612305, 103.43236542, 0. ]), + 'frame': 613, + 'frame_number': 613, + 'framesequence': 611, + 'gaze_dir': array([0.98058069, 0.11871286, 0.15610512]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11871286, 0.15610512]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11871286, 0.15610512]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.0189328789711, + 'timestamp_carla': 14018, + 'timestamp_device': 13487, + 'timestamp_stream': 14.0189328789711, + 'transform': [array([4.03386116e+00, 1.41031092e-06, 1.78260799e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.4256717 , -0.58353049, -4.93018341]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.760082244873047, + 'FR_Wheel_Angle': -20.150022506713867, + 'Location': array([2.63030777e+01, 1.81290247e-02, 1.74618245e-03]), + 'Rotation': array([ 3.87954712e-03, 5.74704590e+01, -1.42425507e-01]), + 'Velocity': array([4.60362762e-01, 4.56171602e-01, 2.71739962e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 858.2673950195312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([716.90441895, 101.88754272, 0. ]), + 'frame': 614, + 'frame_number': 614, + 'framesequence': 612, + 'gaze_dir': array([0.98058069, 0.11651583, 0.15775174]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11651583, 0.15775174]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11651583, 0.15775174]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.032978877425194, + 'timestamp_carla': 14032, + 'timestamp_device': 13501, + 'timestamp_stream': 14.032978877425194, + 'transform': [array([4.04707956e+00, 1.42231102e-06, 1.78478239e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44343573, -0.58958024, -5.05412483]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.969175338745117, + 'FR_Wheel_Angle': -20.301393508911133, + 'Location': array([2.63805656e+01, 8.55699331e-02, 1.72523968e-03]), + 'Rotation': array([ 4.30301903e-03, 5.66664696e+01, -1.47003159e-01]), + 'Velocity': array([4.75688547e-01, 4.56803858e-01, 1.77860256e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 861.724365234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.22256226e+02, 1.00404716e+02, -3.05175781e-05]), + 'frame': 615, + 'frame_number': 615, + 'framesequence': 613, + 'gaze_dir': array([0.98058069, 0.11413649, 0.1594817 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11413649, 0.1594817 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11413649, 0.1594817 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.047890979796648, + 'timestamp_carla': 14047, + 'timestamp_device': 13516, + 'timestamp_stream': 14.047890979796648, + 'transform': [array([4.06101656e+00, 1.43347756e-06, 1.78108213e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.45765877, -0.5901736 , -5.12809372]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.90792465209961, + 'FR_Wheel_Angle': -20.266061782836914, + 'Location': array([2.64591846e+01, 1.52348384e-01, 1.73386093e-03]), + 'Rotation': array([ 4.55573574e-03, 5.58574486e+01, -1.49292007e-01]), + 'Velocity': array([4.89844322e-01, 4.57660973e-01, 4.28628919e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 865.3890991210938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.27727783e+02, 9.87726517e+01, 3.05175781e-05]), + 'frame': 616, + 'frame_number': 616, + 'framesequence': 614, + 'gaze_dir': array([0.98058069, 0.11173145, 0.16117577]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.11173145, 0.16117577]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.11173145, 0.16117577]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.062583480030298, + 'timestamp_carla': 14062, + 'timestamp_device': 13531, + 'timestamp_stream': 14.062583480030298, + 'transform': [array([4.07465410e+00, 1.44656735e-06, 1.77986140e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44081718, -0.54789221, -5.16957521]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.906505584716797, + 'FR_Wheel_Angle': -20.279125213623047, + 'Location': array([2.65509548e+01, 2.30211213e-01, 1.74889085e-03]), + 'Rotation': array([ 3.68147180e-03, 5.49162178e+01, -1.36932358e-01]), + 'Velocity': array([5.01865327e-01, 4.53497529e-01, 1.28808024e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 869.0067138671875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.33218140e+02, 9.70955658e+01, -3.05175781e-05]), + 'frame': 617, + 'frame_number': 617, + 'framesequence': 615, + 'gaze_dir': array([0.98058069, 0.10930144, 0.1628335 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.10930144, 0.1628335 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.10930144, 0.1628335 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.077213376760483, + 'timestamp_carla': 14077, + 'timestamp_device': 13546, + 'timestamp_stream': 14.077213376760483, + 'transform': [array([4.08814335e+00, 1.45682577e-06, 1.77944184e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.4268353 , -0.51292938, -5.23914051]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.90057945251465, + 'FR_Wheel_Angle': -20.275728225708008, + 'Location': array([2.66454678e+01, 3.08205545e-01, 1.74419873e-03]), + 'Rotation': array([ 3.10090580e-03, 5.39589767e+01, -1.29608139e-01]), + 'Velocity': array([ 5.16541302e-01, 4.50932920e-01, -5.32341001e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 872.57666015625, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 7.38624512e+02, 9.53740692e+01, -3.05175781e-05]), + 'frame': 618, + 'frame_number': 618, + 'framesequence': 616, + 'gaze_dir': array([0.98058069, 0.10701115, 0.16434769]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.10701115, 0.16434769]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.10701115, 0.16434769]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.091762878000736, + 'timestamp_carla': 14091, + 'timestamp_device': 13560, + 'timestamp_stream': 14.091762878000736, + 'transform': [array([4.10147142e+00, 1.47221590e-06, 1.77970878e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44419256, -0.51993203, -5.34322882]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.89646339416504, + 'FR_Wheel_Angle': -20.27162742614746, + 'Location': array([2.67295628e+01, 3.74212652e-01, 1.74263469e-03]), + 'Rotation': array([ 3.56535846e-03, 5.31227074e+01, -1.37451157e-01]), + 'Velocity': array([ 5.33583462e-01, 4.52221215e-01, -7.86590535e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 875.8633422851562, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 7.43695190e+02, 9.37273331e+01, -3.05175781e-05]), + 'frame': 619, + 'frame_number': 619, + 'framesequence': 617, + 'gaze_dir': array([0.98058057, 0.10436802, 0.16603872]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.10436802, 0.16603872]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.10436802, 0.16603872]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.107478179037571, + 'timestamp_carla': 14107, + 'timestamp_device': 13576, + 'timestamp_stream': 14.107478179037571, + 'transform': [array([4.11704350e+00, 1.48230686e-06, 1.77165982e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.43314105, -0.48790339, -5.37904453]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.8923282623291, + 'FR_Wheel_Angle': -20.26774024963379, + 'Location': array([2.68302460e+01, 4.53140855e-01, 1.75198074e-03]), + 'Rotation': array([ 2.74573592e-03, 5.21246872e+01, -1.25854462e-01]), + 'Velocity': array([ 5.45188844e-01, 4.45816934e-01, -1.25637045e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 879.5635986328125, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([749.21801758, 91.79850006, 0. ]), + 'frame': 620, + 'frame_number': 620, + 'framesequence': 618, + 'gaze_dir': array([0.98058069, 0.10203319, 0.16748366]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.10203319, 0.16748366]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.10203319, 0.16748366]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.122068479657173, + 'timestamp_carla': 14122, + 'timestamp_device': 13590, + 'timestamp_stream': 14.122068479657173, + 'transform': [array([4.13137770e+00, 1.49412062e-06, 1.77383423e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.44011733, -0.48154193, -5.46950531]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.886987686157227, + 'FR_Wheel_Angle': -20.263620376586914, + 'Location': array([2.69215984e+01, 5.21499455e-01, 1.74248219e-03]), + 'Rotation': array([ 2.84135854e-03, 5.12341270e+01, -1.28570557e-01]), + 'Velocity': array([ 5.61513662e-01, 4.44660187e-01, -4.13179405e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 882.7476806640625, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 7.54381287e+02, 9.00697479e+01, -3.05175781e-05]), + 'frame': 621, + 'frame_number': 621, + 'framesequence': 619, + 'gaze_dir': array([0.98058069, 0.0996785 , 0.16889565]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.0996785 , 0.16889565]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.0996785 , 0.16889565]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.13615307956934, + 'timestamp_carla': 14136, + 'timestamp_device': 13604, + 'timestamp_stream': 14.13615307956934, + 'transform': [array([4.14510536e+00, 1.50702874e-06, 1.77890772e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.42588359, -0.44824103, -5.4928112 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.885635375976562, + 'FR_Wheel_Angle': -20.259305953979492, + 'Location': array([2.70249329e+01, 5.97989142e-01, 1.74576277e-03]), + 'Rotation': array([ 2.03539617e-03, 5.02318687e+01, -1.16943344e-01]), + 'Velocity': array([5.71804225e-01, 4.36587095e-01, 2.50515935e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 885.8845825195312, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([759.36663818, 88.30383301, 0. ]), + 'frame': 622, + 'frame_number': 622, + 'framesequence': 620, + 'gaze_dir': array([0.98058057, 0.09730428, 0.17027456]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.09730428, 0.17027456]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.09730428, 0.17027456]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.149790178984404, + 'timestamp_carla': 14149, + 'timestamp_device': 13618, + 'timestamp_stream': 14.149790178984404, + 'transform': [array([4.15829897e+00, 1.51443749e-06, 1.78562163e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.4469007 , -0.45490029, -5.91024971]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -27.212392807006836, + 'FR_Wheel_Angle': -22.274789810180664, + 'Location': array([2.71235027e+01, 6.67793393e-01, 1.72966474e-03]), + 'Rotation': array([ 1.89196225e-03, 4.92818146e+01, -1.17126428e-01]), + 'Velocity': array([ 5.94077408e-01, 4.26496983e-01, -1.92832940e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 888.9703979492188, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 7.64233521e+02, 8.65008240e+01, -3.05175781e-05]), + 'frame': 623, + 'frame_number': 623, + 'framesequence': 621, + 'gaze_dir': array([0.98058069, 0.09491099, 0.17162007]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.09491099, 0.17162007]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.09491099, 0.17162007]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.164008978754282, + 'timestamp_carla': 14164, + 'timestamp_device': 13632, + 'timestamp_stream': 14.164008978754282, + 'transform': [array([4.17195559e+00, 1.52294967e-06, 1.78775785e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.42243525, -0.40675467, -7.96068239]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.089900970458984, + 'FR_Wheel_Angle': -26.69013214111328, + 'Location': array([2.72350540e+01, 7.37992942e-01, 1.75137038e-03]), + 'Rotation': array([ 9.28905676e-04, 4.80077324e+01, -1.04492180e-01]), + 'Velocity': array([6.49840891e-01, 3.72481287e-01, 3.05447582e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 892.0028686523438, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 7.68986328e+02, 8.46610794e+01, -6.10351562e-05]), + 'frame': 624, + 'frame_number': 624, + 'framesequence': 622, + 'gaze_dir': array([0.98058057, 0.09232621, 0.17302431]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.09232621, 0.17302431]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.09232621, 0.17302431]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.178662277758121, + 'timestamp_carla': 14178, + 'timestamp_device': 13647, + 'timestamp_stream': 14.178662277758121, + 'transform': [array([4.18592596e+00, 1.53539679e-06, 1.78680418e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37277201, -0.33957529, -7.78269386]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.51551055908203, + 'FR_Wheel_Angle': -25.372175216674805, + 'Location': array([2.73528194e+01, 8.06714356e-01, 1.74335949e-03]), + 'Rotation': array([ 1.77584914e-03, 4.65897179e+01, -1.00250237e-01]), + 'Velocity': array([6.88955069e-01, 3.94275695e-01, 3.57818608e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 895.1881103515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.73958740e+02, 8.26495285e+01, 3.05175781e-05]), + 'frame': 625, + 'frame_number': 625, + 'framesequence': 623, + 'gaze_dir': array([0.98058069, 0.08989491, 0.1742999 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.08989491, 0.1742999 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.08989491, 0.1742999 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.192987978458405, + 'timestamp_carla': 14192, + 'timestamp_device': 13661, + 'timestamp_stream': 14.192987978458405, + 'transform': [array([4.19948816e+00, 1.54563668e-06, 1.78821560e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.35900736, -0.30775771, -8.05798149]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.18169021606445, + 'FR_Wheel_Angle': -25.563297271728516, + 'Location': array([2.74775295e+01, 8.76206815e-01, 1.72977918e-03]), + 'Rotation': array([ 1.44800008e-03, 4.51118088e+01, -9.25292820e-02]), + 'Velocity': array([7.07302153e-01, 3.72577995e-01, 1.30238535e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 898.1005859375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.78653809e+02, 8.07348709e+01, 3.05175781e-05]), + 'frame': 626, + 'frame_number': 626, + 'framesequence': 624, + 'gaze_dir': array([0.98058069, 0.08727035, 0.17562869]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.08727035, 0.17562869]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.08727035, 0.17562869]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.207230579108, + 'timestamp_carla': 14207, + 'timestamp_device': 13676, + 'timestamp_stream': 14.207230579108, + 'transform': [array([4.21287918e+00, 1.55671012e-06, 1.78981782e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.37181199, -0.30254346, -8.20415497]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.22123336791992, + 'FR_Wheel_Angle': -25.658218383789062, + 'Location': array([2.75913029e+01, 9.35952663e-01, 1.71520701e-03]), + 'Rotation': array([ 1.63241511e-03, 4.37870941e+01, -9.33532491e-02]), + 'Velocity': array([7.28521764e-01, 3.62665504e-01, 4.63118544e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 901.1555786132812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([783.46936035, 78.64435577, 0. ]), + 'frame': 627, + 'frame_number': 627, + 'framesequence': 625, + 'gaze_dir': array([0.98058069, 0.08427215, 0.17708685]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.08427215, 0.17708685]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.08427215, 0.17708685]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.22472557798028, + 'timestamp_carla': 14224, + 'timestamp_device': 13693, + 'timestamp_stream': 14.22472557798028, + 'transform': [array([4.22919989e+00, 1.56510600e-06, 1.76437374e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.3609373 , -0.27775806, -8.25526905]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.13623046875, + 'FR_Wheel_Angle': -25.614330291748047, + 'Location': array([2.77153339e+01, 9.98129606e-01, 1.72722340e-03]), + 'Rotation': array([ 1.08600000e-03, 4.23559723e+01, -8.64562839e-02]), + 'Velocity': array([7.43594289e-01, 3.47792268e-01, 4.93397703e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 904.5321044921875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.88631836e+02, 7.62270660e+01, -3.05175781e-05]), + 'frame': 628, + 'frame_number': 628, + 'framesequence': 626, + 'gaze_dir': array([0.98058069, 0.08160658, 0.17833091]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.08160658, 0.17833091]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.08160658, 0.17833091]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.239830579608679, + 'timestamp_carla': 14239, + 'timestamp_device': 13708, + 'timestamp_stream': 14.239830579608679, + 'transform': [array([4.24318981e+00, 1.57611430e-06, 1.76582334e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.34337851, -0.25059363, -8.33684254]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.12367630004883, + 'FR_Wheel_Angle': -25.59853172302246, + 'Location': array([2.78439960e+01, 1.05910218e+00, 1.72134873e-03]), + 'Rotation': array([ 4.09811328e-04, 4.08895454e+01, -7.99255297e-02]), + 'Velocity': array([ 7.60036051e-01, 3.31867099e-01, -4.48322280e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 907.4249267578125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.93541016e+02, 7.40520401e+01, -6.10351562e-05]), + 'frame': 629, + 'frame_number': 629, + 'framesequence': 627, + 'gaze_dir': array([0.98058069, 0.07892248, 0.17953493]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.07892248, 0.17953493]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.07892248, 0.17953493]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.25493597984314, + 'timestamp_carla': 14254, + 'timestamp_device': 13723, + 'timestamp_stream': 14.25493597984314, + 'transform': [array([4.25708389e+00, 1.58978139e-06, 1.76715851e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.31851596, -0.21965164, -8.40141392]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.1198844909668, + 'FR_Wheel_Angle': -25.593399047851562, + 'Location': array([2.79806557e+01, 1.12029982e+00, 1.72623154e-03]), + 'Rotation': array([-3.96150950e-04, 3.93485603e+01, -7.18688890e-02]), + 'Velocity': array([7.74891138e-01, 3.13579232e-01, 2.67734518e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 910.2496337890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.98138672e+02, 7.18393631e+01, 3.05175781e-05]), + 'frame': 630, + 'frame_number': 630, + 'framesequence': 628, + 'gaze_dir': array([0.98058069, 0.07640135, 0.18062221]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.07640135, 0.18062221]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.07640135, 0.18062221]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.26953137665987, + 'timestamp_carla': 14269, + 'timestamp_device': 13737, + 'timestamp_stream': 14.26953137665987, + 'transform': [array([4.27155638e+00, 1.59249623e-06, 1.77085877e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.30571419, -0.19982909, -8.51459026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.11326599121094, + 'FR_Wheel_Angle': -25.587966918945312, + 'Location': array([2.81151199e+01, 1.17648256e+00, 1.74145214e-03]), + 'Rotation': array([-8.53773614e-04, 3.78504601e+01, -6.85119480e-02]), + 'Velocity': array([ 7.93609083e-01, 2.97119975e-01, -1.66034697e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 912.8161010742188, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 8.02434204e+02, 6.97405853e+01, -3.05175781e-05]), + 'frame': 631, + 'frame_number': 631, + 'framesequence': 629, + 'gaze_dir': array([0.98058069, 0.07368346, 0.18174788]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.07368346, 0.18174788]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.07368346, 0.18174788]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.283732779324055, + 'timestamp_carla': 14283, + 'timestamp_device': 13752, + 'timestamp_stream': 14.283732779324055, + 'transform': [array([4.28552246e+00, 1.59986769e-06, 1.77650445e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.28875092, -0.17811824, -8.58363056]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.109214782714844, + 'FR_Wheel_Angle': -25.58291244506836, + 'Location': array([2.82560215e+01, 1.23154712e+00, 1.74526684e-03]), + 'Rotation': array([-1.46849058e-03, 3.62973938e+01, -6.29577562e-02]), + 'Velocity': array([8.08067143e-01, 2.77659893e-01, 9.25779314e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 915.4890747070312, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([ 8.06908020e+02, 6.74566116e+01, -3.05175781e-05]), + 'frame': 632, + 'frame_number': 632, + 'framesequence': 630, + 'gaze_dir': array([0.98058069, 0.07113186, 0.18276161]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.07113186, 0.18276161]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.07113186, 0.18276161]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.29833147674799, + 'timestamp_carla': 14298, + 'timestamp_device': 13766, + 'timestamp_stream': 14.29833147674799, + 'transform': [array([4.29976416e+00, 1.60466857e-06, 1.77879329e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.27978444, -0.16351661, -8.70376205]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.102108001708984, + 'FR_Wheel_Angle': -25.57788848876953, + 'Location': array([2.83911686e+01, 1.28042936e+00, 1.73496723e-03]), + 'Rotation': array([-1.76901894e-03, 3.48238144e+01, -6.13403320e-02]), + 'Velocity': array([8.26565087e-01, 2.60345042e-01, 4.79936607e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 917.9103393554688, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([811.04602051, 65.29286194, 0. ]), + 'frame': 633, + 'frame_number': 633, + 'framesequence': 631, + 'gaze_dir': array([0.98058069, 0.06838247, 0.183808 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.06838247, 0.183808 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.06838247, 0.183808 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.31300788000226, + 'timestamp_carla': 14313, + 'timestamp_device': 13781, + 'timestamp_stream': 14.31300788000226, + 'transform': [array([4.31396914e+00, 1.61863841e-06, 1.78031914e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.256473 , -0.14045164, -8.7222147 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.101051330566406, + 'FR_Wheel_Angle': -25.573097229003906, + 'Location': array([2.85410500e+01, 1.33085418e+00, 1.74446579e-03]), + 'Rotation': array([-2.53399997e-03, 3.32043533e+01, -5.34973033e-02]), + 'Velocity': array([8.35507929e-01, 2.37252250e-01, 1.28130909e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 920.4218139648438, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([8.15314087e+02, 6.29409256e+01, 3.05175781e-05]), + 'frame': 634, + 'frame_number': 634, + 'framesequence': 632, + 'gaze_dir': array([0.98058069, 0.06580256, 0.18474731]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.06580256, 0.18474731]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.06580256, 0.18474731]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.327211879193783, + 'timestamp_carla': 14327, + 'timestamp_device': 13795, + 'timestamp_stream': 14.327211879193783, + 'transform': [array([4.32761478e+00, 1.62982826e-06, 1.78459159e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.2822701 , -0.14216331, -9.4143877 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -35.60255432128906, + 'FR_Wheel_Angle': -27.6268253326416, + 'Location': array([2.86832047e+01, 1.37401819e+00, 1.73798075e-03]), + 'Rotation': array([-3.2033585e-03, 3.1663250e+01, -4.8919674e-02]), + 'Velocity': array([8.53776217e-01, 1.99326381e-01, 1.77936556e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 922.6880493164062, + 'focus_actor_name': 'Road_Marking_Town05_97', + 'focus_actor_pt': array([8.19300659e+02, 6.07154427e+01, 3.05175781e-05]), + 'frame': 635, + 'frame_number': 635, + 'framesequence': 633, + 'gaze_dir': array([0.98058069, 0.06320974, 0.18565041]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.06320974, 0.18565041]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.06320974, 0.18565041]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.34118877723813, + 'timestamp_carla': 14341, + 'timestamp_device': 13809, + 'timestamp_stream': 14.34118877723813, + 'transform': [array([4.34094810e+00, 1.63276195e-06, 1.78935996e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ -0.18762285, -0.09066191, -11.01350975]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.14059829711914, + 'FR_Wheel_Angle': -30.167871475219727, + 'Location': array([2.88309841e+01, 1.40761864e+00, 1.75308704e-03]), + 'Rotation': array([-4.91090585e-03, 2.98055534e+01, -3.60717699e-02]), + 'Velocity': array([8.74686718e-01, 1.22849502e-01, 4.70294937e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 924.8785400390625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.23145386e+02, 5.84615402e+01, -6.10351562e-05]), + 'frame': 636, + 'frame_number': 636, + 'framesequence': 634, + 'gaze_dir': array([0.98058069, 0.0607911 , 0.1864564 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.0607911 , 0.1864564 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.0607911 , 0.1864564 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.354243278503418, + 'timestamp_carla': 14354, + 'timestamp_device': 13822, + 'timestamp_stream': 14.354243278503418, + 'transform': [array([4.35332060e+00, 1.64286212e-06, 1.79786677e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ -0.14706087, -0.06454972, -11.21695232]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.368896484375, + 'FR_Wheel_Angle': -30.58442497253418, + 'Location': array([2.89895020e+01, 1.43710291e+00, 1.76575175e-03]), + 'Rotation': array([-5.58026414e-03, 2.77666683e+01, -2.67639160e-02]), + 'Velocity': array([ 8.91756177e-01, 9.15268287e-02, -1.54304507e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 926.84228515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([826.70202637, 56.34395981, 0. ]), + 'frame': 637, + 'frame_number': 637, + 'framesequence': 635, + 'gaze_dir': array([0.98058069, 0.05817485, 0.18728916]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.05817485, 0.18728916]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.05817485, 0.18728916]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.368503779172897, + 'timestamp_carla': 14368, + 'timestamp_device': 13836, + 'timestamp_stream': 14.368503779172897, + 'transform': [array([4.36674595e+00, 1.65049437e-06, 1.79809565e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ -0.11422637, -0.04716407, -11.36570168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.312591552734375, + 'FR_Wheel_Angle': -30.56691551208496, + 'Location': array([2.91404343e+01, 1.45936871e+00, 1.73866749e-03]), + 'Rotation': array([-6.13350933e-03, 2.58115692e+01, -2.09655743e-02]), + 'Velocity': array([ 9.05926347e-01, 6.16182350e-02, -6.31227507e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 928.881103515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.30247681e+02, 5.40377350e+01, -3.05175781e-05]), + 'frame': 638, + 'frame_number': 638, + 'framesequence': 636, + 'gaze_dir': array([0.98058069, 0.05573515, 0.18802962]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.05573515, 0.18802962]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.05573515, 0.18802962]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.381035178899765, + 'timestamp_carla': 14381, + 'timestamp_device': 13849, + 'timestamp_stream': 14.381035178899765, + 'transform': [array([4.37847137e+00, 1.66145139e-06, 1.80709839e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ -0.08736618, -0.03390764, -11.42919827]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.358699798583984, + 'FR_Wheel_Angle': -30.57557487487793, + 'Location': array([2.92954712e+01, 1.47718585e+00, 1.77772995e-03]), + 'Rotation': array([-6.77554728e-03, 2.38117161e+01, -1.47094717e-02]), + 'Velocity': array([ 9.10816312e-01, 2.92677544e-02, -6.71195958e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 930.69921875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.33649048e+02, 5.18728790e+01, -3.05175781e-05]), + 'frame': 639, + 'frame_number': 639, + 'framesequence': 637, + 'gaze_dir': array([0.98058057, 0.05328621, 0.18873823]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058057, 0.05328621, 0.18873823]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058057, 0.05328621, 0.18873823]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.39385587722063, + 'timestamp_carla': 14393, + 'timestamp_device': 13862, + 'timestamp_stream': 14.39385587722063, + 'transform': [array([4.39039660e+00, 1.67055964e-06, 1.81297294e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ -0.06050988, -0.02315584, -11.47029591]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.357322692871094, + 'FR_Wheel_Angle': -30.572519302368164, + 'Location': array([2.94508057e+01, 1.48992693e+00, 1.77071092e-03]), + 'Rotation': array([-7.50637753e-03, 2.18166275e+01, -8.54492094e-03]), + 'Velocity': array([ 9.13368225e-01, -2.93194549e-03, -3.35474004e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 932.4486694335938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([836.80200195, 49.68687439, 0. ]), + 'frame': 640, + 'frame_number': 640, + 'framesequence': 638, + 'gaze_dir': array([0.98058069, 0.05101756, 0.18936408]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.05101756, 0.18936408]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.05101756, 0.18936408]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.406312178820372, + 'timestamp_carla': 14406, + 'timestamp_device': 13874, + 'timestamp_stream': 14.406312178820372, + 'transform': [array([4.40191650e+00, 1.68479028e-06, 1.81915273e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-2.40397658e-02, -1.09513756e-02, -1.14456291e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.356361389160156, + 'FR_Wheel_Angle': -30.568885803222656, + 'Location': array([2.96048203e+01, 1.49754763e+00, 1.80477614e-03]), + 'Rotation': array([-8.27135891e-03, 1.98442860e+01, -2.50244117e-03]), + 'Velocity': array([ 9.14138854e-01, -3.39019299e-02, 3.28760128e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 933.9985961914062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([839.74926758, 47.65054321, 0. ]), + 'frame': 641, + 'frame_number': 641, + 'framesequence': 639, + 'gaze_dir': array([0.98058069, 0.04874156, 0.18996264]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.04874156, 0.18996264]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.04874156, 0.18996264]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.418230477720499, + 'timestamp_carla': 14418, + 'timestamp_device': 13886, + 'timestamp_stream': 14.418230477720499, + 'transform': [array([4.41287947e+00, 1.69394059e-06, 1.82617188e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 6.62796851e-03, -3.77351046e-03, -1.14579315e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.35965347290039, + 'FR_Wheel_Angle': -30.565828323364258, + 'Location': array([2.97534637e+01, 1.50023282e+00, 1.79646013e-03]), + 'Rotation': array([-9.12513211e-03, 1.79467163e+01, 3.51499394e-03]), + 'Velocity': array([ 9.14126396e-01, -6.43322915e-02, 1.29575725e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 935.4859619140625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([842.58508301, 45.59725952, 0. ]), + 'frame': 642, + 'frame_number': 642, + 'framesequence': 640, + 'gaze_dir': array([0.98058069, 0.0462679 , 0.19058023]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.0462679 , 0.19058023]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.0462679 , 0.19058023]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.430827379226685, + 'timestamp_carla': 14430, + 'timestamp_device': 13899, + 'timestamp_stream': 14.430827379226685, + 'transform': [array([4.42538309e+00, 1.69919781e-06, 1.82281493e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 3.88162769e-02, 1.27851916e-03, -1.14175520e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.357398986816406, + 'FR_Wheel_Angle': -30.564258575439453, + 'Location': array([2.99179802e+01, 1.49779749e+00, 1.77849294e-03]), + 'Rotation': array([-9.91743430e-03, 1.58486214e+01, 9.78240650e-03]), + 'Velocity': array([ 9.08046007e-01, -9.76626873e-02, 1.44710531e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 937.0257568359375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([845.42456055, 43.35443115, 0. ]), + 'frame': 643, + 'frame_number': 643, + 'framesequence': 641, + 'gaze_dir': array([0.98058069, 0.04397783, 0.19112167]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.04397783, 0.19112167]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.04397783, 0.19112167]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.443239979445934, + 'timestamp_carla': 14443, + 'timestamp_device': 13911, + 'timestamp_stream': 14.443239979445934, + 'transform': [array([4.43761444e+00, 1.70679277e-06, 1.82106008e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 7.23936334e-02, 4.01998218e-03, -1.13676090e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.35964584350586, + 'FR_Wheel_Angle': -30.562294006347656, + 'Location': array([3.00710812e+01, 1.49049044e+00, 1.78287982e-03]), + 'Rotation': array([-1.07370568e-02, 1.38964157e+01, 1.57813821e-02]), + 'Velocity': array([ 9.00937021e-01, -1.28177449e-01, -2.03561780e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 938.3768920898438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.48205200e+02, 4.12679977e+01, -3.05175781e-05]), + 'frame': 644, + 'frame_number': 644, + 'framesequence': 642, + 'gaze_dir': array([0.98058069, 0.04148951, 0.19167724]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.04148951, 0.19167724]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.04148951, 0.19167724]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.45580467954278, + 'timestamp_carla': 14455, + 'timestamp_device': 13924, + 'timestamp_stream': 14.45580467954278, + 'transform': [array([4.44990873e+00, 1.71336796e-06, 1.81896205e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 1.03433751e-01, 4.26229415e-03, -1.13095150e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.367408752441406, + 'FR_Wheel_Angle': -30.560894012451172, + 'Location': array([3.02264614e+01, 1.47803819e+00, 1.80042745e-03]), + 'Rotation': array([-1.14132455e-02, 1.19120941e+01, 2.14583315e-02]), + 'Velocity': array([ 8.91527593e-01, -1.58760786e-01, 1.40867225e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 939.767822265625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([851.00341797, 38.99072266, 0. ]), + 'frame': 645, + 'frame_number': 645, + 'framesequence': 643, + 'gaze_dir': array([0.98058069, 0.03918643, 0.19216129]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.03918643, 0.19216129]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.03918643, 0.19216129]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.468552079051733, + 'timestamp_carla': 14468, + 'timestamp_device': 13936, + 'timestamp_stream': 14.468552079051733, + 'transform': [array([4.46229506e+00, 1.72853447e-06, 1.81640626e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 1.32647887e-01, 2.58108834e-03, -1.12299004e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.286502838134766, + 'FR_Wheel_Angle': -30.578529357910156, + 'Location': array([3.03923874e+01, 1.45907831e+00, 1.79558271e-03]), + 'Rotation': array([-0.01215091, 9.7885952 , 0.02711736]), + 'Velocity': array([ 8.79056811e-01, -1.90578893e-01, -2.56538397e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 940.9829711914062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.53609009e+02, 3.68739853e+01, -3.05175781e-05]), + 'frame': 646, + 'frame_number': 646, + 'framesequence': 644, + 'gaze_dir': array([0.98058069, 0.03668518, 0.19265445]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.03668518, 0.19265445]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.03668518, 0.19265445]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.481061577796936, + 'timestamp_carla': 14481, + 'timestamp_device': 13949, + 'timestamp_stream': 14.481061577796936, + 'transform': [array([4.47437048e+00, 1.73554736e-06, 1.81556703e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 1.57201156e-01, -3.38437920e-03, -1.11208105e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.374847412109375, + 'FR_Wheel_Angle': -30.557174682617188, + 'Location': array([3.05540218e+01, 1.43501639e+00, 1.85455789e-03]), + 'Rotation': array([-0.01269732, 7.71237612, 0.0315337 ]), + 'Velocity': array([ 8.61595154e-01, -2.20406011e-01, 3.12185293e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 942.2239379882812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.56253052e+02, 3.45658798e+01, 3.05175781e-05]), + 'frame': 647, + 'frame_number': 647, + 'framesequence': 645, + 'gaze_dir': array([0.98058069, 0.03417755, 0.19311509]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.03417755, 0.19311509]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.03417755, 0.19311509]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.494046580046415, + 'timestamp_carla': 14494, + 'timestamp_device': 13962, + 'timestamp_stream': 14.494046580046415, + 'transform': [array([4.48682165e+00, 1.74564286e-06, 1.81243895e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 1.91758305e-01, -8.05496145e-03, -1.10854511e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.376834869384766, + 'FR_Wheel_Angle': -30.556392669677734, + 'Location': array([3.07016106e+01, 1.40854001e+00, 1.83453073e-03]), + 'Rotation': array([-0.01369453, 5.81213522, 0.03919761]), + 'Velocity': array([ 8.51070285e-01, -2.48314694e-01, 1.93548200e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 943.3865966796875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.58777222e+02, 3.22428665e+01, 3.05175781e-05]), + 'frame': 648, + 'frame_number': 648, + 'framesequence': 646, + 'gaze_dir': array([0.98058069, 0.03185775, 0.19351131]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.03185775, 0.19351131]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.03185775, 0.19351131]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.506703078746796, + 'timestamp_carla': 14506, + 'timestamp_device': 13974, + 'timestamp_stream': 14.506703078746796, + 'transform': [array([4.49888134e+00, 1.75531932e-06, 1.81163789e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.22757527, -0.01598396, -11.00711632]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.38135528564453, + 'FR_Wheel_Angle': -30.556427001953125, + 'Location': array([3.08451710e+01, 1.37842417e+00, 1.83483597e-03]), + 'Rotation': array([-0.01465075, 3.95510101, 0.04634454]), + 'Velocity': array([ 8.36508930e-01, -2.74116337e-01, 1.64299010e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 944.38818359375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([861.15673828, 30.08630943, 0. ]), + 'frame': 649, + 'frame_number': 649, + 'framesequence': 647, + 'gaze_dir': array([0.98058069, 0.02933957, 0.19390908]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.02933957, 0.19390908]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.02933957, 0.19390908]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.519256677478552, + 'timestamp_carla': 14519, + 'timestamp_device': 13987, + 'timestamp_stream': 14.519256677478552, + 'transform': [array([4.51076937e+00, 1.76957792e-06, 1.81148527e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.26478282, -0.02527082, -10.93650723]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.38944625854492, + 'FR_Wheel_Angle': -30.559114456176758, + 'Location': array([3.09806480e+01, 1.34613371e+00, 1.85055251e-03]), + 'Rotation': array([-0.01571626, 2.1947484 , 0.05449846]), + 'Velocity': array([ 8.22289228e-01, -2.98052073e-01, 5.93948353e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 945.3966674804688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([863.50463867, 27.73776627, 0. ]), + 'frame': 650, + 'frame_number': 650, + 'framesequence': 648, + 'gaze_dir': array([0.98058069, 0.02662207, 0.1943008 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.02662207, 0.1943008 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.02662207, 0.1943008 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.532986678183079, + 'timestamp_carla': 14532, + 'timestamp_device': 14001, + 'timestamp_stream': 14.532986678183079, + 'transform': [array([4.52368879e+00, 1.77941263e-06, 1.80496217e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.28587133, -0.03699211, -10.79211426]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.39385986328125, + 'FR_Wheel_Angle': -30.5584659576416, + 'Location': array([3.11294727e+01, 1.30543220e+00, 1.87805644e-03]), + 'Rotation': array([-0.01614657, 0.2431507 , 0.05860133]), + 'Velocity': array([ 8.00709605e-01, -3.21817547e-01, 4.87594603e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 946.3920288085938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.65820679e+02, 2.51951485e+01, 3.05175781e-05]), + 'frame': 651, + 'frame_number': 651, + 'framesequence': 649, + 'gaze_dir': array([0.98058069, 0.02389935, 0.19465446]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.02389935, 0.19465446]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.02389935, 0.19465446]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.547155279666185, + 'timestamp_carla': 14547, + 'timestamp_device': 14015, + 'timestamp_stream': 14.547155279666185, + 'transform': [array([4.53693247e+00, 1.78931725e-06, 1.79706572e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.32591274, -0.05086128, -10.69653702]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.399131774902344, + 'FR_Wheel_Angle': -30.558643341064453, + 'Location': array([3.12587566e+01, 1.26667273e+00, 1.85394764e-03]), + 'Rotation': array([-0.01718475, -1.45922852, 0.06697067]), + 'Velocity': array([ 7.83643186e-01, -3.42725128e-01, -3.42688552e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 947.2906494140625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.68130493e+02, 2.26398602e+01, 3.05175781e-05]), + 'frame': 652, + 'frame_number': 652, + 'framesequence': 650, + 'gaze_dir': array([0.98058069, 0.02117195, 0.19496997]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.02117195, 0.19496997]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.02117195, 0.19496997]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.560732278972864, + 'timestamp_carla': 14560, + 'timestamp_device': 14029, + 'timestamp_stream': 14.560732278972864, + 'transform': [array([4.54954290e+00, 1.80044196e-06, 1.79450982e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3534002 , -0.0666681 , -10.54956245]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4075813293457, + 'FR_Wheel_Angle': -30.562509536743164, + 'Location': array([3.13894882e+01, 1.22352505e+00, 1.85177324e-03]), + 'Rotation': array([-0.01776532, -3.19522142, 0.07189446]), + 'Velocity': array([ 7.62011111e-01, -3.61567229e-01, -6.15310637e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 948.0931396484375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.70364014e+02, 2.00732117e+01, -3.05175781e-05]), + 'frame': 653, + 'frame_number': 653, + 'framesequence': 651, + 'gaze_dir': array([0.98058069, 0.01883082, 0.19520999]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.01883082, 0.19520999]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.01883082, 0.19520999]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.573605477809906, + 'timestamp_carla': 14573, + 'timestamp_device': 14041, + 'timestamp_stream': 14.573605477809906, + 'transform': [array([4.56142902e+00, 1.81067253e-06, 1.79634092e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.37106058, -0.08244354, -10.37975407]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.41728591918945, + 'FR_Wheel_Angle': -30.564767837524414, + 'Location': array([3.15219479e+01, 1.17539573e+00, 1.85070513e-03]), + 'Rotation': array([-0.01794291, -4.97235394, 0.0745009 ]), + 'Velocity': array([ 7.38057673e-01, -3.79052043e-01, -1.69415463e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 948.70556640625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.72318726e+02, 1.78651390e+01, -3.05175781e-05]), + 'frame': 654, + 'frame_number': 654, + 'framesequence': 652, + 'gaze_dir': array([0.98058069, 0.01629148, 0.19543828]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.01629148, 0.19543828]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.01629148, 0.19543828]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.586320478469133, + 'timestamp_carla': 14586, + 'timestamp_device': 14054, + 'timestamp_stream': 14.586320478469133, + 'transform': [array([4.57405090e+00, 1.81508699e-06, 1.79733278e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.380128 , -0.09741484, -10.19724655]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.42771530151367, + 'FR_Wheel_Angle': -30.56746482849121, + 'Location': array([3.16553116e+01, 1.12246513e+00, 1.84486865e-03]), + 'Rotation': array([-0.01803853, -6.78122473, 0.07611126]), + 'Velocity': array([ 7.12663531e-01, -3.95247072e-01, -4.55379486e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 949.2900390625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.74169067e+02, 1.54655704e+01, -3.05175781e-05]), + 'frame': 655, + 'frame_number': 655, + 'framesequence': 653, + 'gaze_dir': array([0.98058069, 0.01374956, 0.19563356]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.01374956, 0.19563356]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.01374956, 0.19563356]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.59906467795372, + 'timestamp_carla': 14599, + 'timestamp_device': 14067, + 'timestamp_stream': 14.59906467795372, + 'transform': [array([4.58660841e+00, 1.82022791e-06, 1.79824827e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39205006, -0.11349297, -10.01926517]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4378547668457, + 'FR_Wheel_Angle': -30.56877326965332, + 'Location': array([3.17862301e+01, 1.06616402e+00, 1.84067246e-03]), + 'Rotation': array([-0.01824343, -8.57630444, 0.07881651]), + 'Velocity': array([ 6.87429190e-01, -4.10258979e-01, -1.36308663e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 949.7903442382812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([875.99768066, 13.05943966, 0. ]), + 'frame': 656, + 'frame_number': 656, + 'framesequence': 654, + 'gaze_dir': array([0.98058069, 0.01120514, 0.19579576]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.01120514, 0.19579576]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.01120514, 0.19579576]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.612238679081202, + 'timestamp_carla': 14612, + 'timestamp_device': 14080, + 'timestamp_stream': 14.612238679081202, + 'transform': [array([4.59949446e+00, 1.83640032e-06, 1.79706572e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41276628, -0.13218343, -9.85897255]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.447322845458984, + 'FR_Wheel_Angle': -30.570005416870117, + 'Location': array([3.19105949e+01, 1.00893593e+00, 1.89941877e-03]), + 'Rotation': array([ -0.01891279, -10.29777622, 0.08449691]), + 'Velocity': array([ 6.63733363e-01, -4.24046516e-01, 1.77521695e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.20654296875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([877.72460938, 10.64743614, 0. ]), + 'frame': 657, + 'frame_number': 657, + 'framesequence': 655, + 'gaze_dir': array([0.98058069, 0.00865902, 0.19592488]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00865902, 0.19592488]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00865902, 0.19592488]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.62538167834282, + 'timestamp_carla': 14625, + 'timestamp_device': 14093, + 'timestamp_stream': 14.62538167834282, + 'transform': [array([4.61225986e+00, 1.84348301e-06, 1.79653161e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.45160756, -0.15527965, -9.73952007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.45396041870117, + 'FR_Wheel_Angle': -30.573604583740234, + 'Location': array([3.20220947e+01, 9.55042422e-01, 1.87881943e-03]), + 'Rotation': array([ -0.02034713, -11.84972 , 0.09595986]), + 'Velocity': array([ 6.43930316e-01, -4.36796904e-01, -2.22678180e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.537353515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.79387939e+02, 8.23095608e+00, -3.05175781e-05]), + 'frame': 658, + 'frame_number': 658, + 'framesequence': 656, + 'gaze_dir': array([0.98058069, 0.00591532, 0.19602691]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00591532, 0.19602691]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00591532, 0.19602691]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.638461876660585, + 'timestamp_carla': 14638, + 'timestamp_device': 14107, + 'timestamp_stream': 14.638461876660585, + 'transform': [array([4.62487650e+00, 1.85704300e-06, 1.79656979e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.47865388, -0.18083465, -9.55526924]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.46455383300781, + 'FR_Wheel_Angle': -30.57759666442871, + 'Location': array([3.21342506e+01, 8.97074819e-01, 1.88423635e-03]), + 'Rotation': array([ -0.02090721, -13.43297291, 0.10067835]), + 'Velocity': array([ 6.19292080e-01, -4.46122110e-01, 7.07149502e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.7990112304688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.80960815e+02, 5.62451982e+00, -3.05175781e-05]), + 'frame': 659, + 'frame_number': 659, + 'framesequence': 657, + 'gaze_dir': array([0.98058069, 0.00375858, 0.1960801 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00375858, 0.1960801 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00375858, 0.1960801 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.650633979588747, + 'timestamp_carla': 14650, + 'timestamp_device': 14118, + 'timestamp_stream': 14.650633979588747, + 'transform': [array([4.63654375e+00, 1.86217926e-06, 1.80103292e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49751484, -0.20259185, -9.38456631]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4742317199707, + 'FR_Wheel_Angle': -30.5805721282959, + 'Location': array([3.22415771e+01, 8.38648081e-01, 1.87683583e-03]), + 'Rotation': array([ -0.0215151 , -14.9623909 , 0.10618205]), + 'Velocity': array([ 5.96028924e-01, -4.54436094e-01, -1.57146453e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.9356079101562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([882.37719727, 3.57441282, 0. ]), + 'frame': 660, + 'frame_number': 660, + 'framesequence': 658, + 'gaze_dir': array([0.98058069, 0.00120939, 0.19611241]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.00120939, 0.19611241]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.00120939, 0.19611241]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.663076177239418, + 'timestamp_carla': 14663, + 'timestamp_device': 14131, + 'timestamp_stream': 14.663076177239418, + 'transform': [array([4.64839697e+00, 1.87656360e-06, 1.80358882e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.51631176, -0.22572781, -9.20880985]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.484317779541016, + 'FR_Wheel_Angle': -30.583967208862305, + 'Location': array([3.23450813e+01, 7.79320896e-01, 1.89484120e-03]), + 'Rotation': array([ -0.02212981, -16.45359612, 0.11148633]), + 'Velocity': array([ 5.72760820e-01, -4.61204857e-01, -1.70660023e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 951.0200805664062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([883.63928223, 1.15039468, 0. ]), + 'frame': 661, + 'frame_number': 661, + 'framesequence': 659, + 'gaze_dir': array([ 0.98058069, -0.0013402 , 0.19611154]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0013402 , 0.19611154]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0013402 , 0.19611154]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.676210179924965, + 'timestamp_carla': 14676, + 'timestamp_device': 14144, + 'timestamp_stream': 14.676210179924965, + 'transform': [array([4.66083050e+00, 1.88591866e-06, 1.80229184e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52594793, -0.24766678, -9.0062151 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.49565887451172, + 'FR_Wheel_Angle': -30.590913772583008, + 'Location': array([3.24486237e+01, 7.16625810e-01, 1.86047074e-03]), + 'Rotation': array([ -0.0222186 , -17.96619606, 0.11258003]), + 'Velocity': array([ 0.54769117, -0.46586999, -0.00076253]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 951.0186157226562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.84822754e+02, -1.27431071e+00, -3.05175781e-05]), + 'frame': 662, + 'frame_number': 662, + 'framesequence': 660, + 'gaze_dir': array([ 0.98058069, -0.00388937, 0.19607756]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00388937, 0.19607756]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00388937, 0.19607756]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.689377177506685, + 'timestamp_carla': 14689, + 'timestamp_device': 14157, + 'timestamp_stream': 14.689377177506685, + 'transform': [array([4.67321730e+00, 1.89678724e-06, 1.80114747e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52498752, -0.26443902, -8.80816269]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.510128021240234, + 'FR_Wheel_Angle': -30.59256935119629, + 'Location': array([3.25492821e+01, 6.52147830e-01, 1.91418163e-03]), + 'Rotation': array([ -0.02234155, -19.45913887, 0.11432146]), + 'Velocity': array([ 5.23286462e-01, -4.69514161e-01, 2.11768143e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.9307861328125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([885.96679688, -3.6982801 , 0. ]), + 'frame': 663, + 'frame_number': 663, + 'framesequence': 661, + 'gaze_dir': array([ 0.98058069, -0.00643808, 0.19601041]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00643808, 0.19601041]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00643808, 0.19601041]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.701871279627085, + 'timestamp_carla': 14701, + 'timestamp_device': 14170, + 'timestamp_stream': 14.701871279627085, + 'transform': [array([4.68490124e+00, 1.90690139e-06, 1.80362700e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52086681, -0.27848098, -8.60344601]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.518714904785156, + 'FR_Wheel_Angle': -30.598289489746094, + 'Location': array([3.26519432e+01, 5.82915425e-01, 1.88755512e-03]), + 'Rotation': array([ -0.02234155, -21.00420189, 0.11601049]), + 'Velocity': array([ 4.98329043e-01, -4.72259879e-01, -2.39830013e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.7581787109375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([887.00994873, -6.12080669, 0. ]), + 'frame': 664, + 'frame_number': 664, + 'framesequence': 662, + 'gaze_dir': array([ 0.98058069, -0.0089855 , 0.19591017]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0089855 , 0.19591017]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0089855 , 0.19591017]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.714958477765322, + 'timestamp_carla': 14714, + 'timestamp_device': 14183, + 'timestamp_stream': 14.714958477765322, + 'transform': [array([4.69706726e+00, 1.91631239e-06, 1.80274958e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55616802, -0.3108654 , -8.45728207]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.52702713012695, + 'FR_Wheel_Angle': -30.601247787475586, + 'Location': array([3.27378159e+01, 5.24011433e-01, 1.89945695e-03]), + 'Rotation': array([ -0.02401494, -22.29444695, 0.12964766]), + 'Velocity': array([ 4.79037821e-01, -4.75432128e-01, 1.65863035e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.50146484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.87887695e+02, -8.54049015e+00, -3.05175781e-05]), + 'frame': 665, + 'frame_number': 665, + 'framesequence': 663, + 'gaze_dir': array([ 0.98058069, -0.01133574, 0.19578823]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01133574, 0.19578823]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01133574, 0.19578823]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.727654479444027, + 'timestamp_carla': 14727, + 'timestamp_device': 14195, + 'timestamp_stream': 14.727654479444027, + 'transform': [array([4.70880127e+00, 1.93015649e-06, 1.80408475e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57585496, -0.34317815, -8.2511425 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.5388298034668, + 'FR_Wheel_Angle': -30.60655403137207, + 'Location': array([3.28257332e+01, 4.60650593e-01, 1.89953321e-03]), + 'Rotation': array([ -0.02419936, -23.6386528 , 0.13138449]), + 'Velocity': array([ 4.55852985e-01, -4.74975467e-01, -4.71115090e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 950.1884765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([888.74987793, -10.77084255, 0. ]), + 'frame': 666, + 'frame_number': 666, + 'framesequence': 664, + 'gaze_dir': array([ 0.98058069, -0.01388005, 0.19562432]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01388005, 0.19562432]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01388005, 0.19562432]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.74012427777052, + 'timestamp_carla': 14740, + 'timestamp_device': 14208, + 'timestamp_stream': 14.74012427777052, + 'transform': [array([4.72118139e+00, 1.93619144e-06, 1.80526730e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.59326291, -0.36714068, -8.09547997]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.55031204223633, + 'FR_Wheel_Angle': -30.609060287475586, + 'Location': array([3.29052086e+01, 4.02076781e-01, 1.89850328e-03]), + 'Rotation': array([ -0.02533317, -24.85645294, 0.14142156]), + 'Velocity': array([ 4.37060028e-01, -4.75578487e-01, -2.02026364e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 949.7686767578125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.89447876e+02, -1.31825924e+01, 3.05175781e-05]), + 'frame': 667, + 'frame_number': 667, + 'framesequence': 665, + 'gaze_dir': array([ 0.98058069, -0.01642184, 0.19542737]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01642184, 0.19542737]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01642184, 0.19542737]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.752942379564047, + 'timestamp_carla': 14752, + 'timestamp_device': 14221, + 'timestamp_stream': 14.752942379564047, + 'transform': [array([4.73381424e+00, 1.94499717e-06, 1.80477137e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57961375, -0.38126686, -7.86648035]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.56064224243164, + 'FR_Wheel_Angle': -30.61650276184082, + 'Location': array([3.29929733e+01, 3.33076924e-01, 1.88873766e-03]), + 'Rotation': array([-2.45955102e-02, -2.62399387e+01, 1.36262953e-01]), + 'Velocity': array([ 4.13013816e-01, -4.72307146e-01, -1.02319718e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 949.2647705078125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.90115173e+02, -1.55884190e+01, -3.05175781e-05]), + 'frame': 668, + 'frame_number': 668, + 'framesequence': 666, + 'gaze_dir': array([ 0.98058069, -0.01896084, 0.19519739]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01896084, 0.19519739]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01896084, 0.19519739]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.76586427912116, + 'timestamp_carla': 14765, + 'timestamp_device': 14234, + 'timestamp_stream': 14.76586427912116, + 'transform': [array([4.74645758e+00, 1.96138853e-06, 1.80404657e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57607734, -0.39942268, -7.66085482]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.57232666015625, + 'FR_Wheel_Angle': -30.61899185180664, + 'Location': array([3.30736923e+01, 2.67602891e-01, 1.88869948e-03]), + 'Rotation': array([-2.44793966e-02, -2.75233955e+01, 1.35691345e-01]), + 'Velocity': array([ 3.91457170e-01, -4.68959123e-01, 1.49345396e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 948.6765747070312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([890.71228027, -17.98745155, 0. ]), + 'frame': 669, + 'frame_number': 669, + 'framesequence': 667, + 'gaze_dir': array([ 0.98058069, -0.0213018 , 0.19495581]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0213018 , 0.19495581]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0213018 , 0.19495581]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.778327479958534, + 'timestamp_carla': 14778, + 'timestamp_device': 14246, + 'timestamp_stream': 14.778327479958534, + 'transform': [array([4.75856876e+00, 1.97142799e-06, 1.80580129e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57532984, -0.41672313, -7.47105694]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.583099365234375, + 'FR_Wheel_Angle': -30.623790740966797, + 'Location': array([3.31506004e+01, 2.03399464e-01, 1.89918990e-03]), + 'Rotation': array([-2.47184541e-02, -2.87567368e+01, 1.38469085e-01]), + 'Velocity': array([ 3.71562719e-01, -4.65539336e-01, 1.08718872e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 948.0589599609375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([891.27740479, -20.19511414, 0. ]), + 'frame': 670, + 'frame_number': 670, + 'framesequence': 668, + 'gaze_dir': array([ 0.98058069, -0.024029 , 0.19463849]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.024029 , 0.19463849]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.024029 , 0.19463849]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.791413079947233, + 'timestamp_carla': 14791, + 'timestamp_device': 14260, + 'timestamp_stream': 14.791413079947233, + 'transform': [array([4.77119970e+00, 1.98336306e-06, 1.80427544e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.59624636, -0.44482031, -7.32123566]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.593955993652344, + 'FR_Wheel_Angle': -30.63031005859375, + 'Location': array([3.32193260e+01, 1.45477429e-01, 1.89857953e-03]), + 'Rotation': array([-2.62415856e-02, -2.98549805e+01, 1.51277110e-01]), + 'Velocity': array([ 3.55105013e-01, -4.63292062e-01, 1.19194985e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 947.250244140625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.91572632e+02, -2.27612190e+01, -3.05175781e-05]), + 'frame': 671, + 'frame_number': 671, + 'framesequence': 669, + 'gaze_dir': array([ 0.98058069, -0.02616864, 0.19436239]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02616864, 0.19436239]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02616864, 0.19436239]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.803284376859665, + 'timestamp_carla': 14803, + 'timestamp_device': 14271, + 'timestamp_stream': 14.803284376859665, + 'transform': [array([4.78258801e+00, 1.99723968e-06, 1.80873869e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57981354, -0.45720533, -7.09473944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.60442352294922, + 'FR_Wheel_Angle': -30.634458541870117, + 'Location': array([3.32955551e+01, 7.65513480e-02, 1.89384934e-03]), + 'Rotation': array([-2.52716988e-02, -3.11194286e+01, 1.44360363e-01]), + 'Velocity': array([ 3.33721817e-01, -4.56492484e-01, 2.18253132e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 946.5465087890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([892.0390625 , -24.76958275, 0. ]), + 'frame': 672, + 'frame_number': 672, + 'framesequence': 670, + 'gaze_dir': array([ 0.98058069, -0.02869298, 0.19400579]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02869298, 0.19400579]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02869298, 0.19400579]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.816000778228045, + 'timestamp_carla': 14816, + 'timestamp_device': 14284, + 'timestamp_stream': 14.816000778228045, + 'transform': [array([4.79471111e+00, 2.00729801e-06, 1.80862425e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.59590417, -0.48370212, -6.94159698]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.61537170410156, + 'FR_Wheel_Angle': -30.63790512084961, + 'Location': array([3.33597374e+01, 1.91537850e-02, 1.88511366e-03]), + 'Rotation': array([-2.66718864e-02, -3.21658783e+01, 1.55967563e-01]), + 'Velocity': array([ 0.31809968, -0.45269957, 0.00049739]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 945.6414184570312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.92152588e+02, -2.71330185e+01, 3.05175781e-05]), + 'frame': 673, + 'frame_number': 673, + 'framesequence': 671, + 'gaze_dir': array([ 0.98058069, -0.03121266, 0.19361639]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03121266, 0.19361639]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03121266, 0.19361639]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.828957378864288, + 'timestamp_carla': 14828, + 'timestamp_device': 14297, + 'timestamp_stream': 14.828957378864288, + 'transform': [array([4.80698586e+00, 2.02163096e-06, 1.80736533e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.57198197, -0.49021599, -6.71066904]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.626068115234375, + 'FR_Wheel_Angle': -30.64479637145996, + 'Location': array([ 3.34318047e+01, -5.03416993e-02, 1.88240525e-03]), + 'Rotation': array([-2.52102260e-02, -3.33940849e+01, 1.45416260e-01]), + 'Velocity': array([ 2.97692537e-01, -4.44130838e-01, 8.60214186e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 944.653564453125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.92246277e+02, -2.94848900e+01, -3.05175781e-05]), + 'frame': 674, + 'frame_number': 674, + 'framesequence': 672, + 'gaze_dir': array([ 0.98058069, -0.03372687, 0.19319427]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03372687, 0.19319427]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03372687, 0.19319427]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.841950178146362, + 'timestamp_carla': 14841, + 'timestamp_device': 14310, + 'timestamp_stream': 14.841950178146362, + 'transform': [array([4.81921911e+00, 2.03132618e-06, 1.80618279e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55883443, -0.49975392, -6.51269341]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.637271881103516, + 'FR_Wheel_Angle': -30.647319793701172, + 'Location': array([ 3.34974937e+01, -1.14902414e-01, 1.88641064e-03]), + 'Rotation': array([-2.48345658e-02, -3.45174713e+01, 1.43218473e-01]), + 'Velocity': array([ 2.80126929e-01, -4.36640471e-01, 4.70399864e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 943.5842895507812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.92263123e+02, -3.18238926e+01, -3.05175781e-05]), + 'frame': 675, + 'frame_number': 675, + 'framesequence': 673, + 'gaze_dir': array([ 0.98058069, -0.03604274, 0.19277565]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03604274, 0.19277565]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03604274, 0.19277565]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.854255679994822, + 'timestamp_carla': 14854, + 'timestamp_device': 14322, + 'timestamp_stream': 14.854255679994822, + 'transform': [array([4.83073759e+00, 2.04562184e-06, 1.80858606e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.54975623, -0.51007313, -6.32651281]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.647762298583984, + 'FR_Wheel_Angle': -30.655488967895508, + 'Location': array([ 3.35604210e+01, -1.77975819e-01, 1.87618728e-03]), + 'Rotation': array([-2.48960387e-02, -3.55993042e+01, 1.44140869e-01]), + 'Velocity': array([ 2.63829708e-01, -4.29262459e-01, 2.02755924e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 942.5265502929688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([892.28875732, -33.97097778, 0. ]), + 'frame': 676, + 'frame_number': 676, + 'framesequence': 674, + 'gaze_dir': array([ 0.98058069, -0.0385458 , 0.1922908 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0385458 , 0.1922908 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0385458 , 0.1922908 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.866758279502392, + 'timestamp_carla': 14866, + 'timestamp_device': 14335, + 'timestamp_stream': 14.866758279502392, + 'transform': [array([4.84237337e+00, 2.05772449e-06, 1.80965418e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55444056, -0.53197157, -6.15342951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.65754699707031, + 'FR_Wheel_Angle': -30.656902313232422, + 'Location': array([ 3.36196175e+01, -2.38555610e-01, 1.89514633e-03]), + 'Rotation': array([-2.54766047e-02, -3.66221275e+01, 1.48738310e-01]), + 'Velocity': array([ 2.48827815e-01, -4.22173917e-01, 1.46808627e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 941.305419921875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([892.05773926, -36.28311157, 0. ]), + 'frame': 677, + 'frame_number': 677, + 'framesequence': 675, + 'gaze_dir': array([ 0.98058069, -0.04085047, 0.19181442]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04085047, 0.19181442]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04085047, 0.19181442]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.879057876765728, + 'timestamp_carla': 14879, + 'timestamp_device': 14347, + 'timestamp_stream': 14.879057876765728, + 'transform': [array([4.85375547e+00, 2.06870482e-06, 1.81140890e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55525208, -0.55183858, -5.97766066]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.66744613647461, + 'FR_Wheel_Angle': -30.661277770996094, + 'Location': array([ 3.36768341e+01, -2.98303187e-01, 1.88934803e-03]), + 'Rotation': array([-2.57566422e-02, -3.76181183e+01, 1.51266783e-01]), + 'Velocity': array([ 2.34243959e-01, -4.14379269e-01, 1.30190849e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 940.1084594726562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([891.86584473, -38.40361404, 0. ]), + 'frame': 678, + 'frame_number': 678, + 'framesequence': 676, + 'gaze_dir': array([ 0.98058069, -0.04334045, 0.19126719]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04334045, 0.19126719]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04334045, 0.19126719]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.892229679971933, + 'timestamp_carla': 14892, + 'timestamp_device': 14360, + 'timestamp_stream': 14.892229679971933, + 'transform': [array([4.86682892e+00, 2.07564312e-06, 1.80709839e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55372781, -0.56909817, -5.80575609]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.67713165283203, + 'FR_Wheel_Angle': -30.66741180419922, + 'Location': array([ 3.37318726e+01, -3.56821597e-01, 1.89045421e-03]), + 'Rotation': array([-2.59410571e-02, -3.85812111e+01, 1.53585628e-01]), + 'Velocity': array([ 2.20429391e-01, -4.06338453e-01, 1.61933902e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 938.7373657226562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([891.45141602, -40.68503952, 0. ]), + 'frame': 679, + 'frame_number': 679, + 'framesequence': 677, + 'gaze_dir': array([ 0.98058069, -0.04582329, 0.19068758]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04582329, 0.19068758]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04582329, 0.19068758]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.904575679451227, + 'timestamp_carla': 14904, + 'timestamp_device': 14373, + 'timestamp_stream': 14.904575679451227, + 'transform': [array([4.87899542e+00, 2.08863048e-06, 1.80797570e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.56951499, -0.59756023, -5.66664076]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.68491744995117, + 'FR_Wheel_Angle': -30.67105484008789, + 'Location': array([ 3.37816315e+01, -4.09292758e-01, 1.89507008e-03]), + 'Rotation': array([-2.74641886e-02, -3.94379082e+01, 1.66321561e-01]), + 'Velocity': array([ 0.20896241, -0.39996922, 0.00046871]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 937.287353515625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.91116943e+02, -4.29493256e+01, 3.05175781e-05]), + 'frame': 680, + 'frame_number': 680, + 'framesequence': 678, + 'gaze_dir': array([ 0.98058069, -0.04829819, 0.19007581]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04829819, 0.19007581]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04829819, 0.19007581]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.917052678763866, + 'timestamp_carla': 14917, + 'timestamp_device': 14386, + 'timestamp_stream': 14.917052678763866, + 'transform': [array([4.89120436e+00, 2.09964787e-06, 1.80824276e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5806213 , -0.63066733, -5.50705481]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.69389343261719, + 'FR_Wheel_Angle': -30.678544998168945, + 'Location': array([ 3.38308029e+01, -4.62614954e-01, 1.87660696e-03]), + 'Rotation': array([-2.78876610e-02, -4.02977600e+01, 1.69125661e-01]), + 'Velocity': array([ 1.96781471e-01, -3.91929775e-01, 2.55632389e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 935.7637329101562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([890.60821533, -45.19543076, 0. ]), + 'frame': 681, + 'frame_number': 681, + 'framesequence': 679, + 'gaze_dir': array([ 0.98058069, -0.05095443, 0.18938103]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05095443, 0.18938103]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05095443, 0.18938103]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.93157197907567, + 'timestamp_carla': 14931, + 'timestamp_device': 14400, + 'timestamp_stream': 14.93157197907567, + 'transform': [array([4.90530586e+00, 2.11919632e-06, 1.79656979e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.55821174, -0.63043237, -5.33007669]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.70395278930664, + 'FR_Wheel_Angle': -30.679492950439453, + 'Location': array([ 3.38805504e+01, -5.18969238e-01, 1.89701549e-03]), + 'Rotation': array([-2.69177742e-02, -4.11909866e+01, 1.61518231e-01]), + 'Velocity': array([ 1.84260786e-01, -3.82250667e-01, 3.57394223e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 934.0392456054688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.89876221e+02, -4.75931702e+01, -3.05175781e-05]), + 'frame': 682, + 'frame_number': 682, + 'framesequence': 680, + 'gaze_dir': array([ 0.98058069, -0.0534121 , 0.18870263]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0534121 , 0.18870263]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0534121 , 0.18870263]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.945444379001856, + 'timestamp_carla': 14945, + 'timestamp_device': 14413, + 'timestamp_stream': 14.945444379001856, + 'transform': [array([4.91868019e+00, 2.12871441e-06, 1.79183960e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.56216067, -0.64545298, -5.19600725]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.713134765625, + 'FR_Wheel_Angle': -30.68471908569336, + 'Location': array([ 3.39256859e+01, -5.68827629e-01, 1.88171864e-03]), + 'Rotation': array([-2.80106049e-02, -4.19784126e+01, 1.71154112e-01]), + 'Velocity': array([ 1.74371660e-01, -3.75182033e-01, 2.51779536e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 932.3576049804688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.89382935e+02, -4.97989120e+01, -3.05175781e-05]), + 'frame': 683, + 'frame_number': 683, + 'framesequence': 681, + 'gaze_dir': array([ 0.98058069, -0.05586056, 0.18799236]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05586056, 0.18799236]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05586056, 0.18799236]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.958447679877281, + 'timestamp_carla': 14958, + 'timestamp_device': 14426, + 'timestamp_stream': 14.958447679877281, + 'transform': [array([4.93113470e+00, 2.13853991e-06, 1.79317466e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5346719 , -0.63859749, -5.01463175]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.72159957885742, + 'FR_Wheel_Angle': -30.689117431640625, + 'Location': array([ 3.39745102e+01, -6.26941085e-01, 1.89430709e-03]), + 'Rotation': array([-2.66445670e-02, -4.28788643e+01, 1.60948336e-01]), + 'Velocity': array([ 1.62330091e-01, -3.64654124e-01, 1.61218632e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 930.6057739257812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([888.73687744, -51.98389435, 0. ]), + 'frame': 684, + 'frame_number': 684, + 'framesequence': 682, + 'gaze_dir': array([ 0.98058069, -0.05848707, 0.18719192]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05848707, 0.18719192]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05848707, 0.18719192]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.971747778356075, + 'timestamp_carla': 14971, + 'timestamp_device': 14440, + 'timestamp_stream': 14.971747778356075, + 'transform': [array([4.94378948e+00, 2.15010232e-06, 1.79286953e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.5301823 , -0.65190995, -4.86452913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.73004150390625, + 'FR_Wheel_Angle': -30.693477630615234, + 'Location': array([ 3.40187225e+01, -6.78699791e-01, 1.89930433e-03]), + 'Rotation': array([-2.67948303e-02, -4.36750984e+01, 1.62306428e-01]), + 'Velocity': array([ 1.52274609e-01, -3.55987221e-01, 8.41856017e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 928.6414184570312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([887.75793457, -54.31324387, 0. ]), + 'frame': 685, + 'frame_number': 685, + 'framesequence': 683, + 'gaze_dir': array([ 0.98058057, -0.06091563, 0.18641575]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.06091563, 0.18641575]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.06091563, 0.18641575]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.984763476997614, + 'timestamp_carla': 14984, + 'timestamp_device': 14453, + 'timestamp_stream': 14.984763476997614, + 'transform': [array([4.95609617e+00, 2.16382546e-06, 1.79424277e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52318019, -0.66164422, -4.71746778]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.73833084106445, + 'FR_Wheel_Angle': -30.69904136657715, + 'Location': array([ 3.40614510e+01, -7.29402900e-01, 1.90773478e-03]), + 'Rotation': array([-2.67948303e-02, -4.44473686e+01, 1.63277954e-01]), + 'Velocity': array([ 0.14277557, -0.3472589 , 0.00044409]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 926.744140625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([886.875 , -56.45294189, 0. ]), + 'frame': 686, + 'frame_number': 686, + 'framesequence': 684, + 'gaze_dir': array([ 0.98058069, -0.06314803, 0.18567137]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06314803, 0.18567137]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06314803, 0.18567137]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 14.997371576726437, + 'timestamp_carla': 14997, + 'timestamp_device': 14465, + 'timestamp_stream': 14.997371576726437, + 'transform': [array([4.96794653e+00, 2.17887555e-06, 1.79744721e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.51387221, -0.66886991, -4.56932688]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.74662399291992, + 'FR_Wheel_Angle': -30.700899124145508, + 'Location': array([ 3.41031036e+01, -7.79680014e-01, 1.89095014e-03]), + 'Rotation': array([-2.65216231e-02, -4.52049370e+01, 1.62172094e-01]), + 'Velocity': array([ 0.13359457, -0.33821926, 0.00034076]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 924.9320678710938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.86053711e+02, -5.84073639e+01, 3.05175781e-05]), + 'frame': 687, + 'frame_number': 687, + 'framesequence': 685, + 'gaze_dir': array([ 0.98058069, -0.06555644, 0.18483481]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06555644, 0.18483481]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06555644, 0.18483481]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.010283377021551, + 'timestamp_carla': 15010, + 'timestamp_device': 14478, + 'timestamp_stream': 15.010283377021551, + 'transform': [array([4.98000860e+00, 2.18542732e-06, 1.79866783e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.53325009, -0.70023829, -4.45997047]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.75408935546875, + 'FR_Wheel_Angle': -30.706087112426758, + 'Location': array([ 3.41405487e+01, -8.22650433e-01, 1.90044881e-03]), + 'Rotation': array([-2.85911709e-02, -4.58507843e+01, 1.78870425e-01]), + 'Velocity': array([ 1.26480088e-01, -3.31794858e-01, 2.48527533e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 922.9049682617188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([884.94299316, -60.50209045, 0. ]), + 'frame': 688, + 'frame_number': 688, + 'framesequence': 686, + 'gaze_dir': array([ 0.98058069, -0.06795377, 0.18396695]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06795377, 0.18396695]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06795377, 0.18396695]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.023486379534006, + 'timestamp_carla': 15023, + 'timestamp_device': 14491, + 'timestamp_stream': 15.023486379534006, + 'transform': [array([4.99226999e+00, 2.19886169e-06, 1.79828645e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.51323998, -0.70112592, -4.30241919]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76155471801758, + 'FR_Wheel_Angle': -30.70901107788086, + 'Location': array([ 3.41811066e+01, -8.73621941e-01, 1.89133163e-03]), + 'Rotation': array([-2.72183027e-02, -4.66047974e+01, 1.68331906e-01]), + 'Velocity': array([ 1.17453411e-01, -3.21676970e-01, 1.19447708e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 920.8106689453125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([883.77758789, -62.57228088, 0. ]), + 'frame': 689, + 'frame_number': 689, + 'framesequence': 687, + 'gaze_dir': array([ 0.98058069, -0.07033927, 0.18306807]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07033927, 0.18306807]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07033927, 0.18306807]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.036251679062843, + 'timestamp_carla': 15036, + 'timestamp_device': 14504, + 'timestamp_stream': 15.036251679062843, + 'transform': [array([5.00405455e+00, 2.20781180e-06, 1.80023187e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50314569, -0.70641613, -4.16697454]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.76915740966797, + 'FR_Wheel_Angle': -30.7117862701416, + 'Location': array([ 3.42186470e+01, -9.19948101e-01, 1.90079212e-03]), + 'Rotation': array([-2.69724149e-02, -4.72852249e+01, 1.66911215e-01]), + 'Velocity': array([ 1.09819114e-01, -3.12941343e-01, 2.68878939e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 918.65087890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([882.55810547, -64.61695862, 0. ]), + 'frame': 690, + 'frame_number': 690, + 'framesequence': 688, + 'gaze_dir': array([ 0.98058069, -0.07271324, 0.18213817]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07271324, 0.18213817]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07271324, 0.18213817]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.049084179103374, + 'timestamp_carla': 15049, + 'timestamp_device': 14517, + 'timestamp_stream': 15.049084179103374, + 'transform': [array([5.01679277e+00, 2.21522032e-06, 1.80000300e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.52246487, -0.73632759, -4.06967449]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.775787353515625, + 'FR_Wheel_Angle': -30.71721076965332, + 'Location': array([ 3.42524910e+01, -9.58793998e-01, 1.91769120e-03]), + 'Rotation': array([-2.92058866e-02, -4.78537979e+01, 1.85749963e-01]), + 'Velocity': array([ 1.04070850e-01, -3.06901723e-01, 2.49967561e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 916.4279174804688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.81219360e+02, -6.66361771e+01, -3.05175781e-05]), + 'frame': 691, + 'frame_number': 691, + 'framesequence': 689, + 'gaze_dir': array([ 0.98058069, -0.07489345, 0.18125258]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07489345, 0.18125258]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07489345, 0.18125258]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.061600178480148, + 'timestamp_carla': 15061, + 'timestamp_device': 14529, + 'timestamp_stream': 15.061600178480148, + 'transform': [array([5.02912664e+00, 2.22821245e-06, 1.80164329e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50654352, -0.74182224, -3.9279561 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.78251266479492, + 'FR_Wheel_Angle': -30.718921661376953, + 'Location': array([ 3.42890816e+01, -1.00508523e+00, 1.90071575e-03]), + 'Rotation': array([-2.79218126e-02, -4.85223923e+01, 1.75304800e-01]), + 'Velocity': array([ 9.65857953e-02, -2.97421098e-01, 6.90126399e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 914.320068359375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([880.10632324, -68.47631836, 0. ]), + 'frame': 692, + 'frame_number': 692, + 'framesequence': 690, + 'gaze_dir': array([ 0.98058069, -0.07742355, 0.18018635]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07742355, 0.18018635]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07742355, 0.18018635]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.074501179158688, + 'timestamp_carla': 15074, + 'timestamp_device': 14543, + 'timestamp_stream': 15.074501179158688, + 'transform': [array([5.04174805e+00, 2.23621714e-06, 1.80126191e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.51936096, -0.76820135, -3.82884502]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.78924560546875, + 'FR_Wheel_Angle': -30.72255516052246, + 'Location': array([ 3.43214111e+01, -1.04261780e+00, 1.91616535e-03]), + 'Rotation': array([-2.95405667e-02, -4.90632553e+01, 1.88671023e-01]), + 'Velocity': array([ 9.12139565e-02, -2.90983528e-01, 2.27947225e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 911.7960205078125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([878.48138428, -70.59421539, 0. ]), + 'frame': 693, + 'frame_number': 693, + 'framesequence': 691, + 'gaze_dir': array([ 0.98058057, -0.07958034, 0.17924429]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.07958034, 0.17924429]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.07958034, 0.17924429]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.087100677192211, + 'timestamp_carla': 15087, + 'timestamp_device': 14555, + 'timestamp_stream': 15.087100677192211, + 'transform': [array([5.05399132e+00, 2.25267809e-06, 1.80267333e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49640015, -0.75925004, -3.69608331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.79549026489258, + 'FR_Wheel_Angle': -30.728479385375977, + 'Location': array([ 3.43559189e+01, -1.08661342e+00, 1.92997453e-03]), + 'Rotation': array([-2.81745289e-02, -4.96899414e+01, 1.77748933e-01]), + 'Velocity': array([ 8.47293437e-02, -2.81833708e-01, 2.18195913e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 909.576904296875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.77230713e+02, -7.23841858e+01, -3.05175781e-05]), + 'frame': 694, + 'frame_number': 694, + 'framesequence': 692, + 'gaze_dir': array([ 0.98058069, -0.08190382, 0.17819461]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08190382, 0.17819461]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08190382, 0.17819461]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.099813878536224, + 'timestamp_carla': 15099, + 'timestamp_device': 14568, + 'timestamp_stream': 15.099813878536224, + 'transform': [array([5.06626225e+00, 2.26418001e-06, 1.80339813e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.50636727, -0.78578228, -3.56609488]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.924949645996094, + 'FR_Wheel_Angle': -29.819992065429688, + 'Location': array([ 3.43868523e+01, -1.12340832e+00, 1.90723897e-03]), + 'Rotation': array([-2.92058866e-02, -5.02100601e+01, 1.86398834e-01]), + 'Velocity': array([ 8.06770101e-02, -2.75057554e-01, 1.72724715e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 907.1173706054688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.75669800e+02, -7.42961044e+01, -3.05175781e-05]), + 'frame': 695, + 'frame_number': 695, + 'framesequence': 693, + 'gaze_dir': array([ 0.98058069, -0.08421312, 0.17711487]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08421312, 0.17711487]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08421312, 0.17711487]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.11271507665515, + 'timestamp_carla': 15112, + 'timestamp_device': 14581, + 'timestamp_stream': 15.11271507665515, + 'transform': [array([5.07863379e+00, 2.28043632e-06, 1.80313108e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49583164, -0.78341585, -2.87576246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.1374626159668, + 'FR_Wheel_Angle': -24.551427841186523, + 'Location': array([ 3.44219208e+01, -1.16640615e+00, 1.91891193e-03]), + 'Rotation': array([-2.70953588e-02, -5.07488327e+01, 1.76779553e-01]), + 'Velocity': array([ 1.04935221e-01, -2.76214868e-01, 9.99164549e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 904.6011962890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.74047607e+02, -7.61790085e+01, -3.05175781e-05]), + 'frame': 696, + 'frame_number': 696, + 'framesequence': 694, + 'gaze_dir': array([ 0.98058069, -0.08633256, 0.17609158]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08633256, 0.17609158]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08633256, 0.17609158]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.125420577824116, + 'timestamp_carla': 15125, + 'timestamp_device': 14593, + 'timestamp_stream': 15.125420577824116, + 'transform': [array([5.09074163e+00, 2.29633861e-06, 1.80397031e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4907307 , -0.76311725, -3.52776146]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.434200286865234, + 'FR_Wheel_Angle': -26.32956886291504, + 'Location': array([ 3.44588509e+01, -1.21224940e+00, 1.89888477e-03]), + 'Rotation': array([-2.49575097e-02, -5.12710190e+01, 1.80400312e-01]), + 'Velocity': array([ 1.12816989e-01, -3.20639193e-01, 1.36156086e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 902.2288818359375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.72598572e+02, -7.78914566e+01, -3.05175781e-05]), + 'frame': 697, + 'frame_number': 697, + 'framesequence': 695, + 'gaze_dir': array([ 0.98058057, -0.08861447, 0.17495435]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.08861447, 0.17495435]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.08861447, 0.17495435]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.137939378619194, + 'timestamp_carla': 15137, + 'timestamp_device': 14606, + 'timestamp_stream': 15.137939378619194, + 'transform': [array([5.10259819e+00, 2.30694172e-06, 1.80561061e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49477139, -0.78317499, -3.2248354 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.05842590332031, + 'FR_Wheel_Angle': -25.545949935913086, + 'Location': array([ 3.44943924e+01, -1.25623131e+00, 1.88377849e-03]), + 'Rotation': array([-2.43564527e-02, -5.17923203e+01, 1.80292219e-01]), + 'Velocity': array([ 1.08432941e-01, -3.05479437e-01, -5.65052032e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 899.607421875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([870.84069824, -79.7179718 , 0. ]), + 'frame': 698, + 'frame_number': 698, + 'framesequence': 696, + 'gaze_dir': array([ 0.98058069, -0.09070735, 0.17387842]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09070735, 0.17387842]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09070735, 0.17387842]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.150479178875685, + 'timestamp_carla': 15150, + 'timestamp_device': 14618, + 'timestamp_stream': 15.150479178875685, + 'transform': [array([5.11440468e+00, 2.32189882e-06, 1.80690759e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4690066 , -0.75343317, -3.22656178]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.34249496459961, + 'FR_Wheel_Angle': -25.616613388061523, + 'Location': array([ 3.45316277e+01, -1.30528378e+00, 1.86794752e-03]), + 'Rotation': array([-2.28606425e-02, -5.23633614e+01, 1.72095031e-01]), + 'Velocity': array([ 1.03278957e-01, -3.03494036e-01, 9.14525954e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 897.1416015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([869.23406982, -81.37705231, 0. ]), + 'frame': 699, + 'frame_number': 699, + 'framesequence': 697, + 'gaze_dir': array([ 0.98058057, -0.09296012, 0.17268458]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.09296012, 0.17268458]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.09296012, 0.17268458]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.1635981798172, + 'timestamp_carla': 15163, + 'timestamp_device': 14631, + 'timestamp_stream': 15.1635981798172, + 'transform': [array([5.12668085e+00, 2.33388027e-06, 1.80503842e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.47454813, -0.77383566, -3.16811252]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.38163757324219, + 'FR_Wheel_Angle': -25.657438278198242, + 'Location': array([ 3.45657082e+01, -1.34831429e+00, 1.88335893e-03]), + 'Rotation': array([-2.31953207e-02, -5.28639374e+01, 1.77977026e-01]), + 'Velocity': array([ 9.83224437e-02, -2.98628122e-01, 2.34990119e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 894.4212036132812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([867.33410645, -83.14522552, 0. ]), + 'frame': 700, + 'frame_number': 700, + 'framesequence': 698, + 'gaze_dir': array([ 0.98058069, -0.09519719, 0.17146152]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09519719, 0.17146152]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09519719, 0.17146152]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.176427379250526, + 'timestamp_carla': 15176, + 'timestamp_device': 14644, + 'timestamp_stream': 15.176427379250526, + 'transform': [array([5.13861513e+00, 2.35003859e-06, 1.80507661e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.46328241, -0.76876801, -3.08655572]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.43511962890625, + 'FR_Wheel_Angle': -25.6961612701416, + 'Location': array([ 3.46003304e+01, -1.39407682e+00, 1.90475932e-03]), + 'Rotation': array([-2.28879619e-02, -5.33916130e+01, 1.76957861e-01]), + 'Velocity': array([ 9.28487182e-02, -2.91591585e-01, -1.43527977e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 891.650146484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([865.42401123, -84.88230133, 0. ]), + 'frame': 701, + 'frame_number': 701, + 'framesequence': 699, + 'gaze_dir': array([ 0.98058069, -0.09741783, 0.17020954]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09741783, 0.17020954]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09741783, 0.17020954]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.188981179147959, + 'timestamp_carla': 15188, + 'timestamp_device': 14657, + 'timestamp_stream': 15.188981179147959, + 'transform': [array([5.15022564e+00, 2.36210849e-06, 1.80648803e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.47849849, -0.80751455, -3.01548791]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.43279266357422, + 'FR_Wheel_Angle': -25.698223114013672, + 'Location': array([ 3.46322250e+01, -1.43362916e+00, 1.90700998e-03]), + 'Rotation': array([-2.37144157e-02, -5.38479996e+01, 1.86174184e-01]), + 'Velocity': array([ 8.80787671e-02, -2.85842240e-01, -1.51839253e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 888.8322143554688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.63426392e+02, -8.65878143e+01, -3.05175781e-05]), + 'frame': 702, + 'frame_number': 702, + 'framesequence': 700, + 'gaze_dir': array([ 0.98058069, -0.09962235, 0.16892873]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09962235, 0.16892873]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09962235, 0.16892873]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.202199179679155, + 'timestamp_carla': 15202, + 'timestamp_device': 14670, + 'timestamp_stream': 15.202199179679155, + 'transform': [array([5.16334438e+00, 2.37066752e-06, 1.80316926e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.49569595, -0.84454107, -2.95798802]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.43708801269531, + 'FR_Wheel_Angle': -25.700645446777344, + 'Location': array([ 3.46623001e+01, -1.46944511e+00, 1.90021982e-03]), + 'Rotation': array([-2.51146033e-02, -5.42603798e+01, 2.01045647e-01]), + 'Velocity': array([ 0.08410501, -0.2812019 , -0.00030923]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 885.9677124023438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.61343750e+02, -8.82618866e+01, 3.05175781e-05]), + 'frame': 703, + 'frame_number': 703, + 'framesequence': 701, + 'gaze_dir': array([ 0.98058069, -0.10181002, 0.16761944]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10181002, 0.16761944]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10181002, 0.16761944]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.215008579194546, + 'timestamp_carla': 15215, + 'timestamp_device': 14683, + 'timestamp_stream': 15.215008579194546, + 'transform': [array([5.17596292e+00, 2.37961285e-06, 1.80294027e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.46937159, -0.82505125, -2.86738133]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.44131851196289, + 'FR_Wheel_Angle': -25.70272445678711, + 'Location': array([ 3.46948967e+01, -1.51298594e+00, 1.90388202e-03]), + 'Rotation': array([-2.35914718e-02, -5.47548790e+01, 1.85433537e-01]), + 'Velocity': array([ 7.89850429e-02, -2.73237497e-01, 9.66119769e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 883.0574951171875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.59360352e+02, -8.99038162e+01, -3.05175781e-05]), + 'frame': 704, + 'frame_number': 704, + 'framesequence': 702, + 'gaze_dir': array([ 0.98058069, -0.10414662, 0.16617772]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10414662, 0.16617772]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10414662, 0.16617772]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.229055676609278, + 'timestamp_carla': 15229, + 'timestamp_device': 14697, + 'timestamp_stream': 15.229055676609278, + 'transform': [array([5.18969584e+00, 2.39309361e-06, 1.79580681e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.46502134, -0.83050632, -2.7999506 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.4452018737793, + 'FR_Wheel_Angle': -25.705530166625977, + 'Location': array([ 3.47250633e+01, -1.55095565e+00, 1.90483569e-03]), + 'Rotation': array([-2.37417370e-02, -5.51855431e+01, 1.87620327e-01]), + 'Velocity': array([ 0.0749564 , -0.26744741, 0.00030186]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 879.8761596679688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.57019714e+02, -9.16358414e+01, -1.22070312e-04]), + 'frame': 705, + 'frame_number': 705, + 'framesequence': 703, + 'gaze_dir': array([ 0.98058069, -0.10646283, 0.16470344]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10646283, 0.16470344]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10646283, 0.16470344]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.242970678955317, + 'timestamp_carla': 15242, + 'timestamp_device': 14711, + 'timestamp_stream': 15.242970678955317, + 'transform': [array([5.20319796e+00, 2.40129407e-06, 1.79130549e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4702903 , -0.85186231, -2.73702335]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.44876480102539, + 'FR_Wheel_Angle': -25.706649780273438, + 'Location': array([ 3.47543411e+01, -1.58710766e+00, 1.89556589e-03]), + 'Rotation': array([-2.41037365e-02, -5.55936813e+01, 1.92608431e-01]), + 'Velocity': array([ 7.11433887e-02, -2.62086332e-01, -2.48937606e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 876.6441650390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.54733521e+02, -9.33297119e+01, -3.05175781e-05]), + 'frame': 706, + 'frame_number': 706, + 'framesequence': 704, + 'gaze_dir': array([ 0.98058069, -0.10875815, 0.16319689]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10875815, 0.16319689]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10875815, 0.16319689]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.256936077028513, + 'timestamp_carla': 15256, + 'timestamp_device': 14725, + 'timestamp_stream': 15.256936077028513, + 'transform': [array([5.21665096e+00, 2.41006228e-06, 1.78764341e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.47095251, -0.86782515, -2.67325807]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.45240783691406, + 'FR_Wheel_Angle': -25.70063018798828, + 'Location': array([ 3.47832184e+01, -1.62255800e+00, 1.90102099e-03]), + 'Rotation': array([-2.43223030e-02, -5.59925308e+01, 1.94868803e-01]), + 'Velocity': array([ 0.06744 , -0.25656557, -0.00043993]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 873.3665161132812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.52372620e+02, -9.49854355e+01, -6.10351562e-05]), + 'frame': 707, + 'frame_number': 707, + 'framesequence': 705, + 'gaze_dir': array([ 0.98058069, -0.11087054, 0.16176923]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11087054, 0.16176923]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11087054, 0.16176923]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.269850578159094, + 'timestamp_carla': 15269, + 'timestamp_device': 14738, + 'timestamp_stream': 15.269850578159094, + 'transform': [array([5.22901011e+00, 2.42069814e-06, 1.79073331e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.43729573, -0.83094233, -2.07600951]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.1409912109375, + 'FR_Wheel_Angle': -20.396238327026367, + 'Location': array([ 3.48139687e+01, -1.66266537e+00, 1.85917376e-03]), + 'Rotation': array([-2.20000390e-02, -5.64004936e+01, 1.73472419e-01]), + 'Velocity': array([ 0.08075334, -0.24731064, 0.00036023]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 870.2830200195312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.50226624e+02, -9.64884644e+01, 9.15527344e-05]), + 'frame': 708, + 'frame_number': 708, + 'framesequence': 706, + 'gaze_dir': array([ 0.98058069, -0.11296389, 0.16031434]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11296389, 0.16031434]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11296389, 0.16031434]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.283142477273941, + 'timestamp_carla': 15283, + 'timestamp_device': 14751, + 'timestamp_stream': 15.283142477273941, + 'transform': [array([5.24164724e+00, 2.43725708e-06, 1.79149618e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.43606746, -0.80028951, -2.38951802]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.635881423950195, + 'FR_Wheel_Angle': -20.935468673706055, + 'Location': array([ 3.48471375e+01, -1.70484984e+00, 1.84238912e-03]), + 'Rotation': array([-2.03198120e-02, -5.67497025e+01, 1.83554873e-01]), + 'Velocity': array([ 9.99554321e-02, -2.95516908e-01, 3.97443764e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 867.165771484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.47932312e+02, -9.79581223e+01, -3.05175781e-05]), + 'frame': 709, + 'frame_number': 709, + 'framesequence': 707, + 'gaze_dir': array([ 0.98058069, -0.11503844, 0.15883225]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11503844, 0.15883225]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11503844, 0.15883225]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.296153277158737, + 'timestamp_carla': 15296, + 'timestamp_device': 14764, + 'timestamp_stream': 15.296153277158737, + 'transform': [array([5.25394011e+00, 2.44619287e-06, 1.79370877e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.43425965, -0.80528247, -2.28555703]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.559389114379883, + 'FR_Wheel_Angle': -19.977975845336914, + 'Location': array([ 3.48811340e+01, -1.75103784e+00, 1.82651996e-03]), + 'Rotation': array([-1.92884523e-02, -5.71582108e+01, 1.80714771e-01]), + 'Velocity': array([ 0.09649494, -0.28866976, 0.00048398]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 864.01171875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.45624451e+02, -9.93942642e+01, 6.10351562e-05]), + 'frame': 710, + 'frame_number': 710, + 'framesequence': 708, + 'gaze_dir': array([ 0.98058069, -0.11725075, 0.15720619]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11725075, 0.15720619]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11725075, 0.15720619]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.309771679341793, + 'timestamp_carla': 15309, + 'timestamp_device': 14778, + 'timestamp_stream': 15.309771679341793, + 'transform': [array([5.26672554e+00, 2.46163427e-06, 1.79233542e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42647994, -0.80104893, -2.35401869]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.13739013671875, + 'FR_Wheel_Angle': -20.326229095458984, + 'Location': array([ 3.49145622e+01, -1.79719007e+00, 1.85566419e-03]), + 'Rotation': array([-1.81546416e-02, -5.75589371e+01, 1.74743265e-01]), + 'Velocity': array([ 0.09376618, -0.29207703, 0.00088951]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 860.5785522460938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 842.96594238, -100.90318298, 0. ]), + 'frame': 711, + 'frame_number': 711, + 'framesequence': 709, + 'gaze_dir': array([ 0.98058057, -0.11928453, 0.15566875]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11928453, 0.15566875]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11928453, 0.15566875]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.32263357937336, + 'timestamp_carla': 15322, + 'timestamp_device': 14791, + 'timestamp_stream': 15.32263357937336, + 'transform': [array([5.27872658e+00, 2.47093817e-06, 1.79534906e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44261739, -0.83396602, -2.31429219]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.110118865966797, + 'FR_Wheel_Angle': -20.324474334716797, + 'Location': array([ 3.49458733e+01, -1.83735549e+00, 1.85783859e-03]), + 'Rotation': array([-1.88308302e-02, -5.79116631e+01, 1.88092813e-01]), + 'Velocity': array([ 9.04080272e-02, -2.88222164e-01, -1.92670821e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 857.3562622070312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 840.59570312, -102.26905823, 0. ]), + 'frame': 712, + 'frame_number': 712, + 'framesequence': 710, + 'gaze_dir': array([ 0.98058069, -0.12160596, 0.153862 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12160596, 0.153862 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12160596, 0.153862 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.33798997849226, + 'timestamp_carla': 15337, + 'timestamp_device': 14806, + 'timestamp_stream': 15.33798997849226, + 'transform': [array([5.29296017e+00, 2.48513152e-06, 1.78203580e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.45198491, -0.86448389, -2.27001524]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.08321762084961, + 'FR_Wheel_Angle': -20.320077896118164, + 'Location': array([ 3.49769173e+01, -1.87716925e+00, 1.86874857e-03]), + 'Rotation': array([-1.91996600e-02, -5.82606010e+01, 1.93557993e-01]), + 'Velocity': array([ 8.67775157e-02, -2.83674866e-01, -5.58757783e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 853.6014404296875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 837.54394531, -103.80273438, 0. ]), + 'frame': 713, + 'frame_number': 713, + 'framesequence': 711, + 'gaze_dir': array([ 0.98058069, -0.12374804, 0.15214449]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12374804, 0.15214449]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12374804, 0.15214449]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.351467277854681, + 'timestamp_carla': 15351, + 'timestamp_device': 14820, + 'timestamp_stream': 15.351467277854681, + 'transform': [array([5.30537271e+00, 2.50108496e-06, 1.78421021e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.45825192, -0.88715935, -2.23119974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.075977325439453, + 'FR_Wheel_Angle': -20.32062530517578, + 'Location': array([ 3.50070419e+01, -1.91528547e+00, 1.88637257e-03]), + 'Rotation': array([-1.96163021e-02, -5.85940590e+01, 2.00052679e-01]), + 'Velocity': array([ 8.34831223e-02, -2.79519886e-01, -5.97906110e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 850.0579833984375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.34955566e+02, -1.05192719e+02, 3.05175781e-05]), + 'frame': 714, + 'frame_number': 714, + 'framesequence': 712, + 'gaze_dir': array([ 0.98058069, -0.12571548, 0.1505229 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12571548, 0.1505229 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12571548, 0.1505229 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.365385178476572, + 'timestamp_carla': 15365, + 'timestamp_device': 14833, + 'timestamp_stream': 15.365385178476572, + 'transform': [array([5.31917953e+00, 2.50694779e-06, 1.78195944e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44315049, -0.87123555, -2.18588209]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.07857894897461, + 'FR_Wheel_Angle': -20.321868896484375, + 'Location': array([ 3.50381851e+01, -1.95688641e+00, 1.87424175e-03]), + 'Rotation': array([-1.91655103e-02, -5.89546394e+01, 1.95190728e-01]), + 'Velocity': array([ 8.00463408e-02, -2.74337888e-01, -1.21502875e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 846.74365234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 832.44354248, -106.44848633, 0. ]), + 'frame': 715, + 'frame_number': 715, + 'framesequence': 713, + 'gaze_dir': array([ 0.98058069, -0.127959 , 0.1486204 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.127959 , 0.1486204 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.127959 , 0.1486204 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.379297878593206, + 'timestamp_carla': 15379, + 'timestamp_device': 14848, + 'timestamp_stream': 15.379297878593206, + 'transform': [array([5.33287096e+00, 2.51742517e-06, 1.78062438e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41628194, -0.83717227, -2.13215494]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.08098793029785, + 'FR_Wheel_Angle': -20.323518753051758, + 'Location': array([ 3.50700264e+01, -2.00105405e+00, 1.86913006e-03]), + 'Rotation': array([-1.80658493e-02, -5.93351631e+01, 1.81527495e-01]), + 'Velocity': array([ 7.63035789e-02, -2.68017292e-01, 1.60446158e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 842.8861083984375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.29456299e+02, -1.07854568e+02, 9.15527344e-05]), + 'frame': 716, + 'frame_number': 716, + 'framesequence': 714, + 'gaze_dir': array([ 0.98058069, -0.12988026, 0.14694434]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12988026, 0.14694434]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12988026, 0.14694434]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.393298879265785, + 'timestamp_carla': 15393, + 'timestamp_device': 14861, + 'timestamp_stream': 15.393298879265785, + 'transform': [array([5.34654140e+00, 2.53166036e-06, 1.77944184e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.416004 , -0.84743059, -2.094028 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.0831298828125, + 'FR_Wheel_Angle': -20.32762336730957, + 'Location': array([ 3.50996704e+01, -2.03997064e+00, 1.81709765e-03]), + 'Rotation': array([-1.82161126e-02, -5.96708870e+01, 1.84494331e-01]), + 'Velocity': array([ 7.32321292e-02, -2.63724476e-01, -1.55735019e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 839.5175170898438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.27010864e+02, -1.09036461e+02, -3.05175781e-05]), + 'frame': 717, + 'frame_number': 717, + 'framesequence': 715, + 'gaze_dir': array([ 0.98058069, -0.13192469, 0.14511169]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13192469, 0.14511169]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13192469, 0.14511169]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.407204378396273, + 'timestamp_carla': 15407, + 'timestamp_device': 14875, + 'timestamp_stream': 15.407204378396273, + 'transform': [array([5.36001873e+00, 2.54034489e-06, 1.77940365e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40507501, -0.84101981, -2.0490489 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.085769653320312, + 'FR_Wheel_Angle': -20.327699661254883, + 'Location': array([ 3.51289062e+01, -2.08020353e+00, 1.84891222e-03]), + 'Rotation': array([-1.78267919e-02, -6.00148468e+01, 1.79542914e-01]), + 'Velocity': array([ 6.99881166e-02, -2.58489877e-01, 1.79786672e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 835.864501953125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.24241455e+02, -1.10270859e+02, -3.05175781e-05]), + 'frame': 718, + 'frame_number': 718, + 'framesequence': 716, + 'gaze_dir': array([ 0.98058069, -0.13394324, 0.1432506 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13394324, 0.1432506 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13394324, 0.1432506 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.420643977820873, + 'timestamp_carla': 15420, + 'timestamp_device': 14889, + 'timestamp_stream': 15.420643977820873, + 'transform': [array([5.37295294e+00, 2.55252189e-06, 1.78234093e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39121252, -0.82597387, -2.00433183]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -25.088308334350586, + 'FR_Wheel_Angle': -20.313215255737305, + 'Location': array([ 3.51580429e+01, -2.12080979e+00, 1.82438374e-03]), + 'Rotation': array([-1.73076987e-02, -6.03606529e+01, 1.73322082e-01]), + 'Velocity': array([ 0.06689179, -0.25324202, -0.00060876]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 832.1876831054688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.21425659e+02, -1.11465622e+02, -3.05175781e-05]), + 'frame': 719, + 'frame_number': 719, + 'framesequence': 717, + 'gaze_dir': array([ 0.98058069, -0.13593556, 0.14136142]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13593556, 0.14136142]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13593556, 0.14136142]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.434822376817465, + 'timestamp_carla': 15434, + 'timestamp_device': 14903, + 'timestamp_stream': 15.434822376817465, + 'transform': [array([5.38650179e+00, 2.56514136e-06, 1.78070064e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39181149, -0.83699811, -1.45573461]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -18.000167846679688, + 'FR_Wheel_Angle': -14.743512153625488, + 'Location': array([ 3.51871300e+01, -2.15959024e+00, 1.87378400e-03]), + 'Rotation': array([-1.71506032e-02, -6.06546669e+01, 1.73566863e-01]), + 'Velocity': array([ 0.08051787, -0.24700417, 0.00027539]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 828.48876953125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 818.53045654, -112.62078857, 0. ]), + 'frame': 720, + 'frame_number': 720, + 'framesequence': 718, + 'gaze_dir': array([ 0.98058069, -0.13790122, 0.13944454]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13790122, 0.13944454]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13790122, 0.13944454]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.44874557852745, + 'timestamp_carla': 15448, + 'timestamp_device': 14917, + 'timestamp_stream': 15.44874557852745, + 'transform': [array([5.39971590e+00, 2.58142086e-06, 1.78119657e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.38583842, -0.80325836, -1.6311717 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.97305679321289, + 'FR_Wheel_Angle': -14.891146659851074, + 'Location': array([ 3.52211533e+01, -2.20588660e+00, 1.87077036e-03]), + 'Rotation': array([-1.49854338e-02, -6.09118156e+01, 1.73915371e-01]), + 'Velocity': array([ 9.93077755e-02, -2.92859495e-01, -2.41622925e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 824.76806640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 815.67224121, -113.73621368, 0. ]), + 'frame': 721, + 'frame_number': 721, + 'framesequence': 719, + 'gaze_dir': array([ 0.98058069, -0.13983986, 0.13750032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13983986, 0.13750032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13983986, 0.13750032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.462302077561617, + 'timestamp_carla': 15462, + 'timestamp_device': 14931, + 'timestamp_stream': 15.462302077561617, + 'transform': [array([5.41249800e+00, 2.59979583e-06, 1.78386678e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41530555, -0.86078149, -1.57494915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.229310989379883, + 'FR_Wheel_Angle': -14.02211856842041, + 'Location': array([ 3.52524300e+01, -2.24621463e+00, 1.87069410e-03]), + 'Rotation': array([-1.51903396e-02, -6.11606369e+01, 1.91838831e-01]), + 'Velocity': array([ 9.88723561e-02, -2.92399168e-01, -9.25970089e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 821.0289916992188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.12759583e+02, -1.14812286e+02, -3.05175781e-05]), + 'frame': 722, + 'frame_number': 722, + 'framesequence': 720, + 'gaze_dir': array([ 0.98058069, -0.1417511 , 0.13552916]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1417511 , 0.13552916]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1417511 , 0.13552916]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.477346178144217, + 'timestamp_carla': 15477, + 'timestamp_device': 14945, + 'timestamp_stream': 15.477346178144217, + 'transform': [array([5.42658424e+00, 2.61759806e-06, 1.77665707e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4099502 , -0.85337955, -1.64345622]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.803003311157227, + 'FR_Wheel_Angle': -14.42773723602295, + 'Location': array([ 3.52862244e+01, -2.29313064e+00, 1.83472154e-03]), + 'Rotation': array([-1.42204529e-02, -6.14391174e+01, 1.88098431e-01]), + 'Velocity': array([ 9.76472571e-02, -2.97420323e-01, 1.65734295e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 817.2730102539062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.09784363e+02, -1.15849037e+02, -3.05175781e-05]), + 'frame': 723, + 'frame_number': 723, + 'framesequence': 721, + 'gaze_dir': array([ 0.98058069, -0.14363454, 0.13353144]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14363454, 0.13353144]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14363454, 0.13353144]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.491440378129482, + 'timestamp_carla': 15491, + 'timestamp_device': 14959, + 'timestamp_stream': 15.491440378129482, + 'transform': [array([5.43969488e+00, 2.62812205e-06, 1.77761074e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4131771 , -0.86478508, -1.611112 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.761655807495117, + 'FR_Wheel_Angle': -14.432714462280273, + 'Location': array([ 3.53186531e+01, -2.33686399e+00, 1.83750631e-03]), + 'Rotation': array([-1.43160755e-02, -6.17019501e+01, 1.94771230e-01]), + 'Velocity': array([ 9.51522812e-02, -2.93708235e-01, -9.86099185e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 813.4986572265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.06919495e+02, -1.16846207e+02, -3.05175781e-05]), + 'frame': 724, + 'frame_number': 724, + 'framesequence': 722, + 'gaze_dir': array([ 0.98058069, -0.14562145, 0.13136193]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14562145, 0.13136193]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14562145, 0.13136193]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.506018277257681, + 'timestamp_carla': 15506, + 'timestamp_device': 14974, + 'timestamp_stream': 15.506018277257681, + 'transform': [array([5.45316505e+00, 2.64628761e-06, 1.77555077e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.43125007, -0.91284138, -1.58762205]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.722572326660156, + 'FR_Wheel_Angle': -14.409280776977539, + 'Location': array([ 3.53492241e+01, -2.37670088e+00, 1.85085775e-03]), + 'Rotation': array([-1.47122266e-02, -6.19422455e+01, 2.02966556e-01]), + 'Velocity': array([ 9.24017429e-02, -2.90621728e-01, -1.10659596e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 809.44140625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 8.03636108e+02, -1.17871712e+02, -3.05175781e-05]), + 'frame': 725, + 'frame_number': 725, + 'framesequence': 723, + 'gaze_dir': array([ 0.98058057, -0.14744617, 0.12931041]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.14744617, 0.12931041]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.14744617, 0.12931041]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.519868478178978, + 'timestamp_carla': 15519, + 'timestamp_device': 14988, + 'timestamp_stream': 15.519868478178978, + 'transform': [array([5.46588326e+00, 2.65669973e-06, 1.77860260e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40690359, -0.8750568 , -1.55903327]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.723697662353516, + 'FR_Wheel_Angle': -14.410236358642578, + 'Location': array([ 3.53821449e+01, -2.42305636e+00, 1.85654161e-03]), + 'Rotation': array([-1.38857737e-02, -6.22186089e+01, 1.89396009e-01]), + 'Velocity': array([ 8.94381776e-02, -2.85722703e-01, 2.57334701e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 805.6409301757812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 800.67974854, -118.78836823, 0. ]), + 'frame': 726, + 'frame_number': 726, + 'framesequence': 724, + 'gaze_dir': array([ 0.98058069, -0.14936909, 0.12708436]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14936909, 0.12708436]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14936909, 0.12708436]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.534278277307749, + 'timestamp_carla': 15534, + 'timestamp_device': 15003, + 'timestamp_stream': 15.534278277307749, + 'transform': [array([5.48017216e+00, 2.67015730e-06, 1.77543634e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41884869, -0.90452147, -1.54888773]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.72478675842285, + 'FR_Wheel_Angle': -14.411136627197266, + 'Location': array([ 3.54117393e+01, -2.46076870e+00, 1.84853072e-03]), + 'Rotation': array([-1.45892836e-02, -6.24458466e+01, 2.04573154e-01]), + 'Velocity': array([ 8.76066536e-02, -2.84306228e-01, 2.20246307e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 801.5587768554688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.97328918e+02, -1.19727791e+02, -3.05175781e-05]), + 'frame': 727, + 'frame_number': 727, + 'framesequence': 725, + 'gaze_dir': array([ 0.98058069, -0.15113357, 0.12498068]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15113357, 0.12498068]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15113357, 0.12498068]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.54854927957058, + 'timestamp_carla': 15548, + 'timestamp_device': 15017, + 'timestamp_stream': 15.54854927957058, + 'transform': [array([5.49420786e+00, 2.68209214e-06, 1.77429197e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40337029, -0.88681477, -1.52006805]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.725948333740234, + 'FR_Wheel_Angle': -14.411993980407715, + 'Location': array([ 3.54437370e+01, -2.50572205e+00, 1.85146800e-03]), + 'Rotation': array([-1.39813963e-02, -6.27129974e+01, 1.91682220e-01]), + 'Velocity': array([ 8.45564082e-02, -2.79392600e-01, 2.57873529e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 797.7371215820312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.94430542e+02, -1.20564560e+02, 6.10351562e-05]), + 'frame': 728, + 'frame_number': 728, + 'framesequence': 726, + 'gaze_dir': array([ 0.98058069, -0.15286842, 0.12285264]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15286842, 0.12285264]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15286842, 0.12285264]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.562526479363441, + 'timestamp_carla': 15562, + 'timestamp_device': 15031, + 'timestamp_stream': 15.562526479363441, + 'transform': [array([5.50784731e+00, 2.69786415e-06, 1.77562714e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41303766, -0.91384405, -1.50694847]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.72722053527832, + 'FR_Wheel_Angle': -14.413458824157715, + 'Location': array([ 3.54730721e+01, -2.54365563e+00, 1.82522298e-03]), + 'Rotation': array([-1.44595094e-02, -6.29404488e+01, 2.01854363e-01]), + 'Velocity': array([ 0.08256388, -0.27740529, -0.000323 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 793.9087524414062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.91499023e+02, -1.21363274e+02, 6.10351562e-05]), + 'frame': 729, + 'frame_number': 729, + 'framesequence': 727, + 'gaze_dir': array([ 0.98058069, -0.15469387, 0.12054598]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15469387, 0.12054598]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15469387, 0.12054598]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.577479779720306, + 'timestamp_carla': 15577, + 'timestamp_device': 15046, + 'timestamp_stream': 15.577479779720306, + 'transform': [array([5.52232361e+00, 2.71368276e-06, 1.77078240e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.38963071, -0.87702441, -1.47896695]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.72831916809082, + 'FR_Wheel_Angle': -14.413847923278809, + 'Location': array([ 3.55044823e+01, -2.58860183e+00, 1.86127180e-03]), + 'Rotation': array([-1.37628308e-02, -6.32057610e+01, 1.88013598e-01]), + 'Velocity': array([ 0.07983133, -0.2725338 , 0.00031511]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 789.8013305664062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.88211731e+02, -1.22177116e+02, -3.05175781e-05]), + 'frame': 730, + 'frame_number': 730, + 'framesequence': 728, + 'gaze_dir': array([ 0.98058069, -0.15624791, 0.11852475]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15624791, 0.11852475]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15624791, 0.11852475]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.591282278299332, + 'timestamp_carla': 15591, + 'timestamp_device': 15059, + 'timestamp_stream': 15.591282278299332, + 'transform': [array([5.53558826e+00, 2.72477951e-06, 1.77463528e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39808038, -0.90205097, -1.46571207]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.729055404663086, + 'FR_Wheel_Angle': -14.414947509765625, + 'Location': array([ 3.55333061e+01, -2.62640381e+00, 1.83498859e-03]), + 'Rotation': array([-1.42204529e-02, -6.34308586e+01, 1.97869986e-01]), + 'Velocity': array([ 7.78904632e-02, -2.70486832e-01, 9.32168914e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 786.2352905273438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.85621460e+02, -1.22847313e+02, -6.10351562e-05]), + 'frame': 731, + 'frame_number': 731, + 'framesequence': 729, + 'gaze_dir': array([ 0.98058069, -0.15789188, 0.11632574]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15789188, 0.11632574]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15789188, 0.11632574]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.60524707660079, + 'timestamp_carla': 15605, + 'timestamp_device': 15073, + 'timestamp_stream': 15.60524707660079, + 'transform': [array([5.54891443e+00, 2.74149670e-06, 1.77700038e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41539341, -0.95127815, -1.18336737]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -12.560449600219727, + 'FR_Wheel_Angle': -10.633723258972168, + 'Location': array([ 3.55618553e+01, -2.66318631e+00, 1.84509752e-03]), + 'Rotation': array([-1.44936610e-02, -6.36388702e+01, 2.04129353e-01]), + 'Velocity': array([ 8.34720954e-02, -2.66110390e-01, -1.62096025e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 782.3938598632812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.82597900e+02, -1.23533318e+02, 6.10351562e-05]), + 'frame': 732, + 'frame_number': 732, + 'framesequence': 730, + 'gaze_dir': array([ 0.98058069, -0.15950492, 0.11410394]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15950492, 0.11410394]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15950492, 0.11410394]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.618904579430819, + 'timestamp_carla': 15618, + 'timestamp_device': 15087, + 'timestamp_stream': 15.618904579430819, + 'transform': [array([5.56186104e+00, 2.75855859e-06, 1.78089133e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.38513577, -0.87210399, -0.68680012]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -6.857305526733398, + 'FR_Wheel_Angle': -6.760173320770264, + 'Location': array([ 3.55970268e+01, -2.71113896e+00, 1.81953900e-03]), + 'Rotation': array([-1.20279621e-02, -6.37914009e+01, 1.85613900e-01]), + 'Velocity': array([ 1.12204961e-01, -2.90680796e-01, 4.73928449e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 778.5509033203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.79578674e+02, -1.24182396e+02, -9.15527344e-05]), + 'frame': 733, + 'frame_number': 733, + 'framesequence': 731, + 'gaze_dir': array([ 0.98058069, -0.16108668, 0.11185977]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16108668, 0.11185977]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16108668, 0.11185977]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.633235078305006, + 'timestamp_carla': 15633, + 'timestamp_device': 15101, + 'timestamp_stream': 15.633235078305006, + 'transform': [array([5.57535267e+00, 2.77408367e-06, 1.78024289e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40437886, -0.89536488, -0.96390313]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.648006439208984, + 'FR_Wheel_Angle': -7.793337821960449, + 'Location': array([ 3.56301270e+01, -2.75528216e+00, 1.82247639e-03]), + 'Rotation': array([-1.07985288e-02, -6.39326096e+01, 1.98959872e-01]), + 'Velocity': array([ 1.15743726e-01, -3.19123119e-01, 2.89640418e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 774.7072143554688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 776.52056885, -124.79469299, 0. ]), + 'frame': 734, + 'frame_number': 734, + 'framesequence': 732, + 'gaze_dir': array([ 0.98058057, -0.16274652, 0.10943091]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16274652, 0.10943091]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16274652, 0.10943091]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.648367278277874, + 'timestamp_carla': 15648, + 'timestamp_device': 15116, + 'timestamp_stream': 15.648367278277874, + 'transform': [array([5.58949900e+00, 2.79001392e-06, 1.77448266e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3847068 , -0.85400212, -0.90734267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.463628768920898, + 'FR_Wheel_Angle': -7.879841327667236, + 'Location': array([ 3.56671104e+01, -2.80835223e+00, 1.79562089e-03]), + 'Rotation': array([-9.58275516e-03, -6.40963669e+01, 1.82498366e-01]), + 'Velocity': array([ 1.14683956e-01, -3.14565033e-01, -3.21102125e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 770.58837890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.73205811e+02, -1.25410271e+02, 9.15527344e-05]), + 'frame': 735, + 'frame_number': 735, + 'framesequence': 733, + 'gaze_dir': array([ 0.98058057, -0.16436955, 0.1069776 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.16436955, 0.1069776 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.16436955, 0.1069776 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.662167578935623, + 'timestamp_carla': 15662, + 'timestamp_device': 15131, + 'timestamp_stream': 15.662167578935623, + 'transform': [array([5.60231686e+00, 2.80535278e-06, 1.77871704e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.38891232, -0.86526889, -0.88626701]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.362395286560059, + 'FR_Wheel_Angle': -7.750307559967041, + 'Location': array([ 3.57010498e+01, -2.85509944e+00, 1.83327193e-03]), + 'Rotation': array([-9.49396286e-03, -6.42434769e+01, 1.86662063e-01]), + 'Velocity': array([ 1.13301978e-01, -3.12361807e-01, 1.70125961e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 766.4716186523438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.69959045e+02, -1.25984291e+02, 3.05175781e-05]), + 'frame': 736, + 'frame_number': 736, + 'framesequence': 734, + 'gaze_dir': array([ 0.98058069, -0.16574639, 0.10483174]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16574639, 0.10483174]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16574639, 0.10483174]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.6760328784585, + 'timestamp_carla': 15676, + 'timestamp_device': 15144, + 'timestamp_stream': 15.6760328784585, + 'transform': [array([5.61511278e+00, 2.81967186e-06, 1.78184500e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3788453 , -0.84721541, -0.88531953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.354711532592773, + 'FR_Wheel_Angle': -7.723334312438965, + 'Location': array([ 3.57366753e+01, -2.90580487e+00, 1.82533741e-03]), + 'Rotation': array([-9.22075473e-03, -6.44016876e+01, 1.82742029e-01]), + 'Velocity': array([ 1.11872353e-01, -3.11071992e-01, 8.17203472e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 762.9088134765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.67206116e+02, -1.26449059e+02, -3.05175781e-05]), + 'frame': 737, + 'frame_number': 737, + 'framesequence': 735, + 'gaze_dir': array([ 0.98058069, -0.16730011, 0.10233395]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16730011, 0.10233395]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16730011, 0.10233395]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.691281579434872, + 'timestamp_carla': 15691, + 'timestamp_device': 15159, + 'timestamp_stream': 15.691281579434872, + 'transform': [array([5.62909222e+00, 2.83710619e-06, 1.77543634e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.38999352, -0.87680244, -0.8821044 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.35617446899414, + 'FR_Wheel_Angle': -7.723546028137207, + 'Location': array([ 3.57701035e+01, -2.95136356e+00, 1.82785501e-03]), + 'Rotation': array([-9.39833932e-03, -6.45449066e+01, 1.89498499e-01]), + 'Velocity': array([ 1.10448539e-01, -3.10269594e-01, -7.13348345e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 758.8026733398438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 763.83587646, -126.94744873, 0. ]), + 'frame': 738, + 'frame_number': 738, + 'framesequence': 736, + 'gaze_dir': array([ 0.98058069, -0.16881616, 0.09981297]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16881616, 0.09981297]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16881616, 0.09981297]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.706015579402447, + 'timestamp_carla': 15706, + 'timestamp_device': 15174, + 'timestamp_stream': 15.706015579402447, + 'transform': [array([5.64369965e+00, 2.84780708e-06, 1.77932740e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40355414, -0.91046309, -0.88115889]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.356523513793945, + 'FR_Wheel_Angle': -7.723826885223389, + 'Location': array([ 3.58020058e+01, -2.99320889e+00, 1.82480330e-03]), + 'Rotation': array([-9.76717006e-03, -6.46774521e+01, 2.03632087e-01]), + 'Velocity': array([ 1.09454066e-01, -3.10280204e-01, 2.89487834e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 754.7003784179688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.60588928e+02, -1.27405319e+02, 6.10351562e-05]), + 'frame': 739, + 'frame_number': 739, + 'framesequence': 737, + 'gaze_dir': array([ 0.98058069, -0.17019695, 0.09743985]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17019695, 0.09743985]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17019695, 0.09743985]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.720202676951885, + 'timestamp_carla': 15720, + 'timestamp_device': 15188, + 'timestamp_stream': 15.720202676951885, + 'transform': [array([5.65764856e+00, 2.86061277e-06, 1.78592675e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39278474, -0.89488602, -0.87066913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.356820106506348, + 'FR_Wheel_Angle': -7.724182605743408, + 'Location': array([ 3.58367920e+01, -3.04259992e+00, 1.82220933e-03]), + 'Rotation': array([-9.43249092e-03, -6.48316727e+01, 1.92146614e-01]), + 'Velocity': array([ 1.07263163e-01, -3.06858212e-01, -1.56702998e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 750.8817749023438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 757.72546387, -127.79748535, 0. ]), + 'frame': 740, + 'frame_number': 740, + 'framesequence': 738, + 'gaze_dir': array([ 0.98058057, -0.17173421, 0.09470437]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.17173421, 0.09470437]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.17173421, 0.09470437]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.735693577677011, + 'timestamp_carla': 15735, + 'timestamp_device': 15204, + 'timestamp_stream': 15.735693577677011, + 'transform': [array([5.67275143e+00, 2.88352339e-06, 1.78260799e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39078155, -0.89630324, -0.86510944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.357144355773926, + 'FR_Wheel_Angle': -7.724621772766113, + 'Location': array([ 3.58696175e+01, -3.08763337e+00, 1.82873243e-03]), + 'Rotation': array([-9.45981126e-03, -6.49728012e+01, 1.93112209e-01]), + 'Velocity': array([ 1.05762251e-01, -3.05171549e-01, 1.83663360e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 746.5282592773438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.54190125e+02, -1.28204147e+02, -3.05175781e-05]), + 'frame': 741, + 'frame_number': 741, + 'framesequence': 739, + 'gaze_dir': array([ 0.98058069, -0.17313536, 0.09211774]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17313536, 0.09211774]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17313536, 0.09211774]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.75028457865119, + 'timestamp_carla': 15750, + 'timestamp_device': 15219, + 'timestamp_stream': 15.75028457865119, + 'transform': [array([5.68686342e+00, 2.89641753e-06, 1.78627006e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39941004, -0.91968781, -0.86337811]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.357515335083008, + 'FR_Wheel_Angle': -7.724734306335449, + 'Location': array([ 3.59009972e+01, -3.12932515e+00, 1.81824202e-03]), + 'Rotation': array([-9.70569812e-03, -6.51041336e+01, 2.03823641e-01]), + 'Velocity': array([ 1.04777999e-01, -3.04853499e-01, 1.67231556e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 742.455078125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.51088318e+02, -1.28544907e+02, 9.15527344e-05]), + 'frame': 742, + 'frame_number': 742, + 'framesequence': 740, + 'gaze_dir': array([ 0.98058069, -0.17449769, 0.08951039]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17449769, 0.08951039]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17449769, 0.08951039]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.766323279589415, + 'timestamp_carla': 15766, + 'timestamp_device': 15234, + 'timestamp_stream': 15.766323279589415, + 'transform': [array([5.70225000e+00, 2.91157016e-06, 1.77871704e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40095469, -0.9278695 , -0.85948557]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.357444763183594, + 'FR_Wheel_Angle': -7.725091457366943, + 'Location': array([ 3.59331970e+01, -3.17293787e+00, 1.80725567e-03]), + 'Rotation': array([-9.79449041e-03, -6.52409515e+01, 2.08231747e-01]), + 'Velocity': array([ 1.03539683e-01, -3.03748131e-01, -2.77667044e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 738.396240234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 747.90307617, -128.84812927, 0. ]), + 'frame': 743, + 'frame_number': 743, + 'framesequence': 741, + 'gaze_dir': array([ 0.98058069, -0.17599395, 0.08653127]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17599395, 0.08653127]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17599395, 0.08653127]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.783160276710987, + 'timestamp_carla': 15783, + 'timestamp_device': 15251, + 'timestamp_stream': 15.783160276710987, + 'transform': [array([5.71826887e+00, 2.93023390e-06, 1.76605221e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40321207, -0.94354093, -0.78282535]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.639219760894775, + 'FR_Wheel_Angle': -6.71834659576416, + 'Location': array([ 3.59655113e+01, -3.21728849e+00, 1.81999675e-03]), + 'Rotation': array([-9.70569812e-03, -6.53786087e+01, 2.00550318e-01]), + 'Velocity': array([ 0.10301915, -0.29984891, 0.00033645]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 733.8099975585938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.44248779e+02, -1.29145798e+02, -9.15527344e-05]), + 'frame': 744, + 'frame_number': 744, + 'framesequence': 742, + 'gaze_dir': array([ 0.98058069, -0.17735593, 0.08370427]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17735593, 0.08370427]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17735593, 0.08370427]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.797901377081871, + 'timestamp_carla': 15797, + 'timestamp_device': 15267, + 'timestamp_stream': 15.797901377081871, + 'transform': [array([5.73218966e+00, 2.94285314e-06, 1.77261350e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.01068538e-01, -9.33915377e-01, -1.05420018e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.59993553e+01, -3.26100445e+00, 1.79192063e-03]), + 'Rotation': array([-9.09781177e-03, -6.54389496e+01, 1.98023409e-01]), + 'Velocity': array([ 1.29282236e-01, -3.01147282e-01, 9.72270936e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 729.5084838867188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.40980469e+02, -1.29382339e+02, -6.10351562e-05]), + 'frame': 745, + 'frame_number': 745, + 'framesequence': 743, + 'gaze_dir': array([ 0.98058069, -0.17851037, 0.08121318]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17851037, 0.08121318]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17851037, 0.08121318]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.813115879893303, + 'timestamp_carla': 15813, + 'timestamp_device': 15281, + 'timestamp_stream': 15.813115879893303, + 'transform': [array([5.74645472e+00, 2.95482073e-06, 1.77467347e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.05618370e-01, -9.12531495e-01, 5.58224565e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.60366516e+01, -3.30935574e+00, 1.79947377e-03]), + 'Rotation': array([-6.77554728e-03, -6.54245453e+01, 2.03724608e-01]), + 'Velocity': array([ 1.52356684e-01, -3.50743920e-01, -3.62920764e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 725.7639770507812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.38132019e+02, -1.29556076e+02, -6.10351562e-05]), + 'frame': 746, + 'frame_number': 746, + 'framesequence': 744, + 'gaze_dir': array([ 0.98058069, -0.17970838, 0.0785266 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17970838, 0.0785266 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17970838, 0.0785266 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.828037578612566, + 'timestamp_carla': 15828, + 'timestamp_device': 15296, + 'timestamp_stream': 15.828037578612566, + 'transform': [array([5.76034832e+00, 2.97267411e-06, 1.77829736e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.06731963e-01, -9.03290749e-01, 6.36742470e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.60754280e+01, -3.36129761e+00, 1.78783888e-03]), + 'Rotation': array([-5.77150937e-03, -6.54240417e+01, 2.02958643e-01]), + 'Velocity': array([ 1.52825147e-01, -3.51585537e-01, -1.59893039e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 721.76708984375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 735.03253174, -129.70727539, 0. ]), + 'frame': 747, + 'frame_number': 747, + 'framesequence': 745, + 'gaze_dir': array([ 0.98058069, -0.18094181, 0.07564137]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18094181, 0.07564137]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18094181, 0.07564137]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.84271627664566, + 'timestamp_carla': 15842, + 'timestamp_device': 15312, + 'timestamp_stream': 15.84271627664566, + 'transform': [array([5.77392244e+00, 2.99071394e-06, 1.78268424e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.13558513e-01, -9.12803054e-01, -6.74324110e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.61135597e+01, -3.41204619e+00, 1.77731027e-03]), + 'Rotation': array([-5.37535874e-03, -6.54235153e+01, 1.99902877e-01]), + 'Velocity': array([ 1.52567536e-01, -3.51457745e-01, 1.74732209e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 717.52392578125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 731.61682129, -129.82974243, 0. ]), + 'frame': 748, + 'frame_number': 748, + 'framesequence': 746, + 'gaze_dir': array([ 0.98058069, -0.18198302, 0.07310069]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18198302, 0.07310069]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18198302, 0.07310069]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.858266778290272, + 'timestamp_carla': 15858, + 'timestamp_device': 15326, + 'timestamp_stream': 15.858266778290272, + 'transform': [array([5.78820372e+00, 2.99899330e-06, 1.78005209e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.06895936e-01, -8.95343184e-01, -8.22592938e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.61527672e+01, -3.46518517e+00, 1.79470540e-03]), + 'Rotation': array([-5.19094337e-03, -6.54229736e+01, 1.91652939e-01]), + 'Velocity': array([ 1.52302697e-01, -3.50622982e-01, -3.22594628e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 713.8290405273438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.28789978e+02, -1.29904449e+02, -6.10351562e-05]), + 'frame': 749, + 'frame_number': 749, + 'framesequence': 747, + 'gaze_dir': array([ 0.98058069, -0.18305896, 0.07036294]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18305896, 0.07036294]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18305896, 0.07036294]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.872818280011415, + 'timestamp_carla': 15872, + 'timestamp_device': 15341, + 'timestamp_stream': 15.872818280011415, + 'transform': [array([5.80263186e+00, 3.01249747e-06, 1.78691861e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.09791917e-01, -8.99662971e-01, 5.46150977e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.61893463e+01, -3.51276302e+00, 1.81961537e-03]), + 'Rotation': array([-5.12947189e-03, -6.54225311e+01, 2.03497618e-01]), + 'Velocity': array([ 1.53571784e-01, -3.53135258e-01, 2.44011870e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 709.8877563476562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.25755310e+02, -1.29951004e+02, 3.05175781e-05]), + 'frame': 750, + 'frame_number': 750, + 'framesequence': 748, + 'gaze_dir': array([ 0.98058069, -0.18402608, 0.06779332]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18402608, 0.06779332]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18402608, 0.06779332]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.887157879769802, + 'timestamp_carla': 15887, + 'timestamp_device': 15355, + 'timestamp_stream': 15.887157879769802, + 'transform': [array([5.81673288e+00, 3.02172703e-06, 1.79367058e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.03322786e-01, -8.85438025e-01, -4.81828056e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.62298431e+01, -3.56834292e+00, 1.80473796e-03]), + 'Rotation': array([-5.09532075e-03, -6.54222031e+01, 1.93187132e-01]), + 'Velocity': array([ 1.52858451e-01, -3.51527393e-01, -2.00920098e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 706.23046875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 723.05627441, -129.9644928 , 0. ]), + 'frame': 751, + 'frame_number': 751, + 'framesequence': 749, + 'gaze_dir': array([ 0.98058069, -0.18495712, 0.0652104 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18495712, 0.0652104 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18495712, 0.0652104 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.900831878185272, + 'timestamp_carla': 15900, + 'timestamp_device': 15369, + 'timestamp_stream': 15.900831878185272, + 'transform': [array([5.83007479e+00, 3.03653496e-06, 1.80259696e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 3.98179024e-01, -8.73388886e-01, 8.79697654e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.62685699e+01, -3.62007165e+00, 1.80084701e-03]), + 'Rotation': array([-5.09532075e-03, -6.54217682e+01, 1.99194834e-01]), + 'Velocity': array([ 1.53834984e-01, -3.53116840e-01, 1.61600110e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 702.5918579101562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 720.34576416, -129.94903564, 0. ]), + 'frame': 752, + 'frame_number': 752, + 'framesequence': 750, + 'gaze_dir': array([ 0.98058069, -0.1858519 , 0.06261471]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1858519 , 0.06261471]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1858519 , 0.06261471]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.914838578552008, + 'timestamp_carla': 15914, + 'timestamp_device': 15383, + 'timestamp_stream': 15.914838578552008, + 'transform': [array([5.84363985e+00, 3.05217645e-06, 1.80774683e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.05070305e-01, -8.89224350e-01, -1.05390272e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.63077736e+01, -3.67309356e+00, 1.78772444e-03]), + 'Rotation': array([-5.09532075e-03, -6.54214096e+01, 1.92131564e-01]), + 'Velocity': array([ 1.52506992e-01, -3.50897968e-01, 2.84881593e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 698.9733276367188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.17581909e+02, -1.29905197e+02, 3.05175781e-05]), + 'frame': 753, + 'frame_number': 753, + 'framesequence': 751, + 'gaze_dir': array([ 0.98058069, -0.1866502 , 0.06019332]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1866502 , 0.06019332]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1866502 , 0.06019332]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.928380079567432, + 'timestamp_carla': 15928, + 'timestamp_device': 15396, + 'timestamp_stream': 15.928380079567432, + 'transform': [array([5.85666180e+00, 3.06470292e-06, 1.81407924e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.11068082e-01, -9.01647151e-01, 4.15707882e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.63447227e+01, -3.72103763e+00, 1.77822588e-03]), + 'Rotation': array([-5.09532075e-03, -6.54209213e+01, 2.02403247e-01]), + 'Velocity': array([ 1.53523773e-01, -3.53051722e-01, -1.19071003e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 695.6306762695312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 715.1529541 , -129.83927917, 0. ]), + 'frame': 754, + 'frame_number': 754, + 'framesequence': 752, + 'gaze_dir': array([ 0.98058069, -0.18747458, 0.05757441]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18747458, 0.05757441]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18747458, 0.05757441]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.94223677739501, + 'timestamp_carla': 15942, + 'timestamp_device': 15410, + 'timestamp_stream': 15.94223677739501, + 'transform': [array([5.86989355e+00, 3.07958544e-06, 1.81716913e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.14084464e-01, -9.08646047e-01, -7.08533253e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.63832130e+01, -3.77246213e+00, 1.80496683e-03]), + 'Rotation': array([-5.09532075e-03, -6.54204941e+01, 1.98008433e-01]), + 'Velocity': array([ 1.52757019e-01, -3.51717949e-01, 2.04901691e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 692.0511474609375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.12401489e+02, -1.29741684e+02, -3.05175781e-05]), + 'frame': 755, + 'frame_number': 755, + 'framesequence': 753, + 'gaze_dir': array([ 0.98058069, -0.18826221, 0.05494422]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18826221, 0.05494422]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18826221, 0.05494422]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.95591227710247, + 'timestamp_carla': 15955, + 'timestamp_device': 15424, + 'timestamp_stream': 15.95591227710247, + 'transform': [array([5.88286448e+00, 3.09395568e-06, 1.82029721e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 4.17075187e-01, -9.14647341e-01, 5.78053687e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 3.64199028e+01, -3.81982374e+00, 1.79535383e-03]), + 'Rotation': array([-5.12947189e-03, -6.54200897e+01, 2.07058087e-01]), + 'Velocity': array([ 1.53631270e-01, -3.53456765e-01, 2.71329860e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 688.4923706054688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.09694641e+02, -1.29616776e+02, 3.05175781e-05]), + 'frame': 756, + 'frame_number': 756, + 'framesequence': 754, + 'gaze_dir': array([ 0.98058069, -0.18896058, 0.05249232]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18896058, 0.05249232]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18896058, 0.05249232]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.968707580119371, + 'timestamp_carla': 15968, + 'timestamp_device': 15437, + 'timestamp_stream': 15.968707580119371, + 'transform': [array([5.89492369e+00, 3.10676592e-06, 1.82689668e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41223046, -0.90404963, 0.31090948]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 2.511333703994751, + 'FR_Wheel_Angle': 3.3036293983459473, + 'Location': array([ 3.64616013e+01, -3.87792850e+00, 1.79512496e-03]), + 'Rotation': array([-5.09532075e-03, -6.54136276e+01, 1.87254235e-01]), + 'Velocity': array([ 1.60343468e-01, -3.46720994e-01, 1.75285342e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 685.2075805664062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.07271973e+02, -1.29476913e+02, 9.15527344e-05]), + 'frame': 757, + 'frame_number': 757, + 'framesequence': 755, + 'gaze_dir': array([ 0.98058069, -0.18957683, 0.05022106]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18957683, 0.05022106]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18957683, 0.05022106]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.981401078402996, + 'timestamp_carla': 15981, + 'timestamp_device': 15449, + 'timestamp_stream': 15.981401078402996, + 'transform': [array([5.90681505e+00, 3.11611643e-06, 1.83231349e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41334698, -0.88688481, 1.35583508]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 9.449921607971191, + 'FR_Wheel_Angle': 10.222664833068848, + 'Location': array([ 3.65029526e+01, -3.92824125e+00, 1.78703782e-03]), + 'Rotation': array([-4.08445299e-03, -6.52759857e+01, 1.93481922e-01]), + 'Velocity': array([ 2.01867074e-01, -3.58656615e-01, 4.35399998e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 682.1937255859375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.05064697e+02, -1.29327805e+02, 3.05175781e-05]), + 'frame': 758, + 'frame_number': 758, + 'framesequence': 756, + 'gaze_dir': array([ 0.98058069, -0.19026132, 0.04756216]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19026132, 0.04756216]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19026132, 0.04756216]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 15.994516979902983, + 'timestamp_carla': 15994, + 'timestamp_device': 15463, + 'timestamp_stream': 15.994516979902983, + 'transform': [array([5.91902828e+00, 3.12959264e-06, 1.83418265e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3922593 , -0.80814075, 1.10378981]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.067267894744873, + 'FR_Wheel_Angle': 7.811016082763672, + 'Location': array([ 3.65545616e+01, -3.99624348e+00, 1.75335398e-03]), + 'Rotation': array([-2.22664163e-03, -6.50435333e+01, 1.74733549e-01]), + 'Velocity': array([ 2.14666724e-01, -3.98737341e-01, -1.11765861e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 678.6983032226562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.02295410e+02, -1.29129700e+02, 6.10351562e-05]), + 'frame': 759, + 'frame_number': 759, + 'framesequence': 757, + 'gaze_dir': array([ 0.98058069, -0.1908184 , 0.04527564]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1908184 , 0.04527564]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1908184 , 0.04527564]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.00705287978053, + 'timestamp_carla': 16007, + 'timestamp_device': 15475, + 'timestamp_stream': 16.00705287978053, + 'transform': [array([5.93063450e+00, 3.13808641e-06, 1.83811178e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3885389 , -0.78835452, 1.21056223]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.738333225250244, + 'FR_Wheel_Angle': 8.245240211486816, + 'Location': array([ 3.66028824e+01, -4.05793238e+00, 1.77353376e-03]), + 'Rotation': array([-1.70754723e-03, -6.48316269e+01, 1.73029780e-01]), + 'Velocity': array([ 2.17942730e-01, -3.93603951e-01, 1.17444986e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 675.7207641601562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 7.00144836e+02, -1.28939621e+02, -9.15527344e-05]), + 'frame': 760, + 'frame_number': 760, + 'framesequence': 758, + 'gaze_dir': array([ 0.98058069, -0.19139087, 0.04279115]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19139087, 0.04279115]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19139087, 0.04279115]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.020132578909397, + 'timestamp_carla': 16020, + 'timestamp_device': 15488, + 'timestamp_stream': 16.020132578909397, + 'transform': [array([5.94267273e+00, 3.15147417e-06, 1.83818815e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4056192 , -0.81273133, 1.23819983]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.807521343231201, + 'FR_Wheel_Angle': 8.417948722839355, + 'Location': array([ 3.66486740e+01, -4.11513996e+00, 1.77147379e-03]), + 'Rotation': array([-1.24992453e-03, -6.46374664e+01, 1.83630794e-01]), + 'Velocity': array([ 2.22813025e-01, -3.98861140e-01, 3.37867736e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 672.5147094726562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 697.67492676, -128.71286011, 0. ]), + 'frame': 761, + 'frame_number': 761, + 'framesequence': 759, + 'gaze_dir': array([ 0.98058069, -0.19189054, 0.04049142]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19189054, 0.04049142]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19189054, 0.04049142]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.03217837959528, + 'timestamp_carla': 16032, + 'timestamp_device': 15500, + 'timestamp_stream': 16.03217837959528, + 'transform': [array([5.95463324e+00, 3.15793750e-06, 1.84280390e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39590991, -0.78262573, 1.23261034]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.742641448974609, + 'FR_Wheel_Angle': 8.358912467956543, + 'Location': array([ 3.67008553e+01, -4.18260956e+00, 1.76784990e-03]), + 'Rotation': array([-1.31139625e-03, -6.44091721e+01, 1.72456607e-01]), + 'Velocity': array([ 2.25210160e-01, -3.99650633e-01, 3.77883902e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 669.5734252929688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.95548035e+02, -1.28484467e+02, 3.05175781e-05]), + 'frame': 762, + 'frame_number': 762, + 'framesequence': 760, + 'gaze_dir': array([ 0.98058069, -0.19236265, 0.03818586]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19236265, 0.03818586]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19236265, 0.03818586]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.04448137804866, + 'timestamp_carla': 16044, + 'timestamp_device': 15512, + 'timestamp_stream': 16.04448137804866, + 'transform': [array([5.96676111e+00, 3.16373962e-06, 1.84520718e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41517606, -0.81460696, 1.24570501]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.713804244995117, + 'FR_Wheel_Angle': 8.334151268005371, + 'Location': array([ 3.67466125e+01, -4.23814964e+00, 1.76056381e-03]), + 'Rotation': array([-9.15245269e-04, -6.42171173e+01, 1.87888175e-01]), + 'Velocity': array([ 2.29666516e-01, -4.04741317e-01, -1.08289714e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 666.6516723632812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.93435303e+02, -1.28238541e+02, -3.05175781e-05]), + 'frame': 763, + 'frame_number': 763, + 'framesequence': 761, + 'gaze_dir': array([ 0.98058069, -0.19284274, 0.03568208]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19284274, 0.03568208]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19284274, 0.03568208]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.056994777172804, + 'timestamp_carla': 16056, + 'timestamp_device': 15525, + 'timestamp_stream': 16.056994777172804, + 'transform': [array([5.97901011e+00, 3.18112757e-06, 1.84589380e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40943459, -0.79399365, 1.24444067]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.713470458984375, + 'FR_Wheel_Angle': 8.333651542663574, + 'Location': array([ 3.67994957e+01, -4.30587530e+00, 1.76083087e-03]), + 'Rotation': array([-1.22260384e-03, -6.39870377e+01, 1.74799398e-01]), + 'Velocity': array([ 2.31075183e-01, -4.03416842e-01, -3.07579030e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 663.506591796875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.91086609e+02, -1.27952103e+02, -6.10351562e-05]), + 'frame': 764, + 'frame_number': 764, + 'framesequence': 762, + 'gaze_dir': array([ 0.98058069, -0.19329031, 0.03317209]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19329031, 0.03317209]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19329031, 0.03317209]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.069659378379583, + 'timestamp_carla': 16069, + 'timestamp_device': 15538, + 'timestamp_stream': 16.069659378379583, + 'transform': [array([5.99132204e+00, 3.19506944e-06, 1.84539787e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41934741, -0.80726826, 1.2603265 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.713086128234863, + 'FR_Wheel_Angle': 8.333255767822266, + 'Location': array([ 3.68464432e+01, -4.36265135e+00, 1.77883625e-03]), + 'Rotation': array([-9.15245269e-04, -6.37902069e+01, 1.86816245e-01]), + 'Velocity': array([ 2.35508144e-01, -4.07756478e-01, 4.02250269e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 660.3829956054688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 688.77441406, -127.64530945, 0. ]), + 'frame': 765, + 'frame_number': 765, + 'framesequence': 763, + 'gaze_dir': array([ 0.98058057, -0.19367447, 0.03085025]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19367447, 0.03085025]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19367447, 0.03085025]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.082469176501036, + 'timestamp_carla': 16082, + 'timestamp_device': 15550, + 'timestamp_stream': 16.082469176501036, + 'transform': [array([6.00369120e+00, 3.20621734e-06, 1.84387201e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42633417, -0.81330204, 1.26840234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7122955322265625, + 'FR_Wheel_Angle': 8.332658767700195, + 'Location': array([ 3.68969078e+01, -4.42489100e+00, 1.76495069e-03]), + 'Rotation': array([-9.49396228e-04, -6.35757942e+01, 1.86877817e-01]), + 'Velocity': array([ 0.23855782, -0.40949997, -0.00045324]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 657.5196533203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.86763123e+02, -1.27344452e+02, -6.10351562e-05]), + 'frame': 766, + 'frame_number': 766, + 'framesequence': 764, + 'gaze_dir': array([ 0.98058069, -0.19405912, 0.02833004]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19405912, 0.02833004]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19405912, 0.02833004]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.095422476530075, + 'timestamp_carla': 16095, + 'timestamp_device': 15563, + 'timestamp_stream': 16.095422476530075, + 'transform': [array([6.01611614e+00, 3.22442474e-06, 1.84150692e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44168323, -0.83534306, 1.27691126]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.7122802734375, + 'FR_Wheel_Angle': 8.332254409790039, + 'Location': array([ 3.69443398e+01, -4.48175573e+00, 1.79096696e-03]), + 'Rotation': array([-8.26452859e-04, -6.33774567e+01, 1.93407699e-01]), + 'Velocity': array([ 2.41458923e-01, -4.11511779e-01, 2.54354469e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 654.43896484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.84511780e+02, -1.26999527e+02, 3.05175781e-05]), + 'frame': 767, + 'frame_number': 767, + 'framesequence': 765, + 'gaze_dir': array([ 0.98058069, -0.19443671, 0.02561054]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19443671, 0.02561054]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19443671, 0.02561054]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.108521576970816, + 'timestamp_carla': 16108, + 'timestamp_device': 15577, + 'timestamp_stream': 16.108521576970816, + 'transform': [array([6.02859926e+00, 3.23519066e-06, 1.83845521e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.43957442, -0.82410711, 1.28548574]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.711470127105713, + 'FR_Wheel_Angle': 8.331670761108398, + 'Location': array([ 3.69950027e+01, -4.54338360e+00, 1.77956105e-03]), + 'Rotation': array([-8.53773614e-04, -6.31638031e+01, 1.91737235e-01]), + 'Velocity': array([ 2.44771346e-01, -4.13312644e-01, -2.94694881e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 651.1470336914062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.82026672e+02, -1.26606544e+02, 3.05175781e-05]), + 'frame': 768, + 'frame_number': 768, + 'framesequence': 766, + 'gaze_dir': array([ 0.98058069, -0.19473004, 0.02327549]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19473004, 0.02327549]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19473004, 0.02327549]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.12161387875676, + 'timestamp_carla': 16121, + 'timestamp_device': 15589, + 'timestamp_stream': 16.12161387875676, + 'transform': [array([6.04099607e+00, 3.24930033e-06, 1.83567044e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.45405099, -0.84340417, 1.28943205]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.70686149597168, + 'FR_Wheel_Angle': 8.440199851989746, + 'Location': array([ 3.70440941e+01, -4.60217428e+00, 1.76987168e-03]), + 'Rotation': array([-8.53773614e-04, -6.29584732e+01, 1.91680863e-01]), + 'Velocity': array([ 0.24694274, -0.41405791, -0.00065981]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 648.3466186523438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.80104065e+02, -1.26252220e+02, -3.05175781e-05]), + 'frame': 769, + 'frame_number': 769, + 'framesequence': 767, + 'gaze_dir': array([ 0.98058069, -0.19503683, 0.02054709]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19503683, 0.02054709]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19503683, 0.02054709]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.134774677455425, + 'timestamp_carla': 16134, + 'timestamp_device': 15603, + 'timestamp_stream': 16.134774677455425, + 'transform': [array([6.05337954e+00, 3.26740974e-06, 1.83277123e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.46571481, -0.85172665, 2.28455234]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.84620189666748, + 'FR_Wheel_Angle': 16.739715576171875, + 'Location': array([ 3.70956802e+01, -4.66203642e+00, 1.79455278e-03]), + 'Rotation': array([-9.49396228e-04, -6.26795845e+01, 1.84069619e-01]), + 'Velocity': array([ 2.74711996e-01, -3.99022162e-01, 1.58109659e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 645.10498046875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.77673096e+02, -1.25818901e+02, -6.10351562e-05]), + 'frame': 770, + 'frame_number': 770, + 'framesequence': 768, + 'gaze_dir': array([ 0.98058069, -0.19528745, 0.01800985]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19528745, 0.01800985]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19528745, 0.01800985]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.147740878164768, + 'timestamp_carla': 16147, + 'timestamp_device': 15616, + 'timestamp_stream': 16.147740878164768, + 'transform': [array([6.06550503e+00, 3.28298165e-06, 1.83113094e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3978698 , -0.69508743, 2.71822357]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 13.971920013427734, + 'FR_Wheel_Angle': 15.779699325561523, + 'Location': array([ 3.71625862e+01, -4.73706818e+00, 1.76765909e-03]), + 'Rotation': array([ 3.41509440e-04, -6.21333656e+01, 1.61411420e-01]), + 'Velocity': array([ 3.15607071e-01, -4.34516400e-01, -1.07283588e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 642.119140625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.75530518e+02, -1.25397461e+02, 3.05175781e-05]), + 'frame': 771, + 'frame_number': 771, + 'framesequence': 769, + 'gaze_dir': array([ 0.98058069, -0.19548948, 0.01566514]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19548948, 0.01566514]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19548948, 0.01566514]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.16029977798462, + 'timestamp_carla': 16160, + 'timestamp_device': 15628, + 'timestamp_stream': 16.16029977798462, + 'transform': [array([6.07718134e+00, 3.29681643e-06, 1.83158868e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42826214, -0.72715837, 2.90821314]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.746888160705566, + 'FR_Wheel_Angle': 17.168066024780273, + 'Location': array([ 3.72224274e+01, -4.80236101e+00, 1.75327773e-03]), + 'Rotation': array([ 1.24309433e-03, -6.16777382e+01, 1.66578561e-01]), + 'Velocity': array([ 3.26513171e-01, -4.35216069e-01, -2.63261791e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 639.3846435546875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 673.64678955, -124.99263 , 0. ]), + 'frame': 772, + 'frame_number': 772, + 'framesequence': 770, + 'gaze_dir': array([ 0.98058069, -0.19567659, 0.01312262]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19567659, 0.01312262]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19567659, 0.01312262]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.173629079014063, + 'timestamp_carla': 16173, + 'timestamp_device': 15641, + 'timestamp_stream': 16.173629079014063, + 'transform': [array([6.08949995e+00, 3.30933790e-06, 1.82758330e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.437354 , -0.72350323, 2.87726402]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.204733848571777, + 'FR_Wheel_Angle': 16.482181549072266, + 'Location': array([ 3.72833214e+01, -4.86759043e+00, 1.69804087e-03]), + 'Rotation': array([ 2.02856609e-03, -6.12043381e+01, 1.70540020e-01]), + 'Velocity': array([ 0.33734465, -0.44737408, -0.00060225]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 636.4462280273438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.71487000e+02, -1.24537308e+02, -6.10351562e-05]), + 'frame': 773, + 'frame_number': 773, + 'framesequence': 771, + 'gaze_dir': array([ 0.98058069, -0.19583066, 0.01057788]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19583066, 0.01057788]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19583066, 0.01057788]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.186066579073668, + 'timestamp_carla': 16186, + 'timestamp_device': 15654, + 'timestamp_stream': 16.186066579073668, + 'transform': [array([6.10184860e+00, 3.31565229e-06, 1.83197018e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4272241 , -0.6884129 , 2.89989591]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.323522567749023, + 'FR_Wheel_Angle': 16.559982299804688, + 'Location': array([ 3.73500977e+01, -4.94087410e+00, 1.72062393e-03]), + 'Rotation': array([ 1.63241511e-03, -6.06806259e+01, 1.57909930e-01]), + 'Velocity': array([ 0.34192389, -0.44330269, 0.00056104]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 633.5311889648438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.69418213e+02, -1.24064499e+02, -6.10351562e-05]), + 'frame': 774, + 'frame_number': 774, + 'framesequence': 772, + 'gaze_dir': array([ 0.98058069, -0.19595161, 0.00803116]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19595161, 0.00803116]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19595161, 0.00803116]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.198564879596233, + 'timestamp_carla': 16198, + 'timestamp_device': 15667, + 'timestamp_stream': 16.198564879596233, + 'transform': [array([6.11416721e+00, 3.32603190e-06, 1.83506007e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42792308, -0.67666715, 2.95309639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.343490600585938, + 'FR_Wheel_Angle': 16.609912872314453, + 'Location': array([ 3.74147720e+01, -5.00998402e+00, 1.73286907e-03]), + 'Rotation': array([ 1.71437743e-03, -6.01815109e+01, 1.59629405e-01]), + 'Velocity': array([ 0.35155717, -0.44708869, 0.00057519]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 630.6419677734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.67381165e+02, -1.23574966e+02, 3.05175781e-05]), + 'frame': 775, + 'frame_number': 775, + 'framesequence': 773, + 'gaze_dir': array([ 0.98058069, -0.19603945, 0.00548327]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19603945, 0.00548327]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19603945, 0.00548327]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.21183867752552, + 'timestamp_carla': 16211, + 'timestamp_device': 15680, + 'timestamp_stream': 16.21183867752552, + 'transform': [array([6.12715483e+00, 3.34228343e-06, 1.83341978e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42304119, -0.65548354, 2.99892592]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.3732328414917, + 'FR_Wheel_Angle': 16.64202117919922, + 'Location': array([ 3.74850960e+01, -5.08505249e+00, 1.74839492e-03]), + 'Rotation': array([ 1.55728310e-03, -5.96390915e+01, 1.56901717e-01]), + 'Velocity': array([ 3.61004442e-01, -4.49618340e-01, 8.36849213e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 627.7777709960938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.65369446e+02, -1.23068863e+02, -3.05175781e-05]), + 'frame': 776, + 'frame_number': 776, + 'framesequence': 774, + 'gaze_dir': array([ 0.98058069, -0.19609702, 0.0027381 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19609702, 0.0027381 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19609702, 0.0027381 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.225881576538086, + 'timestamp_carla': 16225, + 'timestamp_device': 15694, + 'timestamp_stream': 16.225881576538086, + 'transform': [array([6.14079285e+00, 3.35644904e-06, 1.82727806e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41221017, -0.6230424 , 3.01534605]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.371617317199707, + 'FR_Wheel_Angle': 16.640666961669922, + 'Location': array([ 3.75616074e+01, -5.16647959e+00, 1.79306499e-03]), + 'Rotation': array([ 9.97207593e-04, -5.90498772e+01, 1.45247519e-01]), + 'Velocity': array([ 3.67789537e-01, -4.48278308e-01, 1.94644927e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 624.7196655273438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.63205444e+02, -1.22505318e+02, -6.10351562e-05]), + 'frame': 777, + 'frame_number': 777, + 'framesequence': 775, + 'gaze_dir': array([ 9.80580688e-01, -1.96116120e-01, -7.42668863e-06]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, -1.96116120e-01, -7.42668863e-06]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, -1.96116120e-01, -7.42668863e-06]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.239865377545357, + 'timestamp_carla': 16239, + 'timestamp_device': 15708, + 'timestamp_stream': 16.239865377545357, + 'transform': [array([6.15427351e+00, 3.37077267e-06, 1.82250969e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.43294901, -0.64385581, 3.07181978]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.369124412536621, + 'FR_Wheel_Angle': 16.63822364807129, + 'Location': array([ 3.76285210e+01, -5.23381758e+00, 1.76769728e-03]), + 'Rotation': array([ 1.44116988e-03, -5.85489235e+01, 1.56253383e-01]), + 'Velocity': array([ 3.78688574e-01, -4.53458995e-01, -1.73091888e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 621.6895751953125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.61138428e+02, -1.21923004e+02, 6.10351562e-05]), + 'frame': 778, + 'frame_number': 778, + 'framesequence': 776, + 'gaze_dir': array([ 0.98058069, -0.19609946, -0.00255677]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19609946, -0.00255677]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19609946, -0.00255677]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.252928979694843, + 'timestamp_carla': 16252, + 'timestamp_device': 15721, + 'timestamp_stream': 16.252928979694843, + 'transform': [array([6.16678333e+00, 3.38531072e-06, 1.82369223e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44557893, -0.64875871, 3.09596992]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.368937492370605, + 'FR_Wheel_Angle': 16.63558578491211, + 'Location': array([ 3.76992188e+01, -5.30467510e+00, 1.74973009e-03]), + 'Rotation': array([ 1.40018866e-03, -5.80203896e+01, 1.55261844e-01]), + 'Velocity': array([ 3.85816514e-01, -4.53597397e-01, -2.23684310e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 618.9026489257812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.59330933e+02, -1.21366135e+02, 3.05175781e-05]), + 'frame': 779, + 'frame_number': 779, + 'framesequence': 777, + 'gaze_dir': array([ 0.98058069, -0.19605467, -0.00490974]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19605467, -0.00490974]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19605467, -0.00490974]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.265317976474762, + 'timestamp_carla': 16265, + 'timestamp_device': 15733, + 'timestamp_stream': 16.265317976474762, + 'transform': [array([6.17857361e+00, 3.39980193e-06, 1.82762137e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42457607, -0.60401505, 3.11825323]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.367088317871094, + 'FR_Wheel_Angle': 16.632625579833984, + 'Location': array([ 3.77792397e+01, -5.38544178e+00, 1.75362104e-03]), + 'Rotation': array([ 8.19622655e-04, -5.74212189e+01, 1.43816754e-01]), + 'Velocity': array([ 3.93671304e-01, -4.52624202e-01, 3.60345839e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 616.3538208007812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.57695557e+02, -1.20838699e+02, -9.15527344e-05]), + 'frame': 780, + 'frame_number': 780, + 'framesequence': 778, + 'gaze_dir': array([ 0.98058069, -0.19596671, -0.00765392]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19596671, -0.00765392]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19596671, -0.00765392]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.278964579105377, + 'timestamp_carla': 16278, + 'timestamp_device': 15747, + 'timestamp_stream': 16.278964579105377, + 'transform': [array([6.19147682e+00, 3.41379041e-06, 1.82403566e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.44230458, -0.61801016, 3.1657939 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.370682716369629, + 'FR_Wheel_Angle': 16.729795455932617, + 'Location': array([ 3.78517876e+01, -5.45605755e+00, 1.72848220e-03]), + 'Rotation': array([ 9.97207593e-04, -5.68871574e+01, 1.49180561e-01]), + 'Velocity': array([ 0.40394703, -0.45587623, -0.00115764]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 613.4078979492188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.55538452e+02, -1.20207169e+02, -6.10351562e-05]), + 'frame': 781, + 'frame_number': 781, + 'framesequence': 779, + 'gaze_dir': array([ 0.98058069, -0.19585066, -0.01020087]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19585066, -0.01020087]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19585066, -0.01020087]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.29212737828493, + 'timestamp_carla': 16292, + 'timestamp_device': 15760, + 'timestamp_stream': 16.29212737828493, + 'transform': [array([6.20384502e+00, 3.43081501e-06, 1.82365417e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.45691627, -0.61865819, 4.45642328]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.483760833740234, + 'FR_Wheel_Angle': 24.55898094177246, + 'Location': array([ 3.79336624e+01, -5.53310490e+00, 1.74480909e-03]), + 'Rotation': array([ 4.16641531e-04, -5.62046013e+01, 1.39650792e-01]), + 'Velocity': array([ 4.39152360e-01, -4.27386612e-01, -7.59029354e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 610.6970825195312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.53759399e+02, -1.19605064e+02, 3.05175781e-05]), + 'frame': 782, + 'frame_number': 782, + 'framesequence': 780, + 'gaze_dir': array([ 0.98058069, -0.19570148, -0.0127459 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19570148, -0.0127459 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19570148, -0.0127459 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.305340480059385, + 'timestamp_carla': 16305, + 'timestamp_device': 15773, + 'timestamp_stream': 16.305340480059385, + 'transform': [array([6.21618414e+00, 3.44274531e-06, 1.82277674e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39013132, -0.50425935, 4.97947168]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.99560546875, + 'FR_Wheel_Angle': 24.11071014404297, + 'Location': array([ 3.80235367e+01, -5.60912991e+00, 1.72058574e-03]), + 'Rotation': array([ 1.27724535e-03, -5.52607841e+01, 1.29948109e-01]), + 'Velocity': array([ 4.85858798e-01, -4.46378231e-01, 2.95619946e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 608.0132446289062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.51957092e+02, -1.18988747e+02, -9.15527344e-05]), + 'frame': 783, + 'frame_number': 783, + 'framesequence': 781, + 'gaze_dir': array([ 0.98058069, -0.19551925, -0.01528897]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19551925, -0.01528897]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19551925, -0.01528897]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.317950379103422, + 'timestamp_carla': 16317, + 'timestamp_device': 15786, + 'timestamp_stream': 16.317950379103422, + 'transform': [array([6.22789049e+00, 3.45249623e-06, 1.82491296e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.42952612, -0.53093022, 5.23678541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.600244522094727, + 'FR_Wheel_Angle': 25.36480140686035, + 'Location': array([ 3.81095505e+01, -5.68106604e+00, 1.70666212e-03]), + 'Rotation': array([ 2.04222649e-03, -5.43991089e+01, 1.32599249e-01]), + 'Velocity': array([ 5.05658209e-01, -4.45603430e-01, 1.50504115e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 605.3543701171875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.50180237e+02, -1.18358070e+02, 3.05175781e-05]), + 'frame': 784, + 'frame_number': 784, + 'framesequence': 782, + 'gaze_dir': array([ 0.98058069, -0.19530401, -0.01782927]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19530401, -0.01782927]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19530401, -0.01782927]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.330446377396584, + 'timestamp_carla': 16330, + 'timestamp_device': 15799, + 'timestamp_stream': 16.330446377396584, + 'transform': [array([6.23942614e+00, 3.46288039e-06, 1.82689668e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40629697, -0.48050171, 5.24440718]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.19729995727539, + 'FR_Wheel_Angle': 24.904672622680664, + 'Location': array([ 3.82103004e+01, -5.76454782e+00, 1.71059126e-03]), + 'Rotation': array([ 1.82366045e-03, -5.33755875e+01, 1.22527264e-01]), + 'Velocity': array([ 5.23166060e-01, -4.48367715e-01, 5.54466242e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 602.722412109375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.48370422e+02, -1.17713753e+02, -6.10351562e-05]), + 'frame': 785, + 'frame_number': 785, + 'framesequence': 783, + 'gaze_dir': array([ 0.98058069, -0.19507599, -0.02017159]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19507599, -0.02017159]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19507599, -0.02017159]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.343147177249193, + 'timestamp_carla': 16343, + 'timestamp_device': 15811, + 'timestamp_stream': 16.343147177249193, + 'transform': [array([6.25203419e+00, 3.47409355e-06, 1.82582845e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40508565, -0.46180186, 5.31885052]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.233367919921875, + 'FR_Wheel_Angle': 24.910091400146484, + 'Location': array([ 3.83066483e+01, -5.84111071e+00, 1.69876567e-03]), + 'Rotation': array([ 1.77584914e-03, -5.24146919e+01, 1.20212272e-01]), + 'Velocity': array([ 0.5375669 , -0.44460982, 0.00071496]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 600.3154296875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.46798340e+02, -1.17106766e+02, 6.10351562e-05]), + 'frame': 786, + 'frame_number': 786, + 'framesequence': 784, + 'gaze_dir': array([ 0.98058069, -0.19477446, -0.02290058]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19477446, -0.02290058]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19477446, -0.02290058]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.356597777456045, + 'timestamp_carla': 16356, + 'timestamp_device': 15825, + 'timestamp_stream': 16.356597777456045, + 'transform': [array([6.26528358e+00, 3.49158381e-06, 1.82086939e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40951821, -0.45105746, 5.4055624 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.252635955810547, + 'FR_Wheel_Angle': 24.905641555786133, + 'Location': array([ 3.84046249e+01, -5.91631413e+00, 1.73206802e-03]), + 'Rotation': array([ 1.70071702e-03, -5.14514008e+01, 1.19129591e-01]), + 'Velocity': array([ 5.53234994e-01, -4.41709876e-01, 4.24919126e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 597.5349731445312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.44910645e+02, -1.16384193e+02, 3.05175781e-05]), + 'frame': 787, + 'frame_number': 787, + 'framesequence': 785, + 'gaze_dir': array([ 0.98058069, -0.19448566, -0.02523618]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19448566, -0.02523618]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19448566, -0.02523618]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.369150176644325, + 'timestamp_carla': 16369, + 'timestamp_device': 15837, + 'timestamp_stream': 16.369150176644325, + 'transform': [array([6.27756071e+00, 3.50499499e-06, 1.82163238e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4177323 , -0.44552034, 5.49176979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.252376556396484, + 'FR_Wheel_Angle': 24.899127960205078, + 'Location': array([ 3.85022583e+01, -5.98864746e+00, 1.73012249e-03]), + 'Rotation': array([ 1.70071702e-03, -5.05042839e+01, 1.20280422e-01]), + 'Velocity': array([ 5.69490671e-01, -4.39379752e-01, 5.15842439e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 595.1749877929688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.43563477e+02, -1.15752647e+02, -6.10351562e-05]), + 'frame': 788, + 'frame_number': 788, + 'framesequence': 786, + 'gaze_dir': array([ 0.98058069, -0.19411331, -0.02795641]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19411331, -0.02795641]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19411331, -0.02795641]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.38289337977767, + 'timestamp_carla': 16382, + 'timestamp_device': 15851, + 'timestamp_stream': 16.38289337977767, + 'transform': [array([6.29090548e+00, 3.51998915e-06, 1.81564328e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40670159, -0.41816717, 5.56046915]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.248186111450195, + 'FR_Wheel_Angle': 24.893861770629883, + 'Location': array([ 3.86107330e+01, -6.06752014e+00, 1.72398088e-03]), + 'Rotation': array([ 1.22260384e-03, -4.94604836e+01, 1.14735462e-01]), + 'Velocity': array([ 5.84879100e-01, -4.34228241e-01, 4.29773318e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 592.4508666992188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.41706421e+02, -1.15002235e+02, -6.10351562e-05]), + 'frame': 789, + 'frame_number': 789, + 'framesequence': 787, + 'gaze_dir': array([ 0.98058069, -0.19373348, -0.03047735]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19373348, -0.03047735]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19373348, -0.03047735]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.396230276674032, + 'timestamp_carla': 16396, + 'timestamp_device': 15864, + 'timestamp_stream': 16.396230276674032, + 'transform': [array([6.30376530e+00, 3.53604514e-06, 1.81320182e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.4089407 , -0.4057571 , 5.61837864]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.245758056640625, + 'FR_Wheel_Angle': 24.88759422302246, + 'Location': array([ 3.87172127e+01, -6.14203405e+00, 1.70105451e-03]), + 'Rotation': array([ 9.22075473e-04, -4.84484673e+01, 1.11063570e-01]), + 'Velocity': array([ 0.59873927, -0.42830077, -0.00072695]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 589.947021484375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.40206055e+02, -1.14292137e+02, -3.05175781e-05]), + 'frame': 790, + 'frame_number': 790, + 'framesequence': 788, + 'gaze_dir': array([ 0.98058069, -0.1933209 , -0.03299334]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1933209 , -0.03299334]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1933209 , -0.03299334]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.409226078540087, + 'timestamp_carla': 16409, + 'timestamp_device': 15877, + 'timestamp_stream': 16.409226078540087, + 'transform': [array([6.31621265e+00, 3.55435031e-06, 1.81304931e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.40423343, -0.38735422, 5.69210434]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.24292755126953, + 'FR_Wheel_Angle': 24.881559371948242, + 'Location': array([ 3.88250885e+01, -6.21514463e+00, 1.76121236e-03]), + 'Rotation': array([ 6.89849083e-04, -4.74341850e+01, 1.08995765e-01]), + 'Velocity': array([ 6.14389837e-01, -4.23087984e-01, 1.15585326e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 587.4699096679688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.38687073e+02, -1.13569855e+02, -3.05175781e-05]), + 'frame': 791, + 'frame_number': 791, + 'framesequence': 789, + 'gaze_dir': array([ 0.98058069, -0.19284007, -0.0356965 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19284007, -0.0356965 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19284007, -0.0356965 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.42253777757287, + 'timestamp_carla': 16422, + 'timestamp_device': 15891, + 'timestamp_stream': 16.42253777757287, + 'transform': [array([6.32887983e+00, 3.57077420e-06, 1.81118003e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3976309 , -0.3674787 , 5.75540781]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.24040985107422, + 'FR_Wheel_Angle': 24.875532150268555, + 'Location': array([ 3.89368286e+01, -6.28846502e+00, 1.74358836e-03]), + 'Rotation': array([ 3.48339614e-04, -4.63949280e+01, 1.05234616e-01]), + 'Velocity': array([ 6.29071057e-01, -4.16429579e-01, 2.28767385e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 584.83203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 636.94482422, -112.77868652, 0. ]), + 'frame': 792, + 'frame_number': 792, + 'framesequence': 790, + 'gaze_dir': array([ 0.98058069, -0.19235978, -0.03820024]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19235978, -0.03820024]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19235978, -0.03820024]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.43599097803235, + 'timestamp_carla': 16435, + 'timestamp_device': 15904, + 'timestamp_stream': 16.43599097803235, + 'transform': [array([6.34159946e+00, 3.58336570e-06, 1.80885312e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.39923084, -0.35477191, 5.94338655]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.677406311035156, + 'FR_Wheel_Angle': 26.11905860900879, + 'Location': array([ 3.90526199e+01, -6.36193514e+00, 1.72474375e-03]), + 'Rotation': array([-9.56226431e-05, -4.53275642e+01, 1.00382745e-01]), + 'Velocity': array([ 6.45165026e-01, -4.05587882e-01, 3.95727140e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 582.4094848632812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.35468384e+02, -1.12031784e+02, 3.05175781e-05]), + 'frame': 793, + 'frame_number': 793, + 'framesequence': 791, + 'gaze_dir': array([ 0.98058069, -0.1918875 , -0.04050577]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1918875 , -0.04050577]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1918875 , -0.04050577]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.448490377515554, + 'timestamp_carla': 16448, + 'timestamp_device': 15916, + 'timestamp_stream': 16.448490377515554, + 'transform': [array([6.35334539e+00, 3.60260674e-06, 1.81179040e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.41139111, -0.3446683 , 8.03344822]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 26.51471519470215, + 'FR_Wheel_Angle': 35.06813430786133, + 'Location': array([ 3.91718063e+01, -6.42889833e+00, 1.73614977e-03]), + 'Rotation': array([-1.18845282e-03, -4.40579910e+01, 8.97240788e-02]), + 'Velocity': array([ 6.89915895e-01, -3.39952946e-01, 1.88364982e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 580.1963500976562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 634.234375 , -111.3320694, 0. ]), + 'frame': 794, + 'frame_number': 794, + 'framesequence': 792, + 'gaze_dir': array([ 0.98058069, -0.19134469, -0.04299691]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19134469, -0.04299691]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19134469, -0.04299691]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.461338076740503, + 'timestamp_carla': 16461, + 'timestamp_device': 15929, + 'timestamp_stream': 16.461338076740503, + 'transform': [array([6.36534643e+00, 3.61570119e-06, 1.81243895e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.32154906, -0.25643641, 7.95983267]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 24.923025131225586, + 'FR_Wheel_Angle': 32.165626525878906, + 'Location': array([ 3.92990570e+01, -6.49277258e+00, 1.73256395e-03]), + 'Rotation': array([-5.53245307e-04, -4.25657463e+01, 8.49525928e-02]), + 'Velocity': array([ 7.35607445e-01, -3.56048912e-01, 8.27217082e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 577.8248291015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 632.72338867, -110.56335449, 0. ]), + 'frame': 795, + 'frame_number': 795, + 'framesequence': 793, + 'gaze_dir': array([ 0.98058057, -0.19076963, -0.04548059]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.19076963, -0.04548059]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.19076963, -0.04548059]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.474112879484892, + 'timestamp_carla': 16474, + 'timestamp_device': 15942, + 'timestamp_stream': 16.474112879484892, + 'transform': [array([6.37721014e+00, 3.63329855e-06, 1.81327818e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.3389042 , -0.2533811 , 8.38715744]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.748641967773438, + 'FR_Wheel_Angle': 33.19789123535156, + 'Location': array([ 3.94222374e+01, -6.55169678e+00, 1.70670031e-03]), + 'Rotation': array([-4.57622635e-04, -4.11620560e+01, 8.34062025e-02]), + 'Velocity': array([ 7.55443037e-01, -3.31167251e-01, 2.27031705e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 575.4791870117188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.31267334e+02, -1.09783585e+02, 3.05175781e-05]), + 'frame': 796, + 'frame_number': 796, + 'framesequence': 794, + 'gaze_dir': array([ 0.98058069, -0.19021012, -0.04776652]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.19021012, -0.04776652]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.19021012, -0.04776652]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.486368779093027, + 'timestamp_carla': 16486, + 'timestamp_device': 15954, + 'timestamp_stream': 16.486368779093027, + 'transform': [array([6.38852787e+00, 3.64720313e-06, 1.81625364e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.32876298, -0.23110808, 8.44958401]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.656227111816406, + 'FR_Wheel_Angle': 33.21424865722656, + 'Location': array([ 3.95576019e+01, -6.61324501e+00, 1.73748494e-03]), + 'Rotation': array([-7.30830187e-04, -3.96353874e+01, 7.89371952e-02]), + 'Velocity': array([ 7.76854157e-01, -3.19155335e-01, -1.14278788e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 573.3372192382812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.30028076e+02, -1.09054169e+02, 3.05175781e-05]), + 'frame': 797, + 'frame_number': 797, + 'framesequence': 795, + 'gaze_dir': array([ 0.98058069, -0.18957306, -0.05023524]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18957306, -0.05023524]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18957306, -0.05023524]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.499249078333378, + 'timestamp_carla': 16499, + 'timestamp_device': 15967, + 'timestamp_stream': 16.499249078333378, + 'transform': [array([6.40131283e+00, 3.66002746e-06, 1.81316375e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.32158503, -0.90325511, 4.40822649]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.68378448486328, + 'FR_Wheel_Angle': 33.14704132080078, + 'Location': array([ 3.96883774e+01, -6.67449093e+00, 5.45284757e-03]), + 'Rotation': array([ 0.21192026, -38.2796669 , 0.68503368]), + 'Velocity': array([ 0.5502674 , -0.24254735, 0.03193442]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 571.0419921875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.28560669e+02, -1.08253815e+02, 3.05175781e-05]), + 'frame': 798, + 'frame_number': 798, + 'framesequence': 796, + 'gaze_dir': array([ 0.98058069, -0.18890408, -0.05269529]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18890408, -0.05269529]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18890408, -0.05269529]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.51195927709341, + 'timestamp_carla': 16511, + 'timestamp_device': 15980, + 'timestamp_stream': 16.51195927709341, + 'transform': [array([6.41383600e+00, 3.67027201e-06, 1.81171414e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-3.10230565, 0.40585452, 7.76071644]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.608613967895508, + 'FR_Wheel_Angle': 33.08708572387695, + 'Location': array([ 3.98140144e+01, -6.74055910e+00, 2.99599525e-02]), + 'Rotation': array([ 1.18082356, -36.88280487, 2.49661684]), + 'Velocity': array([ 0.73410881, -0.23631738, 0.06049575]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 568.772216796875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.27269104e+02, -1.07443024e+02, -3.05175781e-05]), + 'frame': 799, + 'frame_number': 799, + 'framesequence': 797, + 'gaze_dir': array([ 0.98058057, -0.18814786, -0.05533468]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.18814786, -0.05533468]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.18814786, -0.05533468]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.52619417756796, + 'timestamp_carla': 16526, + 'timestamp_device': 15994, + 'timestamp_stream': 16.52619417756796, + 'transform': [array([6.42775393e+00, 3.69206964e-06, 1.80171966e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-1.3052783 , 0.14272363, 7.99024773]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.60163116455078, + 'FR_Wheel_Angle': 33.07782745361328, + 'Location': array([ 3.99419441e+01, -6.78899145e+00, 3.22899297e-02]), + 'Rotation': array([ 1.32065117, -35.51200104, 2.79024744]), + 'Velocity': array([ 0.75577623, -0.23823361, 0.02463165]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 566.3570556640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 625.78662109, -106.55851746, 0. ]), + 'frame': 800, + 'frame_number': 800, + 'framesequence': 798, + 'gaze_dir': array([ 0.98058069, -0.18729663, -0.05815064]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18729663, -0.05815064]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18729663, -0.05815064]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.540369980037212, + 'timestamp_carla': 16540, + 'timestamp_device': 16009, + 'timestamp_stream': 16.540369980037212, + 'transform': [array([6.44150877e+00, 3.70777639e-06, 1.79443357e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.4098576 , -0.04201168, 8.62397099]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.576120376586914, + 'FR_Wheel_Angle': 33.068504333496094, + 'Location': array([ 4.00955925e+01, -6.84298372e+00, 3.46249081e-02]), + 'Rotation': array([ 1.40276372, -33.84770584, 2.97332978]), + 'Velocity': array([ 0.8212657 , -0.24007791, 0.01496662]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 563.80126953125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.24284973e+02, -1.05597702e+02, 3.05175781e-05]), + 'frame': 801, + 'frame_number': 801, + 'framesequence': 799, + 'gaze_dir': array([ 0.98058069, -0.18658541, -0.06039379]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18658541, -0.06039379]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18658541, -0.06039379]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.55343207716942, + 'timestamp_carla': 16553, + 'timestamp_device': 16021, + 'timestamp_stream': 16.55343207716942, + 'transform': [array([6.45409489e+00, 3.72419572e-06, 1.79531088e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.01500782, -0.1039165 , 8.77537918]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.57120704650879, + 'FR_Wheel_Angle': 33.06223678588867, + 'Location': array([ 4.02429657e+01, -6.89018679e+00, 3.56733762e-02]), + 'Rotation': array([ 1.43112266, -32.26259232, 3.03784823]), + 'Velocity': array([ 0.84114075, -0.22416042, 0.00800123]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 561.7820434570312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.23374390e+02, -1.04819969e+02, -3.05175781e-05]), + 'frame': 802, + 'frame_number': 802, + 'framesequence': 800, + 'gaze_dir': array([ 0.98058069, -0.18572164, -0.06299997]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18572164, -0.06299997]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18572164, -0.06299997]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.566622979938984, + 'timestamp_carla': 16566, + 'timestamp_device': 16035, + 'timestamp_stream': 16.566622979938984, + 'transform': [array([6.46671963e+00, 3.73818398e-06, 1.79553987e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.12969352, -0.11785768, 8.88629913]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.567142486572266, + 'FR_Wheel_Angle': 33.05519104003906, + 'Location': array([ 4.03884659e+01, -6.93266964e+00, 3.62473354e-02]), + 'Rotation': array([ 1.44110155, -30.71113205, 3.06125474]), + 'Velocity': array([ 0.8573885 , -0.20500875, 0.00431243]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 559.4557495117188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.21998657e+02, -1.03902664e+02, -3.05175781e-05]), + 'frame': 803, + 'frame_number': 803, + 'framesequence': 801, + 'gaze_dir': array([ 0.98058069, -0.18495221, -0.06522424]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18495221, -0.06522424]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18495221, -0.06522424]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.579192377626896, + 'timestamp_carla': 16579, + 'timestamp_device': 16047, + 'timestamp_stream': 16.579192377626896, + 'transform': [array([6.47867537e+00, 3.75858463e-06, 1.79889670e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.18282034, -0.11768822, 9.0175581 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.564552307128906, + 'FR_Wheel_Angle': 33.0480842590332, + 'Location': array([ 4.05229645e+01, -6.96826601e+00, 3.65177207e-02]), + 'Rotation': array([ 1.44453716, -29.28783989, 3.07103896]), + 'Velocity': array([ 0.87502652, -0.18681945, 0.0025483 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 557.4854125976562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 621.0300293 , -103.10778809, 0. ]), + 'frame': 804, + 'frame_number': 804, + 'framesequence': 802, + 'gaze_dir': array([ 0.98058069, -0.18415628, -0.06743876]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18415628, -0.06743876]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18415628, -0.06743876]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.59146587923169, + 'timestamp_carla': 16591, + 'timestamp_device': 16059, + 'timestamp_stream': 16.59146587923169, + 'transform': [array([6.49028111e+00, 3.76983508e-06, 1.80301664e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.22498375, -0.12205741, 9.58324432]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.448694229125977, + 'FR_Wheel_Angle': 36.96122360229492, + 'Location': array([ 4.06740456e+01, -7.00427580e+00, 3.67029235e-02]), + 'Rotation': array([ 1.44588268, -27.68284798, 3.06861496]), + 'Velocity': array([ 0.88456398, -0.14705157, 0.00132512]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 555.5380859375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.20020264e+02, -1.02305450e+02, -3.05175781e-05]), + 'frame': 805, + 'frame_number': 805, + 'framesequence': 803, + 'gaze_dir': array([ 0.98058069, -0.18319412, -0.07001024]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18319412, -0.07001024]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18319412, -0.07001024]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.604980379343033, + 'timestamp_carla': 16604, + 'timestamp_device': 16073, + 'timestamp_stream': 16.604980379343033, + 'transform': [array([6.50297976e+00, 3.78431241e-06, 1.80019380e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.14721988, -0.07220543, 11.29213047]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.196552276611328, + 'FR_Wheel_Angle': 40.24680709838867, + 'Location': array([ 4.08263741e+01, -7.02912140e+00, 3.68099287e-02]), + 'Rotation': array([ 1.44587588, -25.80152702, 3.05578232]), + 'Velocity': array([ 8.98532629e-01, -6.44123852e-02, 6.07514346e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 553.2938232421875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 618.63922119, -101.35977936, 0. ]), + 'frame': 806, + 'frame_number': 806, + 'framesequence': 804, + 'gaze_dir': array([ 0.98058069, -0.18234076, -0.07220367]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18234076, -0.07220367]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18234076, -0.07220367]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.617249879986048, + 'timestamp_carla': 16617, + 'timestamp_device': 16085, + 'timestamp_stream': 16.617249879986048, + 'transform': [array([6.51444006e+00, 3.79971652e-06, 1.80423737e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.10172212, -0.04651268, 11.41341782]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60474395751953, + 'FR_Wheel_Angle': 41.31108474731445, + 'Location': array([ 4.09927979e+01, -7.04912329e+00, 3.68861072e-02]), + 'Rotation': array([ 1.44555485, -23.68494606, 3.04554057]), + 'Velocity': array([ 9.07142818e-01, -2.99678054e-02, 3.62677558e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 551.3927001953125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 617.75646973, -100.54097748, 0. ]), + 'frame': 807, + 'frame_number': 807, + 'framesequence': 805, + 'gaze_dir': array([ 0.98058069, -0.18138669, -0.07456802]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.18138669, -0.07456802]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.18138669, -0.07456802]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.629567477852106, + 'timestamp_carla': 16629, + 'timestamp_device': 16098, + 'timestamp_stream': 16.629567477852106, + 'transform': [array([6.52588177e+00, 3.81354675e-06, 1.80732727e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.0532957 , -0.02718234, 11.44865608]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.603416442871094, + 'FR_Wheel_Angle': 41.30448532104492, + 'Location': array([ 4.11498909e+01, -7.06195927e+00, 3.67597640e-02]), + 'Rotation': array([ 1.43970823, -21.66975594, 3.0264194 ]), + 'Velocity': array([9.10939455e-01, 2.20375066e-03, 3.78913857e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 549.359130859375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.16599609e+02, -9.96460571e+01, 3.05175781e-05]), + 'frame': 808, + 'frame_number': 808, + 'framesequence': 806, + 'gaze_dir': array([ 0.98058069, -0.1804789 , -0.07673908]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1804789 , -0.07673908]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1804789 , -0.07673908]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.64241447672248, + 'timestamp_carla': 16642, + 'timestamp_device': 16110, + 'timestamp_stream': 16.64241447672248, + 'transform': [array([6.53774595e+00, 3.82704138e-06, 1.80732727e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.02128459, -0.01654417, 11.55407619]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.602336883544922, + 'FR_Wheel_Angle': 41.299095153808594, + 'Location': array([ 4.12906418e+01, -7.06909037e+00, 3.68031375e-02]), + 'Rotation': array([ 1.44015217, -19.87151909, 3.02160859]), + 'Velocity': array([9.19059575e-01, 3.12565118e-02, 4.65764984e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 547.5050659179688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([615.644104 , -98.81273651, 0. ]), + 'frame': 809, + 'frame_number': 809, + 'framesequence': 807, + 'gaze_dir': array([ 0.98058069, -0.17946604, -0.07907884]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17946604, -0.07907884]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17946604, -0.07907884]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.655613977462053, + 'timestamp_carla': 16655, + 'timestamp_device': 16123, + 'timestamp_stream': 16.655613977462053, + 'transform': [array([6.55084562e+00, 3.83220595e-06, 1.80561061e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-1.20006418e-02, -5.76828932e-03, 1.15336170e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.603179931640625, + 'FR_Wheel_Angle': 41.29388427734375, + 'Location': array([ 4.14476509e+01, -7.07218790e+00, 3.68108824e-02]), + 'Rotation': array([ 1.44078052, -17.86963844, 3.01617122]), + 'Velocity': array([9.15910840e-01, 6.34813383e-02, 6.70003865e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 545.5202026367188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([614.58288574, -97.90196991, 0. ]), + 'frame': 810, + 'frame_number': 810, + 'framesequence': 808, + 'gaze_dir': array([ 0.98058069, -0.17834139, -0.08158352]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17834139, -0.08158352]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17834139, -0.08158352]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.66838337853551, + 'timestamp_carla': 16668, + 'timestamp_device': 16137, + 'timestamp_stream': 16.66838337853551, + 'transform': [array([6.56342506e+00, 3.84645500e-06, 1.80660246e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-4.60072309e-02, 1.77290617e-03, 1.14355631e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.603750228881836, + 'FR_Wheel_Angle': 41.289520263671875, + 'Location': array([ 4.16194992e+01, -7.06963587e+00, 3.68638299e-02]), + 'Rotation': array([ 1.44159329, -15.68110752, 3.01166654]), + 'Velocity': array([9.05051887e-01, 9.79029313e-02, 3.62491592e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 543.4110717773438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.13504639e+02, -9.69123077e+01, -3.05175781e-05]), + 'frame': 811, + 'frame_number': 811, + 'framesequence': 809, + 'gaze_dir': array([ 0.98058069, -0.17734964, -0.08371754]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17734964, -0.08371754]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17734964, -0.08371754]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.68162827938795, + 'timestamp_carla': 16681, + 'timestamp_device': 16149, + 'timestamp_stream': 16.68162827938795, + 'transform': [array([6.57637691e+00, 3.86286956e-06, 1.80507661e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-7.93736205e-02, 7.04212906e-03, 1.14066381e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.60470962524414, + 'FR_Wheel_Angle': 41.286888122558594, + 'Location': array([ 4.17747345e+01, -7.06216717e+00, 3.68902273e-02]), + 'Rotation': array([ 1.44230366, -13.7069273 , 3.00718474]), + 'Velocity': array([ 8.98936391e-01, 1.28970265e-01, -7.13157642e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 541.6273193359375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([612.74261475, -96.05701447, 0. ]), + 'frame': 812, + 'frame_number': 812, + 'framesequence': 810, + 'gaze_dir': array([ 0.98058069, -0.17624632, -0.08601604]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17624632, -0.08601604]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17624632, -0.08601604]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.69417867809534, + 'timestamp_carla': 16694, + 'timestamp_device': 16162, + 'timestamp_stream': 16.69417867809534, + 'transform': [array([6.58856630e+00, 3.87622003e-06, 1.80744170e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-1.14587501e-01, 1.09070847e-02, 1.14113426e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.604446411132812, + 'FR_Wheel_Angle': 41.28514862060547, + 'Location': array([ 4.19195099e+01, -7.05081606e+00, 3.68981995e-02]), + 'Rotation': array([ 1.44295251, -11.86619759, 3.00183821]), + 'Velocity': array([ 8.94829035e-01, 1.58096224e-01, -1.31483073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 539.7186889648438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([611.87658691, -95.12303925, 0. ]), + 'frame': 813, + 'frame_number': 813, + 'framesequence': 811, + 'gaze_dir': array([ 0.98058069, -0.17502485, -0.08847497]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17502485, -0.08847497]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17502485, -0.08847497]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.7073768787086, + 'timestamp_carla': 16707, + 'timestamp_device': 16176, + 'timestamp_stream': 16.7073768787086, + 'transform': [array([6.60129738e+00, 3.89251818e-06, 1.80622097e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-1.48128524e-01, 1.11303367e-02, 1.13313713e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.609724044799805, + 'FR_Wheel_Angle': 41.275550842285156, + 'Location': array([ 4.20684662e+01, -7.03451872e+00, 3.69351245e-02]), + 'Rotation': array([ 1.44386089, -9.96803093, 2.99804568]), + 'Velocity': array([8.82976353e-01, 1.86643615e-01, 6.37173653e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 537.6923217773438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.10800781e+02, -9.41091461e+01, -3.05175781e-05]), + 'frame': 814, + 'frame_number': 814, + 'framesequence': 812, + 'gaze_dir': array([ 0.98058069, -0.1737691 , -0.09091655]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1737691 , -0.09091655]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1737691 , -0.09091655]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 5.4933319916017354e-05, + 'throttle_input': 0.0, + 'timestamp': 16.721290577203035, + 'timestamp_carla': 16721, + 'timestamp_device': 16190, + 'timestamp_stream': 16.721290577203035, + 'transform': [array([6.61462450e+00, 3.90857895e-06, 1.80110929e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.69671309, -0.13421583, 11.03085804]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.61772918701172, + 'FR_Wheel_Angle': 41.28280258178711, + 'Location': array([ 4.22227325e+01, -7.01380348e+00, 3.56751308e-02]), + 'Rotation': array([ 1.39486802, -8.03174782, 2.89015651]), + 'Velocity': array([0.85221404, 0.21503545, 0.0050781 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 535.6946411132812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([609.81188965, -93.08679199, 0. ]), + 'frame': 815, + 'frame_number': 815, + 'framesequence': 813, + 'gaze_dir': array([ 0.98058069, -0.17257249, -0.09316789]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17257249, -0.09316789]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17257249, -0.09316789]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00043946655932813883, + 'throttle_input': 0.0, + 'timestamp': 16.73456097766757, + 'timestamp_carla': 16734, + 'timestamp_device': 16203, + 'timestamp_stream': 16.73456097766757, + 'transform': [array([6.62725258e+00, 3.92274887e-06, 1.80084223e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([-0.43162018, -0.07894213, 11.09948921]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.615449905395508, + 'FR_Wheel_Angle': 41.27977752685547, + 'Location': array([ 4.23749504e+01, -6.98744726e+00, 3.62633206e-02]), + 'Rotation': array([ 1.42403972, -6.08081484, 2.94639635]), + 'Velocity': array([0.84957355, 0.24354042, 0.00480183]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 533.864990234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([609.07312012, -92.13002777, 0. ]), + 'frame': 816, + 'frame_number': 816, + 'framesequence': 814, + 'gaze_dir': array([ 0.98058069, -0.17134671, -0.09540347]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17134671, -0.09540347]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17134671, -0.09540347]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0022339550778269768, + 'throttle_input': 0.0, + 'timestamp': 16.748305078595877, + 'timestamp_carla': 16748, + 'timestamp_device': 16216, + 'timestamp_stream': 16.748305078595877, + 'transform': [array([6.64024544e+00, 3.94070003e-06, 1.79801940e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 8.93182564, 4.20730448, 10.52762222]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.611129760742188, + 'FR_Wheel_Angle': 41.275672912597656, + 'Location': array([ 4.25215416e+01, -6.95844030e+00, 1.79105829e-02]), + 'Rotation': array([ 0.58605069, -4.25329781, 1.1013298 ]), + 'Velocity': array([ 0.84162122, 0.17193142, -0.16107309]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 532.0613403320312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([608.29345703, -91.16656494, 0. ]), + 'frame': 817, + 'frame_number': 817, + 'framesequence': 815, + 'gaze_dir': array([ 0.98058069, -0.17009217, -0.09762262]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.17009217, -0.09762262]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.17009217, -0.09762262]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.007141331676393747, + 'throttle_input': 0.0, + 'timestamp': 16.761555679142475, + 'timestamp_carla': 16761, + 'timestamp_device': 16229, + 'timestamp_stream': 16.761555679142475, + 'transform': [array([6.65269232e+00, 3.95979714e-06, 1.79855339e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 2.24674201, 1.12219048, 10.82099342]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.61853790283203, + 'FR_Wheel_Angle': 41.27914810180664, + 'Location': array([ 4.26630325e+01, -6.92543364e+00, 1.12390202e-02]), + 'Rotation': array([ 0.18407358, -2.41912842, 0.38262787]), + 'Velocity': array([ 0.82402092, 0.2710149 , -0.06044777]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 530.2825317382812, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.07578613e+02, -9.01965179e+01, -3.05175781e-05]), + 'frame': 818, + 'frame_number': 818, + 'framesequence': 816, + 'gaze_dir': array([ 0.98058069, -0.16880867, -0.09982559]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16880867, -0.09982559]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16880867, -0.09982559]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.012817774899303913, + 'throttle_input': 0.0, + 'timestamp': 16.77423157915473, + 'timestamp_carla': 16774, + 'timestamp_device': 16242, + 'timestamp_stream': 16.77423157915473, + 'transform': [array([6.66452789e+00, 3.97651411e-06, 1.80198660e-03]), + array([-8.24403763e-03, 7.73578722e-06, 1.21980008e-06])]} +{'AngularVelocity': array([ 0.76094794, 0.436021 , 10.8203764 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.62390899658203, + 'FR_Wheel_Angle': 41.28249740600586, + 'Location': array([ 4.27943497e+01, -6.89097643e+00, 7.37690693e-03]), + 'Rotation': array([ 0.06221619, -0.70556641, 0.12735045]), + 'Velocity': array([ 0.80932307, 0.30741444, -0.0340983 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 528.5288696289062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.06837524e+02, -8.92198715e+01, 3.05175781e-05]), + 'frame': 819, + 'frame_number': 819, + 'framesequence': 817, + 'gaze_dir': array([ 0.98058069, -0.16749667, -0.10201169]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16749667, -0.10201169]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16749667, -0.10201169]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.021112704649567604, + 'throttle_input': 0.0, + 'timestamp': 16.7876364775002, + 'timestamp_carla': 16787, + 'timestamp_device': 16255, + 'timestamp_stream': 16.7876364775002, + 'transform': [array([ 6.67696762e+00, -6.68234934e-05, 1.80103292e-03]), + array([-0.00820989, -0.003479 , 0.00052714])]} +{'AngularVelocity': array([ 0.08919409, 0.13465989, 10.69850349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.626665115356445, + 'FR_Wheel_Angle': 41.28692626953125, + 'Location': array([ 4.29374046e+01, -6.84857273e+00, 4.75323433e-03]), + 'Rotation': array([0.01095562, 1.17949533, 0.00991364]), + 'Velocity': array([ 0.7870568 , 0.33533919, -0.01724659]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 526.80078125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.06064087e+02, -8.82369919e+01, -3.05175781e-05]), + 'frame': 820, + 'frame_number': 820, + 'framesequence': 818, + 'gaze_dir': array([ 0.98058069, -0.16615634, -0.10418054]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16615634, -0.10418054]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16615634, -0.10418054]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.02924283593893051, + 'throttle_input': 0.0, + 'timestamp': 16.800440777093172, + 'timestamp_carla': 16800, + 'timestamp_device': 16268, + 'timestamp_stream': 16.800440777093172, + 'transform': [array([ 6.68877745e+00, -2.08999671e-04, 1.80335995e-03]), + array([-0.00818257, -0.01000976, 0.00132092])]} +{'AngularVelocity': array([-0.17986648, 0.01611177, 10.59727192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.632863998413086, + 'FR_Wheel_Angle': 41.288875579833984, + 'Location': array([ 4.30633392e+01, -6.80782413e+00, 3.53642227e-03]), + 'Rotation': array([-0.00720585, 2.84756136, -0.03909302]), + 'Velocity': array([ 0.76855212, 0.35679629, -0.01016921]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 525.097900390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([605.3739624 , -87.25124359, 0. ]), + 'frame': 821, + 'frame_number': 821, + 'framesequence': 819, + 'gaze_dir': array([ 0.98058069, -0.16468158, -0.10649644]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16468158, -0.10649644]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16468158, -0.10649644]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.03966185823082924, + 'throttle_input': 0.0, + 'timestamp': 16.81380197778344, + 'timestamp_carla': 16813, + 'timestamp_device': 16282, + 'timestamp_stream': 16.81380197778344, + 'transform': [array([ 6.70202971e+00, -3.50788381e-04, 1.80053711e-03]), + array([-0.00820989, -0.02020264, 0.00298105])]} +{'AngularVelocity': array([-0.30270001, -0.04673273, 10.43925381]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.638341903686523, + 'FR_Wheel_Angle': 41.293399810791016, + 'Location': array([ 4.31996002e+01, -6.75905037e+00, 2.73342850e-03]), + 'Rotation': array([-0.01498543, 4.67308044, -0.06167603]), + 'Velocity': array([ 0.74484885, 0.37640795, -0.00544238]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 523.2927856445312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.04500366e+02, -8.61863403e+01, -3.05175781e-05]), + 'frame': 822, + 'frame_number': 822, + 'framesequence': 820, + 'gaze_dir': array([ 0.98058069, -0.16328341, -0.108628 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16328341, -0.108628 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16328341, -0.108628 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.050227366387844086, + 'throttle_input': 0.0, + 'timestamp': 16.82681107893586, + 'timestamp_carla': 16826, + 'timestamp_device': 16295, + 'timestamp_stream': 16.82681107893586, + 'transform': [array([ 6.71482897e+00, -6.21122832e-04, 1.80049893e-03]), + array([-0.00827136, -0.03320312, 0.00469953])]} +{'AngularVelocity': array([-0.35873914, -0.08214147, 10.26420784]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.642047882080078, + 'FR_Wheel_Angle': 41.29891586303711, + 'Location': array([ 4.33350830e+01, -6.70597601e+00, 2.29069474e-03]), + 'Rotation': array([-0.01803853, 6.50768089, -0.07226562]), + 'Velocity': array([ 0.71967655, 0.39385787, -0.0024014 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 521.6439208984375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([603.94226074, -85.18753052, 0. ]), + 'frame': 823, + 'frame_number': 823, + 'framesequence': 821, + 'gaze_dir': array([ 0.98058069, -0.16185743, -0.11074153]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.16185743, -0.11074153]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.16185743, -0.11074153]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.059694208204746246, + 'throttle_input': 0.0, + 'timestamp': 16.839629277586937, + 'timestamp_carla': 16839, + 'timestamp_device': 16308, + 'timestamp_stream': 16.839629277586937, + 'transform': [array([ 6.72734499e+00, -9.73006885e-04, 1.80183409e-03]), + array([-0.00833283, -0.04867553, 0.00619848])]} +{'AngularVelocity': array([-0.40620345, -0.109543 , 10.12147808]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.646934509277344, + 'FR_Wheel_Angle': 41.3011474609375, + 'Location': array([ 4.34550972e+01, -6.65571499e+00, 2.09500059e-03]), + 'Rotation': array([-0.01983487, 8.14401531, -0.08215333]), + 'Velocity': array([ 0.6979695 , 0.40889966, -0.00120521]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 520.0199584960938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.03362976e+02, -8.41917572e+01, -6.10351562e-05]), + 'frame': 824, + 'frame_number': 824, + 'framesequence': 822, + 'gaze_dir': array([ 0.98058069, -0.1604041 , -0.11283634]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1604041 , -0.11283634]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1604041 , -0.11283634]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.07110202312469482, + 'throttle_input': 0.0, + 'timestamp': 16.853342976421118, + 'timestamp_carla': 16853, + 'timestamp_device': 16321, + 'timestamp_stream': 16.853342976421118, + 'transform': [array([ 6.74062920e+00, -1.43569813e-03, 1.79798121e-03]), + array([-0.0083943 , -0.06838988, 0.00759935])]} +{'AngularVelocity': array([-0.43407282, -0.13239574, 9.95335007]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.654939651489258, + 'FR_Wheel_Angle': 41.30691909790039, + 'Location': array([ 4.35740089e+01, -6.60236263e+00, 1.95839629e-03]), + 'Rotation': array([-0.02072279, 9.78224754, -0.08779906]), + 'Velocity': array([ 6.74266696e-01, 4.21856552e-01, -4.59351519e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 518.4199829101562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.02779602e+02, -8.31946030e+01, -3.05175781e-05]), + 'frame': 825, + 'frame_number': 825, + 'framesequence': 823, + 'gaze_dir': array([ 0.98058069, -0.15892366, -0.11491208]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15892366, -0.11491208]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15892366, -0.11491208]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.08086184412240982, + 'throttle_input': 0.0, + 'timestamp': 16.866078078746796, + 'timestamp_carla': 16866, + 'timestamp_device': 16334, + 'timestamp_stream': 16.866078078746796, + 'transform': [array([ 6.75287580e+00, -1.93408947e-03, 1.80038449e-03]), + array([-0.00842162, -0.08926391, 0.00869536])]} +{'AngularVelocity': array([-0.43436232, -0.14823414, 9.74296093]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.659719467163086, + 'FR_Wheel_Angle': 41.31333923339844, + 'Location': array([ 4.37035065e+01, -6.53914309e+00, 1.90296886e-03]), + 'Rotation': array([-0.02069547, 11.59609509, -0.08792114]), + 'Velocity': array([ 6.46305740e-01, 4.33714598e-01, -2.36005784e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 516.843017578125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([602.29406738, -82.19656372, 0. ]), + 'frame': 826, + 'frame_number': 826, + 'framesequence': 824, + 'gaze_dir': array([ 0.98058069, -0.15741657, -0.1169681 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15741657, -0.1169681 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15741657, -0.1169681 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.09250771254301071, + 'throttle_input': 0.0, + 'timestamp': 16.879446379840374, + 'timestamp_carla': 16879, + 'timestamp_device': 16347, + 'timestamp_stream': 16.879446379840374, + 'transform': [array([ 6.76563692e+00, -2.53428612e-03, 1.79924013e-03]), + array([-0.00845577, -0.11413573, 0.00971918])]} +{'AngularVelocity': array([-0.45493689, -0.17107034, 9.53736687]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.66624641418457, + 'FR_Wheel_Angle': 41.32035446166992, + 'Location': array([ 4.38215942e+01, -6.47797203e+00, 1.84017897e-03]), + 'Rotation': array([-0.02108479, 13.26658821, -0.09091185]), + 'Velocity': array([ 0.62036592, 0.44335055, -0.00071963]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 515.2906494140625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([601.73162842, -81.19421387, 0. ]), + 'frame': 827, + 'frame_number': 827, + 'framesequence': 825, + 'gaze_dir': array([ 0.98058069, -0.15588267, -0.11900465]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15588267, -0.11900465]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15588267, -0.11900465]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1025421991944313, + 'throttle_input': 0.0, + 'timestamp': 16.891983777284622, + 'timestamp_carla': 16891, + 'timestamp_device': 16360, + 'timestamp_stream': 16.891983777284622, + 'transform': [array([ 6.77752066e+00, -3.16320313e-03, 1.80278777e-03]), + array([-0.00848309, -0.1399536 , 0.01055265])]} +{'AngularVelocity': array([-0.4703877 , -0.19113608, 9.3787775 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.67209243774414, + 'FR_Wheel_Angle': 41.32655334472656, + 'Location': array([ 4.39327888e+01, -6.41706896e+00, 1.87824958e-03]), + 'Rotation': array([-0.0217883 , 14.8559761 , -0.09707641]), + 'Velocity': array([5.96772850e-01, 4.52612340e-01, 1.40171047e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 513.761474609375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.01242371e+02, -8.01901016e+01, -3.05175781e-05]), + 'frame': 828, + 'frame_number': 828, + 'framesequence': 826, + 'gaze_dir': array([ 0.98058069, -0.15432242, -0.12102109]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15432242, -0.12102109]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15432242, -0.12102109]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.11422467976808548, + 'throttle_input': 0.0, + 'timestamp': 16.90562227740884, + 'timestamp_carla': 16905, + 'timestamp_device': 16373, + 'timestamp_stream': 16.90562227740884, + 'transform': [array([ 6.79035330e+00, -3.92616075e-03, 1.79996481e-03]), + array([-0.00851042, -0.17108151, 0.01137989])]} +{'AngularVelocity': array([-0.48950288, -0.21472651, 9.19025993]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.680519104003906, + 'FR_Wheel_Angle': 41.33406066894531, + 'Location': array([ 4.40410652e+01, -6.35437679e+00, 1.84551952e-03]), + 'Rotation': array([-0.02234155, 16.422966 , -0.10144042]), + 'Velocity': array([ 5.72102785e-01, 4.59567219e-01, -2.79140455e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 512.256591796875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.00692383e+02, -7.91810455e+01, -3.05175781e-05]), + 'frame': 829, + 'frame_number': 829, + 'framesequence': 827, + 'gaze_dir': array([ 0.98058069, -0.15273608, -0.12301707]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15273608, -0.12301707]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15273608, -0.12301707]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.12620015442371368, + 'throttle_input': 0.0, + 'timestamp': 16.918574776500463, + 'timestamp_carla': 16918, + 'timestamp_device': 16386, + 'timestamp_stream': 16.918574776500463, + 'transform': [array([ 6.80245209e+00, -4.72530117e-03, 1.80149078e-03]), + array([-0.00854457, -0.20349118, 0.01210492])]} +{'AngularVelocity': array([-0.49923062, -0.23132339, 9.02906704]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.685976028442383, + 'FR_Wheel_Angle': 41.342708587646484, + 'Location': array([ 4.41462822e+01, -6.29016638e+00, 1.81935064e-03]), + 'Rotation': array([-0.02325679, 17.96391296, -0.11007689]), + 'Velocity': array([5.49584925e-01, 4.66538876e-01, 2.79550557e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 510.7745666503906, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.00257324e+02, -7.81714859e+01, -3.05175781e-05]), + 'frame': 830, + 'frame_number': 830, + 'framesequence': 828, + 'gaze_dir': array([ 0.98058069, -0.15099895, -0.12514324]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.15099895, -0.12514324]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.15099895, -0.12514324]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.13616138696670532, + 'throttle_input': 0.0, + 'timestamp': 16.932179879397154, + 'timestamp_carla': 16932, + 'timestamp_device': 16400, + 'timestamp_stream': 16.932179879397154, + 'transform': [array([ 6.81506872e+00, -5.63868042e-03, 1.79927819e-03]), + array([-0.00854457, -0.24023436, 0.01276218])]} +{'AngularVelocity': array([-0.51764685, -0.25824237, 8.81103802]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.69293212890625, + 'FR_Wheel_Angle': 41.34889221191406, + 'Location': array([ 4.42508812e+01, -6.22251034e+00, 1.82266941e-03]), + 'Rotation': array([-0.02362562, 19.52159691, -0.11346434]), + 'Velocity': array([5.23984075e-01, 4.70265567e-01, 4.86059173e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 509.20556640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([599.64990234, -77.07631683, 0. ]), + 'frame': 831, + 'frame_number': 831, + 'framesequence': 829, + 'gaze_dir': array([ 0.98058069, -0.14935955, -0.12709539]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14935955, -0.12709539]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14935955, -0.12709539]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.1480269879102707, + 'throttle_input': 0.0, + 'timestamp': 16.94501967728138, + 'timestamp_carla': 16945, + 'timestamp_device': 16413, + 'timestamp_stream': 16.94501967728138, + 'transform': [array([ 6.82689095e+00, -6.57016924e-03, 1.80168147e-03]), + array([-0.00854457, -0.27749634, 0.01332589])]} +{'AngularVelocity': array([-0.50350457, -0.27327788, 8.54792404]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.699792861938477, + 'FR_Wheel_Angle': 41.35905456542969, + 'Location': array([ 4.43602982e+01, -6.14706469e+00, 1.81870221e-03]), + 'Rotation': array([-0.0226694 , 21.1858139 , -0.10714722]), + 'Velocity': array([4.94487852e-01, 4.70889896e-01, 3.01017746e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 507.7726745605469, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([599.24414062, -76.06036377, 0. ]), + 'frame': 832, + 'frame_number': 832, + 'framesequence': 830, + 'gaze_dir': array([ 0.98058069, -0.14782354, -0.12887865]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14782354, -0.12887865]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14782354, -0.12887865]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.15826289355754852, + 'throttle_input': 0.0, + 'timestamp': 16.95756707713008, + 'timestamp_carla': 16957, + 'timestamp_device': 16425, + 'timestamp_stream': 16.95756707713008, + 'transform': [array([ 6.83836460e+00, -7.54454639e-03, 1.80526730e-03]), + array([-0.00854457, -0.31625366, 0.0138156 ])]} +{'AngularVelocity': array([-0.51593125, -0.29667261, 8.36465359]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.706289291381836, + 'FR_Wheel_Angle': 41.36670684814453, + 'Location': array([ 4.44552956e+01, -6.07937050e+00, 1.82907819e-03]), + 'Rotation': array([-0.02327728, 22.63889694, -0.11206056]), + 'Velocity': array([4.71124798e-01, 4.72728252e-01, 6.44016254e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 506.4715576171875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.98908203e+02, -7.51205902e+01, -3.05175781e-05]), + 'frame': 833, + 'frame_number': 833, + 'framesequence': 831, + 'gaze_dir': array([ 0.98058069, -0.14613561, -0.13078949]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14613561, -0.13078949]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14613561, -0.13078949]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.17000031471252441, + 'throttle_input': 0.0, + 'timestamp': 16.970028679817915, + 'timestamp_carla': 16970, + 'timestamp_device': 16438, + 'timestamp_stream': 16.970028679817915, + 'transform': [array([ 6.85064983e+00, -8.02382268e-03, 1.80644984e-03]), + array([-0.00870166, -0.35858154, 0.01810798])]} +{'AngularVelocity': array([-0.53060651, -0.32187602, 8.17469311]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.7127742767334, + 'FR_Wheel_Angle': 41.37129211425781, + 'Location': array([ 4.45454102e+01, -6.01258612e+00, 1.85158488e-03]), + 'Rotation': array([-2.39261519e-02, 2.40327034e+01, -1.17797822e-01]), + 'Velocity': array([4.48648989e-01, 4.73197997e-01, 2.36835476e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 505.0843200683594, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.98439819e+02, -7.40950623e+01, 3.05175781e-05]), + 'frame': 834, + 'frame_number': 834, + 'framesequence': 832, + 'gaze_dir': array([ 0.98058069, -0.14442325, -0.13267796]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14442325, -0.13267796]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14442325, -0.13267796]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.18029116094112396, + 'throttle_input': 0.0, + 'timestamp': 16.98308937996626, + 'timestamp_carla': 16983, + 'timestamp_device': 16451, + 'timestamp_stream': 16.98308937996626, + 'transform': [array([ 6.86335993e+00, -9.02253296e-03, 1.80522911e-03]), + array([-0.0089134 , -0.40661618, 0.02316278])]} +{'AngularVelocity': array([-0.53786111, -0.34494549, 7.96874094]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.721498489379883, + 'FR_Wheel_Angle': 41.38058090209961, + 'Location': array([ 4.46335182e+01, -5.94447565e+00, 1.83483830e-03]), + 'Rotation': array([-2.41652075e-02, 2.54153500e+01, -1.20117180e-01]), + 'Velocity': array([ 4.25693959e-01, 4.71835554e-01, -1.08900065e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 503.7291259765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([598.08300781, -73.00969696, 0. ]), + 'frame': 835, + 'frame_number': 835, + 'framesequence': 833, + 'gaze_dir': array([ 0.98058069, -0.1426862 , -0.13454425]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1426862 , -0.13454425]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1426862 , -0.13454425]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.19039888679981232, + 'throttle_input': 0.0, + 'timestamp': 16.996159579604864, + 'timestamp_carla': 16996, + 'timestamp_device': 16464, + 'timestamp_stream': 16.996159579604864, + 'transform': [array([ 6.87594795e+00, -1.02400826e-02, 1.80435181e-03]), + array([-0.00909781, -0.45748904, 0.02700265])]} +{'AngularVelocity': array([-0.51518446, -0.34982735, 7.69336176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.727848052978516, + 'FR_Wheel_Angle': 41.39500045776367, + 'Location': array([ 4.47276001e+01, -5.86717415e+00, 1.78311102e-03]), + 'Rotation': array([-2.33387556e-02, 2.69299107e+01, -1.15051247e-01]), + 'Velocity': array([ 4.00391221e-01, 4.67501819e-01, -1.91783896e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 502.3979187011719, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([597.7901001 , -71.96099091, 0. ]), + 'frame': 836, + 'frame_number': 836, + 'framesequence': 834, + 'gaze_dir': array([ 0.98058069, -0.14092506, -0.13638784]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.14092506, -0.13638784]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.14092506, -0.13638784]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.20228278636932373, + 'throttle_input': 0.0, + 'timestamp': 17.008604377508163, + 'timestamp_carla': 17008, + 'timestamp_device': 16477, + 'timestamp_stream': 17.008604377508163, + 'transform': [array([ 6.88782644e+00, -1.15143368e-02, 1.80713646e-03]), + array([-0.00924808, -0.50848383, 0.02944898])]} +{'AngularVelocity': array([-0.52284485, -0.3718164 , 7.54817057]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.734012603759766, + 'FR_Wheel_Angle': 41.4354133605957, + 'Location': array([ 4.48074150e+01, -5.80014133e+00, 1.85604801e-03]), + 'Rotation': array([-2.43564527e-02, 2.82184143e+01, -1.24053955e-01]), + 'Velocity': array([0.38037041, 0.46619686, 0.00227561]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 501.08734130859375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([597.50775146, -70.92279816, 0. ]), + 'frame': 837, + 'frame_number': 837, + 'framesequence': 835, + 'gaze_dir': array([ 0.98058069, -0.13914008, -0.13820834]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13914008, -0.13820834]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13914008, -0.13820834]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.21257363259792328, + 'throttle_input': 0.0, + 'timestamp': 17.021934177726507, + 'timestamp_carla': 17021, + 'timestamp_device': 16490, + 'timestamp_stream': 17.021934177726507, + 'transform': [array([ 6.90043926e+00, -1.29715856e-02, 1.80480955e-03]), + array([-0.00937102, -0.56564325, 0.03098143])]} +{'AngularVelocity': array([-0.54181641, -0.40400243, 7.11536026]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.74201011657715, + 'FR_Wheel_Angle': 41.41197967529297, + 'Location': array([ 4.48917046e+01, -5.72606087e+00, 1.74240826e-03]), + 'Rotation': array([-2.33729053e-02, 2.96086903e+01, -1.17034912e-01]), + 'Velocity': array([3.58470559e-01, 4.56431419e-01, 1.74236302e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 499.7973937988281, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.97180542e+02, -6.98831787e+01, 3.05175781e-05]), + 'frame': 838, + 'frame_number': 838, + 'framesequence': 836, + 'gaze_dir': array([ 0.98058069, -0.13733187, -0.14000525]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13733187, -0.14000525]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13733187, -0.14000525]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2243659943342209, + 'throttle_input': 0.0, + 'timestamp': 17.03519317880273, + 'timestamp_carla': 17035, + 'timestamp_device': 16503, + 'timestamp_stream': 17.03519317880273, + 'transform': [array([ 6.91287756e+00, -1.45030124e-02, 1.80370326e-03]), + array([-0.00945981, -0.62509155, 0.03173228])]} +{'AngularVelocity': array([-0.54082263, -0.41897506, 7.07742786]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.748611450195312, + 'FR_Wheel_Angle': 41.41452407836914, + 'Location': array([ 4.49639244e+01, -5.66111135e+00, 1.80577033e-03]), + 'Rotation': array([-2.48687174e-02, 3.08027725e+01, -1.29272446e-01]), + 'Velocity': array([0.3405208 , 0.45653296, 0.00109541]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 498.5280456542969, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.96945984e+02, -6.88452835e+01, 3.05175781e-05]), + 'frame': 839, + 'frame_number': 839, + 'framesequence': 837, + 'gaze_dir': array([ 0.98058069, -0.13535841, -0.1419141 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13535841, -0.1419141 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13535841, -0.1419141 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.23467512428760529, + 'throttle_input': 0.0, + 'timestamp': 17.048672877252102, + 'timestamp_carla': 17048, + 'timestamp_device': 16517, + 'timestamp_stream': 17.048672877252102, + 'transform': [array([ 6.92541599e+00, -1.61354486e-02, 1.80156704e-03]), + array([-0.00952128, -0.68795776, 0.0319287 ])]} +{'AngularVelocity': array([-0.51991022, -0.42666802, 6.92502689]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.75507926940918, + 'FR_Wheel_Angle': 41.423126220703125, + 'Location': array([ 4.50418510e+01, -5.58713245e+00, 1.82633160e-03]), + 'Rotation': array([-2.45067179e-02, 3.21292992e+01, -1.27136230e-01]), + 'Velocity': array([0.31755456, 0.45033741, 0.00049047]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 497.1849060058594, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([596.6114502 , -67.71962738, 0. ]), + 'frame': 840, + 'frame_number': 840, + 'framesequence': 838, + 'gaze_dir': array([ 0.98058069, -0.13350208, -0.1436618 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13350208, -0.1436618 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13350208, -0.1436618 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.24668721854686737, + 'throttle_input': 0.0, + 'timestamp': 17.062115978449583, + 'timestamp_carla': 17062, + 'timestamp_device': 16530, + 'timestamp_stream': 17.062115978449583, + 'transform': [array([ 6.93781519e+00, -1.78392958e-02, 1.80038449e-03]), + array([-0.00955543, -0.75320429, 0.03178126])]} +{'AngularVelocity': array([-0.54395038, -0.46271801, 6.73607969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76262092590332, + 'FR_Wheel_Angle': 41.43024826049805, + 'Location': array([ 4.51087151e+01, -5.52379751e+00, 1.84155221e-03]), + 'Rotation': array([-2.56883409e-02, 3.32537651e+01, -1.36718735e-01]), + 'Velocity': array([3.00350308e-01, 4.44721580e-01, 4.42423800e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 495.9604797363281, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([596.41955566, -66.67599487, 0. ]), + 'frame': 841, + 'frame_number': 841, + 'framesequence': 839, + 'gaze_dir': array([ 0.98058069, -0.13162316, -0.14538519]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.13162316, -0.14538519]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.13162316, -0.14538519]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.25842463970184326, + 'throttle_input': 0.0, + 'timestamp': 17.075101479887962, + 'timestamp_carla': 17075, + 'timestamp_device': 16543, + 'timestamp_stream': 17.075101479887962, + 'transform': [array([ 6.94969416e+00, -1.95567943e-02, 1.80175772e-03]), + array([-0.00958276, -0.81866455, 0.03144328])]} +{'AngularVelocity': array([-0.53885382, -0.47741103, 6.53254175]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.76791000366211, + 'FR_Wheel_Angle': 41.4388313293457, + 'Location': array([ 4.51778564e+01, -5.45480967e+00, 1.86302897e-03]), + 'Rotation': array([-2.57224906e-02, 3.44494553e+01, -1.37756377e-01]), + 'Velocity': array([2.81936347e-01, 4.37337548e-01, 1.07765200e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 494.7580871582031, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([596.23876953, -65.62893677, 0. ]), + 'frame': 842, + 'frame_number': 842, + 'framesequence': 840, + 'gaze_dir': array([ 0.98058069, -0.12972201, -0.14708403]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12972201, -0.14708403]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12972201, -0.14708403]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.26860561966896057, + 'throttle_input': 0.0, + 'timestamp': 17.088404778391123, + 'timestamp_carla': 17088, + 'timestamp_device': 16556, + 'timestamp_stream': 17.088404778391123, + 'transform': [array([ 6.96176434e+00, -2.13855710e-02, 1.80149078e-03]), + array([-0.00958276, -0.88796991, 0.03094026])]} +{'AngularVelocity': array([-0.54706001, -0.50592691, 6.34191656]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.774255752563477, + 'FR_Wheel_Angle': 41.44553756713867, + 'Location': array([ 4.52407227e+01, -5.39137268e+00, 1.83876744e-03]), + 'Rotation': array([-2.60025281e-02, 3.55354538e+01, -1.40197754e-01]), + 'Velocity': array([ 2.65224040e-01, 4.29899693e-01, -2.05984106e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 493.57867431640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([596.03448486, -64.57663727, 0. ]), + 'frame': 843, + 'frame_number': 843, + 'framesequence': 841, + 'gaze_dir': array([ 0.98058069, -0.12779923, -0.14875776]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12779923, -0.14875776]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12779923, -0.14875776]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.2805078327655792, + 'throttle_input': 0.0, + 'timestamp': 17.10145017877221, + 'timestamp_carla': 17101, + 'timestamp_device': 16569, + 'timestamp_stream': 17.10145017877221, + 'transform': [array([ 6.97350407e+00, -2.32478324e-02, 1.80294027e-03]), + array([-0.00958276, -0.95825171, 0.03038217])]} +{'AngularVelocity': array([-0.56307775, -0.53538549, 6.1842308 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.780969619750977, + 'FR_Wheel_Angle': 41.45189666748047, + 'Location': array([ 4.52982407e+01, -5.33315945e+00, 1.89720863e-03]), + 'Rotation': array([-2.72524524e-02, 3.65218620e+01, -1.50451660e-01]), + 'Velocity': array([2.51078665e-01, 4.23775613e-01, 8.22639413e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 492.4215393066406, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([595.87341309, -63.52270508, 0. ]), + 'frame': 844, + 'frame_number': 844, + 'framesequence': 842, + 'gaze_dir': array([ 0.98058069, -0.12570417, -0.15053231]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12570417, -0.15053231]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12570417, -0.15053231]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.29068881273269653, + 'throttle_input': 0.0, + 'timestamp': 17.114645779132843, + 'timestamp_carla': 17114, + 'timestamp_device': 16583, + 'timestamp_stream': 17.114645779132843, + 'transform': [array([ 6.98528194e+00, -2.51979791e-02, 1.80324551e-03]), + array([-0.00958276, -1.03152454, 0.02975964])]} +{'AngularVelocity': array([-0.54632092, -0.54051989, 5.98481417]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.786205291748047, + 'FR_Wheel_Angle': 41.464691162109375, + 'Location': array([ 4.53593750e+01, -5.26766634e+00, 1.88614603e-03]), + 'Rotation': array([-2.66718864e-02, 3.76078377e+01, -1.46972626e-01]), + 'Velocity': array([ 2.34914437e-01, 4.14660186e-01, -4.08420543e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 491.2008361816406, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95610474e+02, -6.23778000e+01, 3.05175781e-05]), + 'frame': 845, + 'frame_number': 845, + 'framesequence': 843, + 'gaze_dir': array([ 0.98058069, -0.12373661, -0.15215376]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12373661, -0.15215376]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12373661, -0.15215376]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3026825785636902, + 'throttle_input': 0.0, + 'timestamp': 17.127938378602266, + 'timestamp_carla': 17127, + 'timestamp_device': 16596, + 'timestamp_stream': 17.127938378602266, + 'transform': [array([ 6.99818707e+00, -2.60956921e-02, 1.80515286e-03]), + array([-0.00997891, -1.10940552, 0.03657297])]} +{'AngularVelocity': array([-0.56437433, -0.57438934, 5.84074736]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.792617797851562, + 'FR_Wheel_Angle': 41.47574234008789, + 'Location': array([ 4.54116974e+01, -5.21247721e+00, 1.86627149e-03]), + 'Rotation': array([-2.79491320e-02, 3.85164871e+01, -1.57623276e-01]), + 'Velocity': array([ 2.22144350e-01, 4.08119351e-01, -4.84180455e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 490.09051513671875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([595.47497559, -61.31634903, 0. ]), + 'frame': 846, + 'frame_number': 846, + 'framesequence': 844, + 'gaze_dir': array([ 0.98058069, -0.12174813, -0.15374948]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.12174813, -0.15374948]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.12174813, -0.15374948]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3144383132457733, + 'throttle_input': 0.0, + 'timestamp': 17.14103437960148, + 'timestamp_carla': 17141, + 'timestamp_device': 16609, + 'timestamp_stream': 17.14103437960148, + 'transform': [array([ 7.01059437e+00, -2.78453566e-02, 1.80900574e-03]), + array([-0.01047068, -1.1902771 , 0.04439419])]} +{'AngularVelocity': array([-0.55222631, -0.58040565, 5.66106176]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.79845428466797, + 'FR_Wheel_Angle': 41.479461669921875, + 'Location': array([ 4.54659958e+01, -5.15208626e+00, 1.88400981e-03]), + 'Rotation': array([-2.78876610e-02, 3.94912338e+01, -1.58355698e-01]), + 'Velocity': array([2.08438709e-01, 3.99294853e-01, 3.45182401e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 489.0162658691406, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95486511e+02, -6.01372757e+01, -3.05175781e-05]), + 'frame': 847, + 'frame_number': 847, + 'framesequence': 845, + 'gaze_dir': array([ 0.98058069, -0.11958379, -0.15543883]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11958379, -0.15543883]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11958379, -0.15543883]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.32476577162742615, + 'throttle_input': 0.0, + 'timestamp': 17.154948979616165, + 'timestamp_carla': 17154, + 'timestamp_device': 16623, + 'timestamp_stream': 17.154948979616165, + 'transform': [array([ 7.02356672e+00, -3.00906822e-02, 1.80789945e-03]), + array([-0.0109283 , -1.27947998, 0.05042426])]} +{'AngularVelocity': array([-0.50716817, -0.56255656, 5.43228817]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.80475616455078, + 'FR_Wheel_Angle': 41.484519958496094, + 'Location': array([ 4.55235748e+01, -5.08431101e+00, 1.88828225e-03]), + 'Rotation': array([-2.55380757e-02, 4.05661011e+01, -1.40563950e-01]), + 'Velocity': array([0.192753 , 0.38696143, 0.00041694]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 487.88525390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([595.38562012, -58.94486237, 0. ]), + 'frame': 848, + 'frame_number': 848, + 'framesequence': 846, + 'gaze_dir': array([ 0.98058069, -0.117396 , -0.15709771]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.117396 , -0.15709771]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.117396 , -0.15709771]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3367595374584198, + 'throttle_input': 0.0, + 'timestamp': 17.16863937675953, + 'timestamp_carla': 17168, + 'timestamp_device': 16637, + 'timestamp_stream': 17.16863937675953, + 'transform': [array([ 7.03617334e+00, -3.24777626e-02, 1.80858606e-03]), + array([-0.01126298, -1.36999476, 0.05381144])]} +{'AngularVelocity': array([-0.50746518, -0.57832235, 5.27166414]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.810108184814453, + 'FR_Wheel_Angle': 41.490638732910156, + 'Location': array([ 4.55737114e+01, -5.02693701e+00, 1.88088173e-03]), + 'Rotation': array([-2.60025281e-02, 4.14720764e+01, -1.45080581e-01]), + 'Velocity': array([0.18086471, 0.3785412 , 0.0004963 ]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 486.7759094238281, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95363037e+02, -5.77793655e+01, 3.05175781e-05]), + 'frame': 849, + 'frame_number': 849, + 'framesequence': 847, + 'gaze_dir': array([ 0.98058069, -0.11518522, -0.1587258 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11518522, -0.1587258 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11518522, -0.1587258 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.348533570766449, + 'throttle_input': 0.0, + 'timestamp': 17.182629376649857, + 'timestamp_carla': 17182, + 'timestamp_device': 16651, + 'timestamp_stream': 17.182629376649857, + 'transform': [array([ 7.04891729e+00, -3.50315347e-02, 1.80702202e-03]), + array([-0.01146789, -1.46502686, 0.05523885])]} +{'AngularVelocity': array([-0.51938123, -0.60827571, 5.11931944]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.81514549255371, + 'FR_Wheel_Angle': 41.49726104736328, + 'Location': array([ 4.56211014e+01, -4.97251701e+00, 1.86917058e-03]), + 'Rotation': array([-2.67948303e-02, 4.23239517e+01, -1.51428223e-01]), + 'Velocity': array([ 1.69809207e-01, 3.70372444e-01, -5.95235797e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 485.6876220703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([595.33227539, -56.61833572, 0. ]), + 'frame': 850, + 'frame_number': 850, + 'framesequence': 848, + 'gaze_dir': array([ 0.98058069, -0.1132724 , -0.16009645]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1132724 , -0.16009645]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1132724 , -0.16009645]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3605273962020874, + 'throttle_input': 0.0, + 'timestamp': 17.195226076990366, + 'timestamp_carla': 17195, + 'timestamp_device': 16663, + 'timestamp_stream': 17.195226076990366, + 'transform': [array([ 7.06027985e+00, -3.74089070e-02, 1.81320182e-03]), + array([-0.01159766, -1.55273449, 0.05535179])]} +{'AngularVelocity': array([-0.52223939, -0.63051528, 4.9644556 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.820295333862305, + 'FR_Wheel_Angle': 41.50560760498047, + 'Location': array([ 4.56668587e+01, -4.91895294e+00, 1.88400981e-03]), + 'Rotation': array([-2.70612072e-02, 4.31531601e+01, -1.54144287e-01]), + 'Velocity': array([ 1.59134656e-01, 3.61660421e-01, -2.50430108e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 484.77227783203125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95508179e+02, -5.56351547e+01, 3.05175781e-05]), + 'frame': 851, + 'frame_number': 851, + 'framesequence': 849, + 'gaze_dir': array([ 0.98058069, -0.11102002, -0.16166654]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11102002, -0.16166654]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11102002, -0.16166654]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3707449436187744, + 'throttle_input': 0.0, + 'timestamp': 17.208555176854134, + 'timestamp_carla': 17208, + 'timestamp_device': 16677, + 'timestamp_stream': 17.208555176854134, + 'transform': [array([ 7.07218981e+00, -3.99981029e-02, 1.81465142e-03]), + array([-0.01165913, -1.64761353, 0.05460894])]} +{'AngularVelocity': array([-0.51431775, -0.63983142, 4.81123877]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.825424194335938, + 'FR_Wheel_Angle': 41.51284408569336, + 'Location': array([ 4.57112007e+01, -4.86627245e+00, 1.89232582e-03]), + 'Rotation': array([-2.71226801e-02, 4.39598351e+01, -1.54998779e-01]), + 'Velocity': array([1.49022758e-01, 3.52702886e-01, 1.82490345e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 483.7265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95413879e+02, -5.44657669e+01, -3.05175781e-05]), + 'frame': 852, + 'frame_number': 852, + 'framesequence': 850, + 'gaze_dir': array([ 0.98058069, -0.1087459 , -0.16320491]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.1087459 , -0.16320491]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.1087459 , -0.16320491]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3827204406261444, + 'throttle_input': 0.0, + 'timestamp': 17.223239578306675, + 'timestamp_carla': 17223, + 'timestamp_device': 16691, + 'timestamp_stream': 17.223239578306675, + 'transform': [array([ 7.08517647e+00, -4.29352410e-02, 1.80713646e-03]), + array([-0.01165913, -1.75463855, 0.05315656])]} +{'AngularVelocity': array([-0.52938539, -0.66920304, 4.68575096]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.830482482910156, + 'FR_Wheel_Angle': 41.518924713134766, + 'Location': array([ 4.57517815e+01, -4.81924772e+00, 1.88091991e-03]), + 'Rotation': array([-2.86526419e-02, 4.46753349e+01, -1.67175278e-01]), + 'Velocity': array([1.40592888e-01, 3.45494032e-01, 2.04496377e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 482.70416259765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95399414e+02, -5.32974434e+01, -3.05175781e-05]), + 'frame': 853, + 'frame_number': 853, + 'framesequence': 851, + 'gaze_dir': array([ 0.98058069, -0.10645046, -0.16471131]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10645046, -0.16471131]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10645046, -0.16471131]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.3948240876197815, + 'throttle_input': 0.0, + 'timestamp': 17.2368942797184, + 'timestamp_carla': 17236, + 'timestamp_device': 16705, + 'timestamp_stream': 17.2368942797184, + 'transform': [array([ 7.09713364e+00, -4.57405634e-02, 1.80801388e-03]), + array([-0.01162498, -1.85638428, 0.05150525])]} +{'AngularVelocity': array([-0.50150812, -0.65889585, 4.51695156]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.835208892822266, + 'FR_Wheel_Angle': 41.52734375, + 'Location': array([ 4.57955246e+01, -4.76453543e+00, 1.87142135e-03]), + 'Rotation': array([-2.72524524e-02, 4.54954720e+01, -1.57073975e-01]), + 'Velocity': array([0.13052815, 0.33491024, 0.00043452]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 481.70458984375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95513794e+02, -5.21337204e+01, -3.05175781e-05]), + 'frame': 854, + 'frame_number': 854, + 'framesequence': 852, + 'gaze_dir': array([ 0.98058069, -0.10430019, -0.16608126]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10430019, -0.16608126]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10430019, -0.16608126]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4065798223018646, + 'throttle_input': 0.0, + 'timestamp': 17.25007637962699, + 'timestamp_carla': 17250, + 'timestamp_device': 16718, + 'timestamp_stream': 17.25007637962699, + 'transform': [array([ 7.10856724e+00, -4.85170484e-02, 1.81098934e-03]), + array([-0.01159766, -1.95669544, 0.04977398])]} +{'AngularVelocity': array([-0.49205962, -0.66602117, 4.37106991]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.84005355834961, + 'FR_Wheel_Angle': 41.5334587097168, + 'Location': array([ 4.58357086e+01, -4.71457863e+00, 1.86947582e-03]), + 'Rotation': array([-2.69724149e-02, 4.62381744e+01, -1.55395523e-01]), + 'Velocity': array([0.12185641, 0.32576862, 0.00038872]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 480.7997131347656, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([595.63867188, -51.05077744, 0. ]), + 'frame': 855, + 'frame_number': 855, + 'framesequence': 853, + 'gaze_dir': array([ 0.98058069, -0.10213231, -0.16742314]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10213231, -0.16742314]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10213231, -0.16742314]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4185918867588043, + 'throttle_input': 0.0, + 'timestamp': 17.263444278389215, + 'timestamp_carla': 17263, + 'timestamp_device': 16731, + 'timestamp_stream': 17.263444278389215, + 'transform': [array([ 7.12005186e+00, -5.14027327e-02, 1.81262963e-03]), + array([-0.01153619, -2.06060815, 0.04797195])]} +{'AngularVelocity': array([-0.49226484, -0.68057942, 4.24076557]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.844371795654297, + 'FR_Wheel_Angle': 41.54328918457031, + 'Location': array([ 4.58739548e+01, -4.66781044e+00, 1.86886545e-03]), + 'Rotation': array([-2.74983402e-02, 4.69285469e+01, -1.60095230e-01]), + 'Velocity': array([0.11417621, 0.31757489, 0.00038455]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 479.9170227050781, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([595.74182129, -49.96274567, 0. ]), + 'frame': 856, + 'frame_number': 856, + 'framesequence': 854, + 'gaze_dir': array([ 0.98058069, -0.09994715, -0.16873673]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09994715, -0.16873673]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09994715, -0.16873673]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4289010465145111, + 'throttle_input': 0.0, + 'timestamp': 17.276427280157804, + 'timestamp_carla': 17276, + 'timestamp_device': 16744, + 'timestamp_stream': 17.276427280157804, + 'transform': [array([ 7.13110209e+00, -5.42677045e-02, 1.81587215e-03]), + array([-0.01146789, -2.1633606 , 0.04620679])]} +{'AngularVelocity': array([-0.49948248, -0.70595312, 4.1166153 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.848493576049805, + 'FR_Wheel_Angle': 41.54661560058594, + 'Location': array([ 4.59103584e+01, -4.62329149e+00, 1.88896887e-03]), + 'Rotation': array([-2.82359999e-02, 4.75790367e+01, -1.65924042e-01]), + 'Velocity': array([0.10701478, 0.30968961, 0.00034766]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 479.0555419921875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([595.87585449, -48.87335968, 0. ]), + 'frame': 857, + 'frame_number': 857, + 'framesequence': 855, + 'gaze_dir': array([ 0.98058069, -0.09757512, -0.1701194 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09757512, -0.1701194 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09757512, -0.1701194 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.44080325961112976, + 'throttle_input': 0.0, + 'timestamp': 17.28980937972665, + 'timestamp_carla': 17289, + 'timestamp_device': 16758, + 'timestamp_stream': 17.28980937972665, + 'transform': [array([ 7.14380884e+00, -5.54613993e-02, 1.81770325e-03]), + array([-0.01215091, -2.27194214, 0.05478493])]} +{'AngularVelocity': array([-0.5246954 , -0.74780214, 4.01681709]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.852519989013672, + 'FR_Wheel_Angle': 41.55521774291992, + 'Location': array([ 4.59438705e+01, -4.58448124e+00, 1.89404248e-03]), + 'Rotation': array([-3.03670187e-02, 4.81445503e+01, -1.83044404e-01]), + 'Velocity': array([ 0.10114773, 0.30347621, -0.00032113]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 478.1527404785156, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.95928589e+02, -4.76894226e+01, -3.05175781e-05]), + 'frame': 858, + 'frame_number': 858, + 'framesequence': 856, + 'gaze_dir': array([ 0.98058069, -0.09535564, -0.17137334]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09535564, -0.17137334]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09535564, -0.17137334]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4529252052307129, + 'throttle_input': 0.0, + 'timestamp': 17.303407076746225, + 'timestamp_carla': 17303, + 'timestamp_device': 16771, + 'timestamp_stream': 17.303407076746225, + 'transform': [array([ 7.15613985e+00, -5.80091402e-02, 1.82044983e-03]), + array([-0.01309347, -2.38671899, 0.0657149 ])]} +{'AngularVelocity': array([-0.50279766, -0.74394453, 3.87608051]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.857168197631836, + 'FR_Wheel_Angle': 41.55738830566406, + 'Location': array([ 4.59799843e+01, -4.53830051e+00, 1.90075627e-03]), + 'Rotation': array([-2.89668310e-02, 4.88085022e+01, -1.72027558e-01]), + 'Velocity': array([9.38958973e-02, 2.93960780e-01, 2.84719463e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 477.3518371582031, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.96253967e+02, -4.64138336e+01, -6.10351562e-05]), + 'frame': 859, + 'frame_number': 859, + 'framesequence': 857, + 'gaze_dir': array([ 0.98058069, -0.09294715, -0.17269146]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09294715, -0.17269146]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09294715, -0.17269146]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46303293108940125, + 'throttle_input': 0.0, + 'timestamp': 17.316754177212715, + 'timestamp_carla': 17316, + 'timestamp_device': 16785, + 'timestamp_stream': 17.316754177212715, + 'transform': [array([ 7.16793394e+00, -6.10432811e-02, 1.82464591e-03]), + array([-0.01388577, -2.50302172, 0.07361504])]} +{'AngularVelocity': array([-0.48271623, -0.72930968, 3.74998069]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.860633850097656, + 'FR_Wheel_Angle': 41.564178466796875, + 'Location': array([ 4.60147896e+01, -4.49431944e+00, 1.88870193e-03]), + 'Rotation': array([-2.85911709e-02, 4.94370537e+01, -1.69860825e-01]), + 'Velocity': array([0.0876549 , 0.28535965, 0.00037158]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 476.51519775390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([596.5045166 , -45.16586304, 0. ]), + 'frame': 860, + 'frame_number': 860, + 'framesequence': 858, + 'gaze_dir': array([ 0.98058069, -0.09069429, -0.17388521]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.09069429, -0.17388521]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.09069429, -0.17388521]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4750266969203949, + 'throttle_input': 0.0, + 'timestamp': 17.330570679157972, + 'timestamp_carla': 17330, + 'timestamp_device': 16798, + 'timestamp_stream': 17.330570679157972, + 'transform': [array([ 7.17993164e+00, -6.44292757e-02, 1.82533264e-03]), + array([-0.01445951, -2.62640429, 0.078174 ])]} +{'AngularVelocity': array([-0.48288009, -0.7496981 , 3.63417387]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.8644962310791, + 'FR_Wheel_Angle': 41.57155227661133, + 'Location': array([ 4.60473518e+01, -4.45376730e+00, 1.87901256e-03]), + 'Rotation': array([-2.86867935e-02, 5.00122337e+01, -1.70257553e-01]), + 'Velocity': array([0.08180131, 0.27752078, 0.00036459]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 475.7571716308594, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.96792664e+02, -4.40486259e+01, 3.05175781e-05]), + 'frame': 861, + 'frame_number': 861, + 'framesequence': 859, + 'gaze_dir': array([ 0.98058069, -0.08825109, -0.17513783]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08825109, -0.17513783]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08825109, -0.17513783]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48713037371635437, + 'throttle_input': 0.0, + 'timestamp': 17.34426337853074, + 'timestamp_carla': 17344, + 'timestamp_device': 16812, + 'timestamp_stream': 17.34426337853074, + 'transform': [array([ 7.19165945e+00, -6.79179579e-02, 1.82617188e-03]), + array([-0.01483517, -2.75112939, 0.079814 ])]} +{'AngularVelocity': array([-0.48212031, -0.76354384, 3.52389979]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.868099212646484, + 'FR_Wheel_Angle': 41.57590103149414, + 'Location': array([ 4.60789833e+01, -4.41463995e+00, 1.87504524e-03]), + 'Rotation': array([-2.88097356e-02, 5.05631714e+01, -1.71661362e-01]), + 'Velocity': array([ 0.0764806 , 0.26997441, -0.00036304]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 474.9584045410156, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([597.06213379, -42.85564804, 0. ]), + 'frame': 862, + 'frame_number': 862, + 'framesequence': 860, + 'gaze_dir': array([ 0.98058069, -0.08596683, -0.17627032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08596683, -0.17627032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08596683, -0.17627032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49908751249313354, + 'throttle_input': 0.0, + 'timestamp': 17.357440777122974, + 'timestamp_carla': 17357, + 'timestamp_device': 16825, + 'timestamp_stream': 17.357440777122974, + 'transform': [array([ 7.20281124e+00, -7.13643953e-02, 1.82914734e-03]), + array([-0.01501959, -2.87323022, 0.07951739])]} +{'AngularVelocity': array([-0.48145661, -0.77544671, 3.42302394]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 30.872087478637695, + 'FR_Wheel_Angle': 41.57964324951172, + 'Location': array([ 4.61094856e+01, -4.37774515e+00, 1.92021125e-03]), + 'Rotation': array([-2.94449441e-02, 5.10795517e+01, -1.77032441e-01]), + 'Velocity': array([0.071711 , 0.26301223, 0.00027421]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 474.23486328125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([597.39221191, -41.75601959, 0. ]), + 'frame': 863, + 'frame_number': 863, + 'framesequence': 861, + 'gaze_dir': array([ 0.98058069, -0.0834907 , -0.17745654]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0834907 , -0.17745654]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0834907 , -0.17745654]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5091769099235535, + 'throttle_input': 0.0, + 'timestamp': 17.37107837945223, + 'timestamp_carla': 17371, + 'timestamp_device': 16839, + 'timestamp_stream': 17.37107837945223, + 'transform': [array([ 7.21422243e+00, -7.50066787e-02, 1.82891847e-03]), + array([-0.01507423, -3.0014348 , 0.07788072])]} +{'AngularVelocity': array([-0.4732635 , -0.77935958, 2.94050121]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 27.815797805786133, + 'FR_Wheel_Angle': 35.71101760864258, + 'Location': array([ 4.61411324e+01, -4.33815193e+00, 1.92112685e-03]), + 'Rotation': array([-2.86526419e-02, 5.16095085e+01, -1.72180176e-01]), + 'Velocity': array([7.94245675e-02, 2.53513068e-01, 1.28355023e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 473.476806640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.97638672e+02, -4.05620956e+01, 3.05175781e-05]), + 'frame': 864, + 'frame_number': 864, + 'framesequence': 862, + 'gaze_dir': array([ 0.98058069, -0.08117669, -0.17852692]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.08117669, -0.17852692]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.08117669, -0.17852692]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5210608839988708, + 'throttle_input': 0.0, + 'timestamp': 17.38424377888441, + 'timestamp_carla': 17384, + 'timestamp_device': 16852, + 'timestamp_stream': 17.38424377888441, + 'transform': [array([ 7.22511625e+00, -7.85903260e-02, 1.83082581e-03]), + array([-0.01504691, -3.12701488, 0.07555501])]} +{'AngularVelocity': array([-0.46967548, -0.76766974, 2.96601653]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.143659591674805, + 'FR_Wheel_Angle': 32.684452056884766, + 'Location': array([ 4.61755943e+01, -4.29667091e+00, 1.89442397e-03]), + 'Rotation': array([-2.68563032e-02, 5.20738029e+01, -1.74224839e-01]), + 'Velocity': array([1.01612002e-01, 2.85851270e-01, 1.55148504e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 472.79254150390625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([597.99316406, -39.46170807, 0. ]), + 'frame': 865, + 'frame_number': 865, + 'framesequence': 863, + 'gaze_dir': array([ 0.98058069, -0.07884896, -0.17956714]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07884896, -0.17956714]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07884896, -0.17956714]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5330912470817566, + 'throttle_input': 0.0, + 'timestamp': 17.396896179765463, + 'timestamp_carla': 17396, + 'timestamp_device': 16865, + 'timestamp_stream': 17.396896179765463, + 'transform': [array([ 7.23547459e+00, -8.20970684e-02, 1.83483120e-03]), + array([-0.01495811, -3.24954247, 0.07294503])]} +{'AngularVelocity': array([-0.48681301, -0.79537529, 3.18104506]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.705699920654297, + 'FR_Wheel_Angle': 32.91169357299805, + 'Location': array([ 4.62095222e+01, -4.25432253e+00, 1.87878369e-03]), + 'Rotation': array([-2.59410571e-02, 5.25689316e+01, -1.79473847e-01]), + 'Velocity': array([9.92564932e-02, 2.98164219e-01, 5.68866708e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 472.128662109375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.98326782e+02, -3.83573875e+01, -3.05175781e-05]), + 'frame': 866, + 'frame_number': 866, + 'framesequence': 864, + 'gaze_dir': array([ 0.98058069, -0.07650824, -0.18057688]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07650824, -0.18057688]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07650824, -0.18057688]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5435285568237305, + 'throttle_input': 0.0, + 'timestamp': 17.40965588018298, + 'timestamp_carla': 17409, + 'timestamp_device': 16878, + 'timestamp_stream': 17.40965588018298, + 'transform': [array([ 7.24581099e+00, -8.56933892e-02, 1.83715811e-03]), + array([-0.01480102, -3.37478733, 0.07009685])]} +{'AngularVelocity': array([-0.46052611, -0.7618134 , 3.16139507]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.935047149658203, + 'FR_Wheel_Angle': 33.48080825805664, + 'Location': array([ 4.62449989e+01, -4.20643377e+00, 1.88717595e-03]), + 'Rotation': array([-2.40764152e-02, 5.31172905e+01, -1.71508774e-01]), + 'Velocity': array([0.09551353, 0.29630652, 0.00042173]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 471.4859924316406, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 5.98638184e+02, -3.72488213e+01, -3.05175781e-05]), + 'frame': 867, + 'frame_number': 867, + 'framesequence': 865, + 'gaze_dir': array([ 0.98058069, -0.07415425, -0.18155624]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07415425, -0.18155624]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07415425, -0.18155624]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5552476644515991, + 'throttle_input': 0.0, + 'timestamp': 17.42229997739196, + 'timestamp_carla': 17422, + 'timestamp_device': 16891, + 'timestamp_stream': 17.42229997739196, + 'transform': [array([ 7.25594521e+00, -8.93162638e-02, 1.83948514e-03]), + array([-0.0146166 , -3.50064182, 0.06721126])]} +{'AngularVelocity': array([-0.47164646, -0.79092568, 3.04910374]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.814977645874023, + 'FR_Wheel_Angle': 33.336158752441406, + 'Location': array([ 4.62776604e+01, -4.16547918e+00, 1.87062018e-03]), + 'Rotation': array([-2.45067179e-02, 5.35910797e+01, -1.78619370e-01]), + 'Velocity': array([ 9.05928984e-02, 2.88402379e-01, -6.16121251e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.8635559082031, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([598.97497559, -36.13991547, 0. ]), + 'frame': 868, + 'frame_number': 868, + 'framesequence': 866, + 'gaze_dir': array([ 0.98058069, -0.07178773, -0.18250491]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07178773, -0.18250491]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07178773, -0.18250491]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5654836297035217, + 'throttle_input': 0.0, + 'timestamp': 17.43540257960558, + 'timestamp_carla': 17435, + 'timestamp_device': 16904, + 'timestamp_stream': 17.43540257960558, + 'transform': [array([ 7.26633406e+00, -9.31300074e-02, 1.83887477e-03]), + array([-0.01443219, -3.63272119, 0.06421001])]} +{'AngularVelocity': array([-0.44788063, -0.76919115, 2.96273541]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.79754638671875, + 'FR_Wheel_Angle': 33.28963851928711, + 'Location': array([ 4.63121071e+01, -4.11908579e+00, 1.88576453e-03]), + 'Rotation': array([-2.33114343e-02, 5.41215057e+01, -1.68762192e-01]), + 'Velocity': array([ 8.53801817e-02, 2.81012177e-01, -1.82485572e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.26220703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([599.32092285, -35.0294342 , 0. ]), + 'frame': 869, + 'frame_number': 869, + 'framesequence': 867, + 'gaze_dir': array([ 0.98058069, -0.06959272, -0.18335314]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06959272, -0.18335314]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06959272, -0.18335314]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5775689482688904, + 'throttle_input': 0.0, + 'timestamp': 17.448052678257227, + 'timestamp_carla': 17448, + 'timestamp_device': 16916, + 'timestamp_stream': 17.448052678257227, + 'transform': [array([ 7.27625513e+00, -9.68696102e-02, 1.84059143e-03]), + array([-0.01422045, -3.76196384, 0.06139861])]} +{'AngularVelocity': array([-0.45038265, -0.78626829, 2.8939538 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.798410415649414, + 'FR_Wheel_Angle': 33.29583740234375, + 'Location': array([ 4.63439980e+01, -4.07856035e+00, 1.89430953e-03]), + 'Rotation': array([-2.36529447e-02, 5.45846291e+01, -1.73553437e-01]), + 'Velocity': array([ 8.09575841e-02, 2.75283068e-01, -6.17742553e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 469.7249755859375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([599.76257324, -34.01374054, 0. ]), + 'frame': 870, + 'frame_number': 870, + 'framesequence': 868, + 'gaze_dir': array([ 0.98058069, -0.06720322, -0.18424235]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06720322, -0.18424235]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06720322, -0.18424235]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5875301361083984, + 'throttle_input': 0.0, + 'timestamp': 17.461104076355696, + 'timestamp_carla': 17461, + 'timestamp_device': 16929, + 'timestamp_stream': 17.461104076355696, + 'transform': [array([ 7.28831387e+00, -9.81669128e-02, 1.84410089e-03]), + array([-0.01516302, -3.89444089, 0.07076184])]} +{'AngularVelocity': array([-0.46522978, -0.82032537, 2.83549786]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.800487518310547, + 'FR_Wheel_Angle': 33.29628372192383, + 'Location': array([ 4.63739243e+01, -4.04173994e+00, 1.90090889e-03]), + 'Rotation': array([-2.48345658e-02, 5.50035057e+01, -1.86248779e-01]), + 'Velocity': array([7.70685002e-02, 2.70478278e-01, 3.03745255e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 469.1636962890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.00143005e+02, -3.29022331e+01, 3.05175781e-05]), + 'frame': 871, + 'frame_number': 871, + 'framesequence': 869, + 'gaze_dir': array([ 0.98058069, -0.06480237, -0.18510045]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06480237, -0.18510045]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06480237, -0.18510045]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5974913835525513, + 'throttle_input': 0.0, + 'timestamp': 17.47405707836151, + 'timestamp_carla': 17474, + 'timestamp_device': 16942, + 'timestamp_stream': 17.47405707836151, + 'transform': [array([ 7.29937792e+00, -1.01101771e-01, 1.85134879e-03]), + array([-0.01660419, -4.02871895, 0.08378936])]} +{'AngularVelocity': array([-0.47673741, -0.85500628, 2.77288079]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.803272247314453, + 'FR_Wheel_Angle': 33.304527282714844, + 'Location': array([ 4.64033356e+01, -4.00595617e+00, 1.89644576e-03]), + 'Rotation': array([-2.55380757e-02, 5.54094543e+01, -1.93481460e-01]), + 'Velocity': array([7.31092244e-02, 2.65211910e-01, 2.18868240e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.6375427246094, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.00776245e+02, -3.15386696e+01, -3.05175781e-05]), + 'frame': 872, + 'frame_number': 872, + 'framesequence': 870, + 'gaze_dir': array([ 0.98058069, -0.06239092, -0.18592712]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06239092, -0.18592712]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06239092, -0.18592712]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.48684137687087, + 'timestamp_carla': 17486, + 'timestamp_device': 16955, + 'timestamp_stream': 17.48684137687087, + 'transform': [array([ 7.30982208e+00, -1.04717053e-01, 1.85909262e-03]), + array([-0.01785411, -4.16473532, 0.09396613])]} +{'AngularVelocity': array([-0.46087521, -0.84198755, 2.70083642]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.80582618713379, + 'FR_Wheel_Angle': 33.30368423461914, + 'Location': array([ 4.64333763e+01, -3.96715021e+00, 1.89022778e-03]), + 'Rotation': array([-2.50872839e-02, 5.58450394e+01, -1.89331040e-01]), + 'Velocity': array([6.91682100e-02, 2.58848757e-01, 2.14276311e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.13653564453125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([601.3425293 , -30.33332825, 0. ]), + 'frame': 873, + 'frame_number': 873, + 'framesequence': 871, + 'gaze_dir': array([ 0.98058069, -0.05978192, -0.18678236]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05978192, -0.18678236]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05978192, -0.18678236]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.500881977379322, + 'timestamp_carla': 17500, + 'timestamp_device': 16969, + 'timestamp_stream': 17.500881977379322, + 'transform': [array([ 7.32100821e+00, -1.09018430e-01, 1.85802451e-03]), + array([-0.01883083, -4.31601143, 0.10024948])]} +{'AngularVelocity': array([-0.44081292, -0.82476062, 2.62298155]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.80809783935547, + 'FR_Wheel_Angle': 33.30851745605469, + 'Location': array([ 4.64638138e+01, -3.92719293e+00, 1.87939405e-03]), + 'Rotation': array([-2.40422636e-02, 5.62917480e+01, -1.79595917e-01]), + 'Velocity': array([ 6.51004985e-02, 2.51880556e-01, -6.83355320e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.61529541015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([601.83764648, -29.09720612, 0. ]), + 'frame': 874, + 'frame_number': 874, + 'framesequence': 872, + 'gaze_dir': array([ 0.98058069, -0.05734868, -0.18754373]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05734868, -0.18754373]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05734868, -0.18754373]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.514117877930403, + 'timestamp_carla': 17514, + 'timestamp_device': 16982, + 'timestamp_stream': 17.514117877930403, + 'transform': [array([ 7.33140182e+00, -1.13189265e-01, 1.86035153e-03]), + array([-0.0193226 , -4.45883369, 0.10220139])]} +{'AngularVelocity': array([-0.45287305, -0.85367566, 2.57103705]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 25.809934616088867, + 'FR_Wheel_Angle': 33.31190872192383, + 'Location': array([ 4.64914093e+01, -3.89419580e+00, 1.89324131e-03]), + 'Rotation': array([-2.53331698e-02, 5.66598740e+01, -1.92749053e-01]), + 'Velocity': array([6.19874373e-02, 2.47456774e-01, 1.06873507e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.1478576660156, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([602.46557617, -27.98503876, 0. ]), + 'frame': 875, + 'frame_number': 875, + 'framesequence': 873, + 'gaze_dir': array([ 0.98058069, -0.05471754, -0.18832821]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05471754, -0.18832821]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05471754, -0.18832821]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.5286621786654, + 'timestamp_carla': 17528, + 'timestamp_device': 16996, + 'timestamp_stream': 17.5286621786654, + 'transform': [array([ 7.34270287e+00, -1.17825240e-01, 1.85314170e-03]), + array([-0.01950019, -4.61523628, 0.10103448])]} +{'AngularVelocity': array([-0.46090636, -0.88923275, 2.26448846]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 23.56200408935547, + 'FR_Wheel_Angle': 28.99349594116211, + 'Location': array([ 4.65193024e+01, -3.86030293e+00, 1.88359013e-03]), + 'Rotation': array([-2.52990201e-02, 5.70260735e+01, -1.91925019e-01]), + 'Velocity': array([0.06628765, 0.24089551, 0.00038175]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.66253662109375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.03012329e+02, -2.67843132e+01, -3.05175781e-05]), + 'frame': 876, + 'frame_number': 876, + 'framesequence': 874, + 'gaze_dir': array([ 0.98058069, -0.05150817, -0.18923116]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05150817, -0.18923116]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05150817, -0.18923116]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5969420671463013, + 'throttle_input': 0.0, + 'timestamp': 17.54532277956605, + 'timestamp_carla': 17545, + 'timestamp_device': 17013, + 'timestamp_stream': 17.54532277956605, + 'transform': [array([ 7.35553265e+00, -1.23154178e-01, 1.82849879e-03]), + array([-0.0193226 , -4.79275751, 0.09693256])]} +{'AngularVelocity': array([-0.4604018 , -0.88102597, 1.98741865]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 19.104631423950195, + 'FR_Wheel_Angle': 23.376920700073242, + 'Location': array([ 4.65498123e+01, -3.82380414e+00, 1.87256571e-03]), + 'Rotation': array([-2.38032080e-02, 5.73426933e+01, -1.94335938e-01]), + 'Velocity': array([9.01572704e-02, 2.64726609e-01, 1.79743758e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.0995788574219, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.03590210e+02, -2.53197708e+01, 3.05175781e-05]), + 'frame': 877, + 'frame_number': 877, + 'framesequence': 875, + 'gaze_dir': array([ 0.98058069, -0.04866413, -0.18998244]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04866413, -0.18998244]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04866413, -0.18998244]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5887203812599182, + 'throttle_input': 0.0, + 'timestamp': 17.559743776917458, + 'timestamp_carla': 17559, + 'timestamp_device': 17028, + 'timestamp_stream': 17.559743776917458, + 'transform': [array([ 7.36657381e+00, -1.27751604e-01, 1.82636257e-03]), + array([-0.01891279, -4.94400311, 0.09209166])]} +{'AngularVelocity': array([-0.46721289, -0.88435966, 2.41751385]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.896705627441406, + 'FR_Wheel_Angle': 25.547319412231445, + 'Location': array([ 4.65815468e+01, -3.78308058e+00, 1.85974827e-03]), + 'Rotation': array([-2.19385661e-02, 5.76960182e+01, -1.96838364e-01]), + 'Velocity': array([9.07595828e-02, 2.93133050e-01, 1.98483467e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.6263122558594, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.04414368e+02, -2.40593109e+01, -3.05175781e-05]), + 'frame': 878, + 'frame_number': 878, + 'framesequence': 876, + 'gaze_dir': array([ 0.98058069, -0.04619022, -0.19059902]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04619022, -0.19059902]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04619022, -0.19059902]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5833552479743958, + 'throttle_input': 0.0, + 'timestamp': 17.572631876915693, + 'timestamp_carla': 17572, + 'timestamp_device': 17041, + 'timestamp_stream': 17.572631876915693, + 'transform': [array([ 7.37639618e+00, -1.31840572e-01, 1.83223723e-03]), + array([-0.018462 , -5.07727289, 0.08720633])]} +{'AngularVelocity': array([-0.4684056 , -0.89218169, 2.26166511]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.315637588500977, + 'FR_Wheel_Angle': 25.015790939331055, + 'Location': array([ 4.66122169e+01, -3.74473953e+00, 1.81927439e-03]), + 'Rotation': array([-2.14877743e-02, 5.80326996e+01, -2.00775146e-01]), + 'Velocity': array([ 8.89787972e-02, 2.84673870e-01, -2.22921371e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.2396545410156, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([605.15533447, -22.96989822, 0. ]), + 'frame': 879, + 'frame_number': 879, + 'framesequence': 877, + 'gaze_dir': array([ 0.98058069, -0.04389957, -0.19113961]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04389957, -0.19113961]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04389957, -0.19113961]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5817804336547852, + 'throttle_input': 0.0, + 'timestamp': 17.58487207815051, + 'timestamp_carla': 17584, + 'timestamp_device': 17053, + 'timestamp_stream': 17.58487207815051, + 'transform': [array([ 7.38567924e+00, -1.35711789e-01, 1.83944695e-03]), + array([-0.01794291, -5.20260954, 0.08238408])]} +{'AngularVelocity': array([-0.4437623 , -0.85872173, 2.22781539]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.29778480529785, + 'FR_Wheel_Angle': 24.878149032592773, + 'Location': array([ 4.66450119e+01, -3.69980097e+00, 1.82842964e-03]), + 'Rotation': array([-1.99578125e-02, 5.84229355e+01, -1.85943574e-01]), + 'Velocity': array([ 8.51426572e-02, 2.79875934e-01, -2.71825789e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.90167236328125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.05830811e+02, -2.19628983e+01, 3.05175781e-05]), + 'frame': 880, + 'frame_number': 880, + 'framesequence': 878, + 'gaze_dir': array([ 0.98058069, -0.04141139, -0.1916941 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.04141139, -0.1916941 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.04141139, -0.1916941 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.581908643245697, + 'throttle_input': 0.0, + 'timestamp': 17.597770877182484, + 'timestamp_carla': 17597, + 'timestamp_device': 17066, + 'timestamp_stream': 17.597770877182484, + 'transform': [array([ 7.39540529e+00, -1.39786139e-01, 1.84173579e-03]), + array([-0.01736917, -5.33383465, 0.07731353])]} +{'AngularVelocity': array([-0.43133882, -0.84673089, 2.20120049]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.349109649658203, + 'FR_Wheel_Angle': 24.954557418823242, + 'Location': array([ 4.66759567e+01, -3.65855408e+00, 1.86074013e-03]), + 'Rotation': array([-1.95616614e-02, 5.87809067e+01, -1.83441162e-01]), + 'Velocity': array([0.08198047, 0.27631077, 0.00070391]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.55584716796875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.06458618e+02, -2.08600845e+01, -3.05175781e-05]), + 'frame': 881, + 'frame_number': 881, + 'framesequence': 879, + 'gaze_dir': array([ 0.98058069, -0.03891584, -0.19221623]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03891584, -0.19221623]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03891584, -0.19221623]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5838313102722168, + 'throttle_input': 0.0, + 'timestamp': 17.611213076859713, + 'timestamp_carla': 17611, + 'timestamp_device': 17079, + 'timestamp_stream': 17.611213076859713, + 'transform': [array([ 7.40547085e+00, -1.44035384e-01, 1.84017175e-03]), + array([-0.01675445, -5.47003508, 0.07222808])]} +{'AngularVelocity': array([-0.44166848, -0.87287337, 2.17032814]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.368106842041016, + 'FR_Wheel_Angle': 24.972129821777344, + 'Location': array([ 4.67054672e+01, -3.62122917e+00, 1.85356848e-03]), + 'Rotation': array([-2.02036984e-02, 5.91057014e+01, -1.93817139e-01]), + 'Velocity': array([7.89450184e-02, 2.72774905e-01, 9.05990589e-07]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.2295227050781, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([607.15838623, -19.76383209, 0. ]), + 'frame': 882, + 'frame_number': 882, + 'framesequence': 880, + 'gaze_dir': array([ 0.98058069, -0.03641372, -0.19270591]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03641372, -0.19270591]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03641372, -0.19270591]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5865046977996826, + 'throttle_input': 0.0, + 'timestamp': 17.624511279165745, + 'timestamp_carla': 17624, + 'timestamp_device': 17092, + 'timestamp_stream': 17.624511279165745, + 'transform': [array([ 7.41764927e+00, -1.45468101e-01, 1.84532162e-03]), + array([-0.01745113, -5.60290956, 0.0809935 ])]} +{'AngularVelocity': array([-0.4167217 , -0.84268999, 2.11710954]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.369707107543945, + 'FR_Wheel_Angle': 24.973276138305664, + 'Location': array([ 4.67369423e+01, -3.57726383e+00, 1.85925246e-03]), + 'Rotation': array([-1.91655103e-02, 5.94831429e+01, -1.79595932e-01]), + 'Velocity': array([7.52243251e-02, 2.66513646e-01, 4.88805745e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.923095703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.07920654e+02, -1.86738281e+01, -6.10351562e-05]), + 'frame': 883, + 'frame_number': 883, + 'framesequence': 881, + 'gaze_dir': array([ 0.98058069, -0.03371236, -0.1931968 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03371236, -0.1931968 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03371236, -0.1931968 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5903317928314209, + 'throttle_input': 0.0, + 'timestamp': 17.638052478432655, + 'timestamp_carla': 17638, + 'timestamp_device': 17106, + 'timestamp_stream': 17.638052478432655, + 'transform': [array([ 7.42899084e+00, -1.48759842e-01, 1.85264589e-03]), + array([-0.01876936, -5.74026871, 0.09432694])]} +{'AngularVelocity': array([-0.43381745, -0.87875128, 2.09351349]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.371065139770508, + 'FR_Wheel_Angle': 24.97511100769043, + 'Location': array([ 4.67649803e+01, -3.54293752e+00, 1.87813514e-03]), + 'Rotation': array([-2.04769056e-02, 5.97806282e+01, -1.99035630e-01]), + 'Velocity': array([7.28593618e-02, 2.64074057e-01, 5.01775721e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.6278076171875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([608.91772461, -17.21959686, 0. ]), + 'frame': 884, + 'frame_number': 884, + 'framesequence': 882, + 'gaze_dir': array([ 0.98058069, -0.03119793, -0.19361874]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.03119793, -0.19361874]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.03119793, -0.19361874]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5945066809654236, + 'throttle_input': 0.0, + 'timestamp': 17.650699976831675, + 'timestamp_carla': 17650, + 'timestamp_device': 17119, + 'timestamp_stream': 17.650699976831675, + 'transform': [array([ 7.43908596e+00, -1.52550489e-01, 1.86351768e-03]), + array([-0.01986902, -5.87173891, 0.10402869])]} +{'AngularVelocity': array([-0.429497 , -0.88715398, 2.04968238]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.372325897216797, + 'FR_Wheel_Angle': 24.978090286254883, + 'Location': array([ 4.67944412e+01, -3.50405240e+00, 1.85406441e-03]), + 'Rotation': array([-2.02036984e-02, 6.01146431e+01, -1.95465103e-01]), + 'Velocity': array([6.95632324e-02, 2.59018600e-01, 1.51934626e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.3786926269531, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([609.87939453, -16.03416443, 0. ]), + 'frame': 885, + 'frame_number': 885, + 'framesequence': 883, + 'gaze_dir': array([ 0.98058069, -0.0286786 , -0.1940079 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0286786 , -0.1940079 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0286786 , -0.1940079 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5979675054550171, + 'throttle_input': 0.0, + 'timestamp': 17.66402967646718, + 'timestamp_carla': 17664, + 'timestamp_device': 17132, + 'timestamp_stream': 17.66402967646718, + 'transform': [array([ 7.44944429e+00, -1.56853124e-01, 1.86855311e-03]), + array([-0.02066132, -6.01242495, 0.10975212])]} +{'AngularVelocity': array([-0.44281891, -0.92451161, 2.01819253]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.373998641967773, + 'FR_Wheel_Angle': 24.979013442993164, + 'Location': array([ 4.68218269e+01, -3.47032833e+00, 1.86905614e-03]), + 'Rotation': array([-2.09345277e-02, 6.04051590e+01, -2.05352768e-01]), + 'Velocity': array([ 6.68655261e-02, 2.55542070e-01, -1.36017799e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.1476135253906, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.10744080e+02, -1.49131699e+01, 3.05175781e-05]), + 'frame': 886, + 'frame_number': 886, + 'framesequence': 884, + 'gaze_dir': array([ 0.98058069, -0.02595978, -0.19439037]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02595978, -0.19439037]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02595978, -0.19439037]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.678294878453016, + 'timestamp_carla': 17678, + 'timestamp_device': 17146, + 'timestamp_stream': 17.678294878453016, + 'transform': [array([ 7.46034288e+00, -1.61595151e-01, 1.86584471e-03]), + array([-0.02108479, -6.16376162, 0.11140019])]} +{'AngularVelocity': array([-0.41354316, -0.88403344, 1.96788156]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.37555694580078, + 'FR_Wheel_Angle': 24.98169708251953, + 'Location': array([ 4.68512840e+01, -3.43028164e+00, 1.85520889e-03]), + 'Rotation': array([-1.96163021e-02, 6.07466049e+01, -1.88507080e-01]), + 'Velocity': array([0.06372926, 0.24945138, 0.00042191]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.9166564941406, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([611.65283203, -13.73077011, 0. ]), + 'frame': 887, + 'frame_number': 887, + 'framesequence': 885, + 'gaze_dir': array([ 0.98058069, -0.0232355 , -0.1947348 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0232355 , -0.1947348 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0232355 , -0.1947348 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.691704478114843, + 'timestamp_carla': 17691, + 'timestamp_device': 17160, + 'timestamp_stream': 17.691704478114843, + 'transform': [array([ 7.47047329e+00, -1.66101351e-01, 1.86729431e-03]), + array([-0.02114626, -6.30569935, 0.10998386])]} +{'AngularVelocity': array([-0.41928926, -0.90385884, 1.92085373]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 20.219676971435547, + 'FR_Wheel_Angle': 24.3609561920166, + 'Location': array([ 4.68783913e+01, -3.39601135e+00, 1.82705640e-03]), + 'Rotation': array([-1.99919622e-02, 6.10390663e+01, -1.94854721e-01]), + 'Velocity': array([ 0.0617416 , 0.24584441, -0.00029317]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.7051086425781, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.12646851e+02, -1.25685730e+01, -3.05175781e-05]), + 'frame': 888, + 'frame_number': 888, + 'framesequence': 886, + 'gaze_dir': array([ 0.98058069, -0.02070233, -0.19502036]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.02070233, -0.19502036]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.02070233, -0.19502036]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.70480737835169, + 'timestamp_carla': 17704, + 'timestamp_device': 17173, + 'timestamp_stream': 17.70480737835169, + 'transform': [array([ 7.48028708e+00, -1.70523122e-01, 1.86878198e-03]), + array([-0.02093453, -6.44376135, 0.10673325])]} +{'AngularVelocity': array([-0.43312156, -0.9400689 , 1.38966286]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.818912506103516, + 'FR_Wheel_Angle': 16.373699188232422, + 'Location': array([ 4.69062004e+01, -3.36236668e+00, 1.86852214e-03]), + 'Rotation': array([-1.99919622e-02, 6.12845650e+01, -2.00531006e-01]), + 'Velocity': array([ 7.86026195e-02, 2.46432856e-01, -1.69897085e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.52825927734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.13600586e+02, -1.14982452e+01, 3.05175781e-05]), + 'frame': 889, + 'frame_number': 889, + 'framesequence': 887, + 'gaze_dir': array([ 0.98058069, -0.01836045, -0.19525477]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01836045, -0.19525477]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01836045, -0.19525477]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.71729937940836, + 'timestamp_carla': 17717, + 'timestamp_device': 17185, + 'timestamp_stream': 17.71729937940836, + 'transform': [array([ 7.48957443e+00, -1.74746513e-01, 1.87198631e-03]), + array([-0.02059985, -6.57471228, 0.10257781])]} +{'AngularVelocity': array([-0.41692293, -0.88925928, 1.63298714]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.769728660583496, + 'FR_Wheel_Angle': 17.43478012084961, + 'Location': array([ 4.69390907e+01, -3.31849837e+00, 1.85406441e-03]), + 'Rotation': array([-1.69661883e-02, 6.15290604e+01, -1.91131562e-01]), + 'Velocity': array([9.42947343e-02, 2.91698068e-01, 2.45952597e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.3816833496094, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.14553162e+02, -1.05214081e+01, -6.10351562e-05]), + 'frame': 890, + 'frame_number': 890, + 'framesequence': 888, + 'gaze_dir': array([ 0.98058069, -0.01542979, -0.1955082 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01542979, -0.1955082 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01542979, -0.1955082 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.73143707960844, + 'timestamp_carla': 17731, + 'timestamp_device': 17200, + 'timestamp_stream': 17.73143707960844, + 'transform': [array([ 7.50000572e+00, -1.79530486e-01, 1.86435692e-03]), + array([-0.02005344, -6.72208166, 0.09709234])]} +{'AngularVelocity': array([-0.40563682, -0.87007076, 1.50935471]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.069290161132812, + 'FR_Wheel_Angle': 16.22988510131836, + 'Location': array([ 4.69715233e+01, -3.27435040e+00, 1.82469131e-03]), + 'Rotation': array([-1.55933211e-02, 6.17975388e+01, -1.81610078e-01]), + 'Velocity': array([9.24699306e-02, 2.83432186e-01, 3.10182550e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.2224426269531, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([615.47558594, -9.26965332, 0. ]), + 'frame': 891, + 'frame_number': 891, + 'framesequence': 889, + 'gaze_dir': array([ 0.98058069, -0.01288686, -0.19569227]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.01288686, -0.19569227]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.01288686, -0.19569227]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.745127078145742, + 'timestamp_carla': 17745, + 'timestamp_device': 17213, + 'timestamp_stream': 17.745127078145742, + 'transform': [array([ 7.51003361e+00, -1.84165016e-01, 1.86000823e-03]), + array([-0.01943872, -6.86395884, 0.09148806])]} +{'AngularVelocity': array([-0.39235249, -0.84306479, 1.57670331]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.470113754272461, + 'FR_Wheel_Angle': 16.643522262573242, + 'Location': array([ 4.70040359e+01, -3.22877216e+00, 1.81870221e-03]), + 'Rotation': array([-1.45892836e-02, 6.20677338e+01, -1.75964326e-01]), + 'Velocity': array([9.12431702e-02, 2.87904084e-01, 5.77068313e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.1037292480469, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.16547241e+02, -8.22047043e+00, -3.05175781e-05]), + 'frame': 892, + 'frame_number': 892, + 'framesequence': 890, + 'gaze_dir': array([ 0.98058069, -0.010146 , -0.1958535 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.010146 , -0.1958535 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.010146 , -0.1958535 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.75895057991147, + 'timestamp_carla': 17758, + 'timestamp_device': 17227, + 'timestamp_stream': 17.75895057991147, + 'transform': [array([ 7.52008629e+00, -1.88845158e-01, 1.85504905e-03]), + array([-0.01876936, -7.00641441, 0.08576256])]} +{'AngularVelocity': array([-0.40646407, -0.8738935 , 1.56424618]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.465812683105469, + 'FR_Wheel_Angle': 16.69615364074707, + 'Location': array([ 4.70343208e+01, -3.18927264e+00, 1.83087110e-03]), + 'Rotation': array([-1.51356980e-02, 6.23049011e+01, -1.91802979e-01]), + 'Velocity': array([ 8.92930850e-02, 2.86268711e-01, -1.57346716e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.99920654296875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([617.61096191, -7.08108902, 0. ]), + 'frame': 893, + 'frame_number': 893, + 'framesequence': 891, + 'gaze_dir': array([ 0.98058069, -0.00720729, -0.19598365]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00720729, -0.19598365]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00720729, -0.19598365]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.773810677230358, + 'timestamp_carla': 17773, + 'timestamp_device': 17242, + 'timestamp_stream': 17.773810677230358, + 'transform': [array([ 7.53081226e+00, -1.93875536e-01, 1.84314721e-03]), + array([-0.01803853, -7.15863752, 0.07969996])]} +{'AngularVelocity': array([-0.41967714, -0.9128651 , 1.54070652]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.447579383850098, + 'FR_Wheel_Angle': 16.680973052978516, + 'Location': array([ 4.70644188e+01, -3.14952636e+00, 1.83190103e-03]), + 'Rotation': array([-1.53201139e-02, 6.25431252e+01, -1.97143555e-01]), + 'Velocity': array([ 0.08656808, 0.28286603, -0.00037333]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.9135437011719, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([618.71697998, -5.85779572, 0. ]), + 'frame': 894, + 'frame_number': 894, + 'framesequence': 892, + 'gaze_dir': array([ 0.98058069, -0.00426695, -0.19606969]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00426695, -0.19606969]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00426695, -0.19606969]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.78888537734747, + 'timestamp_carla': 17788, + 'timestamp_device': 17257, + 'timestamp_stream': 17.78888537734747, + 'transform': [array([ 7.54431915e+00, -1.95858493e-01, 1.84757228e-03]), + array([-0.0189811 , -7.30960846, 0.09115089])]} +{'AngularVelocity': array([-0.42235479, -0.92792296, 1.52186131]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.440717697143555, + 'FR_Wheel_Angle': 16.680030822753906, + 'Location': array([ 4.70938072e+01, -3.11067367e+00, 1.86047307e-03]), + 'Rotation': array([-1.54772075e-02, 6.27754860e+01, -2.01599091e-01]), + 'Velocity': array([8.42688158e-02, 2.79968590e-01, 1.68895713e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.8536376953125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([619.92956543, -4.65079117, 0. ]), + 'frame': 895, + 'frame_number': 895, + 'framesequence': 893, + 'gaze_dir': array([ 0.98058069, -0.00152166, -0.19611022]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.00152166, -0.19611022]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.00152166, -0.19611022]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.802603479474783, + 'timestamp_carla': 17802, + 'timestamp_device': 17271, + 'timestamp_stream': 17.802603479474783, + 'transform': [array([ 7.55542755e+00, -1.99552938e-01, 1.86344143e-03]), + array([-0.02038128, -7.44861555, 0.10507185])]} +{'AngularVelocity': array([-0.42460757, -0.94211513, 1.5042311 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.441862106323242, + 'FR_Wheel_Angle': 16.680940628051758, + 'Location': array([ 4.71230659e+01, -3.07268834e+00, 1.84273475e-03]), + 'Rotation': array([-1.56274717e-02, 6.30030632e+01, -2.05017090e-01]), + 'Velocity': array([ 8.20262954e-02, 2.77115494e-01, -1.81484225e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.8305358886719, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([621.45422363, -3.2372818 , 0. ]), + 'frame': 896, + 'frame_number': 896, + 'framesequence': 894, + 'gaze_dir': array([ 0.98058069, 0.00102793, -0.19611344]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00102793, -0.19611344]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00102793, -0.19611344]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.81596937775612, + 'timestamp_carla': 17815, + 'timestamp_device': 17284, + 'timestamp_stream': 17.81596937775612, + 'transform': [array([ 7.56571388e+00, -2.03868255e-01, 1.87786098e-03]), + array([-0.0215151 , -7.58683109, 0.1148818 ])]} +{'AngularVelocity': array([-0.40000191, -0.90143818, 1.4767772 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.442657470703125, + 'FR_Wheel_Angle': 16.682680130004883, + 'Location': array([ 4.71543732e+01, -3.02857757e+00, 1.82785746e-03]), + 'Rotation': array([-1.48351705e-02, 6.32639885e+01, -1.89361542e-01]), + 'Velocity': array([ 0.0793911 , 0.27232313, -0.00052582]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.83294677734375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([622.75891113, -2.1168251 , 0. ]), + 'frame': 897, + 'frame_number': 897, + 'framesequence': 895, + 'gaze_dir': array([ 0.98058069, 0.00338136, -0.19608697]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00338136, -0.19608697]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00338136, -0.19608697]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5989745855331421, + 'throttle_input': 0.0, + 'timestamp': 17.82845927774906, + 'timestamp_carla': 17828, + 'timestamp_device': 17296, + 'timestamp_stream': 17.82845927774906, + 'transform': [array([ 7.57509184e+00, -2.08136365e-01, 1.89197541e-03]), + array([-0.02219128, -7.71698904, 0.11960248])]} +{'AngularVelocity': array([-0.40536398, -0.9187268 , 1.46492124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.443551063537598, + 'FR_Wheel_Angle': 16.683042526245117, + 'Location': array([ 4.71827049e+01, -2.99163508e+00, 1.86215155e-03]), + 'Rotation': array([-1.53815849e-02, 6.34839821e+01, -2.00439423e-01]), + 'Velocity': array([7.76349381e-02, 2.70492047e-01, 3.37314596e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.8516845703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 6.23994385e+02, -1.15335846e+00, 3.05175781e-05]), + 'frame': 898, + 'frame_number': 898, + 'framesequence': 896, + 'gaze_dir': array([ 0.98058069, 0.00632206, -0.1960142 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00632206, -0.1960142 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00632206, -0.1960142 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.598370373249054, + 'throttle_input': 0.0, + 'timestamp': 17.842168878763914, + 'timestamp_carla': 17842, + 'timestamp_device': 17311, + 'timestamp_stream': 17.842168878763914, + 'transform': [array([ 7.58523321e+00, -2.12919846e-01, 1.89567567e-03]), + array([-0.02249181, -7.85980988, 0.12049915])]} +{'AngularVelocity': array([-0.40285453, -0.92120135, 1.44822609]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.443896293640137, + 'FR_Wheel_Angle': 16.684600830078125, + 'Location': array([ 4.72118301e+01, -2.95277333e+00, 1.85219524e-03]), + 'Rotation': array([-1.54772075e-02, 6.37145538e+01, -2.03857407e-01]), + 'Velocity': array([ 7.56308883e-02, 2.67733783e-01, -1.38230316e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.8959655761719, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.25208313e+02, 6.03523254e-02, -3.05175781e-05]), + 'frame': 899, + 'frame_number': 899, + 'framesequence': 897, + 'gaze_dir': array([ 0.98058069, 0.00906553, -0.19590649]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.00906553, -0.19590649]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.00906553, -0.19590649]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5981322526931763, + 'throttle_input': 0.0, + 'timestamp': 17.856596879661083, + 'timestamp_carla': 17856, + 'timestamp_device': 17325, + 'timestamp_stream': 17.856596879661083, + 'transform': [array([ 7.59578800e+00, -2.17993021e-01, 1.89239497e-03]), + array([-0.02243034, -8.00943947, 0.11809762])]} +{'AngularVelocity': array([-0.40505436, -0.94207567, 1.42470658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 14.444916725158691, + 'FR_Wheel_Angle': 16.686359405517578, + 'Location': array([ 4.72403755e+01, -2.91450191e+00, 1.82224985e-03]), + 'Rotation': array([-1.52859623e-02, 6.39413452e+01, -1.99218750e-01]), + 'Velocity': array([ 7.29839057e-02, 2.63775736e-01, -1.18393895e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 461.9586486816406, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([626.51947021, 1.15773773, 0. ]), + 'frame': 900, + 'frame_number': 900, + 'framesequence': 898, + 'gaze_dir': array([ 0.98058069, 0.01161158, -0.1957721 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.01161158, -0.1957721 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.01161158, -0.1957721 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5983337163925171, + 'throttle_input': 0.0, + 'timestamp': 17.86965837702155, + 'timestamp_carla': 17869, + 'timestamp_device': 17338, + 'timestamp_stream': 17.86965837702155, + 'transform': [array([ 7.60526085e+00, -2.22598359e-01, 1.89590454e-03]), + array([-0.02212981, -8.14420414, 0.11415737])]} +{'AngularVelocity': array([-0.40605563, -0.95217985, 1.20150924]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 12.412015914916992, + 'FR_Wheel_Angle': 13.202351570129395, + 'Location': array([ 4.72680511e+01, -2.87830353e+00, 1.81362859e-03]), + 'Rotation': array([-1.53815849e-02, 6.41480713e+01, -2.02667236e-01]), + 'Velocity': array([0.07731937, 0.25994748, 0.00042079]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.0360107421875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.27886353e+02, 2.14822388e+00, -3.05175781e-05]), + 'frame': 901, + 'frame_number': 901, + 'framesequence': 899, + 'gaze_dir': array([ 0.98058069, 0.01435114, -0.19559035]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.01435114, -0.19559035]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.01435114, -0.19559035]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5986999273300171, + 'throttle_input': 0.0, + 'timestamp': 17.884035278111696, + 'timestamp_carla': 17884, + 'timestamp_device': 17352, + 'timestamp_stream': 17.884035278111696, + 'transform': [array([ 7.61560154e+00, -2.27673054e-01, 1.88949576e-03]), + array([-0.02161072, -8.29175663, 0.10856297])]} +{'AngularVelocity': array([-0.40926424, -0.95145565, 0.61337584]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 6.014530181884766, + 'FR_Wheel_Angle': 6.422034740447998, + 'Location': array([ 4.72985687e+01, -2.83902287e+00, 1.79592846e-03]), + 'Rotation': array([-1.40975099e-02, 6.42864685e+01, -2.01568604e-01]), + 'Velocity': array([0.10464239, 0.27735198, 0.00028888]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.1423034667969, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([629.19049072, 3.23466492, 0. ]), + 'frame': 902, + 'frame_number': 902, + 'framesequence': 900, + 'gaze_dir': array([ 0.98058069, 0.0170879 , -0.19537027]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.0170879 , -0.19537027]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.0170879 , -0.19537027]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5991759896278381, + 'throttle_input': 0.0, + 'timestamp': 17.898250676691532, + 'timestamp_carla': 17898, + 'timestamp_device': 17366, + 'timestamp_stream': 17.898250676691532, + 'transform': [array([ 7.62574434e+00, -2.32693434e-01, 1.88381190e-03]), + array([-0.02093453, -8.43689919, 0.10243824])]} +{'AngularVelocity': array([-0.40826634, -0.9257493 , 1.00082946]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 8.405670166015625, + 'FR_Wheel_Angle': 8.891714096069336, + 'Location': array([ 4.73313713e+01, -2.79313803e+00, 1.79062597e-03]), + 'Rotation': array([-1.19050192e-02, 6.44235764e+01, -2.00256318e-01]), + 'Velocity': array([0.11078283, 0.31814614, 0.00050372]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.2703857421875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.30619019e+02, 4.29787064e+00, -3.05175781e-05]), + 'frame': 903, + 'frame_number': 903, + 'framesequence': 901, + 'gaze_dir': array([ 0.98058069, 0.01982131, -0.1951119 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.01982131, -0.1951119 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.01982131, -0.1951119 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.59967041015625, + 'throttle_input': 0.0, + 'timestamp': 17.912295177578926, + 'timestamp_carla': 17912, + 'timestamp_device': 17380, + 'timestamp_stream': 17.912295177578926, + 'transform': [array([ 7.63568783e+00, -2.37654239e-01, 1.87904353e-03]), + array([-0.0202037 , -8.57953835, 0.09618477])]} +{'AngularVelocity': array([-0.38340476, -0.87147319, 0.86300206]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.66058874130249, + 'FR_Wheel_Angle': 8.35872745513916, + 'Location': array([ 4.73671379e+01, -2.74170256e+00, 1.81946508e-03]), + 'Rotation': array([-1.07985288e-02, 6.45840454e+01, -1.83685288e-01]), + 'Velocity': array([1.09411009e-01, 3.06848586e-01, 5.64098355e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.421630859375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([6.32059631e+02, 5.35487366e+00, 3.05175781e-05]), + 'frame': 904, + 'frame_number': 904, + 'framesequence': 902, + 'gaze_dir': array([ 0.98058069, 0.02274553, -0.19479266]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.02274553, -0.19479266]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.02274553, -0.19479266]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.92685367912054, + 'timestamp_carla': 17926, + 'timestamp_device': 17395, + 'timestamp_stream': 17.92685367912054, + 'transform': [array([ 7.64591599e+00, -2.42795825e-01, 1.87061308e-03]), + array([-0.01943872, -8.72663403, 0.08971504])]} +{'AngularVelocity': array([-0.40104911, -0.90870339, 0.86788362]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.6386895179748535, + 'FR_Wheel_Angle': 8.248347282409668, + 'Location': array([ 4.73987541e+01, -2.70030975e+00, 1.82366127e-03]), + 'Rotation': array([-1.09283021e-02, 6.47157288e+01, -2.00561479e-01]), + 'Velocity': array([ 1.09244660e-01, 3.09052169e-01, -1.80997842e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.6103210449219, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([633.54125977, 6.49282074, 0. ]), + 'frame': 905, + 'frame_number': 905, + 'framesequence': 903, + 'gaze_dir': array([ 0.98058069, 0.0254703 , -0.19445516]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.0254703 , -0.19445516]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.0254703 , -0.19445516]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.94073547795415, + 'timestamp_carla': 17940, + 'timestamp_device': 17409, + 'timestamp_stream': 17.94073547795415, + 'transform': [array([ 7.65836143e+00, -2.44515970e-01, 1.87934877e-03]), + array([-0.0202037 , -8.86341572, 0.0995663 ])]} +{'AngularVelocity': array([-0.39912227, -0.90889323, 0.87029433]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.696598052978516, + 'FR_Wheel_Angle': 8.299593925476074, + 'Location': array([ 4.74322319e+01, -2.65409541e+00, 1.81103463e-03]), + 'Rotation': array([-1.07712075e-02, 6.48601456e+01, -1.99645981e-01]), + 'Velocity': array([0.10786568, 0.30825609, 0.00031616]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 462.810302734375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([635.05993652, 7.52869797, 0. ]), + 'frame': 906, + 'frame_number': 906, + 'framesequence': 904, + 'gaze_dir': array([ 0.98058069, 0.02819007, -0.19407953]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.02819007, -0.19407953]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.02819007, -0.19407953]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.955340776592493, + 'timestamp_carla': 17955, + 'timestamp_device': 17423, + 'timestamp_stream': 17.955340776592493, + 'transform': [array([ 7.67000294e+00, -2.48541832e-01, 1.88693998e-03]), + array([-0.02169951, -9.00861931, 0.11499541])]} +{'AngularVelocity': array([-0.41295037, -0.94468713, 0.8701939 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.727639675140381, + 'FR_Wheel_Angle': 8.33548355102539, + 'Location': array([ 4.74635735e+01, -2.61318970e+00, 1.80767768e-03]), + 'Rotation': array([-1.10512450e-02, 6.49893951e+01, -2.09320053e-01]), + 'Velocity': array([1.06375672e-01, 3.07379723e-01, 2.92606361e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.0364990234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.36829712e+02, 8.87617874e+00, -3.05175781e-05]), + 'frame': 907, + 'frame_number': 907, + 'framesequence': 905, + 'gaze_dir': array([ 0.98058069, 0.03090432, -0.19366586]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03090432, -0.19366586]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03090432, -0.19366586]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.96872777864337, + 'timestamp_carla': 17968, + 'timestamp_device': 17437, + 'timestamp_stream': 17.96872777864337, + 'transform': [array([ 7.68005705e+00, -2.53027797e-01, 1.89968105e-03]), + array([-0.02286064, -9.1446352 , 0.12524946])]} +{'AngularVelocity': array([-0.39359871, -0.9095903 , 0.8580367 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.727972030639648, + 'FR_Wheel_Angle': 8.33601188659668, + 'Location': array([ 4.74980507e+01, -2.56375384e+00, 1.80805917e-03]), + 'Rotation': array([-1.05594723e-02, 6.51429901e+01, -1.91406250e-01]), + 'Velocity': array([ 1.04113393e-01, 3.03296477e-01, -1.62744516e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.28558349609375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([638.55639648, 10.00493622, 0. ]), + 'frame': 908, + 'frame_number': 908, + 'framesequence': 906, + 'gaze_dir': array([ 0.98058069, 0.03322623, -0.19328105]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03322623, -0.19328105]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03322623, -0.19328105]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.981358379125595, + 'timestamp_carla': 17981, + 'timestamp_device': 17449, + 'timestamp_stream': 17.981358379125595, + 'transform': [array([ 7.68928194e+00, -2.57517040e-01, 1.91184995e-03]), + array([-0.02355732, -9.27427387, 0.1301609 ])]} +{'AngularVelocity': array([-0.39401105, -0.91462415, 0.85496825]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.728366374969482, + 'FR_Wheel_Angle': 8.336249351501465, + 'Location': array([ 4.75297394e+01, -2.52089024e+00, 1.80527440e-03]), + 'Rotation': array([-1.06824152e-02, 6.52773972e+01, -1.97021484e-01]), + 'Velocity': array([1.03032470e-01, 3.02459657e-01, 1.09601016e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.518798828125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([640.07836914, 10.88871384, 0. ]), + 'frame': 909, + 'frame_number': 909, + 'framesequence': 907, + 'gaze_dir': array([ 0.98058069, 0.03592881, -0.19279695]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03592881, -0.19279695]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03592881, -0.19279695]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 17.995358377695084, + 'timestamp_carla': 17995, + 'timestamp_device': 17463, + 'timestamp_stream': 17.995358377695084, + 'transform': [array([ 7.69933748e+00, -2.62601376e-01, 1.91253657e-03]), + array([-0.02383736, -9.41810226, 0.13090536])]} +{'AngularVelocity': array([-0.37388718, -0.87602174, 0.84494662]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.72859525680542, + 'FR_Wheel_Angle': 8.336823463439941, + 'Location': array([ 4.75639572e+01, -2.47140598e+00, 1.74645183e-03]), + 'Rotation': array([-1.03477361e-02, 6.54304810e+01, -1.83593735e-01]), + 'Velocity': array([1.01169363e-01, 2.99087256e-01, 5.16319269e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 463.8121643066406, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([641.61535645, 11.92219162, 0. ]), + 'frame': 910, + 'frame_number': 910, + 'framesequence': 908, + 'gaze_dir': array([ 0.98058069, 0.03862435, -0.19227508]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.03862435, -0.19227508]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.03862435, -0.19227508]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.00945097953081, + 'timestamp_carla': 18009, + 'timestamp_device': 17477, + 'timestamp_stream': 18.00945097953081, + 'transform': [array([ 7.70934248e+00, -2.67758340e-01, 1.91024772e-03]), + array([-0.02374174, -9.56239033, 0.12825222])]} +{'AngularVelocity': array([-0.37726185, -0.88901395, 0.84098607]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.729056358337402, + 'FR_Wheel_Angle': 8.33724594116211, + 'Location': array([ 4.75957184e+01, -2.42727232e+00, 1.78742164e-03]), + 'Rotation': array([-1.03750564e-02, 6.55677719e+01, -1.88079834e-01]), + 'Velocity': array([9.98877138e-02, 2.97963083e-01, 1.39355659e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.12750244140625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([643.27618408, 12.91995621, 0. ]), + 'frame': 911, + 'frame_number': 911, + 'framesequence': 909, + 'gaze_dir': array([ 0.98058069, 0.04131231, -0.19171551]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.04131231, -0.19171551]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.04131231, -0.19171551]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.023511476814747, + 'timestamp_carla': 18023, + 'timestamp_device': 17491, + 'timestamp_stream': 18.023511476814747, + 'transform': [array([ 7.71923256e+00, -2.72915989e-01, 1.90654746e-03]), + array([-0.02333876, -9.70558071, 0.12346904])]} +{'AngularVelocity': array([-0.36220405, -0.86029375, 0.83321565]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.729170322418213, + 'FR_Wheel_Angle': 8.33754825592041, + 'Location': array([ 4.76291580e+01, -2.37807226e+00, 1.77941076e-03]), + 'Rotation': array([-1.01633212e-02, 6.57192383e+01, -1.80358857e-01]), + 'Velocity': array([9.83217433e-02, 2.95391500e-01, 8.01038695e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.46612548828125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.44964966e+02, 1.39031677e+01, -3.05175781e-05]), + 'frame': 912, + 'frame_number': 912, + 'framesequence': 910, + 'gaze_dir': array([ 0.98058069, 0.04418317, -0.19107431]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.04418317, -0.19107431]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.04418317, -0.19107431]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.03813747689128, + 'timestamp_carla': 18038, + 'timestamp_device': 17506, + 'timestamp_stream': 18.03813747689128, + 'transform': [array([ 7.72943211e+00, -2.78283834e-01, 1.89777371e-03]), + array([-0.02273087, -9.85365105, 0.11717042])]} +{'AngularVelocity': array([-0.37746149, -0.89926445, 0.82481974]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 7.398146152496338, + 'FR_Wheel_Angle': 7.435213088989258, + 'Location': array([ 4.76591873e+01, -2.33764791e+00, 1.78623910e-03]), + 'Rotation': array([-1.06209433e-02, 6.58452759e+01, -1.97418228e-01]), + 'Velocity': array([0.09774283, 0.29568738, 0.00052841]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 464.8551940917969, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([646.71948242, 14.95885086, 0. ]), + 'frame': 913, + 'frame_number': 913, + 'framesequence': 911, + 'gaze_dir': array([ 0.98058069, 0.04666343, -0.19048379]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.04666343, -0.19048379]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.04666343, -0.19048379]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.051278978586197, + 'timestamp_carla': 18051, + 'timestamp_device': 17519, + 'timestamp_stream': 18.051278978586197, + 'transform': [array([ 7.73852825e+00, -2.83105880e-01, 1.89853669e-03]), + array([-0.02206151, -9.98594475, 0.11101473])]} +{'AngularVelocity': array([-3.76205653e-01, -8.97036672e-01, 1.79589522e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.76942520e+01, -2.28917265e+00, 1.82045694e-03]), + 'Rotation': array([-9.91743430e-03, 6.59223938e+01, -1.84661865e-01]), + 'Velocity': array([1.23048373e-01, 2.92961657e-01, 2.21204755e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.21417236328125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([6.48451111e+02, 1.58281670e+01, 3.05175781e-05]), + 'frame': 914, + 'frame_number': 914, + 'framesequence': 912, + 'gaze_dir': array([ 0.98058069, 0.04951521, -0.18976247]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.04951521, -0.18976247]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.04951521, -0.18976247]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.06556297838688, + 'timestamp_carla': 18065, + 'timestamp_device': 17534, + 'timestamp_stream': 18.06556297838688, + 'transform': [array([ 7.74834108e+00, -2.88343340e-01, 1.89079286e-03]), + array([ -0.02126921, -10.12892056, 0.10404754])]} +{'AngularVelocity': array([-3.87852550e-01, -8.91103506e-01, -9.96544600e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.77307930e+01, -2.24174500e+00, 1.78940536e-03]), + 'Rotation': array([-7.69079244e-03, 6.59088211e+01, -1.96990922e-01]), + 'Velocity': array([ 1.46840930e-01, 3.45420629e-01, -6.67619679e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 465.65509033203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([650.18847656, 16.87462997, 0. ]), + 'frame': 915, + 'frame_number': 915, + 'framesequence': 913, + 'gaze_dir': array([ 0.98058057, 0.05216694, -0.18905067]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.05216694, -0.18905067]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.05216694, -0.18905067]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.079700879752636, + 'timestamp_carla': 18079, + 'timestamp_device': 17548, + 'timestamp_stream': 18.079700879752636, + 'transform': [array([ 7.75798130e+00, -2.93522805e-01, 1.88415521e-03]), + array([ -0.02044276, -10.26960754, 0.09720033])]} +{'AngularVelocity': array([-3.93823206e-01, -8.93451929e-01, 2.53968369e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.77693596e+01, -2.18904710e+00, 1.77586311e-03]), + 'Rotation': array([-6.68675499e-03, 6.59083176e+01, -1.95159912e-01]), + 'Velocity': array([ 1.46985009e-01, 3.45895767e-01, -3.09844007e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.0906677246094, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([651.99084473, 17.81031799, 0. ]), + 'frame': 916, + 'frame_number': 916, + 'framesequence': 914, + 'gaze_dir': array([ 0.98058069, 0.05499697, -0.18824688]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.05499697, -0.18824688]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.05499697, -0.18824688]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.09474767744541, + 'timestamp_carla': 18094, + 'timestamp_device': 17563, + 'timestamp_stream': 18.09474767744541, + 'transform': [array([ 7.77124691e+00, -2.95629293e-01, 1.88323972e-03]), + array([ -0.02133068, -10.41508389, 0.10864434])]} +{'AngularVelocity': array([-3.98616672e-01, -8.98671508e-01, 1.33598205e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.78073082e+01, -2.13767767e+00, 1.80138345e-03]), + 'Rotation': array([-6.25645276e-03, 6.59077682e+01, -1.91589326e-01]), + 'Velocity': array([1.46786988e-01, 3.45766634e-01, 1.19943616e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 466.58392333984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([653.86053467, 18.81871796, 0. ]), + 'frame': 917, + 'frame_number': 917, + 'framesequence': 915, + 'gaze_dir': array([ 0.98058069, 0.05781426, -0.18740082]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.05781426, -0.18740082]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.05781426, -0.18740082]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.109683077782393, + 'timestamp_carla': 18109, + 'timestamp_device': 17578, + 'timestamp_stream': 18.109683077782393, + 'transform': [array([ 7.78281164e+00, -3.00024658e-01, 1.88846583e-03]), + array([ -0.02288796, -10.56105042, 0.12455926])]} +{'AngularVelocity': array([-4.05487329e-01, -9.10961151e-01, 1.67220651e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.78435822e+01, -2.09005928e+00, 1.78169960e-03]), + 'Rotation': array([-6.13350933e-03, 6.59072800e+01, -2.00256318e-01]), + 'Velocity': array([ 1.47692651e-01, 3.47788572e-01, -1.67584411e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.09881591796875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.56129578e+02, 2.01335793e+01, -3.05175781e-05]), + 'frame': 918, + 'frame_number': 918, + 'framesequence': 916, + 'gaze_dir': array([ 0.98058069, 0.06024561, -0.18663339]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.06024561, -0.18663339]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.06024561, -0.18663339]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.123401179909706, + 'timestamp_carla': 18123, + 'timestamp_device': 17591, + 'timestamp_stream': 18.123401179909706, + 'transform': [array([ 7.79279041e+00, -3.04841131e-01, 1.89945218e-03]), + array([ -0.02404226, -10.69822598, 0.134611 ])]} +{'AngularVelocity': array([-4.05087799e-01, -9.09321904e-01, 1.40168295e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.78815842e+01, -2.03820300e+00, 1.79646246e-03]), + 'Rotation': array([-6.13350933e-03, 6.59067154e+01, -1.92657471e-01]), + 'Velocity': array([ 1.46870345e-01, 3.46172780e-01, -4.14752940e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 467.5653991699219, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([658.14929199, 21.04867554, 0. ]), + 'frame': 919, + 'frame_number': 919, + 'framesequence': 917, + 'gaze_dir': array([ 0.98058069, 0.06266642, -0.18583453]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.06266642, -0.18583453]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.06266642, -0.18583453]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.13642617687583, + 'timestamp_carla': 18136, + 'timestamp_device': 17604, + 'timestamp_stream': 18.13642617687583, + 'transform': [array([ 7.80199814e+00, -3.09656829e-01, 1.90982816e-03]), + array([ -0.02469113, -10.82975864, 0.13895501])]} +{'AngularVelocity': array([-4.07056779e-01, -9.12522197e-01, 1.03583932e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.79176064e+01, -1.99114120e+00, 1.79054972e-03]), + 'Rotation': array([-6.13350933e-03, 6.59061737e+01, -2.02423081e-01]), + 'Velocity': array([1.47891343e-01, 3.48205060e-01, 1.15780829e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.05560302734375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([660.0333252 , 21.89334869, 0. ]), + 'frame': 920, + 'frame_number': 920, + 'framesequence': 918, + 'gaze_dir': array([ 0.98058057, 0.06507699, -0.18500414]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.06507699, -0.18500414]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.06507699, -0.18500414]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.149532079696655, + 'timestamp_carla': 18149, + 'timestamp_device': 17617, + 'timestamp_stream': 18.149532079696655, + 'transform': [array([ 7.81111622e+00, -3.14587057e-01, 1.91593170e-03]), + array([ -0.02489604, -10.96217632, 0.13908477])]} +{'AngularVelocity': array([-3.90240401e-01, -8.75216424e-01, 1.57647682e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.79581032e+01, -1.93424988e+00, 1.78044080e-03]), + 'Rotation': array([-6.13350933e-03, 6.59057693e+01, -1.86187729e-01]), + 'Velocity': array([1.46999225e-01, 3.45770717e-01, 1.51844026e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 468.5684814453125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([661.86486816, 22.71691895, 0. ]), + 'frame': 921, + 'frame_number': 921, + 'framesequence': 919, + 'gaze_dir': array([ 0.98058069, 0.06766058, -0.18407498]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.06766058, -0.18407498]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.06766058, -0.18407498]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.16323307901621, + 'timestamp_carla': 18163, + 'timestamp_device': 17631, + 'timestamp_stream': 18.16323307901621, + 'transform': [array([ 7.82054186e+00, -3.19772154e-01, 1.91547384e-03]), + array([ -0.02474577, -11.10011387, 0.13600436])]} +{'AngularVelocity': array([-4.01911050e-01, -9.00843620e-01, 3.09136453e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.79948769e+01, -1.88514459e+00, 1.76125288e-03]), + 'Rotation': array([-6.13350933e-03, 6.59051743e+01, -1.93603516e-01]), + 'Velocity': array([ 0.14751162, 0.3472406 , -0.00114822]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 469.14532470703125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([663.78125 , 23.59960175, 0. ]), + 'frame': 922, + 'frame_number': 922, + 'framesequence': 920, + 'gaze_dir': array([ 0.98058057, 0.0702309 , -0.18310973]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.0702309 , -0.18310973]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.0702309 , -0.18310973]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.17709608003497, + 'timestamp_carla': 18177, + 'timestamp_device': 17645, + 'timestamp_stream': 18.17709608003497, + 'transform': [array([ 7.82999134e+00, -3.25027853e-01, 1.91184995e-03]), + array([ -0.0243223 , -11.2389679 , 0.13079995])]} +{'AngularVelocity': array([-4.06350166e-01, -9.10830855e-01, 5.47157470e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.80316238e+01, -1.83579862e+00, 1.82213541e-03]), + 'Rotation': array([-6.13350933e-03, 6.59046555e+01, -1.97021484e-01]), + 'Velocity': array([ 1.47473872e-01, 3.47328097e-01, -2.00757975e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 469.746826171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([6.65766357e+02, 2.44568367e+01, 3.05175781e-05]), + 'frame': 923, + 'frame_number': 923, + 'framesequence': 921, + 'gaze_dir': array([ 0.98058069, 0.07278746, -0.1821086 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.07278746, -0.1821086 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.07278746, -0.1821086 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.190683878958225, + 'timestamp_carla': 18190, + 'timestamp_device': 17659, + 'timestamp_stream': 18.190683878958225, + 'transform': [array([ 7.83917713e+00, -3.30179662e-01, 1.90891267e-03]), + array([ -0.02371442, -11.37431431, 0.12454718])]} +{'AngularVelocity': array([-4.00459379e-01, -8.97902608e-01, 1.45671829e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.80698318e+01, -1.78358567e+00, 1.81648962e-03]), + 'Rotation': array([-6.13350933e-03, 6.59041138e+01, -1.90093979e-01]), + 'Velocity': array([ 1.46928519e-01, 3.46020341e-01, -1.77011490e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.3731689453125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.67787842e+02, 2.52971840e+01, -3.05175781e-05]), + 'frame': 924, + 'frame_number': 924, + 'framesequence': 922, + 'gaze_dir': array([ 0.98058057, 0.07514874, -0.18114695]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.07514874, -0.18114695]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.07514874, -0.18114695]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.203786477446556, + 'timestamp_carla': 18203, + 'timestamp_device': 17672, + 'timestamp_stream': 18.203786477446556, + 'transform': [array([ 7.84796906e+00, -3.35144579e-01, 1.90757751e-03]), + array([ -0.02298358, -11.50410748, 0.11797689])]} +{'AngularVelocity': array([-3.96910995e-01, -8.89684141e-01, 1.14408531e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 4.81075439e+01, -1.73283851e+00, 1.80889841e-03]), + 'Rotation': array([-6.13350933e-03, 6.59035492e+01, -1.90765366e-01]), + 'Velocity': array([ 1.47262052e-01, 3.46510142e-01, -5.64670554e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 470.977294921875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([669.74224854, 26.05241776, 0. ]), + 'frame': 925, + 'frame_number': 925, + 'framesequence': 923, + 'gaze_dir': array([ 0.98058069, 0.07785729, -0.17999944]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.07785729, -0.17999944]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.07785729, -0.17999944]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.21783607825637, + 'timestamp_carla': 18217, + 'timestamp_device': 17687, + 'timestamp_stream': 18.21783607825637, + 'transform': [array([ 7.85732651e+00, -3.40462863e-01, 1.89937593e-03]), + array([ -0.02212981, -11.6425066 , 0.11066832])]} +{'AngularVelocity': array([-0.41333911, -0.92597073, -0.18799843]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -1.8089916706085205, + 'FR_Wheel_Angle': -2.448281764984131, + 'Location': array([ 4.81443291e+01, -1.68411541e+00, 1.78101298e-03]), + 'Rotation': array([-6.13350933e-03, 6.59010239e+01, -1.96502671e-01]), + 'Velocity': array([1.52119026e-01, 3.45376909e-01, 7.32421831e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 471.7005310058594, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([671.82409668, 26.95623398, 0. ]), + 'frame': 926, + 'frame_number': 926, + 'framesequence': 924, + 'gaze_dir': array([ 0.98058069, 0.08036955, -0.17889185]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08036955, -0.17889185]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08036955, -0.17889185]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.23248367756605, + 'timestamp_carla': 18232, + 'timestamp_device': 17701, + 'timestamp_stream': 18.23248367756605, + 'transform': [array([ 7.86700726e+00, -3.46000671e-01, 1.88724510e-03]), + array([ -0.02117359, -11.7859354 , 0.10308683])]} +{'AngularVelocity': array([-0.40742636, -0.89592516, -1.2866987 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -10.203916549682617, + 'FR_Wheel_Angle': -9.359634399414062, + 'Location': array([ 4.81867523e+01, -1.63026857e+00, 1.77895301e-03]), + 'Rotation': array([-5.37535874e-03, 6.57680664e+01, -1.84448227e-01]), + 'Velocity': array([1.90758303e-01, 3.47628772e-01, 1.12600326e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 472.40069580078125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([6.73933594e+02, 2.77528496e+01, 3.05175781e-05]), + 'frame': 927, + 'frame_number': 927, + 'framesequence': 925, + 'gaze_dir': array([ 0.98058069, 0.08286607, -0.17774919]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08286607, -0.17774919]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08286607, -0.17774919]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.246702179312706, + 'timestamp_carla': 18246, + 'timestamp_device': 17715, + 'timestamp_stream': 18.246702179312706, + 'transform': [array([ 7.87952518e+00, -3.47918391e-01, 1.89456937e-03]), + array([ -0.02193857, -11.92088699, 0.11348095])]} +{'AngularVelocity': array([-0.38953304, -0.82116795, -1.06459427]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -7.402393817901611, + 'FR_Wheel_Angle': -7.06499719619751, + 'Location': array([ 4.82348022e+01, -1.56741941e+00, 1.74927467e-03]), + 'Rotation': array([-3.32630193e-03, 6.55514526e+01, -1.74682617e-01]), + 'Velocity': array([ 2.07619950e-01, 3.95394176e-01, -2.67539028e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 473.125244140625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([676.11328125, 28.52439117, 0. ]), + 'frame': 928, + 'frame_number': 928, + 'framesequence': 926, + 'gaze_dir': array([ 0.98058069, 0.08516982, -0.1766569 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08516982, -0.1766569 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08516982, -0.1766569 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.26053797826171, + 'timestamp_carla': 18260, + 'timestamp_device': 17728, + 'timestamp_stream': 18.26053797826171, + 'transform': [array([ 7.89013767e+00, -3.51946563e-01, 1.90746307e-03]), + array([ -0.02340023, -12.05305767, 0.12892359])]} +{'AngularVelocity': array([-0.39421898, -0.81980681, -1.22606969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.59556770324707, + 'FR_Wheel_Angle': -7.843261241912842, + 'Location': array([ 4.82798805e+01, -1.51056719e+00, 1.76266429e-03]), + 'Rotation': array([-2.62279250e-03, 6.53572845e+01, -1.81091294e-01]), + 'Velocity': array([0.21213609, 0.38966304, 0.00044951]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 473.8096008300781, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([678.51367188, 29.55542755, 0. ]), + 'frame': 929, + 'frame_number': 929, + 'framesequence': 927, + 'gaze_dir': array([ 0.98058069, 0.08763459, -0.17544726]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.08763459, -0.17544726]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.08763459, -0.17544726]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.273678179830313, + 'timestamp_carla': 18273, + 'timestamp_device': 17742, + 'timestamp_stream': 18.273678179830313, + 'transform': [array([ 7.89951134e+00, -3.56615126e-01, 1.92119589e-03]), + array([ -0.02462966, -12.18159771, 0.13993073])]} +{'AngularVelocity': array([-0.40541422, -0.8292793 , -1.21320283]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.412858963012695, + 'FR_Wheel_Angle': -7.806940078735352, + 'Location': array([ 4.83268852e+01, -1.45059431e+00, 1.75446272e-03]), + 'Rotation': array([-2.28811335e-03, 6.51548691e+01, -1.78924531e-01]), + 'Velocity': array([2.15361014e-01, 3.94352704e-01, 1.23004909e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 474.5675048828125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.80826050e+02, 3.04315300e+01, -3.05175781e-05]), + 'frame': 930, + 'frame_number': 930, + 'framesequence': 928, + 'gaze_dir': array([ 0.98058069, 0.09008216, -0.17420322]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09008216, -0.17420322]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09008216, -0.17420322]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.287332478910685, + 'timestamp_carla': 18287, + 'timestamp_device': 17756, + 'timestamp_stream': 18.287332478910685, + 'transform': [array([ 7.90890837e+00, -3.61787915e-01, 1.92810060e-03]), + array([ -0.02542196, -12.3169136 , 0.14555117])]} +{'AngularVelocity': array([-0.3965756 , -0.80102092, -1.21156716]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.354037284851074, + 'FR_Wheel_Angle': -7.741006374359131, + 'Location': array([ 4.83757019e+01, -1.38771617e+00, 1.74465892e-03]), + 'Rotation': array([-2.26079253e-03, 6.49415741e+01, -1.71722412e-01]), + 'Velocity': array([2.17919007e-01, 3.95507604e-01, 3.76205426e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 475.353271484375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.83044861e+02, 3.12231178e+01, -3.05175781e-05]), + 'frame': 931, + 'frame_number': 931, + 'framesequence': 929, + 'gaze_dir': array([ 0.98058069, 0.09216624, -0.17310962]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09216624, -0.17310962]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09216624, -0.17310962]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.300544876605272, + 'timestamp_carla': 18300, + 'timestamp_device': 17768, + 'timestamp_stream': 18.300544876605272, + 'transform': [array([ 7.91783142e+00, -3.66897643e-01, 1.93321228e-03]), + array([ -0.02568834, -12.44813919, 0.14624073])]} +{'AngularVelocity': array([-0.40842146, -0.81889552, -1.22389758]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.317473411560059, + 'FR_Wheel_Angle': -7.703662395477295, + 'Location': array([ 4.84208717e+01, -1.33190334e+00, 1.74671889e-03]), + 'Rotation': array([-1.95343397e-03, 6.47498016e+01, -1.84783921e-01]), + 'Velocity': array([2.22300187e-01, 4.00394797e-01, 2.75840750e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 476.0488586425781, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.85139954e+02, 3.18200226e+01, -3.05175781e-05]), + 'frame': 932, + 'frame_number': 932, + 'framesequence': 930, + 'gaze_dir': array([ 0.98058069, 0.09440857, -0.17189701]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09440857, -0.17189701]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09440857, -0.17189701]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.313646379858255, + 'timestamp_carla': 18313, + 'timestamp_device': 17781, + 'timestamp_stream': 18.313646379858255, + 'transform': [array([ 7.92657518e+00, -3.71997744e-01, 1.93561555e-03]), + array([ -0.02559955, -12.57790184, 0.14360155])]} +{'AngularVelocity': array([-0.41511431, -0.82318068, -1.22317195]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.317505836486816, + 'FR_Wheel_Angle': -7.703248500823975, + 'Location': array([ 4.84696198e+01, -1.27013624e+00, 1.74557441e-03]), + 'Rotation': array([-2.07637739e-03, 6.45395050e+01, -1.77917451e-01]), + 'Velocity': array([2.23485962e-01, 3.99435461e-01, 7.02667239e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 476.8267517089844, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.87295837e+02, 3.24749565e+01, -3.05175781e-05]), + 'frame': 933, + 'frame_number': 933, + 'framesequence': 931, + 'gaze_dir': array([ 0.98058057, 0.09680578, -0.17055848]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.09680578, -0.17055848]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.09680578, -0.17055848]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.32731617987156, + 'timestamp_carla': 18327, + 'timestamp_device': 17795, + 'timestamp_stream': 18.32731617987156, + 'transform': [array([ 7.93561125e+00, -3.77328545e-01, 1.93218223e-03]), + array([ -0.02517608, -12.71263504, 0.13851994])]} +{'AngularVelocity': array([-0.42188576, -0.83061379, -1.23828959]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.316638946533203, + 'FR_Wheel_Angle': -7.702686309814453, + 'Location': array([ 4.85156517e+01, -1.21380234e+00, 1.74790144e-03]), + 'Rotation': array([-1.89196225e-03, 6.43454895e+01, -1.87072739e-01]), + 'Velocity': array([ 2.27748767e-01, 4.03566778e-01, -5.43451315e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 477.6908264160156, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([689.54992676, 33.18544388, 0. ]), + 'frame': 934, + 'frame_number': 934, + 'framesequence': 932, + 'gaze_dir': array([ 0.98058069, 0.09918404, -0.16918656]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.09918404, -0.16918656]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.09918404, -0.16918656]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.340996477752924, + 'timestamp_carla': 18341, + 'timestamp_device': 17809, + 'timestamp_stream': 18.340996477752924, + 'transform': [array([ 7.94457817e+00, -3.82663310e-01, 1.92722317e-03]), + array([ -0.02454087, -12.84672928, 0.13206322])]} +{'AngularVelocity': array([-0.42676476, -0.83206582, -1.24132097]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.316461563110352, + 'FR_Wheel_Angle': -7.702387809753418, + 'Location': array([ 4.85638695e+01, -1.15382600e+00, 1.73538923e-03]), + 'Rotation': array([-2.01490568e-03, 6.41397934e+01, -1.83624238e-01]), + 'Velocity': array([2.29687110e-01, 4.03795302e-01, 2.55975727e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 478.5812072753906, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.91872559e+02, 3.38670502e+01, -3.05175781e-05]), + 'frame': 935, + 'frame_number': 935, + 'framesequence': 933, + 'gaze_dir': array([ 0.98058057, 0.10137509, -0.16788283]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.10137509, -0.16788283]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.10137509, -0.16788283]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.353740978986025, + 'timestamp_carla': 18353, + 'timestamp_device': 17822, + 'timestamp_stream': 18.353740978986025, + 'transform': [array([ 7.95286894e+00, -3.87629300e-01, 1.92672724e-03]), + array([ -0.02380321, -12.97099781, 0.12543556])]} +{'AngularVelocity': array([-0.42168996, -0.81445956, -1.24599898]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.316206932067871, + 'FR_Wheel_Angle': -7.701969146728516, + 'Location': array([ 4.86136017e+01, -1.09182405e+00, 1.75602676e-03]), + 'Rotation': array([-2.19932082e-03, 6.39275055e+01, -1.77703843e-01]), + 'Velocity': array([2.32182607e-01, 4.04414237e-01, 9.99355325e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 479.4322204589844, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([694.12854004, 34.46370697, 0. ]), + 'frame': 936, + 'frame_number': 936, + 'framesequence': 934, + 'gaze_dir': array([ 0.98058069, 0.10354903, -0.16655077]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10354903, -0.16655077]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10354903, -0.16655077]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.36664727702737, + 'timestamp_carla': 18366, + 'timestamp_device': 17835, + 'timestamp_stream': 18.36664727702737, + 'transform': [array([ 7.96120596e+00, -3.92652422e-01, 1.92359916e-03]), + array([ -0.02301091, -13.09618092, 0.11843677])]} +{'AngularVelocity': array([-0.40739563, -0.77910703, -1.24912643]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.316027641296387, + 'FR_Wheel_Angle': -7.701539993286133, + 'Location': array([ 4.86653862e+01, -1.02647769e+00, 1.75148726e-03]), + 'Rotation': array([-2.44520768e-03, 6.37046928e+01, -1.68121323e-01]), + 'Velocity': array([2.34578371e-01, 4.04415280e-01, 2.59170512e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 480.3057556152344, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 6.96333130e+02, 3.50665131e+01, -3.05175781e-05]), + 'frame': 937, + 'frame_number': 937, + 'framesequence': 935, + 'gaze_dir': array([ 0.98058069, 0.10570545, -0.16519055]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10570545, -0.16519055]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10570545, -0.16519055]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.379774779081345, + 'timestamp_carla': 18379, + 'timestamp_device': 17848, + 'timestamp_stream': 18.379774779081345, + 'transform': [array([ 7.96962643e+00, -3.97754610e-01, 1.91841123e-03]), + array([ -0.02215713, -13.22282791, 0.11128394])]} +{'AngularVelocity': array([-0.42117792, -0.80028909, -1.26891828]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.314892768859863, + 'FR_Wheel_Angle': -7.7009429931640625, + 'Location': array([ 4.87128105e+01, -9.69523966e-01, 1.75251719e-03]), + 'Rotation': array([-2.13784911e-03, 6.35070801e+01, -1.82281494e-01]), + 'Velocity': array([ 2.39803210e-01, 4.09988463e-01, -1.62410739e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 481.2012634277344, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([6.98571228e+02, 3.56516800e+01, 3.05175781e-05]), + 'frame': 938, + 'frame_number': 938, + 'framesequence': 936, + 'gaze_dir': array([ 0.98058069, 0.10784371, -0.16380261]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10784371, -0.16380261]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10784371, -0.16380261]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.392783477902412, + 'timestamp_carla': 18392, + 'timestamp_device': 17861, + 'timestamp_stream': 18.392783477902412, + 'transform': [array([ 7.97791290e+00, -4.02803183e-01, 1.91364286e-03]), + array([ -0.02126921, -13.34764481, 0.10434102])]} +{'AngularVelocity': array([-0.44932562, -0.84244567, -2.00599074]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -13.464568138122559, + 'FR_Wheel_Angle': -12.566683769226074, + 'Location': array([ 4.87629776e+01, -9.09733713e-01, 1.75194500e-03]), + 'Rotation': array([-2.19932082e-03, 6.32574234e+01, -1.79412797e-01]), + 'Velocity': array([2.59795666e-01, 3.97931665e-01, 2.64263159e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 482.11895751953125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.00847656e+02, 3.62174721e+01, -3.05175781e-05]), + 'frame': 939, + 'frame_number': 939, + 'framesequence': 937, + 'gaze_dir': array([ 0.98058069, 0.10996404, -0.16238679]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.10996404, -0.16238679]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.10996404, -0.16238679]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.40603007748723, + 'timestamp_carla': 18406, + 'timestamp_device': 17874, + 'timestamp_stream': 18.40603007748723, + 'transform': [array([ 7.98959160e+00, -4.04474825e-01, 1.91585533e-03]), + array([ -0.02190442, -13.47069168, 0.11353306])]} +{'AngularVelocity': array([-0.42499784, -0.77043581, -2.8895793 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -17.398881912231445, + 'FR_Wheel_Angle': -14.630486488342285, + 'Location': array([ 4.88189850e+01, -8.48720670e-01, 1.73901313e-03]), + 'Rotation': array([-8.53773614e-04, 6.28212471e+01, -1.76452622e-01]), + 'Velocity': array([3.05752993e-01, 4.18838412e-01, 1.85141558e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 483.0583801269531, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([703.1361084 , 36.77161789, 0. ]), + 'frame': 940, + 'frame_number': 940, + 'framesequence': 938, + 'gaze_dir': array([ 0.98058069, 0.11222661, -0.16083144]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11222661, -0.16083144]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11222661, -0.16083144]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.41961757838726, + 'timestamp_carla': 18419, + 'timestamp_device': 17888, + 'timestamp_stream': 18.41961757838726, + 'transform': [array([ 7.99989653e+00, -4.08396304e-01, 1.92119589e-03]), + array([ -0.02340023, -13.59727859, 0.12950899])]} +{'AngularVelocity': array([-0.4174647 , -0.72467023, -2.8086431 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.75835418701172, + 'FR_Wheel_Angle': -14.653878211975098, + 'Location': array([ 4.88856544e+01, -7.72028923e-01, 1.72688242e-03]), + 'Rotation': array([-2.73207552e-04, 6.22966690e+01, -1.57318085e-01]), + 'Velocity': array([ 3.16105485e-01, 4.33948189e-01, -2.20441812e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 484.07623291015625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.05877136e+02, 3.77117195e+01, -3.05175781e-05]), + 'frame': 941, + 'frame_number': 941, + 'framesequence': 939, + 'gaze_dir': array([ 0.98058069, 0.11430795, -0.15935889]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11430795, -0.15935889]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11430795, -0.15935889]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.432764876633883, + 'timestamp_carla': 18432, + 'timestamp_device': 17901, + 'timestamp_stream': 18.432764876633883, + 'transform': [array([ 8.00905037e+00, -4.13138598e-01, 1.92848197e-03]), + array([ -0.02471845, -13.72292042, 0.14176403])]} +{'AngularVelocity': array([-0.41982886, -0.71168762, -2.83389044]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.39079475402832, + 'FR_Wheel_Angle': -14.202315330505371, + 'Location': array([ 4.89453125e+01, -7.06945658e-01, 1.74927467e-03]), + 'Rotation': array([ 6.89849083e-04, 6.18263092e+01, -1.65191635e-01]), + 'Velocity': array([ 3.27863187e-01, 4.44239825e-01, -5.08403755e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 485.0352478027344, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.08406921e+02, 3.83535576e+01, 3.05175781e-05]), + 'frame': 942, + 'frame_number': 942, + 'framesequence': 940, + 'gaze_dir': array([ 0.98058069, 0.11652768, -0.15774302]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.11652768, -0.15774302]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.11652768, -0.15774302]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.44687407836318, + 'timestamp_carla': 18446, + 'timestamp_device': 17915, + 'timestamp_stream': 18.44687407836318, + 'transform': [array([ 8.01846027e+00, -4.18612003e-01, 1.92726136e-03]), + array([ -0.02562687, -13.85994244, 0.14854228])]} +{'AngularVelocity': array([-0.43779477, -0.72614396, -2.89415431]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.638473510742188, + 'FR_Wheel_Angle': -14.350841522216797, + 'Location': array([ 4.90057793e+01, -6.41942382e-01, 1.73996680e-03]), + 'Rotation': array([ 1.03135849e-03, 6.13584404e+01, -1.68701202e-01]), + 'Velocity': array([3.34620535e-01, 4.43922400e-01, 1.42970079e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 486.0985412597656, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.10957397e+02, 3.89589157e+01, -3.05175781e-05]), + 'frame': 943, + 'frame_number': 943, + 'framesequence': 941, + 'gaze_dir': array([ 0.98058057, 0.11841201, -0.15633345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.11841201, -0.15633345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.11841201, -0.15633345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.459572378546, + 'timestamp_carla': 18459, + 'timestamp_device': 17927, + 'timestamp_stream': 18.459572378546, + 'transform': [array([ 8.02675438e+00, -4.23646718e-01, 1.93183892e-03]), + array([ -0.02597521, -13.98369408, 0.14984408])]} +{'AngularVelocity': array([-0.45045516, -0.7322557 , -2.92782617]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.612024307250977, + 'FR_Wheel_Angle': -14.358760833740234, + 'Location': array([ 4.90669632e+01, -5.76992691e-01, 1.73504592e-03]), + 'Rotation': array([ 1.19528302e-03, 6.08875694e+01, -1.70593232e-01]), + 'Velocity': array([ 3.42500061e-01, 4.46887374e-01, -1.03778839e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 487.0336608886719, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([713.36907959, 39.36850357, 0. ]), + 'frame': 944, + 'frame_number': 944, + 'framesequence': 942, + 'gaze_dir': array([ 0.98058069, 0.12043437, -0.15478088]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12043437, -0.15478088]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12043437, -0.15478088]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.47221627831459, + 'timestamp_carla': 18472, + 'timestamp_device': 17940, + 'timestamp_stream': 18.47221627831459, + 'transform': [array([ 8.03491020e+00, -4.28693354e-01, 1.93340296e-03]), + array([ -0.02591374, -14.10661793, 0.14774229])]} +{'AngularVelocity': array([-0.43052194, -0.68342847, -2.94859767]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.641643524169922, + 'FR_Wheel_Angle': -14.389440536499023, + 'Location': array([ 4.91375427e+01, -5.00621080e-01, 1.74500223e-03]), + 'Rotation': array([ 5.66905655e-04, 6.03392410e+01, -1.56433105e-01]), + 'Velocity': array([3.49243760e-01, 4.46117818e-01, 1.39274591e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 488.07672119140625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.15790649e+02, 3.98476982e+01, -3.05175781e-05]), + 'frame': 945, + 'frame_number': 945, + 'framesequence': 943, + 'gaze_dir': array([ 0.98058069, 0.12304814, -0.15271121]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.12304814, -0.15271121]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.12304814, -0.15271121]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.488769579678774, + 'timestamp_carla': 18488, + 'timestamp_device': 17957, + 'timestamp_stream': 18.488769579678774, + 'transform': [array([ 8.04546547e+00, -4.35311913e-01, 1.90376281e-03]), + array([ -0.02539464, -14.26665211, 0.14141765])]} +{'AngularVelocity': array([-0.43125188, -0.6707148 , -2.97985005]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.639785766601562, + 'FR_Wheel_Angle': -14.38765811920166, + 'Location': array([ 4.92053833e+01, -4.29212719e-01, 1.73500774e-03]), + 'Rotation': array([ 4.02981124e-04, 5.98191910e+01, -1.53167725e-01]), + 'Velocity': array([ 3.57160568e-01, 4.47612673e-01, -1.76606176e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 489.4783935546875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.18676208e+02, 4.05466919e+01, -6.10351562e-05]), + 'frame': 946, + 'frame_number': 946, + 'framesequence': 944, + 'gaze_dir': array([ 0.98058057, 0.12487193, -0.15122354]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.12487193, -0.15122354]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.12487193, -0.15122354]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.50154597684741, + 'timestamp_carla': 18501, + 'timestamp_device': 17969, + 'timestamp_stream': 18.50154597684741, + 'transform': [array([ 8.05354309e+00, -4.40419227e-01, 1.90608972e-03]), + array([ -0.02480725, -14.38951588, 0.13535687])]} +{'AngularVelocity': array([-0.42876276, -0.6530745 , -3.00675726]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.638126373291016, + 'FR_Wheel_Angle': -14.385092735290527, + 'Location': array([ 4.92760429e+01, -3.55465502e-01, 1.72192336e-03]), + 'Rotation': array([ 1.09283021e-04, 5.92799721e+01, -1.47552475e-01]), + 'Velocity': array([ 0.36476558, 0.44822046, -0.00105087]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 490.492919921875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.21329773e+02, 4.08262138e+01, 3.05175781e-05]), + 'frame': 947, + 'frame_number': 947, + 'framesequence': 945, + 'gaze_dir': array([ 0.98058057, 0.12697674, -0.14946058]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.12697674, -0.14946058]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.12697674, -0.14946058]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.51509027928114, + 'timestamp_carla': 18515, + 'timestamp_device': 17983, + 'timestamp_stream': 18.51509027928114, + 'transform': [array([ 8.06203938e+00, -4.45826530e-01, 1.90223695e-03]), + array([ -0.02404226, -14.51903152, 0.12814116])]} +{'AngularVelocity': array([-0.43423668, -0.64989674, -3.05641246]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.63646697998047, + 'FR_Wheel_Angle': -14.38389778137207, + 'Location': array([ 4.93434448e+01, -2.86554128e-01, 1.78173778e-03]), + 'Rotation': array([ 3.27849062e-04, 5.87706947e+01, -1.53594971e-01]), + 'Velocity': array([3.75001103e-01, 4.52288091e-01, 1.84240344e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 491.7050476074219, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.23941528e+02, 4.13020973e+01, 3.05175781e-05]), + 'frame': 948, + 'frame_number': 948, + 'framesequence': 946, + 'gaze_dir': array([ 0.98058057, 0.12890872, -0.14779748]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.12890872, -0.14779748]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.12890872, -0.14779748]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.52842827886343, + 'timestamp_carla': 18528, + 'timestamp_device': 17996, + 'timestamp_stream': 18.52842827886343, + 'transform': [array([ 8.07034397e+00, -4.51143414e-01, 1.89876556e-03]), + array([ -0.02319532, -14.64589691, 0.12074316])]} +{'AngularVelocity': array([-0.41966504, -0.61350733, -3.07507229]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.634258270263672, + 'FR_Wheel_Angle': -14.382279396057129, + 'Location': array([ 4.94213333e+01, -2.06360579e-01, 1.75114395e-03]), + 'Rotation': array([-2.18566041e-04, 5.81809959e+01, -1.42761201e-01]), + 'Velocity': array([3.82187277e-01, 4.51056659e-01, 2.00071328e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 492.8555908203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([726.5189209 , 41.68227768, 0. ]), + 'frame': 949, + 'frame_number': 949, + 'framesequence': 947, + 'gaze_dir': array([ 0.98058057, 0.13096519, -0.14597835]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.13096519, -0.14597835]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.13096519, -0.14597835]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.541707079857588, + 'timestamp_carla': 18541, + 'timestamp_device': 18010, + 'timestamp_stream': 18.541707079857588, + 'transform': [array([ 8.07855225e+00, -4.56427753e-01, 1.89506530e-03]), + array([ -0.0223074 , -14.7715044 , 0.11335918])]} +{'AngularVelocity': array([-0.44277903, -0.63707072, -3.13294601]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -16.63084602355957, + 'FR_Wheel_Angle': -14.380404472351074, + 'Location': array([ 4.94895096e+01, -1.39638931e-01, 1.73825026e-03]), + 'Rotation': array([ 2.52717000e-04, 5.76773643e+01, -1.54205337e-01]), + 'Velocity': array([ 3.93423140e-01, 4.56193060e-01, -3.59420781e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 494.12005615234375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([729.22216797, 42.1061554 , 0. ]), + 'frame': 950, + 'frame_number': 950, + 'framesequence': 948, + 'gaze_dir': array([ 0.98058057, 0.13285185, -0.14426343]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.13285185, -0.14426343]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.13285185, -0.14426343]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.555105179548264, + 'timestamp_carla': 18555, + 'timestamp_device': 18023, + 'timestamp_stream': 18.555105179548264, + 'transform': [array([ 8.08677673e+00, -4.61749762e-01, 1.89014431e-03]), + array([ -0.02139215, -14.897542 , 0.10605991])]} +{'AngularVelocity': array([-0.47415575, -0.66507858, -3.69685793]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.58127212524414, + 'FR_Wheel_Angle': -17.831539154052734, + 'Location': array([ 4.95626984e+01, -6.86739907e-02, 1.73989055e-03]), + 'Rotation': array([ 1.36603776e-05, 5.71169014e+01, -1.49780288e-01]), + 'Velocity': array([4.11091119e-01, 4.43378031e-01, 1.50785447e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 495.31903076171875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([731.82330322, 42.45796585, 0. ]), + 'frame': 951, + 'frame_number': 951, + 'framesequence': 949, + 'gaze_dir': array([ 0.98058069, 0.13471608, -0.14252418]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13471608, -0.14252418]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13471608, -0.14252418]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.56806867942214, + 'timestamp_carla': 18568, + 'timestamp_device': 18036, + 'timestamp_stream': 18.56806867942214, + 'transform': [array([ 8.09815121e+00, -4.63375390e-01, 1.89613341e-03]), + array([ -0.02203419, -15.01527882, 0.11513365])]} +{'AngularVelocity': array([-0.40470704, -0.54353738, -5.09983587]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -26.237770080566406, + 'FR_Wheel_Angle': -20.899765014648438, + 'Location': array([4.96526451e+01, 1.10589024e-02, 1.74454448e-03]), + 'Rotation': array([-3.07358510e-04, 5.62048950e+01, -1.29608139e-01]), + 'Velocity': array([4.65765864e-01, 4.29274857e-01, 1.05895997e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 496.540771484375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([734.4541626 , 42.78916168, 0. ]), + 'frame': 952, + 'frame_number': 952, + 'framesequence': 950, + 'gaze_dir': array([ 0.98058069, 0.13655753, -0.14076081]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13655753, -0.14076081]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13655753, -0.14076081]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.581213179975748, + 'timestamp_carla': 18581, + 'timestamp_device': 18049, + 'timestamp_stream': 18.581213179975748, + 'transform': [array([ 8.10796833e+00, -4.67177182e-01, 1.90567016e-03]), + array([ -0.02353 , -15.13475418, 0.13124873])]} +{'AngularVelocity': array([-0.43106604, -0.55139673, -5.04972172]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.865020751953125, + 'FR_Wheel_Angle': -20.396188735961914, + 'Location': array([4.97370872e+01, 8.32365975e-02, 1.70826667e-03]), + 'Rotation': array([ 1.09283021e-03, 5.53469391e+01, -1.33148178e-01]), + 'Velocity': array([ 0.49216324, 0.45472503, -0.00111015]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 497.7604675292969, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.37395020e+02, 4.34633865e+01, -3.05175781e-05]), + 'frame': 953, + 'frame_number': 953, + 'framesequence': 951, + 'gaze_dir': array([ 0.98058069, 0.13851473, -0.13883528]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.13851473, -0.13883528]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.13851473, -0.13883528]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.595366179943085, + 'timestamp_carla': 18595, + 'timestamp_device': 18063, + 'timestamp_stream': 18.595366179943085, + 'transform': [array([ 8.11752701e+00, -4.72395748e-01, 1.90925598e-03]), + array([ -0.02502581, -15.26704979, 0.1452468 ])]} +{'AngularVelocity': array([-0.41194457, -0.50631595, -5.16558361]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.669097900390625, + 'FR_Wheel_Angle': -20.112071990966797, + 'Location': array([4.98307838e+01, 1.61720216e-01, 1.70799962e-03]), + 'Rotation': array([ 1.25675474e-03, 5.43864822e+01, -1.28448471e-01]), + 'Velocity': array([ 5.09449601e-01, 4.53038484e-01, -1.57051079e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 499.0888366699219, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.40328979e+02, 4.39564667e+01, -3.05175781e-05]), + 'frame': 954, + 'frame_number': 954, + 'framesequence': 952, + 'gaze_dir': array([ 0.98058069, 0.14044477, -0.13688254]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14044477, -0.13688254]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14044477, -0.13688254]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.60862747952342, + 'timestamp_carla': 18608, + 'timestamp_device': 18077, + 'timestamp_stream': 18.60862747952342, + 'transform': [array([ 8.12607384e+00, -4.77653146e-01, 1.91562646e-03]), + array([ -0.02594106, -15.39317799, 0.1522357 ])]} +{'AngularVelocity': array([-0.42856067, -0.50836092, -5.27253008]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.898645401000977, + 'FR_Wheel_Angle': -20.236698150634766, + 'Location': array([4.99196815e+01, 2.33480498e-01, 1.71875709e-03]), + 'Rotation': array([ 1.45483017e-03, 5.34944229e+01, -1.29486084e-01]), + 'Velocity': array([5.23443580e-01, 4.49401379e-01, 4.02402875e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 500.4460754394531, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.43290771e+02, 4.43028831e+01, -6.10351562e-05]), + 'frame': 955, + 'frame_number': 955, + 'framesequence': 953, + 'gaze_dir': array([ 0.98058069, 0.14234728, -0.13490297]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14234728, -0.13490297]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14234728, -0.13490297]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.623151179403067, + 'timestamp_carla': 18623, + 'timestamp_device': 18091, + 'timestamp_stream': 18.623151179403067, + 'transform': [array([ 8.13521385e+00, -4.83543932e-01, 1.91082002e-03]), + array([ -0.02633038, -15.53188133, 0.15369624])]} +{'AngularVelocity': array([-0.43434268, -0.49814254, -5.34143639]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.866350173950195, + 'FR_Wheel_Angle': -20.238603591918945, + 'Location': array([5.00109673e+01, 3.05269420e-01, 1.72562362e-03]), + 'Rotation': array([ 1.41384907e-03, 5.25879288e+01, -1.28295898e-01]), + 'Velocity': array([5.38075984e-01, 4.47567284e-01, 4.27246096e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 501.8422546386719, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([746.18237305, 44.61600876, 0. ]), + 'frame': 956, + 'frame_number': 956, + 'framesequence': 954, + 'gaze_dir': array([ 0.98058069, 0.14408876, -0.13304131]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14408876, -0.13304131]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14408876, -0.13304131]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.63637037947774, + 'timestamp_carla': 18636, + 'timestamp_device': 18104, + 'timestamp_stream': 18.63637037947774, + 'transform': [array([ 8.14341831e+00, -4.88938659e-01, 1.91246031e-03]), + array([ -0.02626891, -15.65782166, 0.15122151])]} +{'AngularVelocity': array([-0.43697664, -0.48499703, -5.41915226]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.896331787109375, + 'FR_Wheel_Angle': -20.269750595092773, + 'Location': array([5.01042709e+01, 3.76696467e-01, 1.73020118e-03]), + 'Rotation': array([ 1.27041514e-03, 5.16708069e+01, -1.26464859e-01]), + 'Velocity': array([5.52745283e-01, 4.44666356e-01, 1.90734863e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 503.16973876953125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([749.05657959, 44.81047821, 0. ]), + 'frame': 957, + 'frame_number': 957, + 'framesequence': 955, + 'gaze_dir': array([ 0.98058057, 0.14593713, -0.1310111 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.14593713, -0.1310111 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.14593713, -0.1310111 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.649930778890848, + 'timestamp_carla': 18649, + 'timestamp_device': 18118, + 'timestamp_stream': 18.649930778890848, + 'transform': [array([ 8.15175056e+00, -4.94478136e-01, 1.91009522e-03]), + array([ -0.02587959, -15.78639507, 0.1461298 ])]} +{'AngularVelocity': array([-0.44659221, -0.48227111, -5.52171707]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.89250373840332, + 'FR_Wheel_Angle': -20.265323638916016, + 'Location': array([5.01930809e+01, 4.42088068e-01, 1.71906233e-03]), + 'Rotation': array([ 1.58460380e-03, 5.08093796e+01, -1.32110581e-01]), + 'Velocity': array([5.70148289e-01, 4.44574386e-01, 1.21998783e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 504.6341552734375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([751.98754883, 45.06623459, 0. ]), + 'frame': 958, + 'frame_number': 958, + 'framesequence': 956, + 'gaze_dir': array([ 0.98058069, 0.14762796, -0.12910284]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.14762796, -0.12910284]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.14762796, -0.12910284]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.66320127993822, + 'timestamp_carla': 18663, + 'timestamp_device': 18131, + 'timestamp_stream': 18.66320127993822, + 'transform': [array([ 8.15983582e+00, -4.99895364e-01, 1.90776819e-03]), + array([ -0.0252717 , -15.91154766, 0.13968775])]} +{'AngularVelocity': array([-0.42789465, -0.44374356, -5.54406977]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.888851165771484, + 'FR_Wheel_Angle': -20.260822296142578, + 'Location': array([5.03023872e+01, 5.22414207e-01, 1.71547651e-03]), + 'Rotation': array([ 5.32754697e-04, 4.97524605e+01, -1.17156975e-01]), + 'Velocity': array([ 5.80788136e-01, 4.35686052e-01, -5.07802935e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 506.0230407714844, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([754.83178711, 45.24285126, 0. ]), + 'frame': 959, + 'frame_number': 959, + 'framesequence': 957, + 'gaze_dir': array([ 0.98058057, 0.14929383, -0.12717274]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.14929383, -0.12717274]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.14929383, -0.12717274]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.676635276526213, + 'timestamp_carla': 18676, + 'timestamp_device': 18144, + 'timestamp_stream': 18.676635276526213, + 'transform': [array([ 8.16795635e+00, -5.05371451e-01, 1.90349575e-03]), + array([ -0.0244794 , -16.03752327, 0.13235746])]} +{'AngularVelocity': array([-0.41119203, -0.41133001, -5.5977788 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.885765075683594, + 'FR_Wheel_Angle': -20.25706672668457, + 'Location': array([5.04090958e+01, 5.98014534e-01, 1.73710578e-03]), + 'Rotation': array([-3.41509440e-05, 4.87335434e+01, -1.10015847e-01]), + 'Velocity': array([5.94405830e-01, 4.29306775e-01, 1.45611761e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 507.4382629394531, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.57675171e+02, 4.54078903e+01, 3.05175781e-05]), + 'frame': 960, + 'frame_number': 960, + 'framesequence': 958, + 'gaze_dir': array([ 0.98058069, 0.15105957, -0.12507026]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15105957, -0.12507026]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15105957, -0.12507026]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.68966767936945, + 'timestamp_carla': 18689, + 'timestamp_device': 18158, + 'timestamp_stream': 18.68966767936945, + 'transform': [array([ 8.17577457e+00, -5.10674775e-01, 1.90078735e-03]), + array([ -0.02362562, -16.15910721, 0.12493753])]} +{'AngularVelocity': array([-0.40681323, -0.39337161, -5.67522001]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.881145477294922, + 'FR_Wheel_Angle': -20.25358772277832, + 'Location': array([5.05163574e+01, 6.71409070e-01, 1.72604318e-03]), + 'Rotation': array([-3.34679266e-04, 4.77214432e+01, -1.07330315e-01]), + 'Velocity': array([ 6.10431552e-01, 4.24512535e-01, -3.07192793e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 508.98980712890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.60695068e+02, 4.55901299e+01, 3.05175781e-05]), + 'frame': 961, + 'frame_number': 961, + 'framesequence': 959, + 'gaze_dir': array([ 0.98058069, 0.15304136, -0.12263729]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15304136, -0.12263729]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15304136, -0.12263729]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.705671977251768, + 'timestamp_carla': 18705, + 'timestamp_device': 18174, + 'timestamp_stream': 18.705671977251768, + 'transform': [array([ 8.18529701e+00, -5.17172277e-01, 1.87557214e-03]), + array([ -0.02249181, -16.30744934, 0.11566126])]} +{'AngularVelocity': array([-0.40105608, -0.37432966, -5.74274826]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -24.87722396850586, + 'FR_Wheel_Angle': -20.249378204345703, + 'Location': array([5.06266632e+01, 7.44372249e-01, 1.73763989e-03]), + 'Rotation': array([-6.42037718e-04, 4.66925240e+01, -1.04248039e-01]), + 'Velocity': array([6.25506818e-01, 4.18374181e-01, 1.15246767e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 510.7958984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([764.00024414, 45.84458542, 0. ]), + 'frame': 962, + 'frame_number': 962, + 'framesequence': 960, + 'gaze_dir': array([ 0.98058069, 0.1546225 , -0.12063766]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1546225 , -0.12063766]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1546225 , -0.12063766]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.718882579356432, + 'timestamp_carla': 18718, + 'timestamp_device': 18187, + 'timestamp_stream': 18.718882579356432, + 'transform': [array([ 8.19676685e+00, -5.18904150e-01, 1.89662934e-03]), + array([ -0.02316117, -16.42518616, 0.12513861])]} +{'AngularVelocity': array([-0.42788199, -0.38137975, -6.55693817]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -28.517311096191406, + 'FR_Wheel_Angle': -23.23984718322754, + 'Location': array([5.07411575e+01, 8.16763163e-01, 1.72005408e-03]), + 'Rotation': array([-1.28407544e-03, 4.56061554e+01, -9.73205417e-02]), + 'Velocity': array([6.49522841e-01, 3.89652729e-01, 4.33702458e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 512.2930297851562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([767.11907959, 45.85554123, 0. ]), + 'frame': 963, + 'frame_number': 963, + 'framesequence': 961, + 'gaze_dir': array([ 0.98058069, 0.15641475, -0.11830463]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15641475, -0.11830463]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15641475, -0.11830463]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.6000000238418579, + 'throttle_input': 0.0, + 'timestamp': 18.733714677393436, + 'timestamp_carla': 18733, + 'timestamp_device': 18202, + 'timestamp_stream': 18.733714677393436, + 'transform': [array([ 8.20746422e+00, -5.23452103e-01, 1.91150664e-03]), + array([ -0.02489604, -16.5575428 , 0.14366572])]} +{'AngularVelocity': array([-0.37393394, -0.31808373, -8.29565239]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -34.857696533203125, + 'FR_Wheel_Angle': -26.44097137451172, + 'Location': array([5.08552628e+01, 8.78164828e-01, 1.69403793e-03]), + 'Rotation': array([-1.68022641e-03, 4.42925529e+01, -9.08813477e-02]), + 'Velocity': array([ 7.04528868e-01, 3.45015734e-01, -9.06753485e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 514.0164184570312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.70681641e+02, 4.63730621e+01, -3.05175781e-05]), + 'frame': 964, + 'frame_number': 964, + 'framesequence': 962, + 'gaze_dir': array([ 0.98058069, 0.15805562, -0.11610331]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15805562, -0.11610331]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15805562, -0.11610331]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5989745855331421, + 'throttle_input': 0.0, + 'timestamp': 18.74830887839198, + 'timestamp_carla': 18748, + 'timestamp_device': 18216, + 'timestamp_stream': 18.74830887839198, + 'transform': [array([ 8.21693134e+00, -5.29036880e-01, 1.92493433e-03]), + array([ -0.02639185, -16.69166565, 0.15713954])]} +{'AngularVelocity': array([-0.36427385, -0.29027215, -8.07731152]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.54887390136719, + 'FR_Wheel_Angle': -25.454500198364258, + 'Location': array([5.09772415e+01, 9.40918565e-01, 1.69289345e-03]), + 'Rotation': array([-9.76716983e-04, 4.28844223e+01, -8.74023363e-02]), + 'Velocity': array([ 0.73556626, 0.35778591, -0.00077252]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 515.63134765625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([774.05859375, 46.55895233, 0. ]), + 'frame': 965, + 'frame_number': 965, + 'framesequence': 963, + 'gaze_dir': array([ 0.98058069, 0.15977925, -0.1137196 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.15977925, -0.1137196 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.15977925, -0.1137196 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5946348309516907, + 'throttle_input': 0.0, + 'timestamp': 18.762809477746487, + 'timestamp_carla': 18762, + 'timestamp_device': 18231, + 'timestamp_stream': 18.762809477746487, + 'transform': [array([ 8.22592354e+00, -5.34928858e-01, 1.93336478e-03]), + array([ -0.0272183 , -16.82649231, 0.16301166])]} +{'AngularVelocity': array([-0.33011892, -0.24928448, -8.29808998]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -32.93829345703125, + 'FR_Wheel_Angle': -25.447778701782227, + 'Location': array([5.11155548e+01, 1.00837982e+00, 1.70319318e-03]), + 'Rotation': array([-1.70754723e-03, 4.12915154e+01, -7.47680515e-02]), + 'Velocity': array([7.50134885e-01, 3.33063453e-01, 3.21264262e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 517.4052124023438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([7.77508667e+02, 4.66520958e+01, 3.05175781e-05]), + 'frame': 966, + 'frame_number': 966, + 'framesequence': 964, + 'gaze_dir': array([ 0.98058069, 0.16146696, -0.11131032]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16146696, -0.11131032]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16146696, -0.11131032]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5879147052764893, + 'throttle_input': 0.0, + 'timestamp': 18.777837079018354, + 'timestamp_carla': 18777, + 'timestamp_device': 18246, + 'timestamp_stream': 18.777837079018354, + 'transform': [array([ 8.23506546e+00, -5.41120470e-01, 1.93321228e-03]), + array([ -0.02740955, -16.96525192, 0.1625116 ])]} +{'AngularVelocity': array([-0.31924012, -0.22519872, -8.39151001]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.15079879760742, + 'FR_Wheel_Angle': -25.577735900878906, + 'Location': array([5.12436714e+01, 1.06684327e+00, 1.71620131e-03]), + 'Rotation': array([-1.83049054e-03, 3.98432884e+01, -7.40661621e-02]), + 'Velocity': array([ 7.70891845e-01, 3.19482327e-01, -4.56361769e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 519.2266235351562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.80960205e+02, 4.66851273e+01, -3.05175781e-05]), + 'frame': 967, + 'frame_number': 967, + 'framesequence': 965, + 'gaze_dir': array([ 0.98058069, 0.16290034, -0.10920183]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16290034, -0.10920183]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16290034, -0.10920183]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5785211324691772, + 'throttle_input': 0.0, + 'timestamp': 18.791637677699327, + 'timestamp_carla': 18791, + 'timestamp_device': 18259, + 'timestamp_stream': 18.791637677699327, + 'transform': [array([ 8.24339008e+00, -5.46802044e-01, 1.93725585e-03]), + array([ -0.02709536, -17.09058762, 0.15815519])]} +{'AngularVelocity': array([-0.31884941, -0.21627833, -8.61010075]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.098873138427734, + 'FR_Wheel_Angle': -25.570688247680664, + 'Location': array([5.13884735e+01, 1.12920547e+00, 1.69945473e-03]), + 'Rotation': array([-2.62279250e-03, 3.82221298e+01, -6.46667406e-02]), + 'Velocity': array([ 7.86907315e-01, 2.97449231e-01, -2.97842023e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 520.843017578125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.84163208e+02, 4.65957260e+01, -3.05175781e-05]), + 'frame': 968, + 'frame_number': 968, + 'framesequence': 966, + 'gaze_dir': array([ 0.98058069, 0.16441315, -0.1069106 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16441315, -0.1069106 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16441315, -0.1069106 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5688528418540955, + 'throttle_input': 0.0, + 'timestamp': 18.805517379194498, + 'timestamp_carla': 18805, + 'timestamp_device': 18273, + 'timestamp_stream': 18.805517379194498, + 'transform': [array([ 8.25172615e+00, -5.52484035e-01, 1.93737028e-03]), + array([ -0.02645332, -17.21412468, 0.15131779])]} +{'AngularVelocity': array([-0.289713 , -0.18227394, -8.57346058]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.09125518798828, + 'FR_Wheel_Angle': -25.57193946838379, + 'Location': array([5.15227776e+01, 1.18275273e+00, 1.76483870e-03]), + 'Rotation': array([-2.84135854e-03, 3.67375946e+01, -6.39953613e-02]), + 'Velocity': array([ 8.04147840e-01, 2.83213973e-01, -2.23407740e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 522.6204833984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.87455872e+02, 4.65548248e+01, -3.05175781e-05]), + 'frame': 969, + 'frame_number': 969, + 'framesequence': 967, + 'gaze_dir': array([ 0.98058069, 0.16589372, -0.10459843]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16589372, -0.10459843]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16589372, -0.10459843]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5599536299705505, + 'throttle_input': 0.0, + 'timestamp': 18.819032978266478, + 'timestamp_carla': 18819, + 'timestamp_device': 18287, + 'timestamp_stream': 18.819032978266478, + 'transform': [array([ 8.25981808e+00, -5.57978630e-01, 1.93679810e-03]), + array([ -0.02559955, -17.33198357, 0.14335167])]} +{'AngularVelocity': array([-0.2819522 , -0.16752601, -8.66362 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.085426330566406, + 'FR_Wheel_Angle': -25.566715240478516, + 'Location': array([5.16602859e+01, 1.23373306e+00, 1.74214120e-03]), + 'Rotation': array([-3.23750940e-03, 3.52340202e+01, -6.11877404e-02]), + 'Velocity': array([ 8.20756733e-01, 2.65115172e-01, -2.65531533e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 524.4318237304688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([790.78173828, 46.48609161, 0. ]), + 'frame': 970, + 'frame_number': 970, + 'framesequence': 968, + 'gaze_dir': array([ 0.98058057, 0.16723949, -0.10243294]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16723949, -0.10243294]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16723949, -0.10243294]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5492599606513977, + 'throttle_input': 0.0, + 'timestamp': 18.83200277760625, + 'timestamp_carla': 18832, + 'timestamp_device': 18300, + 'timestamp_stream': 18.83200277760625, + 'transform': [array([ 8.26756763e+00, -5.63210070e-01, 1.93729391e-03]), + array([ -0.02465698, -17.44263649, 0.13508685])]} +{'AngularVelocity': array([-0.27754575, -0.15742435, -8.81948185]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.08194351196289, + 'FR_Wheel_Angle': -25.562084197998047, + 'Location': array([5.18048668e+01, 1.28349590e+00, 1.71952008e-03]), + 'Rotation': array([-3.84539622e-03, 3.36677437e+01, -5.54809533e-02]), + 'Velocity': array([ 8.34914386e-01, 2.42847398e-01, -5.00726688e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 526.1439208984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([793.94207764, 46.37804031, 0. ]), + 'frame': 971, + 'frame_number': 971, + 'framesequence': 969, + 'gaze_dir': array([ 0.98058057, 0.16865709, -0.10008164]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.16865709, -0.10008164]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.16865709, -0.10008164]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.537962019443512, + 'throttle_input': 0.0, + 'timestamp': 18.84600567817688, + 'timestamp_carla': 18846, + 'timestamp_device': 18314, + 'timestamp_stream': 18.84600567817688, + 'transform': [array([ 8.27592278e+00, -5.68805635e-01, 1.92916871e-03]), + array([ -0.02353 , -17.5591526 , 0.12583846])]} +{'AngularVelocity': array([-0.248686 , -0.13151698, -8.83767605]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.07838821411133, + 'FR_Wheel_Angle': -25.557594299316406, + 'Location': array([5.19531326e+01, 1.33044505e+00, 1.74721470e-03]), + 'Rotation': array([-4.39864164e-03, 3.20756111e+01, -4.98351939e-02]), + 'Velocity': array([ 8.46874058e-01, 2.21593827e-01, -5.70297243e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 528.0153198242188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 7.97249512e+02, 4.62956085e+01, -3.05175781e-05]), + 'frame': 972, + 'frame_number': 972, + 'framesequence': 970, + 'gaze_dir': array([ 0.98058069, 0.16994393, -0.09788062]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.16994393, -0.09788062]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.16994393, -0.09788062]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5262429118156433, + 'throttle_input': 0.0, + 'timestamp': 18.858945477753878, + 'timestamp_carla': 18858, + 'timestamp_device': 18327, + 'timestamp_stream': 18.858945477753878, + 'transform': [array([ 8.28363705e+00, -5.73927879e-01, 1.92703248e-03]), + array([ -0.02246449, -17.66416168, 0.11737742])]} +{'AngularVelocity': array([-0.23084749, -0.11501952, -8.92117596]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.07481384277344, + 'FR_Wheel_Angle': -25.5531005859375, + 'Location': array([5.21046562e+01, 1.37414837e+00, 1.73138373e-03]), + 'Rotation': array([-5.03384927e-03, 3.04630527e+01, -4.45556678e-02]), + 'Velocity': array([8.59243453e-01, 1.98640063e-01, 9.68170134e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 529.78173828125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([800.4909668 , 46.12804794, 0. ]), + 'frame': 973, + 'frame_number': 973, + 'framesequence': 971, + 'gaze_dir': array([ 0.98058057, 0.17129754, -0.0954919 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17129754, -0.0954919 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17129754, -0.0954919 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.5162450671195984, + 'throttle_input': 0.0, + 'timestamp': 18.873016379773617, + 'timestamp_carla': 18873, + 'timestamp_device': 18341, + 'timestamp_stream': 18.873016379773617, + 'transform': [array([ 8.29582405e+00, -5.76000988e-01, 1.92275993e-03]), + array([ -0.02288796, -17.77528 , 0.12739427])]} +{'AngularVelocity': array([-0.21356846, -0.10004921, -8.99970531]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -33.071231842041016, + 'FR_Wheel_Angle': -25.549009323120117, + 'Location': array([5.22580605e+01, 1.41411364e+00, 1.72798871e-03]), + 'Rotation': array([-5.55977365e-03, 2.88424454e+01, -3.96728441e-02]), + 'Velocity': array([ 8.70779037e-01, 1.75070792e-01, -2.63080583e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 531.710205078125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([803.84484863, 46.00242615, 0. ]), + 'frame': 974, + 'frame_number': 974, + 'framesequence': 972, + 'gaze_dir': array([ 0.98058069, 0.1726176 , -0.09308447]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1726176 , -0.09308447]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1726176 , -0.09308447]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.504196286201477, + 'throttle_input': 0.0, + 'timestamp': 18.887393578886986, + 'timestamp_carla': 18887, + 'timestamp_device': 18355, + 'timestamp_stream': 18.887393578886986, + 'transform': [array([ 8.30638027e+00, -5.80531418e-01, 1.92188262e-03]), + array([ -0.02404226, -17.88895416, 0.14437841])]} +{'AngularVelocity': array([ -0.26843172, -0.1122148 , -10.66690445]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.336753845214844, + 'FR_Wheel_Angle': -30.565290451049805, + 'Location': array([5.24109764e+01, 1.44724607e+00, 1.69876812e-03]), + 'Rotation': array([-6.92581153e-03, 2.71406193e+01, -2.96325646e-02]), + 'Velocity': array([8.82414222e-01, 1.00631721e-01, 2.58827204e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 533.6185913085938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([807.64709473, 46.16151428, 0. ]), + 'frame': 975, + 'frame_number': 975, + 'framesequence': 973, + 'gaze_dir': array([ 0.98058069, 0.17381296, -0.09083289]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17381296, -0.09083289]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17381296, -0.09083289]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4921659231185913, + 'throttle_input': 0.0, + 'timestamp': 18.900526076555252, + 'timestamp_carla': 18900, + 'timestamp_device': 18368, + 'timestamp_stream': 18.900526076555252, + 'transform': [array([ 8.31529236e+00, -5.85514188e-01, 1.92783354e-03]), + array([ -0.02489604, -17.99311256, 0.15558264])]} +{'AngularVelocity': array([ -0.10514077, -0.04339099, -11.05625153]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -40.63789749145508, + 'FR_Wheel_Angle': -30.34449005126953, + 'Location': array([5.25844116e+01, 1.47166765e+00, 1.75633188e-03]), + 'Rotation': array([-8.27135891e-03, 2.49332809e+01, -1.78222656e-02]), + 'Velocity': array([ 8.98416579e-01, 5.41065075e-02, -8.57391336e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 535.3955688476562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.11130371e+02, 4.60294952e+01, -3.05175781e-05]), + 'frame': 976, + 'frame_number': 976, + 'framesequence': 974, + 'gaze_dir': array([ 0.98058057, 0.17506751, -0.08839069]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.17506751, -0.08839069]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.17506751, -0.08839069]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48053836822509766, + 'throttle_input': 0.0, + 'timestamp': 18.914141077548265, + 'timestamp_carla': 18914, + 'timestamp_device': 18382, + 'timestamp_stream': 18.914141077548265, + 'transform': [array([ 8.32424164e+00, -5.90941072e-01, 1.92790979e-03]), + array([ -0.02529902, -18.09983063, 0.16058493])]} +{'AngularVelocity': array([ -0.0624723 , -0.02489396, -11.25665855]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.367061614990234, + 'FR_Wheel_Angle': -30.575220108032227, + 'Location': array([5.27591438e+01, 1.48900545e+00, 1.87142135e-03]), + 'Rotation': array([-8.85192491e-03, 2.26868172e+01, -1.03149405e-02]), + 'Velocity': array([8.99792671e-01, 1.15795657e-02, 4.54540248e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 537.3568725585938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.14647766e+02, 4.58422623e+01, -3.05175781e-05]), + 'frame': 977, + 'frame_number': 977, + 'framesequence': 975, + 'gaze_dir': array([ 0.98058069, 0.17628796, -0.08593084]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17628796, -0.08593084]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17628796, -0.08593084]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46898403763771057, + 'throttle_input': 0.0, + 'timestamp': 18.927666276693344, + 'timestamp_carla': 18927, + 'timestamp_device': 18396, + 'timestamp_stream': 18.927666276693344, + 'transform': [array([ 8.33301735e+00, -5.96376598e-01, 1.92607881e-03]), + array([ -0.0252717 , -18.20343971, 0.16006693])]} +{'AngularVelocity': array([ -0.0399166 , -0.01728067, -11.36109352]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.363372802734375, + 'FR_Wheel_Angle': -30.570524215698242, + 'Location': array([5.29294167e+01, 1.49954462e+00, 1.73115486e-03]), + 'Rotation': array([-9.52128321e-03, 2.05056591e+01, -4.18090820e-03]), + 'Velocity': array([ 9.04368818e-01, -2.38441098e-02, -6.37826917e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 539.3630981445312, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.18216431e+02, 4.55825577e+01, 6.10351562e-05]), + 'frame': 978, + 'frame_number': 978, + 'framesequence': 976, + 'gaze_dir': array([ 0.98058069, 0.17739001, -0.08363216]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17739001, -0.08363216]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17739001, -0.08363216]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4590228199958801, + 'throttle_input': 0.0, + 'timestamp': 18.941413577646017, + 'timestamp_carla': 18941, + 'timestamp_device': 18409, + 'timestamp_stream': 18.941413577646017, + 'transform': [array([ 8.34187698e+00, -6.01878881e-01, 1.92085258e-03]), + array([ -0.02486872, -18.30609703, 0.15568265])]} +{'AngularVelocity': array([-1.50578031e-02, -1.09074973e-02, -1.14719810e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.35948944091797, + 'FR_Wheel_Angle': -30.567373275756836, + 'Location': array([5.30907516e+01, 1.50390756e+00, 1.76724186e-03]), + 'Rotation': array([-1.01974718e-02, 1.84422894e+01, 1.84170366e-03]), + 'Velocity': array([ 9.09151971e-01, -5.77025600e-02, 3.38773709e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 541.2661743164062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([821.62310791, 45.27615738, 0. ]), + 'frame': 979, + 'frame_number': 979, + 'framesequence': 977, + 'gaze_dir': array([ 0.98058069, 0.17854343, -0.08114059]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17854343, -0.08114059]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17854343, -0.08114059]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45327314734458923, + 'throttle_input': 0.0, + 'timestamp': 18.954747177660465, + 'timestamp_carla': 18954, + 'timestamp_device': 18423, + 'timestamp_stream': 18.954747177660465, + 'transform': [array([ 8.35042095e+00, -6.07183039e-01, 1.91684719e-03]), + array([ -0.02426083, -18.40366554, 0.14924543])]} +{'AngularVelocity': array([ 2.35126112e-02, -2.07815948e-03, -1.14375362e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.358699798583984, + 'FR_Wheel_Angle': -30.56491470336914, + 'Location': array([5.32461739e+01, 1.50301754e+00, 1.76880590e-03]), + 'Rotation': array([-1.10170944e-02, 1.64591045e+01, 7.97229633e-03]), + 'Velocity': array([ 9.07299757e-01, -8.84865671e-02, -3.11088545e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 543.3546752929688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([825.25378418, 44.95121384, 0. ]), + 'frame': 980, + 'frame_number': 980, + 'framesequence': 978, + 'gaze_dir': array([ 0.98058069, 0.17958319, -0.07881265]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.17958319, -0.07881265]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.17958319, -0.07881265]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4503982663154602, + 'throttle_input': 0.0, + 'timestamp': 18.968332778662443, + 'timestamp_carla': 18968, + 'timestamp_device': 18436, + 'timestamp_stream': 18.968332778662443, + 'transform': [array([ 8.35907364e+00, -6.12557590e-01, 1.91040034e-03]), + array([ -0.0234617 , -18.50165558, 0.14148018])]} +{'AngularVelocity': array([ 5.26402034e-02, 5.21874113e-04, -1.14223280e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.36046600341797, + 'FR_Wheel_Angle': -30.562885284423828, + 'Location': array([5.34032440e+01, 1.49698091e+00, 1.78028818e-03]), + 'Rotation': array([-1.17820753e-02, 1.44552832e+01, 1.38816303e-02]), + 'Velocity': array([ 9.01516795e-01, -1.20336130e-01, 3.10411444e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 545.3277587890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.28693604e+02, 4.46040039e+01, 6.10351562e-05]), + 'frame': 981, + 'frame_number': 981, + 'framesequence': 979, + 'gaze_dir': array([ 0.98058069, 0.18074508, -0.07611025]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18074508, -0.07611025]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18074508, -0.07611025]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4511307179927826, + 'throttle_input': 0.0, + 'timestamp': 18.982860878109932, + 'timestamp_carla': 18982, + 'timestamp_device': 18451, + 'timestamp_stream': 18.982860878109932, + 'transform': [array([ 8.36825752e+00, -6.18282020e-01, 1.89743040e-03]), + array([ -0.02254645, -18.60559654, 0.13263328])]} +{'AngularVelocity': array([ 9.05585065e-02, 3.83100635e-03, -1.13504276e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.362037658691406, + 'FR_Wheel_Angle': -30.562427520751953, + 'Location': array([5.35557899e+01, 1.48625755e+00, 1.78597204e-03]), + 'Rotation': array([-0.01257438, 12.50910187, 0.02013162]), + 'Velocity': array([ 8.94474387e-01, -1.50005624e-01, -1.35421749e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 547.6376342773438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.32548218e+02, 4.42456779e+01, -3.05175781e-05]), + 'frame': 982, + 'frame_number': 982, + 'framesequence': 980, + 'gaze_dir': array([ 0.98058069, 0.18171924, -0.07375411]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18171924, -0.07375411]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18171924, -0.07375411]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4546281397342682, + 'throttle_input': 0.0, + 'timestamp': 18.996265579015017, + 'timestamp_carla': 18996, + 'timestamp_device': 18464, + 'timestamp_stream': 18.996265579015017, + 'transform': [array([ 8.37666035e+00, -6.23553813e-01, 1.89319602e-03]), + array([ -0.02167219, -18.70139122, 0.12454305])]} +{'AngularVelocity': array([ 1.24347165e-01, 3.16518848e-03, -1.12719393e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.36992645263672, + 'FR_Wheel_Angle': -30.561485290527344, + 'Location': array([5.37091942e+01, 1.47050869e+00, 1.79604290e-03]), + 'Rotation': array([-0.01327789, 10.54785919, 0.0258939 ]), + 'Velocity': array([ 8.84075761e-01, -1.79519579e-01, 1.28169064e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 549.6728515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([836.12457275, 43.80196762, 0. ]), + 'frame': 983, + 'frame_number': 983, + 'framesequence': 981, + 'gaze_dir': array([ 0.98058057, 0.18266268, -0.0713855 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.18266268, -0.0713855 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.18266268, -0.0713855 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.45986512303352356, + 'throttle_input': 0.0, + 'timestamp': 19.009576477110386, + 'timestamp_carla': 19009, + 'timestamp_device': 18477, + 'timestamp_stream': 19.009576477110386, + 'transform': [array([ 8.38492870e+00, -6.28785968e-01, 1.88907620e-03]), + array([ -0.02078426, -18.79678917, 0.11676424])]} +{'AngularVelocity': array([ 1.44416720e-01, -1.86088646e-03, -1.11045847e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.374839782714844, + 'FR_Wheel_Angle': -30.559402465820312, + 'Location': array([5.38894424e+01, 1.44527447e+00, 1.79535628e-03]), + 'Rotation': array([-0.01358525, 8.23231792, 0.02874848]), + 'Velocity': array([ 8.63184094e-01, -2.12164417e-01, 1.86829566e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 551.73388671875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.39633179e+02, 4.33773079e+01, -3.05175781e-05]), + 'frame': 984, + 'frame_number': 984, + 'framesequence': 982, + 'gaze_dir': array([ 0.98058069, 0.18364416, -0.06882133]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18364416, -0.06882133]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18364416, -0.06882133]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.46501055359840393, + 'throttle_input': 0.0, + 'timestamp': 19.023548278957605, + 'timestamp_carla': 19023, + 'timestamp_device': 18491, + 'timestamp_stream': 19.023548278957605, + 'transform': [array([ 8.39352417e+00, -6.34277999e-01, 1.88083644e-03]), + array([ -0.01989634, -18.89737129, 0.10896211])]} +{'AngularVelocity': array([ 1.8369633e-01, -5.1701339e-03, -1.1139040e+01]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.37784957885742, + 'FR_Wheel_Angle': -30.559118270874023, + 'Location': array([5.40313454e+01, 1.42114651e+00, 1.80939434e-03]), + 'Rotation': array([-0.01489664, 6.40843725, 0.03843258]), + 'Velocity': array([ 8.57839048e-01, -2.40483075e-01, -9.70125184e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 553.97998046875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.43345642e+02, 4.29361610e+01, 3.05175781e-05]), + 'frame': 985, + 'frame_number': 985, + 'framesequence': 983, + 'gaze_dir': array([ 0.98058069, 0.18458962, -0.06624366]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18458962, -0.06624366]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18458962, -0.06624366]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47151097655296326, + 'throttle_input': 0.0, + 'timestamp': 19.036894377321005, + 'timestamp_carla': 19036, + 'timestamp_device': 18505, + 'timestamp_stream': 19.036894377321005, + 'transform': [array([ 8.40516186e+00, -6.36221230e-01, 1.88720704e-03]), + array([ -0.02034713, -18.99277306, 0.11921965])]} +{'AngularVelocity': array([ 0.215129 , -0.01344814, -11.02596855]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.380062103271484, + 'FR_Wheel_Angle': -30.558910369873047, + 'Location': array([5.41877899e+01, 1.38921821e+00, 1.80748699e-03]), + 'Rotation': array([-0.01562747, 4.3840766 , 0.04429938]), + 'Velocity': array([ 8.40119362e-01, -2.68192142e-01, 3.98287753e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 556.256103515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([847.1295166 , 42.43843842, 0. ]), + 'frame': 986, + 'frame_number': 986, + 'framesequence': 984, + 'gaze_dir': array([ 0.98058069, 0.18543519, -0.06383838]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18543519, -0.06383838]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18543519, -0.06383838]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4778832495212555, + 'throttle_input': 0.0, + 'timestamp': 19.05043187737465, + 'timestamp_carla': 19050, + 'timestamp_device': 18518, + 'timestamp_stream': 19.05043187737465, + 'transform': [array([ 8.41520023e+00, -6.40421510e-01, 1.89586636e-03]), + array([ -0.0215151 , -19.09225845, 0.13646582])]} +{'AngularVelocity': array([ 0.25363004, -0.02311574, -10.94115925]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.389102935791016, + 'FR_Wheel_Angle': -30.560142517089844, + 'Location': array([5.43272629e+01, 1.35661590e+00, 1.80340523e-03]), + 'Rotation': array([-0.01660419, 2.57177639, 0.05176739]), + 'Velocity': array([ 8.24606836e-01, -2.92674929e-01, -8.68654242e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 558.3428955078125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([850.99377441, 42.26894379, 0. ]), + 'frame': 987, + 'frame_number': 987, + 'framesequence': 985, + 'gaze_dir': array([ 0.98058069, 0.18631074, -0.06123612]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18631074, -0.06123612]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18631074, -0.06123612]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4841456413269043, + 'throttle_input': 0.0, + 'timestamp': 19.063774678856134, + 'timestamp_carla': 19063, + 'timestamp_device': 18532, + 'timestamp_stream': 19.063774678856134, + 'transform': [array([ 8.42423344e+00, -6.45522296e-01, 1.90429681e-03]), + array([ -0.02258061, -19.19403458, 0.14977324])]} +{'AngularVelocity': array([ 0.2764138 , -0.03448163, -10.79656124]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.393001556396484, + 'FR_Wheel_Angle': -30.56043243408203, + 'Location': array([5.44791145e+01, 1.31579661e+00, 1.78520917e-03]), + 'Rotation': array([-0.01702766, 0.58141851, 0.05586704]), + 'Velocity': array([ 8.03064942e-01, -3.17152083e-01, -3.48138798e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 560.5980834960938, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.54909851e+02, 4.18481560e+01, 3.05175781e-05]), + 'frame': 988, + 'frame_number': 988, + 'framesequence': 986, + 'gaze_dir': array([ 0.98058069, 0.18714975, -0.05862187]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18714975, -0.05862187]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18714975, -0.05862187]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48974886536598206, + 'throttle_input': 0.0, + 'timestamp': 19.077602177858353, + 'timestamp_carla': 19077, + 'timestamp_device': 18546, + 'timestamp_stream': 19.077602177858353, + 'transform': [array([ 8.43318844e+00, -6.51165128e-01, 1.90685270e-03]), + array([ -0.02325679, -19.30203438, 0.1568947 ])]} +{'AngularVelocity': array([ 0.30184394, -0.04847909, -10.64280128]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.40214157104492, + 'FR_Wheel_Angle': -30.560693740844727, + 'Location': array([5.46221809e+01, 1.27278328e+00, 1.84193370e-03]), + 'Rotation': array([-0.01748528, -1.30718994, 0.0599738 ]), + 'Velocity': array([ 7.80496180e-01, -3.38817924e-01, -2.12826722e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 562.8952026367188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([8.58768005e+02, 4.13042564e+01, 3.05175781e-05]), + 'frame': 989, + 'frame_number': 989, + 'framesequence': 987, + 'gaze_dir': array([ 0.98058069, 0.18789591, -0.0561843 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18789591, -0.0561843 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18789591, -0.0561843 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4934843182563782, + 'throttle_input': 0.0, + 'timestamp': 19.09091627970338, + 'timestamp_carla': 19090, + 'timestamp_device': 18559, + 'timestamp_stream': 19.09091627970338, + 'transform': [array([ 8.44161892e+00, -6.56706631e-01, 1.90990441e-03]), + array([ -0.02349585, -19.40701294, 0.15828842])]} +{'AngularVelocity': array([ 0.33314687, -0.06218209, -10.53960705]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4078483581543, + 'FR_Wheel_Angle': -30.56410789489746, + 'Location': array([5.47548332e+01, 1.22902703e+00, 1.81759591e-03]), + 'Rotation': array([-0.018462 , -3.06918406, 0.06764951]), + 'Velocity': array([ 7.62114227e-01, -3.59394342e-01, -4.31690220e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 565.0704956054688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([862.47015381, 40.6739006 , 0. ]), + 'frame': 990, + 'frame_number': 990, + 'framesequence': 988, + 'gaze_dir': array([ 0.98058069, 0.18861043, -0.05373689]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.18861043, -0.05373689]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.18861043, -0.05373689]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49458298087120056, + 'throttle_input': 0.0, + 'timestamp': 19.104603476822376, + 'timestamp_carla': 19104, + 'timestamp_device': 18572, + 'timestamp_stream': 19.104603476822376, + 'transform': [array([ 8.45016289e+00, -6.62433386e-01, 1.90826412e-03]), + array([ -0.02340023, -19.51492691, 0.15564035])]} +{'AngularVelocity': array([ 0.35890698, -0.07890058, -10.34578323]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4174690246582, + 'FR_Wheel_Angle': -30.569114685058594, + 'Location': array([5.48897743e+01, 1.17993939e+00, 1.80310011e-03]), + 'Rotation': array([-0.01883083, -4.88122797, 0.07133573]), + 'Velocity': array([ 7.38185346e-01, -3.76997411e-01, 9.49764217e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 567.291259765625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.66154846e+02, 4.00238304e+01, -3.05175781e-05]), + 'frame': 991, + 'frame_number': 991, + 'framesequence': 989, + 'gaze_dir': array([ 0.98058057, 0.18944608, -0.05071223]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.18944608, -0.05071223]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.18944608, -0.05071223]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4940885901451111, + 'throttle_input': 0.0, + 'timestamp': 19.118904776871204, + 'timestamp_carla': 19118, + 'timestamp_device': 18588, + 'timestamp_stream': 19.118904776871204, + 'transform': [array([ 8.45899677e+00, -6.68416560e-01, 1.90097804e-03]), + array([ -0.02301091, -19.62707329, 0.15000021])]} +{'AngularVelocity': array([ 0.36020666, -0.09351507, -10.16267014]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.42947769165039, + 'FR_Wheel_Angle': -30.569339752197266, + 'Location': array([5.50298233e+01, 1.12382507e+00, 1.83605903e-03]), + 'Rotation': array([-0.01868057, -6.78595591, 0.07128526]), + 'Velocity': array([ 7.10437298e-01, -3.93908173e-01, 1.53875342e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 570.0744018554688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([870.51269531, 39.3008194 , 0. ]), + 'frame': 992, + 'frame_number': 992, + 'framesequence': 990, + 'gaze_dir': array([ 0.98058057, 0.19008933, -0.04824512]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.19008933, -0.04824512]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.19008933, -0.04824512]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.49203774333000183, + 'throttle_input': 0.0, + 'timestamp': 19.132645279169083, + 'timestamp_carla': 19132, + 'timestamp_device': 18601, + 'timestamp_stream': 19.132645279169083, + 'transform': [array([ 8.46741390e+00, -6.74150586e-01, 1.89708709e-03]), + array([ -0.02243034, -19.73388672, 0.14299731])]} +{'AngularVelocity': array([ 0.39478779, -0.11148503, -10.06261063]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.43528747558594, + 'FR_Wheel_Angle': -30.572099685668945, + 'Location': array([5.51522751e+01, 1.07159936e+00, 1.83483830e-03]), + 'Rotation': array([-0.01993049, -8.46006298, 0.08162729]), + 'Velocity': array([ 6.91367507e-01, -4.10589397e-01, -1.44929887e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 572.3761596679688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([874.32391357, 38.53577423, 0. ]), + 'frame': 993, + 'frame_number': 993, + 'framesequence': 991, + 'gaze_dir': array([ 0.98058069, 0.19070037, -0.04577023]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19070037, -0.04577023]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19070037, -0.04577023]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48978546261787415, + 'throttle_input': 0.0, + 'timestamp': 19.146274980157614, + 'timestamp_carla': 19146, + 'timestamp_device': 18614, + 'timestamp_stream': 19.146274980157614, + 'transform': [array([ 8.47570515e+00, -6.79817736e-01, 1.89285271e-03]), + array([ -0.02169951, -19.83880234, 0.1352113 ])]} +{'AngularVelocity': array([ 0.4176223 , -0.13236821, -9.87994576]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.44562530517578, + 'FR_Wheel_Angle': -30.573158264160156, + 'Location': array([5.52753983e+01, 1.01503158e+00, 1.81290379e-03]), + 'Rotation': array([ -0.02050423, -10.1645031 , 0.08634384]), + 'Velocity': array([ 0.66646427, -0.42351288, 0.00081923]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 574.7096557617188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([878.11206055, 37.76699829, 0. ]), + 'frame': 994, + 'frame_number': 994, + 'framesequence': 992, + 'gaze_dir': array([ 0.98058069, 0.19127928, -0.04328723]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19127928, -0.04328723]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19127928, -0.04328723]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48665425181388855, + 'throttle_input': 0.0, + 'timestamp': 19.159331176429987, + 'timestamp_carla': 19159, + 'timestamp_device': 18627, + 'timestamp_stream': 19.159331176429987, + 'transform': [array([ 8.48359871e+00, -6.85223460e-01, 1.89159391e-03]), + array([ -0.02093453, -19.9382 , 0.12742688])]} +{'AngularVelocity': array([ 0.44932365, -0.15467149, -9.73881912]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4538688659668, + 'FR_Wheel_Angle': -30.576217651367188, + 'Location': array([5.53899384e+01, 9.59333122e-01, 1.82354683e-03]), + 'Rotation': array([ -0.0214263 , -11.76311016, 0.09451665]), + 'Velocity': array([ 6.44524574e-01, -4.35782641e-01, 1.07536311e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 577.0729370117188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([881.91088867, 36.9750061 , 0. ]), + 'frame': 995, + 'frame_number': 995, + 'framesequence': 993, + 'gaze_dir': array([ 0.98058069, 0.19182584, -0.04079692]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19182584, -0.04079692]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19182584, -0.04079692]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4837794303894043, + 'throttle_input': 0.0, + 'timestamp': 19.17245077714324, + 'timestamp_carla': 19172, + 'timestamp_device': 18640, + 'timestamp_stream': 19.17245077714324, + 'transform': [array([ 8.49148750e+00, -6.90630853e-01, 1.88865652e-03]), + array([ -0.02014223, -20.03698349, 0.11954414])]} +{'AngularVelocity': array([ 0.47007495, -0.17740004, -9.55340004]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.46799850463867, + 'FR_Wheel_Angle': -30.579565048217773, + 'Location': array([5.55037994e+01, 9.00316536e-01, 1.82633160e-03]), + 'Rotation': array([ -0.0218771 , -13.37260818, 0.09856626]), + 'Velocity': array([ 6.19659483e-01, -4.45321620e-01, 3.63635991e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 579.4638061523438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([885.68457031, 36.18156815, 0. ]), + 'frame': 996, + 'frame_number': 996, + 'framesequence': 994, + 'gaze_dir': array([ 0.98058069, 0.19237818, -0.03810746]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19237818, -0.03810746]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19237818, -0.03810746]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48062992095947266, + 'throttle_input': 0.0, + 'timestamp': 19.186272479593754, + 'timestamp_carla': 19186, + 'timestamp_device': 18654, + 'timestamp_stream': 19.186272479593754, + 'transform': [array([ 8.49975014e+00, -6.96299791e-01, 1.88125612e-03]), + array([-1.92884523e-02, -2.01398258e+01, 1.11364655e-01])]} +{'AngularVelocity': array([ 0.46901795, -0.19200312, -9.35737705]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.4757194519043, + 'FR_Wheel_Angle': -30.58414077758789, + 'Location': array([5.56217613e+01, 8.34876776e-01, 1.81561231e-03]), + 'Rotation': array([ -0.02200004, -15.0656004 , 0.10095119]), + 'Velocity': array([ 5.93516529e-01, -4.53986436e-01, 5.87143877e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 582.0664672851562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.89697021e+02, 3.53401451e+01, -3.05175781e-05]), + 'frame': 997, + 'frame_number': 997, + 'framesequence': 995, + 'gaze_dir': array([ 0.98058069, 0.1928928 , -0.03541053]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1928928 , -0.03541053]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1928928 , -0.03541053]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47749871015548706, + 'throttle_input': 0.0, + 'timestamp': 19.200199477374554, + 'timestamp_carla': 19200, + 'timestamp_device': 18668, + 'timestamp_stream': 19.200199477374554, + 'transform': [array([ 8.51174068e+00, -6.98423684e-01, 1.88411714e-03]), + array([-1.98690183e-02, -2.02411442e+01, 1.22550331e-01])]} +{'AngularVelocity': array([ 0.48477009, -0.21644275, -9.14548969]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.48787307739258, + 'FR_Wheel_Angle': -30.58745765686035, + 'Location': array([5.57324066e+01, 7.70128906e-01, 1.83029880e-03]), + 'Rotation': array([ -0.02206151, -16.67164421, 0.10256451]), + 'Velocity': array([ 5.66997349e-01, -4.60025311e-01, 2.06823344e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 584.7003784179688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([893.78186035, 34.43416214, 0. ]), + 'frame': 998, + 'frame_number': 998, + 'framesequence': 996, + 'gaze_dir': array([ 0.98058069, 0.19336963, -0.03270666]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19336963, -0.03270666]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19336963, -0.03270666]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4746604859828949, + 'throttle_input': 0.0, + 'timestamp': 19.213791377842426, + 'timestamp_carla': 19213, + 'timestamp_device': 18682, + 'timestamp_stream': 19.213791377842426, + 'transform': [array([ 8.52158833e+00, -7.02767074e-01, 1.89266203e-03]), + array([ -0.02111211, -20.34062958, 0.1401951 ])]} +{'AngularVelocity': array([ 0.49492475, -0.23702084, -8.94834232]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.49899673461914, + 'FR_Wheel_Angle': -30.59113883972168, + 'Location': array([5.58389969e+01, 7.04375207e-01, 1.83743238e-03]), + 'Rotation': array([ -0.02228008, -18.23850441, 0.10545885]), + 'Velocity': array([ 5.41949749e-01, -4.65261817e-01, -3.60574719e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 587.293212890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 8.98202515e+02, 3.38556290e+01, -3.05175781e-05]), + 'frame': 999, + 'frame_number': 999, + 'framesequence': 997, + 'gaze_dir': array([ 0.98058057, 0.19386813, -0.02960891]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.19386813, -0.02960891]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.19386813, -0.02960891]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47297587990760803, + 'throttle_input': 0.0, + 'timestamp': 19.22976027801633, + 'timestamp_carla': 19229, + 'timestamp_device': 18698, + 'timestamp_stream': 19.22976027801633, + 'transform': [array([ 8.53205967e+00, -7.09075272e-01, 1.88404077e-03]), + array([ -0.02234155, -20.4597168 , 0.15511297])]} +{'AngularVelocity': array([ 0.49803016, -0.25551656, -8.7436161 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.51078414916992, + 'FR_Wheel_Angle': -30.594871520996094, + 'Location': array([5.59428177e+01, 6.36924446e-01, 1.86115981e-03]), + 'Rotation': array([ -0.02249181, -19.78561401, 0.10780565]), + 'Velocity': array([ 5.16761243e-01, -4.68860418e-01, 2.17857363e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 590.27392578125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([902.8548584 , 32.97511292, 0. ]), + 'frame': 1000, + 'frame_number': 1000, + 'framesequence': 998, + 'gaze_dir': array([ 0.98058069, 0.19426371, -0.02689159]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19426371, -0.02689159]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19426371, -0.02689159]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47270119190216064, + 'throttle_input': 0.0, + 'timestamp': 19.244058679789305, + 'timestamp_carla': 19244, + 'timestamp_device': 18712, + 'timestamp_stream': 19.244058679789305, + 'transform': [array([ 8.54107380e+00, -7.15022504e-01, 1.88716885e-03]), + array([ -0.02292211, -20.56716156, 0.16072905])]} +{'AngularVelocity': array([ 0.51305473, -0.27908942, -8.55443192]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.52151870727539, + 'FR_Wheel_Angle': -30.600034713745117, + 'Location': array([5.60408134e+01, 5.70456326e-01, 1.86184642e-03]), + 'Rotation': array([ -0.02307238, -21.26165199, 0.11304771]), + 'Velocity': array([ 4.93283898e-01, -4.71771657e-01, -3.00407410e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 592.9121704101562, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([907.19433594, 31.88658142, 0. ]), + 'frame': 1001, + 'frame_number': 1001, + 'framesequence': 999, + 'gaze_dir': array([ 0.98058069, 0.19462113, -0.02416936]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19462113, -0.02416936]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19462113, -0.02416936]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.473415344953537, + 'throttle_input': 0.0, + 'timestamp': 19.258260678499937, + 'timestamp_carla': 19258, + 'timestamp_device': 18726, + 'timestamp_stream': 19.258260678499937, + 'transform': [array([ 8.54986477e+00, -7.20998287e-01, 1.88796991e-03]), + array([ -0.02304506, -20.67379189, 0.1604683 ])]} +{'AngularVelocity': array([ 0.51557833, -0.29907838, -8.33867073]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.533775329589844, + 'FR_Wheel_Angle': -30.604873657226562, + 'Location': array([5.61378746e+01, 5.01164794e-01, 1.85490365e-03]), + 'Rotation': array([ -0.02307238, -22.74794006, 0.11398093]), + 'Velocity': array([ 4.68393415e-01, -4.72315580e-01, -1.41048431e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 595.6181640625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([911.42443848, 30.8026886 , 0. ]), + 'frame': 1002, + 'frame_number': 1002, + 'framesequence': 1000, + 'gaze_dir': array([ 0.98058069, 0.19494042, -0.0214424 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19494042, -0.0214424 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19494042, -0.0214424 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4746604859828949, + 'throttle_input': 0.0, + 'timestamp': 19.271698877215385, + 'timestamp_carla': 19271, + 'timestamp_device': 18740, + 'timestamp_stream': 19.271698877215385, + 'transform': [array([ 8.55808353e+00, -7.26663649e-01, 1.89132686e-03]), + array([ -0.02282649, -20.77440643, 0.15669642])]} +{'AngularVelocity': array([ 0.54685241, -0.32927752, -8.18968105]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.54208755493164, + 'FR_Wheel_Angle': -30.612424850463867, + 'Location': array([5.62228241e+01, 4.39219356e-01, 1.85997726e-03]), + 'Rotation': array([ -0.02459551, -24.04936028, 0.12703626]), + 'Velocity': array([ 4.49150264e-01, -4.74456787e-01, -3.62186431e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 598.3771362304688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([915.67504883, 29.67596436, 0. ]), + 'frame': 1003, + 'frame_number': 1003, + 'framesequence': 1001, + 'gaze_dir': array([ 0.98058069, 0.19518366, -0.0191018 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19518366, -0.0191018 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19518366, -0.0191018 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4763084948062897, + 'throttle_input': 0.0, + 'timestamp': 19.284412678331137, + 'timestamp_carla': 19284, + 'timestamp_device': 18752, + 'timestamp_stream': 19.284412678331137, + 'transform': [array([ 8.56578636e+00, -7.32020617e-01, 1.89594261e-03]), + array([ -0.02243034, -20.86934853, 0.15116073])]} +{'AngularVelocity': array([ 0.55962259, -0.3582058 , -7.97935963]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.5570068359375, + 'FR_Wheel_Angle': -30.613094329833984, + 'Location': array([5.63089523e+01, 3.72842252e-01, 1.86619512e-03]), + 'Rotation': array([-2.47457735e-02, -2.53981094e+01, 1.28487214e-01]), + 'Velocity': array([ 4.26153988e-01, -4.72675532e-01, -1.82771677e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 600.7808837890625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.19435486e+02, 2.86132126e+01, -6.10351562e-05]), + 'frame': 1004, + 'frame_number': 1004, + 'framesequence': 1002, + 'gaze_dir': array([ 0.98058069, 0.19543193, -0.01636746]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19543193, -0.01636746]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19543193, -0.01636746]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47786495089530945, + 'throttle_input': 0.0, + 'timestamp': 19.297783978283405, + 'timestamp_carla': 19297, + 'timestamp_device': 18766, + 'timestamp_stream': 19.297783978283405, + 'transform': [array([ 8.57381344e+00, -7.37646639e-01, 1.89468381e-03]), + array([ -0.02184294, -20.96892548, 0.14406191])]} +{'AngularVelocity': array([ 0.54836899, -0.36774385, -7.77589941]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.56846237182617, + 'FR_Wheel_Angle': -30.61888313293457, + 'Location': array([5.63958969e+01, 3.02856743e-01, 1.85967202e-03]), + 'Rotation': array([-2.48687174e-02, -2.67815399e+01, 1.30549207e-01]), + 'Velocity': array([ 4.03845787e-01, -4.70511913e-01, 1.82476040e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 603.618408203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.23621460e+02, 2.74867096e+01, -3.05175781e-05]), + 'frame': 1005, + 'frame_number': 1005, + 'framesequence': 1003, + 'gaze_dir': array([ 0.98058069, 0.19562821, -0.01382544]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19562821, -0.01382544]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19562821, -0.01382544]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4795861840248108, + 'throttle_input': 0.0, + 'timestamp': 19.311155278235674, + 'timestamp_carla': 19311, + 'timestamp_device': 18779, + 'timestamp_stream': 19.311155278235674, + 'transform': [array([ 8.58177376e+00, -7.43262827e-01, 1.89243315e-03]), + array([ -0.02117359, -21.06822395, 0.13633402])]} +{'AngularVelocity': array([ 0.54435384, -0.3848314 , -7.56226444]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.57785415649414, + 'FR_Wheel_Angle': -30.623350143432617, + 'Location': array([5.64802971e+01, 2.32044175e-01, 1.84643501e-03]), + 'Rotation': array([-2.48960387e-02, -2.81452255e+01, 1.31616622e-01]), + 'Velocity': array([ 0.38142112, -0.46688449, 0.00065012]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 606.2880859375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.27644531e+02, 2.63264923e+01, -3.05175781e-05]), + 'frame': 1006, + 'frame_number': 1006, + 'framesequence': 1004, + 'gaze_dir': array([ 0.98058069, 0.19580258, -0.01108539]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19580258, -0.01108539]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19580258, -0.01108539]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4808862507343292, + 'throttle_input': 0.0, + 'timestamp': 19.32474807649851, + 'timestamp_carla': 19324, + 'timestamp_device': 18793, + 'timestamp_stream': 19.32474807649851, + 'transform': [array([ 8.58979797e+00, -7.48960316e-01, 1.88808434e-03]), + array([-2.04086043e-02, -2.11688766e+01, 1.28239349e-01])]} +{'AngularVelocity': array([ 0.55856711, -0.41546932, -7.3591218 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.58934020996094, + 'FR_Wheel_Angle': -30.6283016204834, + 'Location': array([5.65576897e+01, 1.65728971e-01, 1.85032596e-03]), + 'Rotation': array([-2.51760762e-02, -2.94006405e+01, 1.33995876e-01]), + 'Velocity': array([ 3.60698819e-01, -4.62593138e-01, -1.62501325e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 609.192626953125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([931.91809082, 25.09279633, 0. ]), + 'frame': 1007, + 'frame_number': 1007, + 'framesequence': 1005, + 'gaze_dir': array([ 0.98058069, 0.19593015, -0.00853899]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19593015, -0.00853899]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19593015, -0.00853899]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4824061095714569, + 'throttle_input': 0.0, + 'timestamp': 19.33816357702017, + 'timestamp_carla': 19338, + 'timestamp_device': 18806, + 'timestamp_stream': 19.33816357702017, + 'transform': [array([ 8.59765244e+00, -7.54570961e-01, 1.88426964e-03]), + array([-1.96504537e-02, -2.12679348e+01, 1.20307036e-01])]} +{'AngularVelocity': array([ 0.54617047, -0.42692819, -7.14574289]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.60147476196289, + 'FR_Wheel_Angle': -30.633703231811523, + 'Location': array([5.66341896e+01, 9.71787646e-02, 1.86775916e-03]), + 'Rotation': array([-2.47730948e-02, -3.06665783e+01, 1.31997660e-01]), + 'Velocity': array([ 3.39933157e-01, -4.56836313e-01, 9.79328106e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 611.9208984375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([935.98913574, 23.85172272, 0. ]), + 'frame': 1008, + 'frame_number': 1008, + 'framesequence': 1006, + 'gaze_dir': array([ 0.98058069, 0.19602458, -0.00599153]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.19602458, -0.00599153]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.19602458, -0.00599153]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48315683007240295, + 'throttle_input': 0.0, + 'timestamp': 19.351033177226782, + 'timestamp_carla': 19351, + 'timestamp_device': 18819, + 'timestamp_stream': 19.351033177226782, + 'transform': [array([ 8.60513210e+00, -7.59940624e-01, 1.88335415e-03]), + array([-1.89127922e-02, -2.13626022e+01, 1.12900861e-01])]} +{'AngularVelocity': array([ 0.56660134, -0.45573783, -6.98725557]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.61293029785156, + 'FR_Wheel_Angle': -30.643171310424805, + 'Location': array([5.67021179e+01, 3.59862894e-02, 1.85364485e-03]), + 'Rotation': array([-2.60640010e-02, -3.17830372e+01, 1.43490151e-01]), + 'Velocity': array([ 3.23394716e-01, -4.53300267e-01, -4.04720311e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 614.6744995117188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([9.40059692e+02, 2.25863419e+01, 3.05175781e-05]), + 'frame': 1009, + 'frame_number': 1009, + 'framesequence': 1007, + 'gaze_dir': array([ 0.98058069, 0.1960859 , -0.00344268]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, 0.1960859 , -0.00344268]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, 0.1960859 , -0.00344268]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48315683007240295, + 'throttle_input': 0.0, + 'timestamp': 19.36412037909031, + 'timestamp_carla': 19364, + 'timestamp_device': 18832, + 'timestamp_stream': 19.36412037909031, + 'transform': [array([ 8.61642838e+00, -7.61809349e-01, 1.88541412e-03]), + array([-1.95001885e-02, -2.14566231e+01, 1.23085804e-01])]} +{'AngularVelocity': array([ 0.55099714, -0.46495426, -6.77266788]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.62251281738281, + 'FR_Wheel_Angle': -30.643218994140625, + 'Location': array([ 5.67746277e+01, -3.38899791e-02, 1.86833134e-03]), + 'Rotation': array([-2.56610196e-02, -3.30194588e+01, 1.40902817e-01]), + 'Velocity': array([ 3.03621948e-01, -4.46051270e-01, 3.64789943e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 617.4530639648438, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.44104370e+02, 2.13159790e+01, -3.05175781e-05]), + 'frame': 1010, + 'frame_number': 1010, + 'framesequence': 1008, + 'gaze_dir': array([ 9.80580688e-01, 1.96114898e-01, -6.97240466e-04]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 9.80580688e-01, 1.96114898e-01, -6.97240466e-04]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 9.80580688e-01, 1.96114898e-01, -6.97240466e-04]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4827723205089569, + 'throttle_input': 0.0, + 'timestamp': 19.378098879009485, + 'timestamp_carla': 19378, + 'timestamp_device': 18846, + 'timestamp_stream': 19.378098879009485, + 'transform': [array([ 8.62639904e+00, -7.66251802e-01, 1.88755034e-03]), + array([-2.09072083e-02, -2.15577888e+01, 1.42121896e-01])]} +{'AngularVelocity': array([ 0.54442728, -0.4821339 , -6.5633564 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.634361267089844, + 'FR_Wheel_Angle': -30.651649475097656, + 'Location': array([ 5.68425636e+01, -1.00379176e-01, 1.85879460e-03]), + 'Rotation': array([-2.52102260e-02, -3.41814117e+01, 1.38192475e-01]), + 'Velocity': array([ 2.85045266e-01, -4.38231796e-01, 3.56483470e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 620.39453125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.48723755e+02, 2.03219299e+01, -3.05175781e-05]), + 'frame': 1011, + 'frame_number': 1011, + 'framesequence': 1009, + 'gaze_dir': array([0.98058069, 0.19610542, 0.00204833]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19610542, 0.00204833]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19610542, 0.00204833]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48205816745758057, + 'throttle_input': 0.0, + 'timestamp': 19.392092678695917, + 'timestamp_carla': 19392, + 'timestamp_device': 18860, + 'timestamp_stream': 19.392092678695917, + 'transform': [array([ 8.63535500e+00, -7.71786869e-01, 1.88980100e-03]), + array([ -0.02215713, -21.6613636 , 0.1568768 ])]} +{'AngularVelocity': array([ 0.5679602 , -0.51552391, -6.38687658]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -41.46971893310547, + 'FR_Wheel_Angle': -30.251779556274414, + 'Location': array([ 5.69026337e+01, -1.59527928e-01, 1.84220076e-03]), + 'Rotation': array([-2.66104154e-02, -3.52012711e+01, 1.49804577e-01]), + 'Velocity': array([ 0.27113977, -0.43281218, -0.00076901]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 623.32421875, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([953.2088623, 19.0244751, 0. ]), + 'frame': 1012, + 'frame_number': 1012, + 'framesequence': 1010, + 'gaze_dir': array([0.98058069, 0.19606222, 0.00459756]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19606222, 0.00459756]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19606222, 0.00459756]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4812158942222595, + 'throttle_input': 0.0, + 'timestamp': 19.4055799767375, + 'timestamp_carla': 19405, + 'timestamp_device': 18873, + 'timestamp_stream': 19.4055799767375, + 'transform': [array([ 8.64359951e+00, -7.77451515e-01, 1.89311977e-03]), + array([ -0.02288796, -21.76228523, 0.16403969])]} +{'AngularVelocity': array([ 0.58173865, -0.54904127, -5.09464788]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -31.811912536621094, + 'FR_Wheel_Angle': -24.03772735595703, + 'Location': array([ 5.69654999e+01, -2.20706061e-01, 1.91887608e-03]), + 'Rotation': array([-2.57566422e-02, -3.61511497e+01, 1.46745771e-01]), + 'Velocity': array([ 0.29592377, -0.41356635, 0.00130566]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 626.08203125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([957.38769531, 17.62454987, 0. ]), + 'frame': 1013, + 'frame_number': 1013, + 'framesequence': 1011, + 'gaze_dir': array([0.98058069, 0.19597864, 0.00734188]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19597864, 0.00734188]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19597864, 0.00734188]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4804101884365082, + 'throttle_input': 0.0, + 'timestamp': 19.419513177126646, + 'timestamp_carla': 19419, + 'timestamp_device': 18887, + 'timestamp_stream': 19.419513177126646, + 'transform': [array([ 8.65193558e+00, -7.83396006e-01, 1.89121242e-03]), + array([ -0.02316117, -21.86647415, 0.16516817])]} +{'AngularVelocity': array([ 0.54538083, -0.50854307, -3.68845224]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -20.275020599365234, + 'FR_Wheel_Angle': -16.2016658782959, + 'Location': array([ 5.70443916e+01, -2.92957425e-01, 1.79020641e-03]), + 'Rotation': array([-2.13033594e-02, -3.69994659e+01, 1.32601619e-01]), + 'Velocity': array([ 0.36194164, -0.41776216, -0.00067799]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 629.1182861328125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([961.78308105, 16.11812592, 0. ]), + 'frame': 1014, + 'frame_number': 1014, + 'framesequence': 1012, + 'gaze_dir': array([0.98058069, 0.19585665, 0.01008476]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19585665, 0.01008476]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19585665, 0.01008476]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47943970561027527, + 'throttle_input': 0.0, + 'timestamp': 19.433107379823923, + 'timestamp_carla': 19433, + 'timestamp_device': 18901, + 'timestamp_stream': 19.433107379823923, + 'transform': [array([ 8.65996838e+00, -7.89210141e-01, 1.88983919e-03]), + array([ -0.02304506, -21.96754646, 0.16205969])]} +{'AngularVelocity': array([ 0.49330008, -0.44428992, -1.76366186]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': -8.91225814819336, + 'FR_Wheel_Angle': -7.353987216949463, + 'Location': array([ 5.71423721e+01, -3.74475867e-01, 1.80176494e-03]), + 'Rotation': array([-1.61124151e-02, -3.75760307e+01, 1.12251468e-01]), + 'Velocity': array([ 4.44554597e-01, -4.15917814e-01, 9.21249375e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 632.2095336914062, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([966.23553467, 14.5321579 , 0. ]), + 'frame': 1015, + 'frame_number': 1015, + 'framesequence': 1013, + 'gaze_dir': array([0.98058069, 0.195709 , 0.01263006]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.195709 , 0.01263006]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.195709 , 0.01263006]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4785790741443634, + 'throttle_input': 0.0, + 'timestamp': 19.446623276919127, + 'timestamp_carla': 19446, + 'timestamp_device': 18914, + 'timestamp_stream': 19.446623276919127, + 'transform': [array([ 8.66788006e+00, -7.94982255e-01, 1.88739772e-03]), + array([ -0.0226694 , -22.06733704, 0.15633653])]} +{'AngularVelocity': array([ 0.47595364, -0.40540391, -0.02285832]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.72385292e+01, -4.42916751e-01, 1.77376508e-03]), + 'Rotation': array([-1.30934715e-02, -3.77141800e+01, 1.13452598e-01]), + 'Velocity': array([ 0.52855998, -0.41512215, -0.00058454]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 635.1253051757812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([970.44067383, 12.98088837, 0. ]), + 'frame': 1016, + 'frame_number': 1016, + 'framesequence': 1014, + 'gaze_dir': array([0.98058069, 0.19551301, 0.01536865]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19551301, 0.01536865]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19551301, 0.01536865]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47823116183280945, + 'throttle_input': 0.0, + 'timestamp': 19.460012078285217, + 'timestamp_carla': 19460, + 'timestamp_device': 18928, + 'timestamp_stream': 19.460012078285217, + 'transform': [array([ 8.67565441e+00, -8.00685585e-01, 1.88461295e-03]), + array([-2.21298113e-02, -2.21655121e+01, 1.49161801e-01])]} +{'AngularVelocity': array([ 0.47082326, -0.38288563, -0.00691203]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.73359604e+01, -5.09316266e-01, 1.75728556e-03]), + 'Rotation': array([-1.05321510e-02, -3.77132988e+01, 1.21637993e-01]), + 'Velocity': array([ 5.65648437e-01, -4.43324149e-01, -5.75923914e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 638.3038940429688, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.74908630e+02, 1.13320923e+01, -3.05175781e-05]), + 'frame': 1017, + 'frame_number': 1017, + 'framesequence': 1015, + 'gaze_dir': array([0.98058069, 0.19529673, 0.01790867]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19529673, 0.01790867]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19529673, 0.01790867]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4782677888870239, + 'throttle_input': 0.0, + 'timestamp': 19.473507177084684, + 'timestamp_carla': 19473, + 'timestamp_device': 18941, + 'timestamp_stream': 19.473507177084684, + 'transform': [array([ 8.68342781e+00, -8.06417465e-01, 1.88053132e-03]), + array([-2.14536227e-02, -2.22638721e+01, 1.41139761e-01])]} +{'AngularVelocity': array([ 0.46449071, -0.36917639, 0.03234193]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.74495506e+01, -5.88694155e-01, 1.78509473e-03]), + 'Rotation': array([-9.06366017e-03, -3.77127419e+01, 1.15667500e-01]), + 'Velocity': array([ 0.56881303, -0.44571662, -0.00069739]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 641.2896728515625, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.79132996e+02, 9.71603394e+00, -3.05175781e-05]), + 'frame': 1018, + 'frame_number': 1018, + 'framesequence': 1016, + 'gaze_dir': array([0.98058069, 0.1950061 , 0.02083625]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1950061 , 0.02083625]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1950061 , 0.02083625]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47859737277030945, + 'throttle_input': 0.0, + 'timestamp': 19.488265078514814, + 'timestamp_carla': 19488, + 'timestamp_device': 18956, + 'timestamp_stream': 19.488265078514814, + 'transform': [array([ 8.69186115e+00, -8.12665820e-01, 1.86782831e-03]), + array([-2.06340011e-02, -2.23708038e+01, 1.31981000e-01])]} +{'AngularVelocity': array([ 4.38541919e-01, -3.45280617e-01, -9.70593646e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.75722313e+01, -6.74524307e-01, 1.71841378e-03]), + 'Rotation': array([-8.42162315e-03, -3.77117081e+01, 1.05563603e-01]), + 'Velocity': array([ 0.56675076, -0.44383472, -0.00168417]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 644.7647705078125, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([983.8838501 , 7.91835785, 0. ]), + 'frame': 1019, + 'frame_number': 1019, + 'framesequence': 1017, + 'gaze_dir': array([0.98058069, 0.19469528, 0.0235642 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19469528, 0.0235642 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19469528, 0.0235642 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4790917932987213, + 'throttle_input': 0.0, + 'timestamp': 19.50192167982459, + 'timestamp_carla': 19501, + 'timestamp_device': 18970, + 'timestamp_stream': 19.50192167982459, + 'transform': [array([ 8.69960403e+00, -8.18430483e-01, 1.86386099e-03]), + array([-1.98348686e-02, -2.24692516e+01, 1.23607464e-01])]} +{'AngularVelocity': array([ 4.39489871e-01, -3.44480693e-01, -6.39990913e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.76819267e+01, -7.50294983e-01, 1.81557413e-03]), + 'Rotation': array([-8.27135891e-03, -3.77105522e+01, 1.07473545e-01]), + 'Velocity': array([ 5.67819059e-01, -4.44643319e-01, -1.24588012e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 648.0436401367188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([988.48272705, 6.07361603, 0. ]), + 'frame': 1020, + 'frame_number': 1020, + 'framesequence': 1018, + 'gaze_dir': array([0.98058069, 0.19434634, 0.02628752]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19434634, 0.02628752]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19434634, 0.02628752]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4796777367591858, + 'throttle_input': 0.0, + 'timestamp': 19.51596087962389, + 'timestamp_carla': 19515, + 'timestamp_device': 18984, + 'timestamp_stream': 19.51596087962389, + 'transform': [array([ 8.70750332e+00, -8.24338198e-01, 1.85752870e-03]), + array([-1.90084148e-02, -2.25699940e+01, 1.15219600e-01])]} +{'AngularVelocity': array([ 4.63166416e-01, -3.61828297e-01, -2.91938954e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.77830315e+01, -8.19347501e-01, 1.79104565e-03]), + 'Rotation': array([-8.20988696e-03, -3.77094803e+01, 1.16828807e-01]), + 'Velocity': array([ 5.71850121e-01, -4.47944492e-01, 6.25657995e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 651.34912109375, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([993.01556396, 4.25003052, 0. ]), + 'frame': 1021, + 'frame_number': 1021, + 'framesequence': 1019, + 'gaze_dir': array([0.98058069, 0.19395927, 0.02900569]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19395927, 0.02900569]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19395927, 0.02900569]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4801538288593292, + 'throttle_input': 0.0, + 'timestamp': 19.529978778213263, + 'timestamp_carla': 19529, + 'timestamp_device': 18998, + 'timestamp_stream': 19.529978778213263, + 'transform': [array([ 8.71938992e+00, -8.26515436e-01, 1.86180114e-03]), + array([-1.96777731e-02, -2.26680126e+01, 1.27080739e-01])]} +{'AngularVelocity': array([ 4.53369528e-01, -3.54773611e-01, -1.04734208e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.78947639e+01, -8.96663785e-01, 1.77086587e-03]), + 'Rotation': array([-8.08694400e-03, -3.77084427e+01, 1.10144496e-01]), + 'Velocity': array([ 5.67556858e-01, -4.44603592e-01, 1.80249204e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 654.6819458007812, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 9.97583618e+02, 2.36225128e+00, -6.10351562e-05]), + 'frame': 1022, + 'frame_number': 1022, + 'framesequence': 1020, + 'gaze_dir': array([0.98058069, 0.1935024 , 0.03191159]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1935024 , 0.03191159]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1935024 , 0.03191159]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4804101884365082, + 'throttle_input': 0.0, + 'timestamp': 19.544831477105618, + 'timestamp_carla': 19544, + 'timestamp_device': 19013, + 'timestamp_stream': 19.544831477105618, + 'transform': [array([ 8.72961235e+00, -8.31476450e-01, 1.86592084e-03]), + array([-2.12077368e-02, -2.27731743e+01, 1.47656232e-01])]} +{'AngularVelocity': array([ 4.56062257e-01, -3.56226146e-01, -7.88745892e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.80005264e+01, -9.69347000e-01, 1.73756352e-03]), + 'Rotation': array([-8.08694400e-03, -3.77074394e+01, 1.13114119e-01]), + 'Velocity': array([ 5.69850266e-01, -4.46338713e-01, 4.05807485e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 658.1803588867188, + 'focus_actor_name': 'Road_Road_Town05_121', + 'focus_actor_pt': array([ 1.00273340e+03, 7.43011475e-01, -3.05175781e-05]), + 'frame': 1023, + 'frame_number': 1023, + 'framesequence': 1021, + 'gaze_dir': array([0.98058069, 0.19300193, 0.03481068]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19300193, 0.03481068]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19300193, 0.03481068]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.48053836822509766, + 'throttle_input': 0.0, + 'timestamp': 19.559355277568102, + 'timestamp_carla': 19559, + 'timestamp_device': 19028, + 'timestamp_stream': 19.559355277568102, + 'transform': [array([ 8.73856354e+00, -8.37377071e-01, 1.87164289e-03]), + array([-2.24644914e-02, -2.28787079e+01, 1.62150741e-01])]} +{'AngularVelocity': array([ 4.76272851e-01, -3.71589631e-01, -3.47035279e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.81010818e+01, -1.03794467e+00, 1.74767256e-03]), + 'Rotation': array([-8.12109467e-03, -3.77063675e+01, 1.19919449e-01]), + 'Velocity': array([ 5.72344184e-01, -4.48450983e-01, 8.65936236e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 661.6627807617188, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1007.70355225, -1.21468353, 0. ]), + 'frame': 1024, + 'frame_number': 1024, + 'framesequence': 1022, + 'gaze_dir': array([0.98058069, 0.19249569, 0.0375092 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19249569, 0.0375092 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19249569, 0.0375092 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4803735613822937, + 'throttle_input': 0.0, + 'timestamp': 19.574166178703308, + 'timestamp_carla': 19574, + 'timestamp_device': 19042, + 'timestamp_stream': 19.574166178703308, + 'transform': [array([ 8.74728680e+00, -8.43706846e-01, 1.87278725e-03]), + array([ -0.02316117, -22.98752975, 0.16848268])]} +{'AngularVelocity': array([ 4.72508043e-01, -3.69325012e-01, -9.17832040e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.82098503e+01, -1.11308885e+00, 1.74973242e-03]), + 'Rotation': array([-8.05962272e-03, -3.77053337e+01, 1.14285670e-01]), + 'Velocity': array([ 0.56890273, -0.44580501, -0.00077382]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 664.96142578125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.01232629e+03, -3.23680878e+00, -3.05175781e-05]), + 'frame': 1025, + 'frame_number': 1025, + 'framesequence': 1023, + 'gaze_dir': array([0.98058069, 0.19195171, 0.04020036]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19195171, 0.04020036]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19195171, 0.04020036]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800073504447937, + 'throttle_input': 0.0, + 'timestamp': 19.587611977010965, + 'timestamp_carla': 19587, + 'timestamp_device': 19056, + 'timestamp_stream': 19.587611977010965, + 'transform': [array([ 8.75505257e+00, -8.49515975e-01, 1.87953934e-03]), + array([ -0.02333876, -23.0862236 , 0.16849566])]} +{'AngularVelocity': array([ 4.51091766e-01, -3.52696061e-01, -1.04182118e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.83210907e+01, -1.19009376e+00, 1.78066967e-03]), + 'Rotation': array([-8.02547205e-03, -3.77043228e+01, 1.09275036e-01]), + 'Velocity': array([ 5.67583501e-01, -4.44551319e-01, -3.19156650e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 668.3253173828125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1016.97790527, -5.36295319, 0. ]), + 'frame': 1026, + 'frame_number': 1026, + 'framesequence': 1024, + 'gaze_dir': array([0.98058069, 0.19141296, 0.04269199]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19141296, 0.04269199]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19141296, 0.04269199]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4795861840248108, + 'throttle_input': 0.0, + 'timestamp': 19.601334378123283, + 'timestamp_carla': 19601, + 'timestamp_device': 19069, + 'timestamp_stream': 19.601334378123283, + 'transform': [array([ 8.76288414e+00, -8.55450511e-01, 1.88179000e-03]), + array([-2.31611710e-02, -2.31864147e+01, 1.64553791e-01])]} +{'AngularVelocity': array([ 0.47061768, -0.36692408, 0.00139391]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.84194069e+01, -1.25722849e+00, 1.75301312e-03]), + 'Rotation': array([-8.0869440e-03, -3.7703289e+01, 1.2014357e-01]), + 'Velocity': array([ 5.73155761e-01, -4.48936194e-01, 2.36625667e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 671.5025634765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.02129816e+03, -7.37176514e+00, 3.05175781e-05]), + 'frame': 1027, + 'frame_number': 1027, + 'framesequence': 1025, + 'gaze_dir': array([0.98058069, 0.19079652, 0.04536749]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19079652, 0.04536749]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19079652, 0.04536749]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4794580042362213, + 'throttle_input': 0.0, + 'timestamp': 19.61527207866311, + 'timestamp_carla': 19615, + 'timestamp_device': 19083, + 'timestamp_stream': 19.61527207866311, + 'transform': [array([ 8.77076054e+00, -8.61467183e-01, 1.88045483e-03]), + array([-2.27308683e-02, -2.32875824e+01, 1.58032820e-01])]} +{'AngularVelocity': array([ 0.44806966, -0.35028726, 0.01915734]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.85382423e+01, -1.34033179e+00, 1.74763438e-03]), + 'Rotation': array([-7.99815077e-03, -3.77021255e+01, 1.09902538e-01]), + 'Velocity': array([ 5.68589449e-01, -4.45252568e-01, 2.61096953e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 674.9682006835938, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1025.9173584 , -9.53635406, 0. ]), + 'frame': 1028, + 'frame_number': 1028, + 'framesequence': 1026, + 'gaze_dir': array([0.98058069, 0.19014272, 0.0480341 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.19014272, 0.0480341 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.19014272, 0.0480341 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47932982444763184, + 'throttle_input': 0.0, + 'timestamp': 19.62885557860136, + 'timestamp_carla': 19628, + 'timestamp_device': 19097, + 'timestamp_stream': 19.62885557860136, + 'transform': [array([ 8.77837372e+00, -8.67314994e-01, 1.88003515e-03]), + array([-2.21298113e-02, -2.33855400e+01, 1.50334239e-01])]} +{'AngularVelocity': array([ 0.46403661, -0.3621732 , 0.03381953]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.86413841e+01, -1.41104722e+00, 1.72085525e-03]), + 'Rotation': array([-8.02547205e-03, -3.77008743e+01, 1.15613714e-01]), + 'Velocity': array([ 5.71063936e-01, -4.47277635e-01, -2.61640555e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 678.4714965820312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.03056433e+03, -1.17610855e+01, -3.05175781e-05]), + 'frame': 1029, + 'frame_number': 1029, + 'framesequence': 1027, + 'gaze_dir': array([0.98058069, 0.18950218, 0.05050192]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18950218, 0.05050192]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18950218, 0.05050192]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4794580042362213, + 'throttle_input': 0.0, + 'timestamp': 19.641981977969408, + 'timestamp_carla': 19641, + 'timestamp_device': 19110, + 'timestamp_stream': 19.641981977969408, + 'transform': [array([ 8.78567314e+00, -8.72949302e-01, 1.88072189e-03]), + array([-2.14263014e-02, -2.34796867e+01, 1.42280683e-01])]} +{'AngularVelocity': array([ 0.45283902, -0.35350695, 0.00367292]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.87565079e+01, -1.49152923e+00, 1.79505104e-03]), + 'Rotation': array([-8.02547205e-03, -3.76990776e+01, 1.12004064e-01]), + 'Velocity': array([ 5.70112824e-01, -4.46398765e-01, -6.03198987e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 681.7554931640625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.03493152e+03, -1.39082489e+01, 3.05175781e-05]), + 'frame': 1030, + 'frame_number': 1030, + 'framesequence': 1028, + 'gaze_dir': array([0.98058069, 0.18877663, 0.05314991]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18877663, 0.05314991]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18877663, 0.05314991]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.47969603538513184, + 'throttle_input': 0.0, + 'timestamp': 19.65615137666464, + 'timestamp_carla': 19656, + 'timestamp_device': 19124, + 'timestamp_stream': 19.65615137666464, + 'transform': [array([ 8.79349136e+00, -8.79011571e-01, 1.87408424e-03]), + array([-2.05998495e-02, -2.35807323e+01, 1.33302361e-01])]} +{'AngularVelocity': array([ 4.47443128e-01, -3.49284619e-01, 1.21806013e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.88704071e+01, -1.57077348e+00, 1.78658240e-03]), + 'Rotation': array([-8.05962272e-03, -3.76979790e+01, 1.11378632e-01]), + 'Velocity': array([ 5.70346355e-01, -4.46493626e-01, 2.63881684e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 685.3146362304688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.03953833e+03, -1.61688690e+01, -3.05175781e-05]), + 'frame': 1031, + 'frame_number': 1031, + 'framesequence': 1029, + 'gaze_dir': array([0.98058069, 0.18801405, 0.05578747]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18801405, 0.05578747]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18801405, 0.05578747]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800073504447937, + 'throttle_input': 0.0, + 'timestamp': 19.669849079102278, + 'timestamp_carla': 19669, + 'timestamp_device': 19138, + 'timestamp_stream': 19.669849079102278, + 'transform': [array([ 8.80099201e+00, -8.84853363e-01, 1.87046034e-03]), + array([-1.97733957e-02, -2.36778965e+01, 1.24732159e-01])]} +{'AngularVelocity': array([ 4.54092890e-01, -3.54297101e-01, -2.11949487e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.89811211e+01, -1.64722002e+00, 1.76258804e-03]), + 'Rotation': array([-8.08694400e-03, -3.76969070e+01, 1.14117622e-01]), + 'Velocity': array([ 5.71529210e-01, -4.47450131e-01, -3.01265718e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 688.900634765625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1044.21691895, -18.53996277, 0. ]), + 'frame': 1032, + 'frame_number': 1032, + 'framesequence': 1030, + 'gaze_dir': array([0.98058069, 0.18727292, 0.05822696]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18727292, 0.05822696]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18727292, 0.05822696]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800439774990082, + 'throttle_input': 0.0, + 'timestamp': 19.683127779513597, + 'timestamp_carla': 19683, + 'timestamp_device': 19151, + 'timestamp_stream': 19.683127779513597, + 'transform': [array([ 8.80821133e+00, -8.90497804e-01, 1.86901074e-03]), + array([-1.89810954e-02, -2.37715855e+01, 1.16675101e-01])]} +{'AngularVelocity': array([ 4.52453792e-01, -3.53774011e-01, -9.95894516e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.90920334e+01, -1.72385156e+00, 1.76144356e-03]), + 'Rotation': array([-8.02547205e-03, -3.76958694e+01, 1.09894052e-01]), + 'Velocity': array([ 5.67988396e-01, -4.44784075e-01, -9.03129549e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 692.2531127929688, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1048.59765625, -20.81643677, 0. ]), + 'frame': 1033, + 'frame_number': 1033, + 'framesequence': 1031, + 'gaze_dir': array([0.98058069, 0.18643941, 0.06084298]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18643941, 0.06084298]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18643941, 0.06084298]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.69711657986045, + 'timestamp_carla': 19697, + 'timestamp_device': 19165, + 'timestamp_stream': 19.69711657986045, + 'transform': [array([ 8.82000256e+00, -8.92664194e-01, 1.86882005e-03]), + array([-1.96504537e-02, -2.38674736e+01, 1.28591850e-01])]} +{'AngularVelocity': array([ 4.59446311e-01, -3.58653933e-01, -8.05927411e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.91965942e+01, -1.79560792e+00, 1.74107309e-03]), + 'Rotation': array([-8.05962272e-03, -3.76948967e+01, 1.14189245e-01]), + 'Velocity': array([ 5.70531845e-01, -4.46765065e-01, 1.65433885e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 695.8787231445312, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1053.21716309, -23.21651459, 0. ]), + 'frame': 1034, + 'frame_number': 1034, + 'framesequence': 1032, + 'gaze_dir': array([0.98058069, 0.18556936, 0.06344708]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18556936, 0.06344708]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18556936, 0.06344708]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.711565978825092, + 'timestamp_carla': 19711, + 'timestamp_device': 19179, + 'timestamp_stream': 19.711565978825092, + 'transform': [array([ 8.82978725e+00, -8.97481620e-01, 1.87194790e-03]), + array([-2.11735852e-02, -2.39675999e+01, 1.49144277e-01])]} +{'AngularVelocity': array([ 4.75753486e-01, -3.71193349e-01, -5.28129340e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.92984657e+01, -1.86531305e+00, 1.76186324e-03]), + 'Rotation': array([-8.08694400e-03, -3.76938553e+01, 1.19006597e-01]), + 'Velocity': array([ 5.71923673e-01, -4.47992474e-01, 6.48069399e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 699.414794921875, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1058.20410156, -25.30230713, 0. ]), + 'frame': 1035, + 'frame_number': 1035, + 'framesequence': 1033, + 'gaze_dir': array([0.98058069, 0.18466295, 0.06603873]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18466295, 0.06603873]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18466295, 0.06603873]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.72478437796235, + 'timestamp_carla': 19724, + 'timestamp_device': 19193, + 'timestamp_stream': 19.72478437796235, + 'transform': [array([ 8.83775997e+00, -9.02846515e-01, 1.88163726e-03]), + array([-2.24030185e-02, -2.40615673e+01, 1.63464904e-01])]} +{'AngularVelocity': array([ 4.38388169e-01, -3.42832476e-01, -1.72787841e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.94207077e+01, -1.95084560e+00, 1.74332375e-03]), + 'Rotation': array([-8.02547205e-03, -3.76927834e+01, 1.05596639e-01]), + 'Velocity': array([ 5.66715062e-01, -4.43623900e-01, -3.83033737e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 702.9204711914062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1062.95385742, -27.70423126, 0. ]), + 'frame': 1036, + 'frame_number': 1036, + 'framesequence': 1034, + 'gaze_dir': array([0.98058069, 0.18378884, 0.0684338 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18378884, 0.0684338 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18378884, 0.0684338 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.7380651794374, + 'timestamp_carla': 19738, + 'timestamp_device': 19206, + 'timestamp_stream': 19.7380651794374, + 'transform': [array([ 8.84538174e+00, -9.08542752e-01, 1.88808411e-03]), + array([-2.31611710e-02, -2.41572018e+01, 1.70797840e-01])]} +{'AngularVelocity': array([ 0.43898344, -0.3432551 , 0.01731104]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.95303078e+01, -2.02674413e+00, 1.73523661e-03]), + 'Rotation': array([-8.02547205e-03, -3.76916313e+01, 1.07291326e-01]), + 'Velocity': array([ 5.68206310e-01, -4.44728374e-01, 2.98595423e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 706.219970703125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1067.27941895, -30.07495117, 0. ]), + 'frame': 1037, + 'frame_number': 1037, + 'framesequence': 1035, + 'gaze_dir': array([0.98058069, 0.1828128 , 0.07100003]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1828128 , 0.07100003]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1828128 , 0.07100003]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.751233778893948, + 'timestamp_carla': 19751, + 'timestamp_device': 19220, + 'timestamp_stream': 19.751233778893948, + 'transform': [array([ 8.85276699e+00, -9.14274275e-01, 1.89174619e-03]), + array([-2.34616976e-02, -2.42521763e+01, 1.72133282e-01])]} +{'AngularVelocity': array([ 0.44597626, -0.34845927, 0.0201369 ]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.96384850e+01, -2.10149121e+00, 1.74427743e-03]), + 'Rotation': array([-8.02547205e-03, -3.76904984e+01, 1.09507225e-01]), + 'Velocity': array([ 5.68854213e-01, -4.45296288e-01, 1.08690263e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 709.8350219726562, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.07187537e+03, -3.26565094e+01, 3.05175781e-05]), + 'frame': 1038, + 'frame_number': 1038, + 'framesequence': 1036, + 'gaze_dir': array([0.98058069, 0.18187433, 0.07337063]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18187433, 0.07337063]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18187433, 0.07337063]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.76537737995386, + 'timestamp_carla': 19765, + 'timestamp_device': 19233, + 'timestamp_stream': 19.76537737995386, + 'transform': [array([ 8.86058712e+00, -9.20445740e-01, 1.88724487e-03]), + array([-2.33729053e-02, -2.43537979e+01, 1.68856546e-01])]} +{'AngularVelocity': array([ 0.45498562, -0.35533378, 0.01186464]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.97449493e+01, -2.17514086e+00, 1.76251167e-03]), + 'Rotation': array([-8.02547205e-03, -3.76893692e+01, 1.11969233e-01]), + 'Velocity': array([ 5.69655657e-01, -4.45991635e-01, 4.16374205e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 713.2382202148438, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.07620654e+03, -3.51672211e+01, 3.05175781e-05]), + 'frame': 1039, + 'frame_number': 1039, + 'framesequence': 1037, + 'gaze_dir': array([0.98058069, 0.18082936, 0.07590958]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.18082936, 0.07590958]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.18082936, 0.07590958]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.779689479619265, + 'timestamp_carla': 19779, + 'timestamp_device': 19247, + 'timestamp_stream': 19.779689479619265, + 'transform': [array([ 8.86841583e+00, -9.26681638e-01, 1.88056915e-03]), + array([-2.29835846e-02, -2.44560623e+01, 1.62506446e-01])]} +{'AngularVelocity': array([ 4.51022506e-01, -3.52352649e-01, -5.01188006e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.98537102e+01, -2.25027347e+00, 1.75709487e-03]), + 'Rotation': array([-8.02547205e-03, -3.76883354e+01, 1.10888697e-01]), + 'Velocity': array([ 0.56884021, -0.44532794, 0.00057507]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 716.94580078125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.08087866e+03, -3.79210892e+01, -3.05175781e-05]), + 'frame': 1040, + 'frame_number': 1040, + 'framesequence': 1038, + 'gaze_dir': array([0.98058069, 0.17974894, 0.07843366]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17974894, 0.07843366]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17974894, 0.07843366]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.792913276702166, + 'timestamp_carla': 19792, + 'timestamp_device': 19261, + 'timestamp_stream': 19.792913276702166, + 'transform': [array([ 8.87558651e+00, -9.32428420e-01, 1.88030209e-03]), + array([-2.24303398e-02, -2.45499973e+01, 1.55152082e-01])]} +{'AngularVelocity': array([ 4.56083506e-01, -3.56040001e-01, -2.12369287e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 5.99593315e+01, -2.32281280e+00, 1.72837020e-03]), + 'Rotation': array([-8.05962272e-03, -3.76872978e+01, 1.13673888e-01]), + 'Velocity': array([ 0.57023376, -0.44641349, 0.00094892]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 720.68798828125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.08556555e+03, -4.07363129e+01, -3.05175781e-05]), + 'frame': 1041, + 'frame_number': 1041, + 'framesequence': 1039, + 'gaze_dir': array([0.98058069, 0.17871425, 0.08076345]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17871425, 0.08076345]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17871425, 0.08076345]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.806420978158712, + 'timestamp_carla': 19806, + 'timestamp_device': 19274, + 'timestamp_stream': 19.806420978158712, + 'transform': [array([ 8.88285351e+00, -9.38280523e-01, 1.87744107e-03]), + array([-2.17268299e-02, -2.46453934e+01, 1.46805614e-01])]} +{'AngularVelocity': array([ 4.66904968e-01, -3.64457667e-01, -8.83098328e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.00643692e+01, -2.39489460e+00, 1.71223399e-03]), + 'Rotation': array([-8.02547205e-03, -3.76862869e+01, 1.15507901e-01]), + 'Velocity': array([ 5.70589125e-01, -4.46807325e-01, 1.23262405e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 724.1871337890625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1089.91247559, -43.38848877, 0. ]), + 'frame': 1042, + 'frame_number': 1042, + 'framesequence': 1040, + 'gaze_dir': array([0.98058069, 0.1775661 , 0.08325744]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1775661 , 0.08325744]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1775661 , 0.08325744]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.82009917870164, + 'timestamp_carla': 19820, + 'timestamp_device': 19288, + 'timestamp_stream': 19.82009917870164, + 'transform': [array([ 8.89015579e+00, -9.44186687e-01, 1.87267270e-03]), + array([-2.09345277e-02, -2.47414360e+01, 1.38022020e-01])]} +{'AngularVelocity': array([ 0.46739805, -0.36499056, 0.00054561]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.01707878e+01, -2.46843171e+00, 1.73882244e-03]), + 'Rotation': array([-7.99815077e-03, -3.76852875e+01, 1.14572778e-01]), + 'Velocity': array([ 5.69942474e-01, -4.46322352e-01, -1.14784241e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 727.9739990234375, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([1094.54272461, -46.23863983, 0. ]), + 'frame': 1043, + 'frame_number': 1043, + 'framesequence': 1041, + 'gaze_dir': array([0.98058069, 0.17638314, 0.08573512]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17638314, 0.08573512]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17638314, 0.08573512]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.83404627814889, + 'timestamp_carla': 19834, + 'timestamp_device': 19302, + 'timestamp_stream': 19.83404627814889, + 'transform': [array([ 8.89754581e+00, -9.50188041e-01, 1.86630210e-03]), + array([-2.00807545e-02, -2.48387833e+01, 1.29068941e-01])]} +{'AngularVelocity': array([ 4.66006905e-01, -3.63846332e-01, 2.66463088e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.02770653e+01, -2.54173970e+00, 1.74515485e-03]), + 'Rotation': array([-7.96400011e-03, -3.76841507e+01, 1.14289604e-01]), + 'Velocity': array([ 5.69988370e-01, -4.46326703e-01, -3.65467073e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 731.7779541015625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.09917358e+03, -4.91454926e+01, -3.05175781e-05]), + 'frame': 1044, + 'frame_number': 1044, + 'framesequence': 1042, + 'gaze_dir': array([0.98058069, 0.17516559, 0.08819599]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17516559, 0.08819599]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17516559, 0.08819599]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.848316177725792, + 'timestamp_carla': 19848, + 'timestamp_device': 19316, + 'timestamp_stream': 19.848316177725792, + 'transform': [array([ 8.90504837e+00, -9.56305683e-01, 1.85806246e-03]), + array([-1.91996600e-02, -2.49378147e+01, 1.20139167e-01])]} +{'AngularVelocity': array([ 4.53064889e-01, -3.53987575e-01, -9.22940035e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.03877220e+01, -2.61819363e+00, 1.78383582e-03]), + 'Rotation': array([-7.96400011e-03, -3.76830864e+01, 1.10071771e-01]), + 'Velocity': array([ 5.68142474e-01, -4.44777161e-01, -1.37310024e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 735.5962524414062, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.10380835e+03, -5.21154099e+01, 9.15527344e-05]), + 'frame': 1045, + 'frame_number': 1045, + 'framesequence': 1043, + 'gaze_dir': array([0.98058069, 0.17391355, 0.0906399 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17391355, 0.0906399 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17391355, 0.0906399 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.862251479178667, + 'timestamp_carla': 19862, + 'timestamp_device': 19330, + 'timestamp_stream': 19.862251479178667, + 'transform': [array([ 8.91672039e+00, -9.58461523e-01, 1.86439476e-03]), + array([-1.98690183e-02, -2.50314407e+01, 1.32064879e-01])]} +{'AngularVelocity': array([ 4.33989614e-01, -3.39320481e-01, -1.82584427e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.05015907e+01, -2.69715071e+00, 1.77624461e-03]), + 'Rotation': array([-7.96400011e-03, -3.76820450e+01, 1.05255000e-01]), + 'Velocity': array([ 5.66586614e-01, -4.43348885e-01, 4.10122855e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 739.4283447265625, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.10844849e+03, -5.51523285e+01, 3.05175781e-05]), + 'frame': 1046, + 'frame_number': 1046, + 'framesequence': 1044, + 'gaze_dir': array([0.98058069, 0.1726276 , 0.09306572]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.1726276 , 0.09306572]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.1726276 , 0.09306572]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.875815976411104, + 'timestamp_carla': 19875, + 'timestamp_device': 19344, + 'timestamp_stream': 19.875815976411104, + 'transform': [array([ 8.92580318e+00, -9.62925553e-01, 1.87694503e-03]), + array([-2.13306788e-02, -2.51233921e+01, 1.51707873e-01])]} +{'AngularVelocity': array([ 4.58511174e-01, -3.57500851e-01, -4.58368731e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.06028595e+01, -2.76627874e+00, 1.75385235e-03]), + 'Rotation': array([-8.05962272e-03, -3.76810417e+01, 1.15617141e-01]), + 'Velocity': array([ 5.71976781e-01, -4.47681695e-01, 1.97067260e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 743.1495361328125, + 'focus_actor_name': 'Road_Road_Town05_169', + 'focus_actor_pt': array([ 1.11338379e+03, -5.77934189e+01, -3.05175781e-05]), + 'frame': 1047, + 'frame_number': 1047, + 'framesequence': 1045, + 'gaze_dir': array([0.98058069, 0.17130782, 0.0954733 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([0.98058069, 0.17130782, 0.0954733 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([0.98058069, 0.17130782, 0.0954733 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.4800622761249542, + 'throttle_input': 0.0, + 'timestamp': 19.889702577143908, + 'timestamp_carla': 19889, + 'timestamp_device': 19358, + 'timestamp_stream': 19.889702577143908, + 'transform': [array([ 8.93396378e+00, -9.68578160e-01, 1.88602402e-03]), + array([-2.26693973e-02, -2.52201328e+01, 1.67452544e-01])]} +{'AngularVelocity': array([ 4.80633080e-01, -3.74911636e-01, -3.47410833e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.07043381e+01, -2.83564878e+00, 1.75076246e-03]), + 'Rotation': array([-8.08694400e-03, -3.76800652e+01, 1.20098121e-01]), + 'Velocity': array([ 5.72325706e-01, -4.48211968e-01, -1.42822260e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 909.2007446289062, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1442.39343262, -719.6026001 , 9.86004639]), + 'frame': 1571, + 'frame_number': 1571, + 'framesequence': 1569, + 'gaze_dir': array([ 0.98058057, -0.04518042, 0.19084096]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.04518042, 0.19084096]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.04518042, 0.19084096]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0003295999194961041, + 'throttle_input': 0.0, + 'timestamp': 27.46768267825246, + 'timestamp_carla': 27467, + 'timestamp_device': 26936, + 'timestamp_stream': 27.46768267825246, + 'transform': [array([ 1.22911072e+01, -4.06820011e+00, 1.78161485e-03]), + array([-6.01056591e-03, -4.97783279e+01, 1.21624649e-01])]} +{'AngularVelocity': array([ 4.85704392e-01, -3.78931671e-01, -6.49993171e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.08067856e+01, -2.90575099e+00, 1.75953622e-03]), + 'Rotation': array([-8.08694400e-03, -3.76790504e+01, 1.20962285e-01]), + 'Velocity': array([ 5.72017014e-01, -4.48036730e-01, -6.17027263e-06]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 906.5309448242188, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1439.18432617, -719.66003418, 10.21191406]), + 'frame': 1572, + 'frame_number': 1572, + 'framesequence': 1570, + 'gaze_dir': array([ 0.98058069, -0.0480381 , 0.19014175]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.0480381 , 0.19014175]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.0480381 , 0.19014175]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0011535997036844492, + 'throttle_input': 0.0, + 'timestamp': 27.483447078615427, + 'timestamp_carla': 27483, + 'timestamp_device': 26951, + 'timestamp_stream': 27.483447078615427, + 'transform': [array([ 1.22994642e+01, -4.07423496e+00, 1.76891207e-03]), + array([-6.01056591e-03, -4.97779884e+01, 1.52323067e-01])]} +{'AngularVelocity': array([ 4.64137048e-01, -3.62139165e-01, 7.41131998e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.09206886e+01, -2.98474121e+00, 1.75358530e-03]), + 'Rotation': array([-8.08694400e-03, -3.76779289e+01, 1.14825055e-01]), + 'Velocity': array([ 5.70692718e-01, -4.46759671e-01, -1.65405276e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 904.3058471679688, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1436.84399414, -719.69006348, 10.40518188]), + 'frame': 1573, + 'frame_number': 1573, + 'framesequence': 1571, + 'gaze_dir': array([ 0.98058069, -0.05088459, 0.18939985]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05088459, 0.18939985]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05088459, 0.18939985]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0016113773453980684, + 'throttle_input': 0.0, + 'timestamp': 27.497877079993486, + 'timestamp_carla': 27497, + 'timestamp_device': 26966, + 'timestamp_stream': 27.497877079993486, + 'transform': [array([ 1.23057899e+01, -4.08077240e+00, 1.76902651e-03]), + array([-6.01056591e-03, -4.97778435e+01, 1.72399387e-01])]} +{'AngularVelocity': array([ 4.50304419e-01, -3.51348847e-01, -7.13574336e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.10348358e+01, -3.06393528e+00, 1.73680065e-03]), + 'Rotation': array([-8.08694400e-03, -3.76768875e+01, 1.11996911e-01]), + 'Velocity': array([ 5.70321083e-01, -4.46297318e-01, 4.03146725e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 901.7095947265625, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1434.02270508, -719.73791504, 10.70013428]), + 'frame': 1574, + 'frame_number': 1574, + 'framesequence': 1572, + 'gaze_dir': array([ 0.98058069, -0.05371964, 0.18861535]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05371964, 0.18861535]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05371964, 0.18861535]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00139164412394166, + 'throttle_input': 0.0, + 'timestamp': 27.512697279453278, + 'timestamp_carla': 27512, + 'timestamp_device': 26981, + 'timestamp_stream': 27.512697279453278, + 'transform': [array([ 1.23118992e+01, -4.08770943e+00, 1.76666141e-03]), + array([-6.04471704e-03, -4.97778053e+01, 1.81831017e-01])]} +{'AngularVelocity': array([ 0.45945224, -0.35870603, 0.00050106]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.11409569e+01, -3.13730407e+00, 1.74732925e-03]), + 'Rotation': array([-8.08694400e-03, -3.76759148e+01, 1.13528706e-01]), + 'Velocity': array([ 5.70086360e-01, -4.46235001e-01, 4.98504611e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 899.07666015625, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1430.98291016, -719.78076172, 10.97171021]), + 'frame': 1575, + 'frame_number': 1575, + 'framesequence': 1573, + 'gaze_dir': array([ 0.98058069, -0.05804334, 0.18732998]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.05804334, 0.18732998]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.05804334, 0.18732998]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.000988799729384482, + 'throttle_input': 0.0, + 'timestamp': 27.535800278186798, + 'timestamp_carla': 27535, + 'timestamp_device': 27004, + 'timestamp_stream': 27.535800278186798, + 'transform': [array([ 1.23211803e+01, -4.09853554e+00, 1.75845972e-03]), + array([-6.07203785e-03, -4.97778053e+01, 1.80795833e-01])]} +{'AngularVelocity': array([ 4.74855214e-01, -3.70286644e-01, -4.45509431e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.12425652e+01, -3.20676994e+00, 1.74656627e-03]), + 'Rotation': array([-8.12109467e-03, -3.76749382e+01, 1.18948162e-01]), + 'Velocity': array([ 5.72209477e-01, -4.48001266e-01, 4.36687442e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 895.4654541015625, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1426.21594238, -719.8067627 , 11.1751709 ]), + 'frame': 1576, + 'frame_number': 1576, + 'framesequence': 1574, + 'gaze_dir': array([ 0.98058069, -0.06456297, 0.18518415]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06456297, 0.18518415]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06456297, 0.18518415]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0004577776708174497, + 'throttle_input': 0.0, + 'timestamp': 27.57114727795124, + 'timestamp_carla': 27571, + 'timestamp_device': 27039, + 'timestamp_stream': 27.57114727795124, + 'transform': [array([ 1.23350840e+01, -4.11491156e+00, 1.71691773e-03]), + array([-6.07203785e-03, -4.97778130e+01, 1.61923885e-01])]} +{'AngularVelocity': array([ 4.63892162e-01, -3.61867428e-01, -1.97300710e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.13554039e+01, -3.28493094e+00, 1.74713845e-03]), + 'Rotation': array([-8.08694400e-03, -3.76738091e+01, 1.15210891e-01]), + 'Velocity': array([ 5.71221411e-01, -4.47109431e-01, -3.12204356e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 890.0614624023438, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1419.04602051, -719.81433105, 11.30987549]), + 'frame': 1577, + 'frame_number': 1577, + 'framesequence': 1575, + 'gaze_dir': array([ 0.98058069, -0.06548792, 0.1848591 ]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06548792, 0.1848591 ]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06548792, 0.1848591 ]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0010254220105707645, + 'throttle_input': 0.0, + 'timestamp': 27.57612017914653, + 'timestamp_carla': 27576, + 'timestamp_device': 27044, + 'timestamp_stream': 27.57612017914653, + 'transform': [array([ 1.23370199e+01, -4.11719799e+00, 1.73053623e-03]), + array([-6.07203785e-03, -4.97778473e+01, 1.58829495e-01])]} +{'AngularVelocity': array([ 4.70012993e-01, -3.66784871e-01, -3.06904767e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.14602394e+01, -3.35692525e+00, 1.75949803e-03]), + 'Rotation': array([-8.05962272e-03, -3.76727371e+01, 1.16397277e-01]), + 'Velocity': array([ 5.70870817e-01, -4.46923435e-01, 5.43975802e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 887.4932250976562, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1418.27978516, -719.91931152, 11.88668823]), + 'frame': 1578, + 'frame_number': 1578, + 'framesequence': 1576, + 'gaze_dir': array([ 0.98058069, -0.06825358, 0.18385594]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.06825358, 0.18385594]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.06825358, 0.18385594]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.0009338664240203798, + 'throttle_input': 0.0, + 'timestamp': 27.590581577271223, + 'timestamp_carla': 27590, + 'timestamp_device': 27059, + 'timestamp_stream': 27.590581577271223, + 'transform': [array([ 1.23426189e+01, -4.12381172e+00, 1.74045435e-03]), + array([-6.07203785e-03, -4.97778625e+01, 1.49137139e-01])]} +{'AngularVelocity': array([ 4.74040866e-01, -3.69835526e-01, 1.68774677e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.15648193e+01, -3.42882466e+00, 1.76350353e-03]), + 'Rotation': array([-8.02547205e-03, -3.76716995e+01, 1.17045596e-01]), + 'Velocity': array([ 5.70966661e-01, -4.47031081e-01, -2.34441759e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 885.5223999023438, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1415.21557617, -719.89074707, 11.77304077]), + 'frame': 1579, + 'frame_number': 1579, + 'framesequence': 1577, + 'gaze_dir': array([ 0.98058069, -0.07136915, 0.18266909]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.07136915, 0.18266909]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.07136915, 0.18266909]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -0.00069582206197083, + 'throttle_input': 0.0, + 'timestamp': 27.6078458763659, + 'timestamp_carla': 27607, + 'timestamp_device': 27076, + 'timestamp_stream': 27.6078458763659, + 'transform': [array([ 1.23492479e+01, -4.13164806e+00, 1.72706484e-03]), + array([-6.04471704e-03, -4.97779007e+01, 1.37311295e-01])]} +{'AngularVelocity': array([ 4.75762397e-01, -3.71251553e-01, 1.23604885e-04]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.16702194e+01, -3.50142169e+00, 1.75553083e-03]), + 'Rotation': array([-7.99815077e-03, -3.76707268e+01, 1.16331749e-01]), + 'Velocity': array([ 0.57059163, -0.4467665 , -0.00104629]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 882.8334350585938, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1411.84143066, -719.87878418, 11.75360107]), + 'frame': 1580, + 'frame_number': 1580, + 'framesequence': 1578, + 'gaze_dir': array([ 0.98058069, -0.10541164, 0.16537818]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10541164, 0.16537818]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10541164, 0.16537818]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': -7.32444241293706e-05, + 'throttle_input': 0.0, + 'timestamp': 27.691352982074022, + 'timestamp_carla': 27691, + 'timestamp_device': 27271, + 'timestamp_stream': 27.691352982074022, + 'transform': [array([ 1.23903179e+01, -4.16564798e+00, 1.69746310e-03]), + array([-6.10618899e-03, -4.97771683e+01, 2.02597409e-01])]} +{'AngularVelocity': array([ 4.48790252e-01, -3.50731730e-01, -9.09161884e-07]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.17829971e+01, -3.57970238e+00, 1.80432072e-03]), + 'Rotation': array([-7.96400011e-03, -3.76697502e+01, 1.08675830e-01]), + 'Velocity': array([ 5.67385495e-01, -4.44013000e-01, 2.81667708e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 862.8031616210938, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1374.17285156, -718.63684082, 5.54125977]), + 'frame': 1581, + 'frame_number': 1581, + 'framesequence': 1579, + 'gaze_dir': array([ 0.98058069, -0.10656669, 0.16463627]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10656669, 0.16463627]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10656669, 0.16463627]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 27.80979408696294, + 'timestamp_carla': 27809, + 'timestamp_device': 27278, + 'timestamp_stream': 27.80979408696294, + 'transform': [array([ 1.24290819e+01, -4.21145630e+00, 1.65405148e-03]), + array([-5.92177361e-03, -4.97738152e+01, 1.31521761e-01])]} +{'AngularVelocity': array([ 4.55481052e-01, -3.55334103e-01, 4.16010844e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.18884850e+01, -3.65219665e+00, 1.76800485e-03]), + 'Rotation': array([-8.02547205e-03, -3.76687698e+01, 1.12812869e-01]), + 'Velocity': array([ 5.70300221e-01, -4.46264207e-01, -1.89971925e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 858.2169799804688, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1374.93811035, -718.85028076, 6.68405151]), + 'frame': 1582, + 'frame_number': 1582, + 'framesequence': 1580, + 'gaze_dir': array([ 0.98058069, -0.10886107, 0.16312826]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.10886107, 0.16312826]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.10886107, 0.16312826]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 27.82369128614664, + 'timestamp_carla': 27823, + 'timestamp_device': 27292, + 'timestamp_stream': 27.82369128614664, + 'transform': [array([ 1.24343348e+01, -4.21766758e+00, 1.69895054e-03]), + array([-5.86030213e-03, -4.97744179e+01, 1.22473344e-01])]} +{'AngularVelocity': array([ 4.64866966e-01, -3.62693310e-01, 1.68995120e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.19926453e+01, -3.72385097e+00, 1.76914921e-03]), + 'Rotation': array([-8.05962272e-03, -3.76677284e+01, 1.15900248e-01]), + 'Velocity': array([ 5.71090817e-01, -4.46971506e-01, 5.29532437e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 851.61083984375, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1373.48498535, -719.04534912, 7.75576782]), + 'frame': 1583, + 'frame_number': 1583, + 'framesequence': 1581, + 'gaze_dir': array([ 0.98058057, -0.11097255, 0.16169925]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11097255, 0.16169925]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11097255, 0.16169925]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 27.837300684303045, + 'timestamp_carla': 27837, + 'timestamp_device': 27305, + 'timestamp_stream': 27.837300684303045, + 'transform': [array([ 1.24394445e+01, -4.22371435e+00, 1.73572416e-03]), + array([-5.83298132e-03, -4.97744484e+01, 1.14050172e-01])]} +{'AngularVelocity': array([ 4.74496633e-01, -3.70059937e-01, -1.25873585e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.20961800e+01, -3.79479432e+00, 1.74484961e-03]), + 'Rotation': array([-8.02547205e-03, -3.76666641e+01, 1.18014470e-01]), + 'Velocity': array([ 5.71531653e-01, -4.47405279e-01, 9.81616977e-05]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 849.8128662109375, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1371.31213379, -718.96020508, 7.32550049]), + 'frame': 1584, + 'frame_number': 1584, + 'framesequence': 1582, + 'gaze_dir': array([ 0.98058057, -0.11338536, 0.16001661]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11338536, 0.16001661]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11338536, 0.16001661]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 27.85188728570938, + 'timestamp_carla': 27851, + 'timestamp_device': 27320, + 'timestamp_stream': 27.85188728570938, + 'transform': [array([ 1.24448862e+01, -4.23015404e+00, 1.76074856e-03]), + array([-5.79883019e-03, -4.97744865e+01, 1.05510339e-01])]} +{'AngularVelocity': array([ 4.54698265e-01, -3.55263323e-01, -7.38306017e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.22087975e+01, -3.87279248e+00, 1.74778700e-03]), + 'Rotation': array([-7.96400011e-03, -3.76656914e+01, 1.09592110e-01]), + 'Velocity': array([ 5.67598045e-01, -4.44204509e-01, -3.51438503e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 847.9010009765625, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1368.81213379, -718.84814453, 6.75332642]), + 'frame': 1585, + 'frame_number': 1585, + 'framesequence': 1583, + 'gaze_dir': array([ 0.98058057, -0.11593082, 0.15818217]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, -0.11593082, 0.15818217]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, -0.11593082, 0.15818217]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 27.86835978552699, + 'timestamp_carla': 27868, + 'timestamp_device': 27336, + 'timestamp_stream': 27.86835978552699, + 'transform': [array([ 1.24509897e+01, -4.23737526e+00, 1.76753872e-03]), + array([-5.73735870e-03, -4.97744865e+01, 9.64922085e-02])]} +{'AngularVelocity': array([ 4.59313124e-01, -3.58220011e-01, -4.09477434e-05]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 6.23131447e+01, -3.94435906e+00, 1.75747625e-03]), + 'Rotation': array([-8.05962272e-03, -3.76647453e+01, 1.14334814e-01]), + 'Velocity': array([ 5.70893705e-01, -4.46712285e-01, 2.26926801e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 845.8956909179688, + 'focus_actor_name': 'Road_Curb_Town05_214', + 'focus_actor_pt': array([1366.1796875 , -718.72216797, 6.10690308]), + 'frame': 1586, + 'frame_number': 1586, + 'framesequence': 1584, + 'gaze_dir': array([ 0.98058069, -0.11860307, 0.15618858]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058069, -0.11860307, 0.15618858]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058069, -0.11860307, 0.15618858]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.00027466658502817154, + 'throttle_input': 0.0, + 'timestamp': 27.88485188409686, + 'timestamp_carla': 27884, + 'timestamp_device': 27353, + 'timestamp_stream': 27.88485188409686, + 'transform': [array([ 1.24570570e+01, -4.24455309e+00, 1.77200197e-03]), + array([-5.67588676e-03, -4.97744827e+01, 8.81980509e-02])]} diff --git a/PythonAPI/data/visualize_log_data.py b/PythonAPI/data/visualize_log_data.py new file mode 100644 index 0000000..0d08a5e --- /dev/null +++ b/PythonAPI/data/visualize_log_data.py @@ -0,0 +1,35 @@ +import matplotlib.pyplot as plt +import pandas as pd + +plt.style.use('default') + +columns = ['transformX', 'transformY', 'transformZ', + 'LocationX', 'LocationY', 'LocationZ', + 'transformRoll', 'transformPitch', 'transformYaw', + 'RotationRoll', 'RotationPitch', 'RotationYaw', + 'VelocityX', 'VelocityY', 'VelocityZ', + 'AngularVelocityX', 'AngularVelocityY', 'AngularVelocityZ', + 'brake_input', 'throttle_input', 'steering_input', + ] + +def plot_data_with_timestamp(df): + plt.style.use('default') + plt.figure(figsize=(10, 10)) + cols = 3 + rows = int(len(columns) // cols) + for i in range(len(columns)): + plt.subplot(rows, cols, i+1) + plt.plot(df['timestamp_carla'], df[columns[i]]) + plt.xlabel('timestamp_carla') + plt.ylabel(columns[i]) + plt.grid() + + plt.tight_layout() + plt.show() + plt.close() + +if __name__ == "__main__": + from pathlib import Path + __path__ = Path(__file__).resolve().parent + df = pd.read_excel(f'{__path__}/trials/trial12.xlsx') + plot_data_with_timestamp(df) diff --git a/PythonAPI/examples/DReyeVR_AI.py b/PythonAPI/examples/DReyeVR_AI.py index 4506d9a..49e259d 100755 --- a/PythonAPI/examples/DReyeVR_AI.py +++ b/PythonAPI/examples/DReyeVR_AI.py @@ -1,136 +1,132 @@ -import time -import argparse -from numpy import random -from DReyeVR_utils import find_ego_vehicle - -import carla - - -def set_DReyeVR_autopilot(world, traffic_manager): - DReyeVR_vehicle = find_ego_vehicle(world) - if DReyeVR_vehicle is not None: - DReyeVR_vehicle.set_autopilot(True, traffic_manager.get_port()) - print("Successfully set autopilot on ego vehicle") - return DReyeVR_vehicle - - -def spawn_other_vehicles(client, max_vehicles, world, traffic_manager): - spawn_points = world.get_map().get_spawn_points() - - blueprints = world.get_blueprint_library().filter("vehicle.*") - blueprints = sorted(blueprints, key=lambda bp: bp.id) - - SpawnActor = carla.command.SpawnActor - SetAutopilot = carla.command.SetAutopilot - FutureActor = carla.command.FutureActor - - vehicle_list = [] - batch = [] - for n, transform in enumerate(spawn_points): - if n >= max_vehicles: - break - blueprint = random.choice(blueprints) - if blueprint.has_attribute("color"): - color = random.choice(blueprint.get_attribute("color").recommended_values) - blueprint.set_attribute("color", color) - if blueprint.has_attribute("driver_id"): - driver_id = random.choice( - blueprint.get_attribute("driver_id").recommended_values - ) - blueprint.set_attribute("driver_id", driver_id) - try: - blueprint.set_attribute("role_name", "autopilot") - except IndexError: - pass - - batch.append( - SpawnActor(blueprint, transform).then( - SetAutopilot(FutureActor, True, traffic_manager.get_port()) - ) - ) - synchronous_master = False - for response in client.apply_batch_sync(batch, synchronous_master): - if response.error: - print(f"ERROR: {response.error}") - else: - vehicle_list.append(response.actor_id) - print(f"successfully spawned {len(vehicle_list)} vehicles") - return vehicle_list - - -def main(): - argparser = argparse.ArgumentParser(description=__doc__) - argparser.add_argument( - "--host", - metavar="H", - default="127.0.0.1", - help="IP of the host server (default: 127.0.0.1)", - ) - argparser.add_argument( - "-p", - "--port", - metavar="P", - default=2000, - type=int, - help="TCP port to listen to (default: 2000)", - ) - argparser.add_argument( - "-n", - "--number-of-vehicles", - metavar="N", - default=10, - type=int, - help="number of vehicles (default: 10)", - ) - argparser.add_argument( - "--tm-port", - metavar="P", - default=8000, - type=int, - help="port to communicate with TM (default: 8000)", - ) - argparser.add_argument( - "-s", "--seed", metavar="S", type=int, help="Random device seed" - ) - args = argparser.parse_args() - - client = carla.Client(args.host, args.port) - client.set_timeout(10.0) - random.seed(args.seed if args.seed is not None else int(time.time())) - - other_vehicles = [] - ego_vehicle = None - try: - world = client.get_world() - - traffic_manager = client.get_trafficmanager(args.tm_port) - traffic_manager.set_global_distance_to_leading_vehicle(1.0) - if args.seed is not None: - traffic_manager.set_random_device_seed(args.seed) - - ego_vehicle = set_DReyeVR_autopilot(world, traffic_manager) - - # spawn other vehicles - other_vehicles = spawn_other_vehicles( - client, args.number_of_vehicles, world, traffic_manager - ) - - while True: - world.wait_for_tick() - finally: - if ego_vehicle is not None: - ego_vehicle.set_autopilot(False, traffic_manager.get_port()) - print("\ndestroying %d vehicles" % len(other_vehicles)) - client.apply_batch([carla.command.DestroyActor(x) for x in other_vehicles]) - - time.sleep(0.5) - - -if __name__ == "__main__": - - try: - main() - except KeyboardInterrupt: - pass - finally: - print("\ndone.") +import argparse +import time + +import carla +from DReyeVR_utils import find_ego_vehicle +from numpy import random + + +def set_DReyeVR_autopilot(world, traffic_manager): + DReyeVR_vehicle = find_ego_vehicle(world) + if DReyeVR_vehicle is not None: + DReyeVR_vehicle.set_autopilot(True, traffic_manager.get_port()) + print("Successfully set autopilot on ego vehicle") + return DReyeVR_vehicle + + +def spawn_other_vehicles(client, max_vehicles, world, traffic_manager): + spawn_points = world.get_map().get_spawn_points() + + blueprints = world.get_blueprint_library().filter("vehicle.*") + blueprints = sorted(blueprints, key=lambda bp: bp.id) + + SpawnActor = carla.command.SpawnActor + SetAutopilot = carla.command.SetAutopilot + FutureActor = carla.command.FutureActor + + vehicle_list = [] + batch = [] + for n, transform in enumerate(spawn_points): + if n >= max_vehicles: + break + blueprint = random.choice(blueprints) + if blueprint.has_attribute("color"): + color = random.choice(blueprint.get_attribute("color").recommended_values) + blueprint.set_attribute("color", color) + if blueprint.has_attribute("driver_id"): + driver_id = random.choice(blueprint.get_attribute("driver_id").recommended_values) + blueprint.set_attribute("driver_id", driver_id) + try: + blueprint.set_attribute("role_name", "autopilot") + except IndexError: + pass + + batch.append( + SpawnActor(blueprint, transform).then( + SetAutopilot(FutureActor, True, traffic_manager.get_port()) + ) + ) + synchronous_master = False + for response in client.apply_batch_sync(batch, synchronous_master): + if response.error: + print(f"ERROR: {response.error}") + else: + vehicle_list.append(response.actor_id) + print(f"successfully spawned {len(vehicle_list)} vehicles") + return vehicle_list + + +def main(): + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + "--host", + metavar="H", + default="127.0.0.1", + help="IP of the host server (default: 127.0.0.1)", + ) + argparser.add_argument( + "-p", + "--port", + metavar="P", + default=2000, + type=int, + help="TCP port to listen to (default: 2000)", + ) + argparser.add_argument( + "-n", + "--number-of-vehicles", + metavar="N", + default=10, + type=int, + help="number of vehicles (default: 10)", + ) + argparser.add_argument( + "--tm-port", + metavar="P", + default=8000, + type=int, + help="port to communicate with TM (default: 8000)", + ) + argparser.add_argument("-s", "--seed", metavar="S", type=int, help="Random device seed") + args = argparser.parse_args() + + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) + random.seed(args.seed if args.seed is not None else int(time.time())) + + other_vehicles = [] + ego_vehicle = None + try: + world = client.get_world() + + traffic_manager = client.get_trafficmanager(args.tm_port) + traffic_manager.set_global_distance_to_leading_vehicle(1.0) + if args.seed is not None: + traffic_manager.set_random_device_seed(args.seed) + + ego_vehicle = set_DReyeVR_autopilot(world, traffic_manager) + + # spawn other vehicles + other_vehicles = spawn_other_vehicles( + client, args.number_of_vehicles, world, traffic_manager + ) + + while True: + world.wait_for_tick() + finally: + if ego_vehicle is not None: + ego_vehicle.set_autopilot(False, traffic_manager.get_port()) + print("\ndestroying %d vehicles" % len(other_vehicles)) + client.apply_batch([carla.command.DestroyActor(x) for x in other_vehicles]) + + time.sleep(0.5) + + +if __name__ == "__main__": + + try: + main() + except KeyboardInterrupt: + pass + finally: + print("\ndone.") diff --git a/PythonAPI/examples/DReyeVR_logging.py b/PythonAPI/examples/DReyeVR_logging.py index c0c0159..d4fb620 100755 --- a/PythonAPI/examples/DReyeVR_logging.py +++ b/PythonAPI/examples/DReyeVR_logging.py @@ -1,131 +1,132 @@ -import argparse -import numpy as np -import time -import sys -import os -from DReyeVR_utils import DReyeVRSensor - -try: - import rospy - from std_msgs.msg import String -except ImportError: - rospy = None - String = None - print("Rospy not initialized. Unable to use ROS for logging") - -import carla - - -def create_ros_msg(ego_sensor: DReyeVRSensor, delim: str = "; "): - assert rospy is not None and String is not None - # TODO: need to make this work with custom ROS types - s = "rosT=" + str(rospy.get_time()) + delim - for key in ego_sensor.data: - s += f"{key}={ego_sensor.data[key]}{delim}" - return String(s) - - -def init_ros_pub(IP_SELF, IP_ROSMASTER, PORT_ROSMASTER): - assert rospy is not None and String is not None - # set the environment variables for ROS_IP - os.environ["ROS_IP"] = IP_SELF - os.environ["ROS_MASTER_URI"] = "http://" + IP_ROSMASTER + ":" + str(PORT_ROSMASTER) - - # init ros publisher - try: - rospy.set_param("bebop_ip", IP_ROSMASTER) - rospy.init_node("dreyevr_node") - return rospy.Publisher("dreyevr_pub", String, queue_size=10) - except ConnectionRefusedError: - print("RospyError: Could not initialize rospy connection") - sys.exit(1) - - -def main(): - argparser = argparse.ArgumentParser(description=__doc__) - argparser.add_argument( - "--host", - metavar="H", - default="127.0.0.1", - help="IP of the host server (default: 127.0.0.1)", - ) - argparser.add_argument( - "-p", - "--port", - metavar="P", - default=2000, - type=int, - help="TCP port to listen to (default: 2000)", - ) - argparser.add_argument( - "-rh", - "--roshost", - metavar="Rh", - default="192.168.86.33", - help="IP of the host ROS server (default: 192.168.86.33)", - ) - argparser.add_argument( - "-rp", - "--rosport", - metavar="Rp", - default=11311, - help="TCP port for ROS server (default: 11311)", - ) - argparser.add_argument( - "-sh", - "--selfhost", - metavar="Sh", - default="192.168.86.123", - help="IP of the ROS node (this machine) (default: 192.168.86.123)", - ) - - args = argparser.parse_args() - - client = carla.Client(args.host, args.port) - client.set_timeout(10.0) - sync_mode = False # synchronous mode - np.random.seed(int(time.time())) - - if rospy is not None: - # tunable parameters for your configuration - IP_SELF = args.selfhost # where the rosnode is being run (here) - # NOTE: that IP_SELF may not be the local host if passing main network to VM - # where the rosmaster (carla roslaunch) is being run - IP_ROSMASTER = args.roshost - PORT_ROSMASTER = args.rosport - pub = init_ros_pub(IP_SELF, IP_ROSMASTER, PORT_ROSMASTER) - - world = client.get_world() - sensor = DReyeVRSensor(world) - - def publish_and_print(data): - sensor.update(data) - if rospy is not None: - msg: String = create_ros_msg(sensor) - pub.publish(msg) # publish to ros master - print(sensor.data) # more useful print here (contains all attributes) - # print(data) # this print is defined in LibCarla/source/carla/data/DReyeVREvent.h - - # subscribe to DReyeVR sensor - sensor.ego_sensor.listen(publish_and_print) - try: - while True: - if sync_mode: - world.tick() - else: - world.wait_for_tick() - finally: - if sync_mode: - settings = world.get_settings() - settings.synchronous_mode = False - settings.fixed_delta_seconds = None - world.apply_settings(settings) - - -if __name__ == "__main__": - try: - main() - except KeyboardInterrupt: - pass - finally: - print("\ndone.") +import argparse +import os +import sys +import time + +import numpy as np +from DReyeVR_utils import DReyeVRSensor + +try: + import rospy + from std_msgs.msg import String +except ImportError: + rospy = None + String = None + print("Rospy not initialized. Unable to use ROS for logging") + +import carla + + +def create_ros_msg(ego_sensor: DReyeVRSensor, delim: str = "; "): + assert rospy is not None and String is not None + # TODO: need to make this work with custom ROS types + s = "rosT=" + str(rospy.get_time()) + delim + for key in ego_sensor.data: + s += f"{key}={ego_sensor.data[key]}{delim}" + return String(s) + + +def init_ros_pub(IP_SELF, IP_ROSMASTER, PORT_ROSMASTER): + assert rospy is not None and String is not None + # set the environment variables for ROS_IP + os.environ["ROS_IP"] = IP_SELF + os.environ["ROS_MASTER_URI"] = "http://" + IP_ROSMASTER + ":" + str(PORT_ROSMASTER) + + # init ros publisher + try: + rospy.set_param("bebop_ip", IP_ROSMASTER) + rospy.init_node("dreyevr_node") + return rospy.Publisher("dreyevr_pub", String, queue_size=10) + except ConnectionRefusedError: + print("RospyError: Could not initialize rospy connection") + sys.exit(1) + + +def main(): + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + "--host", + metavar="H", + default="127.0.0.1", + help="IP of the host server (default: 127.0.0.1)", + ) + argparser.add_argument( + "-p", + "--port", + metavar="P", + default=2000, + type=int, + help="TCP port to listen to (default: 2000)", + ) + argparser.add_argument( + "-rh", + "--roshost", + metavar="Rh", + default="192.168.86.33", + help="IP of the host ROS server (default: 192.168.86.33)", + ) + argparser.add_argument( + "-rp", + "--rosport", + metavar="Rp", + default=11311, + help="TCP port for ROS server (default: 11311)", + ) + argparser.add_argument( + "-sh", + "--selfhost", + metavar="Sh", + default="192.168.86.123", + help="IP of the ROS node (this machine) (default: 192.168.86.123)", + ) + + args = argparser.parse_args() + + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) + sync_mode = False # synchronous mode + np.random.seed(int(time.time())) + + if rospy is not None: + # tunable parameters for your configuration + IP_SELF = args.selfhost # where the rosnode is being run (here) + # NOTE: that IP_SELF may not be the local host if passing main network to VM + # where the rosmaster (carla roslaunch) is being run + IP_ROSMASTER = args.roshost + PORT_ROSMASTER = args.rosport + pub = init_ros_pub(IP_SELF, IP_ROSMASTER, PORT_ROSMASTER) + + world = client.get_world() + sensor = DReyeVRSensor(world) + + def publish_and_print(data): + sensor.update(data) + if rospy is not None: + msg: String = create_ros_msg(sensor) + pub.publish(msg) # publish to ros master + print(sensor.data) # more useful print here (contains all attributes) + # print(data) # this print is defined in LibCarla/source/carla/data/DReyeVREvent.h + + # subscribe to DReyeVR sensor + sensor.ego_sensor.listen(publish_and_print) + try: + while True: + if sync_mode: + world.tick() + else: + world.wait_for_tick() + finally: + if sync_mode: + settings = world.get_settings() + settings.synchronous_mode = False + settings.fixed_delta_seconds = None + world.apply_settings(settings) + + +if __name__ == "__main__": + try: + main() + except KeyboardInterrupt: + pass + finally: + print("\ndone.") diff --git a/PythonAPI/examples/DReyeVR_utils.py b/PythonAPI/examples/DReyeVR_utils.py index 604e9ea..0e3f924 100644 --- a/PythonAPI/examples/DReyeVR_utils.py +++ b/PythonAPI/examples/DReyeVR_utils.py @@ -1,151 +1,147 @@ -from typing import Optional, Any, Dict, List -import carla -import numpy as np -import time - -import sys, os -sys.path.append(os.path.join(os.getenv("CARLA_ROOT"), "PythonAPI")) -import examples # calls ./__init__.py to add all the necessary things to path - - -def find_ego_vehicle(world: carla.libcarla.World) -> Optional[carla.libcarla.Vehicle]: - DReyeVR_vehicles: str = "harplab.dreyevr_vehicle.*" - ego_vehicles_in_world = list(world.get_actors().filter(DReyeVR_vehicles)) - if len(ego_vehicles_in_world) >= 1: - print( - f"Found a DReyeVR EgoVehicle in the world ({ego_vehicles_in_world[0].id})" - ) - return ego_vehicles_in_world[0] - - DReyeVR_vehicle: Optional[carla.libcarla.Vehicle] = None - available_ego_vehicles = world.get_blueprint_library().filter(DReyeVR_vehicles) - if len(available_ego_vehicles) == 1: - bp = available_ego_vehicles[0] - print(f'Spawning only available EgoVehicle: "{bp.id}"') - else: - print( - f"Found {len(available_ego_vehicles)} available EgoVehicles. Which one to use?" - ) - for i, ego in enumerate(available_ego_vehicles): - print(f"\t[{i}] - {ego.id}") - print() - ego_choice = f"Pick EgoVehicle to spawn [0-{len(available_ego_vehicles) - 1}]: " - i: int = int(input(ego_choice)) - assert 0 <= i < len(available_ego_vehicles) - bp = available_ego_vehicles[i] - i: int = 0 - spawn_pts = world.get_map().get_spawn_points() - while DReyeVR_vehicle is None: - print(f'Spawning DReyeVR EgoVehicle: "{bp.id}" at {spawn_pts[i]}') - DReyeVR_vehicle = world.spawn_actor(bp, transform=spawn_pts[i]) - i = (i + 1) % len(spawn_pts) - return DReyeVR_vehicle - - -def find_ego_sensor(world: carla.libcarla.World) -> Optional[carla.libcarla.Sensor]: - def get_world_sensors() -> list: - return list(world.get_actors().filter("harplab.dreyevr_sensor.*")) - - ego_sensors: list = get_world_sensors() - if len(ego_sensors) == 0: - # no EgoSensors found in world, trying to spawn EgoVehicle (which spawns an EgoSensor) - if find_ego_vehicle(world) is None: # tries to spawn an EgoVehicle - raise Exception( - "No EgoVehicle (nor EgoSensor) found in the world! EgoSensor needs EgoVehicle as parent" - ) - # in case we had to spawn the EgoVehicle, this effect is not instant and might take some time - # to account for this, we allow some time (max_wait_sec) to continuously ping the server for - # an updated actor list with the EgoSensor in it. - - start_t: float = time.time() - # maximum time to keep checking for EgoSensor spawning after EgoVehicle - maximum_wait_sec: float = 10.0 # might take a while to spawn EgoVehicle (esp in VR) - while len(ego_sensors) == 0 and time.time() - start_t < maximum_wait_sec: - # EgoVehicle should now be present, so we can try again - ego_sensors = get_world_sensors() - time.sleep(0.1) # tick to allow the server some time to breathe - if len(ego_sensors) == 0: - raise Exception("Unable to find EgoSensor in the world!") - assert len(ego_sensors) > 0 # should have spawned with EgoVehicle at least - if len(ego_sensors) > 1: - print("[WARN] There are >1 EgoSensors in the world! Defaulting to first") - return ego_sensors[0] # always return the first one? - - -class DReyeVRSensor: - def __init__(self, world: carla.libcarla.World): - self.ego_sensor: carla.sensor.dreyevrsensor = find_ego_sensor(world) - self.data: Dict[str, Any] = {} - print("initialized DReyeVRSensor PythonAPI client") - - def preprocess(self, obj: Any) -> Any: - if isinstance(obj, carla.libcarla.Vector3D): - return np.array([obj.x, obj.y, obj.z]) - if isinstance(obj, carla.libcarla.Vector2D): - return np.array([obj.x, obj.y]) - if isinstance(obj, carla.libcarla.Transform): - return [ - np.array([obj.location.x, obj.location.y, obj.location.z]), - np.array([obj.rotation.pitch, obj.rotation.yaw, obj.rotation.roll]), - ] - return obj - - def update(self, data) -> None: - # update local variables - elements: List[str] = [key for key in dir(data) if "__" not in key] - for key in elements: - self.data[key] = self.preprocess(getattr(data, key)) - - @classmethod - def spawn(cls, world: carla.libcarla.World): - # TODO: check if dreyevr sensor already exsists, then use it - # spawn a DReyeVR sensor and begin listening - if find_ego_sensor(world) is None: - bp = list(world.get_blueprint_library().filter("harplab.dreyevr_sensor.*")) - try: - bp = bp[0] - except IndexError: - print("no eye tracker in blueprint library?!") - return None - ego_vehicle = find_ego_vehicle() - ego_sensor = world.spawn_actor( - bp, ego_vehicle.get_transform(), attach_to=ego_vehicle - ) - print("Spawned DReyeVR sensor: " + ego_sensor.type_id) - return cls(world) - - def calc_vergence_from_dir(self, L0, R0, LDir, RDir): - # Calculating shortest line segment intersecting both lines - # Implementation sourced from http://paulbourke.net/geometry/Ptlineplane/ - - L0R0 = L0 - R0 # segment between L origin and R origin - epsilon = 0.00000001 # small positive real number - - # Calculating dot-product equation to find perpendicular shortest-line-segment - d1343 = L0R0[0] * RDir[0] + L0R0[1] * RDir[1] + L0R0[2] * RDir[2] - d4321 = RDir[0] * LDir[0] + RDir[1] * LDir[1] + RDir[2] * LDir[2] - d1321 = L0R0[0] * LDir[0] + L0R0[1] * LDir[1] + L0R0[2] * LDir[2] - d4343 = RDir[0] * RDir[0] + RDir[1] * RDir[1] + RDir[2] * RDir[2] - d2121 = LDir[0] * LDir[0] + LDir[1] * LDir[1] + LDir[2] * LDir[2] - denom = d2121 * d4343 - d4321 * d4321 - if abs(denom) < epsilon: - return 1.0 # no intersection, would cause div by 0 err (potentially) - numer = d1343 * d4321 - d1321 * d4343 - - # calculate scalars (mu) that scale the unit direction XDir to reach the desired points - # variable scale of direction vector for LEFT ray - muL = numer / denom - # variable scale of direction vector for RIGHT ray - muR = (d1343 + d4321 * (muL)) / d4343 - - # calculate the points on the respective rays that create the intersecting line - ptL = L0 + muL * LDir # the point on the Left ray - ptR = R0 + muR * RDir # the point on the Right ray - - # calculate the vector between the middle of the two endpoints and return its magnitude - # middle point between two endpoints of shortest-line-segment - ptM = (ptL + ptR) / 2.0 - oM = (L0 + R0) / 2.0 # midpoint between two (L & R) origins - FinalRay = ptM - oM # Combined ray between midpoints of endpoints - # returns the magnitude of the vector (length) - return np.linalg.norm(FinalRay) / 100.0 +import os +import sys +import time +from typing import Any, Dict, List, Optional + +import carla +import numpy as np + +sys.path.append(os.path.join(os.getenv("CARLA_ROOT"), "PythonAPI")) +import examples # calls ./__init__.py to add all the necessary things to path + + +def find_ego_vehicle(world: carla.libcarla.World) -> Optional[carla.libcarla.Vehicle]: + DReyeVR_vehicles: str = "harplab.dreyevr_vehicle.*" + ego_vehicles_in_world = list(world.get_actors().filter(DReyeVR_vehicles)) + if len(ego_vehicles_in_world) >= 1: + print(f"Found a DReyeVR EgoVehicle in the world ({ego_vehicles_in_world[0].id})") + return ego_vehicles_in_world[0] + + DReyeVR_vehicle: Optional[carla.libcarla.Vehicle] = None + available_ego_vehicles = world.get_blueprint_library().filter(DReyeVR_vehicles) + if len(available_ego_vehicles) == 1: + bp = available_ego_vehicles[0] + print(f'Spawning only available EgoVehicle: "{bp.id}"') + else: + print(f"Found {len(available_ego_vehicles)} available EgoVehicles. Which one to use?") + for i, ego in enumerate(available_ego_vehicles): + print(f"\t[{i}] - {ego.id}") + print() + ego_choice = f"Pick EgoVehicle to spawn [0-{len(available_ego_vehicles) - 1}]: " + i: int = int(input(ego_choice)) + assert 0 <= i < len(available_ego_vehicles) + bp = available_ego_vehicles[i] + i: int = 0 + spawn_pts = world.get_map().get_spawn_points() + while DReyeVR_vehicle is None: + print(f'Spawning DReyeVR EgoVehicle: "{bp.id}" at {spawn_pts[i]}') + DReyeVR_vehicle = world.spawn_actor(bp, transform=spawn_pts[i]) + i = (i + 1) % len(spawn_pts) + return DReyeVR_vehicle + + +def find_ego_sensor(world: carla.libcarla.World) -> Optional[carla.libcarla.Sensor]: + def get_world_sensors() -> list: + return list(world.get_actors().filter("harplab.dreyevr_sensor.*")) + + ego_sensors: list = get_world_sensors() + if len(ego_sensors) == 0: + # no EgoSensors found in world, trying to spawn EgoVehicle (which spawns an EgoSensor) + if find_ego_vehicle(world) is None: # tries to spawn an EgoVehicle + raise Exception( + "No EgoVehicle (nor EgoSensor) found in the world! EgoSensor needs EgoVehicle as parent" + ) + # in case we had to spawn the EgoVehicle, this effect is not instant and might take some time + # to account for this, we allow some time (max_wait_sec) to continuously ping the server for + # an updated actor list with the EgoSensor in it. + + start_t: float = time.time() + # maximum time to keep checking for EgoSensor spawning after EgoVehicle + maximum_wait_sec: float = 10.0 # might take a while to spawn EgoVehicle (esp in VR) + while len(ego_sensors) == 0 and time.time() - start_t < maximum_wait_sec: + # EgoVehicle should now be present, so we can try again + ego_sensors = get_world_sensors() + time.sleep(0.1) # tick to allow the server some time to breathe + if len(ego_sensors) == 0: + raise Exception("Unable to find EgoSensor in the world!") + assert len(ego_sensors) > 0 # should have spawned with EgoVehicle at least + if len(ego_sensors) > 1: + print("[WARN] There are >1 EgoSensors in the world! Defaulting to first") + return ego_sensors[0] # always return the first one? + + +class DReyeVRSensor: + def __init__(self, world: carla.libcarla.World): + self.ego_sensor: carla.sensor.dreyevrsensor = find_ego_sensor(world) + self.data: Dict[str, Any] = {} + print("initialized DReyeVRSensor PythonAPI client") + + def preprocess(self, obj: Any) -> Any: + if isinstance(obj, carla.libcarla.Vector3D): + return np.array([obj.x, obj.y, obj.z]) + if isinstance(obj, carla.libcarla.Vector2D): + return np.array([obj.x, obj.y]) + if isinstance(obj, carla.libcarla.Transform): + return [ + np.array([obj.location.x, obj.location.y, obj.location.z]), + np.array([obj.rotation.pitch, obj.rotation.yaw, obj.rotation.roll]), + ] + return obj + + def update(self, data) -> None: + # update local variables + elements: List[str] = [key for key in dir(data) if "__" not in key] + for key in elements: + self.data[key] = self.preprocess(getattr(data, key)) + + @classmethod + def spawn(cls, world: carla.libcarla.World): + # TODO: check if dreyevr sensor already exsists, then use it + # spawn a DReyeVR sensor and begin listening + if find_ego_sensor(world) is None: + bp = list(world.get_blueprint_library().filter("harplab.dreyevr_sensor.*")) + try: + bp = bp[0] + except IndexError: + print("no eye tracker in blueprint library?!") + return None + ego_vehicle = find_ego_vehicle() + ego_sensor = world.spawn_actor(bp, ego_vehicle.get_transform(), attach_to=ego_vehicle) + print("Spawned DReyeVR sensor: " + ego_sensor.type_id) + return cls(world) + + def calc_vergence_from_dir(self, L0, R0, LDir, RDir): + # Calculating shortest line segment intersecting both lines + # Implementation sourced from http://paulbourke.net/geometry/Ptlineplane/ + + L0R0 = L0 - R0 # segment between L origin and R origin + epsilon = 0.00000001 # small positive real number + + # Calculating dot-product equation to find perpendicular shortest-line-segment + d1343 = L0R0[0] * RDir[0] + L0R0[1] * RDir[1] + L0R0[2] * RDir[2] + d4321 = RDir[0] * LDir[0] + RDir[1] * LDir[1] + RDir[2] * LDir[2] + d1321 = L0R0[0] * LDir[0] + L0R0[1] * LDir[1] + L0R0[2] * LDir[2] + d4343 = RDir[0] * RDir[0] + RDir[1] * RDir[1] + RDir[2] * RDir[2] + d2121 = LDir[0] * LDir[0] + LDir[1] * LDir[1] + LDir[2] * LDir[2] + denom = d2121 * d4343 - d4321 * d4321 + if abs(denom) < epsilon: + return 1.0 # no intersection, would cause div by 0 err (potentially) + numer = d1343 * d4321 - d1321 * d4343 + + # calculate scalars (mu) that scale the unit direction XDir to reach the desired points + # variable scale of direction vector for LEFT ray + muL = numer / denom + # variable scale of direction vector for RIGHT ray + muR = (d1343 + d4321 * (muL)) / d4343 + + # calculate the points on the respective rays that create the intersecting line + ptL = L0 + muL * LDir # the point on the Left ray + ptR = R0 + muR * RDir # the point on the Right ray + + # calculate the vector between the middle of the two endpoints and return its magnitude + # middle point between two endpoints of shortest-line-segment + ptM = (ptL + ptR) / 2.0 + oM = (L0 + R0) / 2.0 # midpoint between two (L & R) origins + FinalRay = ptM - oM # Combined ray between midpoints of endpoints + # returns the magnitude of the vector (length) + return np.linalg.norm(FinalRay) / 100.0 diff --git a/PythonAPI/examples/__init__.py b/PythonAPI/examples/__init__.py index 9cb5c4f..055b83e 100644 --- a/PythonAPI/examples/__init__.py +++ b/PythonAPI/examples/__init__.py @@ -1,28 +1,30 @@ -import os, sys, glob -from typing import List - -CARLA_ROOT: str = os.getenv("CARLA_ROOT") -if CARLA_ROOT is None: - raise Exception("Unable to find CARLA_ROOT in environment variable!") - -"""Add Carla PythonAPI .egg file""" -egg_dir: str = os.path.join(CARLA_ROOT, "PythonAPI", "carla", "dist") -carla_eggs: List[str] = glob.glob(os.path.join(egg_dir, f"carla-*.egg")) -for egg in carla_eggs: - sys.path.append(egg) -if len(carla_eggs) == 0: - print(f'No PythonAPI .egg file in "{egg_dir}"') - print("Make sure you built PythonAPI and an .egg was produced!") - -"""Add all Carla paths required by module""" -# see https://carla-scenariorunner.readthedocs.io/en/latest/getting_scenariorunner/#update-from-source -sys.path.extend( - [ - os.path.join(CARLA_ROOT, "PythonAPI", "carla", "agents"), - os.path.join(CARLA_ROOT, "PythonAPI", "carla"), - os.path.join(CARLA_ROOT, "PythonAPI", "examples"), - os.path.join(CARLA_ROOT, "PythonAPI"), - ] -) - -print("Carla import successful!") +import glob +import os +import sys +from typing import List + +CARLA_ROOT: str = os.getenv("CARLA_ROOT") +if CARLA_ROOT is None: + raise Exception("Unable to find CARLA_ROOT in environment variable!") + +"""Add Carla PythonAPI .egg file""" +egg_dir: str = os.path.join(CARLA_ROOT, "PythonAPI", "carla", "dist") +carla_eggs: List[str] = glob.glob(os.path.join(egg_dir, f"carla-*.egg")) +for egg in carla_eggs: + sys.path.append(egg) +if len(carla_eggs) == 0: + print(f'No PythonAPI .egg file in "{egg_dir}"') + print("Make sure you built PythonAPI and an .egg was produced!") + +"""Add all Carla paths required by module""" +# see https://carla-scenariorunner.readthedocs.io/en/latest/getting_scenariorunner/#update-from-source +sys.path.extend( + [ + os.path.join(CARLA_ROOT, "PythonAPI", "carla", "agents"), + os.path.join(CARLA_ROOT, "PythonAPI", "carla"), + os.path.join(CARLA_ROOT, "PythonAPI", "examples"), + os.path.join(CARLA_ROOT, "PythonAPI"), + ] +) + +print("Carla import successful!") diff --git a/PythonAPI/examples/schematic_mode.py b/PythonAPI/examples/schematic_mode.py index d62f10d..d7ae58e 100755 --- a/PythonAPI/examples/schematic_mode.py +++ b/PythonAPI/examples/schematic_mode.py @@ -1,76 +1,73 @@ -from typing import Any, Dict - -from DReyeVR_utils import DReyeVRSensor, find_ego_vehicle -import no_rendering_mode -from no_rendering_mode import ( - COLOR_SCARLET_RED_1, - World, - main, - game_loop, -) - -import carla -import numpy as np -from scipy.spatial.transform import Rotation - - -try: - import pygame -except ImportError: - raise RuntimeError("cannot import pygame, make sure pygame package is installed") - - -class DReyeVRWorld(World): - """Class that contains all World information from no_rendering_mode but with overrided DReyeVR functions""" - - def select_hero_actor(self): - print("Initializing DReyeVR ego vehicle as hero_actor") - world = self.client.get_world() - self.hero_actor = find_ego_vehicle(world) - self.hero_transform = self.hero_actor.get_transform() - self.sensor = DReyeVRSensor(world) - self.sensor.ego_sensor.listen(self.sensor.update) # subscribe to readout - - def render_ego_sensor(self, surface, world_to_pixel, ray_length=20): - data: Dict[str, Any] = self.sensor.data - if len(data) == 0: - return - rot = Rotation.from_euler("yxz", data["camera_rotation"], degrees=True) - ray_start = data["camera_location"] / 100 + rot.apply(data["gaze_origin"] / 100) - # NOTE: ray_length is in carla metres - ray_end_locn = ray_start + ray_length * rot.apply(data["gaze_dir"]) - gaze_ray_line = [ - carla.Location(ray_start[0], ray_start[1], ray_start[2]), - carla.Location(ray_end_locn[0], ray_end_locn[1], ray_end_locn[2]), - ] - color = COLOR_SCARLET_RED_1 - # attach to ego-vehicle - self.hero_actor.get_transform().transform(gaze_ray_line) - # map gaze data to pixels - gaze_ray_line = [world_to_pixel(p) for p in gaze_ray_line] - # draw lines on schematic - pygame.draw.lines( - surface, - color, - False, - gaze_ray_line, - width=int(np.ceil(4.0 * self.map_image.scale)), - ) - - def render_actors(self, surface, vehicles, traffic_lights, speed_limits, walkers): - super(DReyeVRWorld, self).render_actors( - surface, vehicles, traffic_lights, speed_limits, walkers - ) - # render additional eye tracker components - self.render_ego_sensor(surface, self.map_image.world_to_pixel) - - -def schematic_run(args): - # used when isolated and run in a script such as run_experiment.py - no_rendering_mode.World = DReyeVRWorld # hack to make the no_rendering_mode game_loop use the new DReyeVRWorld - game_loop(args) - - -if __name__ == "__main__": - no_rendering_mode.World = DReyeVRWorld # hack to make the no_rendering_mode game_loop use the new DReyeVRWorld - main() +from typing import Any, Dict + +import carla +import no_rendering_mode +import numpy as np +from DReyeVR_utils import DReyeVRSensor, find_ego_vehicle +from no_rendering_mode import COLOR_SCARLET_RED_1, World, game_loop, main +from scipy.spatial.transform import Rotation + +try: + import pygame +except ImportError: + raise RuntimeError("cannot import pygame, make sure pygame package is installed") + + +class DReyeVRWorld(World): + """Class that contains all World information from no_rendering_mode but with overrided DReyeVR functions""" + + def select_hero_actor(self): + print("Initializing DReyeVR ego vehicle as hero_actor") + world = self.client.get_world() + self.hero_actor = find_ego_vehicle(world) + self.hero_transform = self.hero_actor.get_transform() + self.sensor = DReyeVRSensor(world) + self.sensor.ego_sensor.listen(self.sensor.update) # subscribe to readout + + def render_ego_sensor(self, surface, world_to_pixel, ray_length=20): + data: Dict[str, Any] = self.sensor.data + if len(data) == 0: + return + rot = Rotation.from_euler("yxz", data["camera_rotation"], degrees=True) + ray_start = data["camera_location"] / 100 + rot.apply(data["gaze_origin"] / 100) + # NOTE: ray_length is in carla metres + ray_end_locn = ray_start + ray_length * rot.apply(data["gaze_dir"]) + gaze_ray_line = [ + carla.Location(ray_start[0], ray_start[1], ray_start[2]), + carla.Location(ray_end_locn[0], ray_end_locn[1], ray_end_locn[2]), + ] + color = COLOR_SCARLET_RED_1 + # attach to ego-vehicle + self.hero_actor.get_transform().transform(gaze_ray_line) + # map gaze data to pixels + gaze_ray_line = [world_to_pixel(p) for p in gaze_ray_line] + # draw lines on schematic + pygame.draw.lines( + surface, + color, + False, + gaze_ray_line, + width=int(np.ceil(4.0 * self.map_image.scale)), + ) + + def render_actors(self, surface, vehicles, traffic_lights, speed_limits, walkers): + super(DReyeVRWorld, self).render_actors( + surface, vehicles, traffic_lights, speed_limits, walkers + ) + # render additional eye tracker components + self.render_ego_sensor(surface, self.map_image.world_to_pixel) + + +def schematic_run(args): + # used when isolated and run in a script such as run_experiment.py + no_rendering_mode.World = ( + DReyeVRWorld # hack to make the no_rendering_mode game_loop use the new DReyeVRWorld + ) + game_loop(args) + + +if __name__ == "__main__": + no_rendering_mode.World = ( + DReyeVRWorld # hack to make the no_rendering_mode game_loop use the new DReyeVRWorld + ) + main() diff --git a/PythonAPI/examples/start_recording.py b/PythonAPI/examples/start_recording.py index 4e43245..80bd1a8 100755 --- a/PythonAPI/examples/start_recording.py +++ b/PythonAPI/examples/start_recording.py @@ -1,158 +1,173 @@ -#!/usr/bin/env python - -# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de -# Barcelona (UAB). -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . - -import glob -import os -import sys - -try: - sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % ( - sys.version_info.major, - sys.version_info.minor, - 'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0]) -except IndexError: - pass - -import carla - -import argparse -import random -import time -import logging - - -def main(): - argparser = argparse.ArgumentParser( - description=__doc__) - argparser.add_argument( - '--host', - metavar='H', - default='127.0.0.1', - help='IP of the host server (default: 127.0.0.1)') - argparser.add_argument( - '-p', '--port', - metavar='P', - default=2000, - type=int, - help='TCP port to listen to (default: 2000)') - argparser.add_argument( - '-n', '--number-of-vehicles', - metavar='N', - default=10, - type=int, - help='number of vehicles (default: 10)') - argparser.add_argument( - '-d', '--delay', - metavar='D', - default=2.0, - type=float, - help='delay in seconds between spawns (default: 2.0)') - argparser.add_argument( - '--safe', - action='store_true', - help='avoid spawning vehicles prone to accidents') - argparser.add_argument( - '-f', '--recorder_filename', - metavar='F', - default="test1.log", - help='recorder filename (test1.log)') - argparser.add_argument( - '-t', '--recorder_time', - metavar='T', - default=0, - type=int, - help='recorder duration (auto-stop)') - args = argparser.parse_args() - - actor_list = [] - logging.basicConfig(format='%(levelname)s: %(message)s', level=logging.INFO) - - try: - - client = carla.Client(args.host, args.port) - client.set_timeout(2.0) - world = client.get_world() - blueprints = world.get_blueprint_library().filter('vehicle.*') - - spawn_points = world.get_map().get_spawn_points() - random.shuffle(spawn_points) - - print('found %d spawn points.' % len(spawn_points)) - - count = args.number_of_vehicles - - print("Recording on file: %s" % client.start_recorder(args.recorder_filename)) - - if args.safe: - blueprints = [x for x in blueprints if int(x.get_attribute('number_of_wheels')) == 4] - blueprints = [x for x in blueprints if not x.id.endswith('microlino')] - blueprints = [x for x in blueprints if not x.id.endswith('carlacola')] - blueprints = [x for x in blueprints if not x.id.endswith('cybertruck')] - blueprints = [x for x in blueprints if not x.id.endswith('t2')] - blueprints = [x for x in blueprints if not x.id.endswith('sprinter')] - blueprints = [x for x in blueprints if not x.id.endswith('firetruck')] - blueprints = [x for x in blueprints if not x.id.endswith('ambulance')] - - spawn_points = world.get_map().get_spawn_points() - number_of_spawn_points = len(spawn_points) - - if count < number_of_spawn_points: - random.shuffle(spawn_points) - elif count > number_of_spawn_points: - msg = 'requested %d vehicles, but could only find %d spawn points' - logging.warning(msg, count, number_of_spawn_points) - count = number_of_spawn_points - - # @todo cannot import these directly. - SpawnActor = carla.command.SpawnActor - SetAutopilot = carla.command.SetAutopilot - FutureActor = carla.command.FutureActor - - batch = [] - for n, transform in enumerate(spawn_points): - if n >= count: - break - blueprint = random.choice(blueprints) - assert blueprint is not None - if blueprint.has_attribute('color'): - color = random.choice(blueprint.get_attribute('color').recommended_values) - blueprint.set_attribute('color', color) - blueprint.set_attribute('role_name', 'autopilot') - batch.append(SpawnActor(blueprint, transform).then(SetAutopilot(FutureActor, True))) - - for response in client.apply_batch_sync(batch): - if response.error: - logging.error(response.error) - else: - actor_list.append(response.actor_id) - - print('spawned %d vehicles, press Ctrl+C to exit.' % len(actor_list)) - - if (args.recorder_time > 0): - time.sleep(args.recorder_time) - else: - while True: - world.wait_for_tick() - - finally: - - print('\ndestroying %d actors' % len(actor_list)) - client.apply_batch_sync([carla.command.DestroyActor(x) for x in actor_list]) - - print("Stop recording") - client.stop_recorder() - - -if __name__ == '__main__': - - try: - main() - except KeyboardInterrupt: - pass - finally: - print('\ndone.') \ No newline at end of file +#!/usr/bin/env python + +# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de +# Barcelona (UAB). +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import glob +import os +import sys + +try: + sys.path.append( + glob.glob( + "../carla/dist/carla-*%d.%d-%s.egg" + % ( + sys.version_info.major, + sys.version_info.minor, + "win-amd64" if os.name == "nt" else "linux-x86_64", + ) + )[0] + ) +except IndexError: + pass + +import argparse +import logging +import random +import time + +import carla + + +def main(): + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + "--host", + metavar="H", + default="127.0.0.1", + help="IP of the host server (default: 127.0.0.1)", + ) + argparser.add_argument( + "-p", + "--port", + metavar="P", + default=2000, + type=int, + help="TCP port to listen to (default: 2000)", + ) + argparser.add_argument( + "-n", + "--number-of-vehicles", + metavar="N", + default=10, + type=int, + help="number of vehicles (default: 10)", + ) + argparser.add_argument( + "-d", + "--delay", + metavar="D", + default=2.0, + type=float, + help="delay in seconds between spawns (default: 2.0)", + ) + argparser.add_argument( + "--safe", action="store_true", help="avoid spawning vehicles prone to accidents" + ) + argparser.add_argument( + "-f", + "--recorder_filename", + metavar="F", + default="test1.log", + help="recorder filename (test1.log)", + ) + argparser.add_argument( + "-t", + "--recorder_time", + metavar="T", + default=0, + type=int, + help="recorder duration (auto-stop)", + ) + args = argparser.parse_args() + + actor_list = [] + logging.basicConfig(format="%(levelname)s: %(message)s", level=logging.INFO) + + try: + + client = carla.Client(args.host, args.port) + client.set_timeout(2.0) + world = client.get_world() + blueprints = world.get_blueprint_library().filter("vehicle.*") + + spawn_points = world.get_map().get_spawn_points() + random.shuffle(spawn_points) + + print("found %d spawn points." % len(spawn_points)) + + count = args.number_of_vehicles + + print("Recording on file: %s" % client.start_recorder(args.recorder_filename)) + + if args.safe: + blueprints = [x for x in blueprints if int(x.get_attribute("number_of_wheels")) == 4] + blueprints = [x for x in blueprints if not x.id.endswith("microlino")] + blueprints = [x for x in blueprints if not x.id.endswith("carlacola")] + blueprints = [x for x in blueprints if not x.id.endswith("cybertruck")] + blueprints = [x for x in blueprints if not x.id.endswith("t2")] + blueprints = [x for x in blueprints if not x.id.endswith("sprinter")] + blueprints = [x for x in blueprints if not x.id.endswith("firetruck")] + blueprints = [x for x in blueprints if not x.id.endswith("ambulance")] + + spawn_points = world.get_map().get_spawn_points() + number_of_spawn_points = len(spawn_points) + + if count < number_of_spawn_points: + random.shuffle(spawn_points) + elif count > number_of_spawn_points: + msg = "requested %d vehicles, but could only find %d spawn points" + logging.warning(msg, count, number_of_spawn_points) + count = number_of_spawn_points + + # @todo cannot import these directly. + SpawnActor = carla.command.SpawnActor + SetAutopilot = carla.command.SetAutopilot + FutureActor = carla.command.FutureActor + + batch = [] + for n, transform in enumerate(spawn_points): + if n >= count: + break + blueprint = random.choice(blueprints) + assert blueprint is not None + if blueprint.has_attribute("color"): + color = random.choice(blueprint.get_attribute("color").recommended_values) + blueprint.set_attribute("color", color) + blueprint.set_attribute("role_name", "autopilot") + batch.append(SpawnActor(blueprint, transform).then(SetAutopilot(FutureActor, True))) + + for response in client.apply_batch_sync(batch): + if response.error: + logging.error(response.error) + else: + actor_list.append(response.actor_id) + + print("spawned %d vehicles, press Ctrl+C to exit." % len(actor_list)) + + if args.recorder_time > 0: + time.sleep(args.recorder_time) + else: + while True: + world.wait_for_tick() + + finally: + + print("\ndestroying %d actors" % len(actor_list)) + client.apply_batch_sync([carla.command.DestroyActor(x) for x in actor_list]) + + print("Stop recording") + client.stop_recorder() + + +if __name__ == "__main__": + + try: + main() + except KeyboardInterrupt: + pass + finally: + print("\ndone.") diff --git a/PythonAPI/requirements.txt b/PythonAPI/requirements.txt new file mode 100644 index 0000000..f8013bb Binary files /dev/null and b/PythonAPI/requirements.txt differ diff --git a/PythonAPI/scripts/DReyeVR_DAS.py b/PythonAPI/scripts/DReyeVR_DAS.py new file mode 100644 index 0000000..71c8bf0 --- /dev/null +++ b/PythonAPI/scripts/DReyeVR_DAS.py @@ -0,0 +1,458 @@ +import argparse +import datetime +import sys +import time +from pathlib import Path +from typing import Any, Dict, List, Optional + +import numpy as np +from config_manager import ConfigManager +from DReyeVR_utils import DReyeVRSensor, find_ego_vehicle, save_sensor_data_to_csv +from HapticSharedControl.haptic_algo import HapticSharedControl +from HapticSharedControl.utils import dist +from HapticSharedControl.wheel_control import WheelController + +import carla + + +class DReyeVRController: + """Main controller class for DReyeVR haptic control system""" + + def __init__(self, config_manager: ConfigManager, path_idx: Optional[str] = None): + """ + Initialize the controller + + Args: + config_manager: Configuration manager + path_idx: Path index to use (overrides default from config) + """ + # Configuration + self.config = config_manager + + # Setup timestamp and paths + self.timestamp = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") + self.log_dir = self.config.get_logging_dir() + + # State variables + self.ready = True + self.take_control = False + self.backward_btn_pressed_cnt = 0 + self.delta_t = self.config.get_config("simulation.delta_t", 1.0/60) + self.path_idx = path_idx or self.config.get_default_path_idx() + self.current_path_param = None + + # Get vehicle + self.vehicle = self.config.get_vehicle() + + # Calibration data + self.init_sa_swa = [[], []] # [steering_angles, steering_wheel_angles] + self.coef = [[], []] # Calibration coefficients + + # Initialize wheel controller + self.controller = WheelController() + + # Create log file paths + self.haptic_log_path = self.log_dir / f"haptic_shared_control_log_{self.timestamp}.csv" + self.wheel_log_path = self.log_dir / f"steering_wheel_log_{self.timestamp}.csv" + self.sensor_log_path = self.log_dir / f"carla_sensor_log_{self.timestamp}.csv" + + print(f"Using path index: {self.path_idx}") + print(f"Logs will be saved to: {self.log_dir}") + + def initialize_steering_calibration(self, measured_carla_data: Dict) -> bool: + """ + Calibrate steering wheel angle and steering angle relationship + + Args: + measured_carla_data: Sensor data from CARLA + + Returns: + bool: True if calibration is complete + """ + # Calculate offset for spring force + desired_offset = len(self.init_sa_swa[0]) - 100 + + # Apply spring force for calibration + self.controller.play_spring_force( + offset_percentage=desired_offset, + saturation_percentage=100, + coefficient_percentage=100, + ) + + # Get current angles + steering_wheel_angle = self.controller.get_angle() * 450.0 # in degrees + steering_angles = [ + measured_carla_data["FL_Wheel_Angle"], + measured_carla_data["FR_Wheel_Angle"], + ] + + # Calculate vehicle steering angle + vehicle_steering_angle = self.vehicle.calc_turning_radius(steering_angles)["Delta"] + + # Store calibration data + self.init_sa_swa[0].append(vehicle_steering_angle) + self.init_sa_swa[1].append(steering_wheel_angle) + + # Check if calibration is complete + max_samples = self.config.get_config("simulation.calibration_samples", 201) + if len(self.init_sa_swa[0]) > max_samples: + x = np.array(self.init_sa_swa[0]) + y = np.array(self.init_sa_swa[1]) + + # Calculate linear relationships + self.coef[0] = np.polyfit(x, y, 1) # steering angle to wheel angle + self.coef[1] = np.polyfit(y, x, 1) # wheel angle to steering angle + + print("Calibration completed") + print(f"Steering Wheel Angle = {self.coef[0][0]} * Steering Angle + {self.coef[0][1]}") + print(f"Steering Angle = {self.coef[1][0]} * Steering Wheel Angle + {self.coef[1][1]}") + + return True + + return False + + def log_wheel_data(self, desired_steering_angle_deg: float) -> None: + """ + Log steering wheel data to CSV + + Args: + desired_steering_angle_deg: Desired steering angle in degrees + """ + # Create file with header if it doesn't exist + if not self.wheel_log_path.exists(): + with open(self.wheel_log_path, "w") as f: + f.write("Desired Steering Angle, Acceleration Pedal, Steering Wheel Angle\n") + + # Append data + with open(self.wheel_log_path, "a") as f: + f.write(f"{desired_steering_angle_deg},{self.controller.get_acceleration_pedal()},{self.controller.get_angle()}\n") + + def handle_driving_direction(self, buttons: Dict) -> bool: + """ + Handle driving direction changes based on button presses + + Args: + buttons: Button states from wheel controller + + Returns: + bool: True if driving backward, False if forward + """ + if any([btn_value for btn_value in list(buttons.values())[1:]]): + self.backward_btn_pressed_cnt += 1 + print("Backward button pressed") + + return self.backward_btn_pressed_cnt % 2 == 1 + + def check_path_control_triggers(self, position_to_world: List[float]) -> bool: + """ + Check if vehicle should begin path control + + Args: + position_to_world: Current vehicle position [x, y] + + Returns: + bool: True if control should be triggered + """ + # Get path data for current index + path_data = self.config.get_path(self.path_idx) + + # If vehicle is near destination control point + if "P_d" in path_data and len(path_data["P_d"]) > 0: + if dist(position_to_world, path_data["P_d"]) < 5 and not self.take_control: + # Set backward path + self.current_path_param = path_data["backward paths"] + self.take_control = True + print("Control triggered - starting haptic guidance") + return True + + return False + + def execute_haptic_control( + self, + position_to_world: List[float], + vehicle_yaw: float, + steering_angles: List[float], + steering_wheel_angle: float, + speed: float + ) -> float: + """ + Execute haptic shared control + + Args: + position_to_world: Current vehicle position [x, y] + vehicle_yaw: Current vehicle yaw angle in degrees + steering_angles: Wheel steering angles [FL, FR] in degrees + steering_wheel_angle: Steering wheel angle in degrees + speed: Vehicle speed in m/s + + Returns: + float: Desired steering angle in degrees + """ + # Get haptic control settings + haptic_settings = self.config.get_haptic_control_settings() + + # Create haptic control object + haptic_control = HapticSharedControl( + Cs=haptic_settings["Cs"], + Kc=haptic_settings["Kc"], + tp=haptic_settings["tp"], + speed=speed, + desired_trajectory_params=self.current_path_param, + vehicle_config=self.config.vehicle_config, + simulation=False, + log_save_path=str(self.haptic_log_path) + ) + haptic_control.debug = self.config.get_config("logging.enable_debug", True) + + # Calculate torque and desired steering angle + _, _, desired_steering_angle_deg = haptic_control.calculate_torque( + current_position=position_to_world, + current_yaw_angle_deg=vehicle_yaw, + steering_angles_deg=steering_angles, + steering_wheel_angle_deg=steering_wheel_angle, + ) + + # Clip to valid range + desired_steering_angle_deg = np.clip(desired_steering_angle_deg, -450, 450) + + # Calculate desired offset for force feedback + try: + desired_offset = int(desired_steering_angle_deg * 100 / 450.0) + except Exception: + # Fallback calculation if normal calculation fails + try: + desired_offset_deg = np.degrees( + np.arctan( + (self.current_path_param["end_y"] - position_to_world[1]) / + (self.current_path_param["end_x"] - position_to_world[0]) + ) + ) + desired_offset = int(desired_offset_deg * 100 / 450.0) + except Exception: + # Safe fallback + desired_offset = 0 + + # Get force feedback settings + saturation, coefficient = self.config.get_force_feedback_settings() + + # Apply force feedback + print(f"--> Desired Offset: {desired_offset}") + if coefficient > 0: + self.controller.play_spring_force( + offset_percentage=desired_offset, + saturation_percentage=saturation, + coefficient_percentage=coefficient, + ) + + # Log wheel data + self.log_wheel_data(desired_steering_angle_deg) + + return desired_steering_angle_deg + + def check_destination_reached(self, position_to_world: List[float]) -> bool: + """ + Check if vehicle has reached the destination + + Args: + position_to_world: Current vehicle position [x, y] + + Returns: + bool: True if destination reached + """ + path_data = self.config.get_path(self.path_idx) + + if "P_f" in path_data and len(path_data["P_f"]) > 0: + if dist(position_to_world, path_data["P_f"]) < 1: + self.controller.stop_spring_force() + print("Simulation Completed - reached destination") + return True + + return False + + def print_distance_info(self, position_to_world: List[float]) -> None: + """ + Print distance information + + Args: + position_to_world: Current vehicle position [x, y] + """ + path_data = self.config.get_path(self.path_idx) + + distance_to_SP = float('inf') + distance_to_DCP = float('inf') + + if "P_0" in path_data and len(path_data["P_0"]) > 0: + distance_to_SP = dist(position_to_world, path_data["P_0"]) + + if "P_d" in path_data and len(path_data["P_d"]) > 0: + distance_to_DCP = dist(position_to_world, path_data["P_d"]) + + print( + f"Distance to SP: {distance_to_SP:.3f}m", + f" | Distance to DCP: {distance_to_DCP:.3f}m", + ) + + def control_loop(self, data: Dict) -> None: + """ + Main control loop executed for each sensor update + + Args: + data: Sensor data from CARLA + """ + # Update sensor data + sensor.update(data) + measured_carla_data = sensor.data + + # Handle calibration if not ready + if not self.ready: + calibration_complete = self.initialize_steering_calibration(measured_carla_data) + + if calibration_complete: + self.ready = True + print("Ready to start the simulation") + sys.exit(0) + + time.sleep(0.5) + return + + print("=====================================") + + + # 1. Get vehicle state + position_to_world = measured_carla_data["Location"][0:2] + vehicle_yaw = measured_carla_data["Rotation"][1] + velocity = measured_carla_data["Velocity"][0:2] + speed = np.linalg.norm(velocity) + + # 2. Handle driving direction + buttons = self.controller.get_buttons_pressed() + backward = self.handle_driving_direction(buttons) + + # Adjust speed for direction + speed *= -1 if backward else 1 + print("Driving Direction:", "Backward" if backward else "Forward") + + # 3. Get steering information + steering_wheel_angle = self.controller.get_angle() * 450.0 + steering_angles = [ + measured_carla_data["FL_Wheel_Angle"], + measured_carla_data["FR_Wheel_Angle"], + ] + + # 4. Check if control should be triggered + self.check_path_control_triggers(position_to_world) + + # 5. Execute control or show distance info + if self.take_control: + self.execute_haptic_control( + position_to_world, + vehicle_yaw, + steering_angles, + steering_wheel_angle, + speed + ) + + # Save sensor data + save_sensor_data_to_csv(measured_carla_data, file_path=str(self.sensor_log_path)) + else: + self.print_distance_info(position_to_world) + + # 6. Check if destination reached + if self.check_destination_reached(position_to_world): + sys.exit(0) + + # Wait for next frame + time.sleep(self.delta_t) + + +def main(): + """Main function to set up and run the DReyeVR system""" + # Parse command line arguments + argparser = argparse.ArgumentParser( + description="DReyeVR Haptic Shared Control System" + ) + argparser.add_argument( + "--host", + metavar="H", + default="127.0.0.1", + help="IP of the host server (default: 127.0.0.1)", + ) + argparser.add_argument( + "-p", + "--port", + metavar="P", + default=2000, + type=int, + help="TCP port to listen to (default: 2000)", + ) + argparser.add_argument( + "--config", + default=None, + help="Path to config file", + ) + argparser.add_argument( + "--paths", + default=None, + help="Path to paths definition file", + ) + argparser.add_argument( + "--path-idx", + default=None, + help="Path index to use (overrides config)", + ) + + args = argparser.parse_args() + + # Initialize configuration manager + config_manager = ConfigManager( + config_path=args.config, + paths_path=args.paths + ) + + # Connect to CARLA + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) + sync_mode = config_manager.get_config("simulation.sync_mode", True) + np.random.seed(int(time.time())) + + world = client.get_world() + + # Initialize sensor and find ego vehicle + global sensor + sensor = DReyeVRSensor(world) + find_ego_vehicle(world) + + # Create controller + controller = DReyeVRController( + config_manager=config_manager, + path_idx=args.path_idx + ) + + # Subscribe sensor to control loop + sensor.ego_sensor.listen(controller.control_loop) + + try: + # Main loop + while True: + if sync_mode: + world.tick() + else: + world.wait_for_tick() + finally: + # Clean up + if sync_mode: + settings = world.get_settings() + settings.synchronous_mode = False + settings.fixed_delta_seconds = None + world.apply_settings(settings) + + controller.controller.exit() + + +if __name__ == "__main__": + try: + main() + except KeyboardInterrupt: + pass + finally: + print("\ndone.") \ No newline at end of file diff --git a/PythonAPI/scripts/DReyeVR_area_walker_spawn.py b/PythonAPI/scripts/DReyeVR_area_walker_spawn.py new file mode 100644 index 0000000..c7a9213 --- /dev/null +++ b/PythonAPI/scripts/DReyeVR_area_walker_spawn.py @@ -0,0 +1,829 @@ +#!/usr/bin/env python3 + +# Copyright (c) 2025 NAIST HuRoLab +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +""" +Script to track vehicle position and spawn walkers in defined area. +Based on DReyeVR_generate_traffic.py +""" + +import glob +import json +import logging +import math +import os +import sys +import time +from pathlib import Path +from typing import Any, Dict, List, Optional + +try: + sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % ( + sys.version_info.major, + sys.version_info.minor, + 'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0]) +except IndexError: + pass + +import argparse + +from numpy import random + +import carla + + +class WalkerSpawnConfig: + """Configuration manager for walker spawning system""" + + def __init__(self, config_path: str): + """ + Initialize configuration from JSON file + + Args: + config_path: Path to configuration JSON file + """ + self.config_path = Path(config_path) + self._load_config() + + def _load_config(self) -> None: + """Load configuration from JSON file""" + try: + with open(self.config_path, 'r') as f: + self.config = json.load(f) + except FileNotFoundError: + raise FileNotFoundError(f"Configuration file not found: {self.config_path}") + except json.JSONDecodeError as e: + raise ValueError(f"Invalid JSON in configuration file: {e}") + + def get_simulation_config(self) -> Dict[str, Any]: + """Get simulation configuration""" + return self.config.get("simulation", {}) + + def get_trigger_area(self) -> Dict[str, Any]: + """Get trigger area configuration""" + return self.config.get("trigger_area", {}) + + def get_walker_spawn_config(self) -> Dict[str, Any]: + """Get walker spawn configuration""" + return self.config.get("walker_spawn", {}) + + def get_vehicle_tracking_config(self) -> Dict[str, Any]: + """Get vehicle tracking configuration""" + return self.config.get("vehicle_tracking", {}) + + def get_logging_config(self) -> Dict[str, Any]: + """Get logging configuration""" + return self.config.get("logging", {}) + + +class VehicleTracker: + """Tracks vehicle position and detects area entry""" + + def __init__(self, config: WalkerSpawnConfig): + """ + Initialize vehicle tracker + + Args: + config: Configuration manager + """ + self.config = config + self.trigger_area = config.get_trigger_area() + self.vehicle_config = config.get_vehicle_tracking_config() + + self.center = self.trigger_area.get("center", {"x": 0, "y": 0, "z": 0}) + self.radius = self.trigger_area.get("radius", 50.0) + self.spawn_once_per_entry = self.vehicle_config.get("spawn_once_per_entry", True) + + self.vehicle_in_area = False + self.has_spawned_this_entry = False + + logging.info(f"Vehicle tracker initialized. Area center: ({self.center['x']}, {self.center['y']}), radius: {self.radius}") + + def is_vehicle_in_area(self, vehicle_location: carla.Location) -> bool: + """ + Check if vehicle is in the trigger area + + Args: + vehicle_location: Current vehicle location + + Returns: + bool: True if vehicle is in area + """ + distance = math.sqrt( + (vehicle_location.x - self.center["x"]) ** 2 + + (vehicle_location.y - self.center["y"]) ** 2 + ) + return distance <= self.radius + + def update(self, vehicle_location: carla.Location) -> bool: + """ + Update tracker with current vehicle position + + Args: + vehicle_location: Current vehicle location + + Returns: + bool: True if walkers should be spawned + """ + currently_in_area = self.is_vehicle_in_area(vehicle_location) + + # Detect entry into area + if currently_in_area and not self.vehicle_in_area: + logging.info(f"Vehicle entered trigger area at ({vehicle_location.x:.2f}, {vehicle_location.y:.2f})") + self.vehicle_in_area = True + + # Spawn walkers if conditions are met + if not self.spawn_once_per_entry or not self.has_spawned_this_entry: + self.has_spawned_this_entry = True + return True + + # Detect exit from area + elif not currently_in_area and self.vehicle_in_area: + logging.info(f"Vehicle exited trigger area at ({vehicle_location.x:.2f}, {vehicle_location.y:.2f})") + self.vehicle_in_area = False + self.has_spawned_this_entry = False + + return False + + +class WalkerSpawner: + """Handles spawning and control of walkers""" + + def __init__(self, world: carla.World, client: carla.Client, config: WalkerSpawnConfig): + """ + Initialize walker spawner + + Args: + world: CARLA world instance + client: CARLA client instance + config: Configuration manager + """ + self.world = world + self.client = client + self.config = config + self.walker_config = config.get_walker_spawn_config() + + self.walkers_list: List[Dict[str, int]] = [] + self.all_walker_ids: List[int] = [] + + # Get walker blueprints + walker_filter = self.walker_config.get("walker_filter", "walker.pedestrian.*") + generation = self.walker_config.get("generation", "2") + self.walker_blueprints = self._get_walker_blueprints(walker_filter, generation) + + logging.info(f"Walker spawner initialized with {len(self.walker_blueprints)} walker blueprints") + + def _get_walker_blueprints(self, filter_pattern: str, generation: str) -> List[carla.ActorBlueprint]: + """ + Get walker blueprints from world + + Args: + filter_pattern: Blueprint filter pattern + generation: Generation filter + + Returns: + List of walker blueprints + """ + bps = self.world.get_blueprint_library().filter(filter_pattern) + + if generation.lower() == "all": + return list(bps) + + if len(bps) == 1: + return list(bps) + + try: + int_generation = int(generation) + if int_generation in [1, 2]: + bps = [x for x in bps if int(x.get_attribute('generation')) == int_generation] + return list(bps) + else: + logging.warning("Invalid generation specified. Using all blueprints.") + return list(bps) + except ValueError: + logging.warning("Invalid generation format. Using all blueprints.") + return list(bps) + + def spawn_walkers(self) -> bool: + """ + Spawn walkers at configured positions + + Returns: + bool: True if spawning was successful + """ + spawn_positions = self.walker_config.get("spawn_positions", []) + target_positions = self.walker_config.get("target_positions", []) + number_of_walkers = self.walker_config.get("number_of_walkers", 10) + speed_config = self.walker_config.get("walker_speed", {}) + is_invincible = self.walker_config.get("is_invincible", False) + + # Limit number of walkers to available positions + max_walkers = min(number_of_walkers, len(spawn_positions)) + + if max_walkers == 0: + logging.warning("No spawn positions defined. Cannot spawn walkers.") + return False + + # Get movement configuration + movement_config = self.walker_config.get("walker_movement", {}) + movement_type = movement_config.get("type", "target_based") + + logging.info(f"Spawning {max_walkers} walkers with movement type: {movement_type}") + + if movement_type == "target_based": + logging.info(f"Walkers will walk to predefined target positions at default speed: {speed_config.get('default', 1.5):.1f} m/s") + else: + logging.info(f"Walkers will use random walk within {movement_config.get('movement_radius', 5.0):.1f}m radius") + + # Prepare spawn points + spawn_points = [] + walker_speeds = [] + + for i in range(max_walkers): + pos_idx = i % len(spawn_positions) + spawn_pos = spawn_positions[pos_idx] + + spawn_point = carla.Transform() + spawn_point.location = carla.Location( + x=spawn_pos["x"], + y=spawn_pos["y"], + z=spawn_pos["z"] + ) + spawn_points.append(spawn_point) + + # Determine walker speed based on movement type + movement_config = self.walker_config.get("walker_movement", {}) + movement_type = movement_config.get("type", "target_based") + + min_speed = speed_config.get("min", 1.0) + max_speed = speed_config.get("max", 2.5) + default_speed = speed_config.get("default", 1.5) + + if movement_type == "random_walk": + # Use random speed for random walk mode + if min_speed == max_speed: + speed = default_speed + else: + speed = random.uniform(min_speed, max_speed) + else: + # Use default speed for target-based movement + speed = default_speed + + walker_speeds.append(speed) + + # Spawn walker actors + batch = [] + for i, spawn_point in enumerate(spawn_points): + walker_bp = random.choice(self.walker_blueprints) + + # Set invincibility + if walker_bp.has_attribute('is_invincible'): + walker_bp.set_attribute('is_invincible', str(is_invincible).lower()) + + batch.append(carla.command.SpawnActor(walker_bp, spawn_point)) + + # Execute spawn batch + results = self.client.apply_batch_sync(batch, True) + + # Process spawn results + successful_spawns = [] + for i, result in enumerate(results): + if result.error: + logging.error(f"Failed to spawn walker {i}: {result.error}") + else: + self.walkers_list.append({"id": result.actor_id}) + successful_spawns.append(i) + + if not successful_spawns: + logging.error("Failed to spawn any walkers") + return False + + # Spawn walker controllers + batch = [] + walker_controller_bp = self.world.get_blueprint_library().find('controller.ai.walker') + for walker_data in self.walkers_list: + batch.append(carla.command.SpawnActor(walker_controller_bp, carla.Transform(), walker_data["id"])) + + results = self.client.apply_batch_sync(batch, True) + + # Process controller spawn results + for i, result in enumerate(results): + if result.error: + logging.error(f"Failed to spawn walker controller {i}: {result.error}") + else: + self.walkers_list[i]["con"] = result.actor_id + + # Build ID list for actor retrieval + for walker_data in self.walkers_list: + self.all_walker_ids.append(walker_data["con"]) + self.all_walker_ids.append(walker_data["id"]) + + # Get all actors + all_actors = self.world.get_actors(self.all_walker_ids) + + # Wait for tick to ensure actors are ready + self.world.wait_for_tick() + + # Initialize walker controllers and set targets + movement_config = self.walker_config.get("walker_movement", {}) + movement_type = movement_config.get("type", "target_based") + + for i in range(0, len(self.all_walker_ids), 2): + controller_actor = all_actors[i] + walker_idx = i // 2 + + # Start walker + controller_actor.start() + + # Set movement behavior based on configuration + if movement_type == "random_walk": + # Use random walking within radius + spawn_location = carla.Location( + x=spawn_points[walker_idx].location.x, + y=spawn_points[walker_idx].location.y, + z=spawn_points[walker_idx].location.z + ) + self._setup_random_walking(controller_actor, spawn_location, movement_config) + else: + # Use traditional target-based movement + if walker_idx < len(target_positions): + target_pos = target_positions[walker_idx % len(target_positions)] + target_location = carla.Location( + x=target_pos["x"], + y=target_pos["y"], + z=target_pos["z"] + ) + controller_actor.go_to_location(target_location) + logging.debug(f"Walker {walker_idx} walking to target: ({target_pos['x']:.1f}, {target_pos['y']:.1f})") + else: + # Use random location if no specific target + controller_actor.go_to_location(self.world.get_random_location_from_navigation()) + logging.debug(f"Walker {walker_idx} walking to random navigation location") + + # Set speed + if walker_idx < len(walker_speeds): + controller_actor.set_max_speed(walker_speeds[walker_idx]) + + logging.info(f"Successfully spawned {len(self.walkers_list)} walkers with controllers") + return True + + def destroy_walkers(self) -> None: + """Destroy all spawned walkers and controllers""" + if not self.all_walker_ids: + return + + # Stop controllers + all_actors = self.world.get_actors(self.all_walker_ids) + for i in range(0, len(self.all_walker_ids), 2): + try: + all_actors[i].stop() + except Exception as e: + logging.warning(f"Failed to stop walker controller: {e}") + + # Destroy all actors + self.client.apply_batch([carla.command.DestroyActor(x) for x in self.all_walker_ids]) + + logging.info(f"Destroyed {len(self.walkers_list)} walkers") + + # Reset tracking data + self.reset_walker_tracking() + + # Clear lists + self.walkers_list.clear() + self.all_walker_ids.clear() + + def _get_random_location_in_radius(self, center: carla.Location, radius: float) -> carla.Location: + """ + Generate a random location within a specified radius from center point + + Args: + center: Center location + radius: Maximum radius in meters + + Returns: + Random location within radius + """ + import random + import math + + # Generate random angle and distance + angle = random.uniform(0, 2 * math.pi) + distance = random.uniform(0, radius) + + # Calculate new position + x = center.x + distance * math.cos(angle) + y = center.y + distance * math.sin(angle) + + return carla.Location(x=x, y=y, z=center.z) + + def _setup_random_walking(self, controller_actor: carla.WalkerAIController, + spawn_location: carla.Location, movement_config: Dict[str, Any]) -> None: + """ + Setup random walking behavior for a walker controller + + Args: + controller_actor: Walker AI controller + spawn_location: Original spawn location (center of movement area) + movement_config: Movement configuration from config file + """ + radius = movement_config.get("movement_radius", 5.0) + use_navigation = movement_config.get("use_navigation_mesh", True) + + if use_navigation: + # Use CARLA's navigation mesh for more realistic movement + random_location = self.world.get_random_location_from_navigation() + if random_location: + controller_actor.go_to_location(random_location) + else: + # Fallback to random location within radius + target_location = self._get_random_location_in_radius(spawn_location, radius) + controller_actor.go_to_location(target_location) + else: + # Use simple random walking within radius + target_location = self._get_random_location_in_radius(spawn_location, radius) + controller_actor.go_to_location(target_location) + + def update_walker_destinations(self) -> None: + """ + Update walker destinations for continuous random walking behavior + Should be called periodically to keep walkers moving randomly + """ + if not self.walkers_list: + return + + movement_config = self.walker_config.get("walker_movement", {}) + movement_type = movement_config.get("type", "target_based") + + if movement_type != "random_walk": + return + + try: + all_actors = self.world.get_actors(self.all_walker_ids) + spawn_positions = self.walker_config.get("spawn_positions", []) + + for i in range(0, len(self.all_walker_ids), 2): + controller_actor = all_actors[i] + walker_idx = i // 2 + + # Always update destination for random walk mode (no state check) + # Get original spawn location as center for random walking + if walker_idx < len(spawn_positions): + spawn_pos = spawn_positions[walker_idx] + spawn_location = carla.Location( + x=spawn_pos["x"], + y=spawn_pos["y"], + z=spawn_pos["z"] + ) + self._setup_random_walking(controller_actor, spawn_location, movement_config) + + except Exception as e: + logging.warning(f"Failed to update walker destinations: {e}") + + def monitor_walker_progress(self) -> None: + """ + Monitor walker progress and log when they reach their destinations + + Note: Since WalkerAIController doesn't have get_state() method in CARLA, + we use position-based detection and movement tracking to determine + when walkers have reached their destinations. + + For target-based movement: + - Walker is considered "reached" only when within 2 meters of target + - Walker is considered "stuck" if stationary for 5+ seconds but not at target + - Stuck walkers are logged as warnings with diagnostic information + """ + if not self.walkers_list: + return + + try: + all_actors = self.world.get_actors(self.all_walker_ids) + target_positions = self.walker_config.get("target_positions", []) + movement_config = self.walker_config.get("walker_movement", {}) + movement_type = movement_config.get("type", "target_based") + + for i in range(0, len(self.all_walker_ids), 2): + controller_actor = all_actors[i] + walker_actor = all_actors[i + 1] if i + 1 < len(all_actors) else None + walker_idx = i // 2 + + if not controller_actor or not walker_actor: + continue + + walker_data = self.walkers_list[walker_idx] if walker_idx < len(self.walkers_list) else None + + if not walker_data: + continue + + # Initialize tracking if not already done + if 'destination_reached' not in walker_data: + walker_data['destination_reached'] = False + walker_data['start_location'] = walker_actor.get_location() + walker_data['target_set'] = True + walker_data['last_location'] = walker_actor.get_location() + walker_data['stationary_time'] = 0.0 + + # Skip if already reached destination + if walker_data['destination_reached']: + continue + + current_location = walker_actor.get_location() + start_location = walker_data['start_location'] + last_location = walker_data['last_location'] + + # Check if walker is moving (simple velocity check) + movement_threshold = 0.1 # meters + distance_moved = current_location.distance(last_location) + + if distance_moved < movement_threshold: + walker_data['stationary_time'] += 0.1 # Approximate time step + else: + walker_data['stationary_time'] = 0.0 + + walker_data['last_location'] = current_location + + # Check if walker has reached destination based on movement type + destination_reached = False + + if movement_type == "target_based" and walker_idx < len(target_positions): + # For target-based movement, check proximity to target + target_pos = target_positions[walker_idx % len(target_positions)] + target_location = carla.Location(x=target_pos["x"], y=target_pos["y"], z=target_pos["z"]) + distance_to_target = current_location.distance(target_location) + + # Only consider reached if within 2 meters of target + if distance_to_target < 2.0: + destination_reached = True + + distance_traveled = current_location.distance(start_location) + logging.info(f"Walker {walker_idx} reached target destination at " + f"({current_location.x:.2f}, {current_location.y:.2f}). " + f"Target was ({target_pos['x']:.2f}, {target_pos['y']:.2f}). " + f"Distance traveled: {distance_traveled:.2f}m, " + f"Distance to target: {distance_to_target:.2f}m") + + # Log if walker is stuck (stationary for too long but not at target) + elif walker_data['stationary_time'] > 5.0: + distance_traveled = current_location.distance(start_location) + logging.warning(f"Walker {walker_idx} appears stuck at " + f"({current_location.x:.2f}, {current_location.y:.2f}). " + f"Target was ({target_pos['x']:.2f}, {target_pos['y']:.2f}). " + f"Distance traveled: {distance_traveled:.2f}m, " + f"Distance to target: {distance_to_target:.2f}m, " + f"Stationary for: {walker_data['stationary_time']:.1f}s") + + # Mark as reached to avoid repeated warnings + walker_data['destination_reached'] = True + walker_data['stuck'] = True + + elif movement_type == "random_walk": + # For random walk, check if walker has been stationary for a while + if walker_data['stationary_time'] > 3.0: + destination_reached = True + + distance_traveled = current_location.distance(start_location) + logging.info(f"Walker {walker_idx} reached random destination at " + f"({current_location.x:.2f}, {current_location.y:.2f}). " + f"Distance traveled: {distance_traveled:.2f}m") + + if destination_reached: + walker_data['destination_reached'] = True + walker_data['final_location'] = current_location + + except Exception as e: + logging.warning(f"Failed to monitor walker progress: {e}") + + def log_walker_progress(self) -> None: + """ + Log periodic progress updates for debugging walker navigation + """ + if not self.walkers_list: + return + + try: + all_actors = self.world.get_actors(self.all_walker_ids) + target_positions = self.walker_config.get("target_positions", []) + + for i in range(0, len(self.all_walker_ids), 2): + walker_actor = all_actors[i + 1] if i + 1 < len(all_actors) else None + walker_idx = i // 2 + + if not walker_actor: + continue + + walker_data = self.walkers_list[walker_idx] if walker_idx < len(self.walkers_list) else None + if not walker_data or walker_data.get('destination_reached', False): + continue + + current_location = walker_actor.get_location() + + if walker_idx < len(target_positions): + target_pos = target_positions[walker_idx % len(target_positions)] + target_location = carla.Location(x=target_pos["x"], y=target_pos["y"], z=target_pos["z"]) + distance_to_target = current_location.distance(target_location) + + logging.debug(f"Walker {walker_idx} progress: " + f"Current ({current_location.x:.2f}, {current_location.y:.2f}), " + f"Target ({target_pos['x']:.2f}, {target_pos['y']:.2f}), " + f"Distance to target: {distance_to_target:.2f}m, " + f"Stationary time: {walker_data.get('stationary_time', 0):.1f}s") + + except Exception as e: + logging.debug(f"Failed to log walker progress: {e}") + + def reset_walker_tracking(self) -> None: + """ + Reset walker tracking data for fresh monitoring + """ + for walker_data in self.walkers_list: + walker_data.pop('destination_reached', None) + walker_data.pop('start_location', None) + walker_data.pop('final_location', None) + walker_data.pop('target_set', None) + walker_data.pop('last_location', None) + walker_data.pop('stationary_time', None) + walker_data.pop('stuck', None) + + logging.debug("Walker tracking data reset") + +def find_hero_vehicle(world: carla.World, role_name: str = "hero") -> Optional[carla.Vehicle]: + """ + Find the hero vehicle in the world + + Args: + world: CARLA world instance + role_name: Role name to search for + + Returns: + Hero vehicle actor or None if not found + """ + for actor in world.get_actors(): + if hasattr(actor, 'attributes') and actor.attributes.get('role_name') == role_name: + if 'vehicle' in actor.type_id: + return actor + return None + + +def main(): + """Main function""" + # Parse command line arguments + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + '--host', + metavar='H', + default='127.0.0.1', + help='IP of the host server (default: 127.0.0.1)' + ) + argparser.add_argument( + '-p', '--port', + metavar='P', + default=2000, + type=int, + help='TCP port to listen to (default: 2000)' + ) + argparser.add_argument( + '--config', + default='./walker_spawn_config.json', + help='Path to configuration file (default: walker_spawn_config.json)' + ) + argparser.add_argument( + '--log-level', + default='INFO', + choices=['DEBUG', 'INFO', 'WARNING', 'ERROR'], + help='Logging level (default: INFO)' + ) + + args = argparser.parse_args() + + # Setup logging + logging.basicConfig( + level=getattr(logging, args.log_level), + format='%(asctime)s - %(levelname)s - %(message)s' + ) + + # Load configuration + try: + config = WalkerSpawnConfig(args.config) + except (FileNotFoundError, ValueError) as e: + logging.error(f"Configuration error: {e}") + return 1 + + # Connect to CARLA + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) + + try: + world = client.get_world() + + # Configure simulation settings + sim_config = config.get_simulation_config() + settings = world.get_settings() + settings.synchronous_mode = sim_config.get("sync_mode", False) + if not settings.synchronous_mode: + settings.fixed_delta_seconds = None + else: + settings.fixed_delta_seconds = sim_config.get("delta_t", 0.05) + world.apply_settings(settings) + + logging.info(f"Simulation configured - Sync mode: {settings.synchronous_mode}") + + # Initialize components + vehicle_tracker = VehicleTracker(config) + walker_spawner = WalkerSpawner(world, client, config) + + # Get tracking configuration + vehicle_config = config.get_vehicle_tracking_config() + role_name = vehicle_config.get("role_name", "hero") + check_interval = vehicle_config.get("check_interval", 0.1) + + logging.info(f"Starting vehicle tracking for role: {role_name}") + + # Main loop + last_check_time = 0 + last_walker_update = 0 + last_progress_log = 0 + walker_update_interval = 5.0 # Update walker destinations every 5 seconds + progress_log_interval = 10.0 # Log walker progress every 10 seconds + + while True: + current_time = time.time() + + # Check at specified interval + if current_time - last_check_time >= check_interval: + # Find hero vehicle + hero_vehicle = find_hero_vehicle(world, role_name) + + if hero_vehicle is None: + logging.debug(f"Hero vehicle with role '{role_name}' not found") + else: + # Get vehicle location + vehicle_location = hero_vehicle.get_location() + + # Update tracker and check if walkers should be spawned + should_spawn = vehicle_tracker.update(vehicle_location) + + if should_spawn: + success = walker_spawner.spawn_walkers() + if success: + logging.info("Walkers spawned successfully") + else: + logging.error("Failed to spawn walkers") + + last_check_time = current_time + + # Update walker destinations for random walking (only if in random walk mode) + movement_config = config.get_walker_spawn_config().get("walker_movement", {}) + if (movement_config.get("type", "target_based") == "random_walk" and + current_time - last_walker_update >= walker_update_interval): + walker_spawner.update_walker_destinations() + last_walker_update = current_time + + # Monitor walker progress and log when they reach destinations + walker_spawner.monitor_walker_progress() + + # Log walker progress for debugging (only in DEBUG mode) + if (logging.getLogger().isEnabledFor(logging.DEBUG) and + current_time - last_progress_log >= progress_log_interval): + walker_spawner.log_walker_progress() + last_progress_log = current_time + + # Handle world tick based on sync mode + if settings.synchronous_mode: + world.tick() + else: + time.sleep(0.01) # Small sleep to prevent high CPU usage + + except KeyboardInterrupt: + logging.info("Interrupted by user") + except Exception as e: + logging.error(f"Unexpected error: {e}") + return 1 + finally: + # Cleanup + try: + walker_spawner.destroy_walkers() + except Exception as e: + logging.warning(f"Error during cleanup: {e}") + + # Reset world settings + try: + settings = world.get_settings() + settings.synchronous_mode = False + settings.fixed_delta_seconds = None + world.apply_settings(settings) + except Exception as e: + logging.warning(f"Failed to reset world settings: {e}") + + return 0 + + +if __name__ == '__main__': + try: + exit_code = main() + sys.exit(exit_code) + except KeyboardInterrupt: + pass + finally: + logging.info("Script finished") diff --git a/PythonAPI/scripts/DReyeVR_generate_traffic.py b/PythonAPI/scripts/DReyeVR_generate_traffic.py new file mode 100644 index 0000000..87dea78 --- /dev/null +++ b/PythonAPI/scripts/DReyeVR_generate_traffic.py @@ -0,0 +1,381 @@ +#!/usr/bin/env python + +# Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma de +# Barcelona (UAB). +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +"""Example script to generate traffic in the simulation""" + +import glob +import os +import sys +import time + +try: + sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % ( + sys.version_info.major, + sys.version_info.minor, + 'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0]) +except IndexError: + pass + +import argparse +import logging + +import carla +from carla import VehicleLightState as vls +from numpy import random + + +def get_actor_blueprints(world, filter, generation): + bps = world.get_blueprint_library().filter(filter) + + if generation.lower() == "all": + return bps + + # If the filter returns only one bp, we assume that this one needed + # and therefore, we ignore the generation + if len(bps) == 1: + return bps + + try: + int_generation = int(generation) + # Check if generation is in available generations + if int_generation in [1, 2]: + bps = [x for x in bps if int(x.get_attribute('generation')) == int_generation] + return bps + else: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + except: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + +def main(): + argparser = argparse.ArgumentParser( + description=__doc__) + argparser.add_argument( + '--host', + metavar='H', + default='127.0.0.1', + help='IP of the host server (default: 127.0.0.1)') + argparser.add_argument( + '-p', '--port', + metavar='P', + default=2000, + type=int, + help='TCP port to listen to (default: 2000)') + argparser.add_argument( + '-n', '--number-of-vehicles', + metavar='N', + default=30, + type=int, + help='Number of vehicles (default: 30)') + argparser.add_argument( + '-w', '--number-of-walkers', + metavar='W', + default=10, + type=int, + help='Number of walkers (default: 10)') + argparser.add_argument( + '--safe', + action='store_true', + help='Avoid spawning vehicles prone to accidents') + argparser.add_argument( + '--filterv', + metavar='PATTERN', + default='vehicle.*', + help='Filter vehicle model (default: "vehicle.*")') + argparser.add_argument( + '--generationv', + metavar='G', + default='All', + help='restrict to certain vehicle generation (values: "1","2","All" - default: "All")') + argparser.add_argument( + '--filterw', + metavar='PATTERN', + default='walker.pedestrian.*', + help='Filter pedestrian type (default: "walker.pedestrian.*")') + argparser.add_argument( + '--generationw', + metavar='G', + default='2', + help='restrict to certain pedestrian generation (values: "1","2","All" - default: "2")') + argparser.add_argument( + '--tm-port', + metavar='P', + default=8000, + type=int, + help='Port to communicate with TM (default: 8000)') + argparser.add_argument( + '--asynch', + action='store_true', + help='Activate asynchronous mode execution') + argparser.add_argument( + '--hybrid', + action='store_true', + help='Activate hybrid mode for Traffic Manager') + argparser.add_argument( + '-s', '--seed', + metavar='S', + type=int, + help='Set random device seed and deterministic mode for Traffic Manager') + argparser.add_argument( + '--seedw', + metavar='S', + default=0, + type=int, + help='Set the seed for pedestrians module') + argparser.add_argument( + '--car-lights-on', + action='store_true', + default=False, + help='Enable automatic car light management') + argparser.add_argument( + '--hero', + action='store_true', + default=False, + help='Set one of the vehicles as hero') + argparser.add_argument( + '--respawn', + action='store_true', + default=False, + help='Automatically respawn dormant vehicles (only in large maps)') + argparser.add_argument( + '--no-rendering', + action='store_true', + default=False, + help='Activate no rendering mode') + + args = argparser.parse_args() + + logging.basicConfig(format='%(levelname)s: %(message)s', level=logging.INFO) + + vehicles_list = [] + walkers_list = [] + all_id = [] + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) + synchronous_master = False + random.seed(args.seed if args.seed is not None else int(time.time())) + + try: + world = client.get_world() + + traffic_manager = client.get_trafficmanager(args.tm_port) + traffic_manager.set_global_distance_to_leading_vehicle(2.5) + if args.respawn: + traffic_manager.set_respawn_dormant_vehicles(True) + if args.hybrid: + traffic_manager.set_hybrid_physics_mode(True) + traffic_manager.set_hybrid_physics_radius(70.0) + if args.seed is not None: + traffic_manager.set_random_device_seed(args.seed) + + settings = world.get_settings() + if not args.asynch: + traffic_manager.set_synchronous_mode(True) + if not settings.synchronous_mode: + synchronous_master = True + settings.synchronous_mode = True + settings.fixed_delta_seconds = 0.05 + else: + synchronous_master = False + else: + print("You are currently in asynchronous mode. If this is a traffic simulation, \ + you could experience some issues. If it's not working correctly, switch to synchronous \ + mode by using traffic_manager.set_synchronous_mode(True)") + + if args.no_rendering: + settings.no_rendering_mode = True + world.apply_settings(settings) + + blueprints = get_actor_blueprints(world, args.filterv, args.generationv) + blueprintsWalkers = get_actor_blueprints(world, args.filterw, args.generationw) + + if args.safe: + blueprints = [x for x in blueprints if int(x.get_attribute('number_of_wheels')) == 4] + blueprints = [x for x in blueprints if not x.id.endswith('microlino')] + blueprints = [x for x in blueprints if not x.id.endswith('carlacola')] + blueprints = [x for x in blueprints if not x.id.endswith('cybertruck')] + blueprints = [x for x in blueprints if not x.id.endswith('t2')] + blueprints = [x for x in blueprints if not x.id.endswith('sprinter')] + blueprints = [x for x in blueprints if not x.id.endswith('firetruck')] + blueprints = [x for x in blueprints if not x.id.endswith('ambulance')] + + blueprints = sorted(blueprints, key=lambda bp: bp.id) + + spawn_points = world.get_map().get_spawn_points() + number_of_spawn_points = len(spawn_points) + + if args.number_of_vehicles < number_of_spawn_points: + random.shuffle(spawn_points) + elif args.number_of_vehicles > number_of_spawn_points: + msg = 'requested %d vehicles, but could only find %d spawn points' + logging.warning(msg, args.number_of_vehicles, number_of_spawn_points) + args.number_of_vehicles = number_of_spawn_points + + # @todo cannot import these directly. + SpawnActor = carla.command.SpawnActor + SetAutopilot = carla.command.SetAutopilot + FutureActor = carla.command.FutureActor + + # -------------- + # Spawn vehicles + # -------------- + batch = [] + hero = args.hero + for n, transform in enumerate(spawn_points): + if n >= args.number_of_vehicles: + break + blueprint = random.choice(blueprints) + if blueprint.has_attribute('color'): + color = random.choice(blueprint.get_attribute('color').recommended_values) + blueprint.set_attribute('color', color) + if blueprint.has_attribute('driver_id'): + driver_id = random.choice(blueprint.get_attribute('driver_id').recommended_values) + blueprint.set_attribute('driver_id', driver_id) + if hero: + blueprint.set_attribute('role_name', 'hero') + hero = False + else: + blueprint.set_attribute('role_name', 'autopilot') + + # spawn the cars and set their autopilot and light state all together + batch.append(SpawnActor(blueprint, transform) + .then(SetAutopilot(FutureActor, True, traffic_manager.get_port()))) + + for response in client.apply_batch_sync(batch, synchronous_master): + if response.error: + logging.error(response.error) + else: + vehicles_list.append(response.actor_id) + + # Set automatic vehicle lights update if specified + if args.car_lights_on: + all_vehicle_actors = world.get_actors(vehicles_list) + for actor in all_vehicle_actors: + traffic_manager.update_vehicle_lights(actor, True) + + # ------------- + # Spawn Walkers + # ------------- + # some settings + percentagePedestriansRunning = 0.0 # how many pedestrians will run + percentagePedestriansCrossing = 0.0 # how many pedestrians will walk through the road + if args.seedw: + world.set_pedestrians_seed(args.seedw) + random.seed(args.seedw) + # 1. take all the random locations to spawn + spawn_points = [] + for i in range(args.number_of_walkers): + spawn_point = carla.Transform() + loc = world.get_random_location_from_navigation() + if (loc != None): + spawn_point.location = loc + spawn_points.append(spawn_point) + # 2. we spawn the walker object + batch = [] + walker_speed = [] + for spawn_point in spawn_points: + walker_bp = random.choice(blueprintsWalkers) + # set as not invincible + if walker_bp.has_attribute('is_invincible'): + walker_bp.set_attribute('is_invincible', 'false') + # set the max speed + if walker_bp.has_attribute('speed'): + if (random.random() > percentagePedestriansRunning): + # walking + walker_speed.append(walker_bp.get_attribute('speed').recommended_values[1]) + else: + # running + walker_speed.append(walker_bp.get_attribute('speed').recommended_values[2]) + else: + print("Walker has no speed") + walker_speed.append(0.0) + batch.append(SpawnActor(walker_bp, spawn_point)) + results = client.apply_batch_sync(batch, True) + walker_speed2 = [] + for i in range(len(results)): + if results[i].error: + logging.error(results[i].error) + else: + walkers_list.append({"id": results[i].actor_id}) + walker_speed2.append(walker_speed[i]) + walker_speed = walker_speed2 + # 3. we spawn the walker controller + batch = [] + walker_controller_bp = world.get_blueprint_library().find('controller.ai.walker') + for i in range(len(walkers_list)): + batch.append(SpawnActor(walker_controller_bp, carla.Transform(), walkers_list[i]["id"])) + results = client.apply_batch_sync(batch, True) + for i in range(len(results)): + if results[i].error: + logging.error(results[i].error) + else: + walkers_list[i]["con"] = results[i].actor_id + # 4. we put together the walkers and controllers id to get the objects from their id + for i in range(len(walkers_list)): + all_id.append(walkers_list[i]["con"]) + all_id.append(walkers_list[i]["id"]) + all_actors = world.get_actors(all_id) + + # wait for a tick to ensure client receives the last transform of the walkers we have just created + if args.asynch or not synchronous_master: + world.wait_for_tick() + else: + world.tick() + + # 5. initialize each controller and set target to walk to (list is [controler, actor, controller, actor ...]) + # set how many pedestrians can cross the road + world.set_pedestrians_cross_factor(percentagePedestriansCrossing) + for i in range(0, len(all_id), 2): + # start walker + all_actors[i].start() + # set walk to random point + all_actors[i].go_to_location(world.get_random_location_from_navigation()) + # max speed + all_actors[i].set_max_speed(float(walker_speed[int(i/2)])) + + print('spawned %d vehicles and %d walkers, press Ctrl+C to exit.' % (len(vehicles_list), len(walkers_list))) + + # Example of how to use Traffic Manager parameters + traffic_manager.global_percentage_speed_difference(30.0) + + while True: + if not args.asynch and synchronous_master: + world.tick() + else: + world.wait_for_tick() + + finally: + + if not args.asynch and synchronous_master: + settings = world.get_settings() + settings.synchronous_mode = False + settings.no_rendering_mode = False + settings.fixed_delta_seconds = None + world.apply_settings(settings) + + print('\ndestroying %d vehicles' % len(vehicles_list)) + client.apply_batch([carla.command.DestroyActor(x) for x in vehicles_list]) + + # stop walker controllers (list is [controller, actor, controller, actor ...]) + for i in range(0, len(all_id), 2): + all_actors[i].stop() + + print('\ndestroying %d walkers' % len(walkers_list)) + client.apply_batch([carla.command.DestroyActor(x) for x in all_id]) + + time.sleep(0.5) + +if __name__ == '__main__': + + try: + main() + except KeyboardInterrupt: + pass + finally: + print('\ndone.') \ No newline at end of file diff --git a/PythonAPI/scripts/DReyeVR_logging.py b/PythonAPI/scripts/DReyeVR_logging.py new file mode 100644 index 0000000..5a26200 --- /dev/null +++ b/PythonAPI/scripts/DReyeVR_logging.py @@ -0,0 +1,142 @@ +import argparse +import csv +import os +import sys +import time +from pprint import pprint + +import numpy as np +from DReyeVR_utils import DReyeVRSensor, find_ego_sensor, find_ego_vehicle + +try: + import rospy + from std_msgs.msg import String +except ImportError: + rospy = None + String = None + print("Rospy not initialized. Unable to use ROS for logging") + +import carla + + +def create_ros_msg(ego_sensor: DReyeVRSensor, delim: str = "; "): + assert rospy is not None and String is not None + s = "rosT=" + str(rospy.get_time()) + delim + for key in ego_sensor.data: + s += f"{key}={ego_sensor.data[key]}{delim}" + return String(s) + + +def init_ros_pub(IP_SELF, IP_ROSMASTER, PORT_ROSMASTER): + assert rospy is not None and String is not None + # set the environment variables for ROS_IP + os.environ["ROS_IP"] = IP_SELF + os.environ["ROS_MASTER_URI"] = "http://" + IP_ROSMASTER + ":" + str(PORT_ROSMASTER) + + # init ros publisher + try: + rospy.set_param("bebop_ip", IP_ROSMASTER) + rospy.init_node("dreyevr_node") + return rospy.Publisher("dreyevr_pub", String, queue_size=10) + except ConnectionRefusedError: + print("RospyError: Could not initialize rospy connection") + sys.exit(1) + + +def main(): + + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + "--host", + metavar="H", + default="127.0.0.1", + help="IP of the host server (default: 127.0.0.1)", + ) + argparser.add_argument( + "-p", + "--port", + metavar="P", + default=2000, + type=int, + help="TCP port to listen to (default: 2000)", + ) + argparser.add_argument( + "-rh", + "--roshost", + metavar="Rh", + default="172.31.25.167", + help="IP of the host ROS server (default: 192.168.86.33)", + ) + argparser.add_argument( + "-rp", + "--rosport", + metavar="Rp", + default=11311, + help="TCP port for ROS server (default: 11311)", + ) + argparser.add_argument( + "-sh", + "--selfhost", + metavar="Sh", + default="163.221.139.137", + help="IP of the ROS node (this machine) (default: 192.168.86.123)", + ) + + args = argparser.parse_args() + + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) + sync_mode = True # synchronous mode + np.random.seed(int(time.time())) + + if rospy is not None: + # tunable parameters for your configuration + IP_SELF = args.selfhost # where the rosnode is being run (here) + # NOTE: that IP_SELF may not be the local host if passing main network to VM + # where the rosmaster (carla roslaunch) is being run + IP_ROSMASTER = args.roshost + PORT_ROSMASTER = args.rosport + pub = init_ros_pub(IP_SELF, IP_ROSMASTER, PORT_ROSMASTER) + + world = client.get_world() + sensor = DReyeVRSensor(world) + + # Note: set the vehicle speed to be stable + vehicle = find_ego_vehicle(world) + # stop the vehicle + + + def publish_and_print(data): + # global df + vehicle.set_target_velocity(carla.Vector3D(x=1.0, y =0.0, z=0.0)) + sensor.update(data) + if rospy is not None: + msg: String = create_ros_msg(sensor) + pub.publish(msg) # publish to ros master + pprint(sensor.data) # more useful print here (contains all attributes) + time.sleep(0.1) + + # subscribe to DReyeVR sensor + sensor.ego_sensor.listen(publish_and_print) + try: + while True: + if sync_mode: + world.tick() + else: + world.wait_for_tick() + finally: + if sync_mode: + settings = world.get_settings() + settings.synchronous_mode = False + settings.fixed_delta_seconds = None + world.apply_settings(settings) + + +if __name__ == "__main__": + try: + main() + + except KeyboardInterrupt: + pass + finally: + print("\ndone.") diff --git a/PythonAPI/scripts/DReyeVR_utils.py b/PythonAPI/scripts/DReyeVR_utils.py new file mode 100644 index 0000000..89911e5 --- /dev/null +++ b/PythonAPI/scripts/DReyeVR_utils.py @@ -0,0 +1,274 @@ +import csv +import os +import sys +import time +from typing import Any, Dict, List, Optional + +import carla +import numpy as np + +sys.path.append(os.path.join(os.getenv("CARLA_ROOT"), "PythonAPI")) +import examples # calls ./__init__.py to add all the necessary things to path + +# cspell: ignore dreyevr dreyevrsensor libcarla harplab vergence numer linalg + +def find_ego_vehicle(world: carla.libcarla.World) -> Optional[carla.libcarla.Vehicle]: + DReyeVR_vehicles: str = "harplab.dreyevr_vehicle.*" + ego_vehicles_in_world = list(world.get_actors().filter(DReyeVR_vehicles)) + if len(ego_vehicles_in_world) >= 1: + print(f"Found a DReyeVR EgoVehicle in the world ({ego_vehicles_in_world[0].id})") + return ego_vehicles_in_world[0] + + DReyeVR_vehicle: Optional[carla.libcarla.Vehicle] = None + available_ego_vehicles = world.get_blueprint_library().filter(DReyeVR_vehicles) + if len(available_ego_vehicles) == 1: + bp = available_ego_vehicles[0] + print(f'Spawning only available EgoVehicle: "{bp.id}"') + else: + print(f"Found {len(available_ego_vehicles)} available EgoVehicles. Which one to use?") + for i, ego in enumerate(available_ego_vehicles): + print(f"\t[{i}] - {ego.id}") + print() + ego_choice = f"Pick EgoVehicle to spawn [0-{len(available_ego_vehicles) - 1}]: " + i: int = int(input(ego_choice)) + assert 0 <= i < len(available_ego_vehicles) + bp = available_ego_vehicles[i] + i: int = 0 + spawn_pts = world.get_map().get_spawn_points() + while DReyeVR_vehicle is None: + print(f'Spawning DReyeVR EgoVehicle: "{bp.id}" at {spawn_pts[i]}') + DReyeVR_vehicle = world.spawn_actor(bp, transform=spawn_pts[i]) + i = (i + 1) % len(spawn_pts) + return DReyeVR_vehicle + + +def find_ego_sensor(world: carla.libcarla.World) -> Optional[carla.libcarla.Sensor]: + def get_world_sensors() -> list: + return list(world.get_actors().filter("harplab.dreyevr_sensor.*")) + + ego_sensors: list = get_world_sensors() + if len(ego_sensors) == 0: + # no EgoSensors found in world, trying to spawn EgoVehicle (which spawns an EgoSensor) + if find_ego_vehicle(world) is None: # tries to spawn an EgoVehicle + raise Exception( + "No EgoVehicle (nor EgoSensor) found in the world! EgoSensor needs EgoVehicle as parent" + ) + # in case we had to spawn the EgoVehicle, this effect is not instant and might take some time + # to account for this, we allow some time (max_wait_sec) to continuously ping the server for + # an updated actor list with the EgoSensor in it. + + start_t: float = time.time() + # maximum time to keep checking for EgoSensor spawning after EgoVehicle + maximum_wait_sec: float = 10.0 # might take a while to spawn EgoVehicle (esp in VR) + while len(ego_sensors) == 0 and time.time() - start_t < maximum_wait_sec: + # EgoVehicle should now be present, so we can try again + ego_sensors = get_world_sensors() + time.sleep(0.1) # tick to allow the server some time to breathe + if len(ego_sensors) == 0: + raise Exception("Unable to find EgoSensor in the world!") + assert len(ego_sensors) > 0 # should have spawned with EgoVehicle at least + if len(ego_sensors) > 1: + print("[WARN] There are >1 EgoSensors in the world! Defaulting to first") + return ego_sensors[0] # always return the first one? + + +class DReyeVRSensor: + def __init__(self, world: carla.libcarla.World): + self.ego_vehicle: carla.libcarla.Vehicle = find_ego_vehicle(world) + self.ego_sensor: carla.sensor.dreyevrsensor = find_ego_sensor(world) + self.data: Dict[str, Any] = {} + print("initialized DReyeVRSensor PythonAPI client") + + def preprocess(self, obj: Any) -> Any: + if isinstance(obj, carla.libcarla.Vector3D): + return np.array([obj.x, obj.y, obj.z]) + if isinstance(obj, carla.libcarla.Vector2D): + return np.array([obj.x, obj.y]) + if isinstance(obj, carla.libcarla.Transform): + return [ + np.array([obj.location.x, obj.location.y, obj.location.z]), + np.array([obj.rotation.pitch, obj.rotation.yaw, obj.rotation.roll]), + ] + return obj + + def update(self, data: dict) -> None: + # update local variables + elements: List[str] = [key for key in dir(data) if "__" not in key] + for key in elements: + self.data[key] = self.preprocess(getattr(data, key)) + # update location and rotation + location = self.ego_vehicle.get_transform().location + rotation = self.ego_vehicle.get_transform().rotation + self.data["Location"] = np.array([location.x, location.y, location.z]) + self.data["Rotation"] = np.array([rotation.pitch, rotation.yaw, rotation.roll]) + # velocity + velocity = self.ego_vehicle.get_velocity() + self.data["Velocity"] = np.array([velocity.x, velocity.y, velocity.z]) + # acceleration + acceleration = self.ego_vehicle.get_acceleration() + self.data["Acceleration"] = np.array( + [acceleration.x, acceleration.y, acceleration.z] + ) + # angular velocity + angular_velocity = self.ego_vehicle.get_angular_velocity() + self.data["AngularVelocity"] = np.array( + [angular_velocity.x, angular_velocity.y, angular_velocity.z] + ) + # wheel angles + wheel_locations = { + "FL_Wheel": carla.VehicleWheelLocation.FL_Wheel, + "FR_Wheel": carla.VehicleWheelLocation.FR_Wheel, + "BL_Wheel": carla.VehicleWheelLocation.BL_Wheel, + "BR_Wheel": carla.VehicleWheelLocation.BR_Wheel, + } + for key, wheel_name in wheel_locations.items(): + self.data[f"{key}_Angle"] = float(self.ego_vehicle.get_wheel_steer_angle(wheel_name)) + + @classmethod + def spawn(cls, world: carla.libcarla.World): + # TODO: check if dreyevr sensor already exsists, then use it + # spawn a DReyeVR sensor and begin listening + if find_ego_sensor(world) is None: + bp = list(world.get_blueprint_library().filter("harplab.dreyevr_sensor.*")) + try: + bp = bp[0] + except IndexError: + print("no eye tracker in blueprint library?!") + return None + ego_vehicle = find_ego_vehicle() + ego_sensor = world.spawn_actor(bp, ego_vehicle.get_transform(), attach_to=ego_vehicle) + print("Spawned DReyeVR sensor: " + ego_sensor.type_id) + return cls(world) + + def calc_vergence_from_dir(self, L0, R0, LDir, RDir): + # Calculating shortest line segment intersecting both lines + # Implementation sourced from http://paulbourke.net/geometry/Ptlineplane/ + + L0R0 = L0 - R0 # segment between L origin and R origin + epsilon = 0.00000001 # small positive real number + + # Calculating dot-product equation to find perpendicular shortest-line-segment + d1343 = L0R0[0] * RDir[0] + L0R0[1] * RDir[1] + L0R0[2] * RDir[2] + d4321 = RDir[0] * LDir[0] + RDir[1] * LDir[1] + RDir[2] * LDir[2] + d1321 = L0R0[0] * LDir[0] + L0R0[1] * LDir[1] + L0R0[2] * LDir[2] + d4343 = RDir[0] * RDir[0] + RDir[1] * RDir[1] + RDir[2] * RDir[2] + d2121 = LDir[0] * LDir[0] + LDir[1] * LDir[1] + LDir[2] * LDir[2] + denom = d2121 * d4343 - d4321 * d4321 + if abs(denom) < epsilon: + return 1.0 # no intersection, would cause div by 0 err (potentially) + numer = d1343 * d4321 - d1321 * d4343 + + # calculate scalars (mu) that scale the unit direction XDir to reach the desired points + # variable scale of direction vector for LEFT ray + muL = numer / denom + # variable scale of direction vector for RIGHT ray + muR = (d1343 + d4321 * (muL)) / d4343 + + # calculate the points on the respective rays that create the intersecting line + ptL = L0 + muL * LDir # the point on the Left ray + ptR = R0 + muR * RDir # the point on the Right ray + + # calculate the vector between the middle of the two endpoints and return its magnitude + # middle point between two endpoints of shortest-line-segment + ptM = (ptL + ptR) / 2.0 + oM = (L0 + R0) / 2.0 # midpoint between two (L & R) origins + FinalRay = ptM - oM # Combined ray between midpoints of endpoints + # returns the magnitude of the vector (length) + return np.linalg.norm(FinalRay) / 100.0 + +def save_sensor_data_to_csv(data, file_path="dreyevr_sensor_data.csv"): + """ + Save DReyeVR sensor data to a CSV file in tabular format. + + Args: + data (dict): The sensor data dictionary from DReyeVR + file_path (str): Path to save the CSV file + """ + + + file_exists = os.path.isfile(file_path) + + # Define headers - flatten nested arrays + headers = [] + row_data = {} + + for key, value in data.items(): + # Handle special case for transform (list of arrays) + if key == 'transform': + for i, arr in enumerate(value): + for j, val in enumerate(arr): + column_name = f"{key}_{i}_{j}" + headers.append(column_name) + row_data[column_name] = val + # Handle numpy arrays + elif isinstance(value, np.ndarray): + for i, val in enumerate(value): + column_name = f"{key}_{i}" + headers.append(column_name) + row_data[column_name] = val + # Handle standard values + else: + headers.append(key) + row_data[key] = value + + # Write to CSV file + with open(file_path, 'a', newline='') as csvfile: + writer = csv.DictWriter(csvfile, fieldnames=headers) + + # Write header only if the file is newly created + if not file_exists: + writer.writeheader() + + # Write the data row + writer.writerow(row_data) + +"""sensor data example: +{'AngularVelocity': array([ 6.43164603e-05, 3.80409183e-05, -1.56078613e-06]), + 'BL_Wheel_Angle': 0.0, + 'BR_Wheel_Angle': 0.0, + 'FL_Wheel_Angle': 0.0, + 'FR_Wheel_Angle': 0.0, + 'Location': array([ 1.03617442, -18.3298645 , 0.16717896]), + 'Rotation': array([-4.49221507e-02, 4.99724770e+01, -3.72619666e-02]), + 'Velocity': array([4.93484549e-06, 2.47542033e-07, 4.61575430e-04]), + 'brake_input': 0.0, + 'camera_location': array([0., 0., 0.]), + 'camera_rotation': array([0., 0., 0.]), + 'current_gear_input': False, + 'focus_actor_dist': 1164.83837890625, + 'focus_actor_name': 'Road_Grass_Town05_123', + 'focus_actor_pt': array([ -111.9954071 , -1904.90673828, 16.88562012]), + 'frame': 13614, + 'frame_number': 13614, + 'framesequence': 13612, + 'gaze_dir': array([ 0.98058057, 0.10336377, -0.16666579]), + 'gaze_origin': array([0., 0., 0.]), + 'gaze_valid': True, + 'gaze_vergence': 0.0, + 'handbrake_input': False, + 'left_eye_openness': 0.0, + 'left_eye_openness_valid': False, + 'left_gaze_dir': array([ 0.98058057, 0.10336377, -0.16666579]), + 'left_gaze_origin': array([ 0., -5., 0.]), + 'left_gaze_valid': False, + 'left_pupil_diam': 0.0, + 'left_pupil_posn': array([0., 0.]), + 'left_pupil_posn_valid': False, + 'right_eye_openness': 0.0, + 'right_eye_openness_valid': False, + 'right_gaze_dir': array([ 0.98058057, 0.10336377, -0.16666579]), + 'right_gaze_origin': array([0., 5., 0.]), + 'right_gaze_valid': False, + 'right_pupil_diam': 0.0, + 'right_pupil_posn': array([0., 0.]), + 'right_pupil_posn_valid': False, + 'steering_input': 0.0002929776965174824, + 'throttle_input': 0.0, + 'timestamp': 55.89655466005206, + 'timestamp_carla': 55896, + 'timestamp_device': 55533, + 'timestamp_stream': 55.89655466005206, + 'transform': [array([ 0.00987167, -0.00354858, 0.1648705 ]), + array([-0.0574214 , -0.02758213, 0.01046066])]} + +""" \ No newline at end of file diff --git a/PythonAPI/scripts/HapticSharedControl/config.json b/PythonAPI/scripts/HapticSharedControl/config.json new file mode 100644 index 0000000..8b3351e --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/config.json @@ -0,0 +1,21 @@ +{ + "simulation": { + "sync_mode": true, + "delta_t": 0.01666666667, + "calibration_samples": 201 + }, + "haptic_control": { + "Cs": 0.5, + "Kc": 0.5, + "tp": 12.0 + }, + "force_feedback": { + "saturation_percentage": 100, + "coefficient_percentage": 0 + }, + "logging": { + "enable_debug": true, + "log_dir": "./logs" + }, + "default_path_idx": "3" +} diff --git a/PythonAPI/scripts/HapticSharedControl/haptic_algo.py b/PythonAPI/scripts/HapticSharedControl/haptic_algo.py new file mode 100644 index 0000000..336994b --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/haptic_algo.py @@ -0,0 +1,594 @@ +import csv +import datetime +import os +import time +from pathlib import Path +from typing import Any, Dict, List, Optional, Tuple, Union + +import numpy as np +from scipy.spatial import KDTree + +from .utils import ( + Vehicle, + dist, + find_closest_point, + getAngle, + linear_fn, + rotation_matrix_cw, + sigmoid, + sign, +) + +# Constants +DEFAULT_LOG_DIR = Path(__file__).parent.parent / "logs" +os.makedirs(DEFAULT_LOG_DIR, exist_ok=True) +CURRENT_TIME = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") + + +def get_sign_of_error( + given_position: List[float], + desired_trajectory: np.ndarray, + tangent_vectors: np.ndarray, + velocity: float +) -> float: + """ + Calculate the sign of the error between current position and desired trajectory. + + Args: + given_position: [x, y] coordinate of the current position + desired_trajectory: Array of trajectory points [[x1, y1], [x2, y2], ...] + tangent_vectors: Tangent vectors of the trajectory + velocity: Vehicle speed + + Returns: + Sign of the error (-1 or 1) + """ + p1 = given_position + _, pt_index = find_closest_point(p1, desired_trajectory) + + p2, p3 = tangent_vectors[pt_index] + angle_rad = getAngle(p1, p2, p3, degrees=False) + + # Return direction based on velocity and angle + return sign(velocity) * (np.sin(angle_rad) / abs(np.sin(angle_rad))) + + +def distance_to_trajectory( + given_position: List[float], + desired_trajectory: np.ndarray +) -> Tuple[float, np.ndarray, int]: + """ + Calculate the distance from a position to the desired trajectory. + + Args: + given_position: The (x, y) coordinates of the position + desired_trajectory: Array of trajectory points [[x1, y1], [x2, y2], ...] + + Returns: + Tuple containing: + - distance: Distance to the closest point on trajectory + - closest_point: Coordinates of the closest point + - index: Index of the closest point in the trajectory array + """ + closest_point, idx = find_closest_point(given_position, desired_trajectory) + return dist(given_position, closest_point), closest_point, idx + +def look_ahead_distance(vel, tp, cur_pos=None, end_pos=None, method="fix"): + """ + Calculate the look-ahead distance based on velocity and time preview. + + Args: + vel: Vehicle speed + tp: Time preview in seconds + + Returns: + Look-ahead distance in meters + """ + if method == 'fix': + return sign(vel) * 4.8 # Fixed distance of 4.8m + elif method == 'dynamic': + return sign(vel) * 1.0 * dist(cur_pos, end_pos) # Dynamic distance based on trajectory + else: + return vel * tp + + +def predict_position( + current_position: List[float], + current_yaw_angle_deg: float, + vehicle_steering_angle_deg: float, + center_of_rotation_to_vehicle: List[float], + turning_radius: float, + look_ahead_distance: float, +) -> Dict[str, Any]: + """ + Predict the vehicle's position after a time preview based on current state. + + Args: + current_position: Current [x, y] position + current_yaw_angle_deg: Current yaw angle in degrees + vehicle_steering_angle_deg: Current steering angle in degrees + center_of_rotation_to_vehicle: Center of rotation relative to vehicle + turning_radius: Vehicle turning radius + look_ahead_distance: Look-ahead distance in meters + + Returns: + Dictionary containing: + - predicted_position: Predicted [x, y] position + - rotating_direction: Direction of rotation (-1: CW, 1: CCW) + - delta_phi_rad: Change in yaw angle in radians + - predict_yaw_angle_rad: Predicted yaw angle in radians + - center_of_rotation_to_world: Center of rotation in world coordinates + """ + # Convert angles to radians + current_yaw_angle_rad = np.radians(current_yaw_angle_deg) + vehicle_steering_angle_rad = np.radians(vehicle_steering_angle_deg) + + # Adjust coordinate system + current_yaw_angle_rad = np.pi / 2 - current_yaw_angle_rad + current_position = np.array(current_position)[::-1] + center_of_rotation_to_vehicle = np.array(center_of_rotation_to_vehicle)[::-1] + + # Define rotation direction for the vehicle + rotating_direction = sign(np.sin(vehicle_steering_angle_rad)) + + # Transform vehicle coordinates to global coordinates + center_of_rotation_to_world = ( + rotation_matrix_cw(current_yaw_angle_rad - np.pi / 2).dot(center_of_rotation_to_vehicle) + + np.array(current_position) + ) + + # Calculate predicted position + # delta_phi_rad = rotating_direction * velocity * tp / turning_radius + delta_phi_rad = rotating_direction * look_ahead_distance / turning_radius + predict_yaw_angle_rad = current_yaw_angle_rad - delta_phi_rad + + # Calculate the predicted position based on circular motion + angle_for_prediction = ( + predict_yaw_angle_rad - + vehicle_steering_angle_rad + + rotating_direction * np.pi / 2 + ) + + predicted_position_in_world = ( + center_of_rotation_to_world + + turning_radius * np.array([ + np.cos(angle_for_prediction), + np.sin(angle_for_prediction) + ]) + ) + + # Convert back to original coordinate system + predict_yaw_angle_rad = np.pi / 2 - predict_yaw_angle_rad + predicted_position_in_world = predicted_position_in_world[::-1] + center_of_rotation_to_world = center_of_rotation_to_world[::-1] + + return { + "predicted_position": predicted_position_in_world, + "rotating_direction": rotating_direction, + "delta_phi_rad": delta_phi_rad, + "predict_yaw_angle_rad": predict_yaw_angle_rad, + "center_of_rotation_to_world": center_of_rotation_to_world, + } + + +# Log data schema with typed dictionary structure +class LoggingManager: + """Manages logging and data storage for the haptic control system""" + + def __init__(self, log_path: Optional[str] = None, debug: bool = False): + """ + Initialize logging manager + + Args: + log_path: Path to save log file + debug: Whether to print debug information + """ + self.log_path = log_path + self.debug = debug + self.log_data = self._create_log_dict() + + def _create_log_dict(self) -> Dict: + """Create empty log dictionary with proper structure""" + return { + "Time (t)": [], + "[Measured] Speed ~ V(t) (m/s)": [], + "[Measured] Current Position ~ X(t) (m)": [], + "[Measured] Current Position ~ Y(t) (m)": [], + "[Measured] Steering Angle FL ~ delta_fl(t) (deg)": [], + "[Measured] Steering Angle FR ~ delta_fr(t) (deg)": [], + "[Measured] Current Yaw Angle ~ Phi(t) (deg)": [], + "[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)": [], + "[Measured] VelocityX ~ Vx(t) (m/s)": [], + "[Measured] VelocityY ~ Vy(t) (m/s)": [], + "[Measured] AccelerationX ~ Ax(t) (m/s^2)": [], + "[Measured] AccelerationY ~ Ay(t) (m/s^2)": [], + "[Measured] Angular VelocityZ ~ Phi_dot(t) (rad/s^2)": [], + "[Computed] Rotation direction ~ rotate(t) (CW/CCW)": [], + "[Computed] Turning Radius ~ R(delta) (m)": [], + "[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)": [], + "[Computed] Center of Rotation to WORLD ~ X_c(t) (m)": [], + "[Computed] Center of Rotation to WORLD ~ Y_c(t) (m)": [], + "[Computed] Current Error to Trajectory ~ e(t) (m)": [], + "[Computed] Predicted Position ~ X_tp(t) (m)": [], + "[Computed] Predicted Position ~ Y_tp(t) (m)": [], + "[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)": [], + "[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)": [], + "[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)": [], + "[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)": [], + "[Computed] Torque applied ~ Tau_das (N.m)": [], + } + + def log(self, data_dict: Dict[str, Any]) -> None: + """ + Log data to internal storage and optionally to file + + Args: + data_dict: Dictionary containing values to log + """ + # Record timestamp + self.log_data["Time (t)"].append(time.time()) + + # Log all provided values + for key, value in data_dict.items(): + if key in self.log_data: + self.log_data[key].append(value) + + # Debug print if enabled + if self.debug: + print("----------------------") + print("Logging data...") + for key in self.log_data: + if len(self.log_data[key]) > 0: + print(f"{key}: {self.log_data[key][-1]}") + + # Save to file if path is provided + if self.log_path: + self.save_log() + + def save_log(self) -> None: + """ + Save the log data to a CSV file in an efficient manner + """ + file_path = self.log_path + file_exists = os.path.isfile(file_path) + + # Prepare headers and row data + headers = list(self.log_data.keys()) + row_data = {} + + # Get the latest value for each field + for key in headers: + values = self.log_data[key] + row_data[key] = values[-1] if values else None + + # Write to file (append mode) + with open(file_path, 'a', newline='') as csv_file: + writer = csv.DictWriter(csv_file, fieldnames=headers) + + # Write header only if file is new + if not file_exists: + writer.writeheader() + + # Write the latest data point + writer.writerow(row_data) + + # Debug message + if self.debug: + print(f"Log data saved to {file_path}") + + +class HapticSharedControl: + """ + Implements haptic shared control algorithm for vehicle steering + + Calculates torque to be applied to the steering wheel based on: + - Current position and orientation + - Desired trajectory + - Steering angles and wheel angle + - Vehicle dynamics + """ + + def __init__( + self, + Cs: float = 0.5, + Kc: float = 0.5, + T: float = 1.0, + tp: float = 1.0, + speed: float = 1.0, + desired_trajectory_params: Dict = None, + vehicle_config: Dict = None, + log_save_path: Optional[str] = None, + simulation: bool = True, + debug: bool = False + ): + """ + Initialize haptic shared control system + + Args: + Cs: Scaling factor for torque calculation + Kc: Preview gain for driver model + T: Time constant for complex preview model + tp: Preview time in seconds + speed: Vehicle speed + desired_trajectory_params: Parameters of desired trajectory + vehicle_config: Vehicle configuration + log_save_path: Path to save log file + simulation: Whether running in simulation mode + debug: Enable debug output + """ + # Control parameters + self.Cs = Cs + self.Kc = Kc + self.T = T + self.tp = tp + + # Vehicle state + self.speed = speed + self.steering_ratio = 10 + self.vehicle_config = vehicle_config or {} + self.vehicle = Vehicle(vehicle_config or {}) + + # Path planning + self.desired_trajectory_params = desired_trajectory_params or {"path": [], "tangent": []} + + # System state + self.simulation = simulation + self.debug = debug + + # Set up logging + self.logger = LoggingManager(log_save_path, debug) + + # Initialize state variables that will be populated during calculations + self._init_state_variables() + + def _init_state_variables(self) -> None: + """Initialize state variables to default values""" + # Core measurements + self.r = [0, 0] # Current position + self.phi = 0.0 # Current yaw angle (deg) + self.deltas = [0.0, 0.0] # Steering angles [FL, FR] + self.steering_wheel_angle_deg = 0.0 + self.steering_wheel_angle_rad = 0.0 + + # Derived measurements + self.turning_radius = 0.0 + self.vehicle_steering_angle_deg = 0.0 + self.vehicle_steering_angle_rad = 0.0 + self.center_of_rotation_to_vehicle = [0, 0] + + # Predictions and calculations + self.e_t = 0.0 # Current error + self.epsilon_tp_t = 0.0 # Predicted error + self.rtp = [0, 0] # Predicted position + self.center_of_rotation_to_world = [0, 0] + self.rotating_direction = 0 + self.delta_phi_rad = 0.0 + self.delta_phi_deg = 0.0 + self.predict_yaw_angle_rad = 0.0 + self.predict_yaw_angle_deg = 0.0 + + # Closest points + self.closest_pt_rt = [0, 0] + self.closest_pt_rt_idx = 0 + self.closest_pt_rtp = [0, 0] + self.closest_pt_rtp_idx = 0 + + # Control outputs + self.theta_d_rad = 0.0 + self.theta_d_deg = 0.0 + self.tau_das = 0.0 + + def calculate_torque( + self, + current_position: List[float], + steering_angles_deg: List[float], + current_yaw_angle_deg: float, + steering_wheel_angle_deg: Optional[float] = None, + ) -> Tuple[float, float, float]: + """ + Calculate torque for haptic shared control + + Args: + current_position: Current vehicle position [x, y] + steering_angles_deg: Wheel steering angles [FL, FR] in degrees + current_yaw_angle_deg: Current yaw angle in degrees + steering_wheel_angle_deg: Current steering wheel angle in degrees + + Returns: + Tuple of (torque, coefficient, desired_steering_wheel_angle) + """ + # Store input state + self.r = current_position + self.phi = current_yaw_angle_deg + self.deltas = steering_angles_deg + + # 1. Calculate vehicle steering geometry + turning_data = self.vehicle.calc_turning_radius(steering_angles=self.deltas) + self.turning_radius = turning_data["R"] + self.vehicle_steering_angle_deg = turning_data["Delta"] + self.center_of_rotation_to_vehicle = turning_data["CoR_v"] + self.vehicle_steering_angle_rad = np.radians(self.vehicle_steering_angle_deg) + + # Use provided steering wheel angle or derive from vehicle angle + if steering_wheel_angle_deg is None: + self.steering_wheel_angle_deg = self.translate_sa_to_swa( + self.vehicle_steering_angle_deg + ) + else: + self.steering_wheel_angle_deg = steering_wheel_angle_deg + self.steering_wheel_angle_rad = np.radians(self.steering_wheel_angle_deg) + + # 2. Calculate error to trajectory + if len(self.desired_trajectory_params.get("path", [])) > 0: + self.e_t, self.closest_pt_rt, self.closest_pt_rt_idx = distance_to_trajectory( + given_position=current_position, + desired_trajectory=self.desired_trajectory_params["path"] + ) + else: + self.e_t = 0.0 + + # 3. Calculate preview driver model + self.theta_d_rad = self._preview_driver_model() + self.theta_d_deg = np.degrees(self.theta_d_rad) + + # 4. Calculate torque + self.tau_das = -(self.Cs * self.e_t) * (self.steering_wheel_angle_rad - self.theta_d_rad) + + # Calculate coefficient based on sigmoid function + coef = sigmoid(self.Cs * self.e_t) + + # Log all data + self._log_data() + + return self.tau_das, coef, self.theta_d_deg + + def _preview_driver_model(self, method: str = "simple") -> float: + """ + Predict desired steering angle using preview driver model + + Args: + method: Method to use ("simple" or "complex") + + Returns: + Desired steering angle in radians + """ + # Skip if no trajectory is available + if not self.desired_trajectory_params or "path" not in self.desired_trajectory_params: + return self.steering_wheel_angle_rad + + # 1. Predict position at preview time + prediction = predict_position( + current_position=self.r, + current_yaw_angle_deg=self.phi, + vehicle_steering_angle_deg=self.vehicle_steering_angle_deg, + center_of_rotation_to_vehicle=self.center_of_rotation_to_vehicle, + turning_radius=self.turning_radius, + look_ahead_distance=look_ahead_distance( + vel=self.speed, + tp=self.tp, + cur_pos=self.r, + end_pos=[self.desired_trajectory_params["end_x"], + self.desired_trajectory_params["end_y"]], + method="fix" + ), + ) + + # Store prediction results + self.rtp = prediction["predicted_position"] + self.rotating_direction = prediction["rotating_direction"] + self.delta_phi_rad = prediction["delta_phi_rad"] + self.predict_yaw_angle_rad = prediction["predict_yaw_angle_rad"] + self.center_of_rotation_to_world = prediction["center_of_rotation_to_world"] + + self.delta_phi_deg = np.degrees(self.delta_phi_rad) + self.predict_yaw_angle_deg = np.degrees(self.predict_yaw_angle_rad) + + # 2. Calculate error between predicted position and trajectory + has_trajectory = len(self.desired_trajectory_params.get("path", [])) > 0 + + if has_trajectory: + # Get distance to trajectory + epsilon_tp_t, self.closest_pt_rtp, self.closest_pt_rtp_idx = distance_to_trajectory( + given_position=self.rtp, + desired_trajectory=self.desired_trajectory_params["path"] + ) + + # Determine sign of error + sign_factor = get_sign_of_error( + given_position=self.rtp, + desired_trajectory=self.desired_trajectory_params["path"], + tangent_vectors=self.desired_trajectory_params["tangent"], + velocity=self.speed, + ) + + self.epsilon_tp_t = sign_factor * epsilon_tp_t + else: + self.epsilon_tp_t = 0.0 + + # 3. Calculate desired steering angle based on method + if method == "simple": + # Simple proportional control + theta_d_rad = self.Kc * self.epsilon_tp_t + self.steering_wheel_angle_rad + else: + # More complex model with time constant + theta_d_rad_curr = self.steering_wheel_angle_rad + update_frequency = 60 # 60 Hz + d_t = 1 / update_frequency + + # Iteratively calculate the desired steering angle + for _ in range(update_frequency): + theta_d_rad_next = ( + self.Kc * self.epsilon_tp_t + ((self.T / d_t) - 1) * theta_d_rad_curr + ) * (d_t / self.T) + theta_d_rad_curr = theta_d_rad_next + + theta_d_rad = theta_d_rad_curr + + return theta_d_rad + + def translate_sa_to_swa(self, sa_deg: float) -> float: + """ + Translate steering angle to steering wheel angle + + Args: + sa_deg: Steering angle in degrees + + Returns: + Steering wheel angle in degrees + """ + if not self.simulation: + return linear_fn( + slope=self.steering_ratio, + intercept=0.0 + )(sa_deg) + return linear_fn(1, 0)(sa_deg) + + def translate_swa_to_sa(self, swa_deg: float) -> float: + """ + Translate steering wheel angle to steering angle + + Args: + swa_deg: Steering wheel angle in degrees + + Returns: + Steering angle in degrees + """ + if not self.simulation: + return linear_fn( + slope=1/self.steering_ratio, + intercept=1.8142561990902186e-05 + )(swa_deg) + return linear_fn(1, 0)(swa_deg) + + def _log_data(self) -> None: + """Log all calculated data to the logging manager""" + # Prepare data for logging + log_data = { + "[Measured] Speed ~ V(t) (m/s)": self.speed, + "[Measured] Current Position ~ X(t) (m)": self.r[0], + "[Measured] Current Position ~ Y(t) (m)": self.r[1], + "[Measured] Steering Angle FL ~ delta_fl(t) (deg)": self.deltas[0], + "[Measured] Steering Angle FR ~ delta_fr(t) (deg)": self.deltas[1], + "[Measured] Current Yaw Angle ~ Phi(t) (deg)": self.phi, + "[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)": self.steering_wheel_angle_deg, + "[Computed] Rotation direction ~ rotate(t) (CW/CCW)": self.rotating_direction, + "[Computed] Turning Radius ~ R(delta) (m)": self.turning_radius, + "[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)": self.vehicle_steering_angle_deg, + "[Computed] Current Error to Trajectory ~ e(t) (m)": self.e_t, + "[Computed] Predicted Position ~ X_tp(t) (m)": self.rtp[0], + "[Computed] Predicted Position ~ Y_tp(t) (m)": self.rtp[1], + "[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)": self.delta_phi_deg, + "[Computed] Center of Rotation to WORLD ~ X_c(t) (m)": self.center_of_rotation_to_world[0], + "[Computed] Center of Rotation to WORLD ~ Y_c(t) (m)": self.center_of_rotation_to_world[1], + "[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)": self.predict_yaw_angle_deg, + "[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)": self.epsilon_tp_t, + "[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)": self.theta_d_deg, + "[Computed] Torque applied ~ Tau_das (N.m)": self.tau_das, + } + + # Pass to logger + self.logger.log(log_data) + + +if __name__ == "__main__": + pass \ No newline at end of file diff --git a/PythonAPI/scripts/HapticSharedControl/path_planning.py b/PythonAPI/scripts/HapticSharedControl/path_planning.py new file mode 100644 index 0000000..9c3ba49 --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/path_planning.py @@ -0,0 +1,413 @@ +import json +from pathlib import Path +from pprint import pprint + +import bezier as B +import matplotlib.pyplot as plt +import numpy as np +import scipy.special +from scipy.interpolate import CubicSpline + +try: + from utils import * +except ImportError: + from HapticSharedControl.utils import * + + +def calc_control_points_bezier_path(sx, sy, s_yaw, ex, ey, e_yaw, l_d, l_f, n_points=100): + """ + Compute control points and path given start and end position. + + :param sx: (float) x-coordinate of the starting point + :param sy: (float) y-coordinate of the starting point + :param s_yaw: (float) yaw angle at start + :param ex: (float) x-coordinate of the ending point + :param ey: (float) y-coordinate of the ending point + :param e_yaw: (float) yaw angle at the end + + :return: (numpy array, numpy array) + """ + + control_points = np.array( + [ + [sx, sy], + [sx - l_d * np.cos(s_yaw), sy + l_d * np.sin(s_yaw)], + [ex + l_f * np.cos(e_yaw), ey - l_f * np.sin(e_yaw)], + [ex, ey], + ] + ) + + paths = calc_bezier_path(control_points, n_points=n_points) + + return paths, control_points + + +def calc_bezier_path(control_points, n_points=100): + """ + Compute bezier path (trajectory) given control points. + + :param control_points: (numpy array) + :param n_points: (int) number of points in the trajectory + :return: (numpy array) + """ + trajectory = [] + d_trajectory = [] + dd_trajectory = [] + + for u in np.linspace(0, 1, n_points): + point = bezier(u, control_points) + + derivatives_cp = bezier_derivatives_control_points(control_points, 2) + dt = bezier(u, derivatives_cp[1]) + ddt = bezier(u, derivatives_cp[2]) + + trajectory.append(point) + d_trajectory.append(dt) + dd_trajectory.append(ddt) + + return [np.array(trajectory), np.array(d_trajectory), np.array(dd_trajectory)] + + +def bernstein_poly(n, i, u): + """ + Bernstein polynomials. + + :param n: (int) polynomial degree + :param i: (int) + :param u: (float) + :return: (float) + """ + return scipy.special.comb(n, i) * (u**i) * ((1 - u) ** (n - i)) + + +def bezier(u, control_points): + """ + Return one point on the bezier curve. + + :param u: (float) number in [0, 1] + :param control_points: (numpy array) + :return: (numpy array) Coordinates of the point + """ + n = len(control_points) - 1 + return np.sum([bernstein_poly(n, i, u) * control_points[i] for i in range(n + 1)], axis=0) + + +def bezier_derivatives_control_points(control_points, n_derivatives): + """ + Compute control points of the successive derivatives of a given bezier curve. + + A derivative of a bezier curve is a bezier curve. + See https://pomax.github.io/bezierinfo/#derivatives + for detailed explanations + + :param control_points: (numpy array) + :param n_derivatives: (int) + e.g., n_derivatives=2 -> compute control points for first and second derivatives + :return: ([numpy array]) + """ + w = {0: control_points} + for i in range(n_derivatives): + n = len(w[i]) + w[i + 1] = np.array([(n - 1) * (w[i][j + 1] - w[i][j]) for j in range(n - 1)]) + return w + + +def calc_curvature(dx, dy, ddx, ddy): + """k_max + Compute curvature at one point given first and second derivatives. + + :param dx: (float) First derivative along x axis + :param dy: (float) + :param ddx: (float) Second derivative along x axis + :param ddy: (float) + :return: (float) + """ + return (dx * ddy - dy * ddx) / (dx**2 + dy**2) ** (3 / 2) + + +def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): # pragma: no cover + """Plot arrow.""" + if not isinstance(x, float): + for ix, iy, iyaw in zip(x, y, yaw): + plot_arrow(ix, iy, iyaw) + else: + plt.arrow( + x, + y, + length * np.cos(yaw), + length * np.sin(yaw), + fc=fc, + ec=ec, + head_width=width, + head_length=width, + ) + plt.plot(x, y) + + +def calculate_bezier_trajectory( + start_pos, + end_pos, + start_yaw, + end_yaw, + n_points, + turning_radius, + max_res=10, + show_animation=True, +): + start_x, start_y = start_pos + end_x, end_y = end_pos + start_yaw = np.radians(start_yaw) + end_yaw = np.radians(end_yaw) + + dist = np.hypot(end_x - start_x, end_y - start_y) # distance between start and end + + trajectories = {} + # Find the optimal l_d and l_f: assume that ld and lf in range of [dist/4, ] + for l_d in np.linspace(dist / 5, dist, max_res): + for l_f in np.linspace(dist / 5, dist, max_res): + + paths, control_points = calc_control_points_bezier_path( + start_x, start_y, start_yaw, end_x, end_y, end_yaw, l_d, l_f, n_points=n_points + ) + path, d_path, dd_path = paths + control_points = np.asfortranarray(control_points) + + curve = B.Curve(control_points.T, degree=3) + length = curve.length + + # Display the tangent, normal and radius of curvature at a given point + curvatures = [] + for i, u in enumerate(np.linspace(0, 1, n_points)): + curvatures.append( + calc_curvature(d_path[i][0], d_path[i][1], dd_path[i][0], dd_path[i][1]) + ) + + max_curvature = max(curvatures) + + if abs(1 / max_curvature) >= turning_radius: + trajectories[(l_d, l_f)] = length + # print(f"l_d: {l_d}, l_f: {l_f}, length: {length}, radius: {abs(1 / max_curvature)}") + + l_f, l_d = min(trajectories, key=trajectories.get) + + paths, control_points = calc_control_points_bezier_path( + start_x, start_y, start_yaw, end_x, end_y, end_yaw, l_d, l_f, n_points=n_points + ) + path, d_path, dd_path = paths + + # Display the tangent, normal and radius of curvature at a given point + radius_list = [] + tangent_list = [] + normal_list = [] + curvature_center_list = [] + + for i, u in enumerate(np.linspace(0, 1, n_points)): + x_target, y_target = bezier(u, control_points) + derivatives_cp = bezier_derivatives_control_points(control_points, 2) + point = bezier(u, control_points) + dt = bezier(u, derivatives_cp[1]) + ddt = bezier(u, derivatives_cp[2]) + + # Radius of curvature + radius = 1 / calc_curvature(dt[0], dt[1], ddt[0], ddt[1]) + + # Normalize derivative + dt /= np.linalg.norm(dt, 2) + tangent = np.array([point, point + dt]) + normal = np.array([point, point + [-dt[1], dt[0]]]) + curvature_center = point + np.array([-dt[1], dt[0]]) * radius + + radius_list.append(radius) + tangent_list.append(tangent) + normal_list.append(normal) + curvature_center_list.append(curvature_center) + + circle = plt.Circle( + tuple(curvature_center_list[-1]), + radius_list[-1], + color=(0, 0.8, 0.8), + fill=False, + linewidth=1, + ) + + assert path.T[0][0] == start_x, "path is invalid" + assert path.T[1][0] == start_y, "path is invalid" + assert path.T[0][-1] == end_x, "path is invalid" + assert path.T[1][-1] == end_y, "path is invalid" + + path_params = { + "path": path, + "control_points": control_points, + "start_x": start_x, + "start_y": start_y, + "end_x": end_x, + "end_y": end_y, + "start_yaw": start_yaw, + "end_yaw": end_yaw, + "x_target": x_target, + "y_target": y_target, + "dist": dist, + "radius": radius_list, + "tangent": tangent_list, + "normal": normal_list, + "curvature_center": curvature_center_list, + "circle": circle, + } + + if show_animation: # pragma: no cover + fig, ax = plt.subplots() + ax.plot(path.T[0], path.T[1], label="Bezier Path") + ax.plot(control_points.T[0], control_points.T[1], "--o", label="Control Points") + ax.plot(x_target, y_target) + ax.plot(tangent[:, 0], tangent[:, 1], label="Tangent") + ax.plot(normal[:, 0], normal[:, 1], label="Normal") + ax.add_artist(circle) + plot_arrow(start_x, start_y, np.pi - start_yaw, length=0.1 * dist, width=0.05 * dist) + plot_arrow(end_x, end_y, np.pi - end_yaw, length=0.1 * dist, width=0.05 * dist) + ax.legend() + ax.axis("equal") + ax.grid(True) + plt.show() + + return path, control_points, path_params + + +def compute_tangents(points): + tangents = [] + n = len(points) + + for i in range(n): + if i == 0: + dx, dy = points[i + 1][0] - points[i][0], points[i + 1][1] - points[i][1] + elif i == n - 1: + dx, dy = points[i][0] - points[i - 1][0], points[i][1] - points[i - 1][1] + else: + dx, dy = points[i + 1][0] - points[i - 1][0], points[i + 1][1] - points[i - 1][1] + + scale = 1 + p1 = (points[i][0] - scale * dx, points[i][1] - scale * dy) + p2 = (points[i][0] + scale * dx, points[i][1] + scale * dy) + + tangents.append((p1, p2)) + + return tangents + + +def process_exist_path(path): + """ + Process an existing path consisting of a series of points and compute + tangent vectors at each point along the path. + + Args: + path: A list or numpy array of [x,y] coordinates that form a path + + Returns: + param: Dictionary containing the original path and computed tangent vectors + """ + path = np.array(path) + param = { + "path": path, + "start_x": path[0][0], + "start_y": path[0][1], + "end_x": path[-1][0], + "end_y": path[-1][1], + "tangent": compute_tangents(path), + } + + return param + + +if __name__ == "__main__": + import matplotlib.pyplot as plt + + plt.style.use("default") + + __file_path__ = Path(__file__).resolve().parent + + with open(f"{__file_path__}/wheel_setting.json", "r") as f: + vehicle_config = json.load(f) + vehicle = Vehicle(vehicle_config=vehicle_config) + R = vehicle.minimum_turning_radius + + P_0 = [-1.47066772, -13.22415039] # [x, y] in carla -> [y, x] in matplotlib + P_d = [-0.37066772, -29.02415039] + P_f = [-6.87066772, -21.62415039] + + yaw_0 = (-90) + yaw_d = (-110) + yaw_f = (180) + + n_points = 10 + path1, control_points1, params1 = calculate_bezier_trajectory( + start_pos=P_0, + end_pos=P_d, + start_yaw=yaw_0, + end_yaw=yaw_d, + n_points=n_points, + turning_radius=R, + show_animation=False, + ) + + # backward so reverse the yaw angle (+180) + path2, control_points2, params2 = calculate_bezier_trajectory( + start_pos=P_d, + end_pos=P_f, + start_yaw=180 + yaw_d, + end_yaw=180 + yaw_f, + n_points=n_points, + turning_radius=R, + show_animation=False, + ) + print(path2) + # show 2 path in same plot + plt.figure() + plt.plot(path1.T[0], path1.T[1], label="Bezier Path 1") + plt.plot(control_points1.T[0], control_points1.T[1], "--o", label="Control Points 1") + plt.plot(params1["x_target"], params1["y_target"]) + plt.plot(params1["tangent"][-1][:, 0], params1["tangent"][-1][:, 1], label="Tangent 1") + plt.plot(params1["normal"][-1][:, 0], params1["normal"][-1][:, 1], label="Normal 1") + plt.gca().add_artist(params1["circle"]) + plot_arrow( + params1["start_x"], + params1["start_y"], + np.pi - params1["start_yaw"], + length=0.1 * params1["dist"], + width=0.02 * params1["dist"], + ) + plot_arrow( + params1["end_x"], + params1["end_y"], + np.pi - params1["end_yaw"], + length=0.1 * params1["dist"], + width=0.02 * params1["dist"], + ) + + plt.plot(path2.T[0], path2.T[1], label="Bezier Path 2") + plt.plot(control_points2.T[0], control_points2.T[1], "--o", label="Control Points 2") + plt.plot(params2["x_target"], params2["y_target"]) + plt.plot(params2["tangent"][-1][:, 0], params2["tangent"][-1][:, 1], label="Tangent 2") + plt.plot(params2["normal"][-1][:, 0], params2["normal"][-1][:, 1], label="Normal 2") + plt.gca().add_artist(params2["circle"]) + plot_arrow( + params2["start_x"], + params2["start_y"], + np.pi - params2["start_yaw"], + length=0.1 * params2["dist"], + width=0.02 * params2["dist"], + ) + plot_arrow( + params2["end_x"], + params2["end_y"], + np.pi - params2["end_yaw"], + length=0.1 * params2["dist"], + width=0.02 * params2["dist"], + ) + + plt.xlabel("X (m)") + plt.ylabel("Y (m)") + plt.axis("square") + plt.title("Bezier Path with Control Points") + plt.legend() + plt.grid(True) + plt.show() + plt.close() diff --git a/PythonAPI/scripts/HapticSharedControl/paths.json b/PythonAPI/scripts/HapticSharedControl/paths.json new file mode 100644 index 0000000..39f3467 --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/paths.json @@ -0,0 +1,45 @@ +{ + "0": { + "P_0": [-1.47066772, -13.22415039], + "P_d": [-0.37066772, -29.02415039], + "P_f": [-6.87066772, -21.62415039], + "yaw_0": 180, + "yaw_d": 170, + "yaw_f": 90, + "use_bezier": true + }, + "1": { + "P_0": [-2.376371583333333, -13.749357381666668], + "P_d": [-0.566469992644628, -27.297582133636364], + "P_f": [-7.7486732, -21.271947543333333], + "yaw_0": 1.0237121333333334, + "yaw_d": 27.831170400000005, + "yaw_f": 91.9554259149999922, + "forward_path_file": "../data/paths/driving_path_left2right.txt", + "forward_path_range": [0, 40], + "backward_path_file": "../data/paths/driving_path_left2right.txt", + "backward_path_range": [40, -1] + }, + "2": { + "P_0": [-2.284308814, -31.734065629999996], + "P_d": [0.409550333177305, -18.459612079588652], + "P_f": [-7.449310874, -21.459648512], + "yaw_0": 178.9748993, + "yaw_d": 128.76474382600003, + "yaw_f": 88.703015164000007, + "forward_path_file": "../data/paths/driving_path_right2left.txt", + "forward_path_range": [0, 46], + "backward_path_file": "../data/paths/driving_path_right2left.txt", + "backward_path_range": [46, -1] + }, + "3": { + "P_0": [], + "P_d": [1.035116, -18.325821], + "P_f": [-7.685114, -21.214608], + "yaw_0": null, + "yaw_d": 40, + "yaw_f": 90, + "backward_path_file": "../data/paths/hitachi.txt", + "backward_path_range": [0, -1] + } +} diff --git a/PythonAPI/scripts/HapticSharedControl/simulation.py b/PythonAPI/scripts/HapticSharedControl/simulation.py new file mode 100644 index 0000000..bab8746 --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/simulation.py @@ -0,0 +1,126 @@ +import matplotlib.pyplot as plt +import numpy as np + +from .haptic_algo import * +from .path_planning import * +from .utils import * + +plt.style.use("default") + + +# cspell: ignore bezier arctan xlabel figsize ylabel +def simulation( + path, param, i_points, f_points, i_yaw, speed, init_steering_angle, vehicle_config, n_steps +): + print("============================\nSimulation running\n============================") + current_position = i_points + # Haptic Shared Control Initialization + haptic_control = HapticSharedControl( + Cs=0.5, + Kc=0.5, + T=2, + tp=1, + speed=speed, + desired_trajectory_params=param, + vehicle_config=vehicle_config, + ) + + # Simulation Loop + print("Starting Simulation") + + s_angleL = init_steering_angle + s_angleR = init_steering_angle + + trajectory = [current_position] + torques = [] + steering_angles_deg_list = [init_steering_angle] + + yaw_angles_deg = [i_yaw] # if change sign of swa, change sign here + + # Calculate the torque at each step + step = 0 + distances = [np.float("inf")] + while True: + print("=====================================") + print("\n>>> STEP:", step) + + torque, coef, desired_steering_angle_deg = haptic_control.calculate_torque( + current_position=current_position, + steering_angles_deg=[s_angleL, s_angleR], + current_yaw_angle_deg=i_yaw, + ) + + next_position = haptic_control.rtp + + torques.append(torque) + trajectory.append(next_position) + + steering_angles_deg_list.append(desired_steering_angle_deg) + yaw_angles_deg.append(haptic_control.predict_yaw_angle_deg) + + s_angleL = np.clip(desired_steering_angle_deg, -47.95, 69.99) + s_angleR = np.clip(desired_steering_angle_deg, -69.99, 47.95) + + i_yaw = haptic_control.predict_yaw_angle_deg + current_position = next_position + + step += 1 + if n_steps is not None and step >= n_steps: + break + elif n_steps is None: + # consider the point as reached if the distance is less than 0.1 + dist_t = dist(current_position, f_points) + if dist_t > distances[-1]: + trajectory.pop(-1) + torques.pop(-1) + steering_angles_deg_list.pop(-1) + yaw_angles_deg.pop(-1) + print("Distance increased so stop the simulation") + break + distances.append(dist_t) + + return path, trajectory, yaw_angles_deg + + +def plot_trajectory(paths, trajectories, yaw_angles_deg, recorded_path=None): + # Extract trajectory points + # paths.remove(None) + # trajectories.remove(None) + # yaw_angles_deg.remove(None) + + colors = ["red", "green", "orange"] + # Plot the trajectory + plt.figure(figsize=(8, 8)) + for i in range(len(paths)): + trajectory = np.array(trajectories[i]) + x_points = trajectory[:, 0] + y_points = trajectory[:, 1] + + plt.plot(paths[i][:, 0], paths[i][:, 1], "--", label=f"Bezier Path {i}", color="blue") + for idx, point in enumerate(zip(paths[i][:, 0], paths[i][:, 1])): + plt.plot(point[0], point[1], "o", color="blue") + + plt.plot(paths[i][0, 0], paths[i][0, 1], "o", label=f"Start point path {i}", color="Black") + plt.plot( + paths[i][-1, 0], paths[i][-1, 1], "o", label=f"End point path {i}", color="purple" + ) + + # Plot the vehicle trajectory + plt.plot(x_points, y_points, label=f"Predicted Path {i}", color=colors[i]) + for idx, point in enumerate(zip(x_points, y_points)): + plt.plot(point[0], point[1], "o", color=colors[i]) + plot_arrow(point[0], point[1], np.radians(yaw_angles_deg[i][idx]), 0.3, width=0.2) + + if recorded_path is not None: + plt.plot(recorded_path[1], recorded_path[0], label="Recorded Path", color="orange", marker=".") + + plt.xlabel("X (m)") + plt.ylabel("Y (m)") + plt.title("Vehicle Path and Bezier Trajectory") + + plt.legend() + plt.grid(True) + plt.tight_layout() + plt.axis("square") + plt.show() + plt.close() diff --git a/PythonAPI/scripts/HapticSharedControl/utils.py b/PythonAPI/scripts/HapticSharedControl/utils.py new file mode 100644 index 0000000..d2c98fb --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/utils.py @@ -0,0 +1,436 @@ +""" +Utility module for vehicle dynamics and geometry calculations. + +This module provides utility functions and classes for: +- Vehicle dynamics and steering geometry +- Path processing and trajectory calculations +- General mathematical and geometric operations +""" + +import math +from typing import Any, Callable, Dict, List, Optional, Tuple, Union + +import numpy as np +from scipy.spatial import KDTree + +# ===================== +# Mathematical Utilities +# ===================== + +def cot(x: float) -> float: + """ + Calculate cotangent of angle. + + Args: + x: Angle in radians + + Returns: + Cotangent value + """ + return 1 / np.tan(x) + + +def arccot(x: float) -> float: + """ + Calculate inverse cotangent (arccot) of value. + + Args: + x: Value to find arccot for + + Returns: + Angle in radians + """ + return np.arctan(1 / x) + + +def sigmoid(x: float) -> float: + """ + Sigmoid activation function. + + Args: + x: Input value + + Returns: + Sigmoid result in range (0, 1) + """ + return 1 / (1 + np.exp(-x)) + + +def dist(p1: Union[List[float], np.ndarray], + p2: Union[List[float], np.ndarray]) -> float: + """ + Calculate Euclidean distance between two points. + + Args: + p1: First point as [x, y] + p2: Second point as [x, y] + + Returns: + Euclidean distance + """ + return np.linalg.norm(np.array(p1) - np.array(p2)) + + +def sign(x: float) -> float: + """ + Get sign of a value (+1, -1, or 0). + + Args: + x: Input value + + Returns: + Sign of input: +1, -1, or 0 + """ + return x / np.abs(x) if x != 0 else 0 + + +def linear_fn(slope: float, intercept: float) -> Callable[[float], float]: + """ + Create a linear function (y = mx + b). + + Args: + slope: Slope (m) + intercept: Y-intercept (b) + + Returns: + Function that computes y = slope * x + intercept + """ + return lambda x: slope * x + intercept + + +# ===================== +# Geometric Utilities +# ===================== + +def getAngle(a: List[float], b: List[float], c: List[float], degrees: bool = False) -> float: + """ + Calculate the angle between three points (angle at point b). + + Args: + a: First point [x, y] + b: Middle point [x, y] (vertex of angle) + c: Third point [x, y] + degrees: If True, return angle in degrees, otherwise in radians + + Returns: + Angle in degrees or radians + """ + angle_rad = math.atan2(c[1] - b[1], c[0] - b[0]) - math.atan2(a[1] - b[1], a[0] - b[0]) + return math.degrees(angle_rad) if degrees else angle_rad + + +def rotation_matrix_cw(angle_rad: float) -> np.ndarray: + """ + Create a 2D clockwise rotation matrix. + + Args: + angle_rad: Rotation angle in radians + + Returns: + 2x2 rotation matrix + """ + return np.array([ + [np.cos(angle_rad), -np.sin(angle_rad)], + [np.sin(angle_rad), np.cos(angle_rad)] + ]) + + +def rotation_matrix_ccw(angle_rad: float) -> np.ndarray: + """ + Create a 2D counter-clockwise rotation matrix. + + Args: + angle_rad: Rotation angle in radians + + Returns: + 2x2 rotation matrix + """ + return np.array([ + [np.cos(angle_rad), np.sin(angle_rad)], + [-np.sin(angle_rad), np.cos(angle_rad)] + ]) + + +def find_closest_point(given_point: Union[List[float], np.ndarray], + list_of_points: Union[List[List[float]], np.ndarray], + method: str = "Brute") -> Tuple[np.ndarray, int]: + """ + Find the closest point in a list to a given point. + + Args: + given_point: The reference point [x, y] + list_of_points: List of points to search + method: Search method ('KDTree' or 'linear') + + Returns: + Tuple containing (closest_point, index) + """ + # Convert inputs to numpy arrays + given_point_np = np.array(given_point) + points_np = np.array(list_of_points) + + if method == "KDTree": + # Use KD-Tree for efficient nearest neighbor search + tree = KDTree(points_np) + _, nnidx = tree.query(given_point_np, k=1) + else: + # Use linear search (slower but no dependencies) + distances = np.linalg.norm(points_np - given_point_np, axis=1) + nnidx = np.argmin(distances) + + return list_of_points[nnidx], nnidx + + +# ===================== +# Path Processing +# ===================== + +def process_exist_path(path_points: np.ndarray) -> Dict[str, Any]: + """ + Process a sequence of path points to extract path properties. + + Args: + path_points: Array of path coordinates [[x1, y1], [x2, y2], ...] + + Returns: + Dictionary containing processed path data: + - 'path': Array of points + - 'tangent': Array of tangent vectors + - 'end_x', 'end_y': End point coordinates + """ + if len(path_points) < 3: + raise ValueError("Path must have at least 3 points to process") + + # Extract path points + path_x = path_points[:, 0] + path_y = path_points[:, 1] + + # Calculate tangent vectors (p1, p2, p3) for each point + tangent_vectors = [] + for i in range(len(path_points)): + if i == 0: # First point + p1 = path_points[i] + p2 = path_points[i] + p3 = path_points[i+1] + elif i == len(path_points) - 1: # Last point + p1 = path_points[i-1] + p2 = path_points[i] + p3 = path_points[i] + else: # Middle points + p1 = path_points[i-1] + p2 = path_points[i] + p3 = path_points[i+1] + + tangent_vectors.append((p1, p3)) + + # Return processed path data + return { + "path": path_points, + "tangent": np.array(tangent_vectors), + "end_x": path_x[-1], + "end_y": path_y[-1] + } + + +# ===================== +# Vehicle Class +# ===================== + +class Vehicle: + """ + Vehicle model for dynamics and steering calculations. + + This class encapsulates vehicle parameters and provides methods + to calculate turning radius, steering angles, and other dynamics. + """ + + def __init__(self, vehicle_config: Dict[str, Any], model: str = "simple") -> None: + """ + Initialize vehicle model. + + Args: + vehicle_config: Dictionary with vehicle configuration + model: Vehicle model type ('simple' or 'ackermann') + """ + self.vehicle_config = vehicle_config + self.vehicle_model = model.lower() + + # Default parameters + self.wheelbase = 2.7 # meters + self.tire_width = 1.8 # meters + self.center_of_mass_ratio = 0.45 # ratio of wheelbase + self.center_of_mass = 0.0 # calculated from wheelbase + self.minimum_turning_radius = 5.0 # meters + + # Maximum steering angles + self.max_steering_angle_inner_deg = 69.99999237060547 + self.max_steering_angle_outer_deg = 47.425662994384766 + + # Initialize model from config + self._init_vehicle_model() + + def _init_vehicle_model(self) -> None: + """ + Initialize vehicle parameters from configuration. + + Extracts wheelbase, tire width, and center of mass + from the vehicle configuration. + """ + # Check if we have a valid configuration + if not self.vehicle_config or "wheels" not in self.vehicle_config: + return + + try: + # Calculate wheelbase (distance between front and rear axles) + self.wheelbase = ( + abs( + self.vehicle_config["wheels"][0]["position"]["y"] - + self.vehicle_config["wheels"][2]["position"]["y"] + ) / 100.0 # Convert from cm to meters + ) + + # Calculate tire width (track width) + self.tire_width = ( + abs( + self.vehicle_config["wheels"][1]["position"]["x"] - + self.vehicle_config["wheels"][0]["position"]["x"] + ) / 100.0 # Convert from cm to meters + ) + + # Get center of mass position relative to wheelbase + self.center_of_mass_ratio = self.vehicle_config.get("center_of_mass", {}).get("x", 0.45) + + # Calculate center of mass position in meters + self.center_of_mass = self.wheelbase * self.center_of_mass_ratio + + # Calculate minimum turning radius using maximum steering angles + self.minimum_turning_radius = self.calc_turning_radius( + [self.max_steering_angle_inner_deg, self.max_steering_angle_outer_deg] + )["R"] + + except (KeyError, IndexError, TypeError) as e: + print(f"Error initializing vehicle model: {e}") + + def calc_turning_radius(self, steering_angles: List[float]) -> Dict[str, Any]: + """ + Calculate vehicle turning radius and steering parameters. + + This function implements two steering models: + 1. Simple: Basic bicycle model using outer wheel angle + 2. Ackermann: Uses both inner and outer wheel angles for more accuracy + + Args: + steering_angles: List of [left_wheel_angle, right_wheel_angle] in degrees + + Returns: + Dictionary with calculated parameters: + - R: Turning radius (meters) + - Delta: Vehicle steering angle (degrees) + - CoR_v: Center of rotation in vehicle coordinates [x, y] + """ + # Determine inner and outer wheel based on steering direction + if steering_angles[0] > steering_angles[1]: # Turning right + inner_wheel_angle_deg = steering_angles[1] + outer_wheel_angle_deg = steering_angles[0] + else: # Turning left + inner_wheel_angle_deg = steering_angles[0] + outer_wheel_angle_deg = steering_angles[1] + + # Convert to radians + inner_wheel_angle_rad = np.radians(inner_wheel_angle_deg) + outer_wheel_angle_rad = np.radians(outer_wheel_angle_deg) + + # Initialize variables + turning_radius = 0.0 + vehicle_steering_angle_rad = 0.0 + + # Calculate using selected model + if self.vehicle_model == "simple": + # Use the simple bicycle model + # Based on outer wheel angle for better stability + steering_angle_rad = outer_wheel_angle_rad + + # Avoid division by zero at exactly 0 or 180 degrees + if abs(steering_angle_rad % np.pi) < 1e-6: + steering_angle_rad += 1e-6 + + # Calculate turning radius using bicycle model formula + turning_radius = np.sqrt( + self.center_of_mass**2 + + (self.wheelbase**2) / np.tan(steering_angle_rad)**2 + ) + + # Calculate effective vehicle steering angle + vehicle_steering_angle_rad = np.arctan( + self.center_of_mass_ratio * np.tan(steering_angle_rad) + ) + + else: + # Use the Ackermann steering model for more accuracy + # Avoid division by zero + if abs(inner_wheel_angle_rad % np.pi) < 1e-6: + inner_wheel_angle_rad += 1e-6 + if abs(outer_wheel_angle_rad % np.pi) < 1e-6: + outer_wheel_angle_rad += 1e-6 + + # Calculate effective steering angle using Ackermann formula + steering_angle_rad = arccot( + (cot(inner_wheel_angle_rad) + cot(outer_wheel_angle_rad)) / 2 + ) + + # Calculate turning radius + turning_radius = np.sqrt( + self.center_of_mass**2 + + (self.wheelbase**2) * (cot(steering_angle_rad)**2) + ) + + # Calculate effective vehicle steering angle + vehicle_steering_angle_rad = steering_angle_rad + + # Calculate center of rotation in vehicle coordinates + # Avoid division by zero + if abs(vehicle_steering_angle_rad) < 1e-6: + cor_y = float('inf') # Infinite turning radius (straight line) + else: + cor_y = self.center_of_mass / np.tan(vehicle_steering_angle_rad) + + center_of_rotation = np.array([-self.center_of_mass, cor_y]) + + # Return calculated parameters + return { + "R": abs(turning_radius), + "Delta": np.degrees(vehicle_steering_angle_rad), + "CoR_v": center_of_rotation + } + + +# Testing the utilities +if __name__ == "__main__": + # Test angle calculation + a = (5, 0) + b = (0, 0) + c = (0, -5) + angle_deg = getAngle(a, b, c, degrees=True) + print(f"Angle between points: {angle_deg} degrees") + + # Test vehicle model + test_config = { + "wheels": [ + {"position": {"x": -75, "y": 130}}, # Front left + {"position": {"x": 75, "y": 130}}, # Front right + {"position": {"x": -75, "y": -130}}, # Rear left + {"position": {"x": 75, "y": -130}} # Rear right + ], + "center_of_mass": {"x": 0.45} + } + + vehicle = Vehicle(test_config) + print(f"Vehicle wheelbase: {vehicle.wheelbase} m") + print(f"Vehicle track width: {vehicle.tire_width} m") + + # Test turning radius calculation + steering_angles = [20.0, 15.0] # Left and right wheel angles + turning_data = vehicle.calc_turning_radius(steering_angles) + print(f"Turning radius: {turning_data['R']:.2f} m") + print(f"Vehicle steering angle: {turning_data['Delta']:.2f} degrees") + print(f"Center of rotation: {turning_data['CoR_v']}") \ No newline at end of file diff --git a/PythonAPI/scripts/HapticSharedControl/wheel_control.py b/PythonAPI/scripts/HapticSharedControl/wheel_control.py new file mode 100644 index 0000000..19b0a8a --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/wheel_control.py @@ -0,0 +1,707 @@ +""" +Logitech G920 Driving Force Racing Wheel Control Module + +This module provides a robust interface to the Logitech G920 steering wheel controller, +handling force feedback, button mapping, and pedal input with comprehensive error handling. +""" + +import ctypes +import gc +import logging +import sys +import time +from pathlib import Path +from typing import Any, Callable, Dict, List, Optional, Tuple, Union + +import numpy as np +import pandas as pd + +# Add logidrivepy to path +sys.path.append(str(Path(__file__).parent.parent / "logidrivepy")) +from logidrivepy import LogitechController + +# Constants +MAX_ANGLE_RANGE = 900 # Maximum rotation range in degrees +DEFAULT_SATURATION = 50 +DEFAULT_COEFFICIENT = 100 +AXIS_MAX_VALUE = 32767.0 # Maximum raw axis value + +# Configure logging +logging.basicConfig( + level=logging.INFO, + format='%(asctime)s - %(name)s - %(levelname)s - %(message)s' +) +logger = logging.getLogger("WheelController") + + +class WheelController: + """ + Controller interface for Logitech G920 Driving Force Racing Wheel. + + This class provides methods to interact with the G920 wheel, including reading wheel position, + pedal states, button presses, and applying force feedback effects. + """ + + def __init__(self, controller_index: int = 0, log_level: int = logging.INFO): + """ + Initialize the wheel controller. + + Args: + controller_index: Index of the controller (default: 0) + log_level: Logging level (default: INFO) + + Raises: + RuntimeError: If controller initialization fails + """ + # Set up logging + logger.setLevel(log_level) + + # Initialize controller + self.controller_index = controller_index + self.controller = LogitechController() + + # Initialize wheel + init_success = self.controller.steering_initialize() + if not init_success: + raise RuntimeError("Failed to initialize Logitech controller. Check connection and drivers.") + + # Set wheel operating range + self.controller.set_operating_range(index=self.controller_index, range=MAX_ANGLE_RANGE) + + # Cache for reducing state queries + self._state_cache = None + self._last_update_time = 0 + self._cache_validity_ms = 10 # Cache valid for 10ms + + # Log initialization details + self._log_controller_info() + + def _log_controller_info(self) -> None: + """Log controller initialization details""" + logger.info("Logitech Controller Initialized") + logger.info(f"Connected: {self.controller.is_connected(index=self.controller_index)}") + logger.info(f"Force feedback available: {self.controller.has_force_feedback(index=self.controller_index)}") + + operating_range = self.controller.get_operating_range( + index=self.controller_index, + range=ctypes.c_int() + ) + logger.info(f"Operating range: {operating_range} degrees") + + def _update_state(self, force: bool = False) -> None: + """ + Update the controller state. + + Args: + force: Force update even if cache is valid + """ + current_time = time.time() * 1000 # Convert to milliseconds + + # Update if cache is invalid or forced update + if force or (current_time - self._last_update_time > self._cache_validity_ms): + self.controller.logi_update() + self._state_cache = self.controller.get_state_engines(self.controller_index).contents + self._last_update_time = current_time + + def play_spring_force( + self, + offset_percentage: int, + saturation_percentage: int = DEFAULT_SATURATION, + coefficient_percentage: int = DEFAULT_COEFFICIENT + ) -> bool: + """ + Apply spring force effect to the steering wheel. + + Args: + offset_percentage: Center point offset (-100 to 100) + saturation_percentage: Force saturation (0 to 100) + coefficient_percentage: Spring stiffness (0 to 100) + + Returns: + bool: Success status + + Notes: + - offset_percentage: Controls the center position of the spring + -100 = full left, 0 = center, 100 = full right + - saturation_percentage: Controls maximum force applied + 0 = no force, 100 = maximum force + - coefficient_percentage: Controls spring stiffness + 0 = no resistance, 100 = maximum resistance + """ + try: + self._update_state(force=True) + + # Ensure values are within valid ranges + offset = max(-100, min(100, int(offset_percentage))) + saturation = max(0, min(100, int(saturation_percentage))) + coefficient = max(-100, min(100, int(coefficient_percentage))) + + if coefficient < 0: + logger.warning(f"Coefficient {coefficient} will make the steering wheel rotate reversly") + + success = self.controller.play_spring_force( + index=self.controller_index, + offset_percentage=offset, + saturation_percentage=saturation, + coefficient_percentage=coefficient, + ) + + if not success: + logger.warning(f"Failed to apply spring force: {offset}, {saturation}, {coefficient}") + + return success + + except Exception as e: + logger.error(f"Error applying spring force: {e}") + return False + + def stop_spring_force(self) -> bool: + """ + Stop spring force feedback effect. + + Returns: + bool: Success status + """ + try: + self._update_state(force=True) + success = self.controller.stop_spring_force(index=self.controller_index) + + if not success: + logger.warning("Failed to stop spring force") + + return success + + except Exception as e: + logger.error(f"Error stopping spring force: {e}") + return False + + def get_state_engines(self) -> Dict[str, Any]: + """ + Get complete controller state including all axes, buttons, and forces. + + Returns: + Dict containing all controller state parameters + """ + try: + self._update_state() + + # Create dictionary of all state values + return { + # Position axes + "lX": self._state_cache.lX, + "lY": self._state_cache.lY, + "lZ": self._state_cache.lZ, + "lRx": self._state_cache.lRx, + "lRy": self._state_cache.lRy, + "lRz": self._state_cache.lRz, + "rglSlider": list(self._state_cache.rglSlider), + + # D-pad and buttons + "rgdwPOV": list(self._state_cache.rgdwPOV), + "rgbButtons": list(self._state_cache.rgbButtons), + + # Velocity + "lVX": self._state_cache.lVX, + "lVY": self._state_cache.lVY, + "lVZ": self._state_cache.lVZ, + "lVRx": self._state_cache.lVRx, + "lVRy": self._state_cache.lVRy, + "lVRz": self._state_cache.lVRz, + "rglVSlider": list(self._state_cache.rglVSlider), + + # Acceleration + "lAX": self._state_cache.lAX, + "lAY": self._state_cache.lAY, + "lAZ": self._state_cache.lAZ, + "lARx": self._state_cache.lARx, + "lARy": self._state_cache.lARy, + "lARz": self._state_cache.lARz, + "rglASlider": list(self._state_cache.rglASlider), + + # Force + "lFX": self._state_cache.lFX, + "lFY": self._state_cache.lFY, + "lFZ": self._state_cache.lFZ, + "lFRx": self._state_cache.lFRx, + "lFRy": self._state_cache.lFRy, + "lFRz": self._state_cache.lFRz, + "rglFSlider": list(self._state_cache.rglFSlider), + } + + except Exception as e: + logger.error(f"Error getting state: {e}") + # Return empty state on error + return {} + + def get_angle(self, translate: bool = True) -> float: + """ + Get steering wheel angle. + + Args: + translate: If True, normalize to [-1.0, 1.0] range + + Returns: + float: Wheel angle (normalized or raw) + """ + try: + self._update_state() + + raw_value = self._state_cache.lX + + if not translate: + return raw_value + else: + return np.clip(raw_value / AXIS_MAX_VALUE, -1.0, 1.0) + + except Exception as e: + logger.error(f"Error getting wheel angle: {e}") + return 0.0 + + def get_acceleration_pedal(self, translate: bool = True) -> float: + """ + Get acceleration pedal position. + + Args: + translate: If True, normalize to [0, 1] range + + Returns: + float: Pedal position (normalized or raw) + """ + try: + self._update_state() + + raw_value = self._state_cache.lY + + if not translate: + return raw_value + else: + # Map from [-32767, 32767] to [0, 1] + # Note: For acceleration, higher raw value = more pressed + return np.clip((raw_value + AXIS_MAX_VALUE) / (2 * AXIS_MAX_VALUE), 0.0, 1.0) + + except Exception as e: + logger.error(f"Error getting acceleration pedal: {e}") + return 0.0 + + def get_brake_pedal(self, translate: bool = True) -> float: + """ + Get brake pedal position. + + Args: + translate: If True, normalize to [0, 1] range + + Returns: + float: Pedal position (normalized or raw) + """ + try: + self._update_state() + + raw_value = self._state_cache.lRz + + if not translate: + return raw_value + else: + # Brake is fully released at 32767, fully pressed at -32768 + # Map to [0, 1] where 1 is fully pressed + return np.clip(abs(raw_value - AXIS_MAX_VALUE) / (2 * AXIS_MAX_VALUE), 0.0, 1.0) + + except Exception as e: + logger.error(f"Error getting brake pedal: {e}") + return 0.0 + + def get_buttons_pressed(self) -> Dict[str, Union[str, bool]]: + """ + Get status of wheel buttons and D-pad. + + Returns: + Dict containing button states: + - "D-pad": Direction ("up", "right", "down", "left", "center") + - "A", "B", "X", "Y": Boolean button states + """ + try: + self._update_state() + + # Extract D-pad and button values + rgdwPOV = list(self._state_cache.rgdwPOV) + rgbButtons = list(self._state_cache.rgbButtons) + + # Process D-pad values + dpad_direction = self._process_dpad(rgdwPOV[0]) + + # Process buttons (first 4 buttons: A, B, X, Y) + button_states = { + "D-pad": dpad_direction, + "A": self._process_button(rgbButtons[0]), + "B": self._process_button(rgbButtons[1]), + "X": self._process_button(rgbButtons[2]), + "Y": self._process_button(rgbButtons[3]), + } + + return button_states + + except Exception as e: + logger.error(f"Error getting button states: {e}") + return {"D-pad": "center", "A": False, "B": False, "X": False, "Y": False} + + def _process_dpad(self, value: int) -> str: + """ + Process D-pad value into direction. + + Args: + value: Raw D-pad value + + Returns: + str: Direction as string + """ + # Map POV values to directions (in hundredths of degrees) + if value == 0: + return "up" + elif value == 9000: + return "right" + elif value == 18000: + return "down" + elif value == 27000: + return "left" + return "center" + + def _process_button(self, value: int) -> bool: + """ + Process button value to boolean state. + + Args: + value: Raw button value + + Returns: + bool: True if button is pressed + """ + return value != 0 + + def exit(self) -> None: + """ + Clean up controller resources. + """ + try: + self._update_state(force=True) + self.stop_spring_force() + self.controller.steering_shutdown() + del self.controller + gc.collect() + logger.info("Steering controller shutdown successful") + except Exception as e: + logger.error(f"Error during controller shutdown: {e}") + + +class WheelTester: + """ + Test utility for the wheel controller. + + Provides methods to test different aspects of the wheel controller: + - Recording states + - Profiling spring force behavior + - Testing force feedback parameters systematically + """ + + def __init__(self, controller: WheelController): + """ + Initialize the wheel tester. + + Args: + controller: Wheel controller instance + """ + self.controller = controller + self.test_start_time = time.time() + self.logger = logging.getLogger("WheelTester") + + def record_states(self, duration: int = 10, interval: float = 0.5) -> Dict: + """ + Record and monitor controller states for a specified duration. + + Args: + duration: Recording duration in seconds + interval: Sampling interval in seconds + + Returns: + Dict of final controller state + """ + self.logger.info(f"Recording states for {duration} seconds...") + states = {} + start_time = time.time() + + while time.time() - start_time < duration: + curr_state = self.controller.get_state_engines() + + # Initialize states dict if empty + if not states: + states = curr_state.copy() + continue + + # Log changes in state + for (curr_key, curr_values), (key, value) in zip(curr_state.items(), states.items()): + if states[key] != curr_values and key != "lAZ": # Ignore acceleration Z which changes frequently + print(f"{key}: {value} --> {curr_values}") + + states = curr_state.copy() + print("----") + time.sleep(interval) + + self.logger.info("State recording completed") + return states + + def test_force_feedback_profile(self, + offset_range: Tuple[int, int] = (-100, 100), + sat_range: Tuple[int, int] = (10, 100), + coef_range: Tuple[int, int] = (10, 100), + step_size: int = 5) -> pd.DataFrame: + """ + Test all combinations of force feedback parameters. + + Args: + offset_range: Range of offset values (min, max) + sat_range: Range of saturation values (min, max) + coef_range: Range of coefficient values (min, max) + step_size: Step size for parameter increments + + Returns: + DataFrame of test results + """ + self.logger.info("Starting comprehensive force feedback test...") + df_data = {} + + # Test all combinations of parameters + for sat in range(sat_range[0], sat_range[1] + 1, step_size): + print(f"Saturation: {sat}") + for coef in range(coef_range[0], coef_range[1] + 1, step_size): + print(f" Coefficient: {coef}") + for offset in range(offset_range[0], offset_range[1] + 1, step_size): + print(f" Offset: {offset}", end="\r") + + # Apply force feedback + self.controller.play_spring_force( + offset_percentage=offset, + saturation_percentage=sat, + coefficient_percentage=coef, + ) + + # Record state + time.sleep(0.1) # Allow time for force to apply + state = self.controller.get_state_engines() + + # Store data + timestamp = time.time() - self.test_start_time + df_data.setdefault("timestamp", []).append(timestamp) + df_data.setdefault("offset", []).append(offset) + df_data.setdefault("saturation", []).append(sat) + df_data.setdefault("coefficient", []).append(coef) + df_data.setdefault("wheel_angle", []).append(self.controller.get_angle() * MAX_ANGLE_RANGE / 2) + + # Add all state parameters + for key, value in state.items(): + if isinstance(value, (int, float)): + df_data.setdefault(key, []).append(value) + elif isinstance(value, (list, tuple)): + # Handle first element of lists (most relevant) + if value: + df_data.setdefault(f"{key}_0", []).append(value[0]) + + # Create DataFrame + df = pd.DataFrame(df_data) + + # Save results + output_file = f"wheel_test_profile_{time.strftime('%Y%m%d_%H%M%S')}.xlsx" + df.to_excel(output_file, index=False) + self.logger.info(f"Force feedback test completed. Results saved to {output_file}") + + # Stop forces + self.controller.stop_spring_force() + + return df + + def test_force_response(self, + offset: int, + saturation: int, + coefficient: int, + duration: float = 5.0, + sample_rate: float = 100) -> pd.DataFrame: + """ + Test wheel response to a specific force feedback configuration over time. + + Args: + offset: Center offset value (-100 to 100) + saturation: Saturation value (0 to 100) + coefficient: Coefficient value (0 to 100) + duration: Test duration in seconds + sample_rate: Samples per second + + Returns: + DataFrame of response data + """ + self.logger.info(f"Testing response to offset={offset}, sat={saturation}, coef={coefficient}") + + # Calculate time step + time_step = 1.0 / sample_rate + + # Initialize result data + df_data = { + "timestamp": [], + "offset": [], + "saturation": [], + "coefficient": [], + "wheel_angle": [], + "wheel_angle_normalized": [], + "phase": [] + } + + # Phase 1: Reset to center + self._run_test_phase( + df_data, "Centering", + 0, 100, 100, # Full force to center + 2.0, time_step + ) + + # Phase 2: Apply test force + self._run_test_phase( + df_data, "Testing", + offset, saturation, coefficient, + duration, time_step + ) + + # Phase 3: Return to center + self._run_test_phase( + df_data, "Returning", + 0, 100, 100, # Full force to center + 2.0, time_step + ) + + # Create DataFrame + df = pd.DataFrame(df_data) + + # Save results + output_file = f"wheel_response_o{offset}_s{saturation}_c{coefficient}_{time.strftime('%Y%m%d_%H%M%S')}.xlsx" + df.to_excel(output_file, index=False) + self.logger.info(f"Response test completed. Results saved to {output_file}") + + return df + + def _run_test_phase(self, + df_data: Dict[str, List], + phase_name: str, + offset: int, + saturation: int, + coefficient: int, + duration: float, + time_step: float) -> None: + """ + Run a single phase of the response test. + + Args: + df_data: Dictionary to store results + phase_name: Name of the test phase + offset: Center offset value + saturation: Saturation value + coefficient: Coefficient value + duration: Phase duration in seconds + time_step: Sampling interval in seconds + """ + # Apply force + self.controller.play_spring_force( + offset_percentage=offset, + saturation_percentage=saturation, + coefficient_percentage=coefficient + ) + + # Record data for duration + start_time = time.time() + while time.time() - start_time < duration: + current_time = time.time() - self.test_start_time + wheel_angle = self.controller.get_angle(translate=False) + wheel_angle_degrees = self.controller.get_angle(translate=True) * MAX_ANGLE_RANGE / 2 + + # Store data + df_data["timestamp"].append(current_time) + df_data["phase"].append(phase_name) + df_data["offset"].append(offset) + df_data["saturation"].append(saturation) + df_data["coefficient"].append(coefficient) + df_data["wheel_angle"].append(wheel_angle_degrees) + df_data["wheel_angle_normalized"].append(wheel_angle / AXIS_MAX_VALUE) + + # Sleep for precise timing + next_sample = start_time + (time.time() - start_time) // time_step * time_step + time_step + sleep_time = max(0, next_sample - time.time()) + if sleep_time > 0: + time.sleep(sleep_time) + + +# Main test functions +def main_test(): + """Run basic controller tests""" + try: + # Initialize controller + controller = WheelController() + + # Create tester + tester = WheelTester(controller) + + # Run monitoring test + print("Starting controller state monitor. Press Ctrl+C to stop.") + tester.record_states(duration=30) + + # Clean up + controller.exit() + print("Test completed successfully.") + + except KeyboardInterrupt: + print("\nTest interrupted by user.") + if 'controller' in locals(): + controller.exit() + + except Exception as e: + print(f"Test failed: {e}") + if 'controller' in locals(): + controller.exit() + + +def force_feedback_test(): + """Run force feedback tests""" + try: + # Initialize controller + controller = WheelController() + + # Create tester + tester = WheelTester(controller) + + # Run targeted tests + for offset in [-80, -40, 0, 40, 80]: + tester.test_force_response( + offset=offset, + saturation=100, + coefficient=50, + duration=3.0 + ) + time.sleep(1) + + # Clean up + controller.exit() + print("Force feedback test completed successfully.") + + except KeyboardInterrupt: + print("\nTest interrupted by user.") + if 'controller' in locals(): + controller.exit() + + except Exception as e: + print(f"Test failed: {e}") + if 'controller' in locals(): + controller.exit() + + +if __name__ == "__main__": + # Select test to run + test_type = "basic" + + if test_type == "basic": + main_test() + elif test_type == "force": + force_feedback_test() + else: + print(f"Unknown test type: {test_type}") \ No newline at end of file diff --git a/PythonAPI/scripts/HapticSharedControl/wheel_setting.json b/PythonAPI/scripts/HapticSharedControl/wheel_setting.json new file mode 100644 index 0000000..691d595 --- /dev/null +++ b/PythonAPI/scripts/HapticSharedControl/wheel_setting.json @@ -0,0 +1,136 @@ +{ + "torque_curve": [ + { + "x": -9.310944, + "y": 743.0 + }, + { + "x": 9000.0, + "y": 743.0 + }, + { + "x": 9500.0, + "y": 660.0 + }, + { + "x": 10400.0, + "y": 605.0 + }, + { + "x": 12500.0, + "y": 528.0 + }, + { + "x": 15000.0, + "y": 502.0 + } + ], + "max_rpm": 15000.0, + "moi": 1.0, + "damping_rate_full_throttle": 0.15, + "damping_rate_zero_throttle_clutch_engaged": 2.0, + "damping_rate_zero_throttle_clutch_disengaged": 0.35, + "use_gear_autobox": true, + "gear_switch_time": 0.0, + "clutch_strength": 10.0, + "final_ratio": 9.0, + "forward_gears": [ + { + "ratio": 1.0, + "down_ratio": 0.0, + "up_ratio": 0.0 + } + ], + "mass": 1845.0, + "drag_coefficient": 0.15, + "center_of_mass": { + "x": 0.45, + "y": 0.0, + "z": -0.3 + }, + "steering_curve": [ + { + "x": 0.0, + "y": 1.0 + }, + { + "x": 20.0, + "y": 0.9 + }, + { + "x": 60.0, + "y": 0.8 + }, + { + "x": 120.0, + "y": 0.7 + } + ], + "wheels": [ + { + "tire_friction": 3.5, + "damping_rate": 0.25, + "max_steer_angle": 69.999992, + "radius": 37.0, + "max_brake_torque": 700.0, + "max_handbrake_torque": 0.0, + "lat_stiff_max_load": 3.0, + "lat_stiff_value": 20.0, + "long_stiff_value": 3000.0, + "position": { + "x": -230.360107, + "y": -1484.240234, + "z": 53.834698 + } + }, + { + "tire_friction": 3.5, + "damping_rate": 0.25, + "max_steer_angle": 69.999992, + "radius": 37.0, + "max_brake_torque": 700.0, + "max_handbrake_torque": 0.0, + "lat_stiff_max_load": 3.0, + "lat_stiff_value": 20.0, + "long_stiff_value": 3000.0, + "position": { + "x": -63.677315, + "y": -1484.240356, + "z": 53.669857 + } + }, + { + "tire_friction": 3.5, + "damping_rate": 0.25, + "max_steer_angle": 0.0, + "radius": 37.0, + "max_brake_torque": 700.0, + "max_handbrake_torque": 1400.0, + "lat_stiff_max_load": 3.0, + "lat_stiff_value": 20.0, + "long_stiff_value": 3000.0, + "position": { + "x": -230.360168, + "y": -1183.775757, + "z": 53.750481 + } + }, + { + "tire_friction": 3.5, + "damping_rate": 0.25, + "max_steer_angle": 0.0, + "radius": 37.0, + "max_brake_torque": 700.0, + "max_handbrake_torque": 1400.0, + "lat_stiff_max_load": 3.0, + "lat_stiff_value": 20.0, + "long_stiff_value": 3000.0, + "position": { + "x": -63.677383, + "y": -1183.775757, + "z": 53.58186 + } + } + ], + "use_sweep_wheel_collision": 0 +} diff --git a/PythonAPI/scripts/README_walker_spawn.md b/PythonAPI/scripts/README_walker_spawn.md new file mode 100644 index 0000000..db77eb5 --- /dev/null +++ b/PythonAPI/scripts/README_walker_spawn.md @@ -0,0 +1,139 @@ +# Walker Area Spawn System + +This system automatically spawns walkers when a vehicle enters a predefined area. It's designed to work with the DReyeVR simulation environment and runs in asynchronous mode. + +## Files + +1. **walker_spawn_config.json** - Configuration file defining the trigger area, walker spawn/target positions, and behavior parameters +2. **DReyeVR_area_walker_spawn.py** - Main script that tracks vehicle position and spawns walkers + +## Configuration File (walker_spawn_config.json) + +### Main Sections: + +#### `simulation` + +- `sync_mode`: false (runs in asynchronous mode as requested) +- `delta_t`: Time step for simulation updates +- `update_frequency`: How often to check vehicle position + +#### `trigger_area` + +- `center`: Center coordinates of the circular trigger area (x, y, z) +- `radius`: Radius of the trigger area in meters +- `description`: Human-readable description + +#### `walker_spawn` + +- `number_of_walkers`: Maximum number of walkers to spawn +- `spawn_positions`: Array of starting positions for walkers (x, y, z coordinates) +- `target_positions`: Array of target positions where walkers will walk to +- `walker_speed`: Speed configuration (min, max, default values in m/s) +- `walker_filter`: Blueprint filter for walker types +- `generation`: Walker generation (1, 2, or "All") +- `is_invincible`: Whether walkers are invincible + +#### `vehicle_tracking` + +- `role_name`: Role name of the vehicle to track (usually "hero") +- `check_interval`: How often to check vehicle position (seconds) +- `spawn_once_per_entry`: Whether to spawn walkers only once per area entry + +#### `logging` + +- `enable_debug`: Enable debug logging +- `log_file`: Log file name + +## Usage + +### Basic Usage: + +```bash +python DReyeVR_area_walker_spawn.py +``` + +### With Custom Configuration: + +```bash +python DReyeVR_area_walker_spawn.py --config my_walker_config.json +``` + +### With Custom CARLA Connection: + +```bash +python DReyeVR_area_walker_spawn.py --host 192.168.1.100 --port 2000 +``` + +### Command Line Arguments: + +- `--host`: CARLA server IP address (default: 127.0.0.1) +- `--port`: CARLA server port (default: 2000) +- `--config`: Path to configuration file (default: walker_spawn_config.json) +- `--log-level`: Logging level (DEBUG, INFO, WARNING, ERROR) + +## How It Works + +1. **Vehicle Tracking**: The script continuously monitors the position of the hero vehicle +2. **Area Detection**: When the vehicle enters the defined trigger area, the system detects this entry +3. **Walker Spawning**: Upon area entry, walkers are spawned at the configured starting positions +4. **Walker Behavior**: Each walker is assigned a target position and walks there at the configured speed +5. **Entry Management**: Optionally spawn walkers only once per area entry (configurable) + +## Configuration Tips + +### Setting Up the Trigger Area: + +1. Determine the center coordinates where you want the trigger area +2. Set an appropriate radius (e.g., 50 meters for a large area) + +### Defining Walker Positions: + +1. **spawn_positions**: Place these where you want walkers to initially appear +2. **target_positions**: Place these where you want walkers to walk to +3. The system will pair spawn and target positions by index (wrapping around if needed) + +### Speed Configuration: + +- Set `min` and `max` to the same value for consistent speed +- Use different values for random speed variation +- `default` is used as fallback + +### Example Coordinate Setup: + +```json +"spawn_positions": [ + {"x": -389.46, "y": 9917.06, "z": 0.3, // Left side of road + {"x": 0, "y": 0, "z": 0.3} // Right side of road +], +"target_positions": [ + {"x": 413.30, "y": 9917.06, "z": 0.3}, // Cross to other side + {"x": -10, "y": 10, "z": 0.3} // Cross to other side +] +``` + +## Integration with DReyeVR + +This script is designed to work alongside the DReyeVR system. Make sure: + +1. Your vehicle has the role_name "hero" (or configure accordingly) +2. CARLA simulation is running +3. The DReyeVR ego vehicle is spawned before running this script + +## Logging + +The script provides detailed logging including: + +- Vehicle position tracking +- Area entry/exit events +- Walker spawning success/failure +- Error messages and warnings + +Set `--log-level DEBUG` for maximum verbosity during development. + +## Notes + +- The script runs in asynchronous mode by default (sync_mode: false) +- Walkers are automatically cleaned up when the script exits +- The system supports multiple spawn/target position pairs +- Walker speed can be randomized within the specified range +- The trigger area is circular - modify the code for other shapes if needed diff --git a/PythonAPI/scripts/__init__.py b/PythonAPI/scripts/__init__.py new file mode 100644 index 0000000..26666a7 --- /dev/null +++ b/PythonAPI/scripts/__init__.py @@ -0,0 +1,33 @@ +import glob +import os +import sys +from typing import List + +CARLA_ROOT: str = os.getenv("CARLA_ROOT") +if CARLA_ROOT is None: + raise Exception("Unable to find CARLA_ROOT in environment variable!") + +"""Add Carla PythonAPI .egg file""" +egg_dir: str = os.path.join(CARLA_ROOT, "PythonAPI", "carla", "dist") +carla_eggs: List[str] = glob.glob(os.path.join(egg_dir, f"carla-*.egg")) +for egg in carla_eggs: + sys.path.append(egg) +if len(carla_eggs) == 0: + print(f'No PythonAPI .egg file in "{egg_dir}"') + print("Make sure you built PythonAPI and an .egg was produced!") + +"""Add all Carla paths required by module""" +# see https://carla-scenariorunner.readthedocs.io/en/latest/getting_scenariorunner/#update-from-source +sys.path.extend( + [ + os.path.join(CARLA_ROOT, "PythonAPI", "carla", "agents"), + os.path.join(CARLA_ROOT, "PythonAPI", "carla"), + os.path.join(CARLA_ROOT, "PythonAPI", "examples"), + os.path.join(CARLA_ROOT, "PythonAPI", "HapticSharedControl"), + os.path.join(CARLA_ROOT, "PythonAPI", "scripts"), + os.path.join(CARLA_ROOT, "PythonAPI", "notebooks"), + os.path.join(CARLA_ROOT, "PythonAPI"), + ] +) + +print("Carla import successful!") diff --git a/PythonAPI/scripts/check_connection.py b/PythonAPI/scripts/check_connection.py new file mode 100644 index 0000000..7ec0325 --- /dev/null +++ b/PythonAPI/scripts/check_connection.py @@ -0,0 +1,10 @@ +import carla + +client = carla.Client("127.0.0.1", 2000) +client.set_timeout(10.0) + +try: + world = client.get_world() + print("✅ 接続成功: マップ =", world.get_map().name) +except RuntimeError as e: + print("❌ 接続失敗:", e) diff --git a/PythonAPI/scripts/config_manager.py b/PythonAPI/scripts/config_manager.py new file mode 100644 index 0000000..e3b0d08 --- /dev/null +++ b/PythonAPI/scripts/config_manager.py @@ -0,0 +1,272 @@ +import json +import os +from pathlib import Path +from typing import Any, Dict, List, Optional, Tuple + +import numpy as np +from HapticSharedControl.path_planning import calculate_bezier_trajectory +from HapticSharedControl.utils import Vehicle, process_exist_path + + +class ConfigManager: + """Manages configuration and path data for the DReyeVR Haptic Control system""" + + def __init__(self, config_path: Optional[str] = None, paths_path: Optional[str] = None): + """ + Initialize the configuration manager + + Args: + config_path: Path to the config JSON file + paths_path: Path to the paths JSON file + """ + self.base_dir = Path(__file__).resolve().parent + + # Set default paths if not provided + config_path = config_path or str(self.base_dir / "HapticSharedControl" / "config.json") + paths_path = paths_path or str(self.base_dir / "HapticSharedControl" / "paths.json") + + # Load configurations + self.config = self._load_json(config_path) + self.paths_config = self._load_json(paths_path) + + # Load vehicle config + self.vehicle_config = self._load_json( + str(self.base_dir / "HapticSharedControl" / "wheel_setting.json") + ) + self.vehicle = Vehicle(vehicle_config=self.vehicle_config) + + # Process paths to create usable trajectory data + self.predefined_path = self._process_paths() + + def _load_json(self, file_path: str) -> Dict[str, Any]: + """ + Load JSON configuration from file + + Args: + file_path: Path to JSON file + + Returns: + Dictionary containing configuration data + """ + try: + with open(file_path, "r") as f: + return json.load(f) + except Exception as e: + print(f"Error loading config from {file_path}: {e}") + return {} + + def _load_path_data(self, file_path: str) -> np.ndarray: + """ + Load path data from text file + + Args: + file_path: Path to the text file containing path data + + Returns: + NumPy array of path coordinates + """ + try: + path = Path(file_path) + # Resolve relative paths + if not path.is_absolute(): + path = self.base_dir / path + + with open(path, "r") as f: + data = f.readlines() + data = [line.strip().split(",") for line in data] + data = [[float(val) for val in line] for line in data] + return np.array(data) + except Exception as e: + print(f"Error loading path data from {file_path}: {e}") + return np.array([]) + + def _extract_path_range(self, + data: np.ndarray, + range_spec: List[int]) -> np.ndarray: + """ + Extract a range of points from path data + + Args: + data: Array of path data + range_spec: [start_idx, end_idx] where end_idx can be -1 for end + + Returns: + Subset of path data + """ + start, end = range_spec + if end == -1 or end is None: + return data[start:] + return data[start:end] + + def _process_paths(self) -> Dict[str, Dict[str, Any]]: + """ + Process all paths from configuration + + Returns: + Dictionary of processed path data + """ + processed_paths = {} + + for path_idx, path_config in self.paths_config.items(): + processed_path = { + "P_0": path_config.get("P_0", []), + "P_d": path_config.get("P_d", []), + "P_f": path_config.get("P_f", []), + "yaw_0": path_config.get("yaw_0"), + "yaw_d": path_config.get("yaw_d"), + "yaw_f": path_config.get("yaw_f"), + "forward paths": None, + "backward paths": None, + } + + # Process forward path if specified + if "forward_path_file" in path_config: + data = self._load_path_data(path_config["forward_path_file"]) + if len(data) > 0 and "forward_path_range" in path_config: + range_data = self._extract_path_range(data, path_config["forward_path_range"]) + processed_path["forward paths"] = process_exist_path(range_data) + + # Process backward path if specified + if "backward_path_file" in path_config: + data = self._load_path_data(path_config["backward_path_file"]) + if len(data) > 0 and "backward_path_range" in path_config: + range_data = self._extract_path_range(data, path_config["backward_path_range"]) + processed_path["backward paths"] = process_exist_path(range_data) + + # Generate Bezier curve if specified + if path_config.get("use_bezier", False): + self._generate_bezier_curves(processed_path) + + processed_paths[path_idx] = processed_path + + return processed_paths + + def _generate_bezier_curves(self, path_data: Dict[str, Any]) -> None: + """ + Generate Bezier curves for a path + + Args: + path_data: Path data dictionary to be updated with Bezier curves + """ + n_points = 60 + min_radius = self.vehicle.minimum_turning_radius + + # Check for required points + if (not path_data["P_0"] or not path_data["P_d"] or + path_data["yaw_0"] is None or path_data["yaw_d"] is None): + return + + # Generate forward path + _, _, param_fw = calculate_bezier_trajectory( + start_pos=path_data["P_0"][::-1], + end_pos=path_data["P_d"][::-1], + start_yaw=path_data["yaw_0"], + end_yaw=path_data["yaw_d"], + n_points=n_points, + turning_radius=min_radius, + show_animation=False, + ) + + # Generate backward path + _, _, param_bw = calculate_bezier_trajectory( + start_pos=path_data["P_d"][::-1], + end_pos=path_data["P_f"][::-1], + start_yaw=path_data["yaw_d"] + 180, # reverse yaw angle + end_yaw=path_data["yaw_f"] + 180, # reverse yaw angle + n_points=n_points, + turning_radius=min_radius, + show_animation=False, + ) + + path_data["forward paths"] = param_fw + path_data["backward paths"] = param_bw + + def get_config(self, key: str, default: Any = None) -> Any: + """ + Get a value from the main configuration + + Args: + key: Configuration key (can use dot notation for nested keys) + default: Default value if key not found + + Returns: + Configuration value + """ + if "." in key: + parts = key.split(".") + config = self.config + for part in parts: + if part in config: + config = config[part] + else: + return default + return config + return self.config.get(key, default) + + def get_path(self, path_idx: str) -> Dict[str, Any]: + """ + Get processed path data by index + + Args: + path_idx: Path index + + Returns: + Processed path data dictionary + """ + return self.predefined_path.get(path_idx, {}) + + def get_default_path_idx(self) -> str: + """ + Get the default path index from configuration + + Returns: + Default path index + """ + return self.get_config("default_path_idx", "3") + + def get_vehicle(self) -> Vehicle: + """ + Get the vehicle instance + + Returns: + Vehicle instance + """ + return self.vehicle + + def get_force_feedback_settings(self) -> Tuple[int, int]: + """ + Get force feedback settings + + Returns: + Tuple of (saturation_percentage, coefficient_percentage) + """ + saturation = self.get_config("force_feedback.saturation_percentage", 100) + coefficient = self.get_config("force_feedback.coefficient_percentage", 30) + return saturation, coefficient + + def get_haptic_control_settings(self) -> Dict[str, float]: + """ + Get haptic control settings + + Returns: + Dictionary of haptic control parameters + """ + return { + "Cs": self.get_config("haptic_control.Cs", 0.5), + "Kc": self.get_config("haptic_control.Kc", 0.5), + "tp": self.get_config("haptic_control.tp", 12.0) + } + + def get_logging_dir(self) -> Path: + """ + Get logging directory + + Returns: + Path object for logging directory + """ + log_dir = self.get_config("logging.log_dir", "./logs") + path = Path(log_dir) + if not path.is_absolute(): + path = self.base_dir / path + os.makedirs(path, exist_ok=True) + return path \ No newline at end of file diff --git a/PythonAPI/scripts/generate_traffic.py b/PythonAPI/scripts/generate_traffic.py new file mode 100644 index 0000000..17703f8 --- /dev/null +++ b/PythonAPI/scripts/generate_traffic.py @@ -0,0 +1,382 @@ +# !/usr/bin/env python + +# Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma de +# Barcelona (UAB). +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +"""Example script to generate traffic in the simulation""" + +import glob +import os +import sys +import time + +try: + sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % ( + sys.version_info.major, + sys.version_info.minor, + 'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0]) +except IndexError: + pass + +import argparse +import logging + +from numpy import random + +import carla + + +def get_actor_blueprints(world, filter, generation): + bps = world.get_blueprint_library().filter(filter) + + if generation.lower() == "all": + return bps + + # If the filter returns only one bp, we assume that this one needed + # and therefore, we ignore the generation + if len(bps) == 1: + return bps + + try: + int_generation = int(generation) + # Check if generation is in available generations + if int_generation in [1, 2]: + bps = [x for x in bps if int(x.get_attribute('generation')) == int_generation] + return bps + else: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + except: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + +def main(): + argparser = argparse.ArgumentParser( + description=__doc__) + argparser.add_argument( + '--host', + metavar='H', + default='127.0.0.1', + help='IP of the host server (default: 127.0.0.1)') + argparser.add_argument( + '-p', '--port', + metavar='P', + default=2000, + type=int, + help='TCP port to listen to (default: 2000)') + argparser.add_argument( + '-n', '--number-of-vehicles', + metavar='N', + default=50, + type=int, + help='Number of vehicles (default: 30)') + argparser.add_argument( + '-w', '--number-of-walkers', + metavar='W', + default=20, + type=int, + help='Number of walkers (default: 10)') + argparser.add_argument( + '--safe', + action='store_true', + help='Avoid spawning vehicles prone to accidents') + argparser.add_argument( + '--filterv', + metavar='PATTERN', + default='vehicle.*', + help='Filter vehicle model (default: "vehicle.*")') + argparser.add_argument( + '--generationv', + metavar='G', + default='All', + help='restrict to certain vehicle generation (values: "1","2","All" - default: "All")') + argparser.add_argument( + '--filterw', + metavar='PATTERN', + default='walker.pedestrian.*', + help='Filter pedestrian type (default: "walker.pedestrian.*")') + argparser.add_argument( + '--generationw', + metavar='G', + default='2', + help='restrict to certain pedestrian generation (values: "1","2","All" - default: "2")') + argparser.add_argument( + '--tm-port', + metavar='P', + default=8000, + type=int, + help='Port to communicate with TM (default: 8000)') + argparser.add_argument( + '--asynch', + action='store_true', + help='Activate asynchronous mode execution') + argparser.add_argument( + '--hybrid', + action='store_true', + help='Activate hybrid mode for Traffic Manager') + argparser.add_argument( + '-s', '--seed', + metavar='S', + type=int, + help='Set random device seed and deterministic mode for Traffic Manager') + argparser.add_argument( + '--seedw', + metavar='S', + default=0, + type=int, + help='Set the seed for pedestrians module') + argparser.add_argument( + '--car-lights-on', + action='store_true', + default=False, + help='Enable automatic car light management') + argparser.add_argument( + '--hero', + action='store_true', + default=False, + help='Set one of the vehicles as hero') + argparser.add_argument( + '--respawn', + action='store_true', + default=False, + help='Automatically respawn dormant vehicles (only in large maps)') + argparser.add_argument( + '--no-rendering', + action='store_true', + default=False, + help='Activate no rendering mode') + + args = argparser.parse_args() + + logging.basicConfig(format='%(levelname)s: %(message)s', level=logging.INFO) + + vehicles_list = [] + walkers_list = [] + all_id = [] + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) + synchronous_master = False + random.seed(args.seed if args.seed is not None else int(time.time())) + + try: + world = client.get_world() + + traffic_manager = client.get_trafficmanager(args.tm_port) + traffic_manager.set_global_distance_to_leading_vehicle(2.5) + if args.respawn: + traffic_manager.set_respawn_dormant_vehicles(True) + if args.hybrid: + traffic_manager.set_hybrid_physics_mode(True) + traffic_manager.set_hybrid_physics_radius(70.0) + if args.seed is not None: + traffic_manager.set_random_device_seed(args.seed) + + settings = world.get_settings() + if not args.asynch: + traffic_manager.set_synchronous_mode(True) + if not settings.synchronous_mode: + synchronous_master = True + settings.synchronous_mode = True + settings.fixed_delta_seconds = 0.05 + else: + synchronous_master = False + else: + print("You are currently in asynchronous mode. If this is a traffic simulation, \ + you could experience some issues. If it's not working correctly, switch to synchronous \ + mode by using traffic_manager.set_synchronous_mode(True)") + + if args.no_rendering: + settings.no_rendering_mode = True + world.apply_settings(settings) + + blueprints = get_actor_blueprints(world, args.filterv, args.generationv) + blueprintsWalkers = get_actor_blueprints(world, args.filterw, args.generationw) + + if args.safe: + blueprints = [x for x in blueprints if int(x.get_attribute('number_of_wheels')) == 4] + blueprints = [x for x in blueprints if not x.id.endswith('microlino')] + blueprints = [x for x in blueprints if not x.id.endswith('carlacola')] + blueprints = [x for x in blueprints if not x.id.endswith('cybertruck')] + blueprints = [x for x in blueprints if not x.id.endswith('t2')] + blueprints = [x for x in blueprints if not x.id.endswith('sprinter')] + blueprints = [x for x in blueprints if not x.id.endswith('firetruck')] + blueprints = [x for x in blueprints if not x.id.endswith('ambulance')] + + blueprints = sorted(blueprints, key=lambda bp: bp.id) + + spawn_points = world.get_map().get_spawn_points() + number_of_spawn_points = len(spawn_points) + + if args.number_of_vehicles < number_of_spawn_points: + random.shuffle(spawn_points) + elif args.number_of_vehicles > number_of_spawn_points: + msg = 'requested %d vehicles, but could only find %d spawn points' + logging.warning(msg, args.number_of_vehicles, number_of_spawn_points) + args.number_of_vehicles = number_of_spawn_points + + # @todo cannot import these directly. + SpawnActor = carla.command.SpawnActor + SetAutopilot = carla.command.SetAutopilot + FutureActor = carla.command.FutureActor + + # -------------- + # Spawn vehicles + # -------------- + batch = [] + hero = args.hero + for n, transform in enumerate(spawn_points): + if n >= args.number_of_vehicles: + break + blueprint = random.choice(blueprints) + if blueprint.has_attribute('color'): + color = random.choice(blueprint.get_attribute('color').recommended_values) + blueprint.set_attribute('color', color) + if blueprint.has_attribute('driver_id'): + driver_id = random.choice(blueprint.get_attribute('driver_id').recommended_values) + blueprint.set_attribute('driver_id', driver_id) + if hero: + blueprint.set_attribute('role_name', 'hero') + hero = False + else: + blueprint.set_attribute('role_name', 'autopilot') + + # spawn the cars and set their autopilot and light state all together + batch.append(SpawnActor(blueprint, transform) + .then(SetAutopilot(FutureActor, True, traffic_manager.get_port()))) + + for response in client.apply_batch_sync(batch, synchronous_master): + if response.error: + logging.error(response.error) + else: + vehicles_list.append(response.actor_id) + + # Set automatic vehicle lights update if specified + if args.car_lights_on: + all_vehicle_actors = world.get_actors(vehicles_list) + for actor in all_vehicle_actors: + traffic_manager.update_vehicle_lights(actor, True) + + # ------------- + # Spawn Walkers + # ------------- + # some settings + percentagePedestriansRunning = 0.0 # how many pedestrians will run + percentagePedestriansCrossing = 0.0 # how many pedestrians will walk through the road + if args.seedw: + world.set_pedestrians_seed(args.seedw) + random.seed(args.seedw) + # 1. take all the random locations to spawn + spawn_points = [] + for i in range(args.number_of_walkers): + spawn_point = carla.Transform() + loc = world.get_random_location_from_navigation() + if (loc != None): + spawn_point.location = loc + spawn_points.append(spawn_point) + # 2. we spawn the walker object + batch = [] + walker_speed = [] + for spawn_point in spawn_points: + walker_bp = random.choice(blueprintsWalkers) + # set as not invincible + if walker_bp.has_attribute('is_invincible'): + walker_bp.set_attribute('is_invincible', 'false') + # set the max speed + if walker_bp.has_attribute('speed'): + if (random.random() > percentagePedestriansRunning): + # walking + walker_speed.append(walker_bp.get_attribute('speed').recommended_values[1]) + else: + # running + walker_speed.append(walker_bp.get_attribute('speed').recommended_values[2]) + else: + print("Walker has no speed") + walker_speed.append(0.0) + batch.append(SpawnActor(walker_bp, spawn_point)) + results = client.apply_batch_sync(batch, True) + walker_speed2 = [] + for i in range(len(results)): + if results[i].error: + logging.error(results[i].error) + else: + walkers_list.append({"id": results[i].actor_id}) + walker_speed2.append(walker_speed[i]) + walker_speed = walker_speed2 + # 3. we spawn the walker controller + batch = [] + walker_controller_bp = world.get_blueprint_library().find('controller.ai.walker') + for i in range(len(walkers_list)): + batch.append(SpawnActor(walker_controller_bp, carla.Transform(), walkers_list[i]["id"])) + results = client.apply_batch_sync(batch, True) + for i in range(len(results)): + if results[i].error: + logging.error(results[i].error) + else: + walkers_list[i]["con"] = results[i].actor_id + # 4. we put together the walkers and controllers id to get the objects from their id + for i in range(len(walkers_list)): + all_id.append(walkers_list[i]["con"]) + all_id.append(walkers_list[i]["id"]) + all_actors = world.get_actors(all_id) + + # wait for a tick to ensure client receives the last transform of the walkers we have just created + if args.asynch or not synchronous_master: + world.wait_for_tick() + else: + world.tick() + + # 5. initialize each controller and set target to walk to (list is [controler, actor, controller, actor ...]) + # set how many pedestrians can cross the road + world.set_pedestrians_cross_factor(percentagePedestriansCrossing) + for i in range(0, len(all_id), 2): + # start walker + all_actors[i].start() + # set walk to random point + all_actors[i].go_to_location(world.get_random_location_from_navigation()) + # max speed + all_actors[i].set_max_speed(float(walker_speed[int(i/2)])) + + print('spawned %d vehicles and %d walkers, press Ctrl+C to exit.' % (len(vehicles_list), len(walkers_list))) + + # Example of how to use Traffic Manager parameters + traffic_manager.global_percentage_speed_difference(30.0) + + while True: + if not args.asynch and synchronous_master: + world.tick() + else: + world.wait_for_tick() + + finally: + + if not args.asynch and synchronous_master: + settings = world.get_settings() + settings.synchronous_mode = False + settings.no_rendering_mode = False + settings.fixed_delta_seconds = None + world.apply_settings(settings) + + print('\ndestroying %d vehicles' % len(vehicles_list)) + client.apply_batch([carla.command.DestroyActor(x) for x in vehicles_list]) + + # stop walker controllers (list is [controller, actor, controller, actor ...]) + for i in range(0, len(all_id), 2): + all_actors[i].stop() + + print('\ndestroying %d walkers' % len(walkers_list)) + client.apply_batch([carla.command.DestroyActor(x) for x in all_id]) + + time.sleep(0.5) + +if __name__ == '__main__': + + try: + main() + + except KeyboardInterrupt: + pass + finally: + print('\ndone.') diff --git a/PythonAPI/scripts/simulation_haptic_algo.py b/PythonAPI/scripts/simulation_haptic_algo.py new file mode 100644 index 0000000..31529f6 --- /dev/null +++ b/PythonAPI/scripts/simulation_haptic_algo.py @@ -0,0 +1,283 @@ +import json +import os +import sys +from pathlib import Path +from turtle import speed + +import matplotlib.pyplot as plt +import numpy as np +import pandas as pd + +# sys.path.append(os.path.join(os.getenv("DReyeVR"), "PythonAPI")) +from HapticSharedControl.haptic_algo import * +from HapticSharedControl.path_planning import * +from HapticSharedControl.simulation import * +from HapticSharedControl.utils import * + +plt.style.use("default") + + +__file_path__ = Path(__file__).resolve().parent + +# Load the vehicle configuration +with open(f"{__file_path__}/HapticSharedControl/wheel_setting.json", "r") as f: + vehicle_config = json.load(f) +vehicle = Vehicle(vehicle_config=vehicle_config) +R = vehicle.minimum_turning_radius +print("Minimum Turning Radius:", R, "m") + +# define initial and final points +trial = str(input("Enter trial number 0(sample) L-R(1-6) R-L(8-12): ")) +recorded_path = None +if trial == "0": + P_0 = [-1.47066772, -13.22415039] # [x, y] in carla -> [y, x] in matplotlib + P_d = [-0.37066772, -29.02415039] + P_f = [-6.87066772, -21.62415039] + yaw_0 = -90 + yaw_d = -100 + yaw_f = 180 +elif trial == "1": + P_0 = [-2.13139057, -13.58492756] + P_d = [-0.26648349, -27.88323593] + P_f = [-8.6554842, -21.6907711] + yaw_0 = - 2.3220824999999934 - 90 + yaw_d = - 29.3604774 - 90 + yaw_f = 105.7937202 + 90 +elif trial == "2": + P_0 = [-2.0546906, -15.14080429] + P_d = [-0.16853675, -27.82400513] + P_f = [-7.68998575, -21.31655693] + yaw_0 = -1.9093017999999944 - 90 + yaw_d = 30.0815544 - 90 + yaw_f = 93.37516379 + 90 +elif trial == "3": + P_0 = [-2.33013225, -13.42747879] + P_d = [-0.27527067, -27.43535042] + P_f = [-7.19522429, -21.22905159] + yaw_0 = -1.153442400000003 -90 + yaw_d = - 29.3213272 - 90 + yaw_f = 90.37275675 + 90 +elif trial == "4": + P_0 = [-2.59471703, -13.76090431] + P_d = [-0.84754181, -27.41300201] + P_f = [-7.63892126, -21.31984329] + yaw_0 = - 1.9469986000000006 - 90 + yaw_d = - 25.734725999999995 - 90 + yaw_f = 90.29345572 + 90 +elif trial == "5": + P_0 = [-2.46604896, -12.84768295] + P_d = [-0.76953948, -27.44445229] + P_f = [-7.99046612, -21.05567169] + yaw_0 = - 3.3721313000000066 - 90 + yaw_d = - 20.9653397 - 90 + yaw_f = 85.99301052 + 90 +elif trial == "6": + P_0 = [-2.68211842, -13.66109943] + P_d = [-0.15471956, -27.84520721] + P_f = [-7.58486843, -21.00892448] + yaw_0 = - 1.5638045999999974 - 90 + yaw_d = - 31.523597700000003 - 90 + yaw_f = 85.90444851 + 90 +# reverse direction +elif trial == "8": + P_0 = [-2.21546435, -31.60477066] + P_d = [1.03518212, -18.32664871] + P_f = [-7.7015214, -21.18217278] + yaw_0 = 90 - (178.7055664 - 180) + yaw_d = 90 - (124.3087578 - 180) + yaw_f = 88.27893066 + 90 +elif trial == "9": + P_0 = [-1.3271035, -34.64346695] + P_d = [1.54469788, -19.11241913] + P_f = [-7.67417145, -21.5524559] + yaw_0 = 182.4389496 - 90 + yaw_d = 125.65747833 - 90 + yaw_f = 88.90112317 + 90 +elif trial == "10": + P_0 = [-2.41052723, -31.86808777] + P_d = [2.61411977, -16.33299065] + P_f = [-7.40135479, -21.47801208] + yaw_0 = 174.07925419999998 - 90 + yaw_d = 125.3021584 - 90 + yaw_f = 87.58251953 + 90 +elif trial == "11": + P_0 = [-1.99927211, -29.94470215] + P_d = [2.38471651, -17.51079941] + P_f = [-7.10684538, -21.3453064] + yaw_0 = 181.86206049999998 - 90 + yaw_d = 121.4338913 - 90 + yaw_f = 88.89004517 + 90 +elif trial == "12": + P_0 = [-3.46834612, -30.75714493] + P_d = [-0.9832288, -17.28814125] + P_f = [-7.75748634, -21.73072243] + yaw_0 = 177.7886658 - 90 + yaw_d = 147.1214333 - 90 + yaw_f = 89.86245729 + 90 +else: + print("Invalid trial number") + exit() + +if trial != "0": + df = pd.read_excel(f"{__file_path__.parent}/data/trials/trial{trial}.xlsx") + x = df["LocationX"].to_list() + y = df["LocationY"].to_list() + yaw = df["RotationYaw"].to_list() + recorded_path = np.array([y, x]) +else: + recorded_path = None + +# Simulation Parameters +# calculate the bezier path + +n_points = 50 + +n_steps = None +speed = 1.0 # m/s +init_steering_angle = 10 # abs value + +if (P_0 != [] and yaw_0 is not None) and (P_d != [] and yaw_d is not None): + path1, control_points1, params1 = calculate_bezier_trajectory( + start_pos=P_0, + end_pos=P_d, + start_yaw=yaw_0, + end_yaw=yaw_d, + n_points=n_points, + turning_radius=R, + show_animation=False, + ) + # Run the simulation + path1, trajectory1, yaw_angles_deg1 = simulation( + path=path1, + param=params1, + i_points=P_0, + f_points=P_d, + i_yaw=-(180 + yaw_0), + speed=1 * speed, + init_steering_angle=1 * init_steering_angle, + vehicle_config=vehicle_config, + n_steps=n_steps, + ) +else: + path1 = None + trajectory1 = None + yaw_angles_deg1 = None + +print("=====================================") + +if (P_d != [] and yaw_d is not None) and (P_f != [] and yaw_f is not None): + # backward so reverse the yaw angle (+180) + path2, control_points2, params2 = calculate_bezier_trajectory( + start_pos=P_d, + end_pos=P_f, + start_yaw=180 + yaw_d, + end_yaw=180 + yaw_f, + n_points=n_points, + turning_radius=R, + show_animation=False, + ) + + # Run the simulation + path2, trajectory2, yaw_angles_deg2 = simulation( + path=path2, + param=params2, + i_points=P_d, + f_points=P_f, + i_yaw=-(yaw_d + 180), # rotate and flip + speed=-1 * speed, + init_steering_angle=-1 * init_steering_angle, + vehicle_config=vehicle_config, + n_steps=n_steps, + ) +else: + path2 = None + trajectory2 = None + yaw_angles_deg2 = None + +# # Plot the trajectories +plot_trajectory( + paths=[path1, path2], + trajectories=[trajectory1, trajectory2], + yaw_angles_deg=[yaw_angles_deg1, yaw_angles_deg2], + recorded_path=recorded_path, +) +# +with open("../data/paths/driving_path_left2right.txt", "r") as f: + data_left2right = f.readlines() + data_left2right = [line.strip().split(",") for line in data_left2right] + data_left2right = [[float(val) for val in line[::-1]] for line in data_left2right] + data_left2right = np.array(data_left2right) + +with open("../data/paths/driving_path_right2left.txt", "r") as f: + data_right2left = f.readlines() + data_right2left = [line.strip().split(",") for line in data_right2left] + data_right2left = [[float(val) for val in line[::-1]] for line in data_right2left] + data_right2left = np.array(data_right2left) + +with open("../data/paths/hitachi.txt", "r") as f: + data_hitachi = f.readlines() + data_hitachi = [line.strip().split(",") for line in data_hitachi] + data_hitachi = [[float(val) for val in line[::-1]] for line in data_hitachi] + data_hitachi = np.array(data_hitachi) + + +predefined_path = { + "0": { + "P_0": [-1.47066772, -13.22415039], + "P_d": [-0.37066772, -29.02415039], + "P_f": [-6.87066772, -21.62415039], + "yaw_0": 90 - (-90), + "yaw_d": 90 - (-80), + "yaw_f": 90 - 0, + "forward paths": None, + "backward paths": None, + }, + "1": { + "P_0": [-2.376371583333333, -13.749357381666668], + "P_d": [-0.566469992644628, -27.297582133636364], + "P_f": [-7.7486732, -21.271947543333333], + "yaw_0": 90 - (88.97628786666667), + "yaw_d": 90 - (62.168829599999995), + "yaw_f": 90 - (-1.9554259149999922), + "forward paths": process_exist_path(data_left2right[:40]), + "backward paths": process_exist_path(data_left2right[40:]), + }, + "2": { + "P_0": [-2.284308814, -31.734065629999996], + "P_d": [0.409550333177305, -18.459612079588652], + "P_f": [-7.449310874, -21.459648512], + "yaw_0": 90 - (-88.9748993), + "yaw_d": 90 - (-38.76474382600003), + "yaw_f": 90 - (1.296984835999993), + "forward paths": process_exist_path(data_right2left[:46]), + "backward paths": process_exist_path(data_right2left[46:]), + }, + "3": { + "P_0": [], + "P_d": [1.035116, -18.325821], + "P_f": [-7.685114, -21.214608], + "yaw_0": None, + "yaw_d": 90 - (-50), + "yaw_f": 90 - (0), + "forward paths": [], + "backward paths": process_exist_path(data_hitachi), + }, +} +# idx = "1" +# path, trajectory, yaw_angles_deg = simulation( +# path=predefined_path[idx]["backward paths"]["path"], +# param=predefined_path[idx]["backward paths"], +# i_points=predefined_path[idx]["P_d"][::-1], +# f_points=predefined_path[idx]["P_f"][::-1], +# i_yaw=180 - predefined_path[idx]["yaw_d"], +# speed=-1 * speed, +# init_steering_angle=-1 * init_steering_angle, +# vehicle_config=vehicle_config, +# n_steps=n_steps, +# ) +# plot_trajectory( +# paths=[path], +# trajectories=[trajectory], +# yaw_angles_deg=[yaw_angles_deg], +# recorded_path=None, +# ) diff --git a/PythonAPI/scripts/start_recording.py b/PythonAPI/scripts/start_recording.py new file mode 100644 index 0000000..86efc7f --- /dev/null +++ b/PythonAPI/scripts/start_recording.py @@ -0,0 +1,158 @@ +#!/usr/bin/env python + +# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de +# Barcelona (UAB). +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import glob +import os +import sys + +try: + sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % ( + sys.version_info.major, + sys.version_info.minor, + 'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0]) +except IndexError: + pass + +import carla + +import argparse +import random +import time +import logging + + +def main(): + argparser = argparse.ArgumentParser( + description=__doc__) + argparser.add_argument( + '--host', + metavar='H', + default='127.0.0.1', + help='IP of the host server (default: 127.0.0.1)') + argparser.add_argument( + '-p', '--port', + metavar='P', + default=2000, + type=int, + help='TCP port to listen to (default: 2000)') + argparser.add_argument( + '-n', '--number-of-vehicles', + metavar='N', + default=10, + type=int, + help='number of vehicles (default: 10)') + argparser.add_argument( + '-d', '--delay', + metavar='D', + default=2.0, + type=float, + help='delay in seconds between spawns (default: 2.0)') + argparser.add_argument( + '--safe', + action='store_true', + help='avoid spawning vehicles prone to accidents') + argparser.add_argument( + '-f', '--recorder_filename', + metavar='F', + default="test1.log", + help='recorder filename (test1.log)') + argparser.add_argument( + '-t', '--recorder_time', + metavar='T', + default=0, + type=int, + help='recorder duration (auto-stop)') + args = argparser.parse_args() + + actor_list = [] + logging.basicConfig(format='%(levelname)s: %(message)s', level=logging.INFO) + + try: + + client = carla.Client(args.host, args.port) + client.set_timeout(2.0) + world = client.get_world() + blueprints = world.get_blueprint_library().filter('vehicle.*') + + spawn_points = world.get_map().get_spawn_points() + random.shuffle(spawn_points) + + print('found %d spawn points.' % len(spawn_points)) + + count = args.number_of_vehicles + + print("Recording on file: %s" % client.start_recorder(args.recorder_filename)) + + if args.safe: + blueprints = [x for x in blueprints if int(x.get_attribute('number_of_wheels')) == 4] + blueprints = [x for x in blueprints if not x.id.endswith('microlino')] + blueprints = [x for x in blueprints if not x.id.endswith('carlacola')] + blueprints = [x for x in blueprints if not x.id.endswith('cybertruck')] + blueprints = [x for x in blueprints if not x.id.endswith('t2')] + blueprints = [x for x in blueprints if not x.id.endswith('sprinter')] + blueprints = [x for x in blueprints if not x.id.endswith('firetruck')] + blueprints = [x for x in blueprints if not x.id.endswith('ambulance')] + + spawn_points = world.get_map().get_spawn_points() + number_of_spawn_points = len(spawn_points) + + if count < number_of_spawn_points: + random.shuffle(spawn_points) + elif count > number_of_spawn_points: + msg = 'requested %d vehicles, but could only find %d spawn points' + logging.warning(msg, count, number_of_spawn_points) + count = number_of_spawn_points + + # @todo cannot import these directly. + SpawnActor = carla.command.SpawnActor + SetAutopilot = carla.command.SetAutopilot + FutureActor = carla.command.FutureActor + + batch = [] + for n, transform in enumerate(spawn_points): + if n >= count: + break + blueprint = random.choice(blueprints) + assert blueprint is not None + if blueprint.has_attribute('color'): + color = random.choice(blueprint.get_attribute('color').recommended_values) + blueprint.set_attribute('color', color) + blueprint.set_attribute('role_name', 'autopilot') + batch.append(SpawnActor(blueprint, transform).then(SetAutopilot(FutureActor, True))) + + for response in client.apply_batch_sync(batch): + if response.error: + logging.error(response.error) + else: + actor_list.append(response.actor_id) + + print('spawned %d vehicles, press Ctrl+C to exit.' % len(actor_list)) + + if (args.recorder_time > 0): + time.sleep(args.recorder_time) + else: + while True: + world.wait_for_tick() + + finally: + + print('\ndestroying %d actors' % len(actor_list)) + client.apply_batch_sync([carla.command.DestroyActor(x) for x in actor_list]) + + print("Stop recording") + client.stop_recorder() + + +if __name__ == '__main__': + + try: + main() + except KeyboardInterrupt: + pass + finally: + print('\ndone.') \ No newline at end of file diff --git a/PythonAPI/scripts/walker_spawn_config.json b/PythonAPI/scripts/walker_spawn_config.json new file mode 100644 index 0000000..bc10480 --- /dev/null +++ b/PythonAPI/scripts/walker_spawn_config.json @@ -0,0 +1,73 @@ +{ + "simulation": { + "sync_mode": false, + "delta_t": 0.05, + "update_frequency": 20.0 + }, + "trigger_area": { + "center": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + "radius": 50.0, + "description": "Circular area that triggers walker spawning when vehicle enters" + }, + "walker_spawn": { + "number_of_walkers": 2, + "spawn_positions": [ + { + "x": 1.0, + "y": 1.0, + "z": 0.3 + }, + { + "x": 5.0, + "y": 5.0, + "z": 0.3 + } + + ], + "target_positions": [ + { + "x": 10.0, + "y": 10.0, + "z": 0.3 + }, + { + "x": 15.0, + "y": 15.0, + "z": 0.3 + } + ], + "walker_movement": { + "type": "target_based", + "movement_radius": 5.0, + "change_direction_interval": 5.0, + "use_navigation_mesh": true, + "_comments": { + "type": "Movement type: 'target_based' for walking to fixed targets, 'random_walk' for 5m radius movement", + "movement_radius": "Maximum distance in meters walkers will move from their spawn position (for random_walk)", + "change_direction_interval": "How often (in seconds) walkers get new random destinations (for random_walk)", + "use_navigation_mesh": "Whether to use CARLA's navigation mesh for more realistic pathfinding" + } + }, + "walker_speed": { + "min": 0.5, + "max": 2.5, + "default": 1.5 + }, + "walker_filter": "walker.pedestrian.*", + "generation": "2", + "is_invincible": false + }, + "vehicle_tracking": { + "role_name": "hero", + "check_interval": 0.1, + "spawn_once_per_entry": true + }, + "logging": { + "enable_debug": true, + "log_file": "walker_spawn_log.txt" + } +} diff --git a/PythonAPI/scripts/workspace.ipynb b/PythonAPI/scripts/workspace.ipynb new file mode 100644 index 0000000..af28123 --- /dev/null +++ b/PythonAPI/scripts/workspace.ipynb @@ -0,0 +1,4851 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Relation between params" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "\n", + "def compute_tangents(points):\n", + " tangents = []\n", + " n = len(points)\n", + "\n", + " for i in range(n):\n", + " if i == 0:\n", + " dx, dy = points[i + 1][0] - points[i][0], points[i + 1][1] - points[i][1]\n", + " elif i == n - 1:\n", + " dx, dy = points[i][0] - points[i - 1][0], points[i][1] - points[i - 1][1]\n", + " else:\n", + " dx, dy = points[i + 1][0] - points[i - 1][0], points[i + 1][1] - points[i - 1][1]\n", + "\n", + " scale = 1\n", + " p1 = (points[i][0] - scale * dx, points[i][1] - scale * dy)\n", + " p2 = (points[i][0] + scale * dx, points[i][1] + scale * dy)\n", + "\n", + " tangents.append((p1, p2))\n", + "\n", + " return tangents\n", + "\n", + "def process_exist_path(path):\n", + " \"\"\"\n", + " Process an existing path consisting of a series of points and compute\n", + " tangent vectors at each point along the path.\n", + "\n", + " Args:\n", + " path: A list or numpy array of [x,y] coordinates that form a path\n", + "\n", + " Returns:\n", + " param: Dictionary containing the original path and computed tangent vectors\n", + " \"\"\"\n", + " path = np.array(path)\n", + " param = {\n", + " \"path\": path,\n", + " \"start_x\": path[0][0],\n", + " \"start_y\": path[0][1],\n", + " \"end_x\": path[-1][0],\n", + " \"end_y\": path[-1][1],\n", + " \"tangent\": compute_tangents(path),\n", + " }\n", + "\n", + " return param\n", + "\n", + "with open(\"../data/paths/driving_path_left2right.txt\", \"r\") as f:\n", + " data_left2right = f.readlines()\n", + " data_left2right = [line.strip().split(\",\") for line in data_left2right]\n", + " data_left2right = [[float(val) for val in line] for line in data_left2right]\n", + " data_left2right = np.array(data_left2right)\n", + " \n", + "with open(\"../data/paths/hitachi.txt\", \"r\") as f:\n", + " data_hitachi = f.readlines()\n", + " data_hitachi = [line.strip().split(\",\") for line in data_hitachi]\n", + " data_hitachi = [[float(val) for val in line] for line in data_hitachi]\n", + " data_hitachi = np.array(data_hitachi)\n", + "\n", + "\n", + "\n", + "predefined_path = {\n", + " \"1\": {\n", + " \"P_0\": [-2.376371583333333, -13.749357381666668],\n", + " \"P_d\": [-0.566469992644628, -27.297582133636364],\n", + " \"P_f\": [-7.7486732, -21.271947543333333],\n", + " \"yaw_0\": 90 - (-88.97628786666667),\n", + " \"yaw_d\": 90 - (-62.168829599999995),\n", + " \"yaw_f\": 90 - (-1.9554259149999922),\n", + " \"forward paths\": process_exist_path(data_left2right[:40]),\n", + " \"backward paths\": process_exist_path(data_left2right[40:]),\n", + " },\n", + " \"2\": {\n", + " \"P_0\": [],\n", + " \"P_d\": [1.035116, -18.325821],\n", + " \"P_f\": [-7.685114, -21.214608],\n", + " \"yaw_0\": None,\n", + " \"yaw_d\": 90 - (50),\n", + " \"yaw_f\": 90 - (0),\n", + " \"forward paths\": [],\n", + " \"backward paths\": process_exist_path(data_hitachi),\n", + " },\n", + "}\n", + "# predefined_path[\"1\"][\"forward paths\"]" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Haptic shared control" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.microsoft.datawrangler.viewer.v0+json": { + "columns": [ + { + "name": "index", + "rawType": "int64", + "type": "integer" + }, + { + "name": "Time (t)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Carla] Throttle", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Input] Throttle", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Carla] Steering Input", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Input] Steering Input", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Current Position ~ X(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Current Position ~ Y(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Current Yaw Angle ~ Phi(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Speed ~ V(t) (m/s)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] VelocityX ~ Vx(t) (m/s)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] VelocityY ~ Vy(t) (m/s)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] AccelerationX ~ Ax(t) (m/s^2)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] AccelerationY ~ Ay(t) (m/s^2)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Angular VelocityZ ~ Phi_dot(t) (deg/s)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Steering Angle FL ~ delta_fl(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Measured] Steering Angle FR ~ delta_fr(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Rotation direction ~ rotate(t) (CW/CCW)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Turning Radius ~ R(delta) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Center of Rotation to WORLD ~ X_c(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Center of Rotation to WORLD ~ Y_c(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Current Error to Trajectory ~ e(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Predicted Position ~ X_tp(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Predicted Position ~ Y_tp(t) (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)", + "rawType": "float64", + "type": "float" + }, + { + "name": "[Computed] Torque applied ~ Tau_das (N.m)", + "rawType": "float64", + "type": "float" + } + ], + "conversionMethod": "pd.DataFrame", + "ref": "07a89f18-7381-4f8d-b18c-17df003f8fbf", + "rows": [ + [ + "0", + "0.0", + "0.0", + "0.5", + "-9.155553561868146e-05", + "0.0", + "0.0", + "1.0360826253890991", + "-18.3299617767334", + "49.970359802246094", + "5.033166607049592e-06", + "5.019227955926908e-06", + "3.7432181443364243e-07", + "0.0001909582060761", + "6.702581595163792e-05", + "-5.663286628987407e-06", + "0.0", + "0.0", + "1.0", + "3004644.769999303", + "2.578310078089389e-05", + "-inf", + "inf", + "0.0039175610857063", + "inf", + "-inf", + "inf", + "49.97045133377901", + "9.153153291490725e-05", + "inf", + "inf" + ], + [ + "1", + "0.05732274055480957", + "0.0", + "0.5", + "-9.155553561868146e-05", + "0.0", + "0.0", + "1.0360826253890991", + "-18.3299617767334", + "49.970359802246094", + "3.353869772685239e-06", + "3.336444478918565e-06", + "-3.4143914717788e-07", + "-7.502145308535546e-05", + "-3.396857209736481e-05", + "-6.234964985196712e-06", + "0.0", + "0.0", + "1.0", + "3004644.769999303", + "2.578310078089389e-05", + "-inf", + "inf", + "0.0039175610857063", + "inf", + "-inf", + "inf", + "49.97045133377901", + "9.153153291490725e-05", + "inf", + "inf" + ], + [ + "2", + "0.11790180206298828", + "0.0", + "0.5", + "-9.155553561868146e-05", + "0.0", + "0.0", + "1.0360826253890991", + "-18.3299617767334", + "49.970359802246094", + "3.1191340278759653e-06", + "3.089113079113304e-06", + "-4.317145680943213e-07", + "-7.601009565405548e-05", + "-3.348040991113521e-05", + "-6.2209905991039705e-06", + "0.0", + "0.0", + "1.0", + "3004644.769999303", + "2.578310078089389e-05", + "-inf", + "inf", + "0.0039175610857063", + "inf", + "-inf", + "inf", + "49.97045133377901", + "9.153153291490725e-05", + "inf", + "inf" + ], + [ + "3", + "0.16585087776184082", + "0.0", + "0.5", + "-9.155553561868146e-05", + "0.0", + "0.0", + "1.0360826253890991", + "-18.3299617767334", + "49.970359802246094", + "5.711437862007526e-06", + "5.6918197515187785e-06", + "4.729803038117098e-07", + "9.772958583198488e-05", + "1.932206396304537e-05", + "-4.446515049494337e-06", + "0.0", + "0.0", + "1.0", + "3004644.769999303", + "2.578310078089389e-05", + "-inf", + "inf", + "0.0039175610857063", + "inf", + "-inf", + "inf", + "49.97045133377901", + "9.153153291490725e-05", + "inf", + "inf" + ], + [ + "4", + "0.24229097366333008", + "0.0", + "0.5", + "-9.155553561868146e-05", + "0.0", + "0.0", + "1.0360826253890991", + "-18.3299617767334", + "49.970359802246094", + "3.575532588896949e-06", + "3.569461341612623e-06", + "-2.0827631885822487e-07", + "-6.366188608808443e-05", + "-3.062286850763485e-05", + "-5.986280939396238e-06", + "0.0", + "0.0", + "1.0", + "3004644.769999303", + "2.578310078089389e-05", + "-inf", + "inf", + "0.0039175610857063", + "inf", + "-inf", + "inf", + "49.97045133377901", + "9.153153291490725e-05", + "inf", + "inf" + ] + ], + "shape": { + "columns": 30, + "rows": 5 + } + }, + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
Time (t)[Carla] Throttle[Input] Throttle[Carla] Steering Input[Input] Steering Input[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)[Measured] Current Position ~ X(t) (m)[Measured] Current Position ~ Y(t) (m)[Measured] Current Yaw Angle ~ Phi(t) (deg)[Measured] Speed ~ V(t) (m/s)...[Computed] Center of Rotation to WORLD ~ X_c(t) (m)[Computed] Center of Rotation to WORLD ~ Y_c(t) (m)[Computed] Current Error to Trajectory ~ e(t) (m)[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)[Computed] Predicted Position ~ X_tp(t) (m)[Computed] Predicted Position ~ Y_tp(t) (m)[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)[Computed] Torque applied ~ Tau_das (N.m)
00.0000000.00.5-0.0000920.00.01.036083-18.32996249.970360.000005...-infinf0.003918inf-infinf49.9704510.000092infinf
10.0573230.00.5-0.0000920.00.01.036083-18.32996249.970360.000003...-infinf0.003918inf-infinf49.9704510.000092infinf
20.1179020.00.5-0.0000920.00.01.036083-18.32996249.970360.000003...-infinf0.003918inf-infinf49.9704510.000092infinf
30.1658510.00.5-0.0000920.00.01.036083-18.32996249.970360.000006...-infinf0.003918inf-infinf49.9704510.000092infinf
40.2422910.00.5-0.0000920.00.01.036083-18.32996249.970360.000004...-infinf0.003918inf-infinf49.9704510.000092infinf
\n", + "

5 rows × 30 columns

\n", + "
" + ], + "text/plain": [ + " Time (t) [Carla] Throttle [Input] Throttle [Carla] Steering Input \\\n", + "0 0.000000 0.0 0.5 -0.000092 \n", + "1 0.057323 0.0 0.5 -0.000092 \n", + "2 0.117902 0.0 0.5 -0.000092 \n", + "3 0.165851 0.0 0.5 -0.000092 \n", + "4 0.242291 0.0 0.5 -0.000092 \n", + "\n", + " [Input] Steering Input \\\n", + "0 0.0 \n", + "1 0.0 \n", + "2 0.0 \n", + "3 0.0 \n", + "4 0.0 \n", + "\n", + " [Measured] Steering Wheel Angle SWA ~ Theta(t) (deg) \\\n", + "0 0.0 \n", + "1 0.0 \n", + "2 0.0 \n", + "3 0.0 \n", + "4 0.0 \n", + "\n", + " [Measured] Current Position ~ X(t) (m) \\\n", + "0 1.036083 \n", + "1 1.036083 \n", + "2 1.036083 \n", + "3 1.036083 \n", + "4 1.036083 \n", + "\n", + " [Measured] Current Position ~ Y(t) (m) \\\n", + "0 -18.329962 \n", + "1 -18.329962 \n", + "2 -18.329962 \n", + "3 -18.329962 \n", + "4 -18.329962 \n", + "\n", + " [Measured] Current Yaw Angle ~ Phi(t) (deg) [Measured] Speed ~ V(t) (m/s) \\\n", + "0 49.97036 0.000005 \n", + "1 49.97036 0.000003 \n", + "2 49.97036 0.000003 \n", + "3 49.97036 0.000006 \n", + "4 49.97036 0.000004 \n", + "\n", + " ... [Computed] Center of Rotation to WORLD ~ X_c(t) (m) \\\n", + "0 ... -inf \n", + "1 ... -inf \n", + "2 ... -inf \n", + "3 ... -inf \n", + "4 ... -inf \n", + "\n", + " [Computed] Center of Rotation to WORLD ~ Y_c(t) (m) \\\n", + "0 inf \n", + "1 inf \n", + "2 inf \n", + "3 inf \n", + "4 inf \n", + "\n", + " [Computed] Current Error to Trajectory ~ e(t) (m) \\\n", + "0 0.003918 \n", + "1 0.003918 \n", + "2 0.003918 \n", + "3 0.003918 \n", + "4 0.003918 \n", + "\n", + " [Computed] Predicted Error to Trajectory ~ eps_tp(t) (m) \\\n", + "0 inf \n", + "1 inf \n", + "2 inf \n", + "3 inf \n", + "4 inf \n", + "\n", + " [Computed] Predicted Position ~ X_tp(t) (m) \\\n", + "0 -inf \n", + "1 -inf \n", + "2 -inf \n", + "3 -inf \n", + "4 -inf \n", + "\n", + " [Computed] Predicted Position ~ Y_tp(t) (m) \\\n", + "0 inf \n", + "1 inf \n", + "2 inf \n", + "3 inf \n", + "4 inf \n", + "\n", + " [Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg) \\\n", + "0 49.970451 \n", + "1 49.970451 \n", + "2 49.970451 \n", + "3 49.970451 \n", + "4 49.970451 \n", + "\n", + " [Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg) \\\n", + "0 0.000092 \n", + "1 0.000092 \n", + "2 0.000092 \n", + "3 0.000092 \n", + "4 0.000092 \n", + "\n", + " [Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg) \\\n", + "0 inf \n", + "1 inf \n", + "2 inf \n", + "3 inf \n", + "4 inf \n", + "\n", + " [Computed] Torque applied ~ Tau_das (N.m) \n", + "0 inf \n", + "1 inf \n", + "2 inf \n", + "3 inf \n", + "4 inf \n", + "\n", + "[5 rows x 30 columns]" + ] + }, + "execution_count": 12, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "import pandas as pd\n", + "#cspell: ignore logi\n", + "recorded_time = \"2025-03-25_13-31-50\"\n", + "sensor_df = pd.read_csv(f\"./logs/carla_sensor_log_{recorded_time}.csv\")\n", + "haptic_df = pd.read_csv(f\"./logs/haptic_shared_control_log_{recorded_time}.csv\")\n", + "logiSW_df = pd.read_csv(f\"./logs/steering_wheel_log_{recorded_time}.csv\")\n", + "\n", + "data = pd.DataFrame()\n", + "data[\"Time (t)\"] = haptic_df[\"Time (t)\"] - haptic_df[\"Time (t)\"][0]\n", + "data[\"[Carla] Throttle\"] = sensor_df[\"throttle_input\"]\n", + "data[\"[Input] Throttle\"] = logiSW_df[\" Acceleration Pedal\"]\n", + "data[\"[Carla] Steering Input\"] = sensor_df[\"steering_input\"]\n", + "data[\"[Input] Steering Input\"] = logiSW_df[\" Steering Wheel Angle\"]\n", + "data[\"[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)\"] = haptic_df[\"[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)\"]\n", + "\n", + "data[\"[Measured] Current Position ~ X(t) (m)\"] = haptic_df[\"[Measured] Current Position ~ X(t) (m)\"]\n", + "data[\"[Measured] Current Position ~ Y(t) (m)\"] = haptic_df[\"[Measured] Current Position ~ Y(t) (m)\"]\n", + "data[\"[Measured] Current Yaw Angle ~ Phi(t) (deg)\"] = haptic_df[\"[Measured] Current Yaw Angle ~ Phi(t) (deg)\"]\n", + "data[\"[Measured] Speed ~ V(t) (m/s)\"] = haptic_df[\"[Measured] Speed ~ V(t) (m/s)\"]\n", + "\n", + "data[\"[Measured] VelocityX ~ Vx(t) (m/s)\"] = sensor_df[\"Velocity_0\"]\n", + "data[\"[Measured] VelocityY ~ Vy(t) (m/s)\"] = sensor_df[\"Velocity_1\"]\n", + "data[\"[Measured] AccelerationX ~ Ax(t) (m/s^2)\"] = sensor_df[\"Acceleration_0\"]\n", + "data[\"[Measured] AccelerationY ~ Ay(t) (m/s^2)\"] = sensor_df[\"Acceleration_1\"]\n", + "data[\"[Measured] Angular VelocityZ ~ Phi_dot(t) (deg/s)\"] = sensor_df[\"AngularVelocity_2\"]\n", + "\n", + "data[\"[Measured] Steering Angle FL ~ delta_fl(t) (deg)\"] = haptic_df[\"[Measured] Steering Angle FL ~ delta_fl(t) (deg)\"]\n", + "data[\"[Measured] Steering Angle FR ~ delta_fr(t) (deg)\"] = haptic_df[\"[Measured] Steering Angle FR ~ delta_fr(t) (deg)\"]\n", + "\n", + "data[\"[Computed] Rotation direction ~ rotate(t) (CW/CCW)\"] = haptic_df[\"[Computed] Rotation direction ~ rotate(t) (CW/CCW)\"]\n", + "data[\"[Computed] Turning Radius ~ R(delta) (m)\"] = haptic_df[\"[Computed] Turning Radius ~ R(delta) (m)\"]\n", + "data[\"[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)\"] = haptic_df[\"[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)\"]\n", + "data[\"[Computed] Center of Rotation to WORLD ~ X_c(t) (m)\"] = haptic_df[\"[Computed] Center of Rotation to WORLD ~ X_c(t) (m)\"]\n", + "data[\"[Computed] Center of Rotation to WORLD ~ Y_c(t) (m)\"] = haptic_df[\"[Computed] Center of Rotation to WORLD ~ Y_c(t) (m)\"]\n", + "\n", + "data[\"[Computed] Current Error to Trajectory ~ e(t) (m)\"] = haptic_df[\"[Computed] Current Error to Trajectory ~ e(t) (m)\"]\n", + "data[\"[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)\"] = haptic_df[\"[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)\"]\n", + "\n", + "data[\"[Computed] Predicted Position ~ X_tp(t) (m)\"] = haptic_df[\"[Computed] Predicted Position ~ X_tp(t) (m)\"]\n", + "data[\"[Computed] Predicted Position ~ Y_tp(t) (m)\"] = haptic_df[\"[Computed] Predicted Position ~ Y_tp(t) (m)\"]\n", + "data[\"[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)\"] = haptic_df[\"[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)\"]\n", + "data[\"[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)\"] = haptic_df[\"[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)\"]\n", + "\n", + "data[\"[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)\"] = haptic_df[\"[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)\"]\n", + "data[\"[Computed] Torque applied ~ Tau_das (N.m)\"] = haptic_df[\"[Computed] Torque applied ~ Tau_das (N.m)\"]\n", + "\n", + "data.to_excel(f\"../data/path_logs/data_{recorded_time}.xlsx\", index=False)\n", + "data.head()" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "# data.columns" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "# compared paths\n", + "import matplotlib.pyplot as plt\n", + "import numpy as np\n", + "import pandas as pd\n", + "plt.style.use('default')\n", + "\n", + "def plot_trajectories(df, desired_trajectory, output_file='plots/trajectory_comparison.pdf', start_time=0):\n", + " # Set up plot style\n", + " plt.style.use('default')\n", + " plt.rcParams.update({'font.size': 12})\n", + " \n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " \n", + " # Create a 2D visualization of measured vs predicted positions (unchanged)\n", + " plt.figure()\n", + " \n", + " # Select a subset of points for better visualization (every Nth point)\n", + " skip = max(1, len(df) // 50) # Show about 50 points\n", + " subset = df.iloc[::skip].copy()\n", + " \n", + " plt.plot(subset['[Measured] Current Position ~ Y(t) (m)'], \n", + " subset['[Measured] Current Position ~ X(t) (m)'], \n", + " 'bo-', linewidth=1.5, markersize=4, label='Measured Path')\n", + " plt.plot(subset['[Computed] Predicted Position ~ Y_tp(t) (m)'], \n", + " subset['[Computed] Predicted Position ~ X_tp(t) (m)'], \n", + " 'r.--', linewidth=1.5, markersize=4, label='Predicted Path')\n", + " plt.plot(desired_trajectory[:, 1],\n", + " desired_trajectory[:, 0], \n", + " 'g-', linewidth=2, label='Desired Path')\n", + " \n", + " # Connect measured and predicted points with thin lines\n", + " for i in range(len(subset)):\n", + " plt.plot([subset['[Measured] Current Position ~ Y(t) (m)'].iloc[i], \n", + " subset['[Computed] Predicted Position ~ Y_tp(t) (m)'].iloc[i]],\n", + " [subset['[Measured] Current Position ~ X(t) (m)'].iloc[i], \n", + " subset['[Computed] Predicted Position ~ X_tp(t) (m)'].iloc[i]],\n", + " 'k--', linewidth=0.5, alpha=0.3)\n", + " \n", + " # Add arrows to show direction of travel\n", + " for i in range(0, len(subset), 10):\n", + " # Measured direction arrow\n", + " plt.arrow(subset['[Measured] Current Position ~ Y(t) (m)'].iloc[i], \n", + " subset['[Measured] Current Position ~ X(t) (m)'].iloc[i],\n", + " 0.3*np.sin(np.radians(subset['[Measured] Current Yaw Angle ~ Phi(t) (deg)'].iloc[i])),\n", + " 0.3*np.cos(np.radians(subset['[Measured] Current Yaw Angle ~ Phi(t) (deg)'].iloc[i])),\n", + " head_width=0.1, head_length=0.2, fc='blue', ec='blue')\n", + " \n", + " # Predicted direction arrow\n", + " plt.arrow(subset['[Computed] Predicted Position ~ Y_tp(t) (m)'].iloc[i], \n", + " subset['[Computed] Predicted Position ~ X_tp(t) (m)'].iloc[i],\n", + " 0.3*np.sin(np.radians(subset['[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)'].iloc[i])),\n", + " 0.3*np.cos(np.radians(subset['[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)'].iloc[i])),\n", + " head_width=0.1, head_length=0.2, fc='red', ec='red')\n", + " plt.axis('equal')\n", + "\n", + " # plt.ylim(-8,2)\n", + " # plt.xlim(-22.5,-17.5)\n", + " \n", + " plt.grid(visible=True, which='both', alpha=0.3)\n", + " plt.xlabel('Y Position (m)', fontsize=14)\n", + " plt.ylabel('X Position (m)', fontsize=14)\n", + " \n", + " plt.title('2D Visualization of Measured vs Predicted Positions', fontsize=16)\n", + " \n", + " plt.legend(loc='best')\n", + " \n", + " plt.savefig(f\"{output_file}_2D_path.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{output_file}_2D_path.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"2D path plot saved as {output_file}_2D_path.pdf and {output_file}_2D_path.png\")\n", + " \n" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "2D path plot saved as plots/2025-03-25_04-23-51/trajectory_comparison_2D_path.pdf and plots/2025-03-25_04-23-51/trajectory_comparison_2D_path.png\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import os\n", + "df = pd.read_excel(f\"../data/path_logs/data_{recorded_time}.xlsx\")\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "plot_trajectories(df, predefined_path[\"2\"][\"backward paths\"][\"path\"], output_file=f'plots/{recorded_time}/trajectory_comparison', start_time=0)" + ] + }, + { + "cell_type": "code", + "execution_count": 72, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Plot saved as plots/2025-03-24_14-28-22/steering_analysis\n", + "Plot saved as plots/2025-03-24_14-28-22/steering_analysis.pdf\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Zoomed turning radius plot saved as turning_radius_zoomed.png\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Steering input\n", + "import matplotlib.pyplot as plt\n", + "import pandas as pd\n", + "import numpy as np\n", + "plt.rcParams['text.usetex'] = True\n", + "\n", + "def plot_steering_related_parameters(df, output_file='plots/steering_analysis.png'):\n", + " \"\"\"\n", + " Create a multi-panel figure with steering-related parameters sharing a time axis.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the steering data\n", + " output_file (str): Path to save the output plot\n", + " \"\"\"\n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " time_label = 'Time (s)'\n", + " \n", + " # Define parameters to plot in each panel\n", + " panel_params = [\n", + " {\n", + " 'title': 'Steering Inputs',\n", + " 'params': ['[Input] Steering Input', '[Carla] Steering Input'],\n", + " 'ylabel': 'Steering Input',\n", + " 'colors': ['g--', 'b'],\n", + " 'labels': ['Steering Input (Measured in Steering Wheel)', 'Steering Input (Measured in Carla)']\n", + " },\n", + " {\n", + " 'title': 'Steering Wheel Angle',\n", + " 'params': ['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'],\n", + " 'ylabel': 'SWA (degrees)',\n", + " 'colors': ['r-'],\n", + " 'labels': [r'Measured SWA $\\theta(t)$ (deg)']\n", + " },\n", + " {\n", + " 'title': 'Wheel Steering Angles, and Vehicle Turning angle',\n", + " 'params': [\n", + " '[Measured] Steering Angle FL ~ delta_fl(t) (deg)', \n", + " '[Measured] Steering Angle FR ~ delta_fr(t) (deg)', \n", + " '[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)'\n", + " ],\n", + " 'ylabel': 'Steering Angle (degrees)',\n", + " 'colors': ['b-', 'g-', 'r--'],\n", + " 'labels': [r'FL Wheel ~ $\\delta_{fl}(t)$', r'FR Wheel ~ $\\delta_{fr}(t)$', r'Vehicle Turning angle ~ $\\delta_{v}(t)$']\n", + " },\n", + " {\n", + " 'title': 'Rotation Direction (CW/CCW)',\n", + " 'params': ['[Computed] Rotation direction ~ rotate(t) (CW/CCW)'],\n", + " 'ylabel': 'Direction (-1:CW, 1:CCW)',\n", + " 'colors': ['k-'],\n", + " 'labels': [r'Rotation Direction ~ $rotate(t) = \\frac{sin(\\delta)}{|sin(\\delta)|}$']\n", + " },\n", + " {\n", + " 'title': 'Turning Radius',\n", + " 'params': ['[Computed] Turning Radius ~ R(delta) (m)'],\n", + " 'ylabel': 'Radius (m)',\n", + " 'colors': ['m-'],\n", + " 'labels': [r'Turning Radius ~ $R(\\delta)$']\n", + " }\n", + " ]\n", + " \n", + " # Create the figure with subplots\n", + " plt.style.use('default')\n", + " fig, axes = plt.subplots(len(panel_params), 1, figsize=(12, 15), sharex=True)\n", + " \n", + " # Plot each panel\n", + " for i, panel in enumerate(panel_params):\n", + " ax = axes[i]\n", + " \n", + " for j, param in enumerate(panel['params']):\n", + " if param in df.columns:\n", + " ax.plot(df[time_column], df[param], panel['colors'][j], \n", + " linewidth=2, label=panel['labels'][j])\n", + " \n", + " # Add horizontal line at y=0 for reference\n", + " ax.axhline(y=0, color='gray', linestyle='--', alpha=0.3)\n", + " \n", + " # Set titles and labels\n", + " ax.set_title(panel['title'], fontsize=14)\n", + " ax.set_ylabel(panel['ylabel'], fontsize=14)\n", + " ax.grid(True, alpha=0.3)\n", + " ax.legend(loc='best')\n", + " \n", + " # Special case for rotation direction plot\n", + " if 'Rotation Direction' in panel['title']:\n", + " ax.set_yticks([-1, 0, 1])\n", + " ax.set_yticklabels(['CW', 'Straight', 'CCW'])\n", + " \n", + " # Set x-label only for the bottom subplot\n", + " axes[-1].set_xlabel(time_label, fontsize=14)\n", + " \n", + " # Adjust layout\n", + " plt.tight_layout()\n", + " plt.subplots_adjust(hspace=0.15) # Reduce the space between plots\n", + " \n", + " # Add a super title\n", + " fig.suptitle('Steering System Analysis', fontsize=16, y=1.02)\n", + " \n", + " # Add timestamp range to plot\n", + " time_range = f\"Time Range: {df[time_col].iloc[0]:.2f} to {df[time_col].iloc[-1]:.2f} seconds\"\n", + " fig.text(0.5, 0.1, time_range, ha='center', fontsize=14)\n", + " \n", + " # Save the figure\n", + " plt.savefig(output_file, dpi=300, bbox_inches='tight')\n", + " print(f\"Plot saved as {output_file}\")\n", + " pdf_file = f\"{output_file}.pdf\"\n", + " plt.savefig(pdf_file, format='pdf', bbox_inches='tight')\n", + " print(f\"Plot saved as {pdf_file}\")\n", + " \n", + " # Show the plot\n", + " plt.show()\n", + "\n", + " # At the end of your function, add this code to create the zoomed radius plot\n", + " if True:\n", + " # Create a zoomed-in plot of the turning radius from 10s to the end\n", + " plt.figure(figsize=(12, 6))\n", + " \n", + " # Normalize time to start from 0\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " \n", + " # Filter data from 10 seconds onwards\n", + " zoom_df = df[df['Normalized Time'] >= 15]\n", + " \n", + " if len(zoom_df) > 0:\n", + " plt.plot(zoom_df['Normalized Time'], zoom_df['[Computed] Turning Radius ~ R(delta) (m)'], \n", + " 'm-', linewidth=2, label=r'Turning Radius ~ $R(\\delta)$')\n", + " \n", + " # Add horizontal line at y=0 for reference\n", + " plt.axhline(y=0, color='gray', linestyle='--', alpha=0.3)\n", + " \n", + " # Calculate and display average turning radius for this period\n", + " avg_radius = zoom_df['[Computed] Turning Radius ~ R(delta) (m)'].mean()\n", + " std_radius = zoom_df['[Computed] Turning Radius ~ R(delta) (m)'].std()\n", + " \n", + " plt.axhline(y=avg_radius, color='r', linestyle='--', alpha=0.7)\n", + " plt.text(zoom_df['Normalized Time'].iloc[len(zoom_df)//2], avg_radius*1.1, \n", + " f'Avg: {avg_radius:.2f}m, Std: {std_radius:.2f}m',\n", + " fontsize=14, color='red')\n", + " \n", + " # Create the plot\n", + " plt.title('Turning Radius (Zoomed from 15s to End)', fontsize=16)\n", + " plt.xlabel('Time (s)', fontsize=14)\n", + " plt.ylabel('Radius (m)', fontsize=14)\n", + " plt.grid(True, alpha=0.3)\n", + " plt.legend(loc='best')\n", + " \n", + " # Get the y-limits to set a good range\n", + " ymin = zoom_df['[Computed] Turning Radius ~ R(delta) (m)'].min()\n", + " ymax = zoom_df['[Computed] Turning Radius ~ R(delta) (m)'].max()\n", + " margin = (ymax - ymin) * 0.2 # 20% margin\n", + " plt.ylim(max(0, ymin - margin), ymax + margin) # Don't go below 0 for radius\n", + " \n", + " plt.tight_layout()\n", + " plt.savefig('turning_radius_zoomed.png', dpi=300, bbox_inches='tight')\n", + " print(\"Zoomed turning radius plot saved as turning_radius_zoomed.png\")\n", + " plt.show()\n", + " else:\n", + " print(\"No data available after 10 seconds.\")\n", + "# Load your data and call the function\n", + "\n", + "\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Create the plots\n", + "plot_steering_related_parameters(df, output_file=f'plots/{recorded_time}/steering_analysis')" + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Plot saved as plots/2025-03-24_13-53-49/vehicle_dynamics_analysis.pdf\n", + "Plot also saved as plots/2025-03-24_13-53-49/vehicle_dynamics_analysis.png\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# pedal to vehicle dynamics\n", + "\n", + "import matplotlib.pyplot as plt\n", + "import pandas as pd\n", + "import numpy as np\n", + "\n", + "def plot_vehicle_dynamics(df, output_file='vehicle_dynamics_analysis'):\n", + " \"\"\"\n", + " Create a multi-panel figure with vehicle dynamics parameters sharing a time axis.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the data\n", + " output_file (str): Base name for output files (without extension)\n", + " \"\"\"\n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " time_label = 'Time (s)'\n", + " \n", + " # Define plot panels and their parameters\n", + " panel_params = [\n", + " {\n", + " 'title': 'Throttle',\n", + " 'params': ['[Carla] Throttle', '[Input] Throttle'],\n", + " 'ylabel': 'Throttle Value',\n", + " 'colors': ['b-', 'g--'],\n", + " 'labels': ['Carla Throttle', 'Input Throttle']\n", + " },\n", + " {\n", + " 'title': 'Speed',\n", + " 'params': ['[Measured] Speed ~ V(t) (m/s)', '[Measured] VelocityX ~ Vx(t) (m/s)', \n", + " '[Measured] VelocityY ~ Vy(t) (m/s)'],\n", + " 'ylabel': 'Speed (m/s)',\n", + " 'colors': ['b-', 'g--', 'r:'],\n", + " 'labels': [r'Speed V(t)', r'Velocity X ~ $V_x(t)$', r'Velocity Y ~ $V_y(t)$']\n", + " },\n", + " {\n", + " 'title': 'Acceleration',\n", + " 'params': ['[Measured] AccelerationX ~ Ax(t) (m/s^2)', '[Measured] AccelerationY ~ Ay(t) (m/s^2)'],\n", + " 'ylabel': 'Acceleration (m/s²)',\n", + " 'colors': ['g-', 'r--'],\n", + " 'labels': [r'Acceleration X ~ $A_x(t)$', r'Acceleration Y ~ $A_y(t)$']\n", + " },\n", + " {\n", + " 'title': 'Change of yaw angle (Calculated)',\n", + " 'params': ['[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)'],\n", + " 'ylabel': r'$\\Delta \\phi (t)$ (deg)',\n", + " 'colors': ['m-'],\n", + " 'labels': [r'Change of Yaw Angle $\\Delta \\phi (t)$']\n", + " },\n", + " {\n", + " 'title': 'Trajectory Error',\n", + " 'params': ['[Computed] Current Error to Trajectory ~ e(t) (m)', \n", + " '[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)'],\n", + " 'ylabel': 'Error (m)',\n", + " 'colors': ['b-', 'r--'],\n", + " 'labels': ['Current Error ~ e(t) ', r'Predicted Error ~ $\\epsilon^{tp}(t)$']\n", + " }\n", + " ]\n", + " \n", + " # Create figure with subplots\n", + " fig, axes = plt.subplots(len(panel_params), 1, figsize=(12, 15), sharex=True)\n", + " \n", + " # Plot each panel\n", + " for i, panel in enumerate(panel_params):\n", + " ax = axes[i]\n", + " \n", + " for j, param in enumerate(panel['params']):\n", + " if param in df.columns:\n", + " ax.plot(df[time_column], df[param], panel['colors'][j], \n", + " linewidth=2, label=panel['labels'][j])\n", + " \n", + " # Add horizontal line at y=0 for reference\n", + " ax.axhline(y=0, color='gray', linestyle='--', alpha=0.3)\n", + " \n", + " # Set titles and labels\n", + " ax.set_title(panel['title'], fontsize=14)\n", + " ax.set_ylabel(panel['ylabel'], fontsize=14)\n", + " ax.grid(True, alpha=0.3)\n", + " ax.legend(loc='best')\n", + " \n", + " # Set x-label only for the bottom subplot\n", + " axes[-1].set_xlabel(time_label, fontsize=14)\n", + " \n", + " # Adjust layout\n", + " plt.tight_layout()\n", + " plt.subplots_adjust(hspace=0.15) # Reduce the space between plots\n", + " \n", + " # Add a super title\n", + " fig.suptitle('Vehicle Dynamics Analysis', fontsize=16, y=1.02)\n", + " \n", + " # Add timestamp range to plot\n", + " time_range = f\"Time Range: {df[time_col].iloc[0]:.2f} to {df[time_col].iloc[-1]:.2f} seconds\"\n", + " fig.text(0.5, -0.01, time_range, ha='center', fontsize=14)\n", + " \n", + " # Save the figure as PDF\n", + " pdf_file = f\"{output_file}.pdf\"\n", + " plt.savefig(pdf_file, format='pdf', bbox_inches='tight')\n", + " print(f\"Plot saved as {pdf_file}\")\n", + " \n", + " # Also save as PNG for quick viewing\n", + " png_file = f\"{output_file}.png\"\n", + " plt.savefig(png_file, dpi=300, bbox_inches='tight')\n", + " print(f\"Plot also saved as {png_file}\")\n", + " \n", + " # Show the plot\n", + " plt.show()\n", + "\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "plot_vehicle_dynamics(df, output_file=f'plots/{recorded_time}/vehicle_dynamics_analysis')" + ] + }, + { + "cell_type": "code", + "execution_count": 32, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Position time series saved as plots/2025-03-24_13-53-49/plot_position_time_series.pdf\n", + "Also saved as plots/2025-03-24_13-53-49/plot_position_time_series.png\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# position on time series\n", + "import matplotlib.pyplot as plt\n", + "import pandas as pd\n", + "import numpy as np\n", + "\n", + "def plot_position_time_series(df, output_file='position_time_series'):\n", + " \"\"\"\n", + " Create a plot of X and Y position over time.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the position data\n", + " output_file (str): Base name for output files (without extension)\n", + " \"\"\"\n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " time_label = 'Time (s)'\n", + " \n", + " # Create figure with position plots\n", + " fig, (ax1, ax2) = plt.subplots(2, 1, figsize=(12, 4), sharex=True)\n", + " \n", + " # Plot X position\n", + " ax1.plot(df[time_column], df['[Measured] Current Position ~ X(t) (m)'], 'b-', \n", + " linewidth=2, label=r'$X(t)$ (m)')\n", + " ax1.set_title('X Position Over Time', fontsize=14)\n", + " ax1.set_ylabel('X Position (m)', fontsize=14)\n", + " ax1.grid(True, alpha=0.3)\n", + " ax1.legend(loc='best')\n", + " \n", + " # Plot Y position\n", + " ax2.plot(df[time_column], df['[Measured] Current Position ~ Y(t) (m)'], 'g-', \n", + " linewidth=2, label=r'$Y(t)$ (m)')\n", + " ax2.set_title('Y Position Over Time', fontsize=14)\n", + " ax2.set_xlabel(time_label, fontsize=14)\n", + " ax2.set_ylabel('Y Position (m)', fontsize=14)\n", + " ax2.grid(True, alpha=0.3)\n", + " ax2.legend(loc='best')\n", + " \n", + " # Adjust layout\n", + " plt.tight_layout()\n", + " \n", + " # Save the figure as PDF\n", + " pdf_file = f\"{output_file}.pdf\"\n", + " plt.savefig(pdf_file, format='pdf', bbox_inches='tight')\n", + " print(f\"Position time series saved as {pdf_file}\")\n", + " \n", + " # Also save as PNG for quick viewing\n", + " png_file = f\"{output_file}.png\"\n", + " plt.savefig(png_file, dpi=300, bbox_inches='tight')\n", + " print(f\"Also saved as {png_file}\")\n", + " \n", + " # Show the plot\n", + " plt.show()\n", + " \n", + "\n", + "# Load your data\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Create the plots\n", + "plot_position_time_series(df, f'plots/{recorded_time}/plot_position_time_series')" + ] + }, + { + "cell_type": "code", + "execution_count": 35, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Velocity vector analysis saved as plots/2025-03-24_13-53-49/velocity_vector_analysis.pdf\n", + "Also saved as plots/2025-03-24_13-53-49/velocity_vector_analysis.png\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# velocity vector analysis\n", + "import matplotlib.pyplot as plt\n", + "\n", + "import pandas as pd\n", + "import numpy as np\n", + "\n", + "def plot_velocity_vectors(df, output_file='velocity_vector_analysis'):\n", + " \"\"\"\n", + " Create visualizations of velocity vectors, analyzing magnitude, direction, and angle over time.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the velocity data\n", + " output_file (str): Base name for output files (without extension)\n", + " \"\"\"\n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " time_label = 'Time (s)'\n", + " \n", + " # Calculate velocity magnitude and direction\n", + " vx = df['[Measured] VelocityX ~ Vx(t) (m/s)']\n", + " vy = df['[Measured] VelocityY ~ Vy(t) (m/s)']\n", + " \n", + " # Calculate angle between velocity vector and x-axis in degrees\n", + " # Note: arctan2 returns angle in radians, we convert to degrees\n", + " # arctan2(y, x) gives the angle in the correct quadrant\n", + " df['Velocity_angle'] = np.degrees(np.arctan2(vy, vx))\n", + " \n", + " # Calculate speed (magnitude of velocity vector)\n", + " df['Speed_calc'] = np.sqrt(vx**2 + vy**2)\n", + " \n", + " # Create figure with multiple panels\n", + " fig = plt.figure(figsize=(12, 12))\n", + " gs = fig.add_gridspec(4, 1, height_ratios=[1, 1, 1, 1.5])\n", + " \n", + " # Panel 1: Speed over time\n", + " ax1 = fig.add_subplot(gs[0])\n", + " ax1.plot(df[time_column], df['[Measured] Speed ~ V(t) (m/s)'], 'k-', \n", + " linewidth=2, label=r'Measured Speed $V(t)$ (m/s)')\n", + " ax1.set_ylabel('Speed (m/s)', fontsize=14)\n", + " ax1.grid(True, alpha=0.3)\n", + " ax1.legend(loc='best')\n", + " \n", + " # Panel 2: Velocity components over time\n", + " ax2 = fig.add_subplot(gs[1], sharex=ax1)\n", + " ax2.plot(df[time_column], vx, 'b-', linewidth=2, label=r'Velocity X ~ $V_x(t)$ (m/s)')\n", + " ax2.plot(df[time_column], vy, 'g-', linewidth=2, label=r'Velocity Y ~ $V_y(t)$ (m/s)')\n", + " ax2.axhline(y=0, color='gray', linestyle='--', alpha=0.3)\n", + " ax2.set_title('Velocity Components', fontsize=14)\n", + " ax2.set_ylabel('Velocity (m/s)', fontsize=14)\n", + " ax2.grid(True, alpha=0.3)\n", + " ax2.legend(loc='best')\n", + " \n", + " # Panel 3: Direction angle over time\n", + " ax3 = fig.add_subplot(gs[2], sharex=ax1)\n", + " ax3.plot(df[time_column], df['Velocity_angle'], 'm-', linewidth=2)\n", + " ax3.set_title('Velocity Direction Angle', fontsize=14)\n", + " ax3.set_ylabel('Velocity Direction Angle (deg)', fontsize=14)\n", + " ax3.set_yticks(np.arange(-180, 180, 45))\n", + " ax3.grid(True, alpha=0.3)\n", + " \n", + " # Set x-label only for the bottom subplot\n", + " ax3.set_xlabel(time_label, fontsize=14)\n", + " \n", + " # Adjust layout\n", + " plt.tight_layout()\n", + " \n", + " # Save the figure as PDF\n", + " pdf_file = f\"{output_file}.pdf\"\n", + " plt.savefig(pdf_file, format='pdf', bbox_inches='tight')\n", + " print(f\"Velocity vector analysis saved as {pdf_file}\")\n", + " \n", + " # Also save as PNG for quick viewing\n", + " png_file = f\"{output_file}.png\"\n", + " plt.savefig(png_file, dpi=300, bbox_inches='tight')\n", + " print(f\"Also saved as {png_file}\")\n", + " \n", + " plt.show()\n", + " \n", + "\n", + "# Load your data\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Create the plots\n", + "plot_velocity_vectors(df, output_file=f'plots/{recorded_time}/velocity_vector_analysis')" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Plot saved as plots/2025-03-24_13-53-49/acceleration_time_series.pdf\n" + ] + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAABKUAAAGGCAYAAACqvTJ0AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMywgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/NK7nSAAAACXBIWXMAAA9hAAAPYQGoP6dpAAEAAElEQVR4nOzdd1gUxxsH8O8dHaQXRSkWrMHeBSP2xN6N+dmxRrH3Ho2xRKOJJhoNthhj1NhNDMYuKmIXxQ6CAoKA9H7z+2PYK9wBR7ujvJ/n4eFud293bm9ub/fdd2ZEjDEGQgghhBBCCCGEEEI0SKztAhBCCCGEEEIIIYSQioeCUoQQQgghhBBCCCFE4ygoRQghhBBCCCGEEEI0joJShBBCCCGEEEIIIUTjKChFCCGEEEIIIYQQQjSOglKEEEIIIYQQQgghROMoKEUIIYQQQgghhBBCNI6CUoQQQgghhBBCCCFE4ygoRQghhBBCCCGEEEI0joJShBBCSCk3evRoiEQiBAcHa7soaluxYgVEIhEuXbqk7aIQQrLR95IQQkhpQ0EpQgghFdLYsWMhEolgbW2NtLQ0bRenzLl06RJEIhFWrFih7aIUSGZmJnbv3o0ePXqgSpUq0NfXh7m5OVq2bIklS5bgzZs32i5ihaXJOnXx4kUMHToUjo6OMDAwgJWVFdzd3bFp0yakpqaW+PaLg4eHB0Qikdp/FIgihBBSGulquwCEEEKIpiUkJODQoUMQiUSIiYnB8ePHMXToUG0Xq1yZOnUqvvjiCzg5OWm7KFJv3rxB37598eDBA1SuXBldu3aFo6MjkpKScPfuXaxduxYbNmxAQEAAXFxctF1cUgIyMzMxZcoU7NixAyYmJvj888/h4uKCuLg4+Pj4YNasWdi+fTvOnDlT6uvA6NGj4eHhoTDt+PHjePDgAUaNGoXq1asrzKtevXqp/F4SQgip2CgoRQghpML5888/kZSUhFmzZmHz5s3w9vamoFQxs7GxgY2NjbaLIZWQkIDu3bvj2bNnmDt3LlatWgUDAwOFZV6+fIlZs2YhMTFRS6UkJW3hwoXYsWMHWrZsiWPHjqFatWrSeVlZWVi5ciVWrlyJzz77DHfv3oWZmZkWS5u30aNHK00LDg7GgwcPVAasBKXpe0kIIYRQ8z1CCCEVjre3N3R1dTFv3jx07NgR58+fz7PZ1pUrV9CvXz9UrlwZBgYGcHR0xIABA3Dt2jWF5Rhj2L17N9q3bw8LCwsYGxujdu3amDhxIkJCQhSWTUhIwPLly/HJJ5/AyMgIFhYW6N69u9I683PlyhX07t0bNjY2MDAwQO3atbFkyRIkJycrLCffNOr69evo1q0bLCwsIBKJpMvs2rULffv2RfXq1WFoaAgrKyt0794dFy9eVFjXihUr0LFjRwDA119/rdBESOj3Kq++a06dOoWOHTvC3NwcRkZGaNy4Mb7//ntkZmYqLBccHAyRSITRo0fj5cuX6N+/PywtLWFiYoIuXbrgwYMHau+nDRs24NmzZxg+fDjWr1+vFJACABcXF5w8eRINGjRQmO7r64uePXvCysoKhoaGqFevHpYvX660jwFAJBLBw8MD7969w5dffgkbGxuYmpqiZ8+eeP36NQAgMDAQ/fr1g5WVFUxNTTFo0CC8f/8+1/f++PFj9OzZExYWFqhUqRK6deuGO3fuqHyfb968gaenJ6pVqwZ9fX04ODjA09NTqf4BsuZfGRkZWLFiBapXrw4DAwPUqVMHP//8s8r1M8awa9cuuLm5wczMDMbGxmjRogV27dqltKx8HThw4ACaNGkCIyMj2NvbY/r06UhJSVFYNr86FRcXh2XLlqFBgwaoVKkSzMzM4OLiglGjRqnV7PL58+f4/vvvYWVlhVOnTikEpABAR0cHX3/9Nb788ku8evUKGzZskM5zcXGBqampys8cAPr06QORSITnz58rTD9x4gQ6d+4MS0tLGBoawtXVFRs2bEBWVpbCcnv27IFIJMKePXtw6tQpuLm5wdTUVCnbqahUfS/l61pgYCB69eoFCwsLWFpaYtiwYfjw4QMA4MaNG+jcuTPMzMxgaWmJcePGISkpSeV21D0uEUIIIWCEEEJIBfL48WMGgPXo0YMxxtjevXsZALZ8+XKVy2/evJmJRCJmbGzM/ve//7GFCxeykSNHspo1a7Lp06dLl8vKymKDBg1iAFi1atXYpEmT2Lx589iQIUOYhYUFO3bsmHTZ6Oho9sknnzAAzM3Njc2YMYONHTuWWVtbM11dXYVlGWNs1KhRDAALCgpSmP7zzz8zkUjELC0t2ciRI9mcOXOYh4cHA8DatWvH0tLSpMtevHiRAWBdu3Zlenp6rFu3bmzu3Lls6NCh0mUMDQ1Z69atmaenJ1uwYAEbMWIEMzU1ZWKxmB0/flxhXUKZOnTowJYvXy79i42NZYwxtnz5cgaAXbx4UaHMGzduZACYlZUVmzRpEps9ezarXbs2A8D69evHJBKJdNmgoCDpNqytrdmnn37KZs2axfr27csAMEtLSxYREZHLJ63IwcGBAWDPnz9Xa3nBoUOHmI6ODjM2NmZjxoxh8+fPZ02bNmUAWOvWrVlKSorC8gBYo0aNWPXq1VmbNm3YrFmzWK9evRgAVrNmTfbo0SNmYWHBOnfuzGbPni39vDp27KiwHuG9t2/fnpmbm7OOHTuyBQsWsGHDhjFdXV1mbGzMbt68qfCaZ8+eMVtbWwaA9e7dmy1YsEC6bVtbW/bs2TOF5Tt06MAAsIEDBzJHR0c2YcIENnnyZGZtbc0AsB07digsL5FI2LBhwxgAVrt2bTZx4kTm5eXF6tWrxwCw2bNnKywv1IGBAwcyExMT9uWXX7KZM2ey+vXrMwDsyy+/lC6bX52SSCSsdevW0u/MzJkz2ezZs9mgQYOYhYUFO3fuXL6f5aJFixgAtmDBgjyXCwwMlH6Pc76X33//XWn5qKgopqenx1q3bq0wfcGCBdL1jB07ls2cOZO1aNGCAWCDBg1SWHb37t3S45Kuri7r168fmzdvHps0aVK+70uesA9zfu9yvg/5+UJd+/TTT5mFhQXr0qULmz17trR+uLm5satXrzIjIyPWp08fNnv2bNa8eXMGgI0ZM0ZpGwU5LhFCCCEUlCKEEFKhzJo1iwFgf/zxB2OMsYSEBGZiYsKcnJxYVlaWwrL3799nYrGYVa1aVSkgJJFI2Lt376TPt2zZwgCwzp07s+TkZIVlk5OTWXR0tPT5l19+yQCwnTt3Kiz3/v175ujoyGxtbRWCHaqCUo8fP2a6urqscePG7MOHDwrrWbNmDQPANmzYIJ0mBKUAsF27dqncN69fv1aaFhYWxqpWrcpq166tMF1YX27BPFUXvy9fvmS6urrMzs6OhYSESKenpqYyd3d3BoDt27dPOl24WAbA1q5dq7D+JUuWMABszZo1KrcvLzg4mAFgDg4O+S4rLy4ujpmbmzMDAwP24MED6fSsrCw2dOhQBoCtXLlS4TVCeWfOnKkwffLkyQwAs7CwYJs3b5ZOl0gkrEePHgwAu3Pnjsr3njOIcvbsWQaANWzYUGF6x44dGQD2yy+/KEz/6aefGADWqVMnhelC0KF169YsLi5OOv3p06dMV1eX1a1bV2H5HTt2SAMR6enp0ulpaWmsd+/eDAC7ffu2dLpQB8zNzdnTp0+l05OTk1mdOnWYWCxW+A7lVacePnwoDVzmlJqayhISEpSm5yQERtQJYFWtWpUBkNbTFy9eMADs888/V1pW+O5v3bpVOs3Hx4cBYN27d2eJiYnS6RKJhE2aNIkBYEeOHJFOF4JSYrFYrfLlpihBKQC51k0LCwuFwHR6ejpr1KgR09XVVQgMF/S4RAghhFBQihBCSIWRnp7ObG1tmZmZmULQZ/jw4QwA+/fffxWWFwIJuQVx5NWvX5/p6Ojkm4kTFRXFdHR0lAIEgh9//JEBYKdOnZJOUxWUmjZtGgPArly5orSOrKwsZmtry5o3by6dJlzwN2vWLN/3kpOXlxcDwIKDg5XWV5Cg1MqVKxkAtm7dOqXlfX19lQInwsVyjRo1lAKGwrwBAwbkW/6bN28yAKxNmzb5Litv3759DACbPHmy0rw3b94wXV1dVrNmTYXpAFilSpVYUlKSwvQrV64wAKxWrVoK2WDy25GvZ8L7s7CwUBlw6dy5s0IQ6M2bNwwAa9CggdL6s7KypNlM8sFAISh14cIFpfUL8+Lj46XTGjVqxExMTJSCrozJgkby2VJCHVi2bJnS8sK8kydPSqepE5QaNmyY0jx1CftAPkCWGyEry8/PTzqtbdu2TFdXl71//15h2VatWjE9PT0WFRUlndanTx8GgL1580Zp3R8/fmQikYgNHDhQOk0ISvXv378wb02qKEGpvOpmzkw+xmTfZ/n6U9DjEiGEEEIdnRNCCKkwTpw4gaioKHh6esLQ0FA6feTIkdi/fz+8vb3RrVs36fRbt24BgMI0VRITExEYGAgXFxfUrl07z2X9/f2RlZWFtLQ0rFixQmn+ixcvAABPnz5Fr169cl3PzZs3AQD//vsvzp8/rzRfT08PT58+VZresmXLXNf5+vVrrFmzBhcuXMC7d++QlpamMD8sLAzOzs65vj4/9+7dAwCVHTC3bdsWhoaGuH//vtK8Jk2aQCxW7AbTwcEBAPDx48dClyc/eZXXyckJNWvWxPPnz5GQkABTU1PpvNq1a8PY2FhheXt7ewBAo0aNFPrxkp8XFhamtJ2mTZuiUqVKStPbt2+P8+fP4969e2jevLl0v3Xo0EFp/WKxGJ9++imePn2K+/fvw9HRUWF+8+bNldYvv3+FvpQePXqEqlWrYt26dUrLZ2RkAIDKOpff+tVRv359NGrUCH/88Qfevn2Lfv36wcPDQ2XdKCkjRozAjRs38Mcff2D69OkA+Pf11q1b0v6TBDdv3oSJiYnKvrYAwMjISOW+atWqVckUXg151c0mTZooLa+q3hb2uEQIIaTioqAUIYSQCsPb2xsAD0LJ69y5M6pVq4YTJ04gJiYGVlZWAHjHyiKRSHrxlZu4uDgAUOo4WZWYmBgAvPNsX1/fXJfLrQPhnOtZvXp1vtuUV7lyZZXTX758iVatWiE+Ph4dO3ZE7969YWZmBrFYjEuXLuHy5ctKQaqCio+Pz7UMIpEIlStXxrt375TmqRoBTVeXn8Lk7DBalSpVqgCAynUXtrwAvyh//vw54uPjFYJSeZU3r3lCYEdebtsWpgt1T52yyi8nT539GxsbC8YY3r17h6+//lrlNgDV9baon5+w/IULF7BixQr89ddfmD17NgDA1tYWU6dOxeLFi6Gjo5PnOqpUqYKnT58iNDQUdevWzXPZ0NBQAFD47g8dOhQzZszA/v37pUGp3377DQAPWMmLiYlBZmZmgfdVbp+fJhRHvS3scYkQQkjFRaPvEUIIqRBCQ0Ph4+MDQJZNIvzp6OhIM4P2798vfY2FhQUYYwgPD89z3ebm5gDUC3oIF3ezZ88G483oVf4tX75crfXEx8fnuZ6ccmZCCDZt2oTY2Fjs2bMH586dw+bNm7Fy5UqsWLEC9erVy/d9qUMoc86R5gA+qtv79+9VXvwWlbOzM6pVq4bQ0FBpJpo68iovAERERCgsVxJy27YwXah7JV1W4XXNmzfPs77lHKmxOFlbW2PLli149+4dnjx5gq1bt8LKygrLly/H+vXr8319u3btAEBlBo+8p0+fIiwsDNWqVVPIKrOyskKPHj1w+/ZtPHv2DACwf/9+mJubo3fv3grrMDMzg7W1dZ77KigoSGnbuX0/y4rCHpcIIYRUXBSUIoQQUiHs2bMHEokE7u7u8PT0VPobNWoUAFk2FSBrSiMEs3JTqVIlNGjQAEFBQfkGPVq2bAmRSIQbN24U6f20bt0agKy5TFG9evUKANC3b1+F6YwxlRldQlaKupkuAG+KBkBhOHqBn58fUlNTVTYTKg6enp4AgG+++SbfZdPT0wHkXd7Q0FC8evUKNWvWVMiSKm737t1DYmKi0vSrV68qlFHYb1euXFG66GeM4cqVKwrLFZSpqSnq16+PwMDAEmsyqW6dEolEqF+/PqZMmYJz584BAE6ePJnv+keOHAmxWIydO3ciKioq1+WELJ+xY8cqzRMyovbv3w9fX18EBQVh0KBBCs2BAf79jI6OLlAQtDwo7uMSIYSQ8o+CUoQQQso9xhh2794NkUiEvXv34tdff1X627NnD9q2bYuHDx/i9u3bAIBJkyZBR0cHS5YswZs3b5TWKd+XypQpU5CVlYWvvvoKKSkpCsumpqZKm7VUqVIFQ4YMwfXr1/Hdd9+pzBrw8/NDcnJynu/pq6++gq6uLry8vBASEqI0/+PHj9I+kdQh9BV17do1helr165FQECA0vJCE0ehmZM6vvzyS+jq6uL7779X2Hfp6emYP38+AGD06NFqr68g5syZg7p162Lfvn1YtGiRyqaIQUFB6NevH548eQKAB+jMzc2xe/duPH78WLocYwzz589HZmZmiZVX8PHjR6WmUEJ/Pa6urtL+mpycnNCxY0c8fvxYqR+jHTt2IDAwEJ06dVLqT6ogpk2bhuTkZIwfP15l07OgoCAEBwcXev151ang4GCV6xYyw3IGhVSpW7cupk+fjujoaPTu3VspA1IikWDVqlXYv38/atWqhTlz5iito2fPnrC0tMTvv/+Offv2AVBuugfwfQXwwFZ0dLTS/IiICAQGBuZb5rKmuI9LhBBCyj/qU4oQQki5d+HCBQQFBaFDhw6oWbNmrsuNGTMGN27cgLe3N1q0aIGGDRti8+bNmDZtGj755BP069cPzs7OiIiIwJUrV9CzZ09s3rwZADB58mRcvnwZhw4dQu3atdGnTx+YmZkhJCQE//77L7y9vdGvXz8AwM8//4xnz55h3rx5+O2339C2bVtYWFggNDQUt2/fxosXLxAeHq7UWbY8V1dX/Pzzz5g8eTLq1q2LHj16oFatWkhISMDr169x+fJljB49Gtu3b1drH02aNAm7d+/GwIEDMWTIEFhbW+PmzZu4e/cuevbsiTNnzigsX69ePVStWhUHDx6EgYEBHBwcIBKJ4OXlJW1SllOtWrWwbt06zJ49G40aNcKQIUNgYmKCU6dO4dmzZ+jbty+GDx+uVnkLytTUFP/++y/69u2LNWvWYPfu3ejWrRscHByQnJyMe/fuwdfXF7q6utiwYQMA3hRp586dGDZsGFq3bo2hQ4fC1tYW//33H+7cuYNWrVph7ty5JVJeQfv27bFt2zb4+fmhTZs2CA4OxuHDh2FkZIRff/1VYdlt27bB3d0d48ePx6lTp9CgQQM8fvwYJ0+ehK2tLbZt21akskycOBE3b97E3r174evriy5duqBq1ap4//49nj59Cj8/Pxw4cADVq1cv1PrzqlP379/HgAED0KpVKzRo0ABVqlTBu3fvcPz4cYjFYsycOVOtbaxfvx5xcXHYtWsXateujZ49e6JWrVqIj4+Hj48PXrx4gdq1a+Pvv/9W2dTRwMAAQ4YMwS+//ILdu3fD2dkZn376qdJyn332GZYuXYpVq1bBxcUFn332GZydnREdHY2XL1/i6tWr+Oabb1C/fv1C7avSqriPS4QQQiqAEhnTjxBCCClFhg0bxgCw3bt357lcXFwcMzIyYubm5grD3l+8eJH16tWLWVlZMX19febg4MAGDhzIfH19FV4vkUjYr7/+ytq0acNMTEyYsbExq127Nps0aRILCQlRWDY5OZmtX7+eNW/enJmYmDAjIyNWo0YN1q9fP7Zv3z6WkZEhXVYY5j0oKEipzLdu3WJffPEFq1q1KtPT02M2NjasWbNmbMGCBSwwMFDhPQBgy5cvz/X9X7x4kbm5uTFTU1NmYWHBevTowe7cuaNyGHnGGLt58ybr0KEDMzU1ZQAUypjbaxhj7MSJE9LXGRgYsIYNG7KNGzcqvGfGZEPVjxo1SmV5AbAOHTrk+n5USU9PZ7t27WKfffYZq1y5MtPT02OmpqasWbNmbNGiRUqfE2OMXblyhX3++efMwsKC6evrszp16rClS5eyxMREtcuU13tR9dnILx8QEMB69OjBzMzMmImJCevSpQu7ffu2yvcXHBzMxowZw+zt7Zmuri6zt7dnY8aMYcHBwUrLdujQgeV2KphXnfvzzz9Zly5dmKWlJdPT02PVqlVjHh4ebOPGjSwqKkq6XF51YPfu3Sq/k7nVqdDQULZgwQLWpk0bZmdnx/T19ZmTkxMbMGAAu3Hjhsr3kJdz586xwYMHS783FhYWrG3btmzjxo0K331Vrl27Ji3bwoUL891O7969ma2tLdPT02NVqlRhbdu2ZatWrVKoa7ntj4ISPjdV+5wx1Z9JQeumOmVW97hECCGEiBij3gYJIYQQQkqT4OBg1KhRA6NGjcKePXu0XRxCCCGEkBJBfUoRQgghhBBCCCGEEI2joBQhhBBCCCGEEEII0TgKShFCCCGEEEIIIYQQjaM+pQghhBBCCCGEEEKIxlGmFCGEEEIIIYQQQgjROApKEUIIIYQQQgghhBCN09V2AbRNIpEgLCwMpqamEIlE2i4OIYQQQgghhBBCSJnGGENCQgKqVq0KsTj3fKgKH5QKCwuDo6OjtotBCCGEEEIIIYQQUq6EhobCwcEh1/kVPihlamoKgO8oMzMzLZem8CQSCaKiomBra5tnFJKUf1QXCED1gHBUDwhA9YBwVA8IQPWAyFBdIEDJ1oP4+Hg4OjpKYy65qfBBKaHJnpmZWZkPSqWmpsLMzIwOKhUc1QUCUD0gHNUDAlA9IBzVAwJQPSAyVBcIoJl6kF83SVT7CCGEEEIIIYQQQojGUVCKEEIIIYQQQgghhGgcBaUIIYQQQgghhBBCiMZV+D6l1CGRSJCenq7tYuRJIpEgIyMDqamp1Ca4gqO6QICyWQ/09PSgo6Oj7WIQQgghhBBCNISCUvlIT09HUFAQJBKJtouSJ8YYJBIJEhIS8u1IjJRvVBcIUHbrgYWFBapUqVKmykwIIYQQQggpHApK5YExhvDwcOjo6MDR0bFUZxswxpCZmQldXV26mKvgqC4QoOzVA8YYkpOTERkZCQCwt7fXcokIIYQQQgghJY2CUnnIzMxEcnIyqlatCmNjY20XJ09l7QKUlByqCwQom/XAyMgIABAZGQk7OztqykcIIYQQQkg5V3pTf0qBrKwsAIC+vr6WS0IIIRWDcAMgIyNDyyUhhBBCCCGElDQKSqmhrGQZEEJIWUfHW0IIIYQQQioOCkoRQgghhBBCCCk74uO1XQJCSDGhoBQhhBBCCCGEkLJh+3bA3Bz45Rdtl4QQUgwoKEVKHQ8PD8yYMaPCbl9ToqOjYWdnh+Dg4DyX++KLL7Bx48ZiXacmFKTchBBCCCGkjJg8mf+fNEm75SCEFAsKSpVDWVlZaNeuHQYMGKAwPS4uDo6Ojli8eHGer79x4wZ0dHTQs2fPkiym1uUWfDp69ChWrVql+QIV0r1796CnpwcPD48CvW716tXo27cvqlevLp02c+ZMpXqzZMkSrF69GnFxcYVaZ1GMGTMGS5YsyXX+zZs30aVLF7i5uaFZs2a4ffu2dF5Byk0IIYQQQggheQoJASQSbZei3KGgVDmko6ODPXv24OzZs/j999+l0728vGBlZYXly5fn+Xpvb294eXnhypUrCAsLK+niFrv09PQivd7KygqmpqbFVJqSN23aNMyZMwcPHjxQ+zXJycnw9vaGp6enwvRbt26hRYsWCtNcXV1Rq1Yt7N+/v1DrLKysrCycPn0affr0yXWZZs2a4b///oOvry8GDBiAw4cPF7jchBBCCCGkDBk5kv9fvVq75SAVy2+/Ac7OwPjx2i5JuUNBqXKqTp06WLt2Lby8vBAeHo4TJ07g4MGD2LdvH/T19XN9XWJiIv78809MnjwZPXv2xJ49e5SWkUgkWL9+PVxcXGBgYAAnJyeslvtRyGu+RCLBmjVrUKNGDRgZGaFx48Y4cuRInu8lv9d4eHhg6tSpmDFjBmxsbNC9e3cAwNmzZ+Hu7g4LCwtYW1ujV69eePXqFQBg9OjRuHz5Mn744QeIRCKIRCJpk7OcGVRpaWmYNm0a7OzsYGhoCHd3d/j7+ytsf9q0aZg3bx6srKxQpUoVrFixIs/3VFwOHDgAS0tLTJkyBR8/flS72dzff/8NAwMDtGnTBgAP5Onp6eH69etYvHgxRCKRdB4A9O7dGwcPHizQOgG+b7y8vDBjxgxYWlqicuXK2LlzJ5KSkjBmzBiYmprCxcUF//zzj9L6rl+/Dj09PbRs2RJHjhxBw4YNYWRkBGtra3Tp0gVJSUnSuuzv7w8fHx/MnTtXYR3qlJsQQgghhJQhWVn8v4GBdstBKpajR/n/ffu0W45yiIJS5ZiXlxcaN26MESNGYMKECVi2bBkaN26c52sOHTqEevXqoW7duhg+fDh27doFxpjCMgsXLsTatWuxdOlSPHnyBAcOHEDlypXVmr9mzRrs27cP27dvx+PHjzFz5kwMHz4cly9fzrVM6rxm79690NfXh6+vL7Zv3w4ASEpKwqxZs3D79m2cP38eYrEY/fv3h0QiwQ8//IC2bdti/PjxCA8PR3h4OBwdHVVuf968efjrr7+wd+9e3L17Fy4uLujevTtiYmIUtm9iYgI/Pz+sX78eK1euxLlz5/Lc1/mR5JMampSUhEWLFmHdunVwcHCAubk57t+/r9a6r169iubNm0uf6+rqwtfXFwBw//59hIeH4+zZs9L5rVq1wq1bt5CWlqb2OgV79+6FjY0Nbt26BS8vL0yePBmDBw9Gu3btcPfuXXTr1g0jRoxAcnKywutOnjyJ3r17IyIiAsOGDcPYsWMRGBiIS5cuYcCAAdJ66e3tjbVr1+LEiROwsbFRWIc65SaEEEIIIWWI0CqCglJEk4Qb78OHa7cc5RGr4OLi4hgAFhcXpzQvJSWFPXnyhKWkpGihZAUjkUhYeno6k0gkCtMDAwMZANawYUOWkZGR73ratWvHNm/ezBhjLCMjg9nY2LCLFy9K58fHxzMDAwO2c+dOla/Pa35qaiozNjZm169fV5ju6enJhg0bJn3eoUMHNn36dLVf06FDB9a0adN831tUVBQDwB49eqS0HXny0xMTE5menh77/fffpfPT09NZ1apV2fr166XLu7u7K6yjZcuWbP78+bmWJSEhgc2dO5c5OzuzatWqsVGjRrELFy6wjIwMFhERwSZMmMDu37+f5/tZtGgRmzhxovR527Zt2fLly3OtC/L69u3Lxo4dqzDt2LFjzNraWuXyDx48YABYcHBwgdaZc99kZmYyExMTNmLECOm08PBwBoDduHFD4bW1a9dmp0+fZnfu3Ml120ePHmU6OjqsVatWrHXr1mzhwoUFLnd5pU49KI3K0nG3LMjKymLh4eEsKytL20UhWkT1gDBG9YBw5aIeTJjAGMDY8OHaLkmZVi7qgiZ98w2vd+PGabskxaok60FesRZ5utoLh5VNLVoAERGa326VKoBcH85q27VrF4yNjREUFIS3b9/m2QH1s2fPcOvWLRw7dgwAz54ZOnQovL29pZ1oBwYGIi0tDZ07d1a5jrzmv3z5EsnJyejatavC9PT0dDRt2lTl+tR9jaoMnRcvXmDZsmXw8/PDhw8fpJlHISEhcHV1zWUvKHr16hUyMjLg5uYmnaanp4dWrVohMDBQOq1Ro0YKr7O3t0dkZGSu6920aRPi4uJw+PBhpKSk4OjRo/jiiy8QHR0NQ0NDjBs3DnXr1s319a9fv8Yvv/yCgIAA6TRXV1e1M6VSUlJgaGioMO3evXu5ZtIZGRkBgFI2U37rBBT3jY6ODqytrdGwYUPpNCGLTn5/BQYGIiwsDJ07d4aenh46d+6Mhg0bonv37ujWrRsGDRoES0tL9O/fH5mZmbmWSZ1yE0IIIYSQMkQ4j6dMeKJJwuBJ799rtxzlEAWlCigiAnj3TtulUM/169exadMm+Pj44JtvvoGnpyf+++8/iEQilct7e3sjMzMTVatWlU5jjMHAwABbt26Fubm59CI/N3nNT0xMBACcOXMG1apVU5hnkEv6rbqvMTExUXpt79694ezsjJ07d6Jq1aqQSCRwdXUtckfoqujp6Sk8F4lEeTa/8/LygoWFhfT5p59+iu+//x4RERGoXLkydHR08tzezJkzER0dDQcHB+k0iUQCJycnheXc3Nzw/fffo3Xr1vD09ISrqytmzpwJGxsbxMbGKix7//79XINSQlNFW1vbXMukap2A6n0jP02oj/L76+TJk+jatas0yHXu3Dlcv34dPj4+2LJlCxYvXgw/Pz/UqFEj1/KoW25CCCGEEFKGCOeRGRnaLQepWIQ+jU+d0m45yiEKShVQlSplY7vJyckYPXo0Jk+ejI4dO6JGjRpo2LAhtm/fjsmTJystn5mZiX379mHjxo3o1q2bwrx+/frhjz/+wKRJk1C7dm0YGRnh/PnzGDdunNJ68prfoEEDGBgYICQkBB06dFDrfRTmNQAQHR2NZ8+eYefOnWjfvj0A4Nq1awrL6OvrI0voKDEXtWrVkvZV5ezsDADIyMiAv7+/QmfoBSUfkBKIxWKFgGBufHx84Ovri3v37kFXV/YV9vf3x9ixY/Hx40dUqlQJALB06VKsXbsW7du3h1gsxsyZMwEATZs2VRqV7tGjRxg4cKDKbQYEBMDBwUGpzyZ5qtZZWCdOnMCECROkz0UiEdzc3ODm5oZly5bB2dkZx44dw6xZs/JcjzrlJoQQQgghZcjLl/y/ipuhhJCyh4JSBVSYJnTasHDhQjDGsHbtWgBA9erVsWHDBsyZMweff/65UjO+06dPIzY2Fp6enjA3N1eYN3DgQHh7e2PSpEkwNDTE/PnzMW/ePOjr68PNzQ1RUVF4/PgxPD09850/Z84czJw5ExKJBO7u7oiLi4Ovry/MzMwwatQopfdhampa4NcAgKWlJaytrbFjxw7Y29sjJCQECxYsUFimevXq8PPzQ3BwMCpVqgQrKyuIxYp9/5uYmGDy5MmYO3curKys4OTkhPXr1yM5ORmenp4F/ViKLCMjAzNmzMDcuXPRpEkThXlmZmYAeMaTu7s7AOCzzz7D4sWLcebMGYWOy7t3746FCxciNjYWlpaWAHim0rNnzxAWFgYTExOFenD16lWlYGVOqtZZGJGRkbh9+zZOnjwJAPDz88P58+fRrVs32NnZwc/PD1FRUahfv36+61Kn3IQQQgghpAzZuJH/z2OgJEKKnaMjEBSk7VKUSzT6Xjl0+fJl/PTTT9i9ezeMjY2l0ydOnIh27drB09NTaUQ9b29vdOnSRSkgBfCg1O3bt/Hw4UMAPPtm9uzZWLZsGerXr4+hQ4cq9AeU1/xVq1Zh6dKlWLNmDerXr4/PPvsMZ86cybMZVmFeIxaLcfDgQdy5c0faZO27775TWGbOnDnQ0dFBgwYNYGtri5CQEJXrWrt2LQYOHIgRI0agWbNmePnyJf79998iBV4Ka+vWrYiOjsbUqVOV5jk6OsLY2FihXyl/f3/ExMTA3Nxcoclcw4YN0axZMxw6dEg67ZtvvsGePXtQrVo1fPPNN9LpqampOH78OMaPH59n2VStszBOnTqFVq1aSbObzMzMcOXKFfTo0QN16tTBkiVLsHHjRnz++ed5rkfdchNCCCGEEEJInmbP5v9bt9ZuOcohEcsZnahg4uPjYW5ujri4OGmmiSA1NRVBQUGoUaOGyg6cSxPGGDIzM6Grq5trn1GkYhDqwvv379GzZ08cP34cAwcOxL59+xQ6eD9z5gzmzp2LgIAApQwxedu2bcOxY8fg4+OT77bVXWde+vTpA3d3d8ybN69QrxcUpNzlUVk9JpSl425ZIJFIEBkZCTs7u0J/J0nZR/WAAFQPCFcu6oFwXiMWA/l0xUFyVy7qgib98w/QowfQvHnZaT6lhpKsB3nFWuRR7SOkHEpJScGQIUOwZcsW1KhRAwsXLsSqVasUlunZsycmTJiAd/n03K+np4ctW7aotV1115kXd3d3DBs2rNCvFxSk3IQQQgghpIyhQArRJKEvX+pgv9hRphRlSpFyhuoCAcpuPShLx92ygO6CEoDqAeGoHhCgnNQDa2sgJgbw8wNatdJ2acqsclEXNKlNG17nAKAchVAoU4oQQgghhBBCCFGXRML/q+gLl5ASI/TPS/Wu2FFQihBCCCGEEEJI2ZCWxv8bGGi3HKRiEUavX7ZMq8UojygoRQghhBBCCCGkbBg4kP9fv1675SAVS2Ym/y/0LUWKDQWlCCGEEEIIIYSUDV99xf//+692y0EqltRU/j8qSrvlKIcoKEUIIYQQQgghpGwQ+vahUdCIJj15wv9/8412y1EOUVCKEEIIIYQQQkjpl5kJvHjBH1NQipBygYJShBBCCCGEEEJKv6go4Msv+WOhjx9CNMHJSdslKLcoKEUIIYQQQgghpPRLT5c9pkwpokm7dvH/+vraLUc5REEpQgghhBBCCCGlX1qa7DFlShFNEkbdo2BosaOgFCGEEEIIIYSQ0k8+KEXBAaJJQgf7jAESiXbLUs5QUIqUKh4eHpgxY0aF3b6mREdHw87ODsHBwXku98UXX2Djxo3Fuk5NKEi5CSGEEEJIGSEEpXR0gNBQ7ZaFVCwjR8oeU0C0WFFQqpxhjKFLly7o3r270ryff/4ZFhYWePv2ba6vv3HjBnR0dNCzZ8+SLKbW5RZ8Onr0KFatWqX5AhXSvXv3oKenBw8PjwK9bvXq1ejbty+qV68unTZz5kwMGDBAYbklS5Zg9erViIuLK9Q6i2LMmDFYsmRJnsvcvHkTXbp0gZubG5o1a4bbt28DKFi5CSGEEEJIGSEEpWrUAOzstFsWUrGEhPD/VatqtxzlEAWlyhmRSITdu3fDz88Pv/zyi3R6UFAQ5s2bhy1btsDBwSHX13t7e8PLywtXrlxBWFiYJopcrNLlOz8sBCsrK5iamhZTaUretGnTMGfOHDx48EDt1yQnJ8Pb2xuenp4K02/duoUWLVooTHN1dUWtWrWwf//+Qq2zsLKysnD69Gn06dMnz+WaNWuG//77D76+vhgwYAAOHz5coHITQgghhJAyRAhKGRhotxyk4hH6lNq9m+pfMStXQam1a9dCJBJViOZXeXF0dMQPP/yAOXPmICgoCIwxeHp6olu3bhgxYkSur0tMTMSff/6JyZMno2fPntizZ4/SMhKJBOvXr4eLiwsMDAzg5OSE1atXqzVfIpFgzZo1qFGjBoyMjNC4cWMcOXIkz/eS32s8PDwwdepUzJgxAzY2NtIMsbNnz8Ld3R0WFhawtrZGr1698OrVKwDA6NGjcfnyZfzwww8QiUQQiUTSJmc5M6jS0tIwbdo02NnZwdDQEO7u7vD391fY/rRp0zBv3jxYWVmhSpUqWLFiRZ7vqbgcOHAAlpaWmDJlCj5+/Kh2s7m///4bBgYGaNOmDQAeyNPT08P169exePFiiEQi6TwA6N27Nw4ePFigdQJ833h5eWHGjBmwtLRE5cqVsXPnTiQlJWHMmDEwNTWFi4sL/vnnH6X1Xb9+HXp6emjZsiWOHDmChg0bwsjICNbW1ujSpQuSkpIAAPrZo1/4+/vDx8cHc+fOLVC5CSGEEEJIGeLgAHh5AY8fA1OmAKmp2i4RqSiEjvWF4BQpNuUmKOXv749ffvkFjRo10nZRSoVRo0ahc+fOGDt2LLZu3YqAgACFzClVDh06hHr16qFu3boYPnw4du3aBcaYwjILFy7E2rVrsXTpUjx58gQHDhxA5cqV1Zq/Zs0a7Nu3D9u3b8fjx48xc+ZMDB8+HJcvX861TOq8Zu/evdDX14evry+2b98OAEhKSsKsWbNw+/ZtnD9/HmKxGP3794dEIsEPP/yAtm3bYvz48QgPD0d4eDgcHR1Vbn/evHn466+/sHfvXty9excuLi7o3r07YmJiFLZvYmICPz8/rF+/HitXrsS5c+fy3Nf5keTTeV5SUhIWLVqEdevWwcHBAebm5rh//75a67569SqaN28ufa6rqwtfX18AwP379xEeHo6zZ89K57dq1Qq3bt1CmnzHkvmsU7B3717Y2Njg1q1b8PLywuTJkzF48GC0a9cOd+/elQZKk5OTFV538uRJ9O7dGxERERg2bBjGjh2LwMBAXLp0CQMGDFCol97e3li7di1OnDgBGxubApWbEEIIIYSUIXXqABs28Mc//0xBKaI5QlAqMZE6Oi9urBxISEhgtWvXZufOnWMdOnRg06dPV/u1cXFxDACLi4tTmpeSksKePHnCUlJSirG0JUMikbD09HQmkUik096/f89sbGyYWCxmx44dy3cd7dq1Y5s3b2aMMZaRkcFsbGzYxYsXpfPj4+OZgYEB27lzp8rX5zU/NTWVGRsbs+vXrytM9/T0ZMOGDZM+l//81HlNhw4dWNOmTfN9b1FRUQwAe/TokdJ25MlPT0xMZHp6euz333+Xzk9PT2dVq1Zl69evly7v7u6usI6WLVuy+fPn51qWhIQENnfuXObs7MyqVavGRo0axS5cuMAyMjJYREQEmzBhArt//36e72fRokVs4sSJ0udt27Zly5cvZ4yprgvy+vbty8aOHasw7dixY8za2lrl8g8ePGAAWHBwcK7lUbXOnPsmMzOTmZiYsBEjRkinhYeHMwDsxo0bCq+tXbs2O336NLtz506e2z569CjT0dFhrVq1Yq1bt2YLFy4sULnLs/zqQWlVlo67ZUFWVhYLDw9nWVlZ2i4K0SKqB4QxqgeEKxf1ICuLMT4GGmORkdouTZlVLuqCJtWqJat3ISHaLk2xKcl6kFesRV65yD2bMmUKevbsiS5duuCbb74p0W212NECEYkRJboNVapUqoLbE24X6DV2dnaYOHEijh8/jn79+uW57LNnz3Dr1i0cO3YMAM+eGTp0KLy9vaWdaAcGBiItLQ2dO3dWuY685r98+RLJycno2rWrwvT09HQ0bdpU5frUfY2qDJ0XL15g2bJl8PPzw4cPH6SZRyEhIXB1dc1lLyh69eoVMjIy4ObmJp2mp6eHVq1aITAwUDotZ3aevb09IiMjc13vpk2bEBcXh8OHDyMlJQVHjx7FF198gejoaBgaGmLcuHGoW7durq9//fo1fvnlFwQEBEinubq6qp0plZKSAkNDQ4Vp9+7dQ+PGjVUub2RkBABK2Uz5rRNQ3Dc6OjqwtrZGw4YNpdOELDr5/RUYGIiwsDB07twZenp66Ny5Mxo2bIju3bujW7duGDRoECwtLQEA/fv3R6Zw16IQ5SaEEEIIIWVIQgIQGyt7nst5ICHFTr6u0eh7xarMB6UOHjyIu3fvKvTzk5e0tDSF5jzx8fEAeHOpnE2mJBIJGGPSPwCISIzAu4R3xVT6gmE5mtLlNl9+OR0dHejq6ub72l9//RWZmZmoKjeaAGMMBgYG2LJlC8zNzaVBB/n9IS+v+QkJCQCA06dPo1q1agrzDAwMFJYXXq/ua4yNjZW217t3bzg7O2PHjh2oWrUqJBIJGjZsiLS0NIX9pOp95PzMVS0nPy3n/hWJRNK6o8rUqVNhYWEhfd6+fXts3LgRERERqFy5MnR0dKTbUGXmzJmIjo5W6LBeIpHAyclJ+pp79+5h6dKl0mZ4J06cwJkzZ7Bjxw7Y2NggNjZWYf33799Ho0aNVG4zOjoaAGBjY5NrmVStM7d9o6o+ZmVlSaedOHECXbt2hUF2B4I+Pj64fv06fHx8sGXLFixevBg3b95EjRo1VJalIOUu71QdE0o74bul6phMCk44FtG+rNioHhCA6gHhynw9+OMPiCdOlD6VpKVRU6pCKvN1QcNElStD9OYNAECSnl5u6l1J1gN111mmg1KhoaGYPn06zp07pzJLQ5U1a9bg66+/VpoeFRWF1BxtkjMyMiCRSJCZmSnNxqhsUlnptZpQ2aRyrhkhAL+Qy8rKAsAv/AVCJcvrtZmZmfjtt9+wfv16dOnSRWHe4MGD8fvvv2PChAnSzsbPnTuHsWPHKq0nr/l16tSBgYEBgoKCFDKP5MsgvA+hvOq8Rn55QXR0NJ49e4Zt27bB3d0dAKR9JmVlZSEzMxN6enoKn6v8fhTW5+zsDH19fVy5cgXDhg0DwOuEv78/vLy8ct2+cDGd2z6vVKmSynl2dnb5flbnzp2Dr68vbt26BV25Tvbu3LmD8ePH48OHDzA3N0f9+vXx5MkT6XtcuXIljh8/jszMTDRq1AgHDhxQ2M6jR4/Qt29fldt++PAhHBwcYGFhkWvZVK1T1b4R9k/OacLnAvCg1Lhx4xSWad26NVq3bo1FixbBxcUFf/31V74DGqhT7vIst2NCaZeZmQmJRILo6Gjo6elpuzhlnkQiQVxcHBhjEIvLTTeSpICoHhCA6gHhyno9MI6Ohpnc8+iICGSpeR1IFJX1uqBxJ07ArkEDiGNjEf3+PbLkkgzKspKsB0KSSX7KdFDqzp07iIyMRLNmzaTTsrKycOXKFWzduhVpaWnSrBPBwoULMWvWLOnz+Ph4ODo6wtbWFmZmZgrLpqamIiEhAbq6utIAQEGb0Glazos4sVgszU7JzenTpxEbG4vx48fD3NxcYd6AAQOwZ88efPXVV6hUqRLmzZuHhQsXwtDQEG5uboiKisLjx4/h6emZ7/zZs2dj7ty5EIlEcHd3R1xcHHx9fWFmZoZRo0YBgHQ0PF1dXVhaWub7GvnlBba2trC2tsauXbvg4OCAkJAQLFy4EIAsc6x69erw9/fH27dvUalSJVhZWUn3lbA+c3NzTJo0CQsXLoStrS2cnJzw3XffITk5GePHj4eurq7K7YvFYojF4jz3eWFkZGRgzpw5mDNnDlq0aKEwz8rKCgAQEBAgbW7p6OiIt2/f4u+//0bPnj2lnbl//vnnWLJkCRISEqTN4CQSCV6+fInIyEiYmJgo1IPr16+ja9eueb4fVetUtW8AqNw3wucSGRmJO3fu4OTJk9DV1YWfnx/Onz+Pbt26wc7ODn5+foiKisInn3yS7/5Vp9wVQVkL7Ojq6kIsFsPa2lrtmw0kdxKJBCKRCLa2tnTCWYFRPSAA1QPClfl6kD3yssDa3Byws9NSYcq2Ml8XtECU3ZLD2sys3NS7kqwH6p7Ll+mrtc6dO+PRo0cK08aMGYN69eph/vz5SgEpgDf7EpoFyRMCCTmnCRfWpT3TgDEmLaN8WVVNy2nXrl3o0qWLQpMywaBBg/Ddd9/h0aNHaNSoEZYtWwY9PT0sX74cYWFhsLe3x6RJk6Trz2v+N998Azs7O6xduxavX7+GhYUFmjVrhkWLFimVWXiuzmtyfj46Ojo4ePAgpk2bhoYNG6Ju3br48ccf4eHhIV127ty5GDVqFD755BOkpKQgKCgI1atXV1rfunXrwBjDyJEjkZCQgBYtWuDff/+VBoFUbT/nvi8uP/30E6Kjo+Hl5aW0bicnJxgbG+PBgwfS99myZUtcunQJ27dvx/Xr16WvadSoEZo1a4bDhw9jYnb68zfffIP58+djzZo1mDNnDr777jsAPDB7/PhxnD17Ns/3o2qdwj7I+bq8pp0+fRqtWrWCra0tAMDc3BxXr17FDz/8gPj4eDg7O2Pjxo3o0aNHnvtK3XKXZ7kdE0o7oS6oOiaTwqH9SQCqB4SjekCAMl4P0tMVnoqzsoCy+D5KiTJdF7Qh+2a3WCIpV/WupOqBuusTsbLU2YgaPDw80KRJE2zevFmt5ePj42Fubo64uDiVmVJBQUGoUaNGqb9jLzSTErJ3SMUl1IVDhw5h2rRpWLlyJaZMmaKwzJkzZzB37lwEBATkebDYtm0bjh07Bh8fn3y3q+4689KnTx+4u7tj3rx5hXq9oCDlLq/K6jGhLB13ywKJRILIyEjY2dnRCWcFRvWAAFQPCFfm68GKFcDXXwPduwPbtgHVqillTxH1lPm6oGkeHsDly/zxjRtAmzZaLU5xKcl6kFesRV6ZzpQihOSuTp06sLa2VshcEvTs2RMvXrzAu3fvpM36VNHT08OWLVvU2p6668yLu7u7tP+uoihIuQkhhBBCSBkhDFhVrx6Qz6A3hBSrmzf5f3d3ILu7ElI8yl1Q6tKlS9ouAiGlws8//4zvvvsu1z6V8usoHADGjRtXoG2qs868FDVDSlDQchNCCCGkAO7cAd6+Bfr21XZJSEUjBKVUdMdCSIkSBk46dAiwt9duWcoZytMjpJx59eoVPvnkE5iYmKAvnSwSQgghpLi1aAH06wcEBGi7JKSiadsWmDAB8PMD5s0DXr7UdolIRcAYkD2qNSr4IEolgfYoIeVMrVq18Pjx4wo/6hwhhBBCStjz54Crq7ZLQSqSwYP5X6NGwHffAd26AS4u2i4VKe+EgBQgC1CpGFSNFA5lShFCCCGEEEIKTm40YkI0Sk+P/xeaVBFSkuTrWeXKwJkz2itLOUSpFIQQQgghhBD1icWARALUravtkpCK5uNHXveEAeQzMrRaHFJB5Ax+UjC0WFGmFCGEEEIIIUQ9WVk8KAAA+vraLQupeEaPBqytgXv3+HMKShFNyMri9U5A9a5YUVCKEEIIIYQQoh75izHqv5JomjD6noAyVogmmJsDHz4AXbvy51TvihUFpQghhBBCCCHq0dcHbG3544sXtVsWUvHkDEpRxgrRJCEQT/WuWBXp9sbLly/h6+uLt2/f4sOHDzA2NoatrS0aNmyIdu3awcjIqLjKSQghhBBCCNE2sRioVw+IiqJsAaJ5FJQi2kQd7JeIAgelQkND8euvv2LPnj14+/YtAIAJHc1lE4lE0NXVRbdu3TBx4kT07NkTIpGoeEpMCCGEEEII0R6hL6n0dO2Wg1Q8QlBqyxbAwwNwcNBqcUgFER4OfPklcOkSf07B0GKldlAqKioKy5cvx6+//orMzEy4uLhg+PDhaNGiBSpXrgwrKyukpKQgJiYGz549w82bN3HhwgX8/fffqF27NtavX48+ffqU5HshhBBCCCGElKTYWOD8ef6YglJE04Q6V68e4Oqq3bKQiiMxURaQ6tMHcHbWanHKG7WDUrVq1YJYLMa0adMwfPhwNGnSJN/XJCUl4ciRI/j111/Rv39/bNiwATNnzixKeQkhhBBCCCHaEhMje0xBKaJpQqaUgYF2y0EqFqG5npUVcOKEdstSDqkdlJo+fTpmz54NCwsLtVduYmKCUaNGYdSoUbhw4QLi4uIKU0ZCCCGEEEJIaSAfiKKgFNG0fv2Ad+8Af3/gwgWgSxfAzU3bpSLlnRCUohFHS4Tae3XVqlVF2lCnTp2K9HpCCCGEEEKIlsn3pUJBKaJp69bx/2PGAHv2AIaGFJQiJY+CUiVKrO0CEEKIJvz4448QiUTl+o8QQggpcfKBqOrVtVYMUsEJwQEaBY1oglDPwsL4QA8rV2q3POVMgYNScXFxCAgIUJr+999/F0uBCCGkuEVERCAwMBCMsXL9RwghhJQ4IVOqZk1gwADtloVUPAkJPDCqp8ef0yhoRBPkg58ZGZQlWswKFJS6cuUKHB0d0bhxY7Rt2xZBQUHSeStWrCjushFCSLE4c+YMevXqpe1iEEIIIWWfcDGmr6/dcpCKydKSd3IeFcWfU1CKaAJjvKmooIQy9JKTgcGDgREjgE2bSmQTpVKBglILFizA+PHj8ccffyAhIQFt27bFw4cPAYDu0hNCSq3z58+jc+fOBX5daGgoPDw80KBBAzRq1AiHDx8ugdKVnXIQQggh0iCAkKlCiKZkZfE/ADAx4f+p+R7RhHbtgJQUYN48/ryEgqFJSUDkkcv4uP8U7v8TXiLbKI0KFJT6+PEjNm7ciCFDhuDOnTtwd3dHt27d8OLFC+rPhBBSKqWmpgIADOXvbqhJV1cXmzdvxpMnT+Dj44MZM2YgKSmpuItYZspBCCGEoHVroH9/4NEjYOZMbZeGVCRpabLHlSrx/5QpRTSphPsyS0sDVmMxTqEPXBNvlsg2SqMCBaWMjY2ljw0MDHD48GH06NED3bp1Q0xMTLEXjhBCiurChQuFHv3T3t4eTZo0AQBUqVIFNjY2WjnWlZZyEEIIITA1BRo35o9TUrRbFlKxyPfjI2RKUVCKaJIQlCqhepeaChiC31BHIW6ol1UFCkoZGRnh2bNn0ucikQje3t7o2LGjQv9ShOTGw8MDM2bMKHPrFjDGMGHCBFhZWUEkEuH+/fslur3C6tKlS4nvi/xo4vNQx+nTp9GzZ88ir+fOnTvIysqCo6NjMZRKc+WIjo6GnZ0dgoODS7Zgavjiiy+wceNGbReDEEJIURkY8P/U2S/RJPlMqSlTgJs3gblztVee4nboEM9C3LZN2yUhOfn5Ab16yUbdK6FMKfmglMiIglIq/fjjj9DP0amhEJg6cOBAsRaMFM3o0aMhEokwadIkpXlTpkyBSCTC6NGjNV6uo0ePYtWqVQBKT9CiIM6ePYs9e/bg9OnTCA8Ph6ura67L3rhxAzo6OsUSECnNcvsc5T9rbYqIiIC9vX2u8+/duwc9PT14eHjkukxMTAxGjhyJHTt2lEAJS7Ycq1evRt++fVG9GIbtHjNmDJYsWZLnMjdv3kSXLl3g5uaGZs2a4fbt29J5S5YswerVqxEXF1fkshBCCNGSR4+A777jjykoRTRJCEoZGABOTrwpqZOTdstUnF68AI4fB+7e1XZJSE5hYcCZM/xx585AvXolspm0NGAtFmA2NuCjbe0S2UZpVKCgVNOmTVGjRg2l6SKRCEOHDi22QpHi4ejoiIMHDyJFLrU6NTUVBw4cgJOWDuBWVlYwNTXVyraLw6tXr2Bvb4927dqhSpUq0BVSOFXw9vaGl5cXrly5grCwMA2WsnikF/FEszR81vfu3UPTpk3zXGbatGmYM2cOHjx4oHJ+Wloa+vXrhwULFqBdu3ZqbdfDwwN79uwpUFlLohzJycnYtWsXPD09C1QWVbKysnD69Gn06dMnz+WaNWuG//77D76+vhgwYIBCp+yurq6oVasW9u/fX+TyEEII0ZK7dwGhCTkFpYgmyQelyiPhfclnhJHSQciM+vRT4L//gFmzSmQzqanA7xiO7zEbqTYOJbKN0qhAQSl5oaGhuHDhApKTk6XTJBIJ1q1bBzc3N3Tp0gVnhGgi0YpmzZrB0dERR48elU47evQonJycFC7Uz549C3d3d1hYWMDa2hq9evXCq1evFNaVkJCA//3vfzAxMYG9vT02bdqklCHj4eGBadOmYd68ebCyskKVKlWwYsUKhfUIrxk9ejQuX76MH374ASKRCCKRSNq8qHr16ti8ebPC65o0aaKwrqSkJIwcORKVKlWCvb29UpMgiUSCNWvWoEaNGjAyMkLjxo1x5MiRPPdXWloapk2bBjs7OxgaGsLd3R3+/v7S+aNHj4aXlxdCQkIgEonyzDxJTEzEn3/+icmTJ6Nnz54qAxQSiQTr16+Hi4sLDAwM4OTkhNWrV+c7rzDvT53lPTw8MHXqVMyYMQM2Njbo3r07gLzrR16fo3z9yG/fCsvnV38K6tSpU+jdu3eu8w8cOABLS0tMmTIFHz9+VGrixhjD6NGj0alTJ4wYMaJIZclLSZXjn3/+gYGBAdq0aSOd5uHhAS8vL8yYMQOWlpaoXLkydu7ciaSkJIwZMwampqZwcXHBP//8o7Cu69evQ09PDy1btgQAHDlyBA0bNoSRkRGsra3RpUsXJCUlSbNp/f394ePjg7k50up79+6NgwcPFmT3EEIIKU3kA1EUlCKaZGQEDBkC9O0L3LsHbNgAnDyp7VIVH+Gc6bfftFsOokwISuWRkFAcssdnAlChupQqfFBq6dKlGDx4MPTkhoNdvXo1Fi5ciBs3buDChQvo16+f0oUn0ayxY8di9+7d0ue7du3CmDFjFJZJSkrCrFmzcPv2bZw/fx5isRj9+/eHRCKRLjNr1iz4+vri5MmTOHfuHK5evYq7KlJL9+7dCxMTE/j5+WH9+vVYuXIlzp07p7TcDz/8gLZt22L8+PEIDw9HeHh4gfrqmTt3Li5fvowTJ07Ax8cHly5dUijPmjVrsG/fPmzfvh2PHz/GzJkzMXz4cFy+fDnXdc6bNw9//fUX9u7di7t378LFxQXdu3eXdij9ww8/YOXKlXBwcEB4eHiedfvQoUOoV68e6tati+HDh2PXrl1gjCkss3DhQqxduxZLly7FkydPcODAAVSuXDnfeYV5f+ouv3fvXujr68PX1xfbt28HkHf9UPdzzG/fym9fnfqjrvv370s7CM8pKSkJixYtwrp16+Dg4ABzc3OlPsJ8fX3x559/4vjx42jSpAmaNGmCR48eFbo8mi6Hr68vmjdvrjR97969sLGxwa1bt+Dl5YXJkydj8ODBaNeuHe7evYtu3bphxIgRCjcdTp48id69e0MkEiE8PBzDhg3D2LFjERgYiEuXLmHAgAHSOu7t7Y21a9fixIkTsLGxUdh2q1atcOvWLaTRXUBCCCmb5Dv4paAU0SQHB+DPP4F9+wBfXx7EoexrogkaDEq54ypawQ/GOhXoXJkVkouLCxsyZIj0uUQiYXZ2dqx+/fosNDSU+fv7M3NzczZ48ODCbkIj4uLiGAAWFxenNC8lJYU9efKEpaSkKM5ITMz9ryDLJiert6waJBIJS09PZxKJhDHG2KhRo1jfvn1ZZGQkMzAwYMHBwSw4OJgZGhqyqKgo1rdvXzZq1CiV64qKimIA2KNHjxhjjMXHxzM9PT12+PBh6TIfP35kxsbGbPr06dJpHTp0YO7u7grratmyJZs/f77CMsJr5B/Lc3Z2Zps2bVKY1rhxY7Z8+XLGGGMJCQlMX1+fHTp0SDo/OjqaGRkZsenTp7PU1FRmbGzMrl+/rrAOT09PNmzYMJXvOTExkenp6bHff/9dOi09PZ1VrVqVrV+/Xjpt06ZNzNnZWeU65LVr145t3ryZMcZYRkYGs7GxYRcvXpTOj4+PZwYGBmznzp1Kr81rHmMs3/cnkUjYp59+yqZNm6bW8oIOHTqwpk2b5vvectaP3D5HYbq6+1ad+qPKkydP2Lp165Smh4WFsa+++irX1y1atIhNnDhR+rxt27bSOlZUHTp0YLt371Zr2ZIqh0QiYb1792ZjxoxRKpv8fs7MzGQmJiZsxIgR0mnh4eEMALtx44Z0Wu3atdnp06cZY4zduXOHAWDBwcFK2z169CjT0dFhrVq1Yq1bt2YLFy5UmP/gwYNcX8tYHsddUihZWVksPDycZWVlabsoRIuoHhDGirEebNrEGMD/5s0rlrIRzSk3x4Nt23gd7NdP2yUpPsL3qvCX6AVSbuqCJuzaJftsLCwY++KLEtnMX38xlgEdxgD20+J3JbKNnEqyHuQVa5FX6FBfZGQknJ2dpc/v37+PqKgorFixAg4ODnBwcEC/fv3yzEwpsypVyn1ejx6yTtAAwM4OkMs2UNChA3Dpkux59erAhw/Ky+XIsCkIW1tbafMxxhh69uyplLnw4sULLFu2DH5+fvjw4YM0QyokJASurq54/fo1MjIy0KpVK+lrzM3NUbduXaXtNWrUSOG5vb09IiMjC11+VV69eoX09HS0bt1aOs3KykpanpcvXyI5ORldu3ZVeF16enqu/Qu9evUKGRkZcHNzk07T09NDq1atEBgYWKDyPXv2DLdu3cKxY8cAALq6uhg6dCi8vb2lnVgHBgYiLS0NnTt3Vnp9XvMK8/4KsryqrJr86kd+CrJvC1p/rl69ilmzZuH169eYNWuWQh9fZ86cQa9evVS+7vXr1/jll18QEBAgnebq6lro0RS//fZbfPvtt9LnKSkpuHnzJqZOnSqd9uTJE6W+3Iq7HDmlpqbCUEXur/x+1tHRgbW1NRo2bCidJmTlCfs+MDAQYWFh0jrZuHFjdO7cGQ0bNkT37t3RrVs3DBo0CJaWlujfvz8y8xiRxMjICAAUsrAIIYSUIUJ21MiRwLp12i0LqViEVhxiMSC01pHP3COkpMif2378CCQklMhm0pIyoYssAIBupYrTfq/QQSmJRKLQvOvSpUsQiUTo1KmTdFq1atUQERFRtBKSIhs7dqz04vinn35Smt+7d284Oztj586dqFq1KiQSCVxdXQvV0bV8c06Ad4IvX0/UIRaLlZq6ZRTgBycxMREAD0pUq1ZNYZ6BBjpG9Pb2RmZmJqpWrSqdxhiDgYEBtm7dCnNzc+mFuSp5zQMK/v4KsryJiYnS64uzfuSnoPWnffv2uHjxIipXroxr164pjFx34cIFhaar8mbOnIno6Gg4OMg6EJRIJIUeAGDSpEkYMmSI9Pn//vc/DBw4EAMGDJBOk68PJVWOnKytrfHx40el6ar2s/w0kUgkLQvAm+517dpVGuDS0dHBuXPncP36dfj4+GDLli1YvHgx/Pz8VA6GIU9osmlra1vo90UIIUSLhHOyHCNyE1LifHyAzz8HWrQAvLz4tDxuhBFSbHLWsxIKhmYkyprs6VSgoFSh+5RycnLCrVu3pM+PHz8Oe3t7heyZiIgIWFhYFKmApVJiYu5/f/2luGxkZO7L5uhIGMHBqpcros8++wzp6enIyMiQdl4tiI6OxrNnz7BkyRJ07twZ9evXR2xsrMIyNWvWhJ6enkIfSnFxcXj+/HmRyqWvr4+srCyl6ba2tggPD5c+j4+PR1BQkPR5rVq1oKenBz8/P+m02NhYaXkaNGgAAwMDhISEwMXFReEvt36ratWqJe1LSZCRkQF/f380aNBA7feUmZmJffv2YePGjbh//77078GDB6hatSr++OMPAEDt2rVhZGSE8+fPK60jr3mFeX+F2R8CdepHbp+joLj2bW4qVaqELl264NSpU9JpqampEIlEKoN0Pj4+8PX1xb179xQ+I29vb7x580ZlECc/VlZWCvvVyMgIdnZ2CtNyjtRYEuXIqUmTJnjy5EmR13PixAn07dtXYZpIJIKbmxu+/vpr3Lt3D/r6+tLswLwEBATAwcFBKWOTEEJIGSHclMpxg4OQEifUPR0dWd8+5SlTql49/t/HR7vlIMomTwaysmSd0JdQMDQzUdbTuX6lcjrKpAqFzpQaOHAgVq9ejUGDBsHQ0BDXrl1TaKoC8OYqNWvWLHIhSx0V2SQaX7YAdHR0pM2kdHR0FOZZWlrC2toaO3bsgL29PUJCQrBgwQKFZUxNTTFq1CjMnTsXVlZWsLOzw/LlyyEWi6UZFYVRvXp1+Pn5ITg4GJUqVYKVlRXEYjE6deqEPXv2oHfv3rCwsMCyZcsUyl2pUiV4enpi7ty5sLa2hp2dHRYvXgyxWCwt75w5czBz5kxIJBK4u7sjLi4Ovr6+MDMzw6hRo5TKYmJigsmTJ0vfo5OTE9avX4/k5GR4enqq/Z5Onz6N2NhYeHp6wtzcXGHewIED4e3tjUmTJsHQ0BDz58/HvHnzoK+vDzc3N0RFReHx48fw9PTMc15+72/kyJEK2y3M/hCoUz9y+xyLe9/mpU+fPli3bp10FMbz58+rbP6YkZGBGTNmYO7cuUodoJuZmQHgTZGFjCs3Nzd8//33aN26NTw9PeHq6oqZM2cWubwFKce9e/ewYMEC/PvvvwB4gOjMmTPYsWNHvtvp2rUrlixZgtjYWFhaWhaqrJGRkbh9+zZOyo1u4+fnh/Pnz6Nbt26ws7ODn58foqKiUL9+/XzXd/XqVXTr1q1QZSGEEFIKjBvHz1nnzwfu3AHkbhISUqKEQVIMDMpn8z0h0GFsrN1yENXEYtmQeCVU74SgVDr0YGCsk8/S5Uehg1Jz5syBj48Pjh49CoD3USI/fPubN29w69YtpQtYoh3ChW5OYrEYBw8exLRp0+Dq6oq6devixx9/VGgGBQDff/89Jk2ahF69esHMzAzz5s1DaGioyv5q1DVnzhyMGjUKDRo0QEpKCoKCglC9enUsXLgQQUFB6NWrF8zNzbFq1SqFTCkA+O6775CYmIjevXvD1NQUs2fPRlxcnHT+qlWrYGtrizVr1uD169ewsLBAs2bNsGjRolzLs3btWkgkEowYMQIJCQlo0aIF/v333wJdzHt7e6NLly5KASmAB6XWr1+Phw8folGjRli6dCl0dXWxbNkyhIWFwd7eHpMmTQKAPOcV5v0VZn8A6tWP3D5HecWxb/PSq1cvTJgwAYGBgahfvz7OnDmD5cuXKy23detWREdHKwXQAcDR0RHGxsYKQamlS5di7dq1aN++PcRicbEEpApajoYNG0qznTIzM7Fy5UqcPn1are00bNgQzZo1w6FDhzBx4sRClfXUqVNo1aqVQmaTmZkZrly5gs2bNyM+Ph7Ozs7YuHEjPv/88zzXlZqaiuPHj+Ps2bOFKgshhJBSwNEREPqJzDGKLiElSlVQqjw136tThzeLVXEdQUqJEg6GZiXxoFQqDKGBXmdKDRHL2XlPAQkd9NavX18hm+XNmze4f/8+WrRoodSPTWkSHx8Pc3NzxMXFKQVuUlNTERQUhBo1ahQp+KIJjDFkZmZCV1e3SNlL6kpKSkK1atWwcePGYst2IcVD03WhtGjbti369++PefPmYdCgQThy5EixrLd58+awsLDA2bNnlfpi0pR27drhwIED+PvvvxEREYGVK1fm+xqhHvz777+YN28eAgICFDLY1NWnTx+4u7tj3rx5hSm6gm3btuHYsWPwySMtvSwdd8sCiUSCyMhI2NnZFerzJ+UD1QMCFHM98PcHWrUCnJyAN2+Kp4BEI8r08cDbm2fq9eoF7NoFPHoEWFoCuQxkVOaEhACLF/NMxO3bS3xzZbouaNrRo8Cff/LA6IkTvF8zua5tistPXz3GlG2uiIIN7p6NQo6ed0pESdaDvGIt8gqUKfXzzz+jb9++CkGm3EbfcnZ2Vhidj5Rt9+7dw9OnT9GqVSvExcVJL4pz9jNDiLb07dsXJ0+eRJcuXXIdZbGg/P39ERMTA2dnZ60FpACgVatWuHjxIrZt24br168X6LU9e/bEy5cv8e7du3z7EFPF3d0dw4YNK/DrVNHT08OWLVuKZV0kh1mzgLdv+cls48baLg0hpDw7dw44eJA/TkvLe1lCipN8ppStLSA3wFa5kJAA7N8P2NhoJChFCuDxY+DQIX6O1aaNrP+vYhajY4v5WIsM6KFvBbo3W6BQ2NSpU+Hk5ISWLVti9erVePToUUmVi5RCGzZsQOPGjdGlSxckJSXh6tWr1FkxKTX69OmDGzduYNeuXejdu3eR1/fu3TuMGzcOFy5cQHBwsDQrVBtatWqFOXPmYNKkSTA1NS3w62fMmFGogBQAzJs3r9CvzWncuHEKg2GQYnTuHHD4MBAdre2SEELKuz//5FkqgKzjaUI0QT4oVR4J7ys1Ne/liOYJzUTd3YEbN4BcRvguqmgdO6zHfGzCrHJbzVUpUFDK398fixYtQnp6OpYuXYomTZqgVq1amD17Ni5fvpzn0O2kbGvatCnu3LmDxMRExMTE4Ny5c2jYsKG2i0WIVIMGDVCzZk38888/aNSoUZHWlZKSgsGDB2PLli2oUaMGFi5ciFWrVhVTSQuuTp06sLa2LnS/UOVCamqxjEZabgknsNTkkRBS0uT7UqGgFNGk6tWBHj2AJk2AiAhg2zbZaGhlXUoKIAwYQ+c7pY8QlNItdJfcapFPPq1Ip3QF2qvNmzdH8+bNsWrVKgQHB+PYsWM4efIkfvzxR2zevBlWVlbo1asX+vbti27dusGYRg4ghGhQ7969kV4MJ8hGRkYKzeQGDx6MwYMHF3m9hfXzzz/ju+++g24J/xCWWllZQO3aAGPA69e8E1Ci6OVL/v/+faBdO60WhRBSzsn/zlJQimhS//78D+DZKl99BdSsCYwYod1yFYfkZMVO2yUSPtobKR00FJQSx8WiGV4jFpYwNKxZotsqTQpd06tXr46ZM2fi4sWLeP/+PXbv3o327dvjyJEjGDBgAGxsbNC7d2/s2rULkZGRxVlmQghRaezYsRg3bpy2i1FsXr16hbp168LExKRi998WEMD7S3r3DvjwQdulKd1u3dJ2CQgh5Z18plTLlvyGASGaVsKjoGlcSoricwr4li5CUOrxY8DBAWjevEQ2UyvkIu6gBfZiVIVqvlcsoT4rKyuMHDkSI0eORFpaGs6dO4cTJ07g9OnTOHPmDMRiMdq0aYNr164Vx+YIIUSl3AZeKKtq1aqFZ8+eabsY2ufry/9Xrco7NiW5qyjN6JOSeI67lZW2S0JIxSNcLO/cyUdCI0QbyntQKjW1YrXfKu2EoJRYzG+SltD5liiNd8eQCsMK9fEXe06ggYEBevXqhZ07dyIsLAzXrl3D7NmzEU2drxJCCCmMq1f5/0mTZCehRLWKEpSqXBmwtuYjFRFCNEsIAtDxmGjajBmAsTGwerWsGZV8k7eyLGdQika2LF2EemZkpPi8uGX3EZoGAwpKFReRSIR27dph3bp1CAwMLMlNEUIIKY8YkwWl3N21W5bSKmcfFOWdRMIzpQDgyRPtloWQikjIlKL+/YimJSfz4A1j5TdTqlIlfsPFzk675SGKNm0C4uOBJUv48xKqd6J0WaYUNd8rgKioKDx58gRhYWHIyOXDGTlyZFE3QwghpCIKCeFp0gDwzz9ArVqAk5N2y1Ta6OgAK1cCy5aV32Gy5cnfTRaJtFcOQiqq774DoqKAAQOA2bOBu3eBKlW0XSpSESQn8/9GRuU3KOXgwANTpHTR1+d/pqb8eQllSokpKFUwKSkp8PLywm+//YbMXD4UxhhEIhEFpQghhBTOnTuyx999B/TsSUGpnEQiwNycP86Z/l8eCRclhBDtaNaM/2cMCA+nZkZEc4Qs2UqVyl/zPT09oE4dPppgcXn6FLCwoKBxcSrhYKgQlEoXGUJHp0Q2USoVOig1bdo07Nq1C40aNcKgQYNgb2+v8eHK16xZg6NHj+Lp06cwMjKSNhWsW7dusW6H0agihBCiEUrH2wEDgLAwfudQIpG2tSc5GBvz/xUtYEMdnROiPfr6PBBOo4QRTRGCUiYmfOCTkyfLT99mbm7As2fA4sXAmDHA0qVFC1C9ewfUr88f07Vs0W3bBvj7Ax078uclFAzVyQ5KZehWoA6lUISg1F9//YUWLVrgxo0b0NFSGO/y5cuYMmUKWrZsiczMTCxatAjdunXDkydPYGJiUuT1C+8rPT0dRkKnZoQQQkpMcnZQRU/+JNPeng877udHQSlVwsOB338HXF15Nll5Z2tLJ9iEaNOhQ7xvlbg4/pyCUkRTEhP5fxMTPjJd797aLU9JOHQIePmSj2xZlKDU48fFVyYCXLwIHD4MVK8ONGzIM/UYK/ZuBK7rdUA0JAg0bI2Jxbrm0q3QQamsrCx4eHhoLSAFAGfPnlV4vmfPHtjZ2eHOnTv49NNPi7x+XV1dGBsbIyoqCnp6ehCLS7Rf+CJhjCEzMxO6uroQUR8bFRrVBQKUvXrAGENycjIiIyNhYWGh/NsiDEFCzUSURUcDly7xYE0xZwoTQoiSZct4RoeAglKFc/UqzwDu0EHbJSk75JvvlVdCR0JFPd8RmvVXr1609RBOyIyyswMePiyxzVwUd8Z+dIaDeYltolQqdFCqZcuWePHiRXGWpcjisu/YWBVTOr9IJIK9vT2CgoLw5s2bYllnSWGMQSKRQCwWl4kLUFJyqC4QoOzWAwsLC1QR+j548YKnrzs5yU7SKFNKmbBPKtLYwZmZvNmQvn7F6NydkNIkZ18qdLOg4FJSAOEGekJC+Q6yFKeWLXkfSXZ2/HfgwAH+f8SIst+M77ffgPXrZRlORT3fEZrzC837S6v//Y83NTx/HqW6EyUhKFXC3RUJH3tFO7Up9F5dtWoVunTpgtOnT6NXr17FWaZCkUgkmDFjBtzc3ODq6prrcmlpaUiT+/GMj4+Xvl6iYihtXV1d1KpVCxkZGaW6bymJRIKYmBhYWVmV6owuUvKoLhCgbNYDPT096OjogDHGj7dv30L8559g9eoBtWtDBECSnMzvLBOZ5GSIASA0FJJffgHGj5fOkkgk0gBluXHuHMSffQYAkPz6K+97g+SpXNYDUmDFVQ9E6emQv9UhSU2l43JBxcdD+GWWxMVpNHBQpo8HO3bIHqenQzxqFABA0q8fD1aVZWFhEAcESJ9KUlKK9r1KSoIYADMyAstlPVqvC1lZEB84wMty/z7QtKl2yqEGUUYGPw8Vi0v0eGed/BbWSIGlXmVIJGYlth15JVkP1F1noYNSbdu2hY+PD/r06YNmzZqhcePGMDNT3nEikQhLly4t7GbUNmXKFAQEBODatWt5LrdmzRp8/fXXStOjoqKQWobvwEskEiQlJUFXV7fMXICSkkF1gQDlox7oh4XBCkCmnh4yRSIYAUiMjkZyZKS2i1aq6EdEQMgPZitXIqpvX+k8iUSCuLg4MMbKbD3IyeDdO1hmP06IikIK1Yd8lcd6QAquuOqBbVoadABkOjmBmZoiPiUFGfQ9LBDx27ewy34clZQEpsH9V26OB4xBGFMuKiwMrIw3IzX58AGmcs/jo6KQWoR6YRARAUsAojt3EPXgAST29krLaLsuiOLjUTn7ccyHD8gsxccRy+RkGACIT0xEpTp1gMxMRJ89C1aAYKhOUBBMfvwRSVOmIMvFReUyq1LnYggOYW38JkRGflE8hc9HSdaDhIQEtZYrdFAqOjoaCxcuRGxsLM6fP4/z58+rXE4TQampU6fi9OnTuHLlChwcHPJcduHChZg1a5b0eXx8PBwdHWFra6syqFZWSCQSiEQi2Nralu0fGFJkVBcIUE7qgb4+AEDX3Bw6a9ZAsmABKlWvjkp2drJl3r7lHe42aKClQpYCcs32xKmpsJPbP+WiHuQk10TDVFcXpvL1gahULusBKbDiqgei7GYs4n/+AerVkwaJSQFERwMAmKUlbHO5OC0p5el4wHR0IMrKgq2lJW/SV4aJcnwWZgYGMCvKe5L7rbQxNla5f7ReF+RaL1mZmpbqz1CU3bTQzNoa4levAAC25uYFKrOoQweInj+H0bVrYCq6BsrMBAwYT5IRGRkrnM+VpJKsB4Zqdi1R6KCUl5cXrl27hh49euCLL76Avb09dEu4jWVOjDF4eXnh2LFjuHTpEmrUqJHvawwMDGCgopGmWCwu8wdmkUhULt4HKTqqCwQoB/UgO3tVZGwMUW5BJ2dn/j88HBD6oqpo5O4Oi5KTlU5sy3w9yEkuq1mcmgqUl/dVwspdPSCFUiz1ILtPKbGBAX3/Ckv4fTMxUTpma0KZPB4kJ/MAQKVKwKtXfAQ+XV3eBCwrq+zXxRwtdsTp6UV7T+3aydaVx2+lVuuC0HE9AHGTJqX7MxSC8QYGPOCXkQGxRFKwMmcvK3JyUvm9z8gADMHrgUTfSKOfSUnVA3XXV+go0tmzZ+Hh4YHTp08XdhVFNmXKFBw4cAAnTpyAqakpIiIiAADm5uYwMjLSWrkIIYQUg/w66ZTv5+/x44oblJI/kRX6dinNJ3ZFJdSLnI8JIZohdHSenc1KCkE4dr19C8TFyUZKI7lLTORBjKQkQLjO09Pj2TY5O98vi4Q6MX06MH9+0fvIql2bj7wXHMw71i+NTEyA0aN5r96lvUP2kyf5OZa5OQ+GZmQUvN61bAk8fQr0769ydlqaLChVoQavAVDos1bGGFq0aFGcZSmwbdu2IS4uDh4eHrC3t5f+/fnnn1otFyGEkGIgH5S6fh3YsIGPziKQP8kqxQNRlLihQ4HQUNnz0nryWVzkA1Hl/b0SUhodOQL89RewZAlQpw5w9Ki2S1T21Ksne3z5svbKUZYIWTVGRrIbL0ITNWFktLJM+D1zdATs7WWBt6IQ1lFafyudnYHdu4Ht27VdkvxZWPCbn0ZGshH4ClrvEhP5/1xG20xNpaBUgbm5ueHBgwfFWZYCE0Zoyvk3evRorZaLEEJIMZAPSv3zDzB3LnD8uGy+kRG/EwiUjxPSwtLTA6pWlT0v79lDFJQiRLt69QIGDABiY4EXL/j/0iIkhAfN/vtP2yXJm60t0KkTfyzXhInkQdhP8hf0QnCgPGRKmZvz33LLYuql7elTIDCQPy7Nv5VnzgDffgvcuqXtkqivsMHQ7FZdCAlROVs+KMUMKCillg0bNsDf3x9bt24tzvIQQggh3Lx5/GJnwwbZHSP5pmoikazJnpqje5RbYrFsH5X3oFS1arLHzZtrrxyEVHRC873SNOrZzJnA4MFA167aLkn+TEz4fwpKqUfIMhH2GwDs2AEcPsyzi8q6n34C3r0DrK0BLy/Fm3CFsXOn7HFpDUqlpgLe3sDixcDVq9ouTd5Wr+afy/PnhQ+G3rjB/69Zo3J2WhpgAN75u8ioYgWlCt2n1Pr169GoUSNMnz4dP/74Ixo1aqRy9DqRSARvb+8iFZIQQkgFpKcn61NBCLjIjdQCABB+d+LjNVasUufECX6ncdgwYMSIUj16TbGYNIn/EUI0Ly0N+PNPfnzOHo2qVAWlNDzoUqE9ewYI/fJSUEo9qjKl+vXTSlFKlK8vsHUr72epKO9P/gaVqWmRi1UivL2BY8f4YyHoWFr9/jvPPBs0CHBx4eenBT3eVKqU5/tMTQX+wFjYIxxJVuUg0FoAhT5y79mzR/r45cuXePnypcrlKChFCCGkyIRRU+UzpZ494xdG8+cDY8dqp1ylgb8/vyM6bRrQsaNGN50eGoz3f+6Cw1cLICrtnZQSQoouPh4YNYo/Hj6c/y+tQSnGeEZtaXTmjKwvRApKqUdVplR5JJzv5LwJV1BCUGr9eqBbt6Ktq6TIZ7mX9qCU0FRPV5cHDgvDx4ePilizpsrZqanAd5gHAJhhW7hNlFWFDkoFBQUVZzkIIYQQRdu2AXfv8gwgVc333rzh6e1NmgBr12qjhKVDqvY6xQxr8wmqhyXj6s2zaH9Ew/1BSCT8JJFGACNEc4TmKjo6sk6US1NQSujrBeDBnlw6FNY6+SyW0n4xXlqYmQFubsAnn8imnTsHxMQAHh5A5cpaK1qx+OIL3teQ8D6KKyhVmm8YldWgVGHl02RX/iOvYP2cFz4o5ezsXJzlIIQQQhT99x8f1alZM1nqufwvdj6jmFQYQlDq3Dk+/PNnnwE1apT4ZtMy01A9jJ/01r5wv8S3J/XFF7z5EMDvOBb2jiUhpOCEoJSeXunsU0p+JNaPH0vv74P8RSllSqmnY0fg2jXFabNnA48e8d+/sh6UunuXDxzQpw9/Ln8TrjCEfqSKYxS/kiIflCrt3wMNBKVSU4EaeI00GMBIvwoAncJvq4wpdEfnhBBCSImSv8unqvmeEJS6dq1sDCdcUoR9cu8e8NVXwP37GtlsXFqc7ElWlka2CQB4/172uLR23kpIeSUEoPT1eRCgVi0+alhpIZ+BFBeX+3LaJn9RKozCRwpOCBCUhxF4hd8zoS/N4sqU8vQE1q0r2rpKSlnNlPriC6BRI1nH5eqQSIA2bfjjxETFAHq21BSG16iFd3CARVZ0MRS67FA7KHXw4MEibSg0NBS+dDeTEEKIuuSDUp9+Cpw/D/z4o2y+/AnMpUsaLVqpkvNuqoZG3/uY+lH6ONBGI5vk5N8fBaUI0Sz5TKmlS4GXL4FZs7RbJnnywZ7SHJQSjmOrVwN9+2q3LGWZ0FyzoKOglUbC75mlJf9fXEEpAPjwoWjrKillNSj1/DnP0CvIMSYpSfFzUJEJl5Eo+8x1K1Ws9ntqB6WGDx+ORo0aYe/evUgsQKW5ffs2Jk6ciNq1a+PixYuFKiQhhJAKSLi4MDHhd+Q7dQIaN5bNl/8tqsij72kxKPXCij+e2VWC5AzNbJeCUoRokXymVGk0dCj//9lnQJUq2i1LXoTft9Lc309p8/XXQNWqPJAnoKBU7mbNkjUXK62/lUJQytMT2LJFu2XJj3xQqjAZevIB8xUrVA7CkJEgO5+raEEptRtF+vv7Y9asWRgzZgymTJmCzz77DK1bt0bz5s1RuXJlWFhYIDU1FTExMXj27Bn8/Pxw7tw5vHjxAmZmZli5ciWmT59eku+FEEJIeZJfJ53yQSn5u20VjRaDUq2nAbpZQJYIiE6OhrG5Bi6wKChFiPbIZ0qVRqNGyUYHLM2E49iHD3zQDuqrN38fPgDh4Yq/eeWl+R5jst+zYcOA//2Pd+xeFEOGAK9eAYsWld7fyvbteeBszBigbl1tlyZv9+/z45+jY+GCocI5q6kpsHy5ykUyk3ggUgIR9IxL6TG2hKgdlGratCkuXryICxcuYNu2bTh58iSOHj0KUS5DrTLGULNmTaxduxbjxo2DpRD1JYQQQtQhH5T68AE4coSfCHh68umUKcXt38+DcrNnA4cPa7z5XmZ2P5zRKdFwNHcs+Q3L320srSfahJRXNWsCf/zB+/nbvx/YuBH4/HPg22+1XbKyZdYsQCzmWT///QfcvKntEpV+wm++kP0DlJ9MqfR0WR9DlSsXXz9tQifnGjovKLAlS7RdAvU5OckeFyYYqsbgPJmJPOCaCkMYGqmOsZRXBe4+vlOnTujUqRM+fvyIK1euwNfXF2/fvkV0dDSMjIxga2uLhg0bokOHDmjUqFFJlJkQQkhFIB+UCgsDJk/mJ2tCUGr1at7XVP/+FTsoZWHB/4SRhzQYlKqcAFzeA1RKBwKHR2lku5QpRYgWWVvzTn4B4IcfePZAvXpaLZKCp0/5ccHAALCyKr1N+Dp04Be0x4+X/lHHSgv5Jv0CIThQ1oNSaWn8NzwlpfhGy7tyBXjwgD8uzb+VHz8Cv//OB0yZNg2hv/yNSgu9kLJtD6oOba/t0qlWlEyp2FggIICPlpwjQCVJlgtKVazWewUPSgksLCzQp08f9BGGrSSEEEKK09OnPABhZwcEB/Np8mn7RkZAnTr8cUUOSgmEZo4aCkpJgoNw6DBQN3uAmBvRYUAtDWy4YUPg7Vt+cVy9Oh/RRqyBwYQZA6ZN43XOy6vkt0dIaSf0KyX0M1UauLsD0dkHpYULS3cGVz7Dw5McVGWazJzJg6RubtopU3ExMwMiIvjjoCBgxw5+s2n+/MKvs1s3Wb9UpTUolZLCgzRTp/JzumnT4DipJwBA/389gaGl5NyOMWDuXB4EXbKkcMFQof6mpvLzmAsXgI4dFRbJSpIFpYRBpyuKQgelCCGEkBJlZcX/AEh/nXN2/Cn0uZCQwE8acmlSXq6tWsVP6jw8gJMnARcXjWyWhYXh0xDZ8+SIkNwXLk7aGsn3xg1g61b+eOrUilnXCAkL498FO7vSGZQqK6PvnT0ry2Ip7aOOlRaqMqW6ddNOWUpSWBiwdi1Qq1bhg1JZWbLzJTs7xaZnpYm5uSywk5IClpkF4ZfVJCuXvkJ//JE3Hf7nH35zShMkEt5UGeDBKVtboFo1FCidSSTir3n3jj9XcQPxo8gSWzAVSTBBK8qUIoQQQkoZ4Yc/NVUWfPruO95B7D//lP27pEWxdy/vzHTwYKBt25LdVmAg8OIF0KcPsmKjFWalvQ8r2W1rm/wFblJSnv1CEFJu3boFDBoEtGvHm1QDpScolZWlmE1bmoNSnp48+ACU7Uypv/8GatQA6tcv+W0J+6m8H3uF853CjL737BnPOJIP1rx+rRjIKy3S0pQyjeLDk7ATszEHG/FI3BgNVb3u55/5+zx2DBg3TiNFVeg7SlcX+O23gq+je3ee5e3hAVy+rPJ7H2nohO/BRyH0rWBBKQ3kuxNCCCEFlJAATJrEO4NlTPFulHABdPgw8NNP/ELE1LTiZq4IF2Ga6ICgQQOgb1/g2jWw2FiFWZmRESW//ZwYk3UOW9Lkmz9Eaaj/LEJKG+H4q6dX+jKlcmYefPyolWKoRb6syck8E6OsuXUL6NmT/y5oQu3aQKNGgI2NbNrDh8Dp08DLl5opQ0l58oSPRDdiRO6Z4flJSwP69OFNwuQDHsXVR1VxUzFqckxIInzBbzImSIxV/7wLfdhlZZVg4XLIGZQqijya7crH1Cta8z0KShFCCCl9Pn4EfvmFB51EIsVfZ+FETY2RTCoE4SwmIkKW0l7SfH0hynHBJ4nWQKAmKIgPnd6yJW+OoKvL+x7TBPkT+8hIzWyTkNJGyGwojUGpnBd5pTlTKmdZS2ufP3m5cUOz2/vjD97ksVUr2bRNm4DevYG//tJsWYrbhw/AtWs80FfYoJREAjx/zjOj3r/n0wwMNNPnYmEIQSkjI+log3HvEhENnuVljWiFII2UEJT88EEDhcymoaBUVmIK7PAeJkiscB2dl9JaSgghpEKTH3kPUAxKCWcpQlBqwwZg7Fh+IlYRCfvjwQN+l3X9+pLZjvxdyQ4doBOv2A+KODpG9esCAnhgUSQCQkOLVoaEBCAkhK8nK4ufhGvqYu7zz4Ft24AtWwBHR81sk5DSRghA6evzi6vKlQFLS+2WSVBWglIZGbLg3sCBvLPuskj+Ql1bgUkhQCBflrJI+B0zMpKd76iMyOQQF8ebsaWl8deamvLpwuAwaWk8k61ly2IvcpEJQSlTU2m5E0I/Yij+BAAcwSDl7tbi4gAfH/5Ym0Gpb7/l3SUUpBnfTz/xZs+HD/PnKoJSn7w+hfeoglPoTUEpQgghROtyBqVEIuDECd45bPYdNenZypkzwO7dRQ94lFXCiavQKXxJjb4nnxnVvDn04mUnVPeqAJE6uZxAC535AkUPHMrXCyFzSZMZBpMm8U7Oq1bV3DZLg8WLeTMd4WKAVFzymVJdu/IMzdOnS257o0fzES/VyYTJeZFXWpvvyR+j9+8Hvv++dPb5kx9h1NtJk2RZc5qmp8f/F2QUtNJIPiglRCPS03nz9LyaqQ0ZAgwYAKxYwZe1s+PThaAUwPuCfP68JEpdNPJBqeyM94zXIZiCnwEAy/G1clDq+XPZuV50NDRGPiglFvN+PG/e5H1EqevlS8XsQlV9yaVW3NH3KChFCCGk9MkZlAJ4Xwndu8vuIgpnK/b2/H98MQwdHBGh3b49Cnq3OSNDdsJa0kEpoQ+pSpUAPT2Is0+il3YEmk0CfmuSyymFfFO3sCJ2hq7toFRF5ePDOzQurZknxSk5WXP9lJVF8plSmvDvv3xwhdmz81/WygqYM4d3Ij5lCjB+fMmXrzCE45hYXLY7jhGO55oI0qenAw4OQN26ir/16galVq3i5fz225IrY1GoypQCgIAASCytwBYtVv06IbBTsyYPcL56xZ+LxTxret48xfUD/HMrDU1u5YNSO3YAFy8iHLwuxcASWdBV7nYqQq7vSm1kSunp8ZukQoZeQYKhwjlr8+b8eKZqgJ40WVCKMqUIIYQQbVMVlJKXni47GSiuoNR///F1zZ1btPUU1uXL/KKqIENAy6f3l3RQKia7eV5iInDlCqZ8LoHeUmB99nlVdEoudy3lOwUXhkIuLA0GpaL9LuK3z+zx1fKWSMlIAYYO5dudPRt49KhEtlkqpafzzoQBoEUL7ZalpL17x5ujDRum7ZKUXvKZUpogXIS+eZP/sg4OfFTWX38Ftm4Fli4t2bIVlpAhYWzMA72hoWUzuB4ezv9rIiiVlMS/n8+fKw7qoW7zvbAwXt5Nm0pnBp18UKpSJeDePeDJE7z6aiPECfEQrflW9f0y4RygWjXZjSOAB6XmzpUFpeRvYHl68sCXSKTZwE5OVlZAv358NLr27QEPD8TH8M8xEZXggFAkRefIwBbqHKDZstvZAY8fA3fu8OfC8a8gzUaFoNTw4bzbie7dlRYRU1CqcKKiorB+/XoMHjwYXbt2RadOnZT+OnfuXFxlJYQQUlEIwQf5Jg3HjwPe3rwDT/nbZ8UUlIqanT28+fffF2k9hZKSwk/MkpIK1ieUiQlvEvfkSckHpZyceDMBAJKvvkJqZioydYD07GuCj6kfkSlRcYImH5TKLVMqKEgW+MiLBoNSQdvXYsS/Eeh45DaOBh7lF8UpKbx+bNjALwDc3IAffyyR7ZcaAQGyu+qenooXPuXNrl38wuHPP7VdktKra1ce9PH05M1R2rcHevUqmW3lzFgr6020BDY2fB9+/z3g7s6PrZruNLw4nDjBOxn38gL270dqKrCp8R5sqbWp+FtWCYE8+Q72hedA/nVDyNj98EGxSXlpIR+U0tEBmjQB6tfHgZT+0kVePlcRlZLPVouR69dR6OhcfoCOlBTex9SVK7Jp8kEeTWvViveHtWmTdFLWex5ockIoQuEEnft3FF8jnyk1ZIgmSsnp6fG+uRo2lD0HCpcplcfgPOJ0HpRKg0GZTqIsjEJ3H//w4UN06tQJsbGxYHmkOYsq6hDdhBBCCk/+TrJg3jzejOPqVd7B5Nu3/Ed+zRo+v4hBqVspL9Ez+3FE5GtUsaup1usS0xMRlRSFGpY1Cr/xDx94vylCvw+xsep1HiwWAzWyt/viBf9fUkGpKlWAr78Gjh5VCC61CQX2HgPemQGxc2Jha2Kr8LKYZ5HIDpch9dU7KN38k0j4RW2VKnzkwLyaBQkn7sbGsgvWEgpKOV+8BwA4Vg9wiX6meFc2MhJYvRq4fp3/TZtWImUoFW7flj2+eJEHIkpjp7nFQb5JS0yMLNBLZFxd+R/AMweuXQNsbfN+TWHlPKaHh/MATl7Lx8byfgczMnhGjJMTzwphjH+m1tYlU9aCsLDgQT2AB6cA1f3LlHY6OrzpVUoKEBGBM8czMPPhGACA97oe8Fxft/i2JVzQ5+x7S93ggPzNkcePgQ4diq9sxcXYWOn9nWE9sBA60EUW3t0OR5161WQzMzNlwacffpB1cg7wmwm3binW9+Rk3r+U/DlCVBTPDtW2K1eAgAC4vFIMGGa+zxHdFIJSS5fyprraUpgO9oXvuI4Ov8mlo8OzO+XIglKGRR7kr6wpdKbU7NmzERMTg8WLFyMoKAgZGRmQSCRKf1l5dc5GCCGEqNKvH++oc/du2TT5YZJ1dHi6et26gJkZn67U+UDBiOTur7y4mHunusk/bkSiWyuwwEB8TP2IwcsboOaPNbHn/p7Cb9zRkWc7Ce7fL/g6hABecQSlgoL4SVPOE67sZhri2FjsOwr8fgSo/hGoEwPUilHdhC/htexiIP6ZikypwED+3v388h+62tgYqF8fcHbm/TJ07VoyJ9TPnsH2DS/3ND+g8vH/FINSUVG83IV1/Dhw7lzRyqgpd3LcqX7xgl/4e3nxzLny1P+SfCaf/B15opoQQFYxdP2GDTwRQj4po8Byfgb5Nf89dAioXp2PQurqqhjoj4riGUq2tqUr4yqP4eHLBCEg+eEDoh/Jvj/BT9UYOa4ghP2TM8ukVy8+qtnQoXm/PmdQSgOUOunOy5Qp/D3u3cufb9wILFuG9MiPCAEPxH6880rxNUJACuDN/4Us1rp1+efSujUwfbrs3CklhXdTIE9+v2haVpbs9+O334ApU9Dh7X6FRVhUjiZ6wjGhShUNFFDO+/fA8uWyTHo1m++lpvJTBcYgqxD//MOPU0JgWo5OBv/eZOoaoqLl9RQ6Bnfjxg3069cPK1euLM7yEEIIITz44OysOE1oYJ9zmGTh7mARMqUkTIKQ7EH9LlYHbmcGo72K5T6+fAyL6fzuXHT7FvhrUAP880sotrQCdjl6Y3ST0YUuA3R0+PDgf/0F3L0LdOyY/2vCwvgdUhsbaRMKaRZRUc5oFizgF3jffy8brvzpU4WL9hHZre0OZidNWKcAocnKQSmDeNlJr160igv9mzf5/5Ytke+twcGD+V9BpaTwrAmhqWd+jh+XPmzzDgh5+FKxk++oKMUO8Quyv4OCgP7ZTTLev5eNllRaCZlSFhZ8H758yb+LW7fy6R8+lFymjKYJnQT//jtvqkGUBQYCISG8Y2UhKJWj0+TXF9/g2tx76A8/XJncCJ8+LmQfXTmbFuU3UIIQuDAx4dlSkZGy760QnMoeqEGrwsN5c+XKlWVBqQJFMDQrIQG4e1uCGrXEskS1iAj+23DwIH8eFYXURD4S2WvUwLnIxlhVnIXILVOqdWv+lx/5ATc0EJRa0+kcGl38ATGrt2HEIseCr2DdOiAqCi31asAKvFleWuBrAJ/KlpH/PsTEyJrvzZun2BywTh0eiGVMOSilzT6lFi7kTffmzZMGG40kijfVRDG5ZEoZG/OuCxwcNDPoQkQEsHIlD4bNmsXroYVFngMVSCS8G8bHj3krfy9jY34TVQioqQhEP9Rpij0YhXsGatTpcqbQmVL6+vqoVatWcZaFEEIIyZ18UOrpU35CvHUrP0F4+xZYu7bQq45KisLk3oBoBdBpNOAjUT188pLn29DzS/7YOjoZE37hF+yJ+sCrj68LvuEnT4BvvpHd4WzWjP+/e1e91797x/ug2rqV75///Y8HPHILkPz1F892unQp7/UKw0nXkGuSuGMHoKKfyGAbHQCASQYQG6t80Ti12XG09eiC2p+OwNrRT5TmKwSlsk/SQv7cgeDmLkjwmpB3OdXVqxd/30FB6i2fHZR6mB0vqvEqRnF+VBQPIgoKkKXH/v1X9kTI2EhMVJltUiAbNwJt2hTPne/kZH5X+OFD3oStUiXgiy/4vOfPZf1qALJmo+XBqFHA1Kmy72FJKqFsnZQ5S5Dq4AIWmj1UeUwMD7IV1/Z+/RX47DNg585cg1KxU5fgOPpjIdai1pOThd+WWMwzIgUqMqXCn8TiTtNxeLjjhnJQCpB1ai0EperU4UPJvy7E8bq4XL7M96FwcQuUykyplBRgT6Pv8dqsCdp2MkSEcyt8PeABjxUGB8sCUgAQFQXJm1AAQCgcZdkhe/fyfoOKSv6zLajMTMX+lp6o+B0qRomJwMKL3dATZ+D0nZfKZQIDgSVL5BJuc46Glx3s2JbhCQvwwKo46BUuHQjDb67rcP3kB/6bITTPi4uTZU5ZWir2v/jwIRAYiGfvLZB18xaf3pN3ViDSZqZUQgL/bHR1pUGps7q90BU++AefAQDEsTmCZt98w89FxowBatUCnj3TTFmFjCjhxtnixfy8LY/zztBQQOfxA0zALwjae4Wfd8XFAT168AVUfOeP6w3GGOzB32YVb7CNQgelOnTogNvy/QwQQgghxeXMGT5yzJkzsmnyzfeePwc2b+aZQdbWvClfbiP1qSEsQTGYcuvdLUiYYqeid8PvYtvtbfi7DlB3KhCTHSN7YgN83QHQEemgwNau5X0jTJnCn/fpwy/6Fucy/HNOQtaYfGemefnpJ36XPr/h1YWg1KNHspPbmBjVyzo5ITM7BpYUHqI0+7LNUdz0+A8vO/2Ga8n7leZLg1LffScd+XDjuZWofvcVwv45nM8byh+TSIALFwAAH7ZtzP8F8fG8KSGAzW34pOah2V0RyDeDuHiR75O0NFkTUjW8/Ys3SV3SEbiU8YLX5Zo1gaZNi9YUbs4cXu68Rhz74w9e527cyLuJ6J49/K5wt278OxYXB3TqxOedOSPLKAJkF/tF8fIlv0gS6kJJS03l37Gc2xszBtiyBahXr+TL0KkTz3CUD1IWUebJv2G0cTUM373C+Zmn+MRZs/hoT8IxpqiEi2d9fVlQSiKRjuyV/iEe9Z/Imj87ilU3uUt/+hrhE5YjKyqX4woAfPopz9QT+mxT0Snzmy6eaH7fGw0mtkdWvIqglJAplX3xKrlzF+mVHfC6l5f2Wp7KBwzUCUq9e8czXHIUOCCAJ8oKcYX0dN7FV1Hj24IzBxMw8tEcNMYD6CMDjfEAe4+ZokEDIPJejs81Kgp673kg9C0ckBifhagbL4HRo3kz3+zMncOHgQkTZD8xajMw4E0ya9dWnP7uHT8WP3qUe9w1OZl3yC9kX0dFlWizNfkEpqqJqoMmw4bxbgn79QMkWYzflOnfXzbKZPZNODH4Zz4au7FefwnMxgzAiMcLEDfKi3eSHxkpa/bu5MTbzD5/zo/hgMK5wZo+N6ADCV7ABe8dsoO98hlkJSGvL5lwM8fUVBqUCsu0xX/oiqvZueq6H3NkSnXqBIwfz5vxAyozvV7/9xrBl4KLWnJFQlCqAFmW8R/SsQkz8QsmocUrucEzhCaoKr7zwne3oo28BxQhKLVhwwYEBARgw4YNxVkeQgghhJ9kbtjA7ygL5DOl1BjFpCCkQSkGOH4EOt6Px/O3iqPBzfGZIw1Ute40AgPHmmBvY+DXZsDtHcC63W+VAll5eXH3P0gO/M6fCE3kXF15PwPqNh0SglLCvjl9GjhwIPemjEK2S17N2JKTZSeqy5bJRsVTMepahhiwr+IC3ezzzqGfzwEmTlToHDu6xnbp48eGOxVXkJCg2JTizRukpSXjB29+wVP31UceVBJ8/TXwySfAtm3AqlX8wnPBgtzfC4D7AbLmCk+e++a5LAB+tWRhgUhrQ1zNvoYRA0hsXJ9f2Aj7OiqK35EuSNOBzExYXecdqPvUAs7c/oNflQh9VBX2Qkm+Xwt//1wXE+3fz5tMtGvHL4By6w8jOyiH9+95/zwikexiMMdw6hmBxdAU5ocfgL//5v2faMLOncC336ruKPfOHd5XmTCy0+HDCnU06tBFxHYZBLYyu3HS6dN8FLKCevMGiI5GZLoFrl6F6uHeVbl9m194jhsH+PjIXhgTA4wfJ13sZWD2FbqQPbFzZ/H0/yVc+evpKTZdyQ5WPVh6GMaQDT5QjakOSl3ptAI6O7dhz/D/VM5XsHQpv/j89luFyenpQJtwnoWjiyzER+QRlMoOnt6pMwzirAzUDPwbZ6b8rXJz6a9C8fFy7iO07V/6DFvaHkBoSCH3p3zWjzpBqSFDeJ3s3h2xD3jgPysL+PxzYMYM2T2GdZ9fgnN7R3zX4XThypXD+/MBEIMhApUxyT0AY40OIgg18fEj8PRC9m+m0KdfVBSMo3mm1P9wAO9RGe//vSdbWUoK4uMBny/34O3Ov7FuqXJzRcb44cnDA/jlp0xERACHf0vFDzODEVK7M79JIp+dBfAsrE6dEPDFKhgaAl9+yX/CMjN5Mhxj4DcNrlzhx3Yh+7eITfiE7plUfWxh72T1IjNTpPS1i44GvniwAEuxEknP3+LBliv8d/bcOd4kDFBqFnYN7njw1ADN0vmxucvHI/yrLxbLsqW+/poHuRcskGWDyd2suxZZGwvxLbbAC3H62U2u5ZulF7fhw/kNl9y2oSIoVQm8XkSDvyeDhFyaF9rY8P85glL3ryfDrmsjVO9YA4H+xdgkNmemlBoynrxAJ1wEAFglBMvqgaomuzdvAnXr4tyHpqiHQBjpV7w+uQsdlFq9ejVcXV0xf/58uLi4YNCgQRg7dqzSn6eKTrwIIYSQPMnfSRbkFpR69owHdb75hk9jDPD2zvPiPCd28QKi1gHHDgJ3dgDH/wReXDkqnZ+amYrlyy/i7G9Ah4xq+LXPr/D+5iFitn2P1NrV4RoF1I9kiJbrU4m9eYOMQwdzvfC/OH8oxFkSPHC1KfxoZjmDUmPH8iZ8IcoZSwB4ujvAM1NyI9ypFTx6xP8LmVKjR+NeX97fwUdDoJaVC67Jd5mxYwdwj1+MJD15g/U+WZjkD8y4Afzy9z1ZwAPgn5H8GXtICGJfKV4sRAfJPQ8N5SfbsbF8v8bH59t0LvbZfelj86B8+qQBgEaNgOhoeC5tjDfmgBArOLtpCr9oWL2aZ5wJF70FwPz9YZKcgRhD4K49MH3iLoUO0yMD/PJ4dR7kmjWxp09zb6ol39QuOJg351RFCCra2PDvlkgkqzvZ0rITA8PvXVV+/YULvNnfvn3qlf/aNf7/1i1p3SmwV6/UbwIl1GX5jKh373hAKj6eX21evsyDTUOGSEebi/nvLmyHdoLl+b8Qt/c4D9D17s0Di/l1wi0vPV26/K+DzyLz0464NkHNfbV9O//eeHvzlJM3b3hgauJE6EaG4yVqwQjJ8DbOzi46ckR2HC3AMTFXQt0SMqUqVeKfdfZ00aFDAIAdGA8AsGfvkJmheFWelgbohb+BHaLgf1ONiy8bG37hnaNZ8p1Lit/9pLDsYLzQ3wuglCl1StILm8BvArhu+wpxYYp1JjaGQd/FCRYeTeB/JMexEDzgMOibxvC6+T/82KVgTRNfvMg+nMr/vrVrx29EyDdTlJeeLvvczp2DThNXbBp5D69e8VbrgOwr0//yDDjiLZb49S5QuXKT+SAAAPAAjbH4wCeY7NNfOi/xefaxtHlzoEEDsPr18V9yO/yG4QAAG0RD72x2cGzCBMDKCqFvJNiYOQ1/oycSHyk3pb55kydy+l1OwWdTa+GhfTd8PtIG0zfXwN5euWTNZgcJQp8kQiLhyaB9WkXgd2sv6NZywpYhOXra37YN8PXlgV05TwMZvnXajm9731ArdvtD55No39UAP3ZUbpoYHg7MBk/akECUM46P2zcz4YUtWInlqIZ3sFo5g88YPlz2u5IjKBUFW0gyZd+Vj7CQjQMgBGiiovjr5W+UGBsDY8aAubrCCSFYi4XYgml4130skJgI9vvv+b/ZwpBIeLPh4GA+Yq8q8kGp7EDNEBzGWHjjLRywG6PxoHI32fLR0XydV67kGpR6eOgpKiG7G4BffYrv/eQMSh0/DnTpwm+O5ULyXHaeVTPrBbLaufNmu8JxTPi9kkjApkwBnj9HI8l9BKIBPk87XnxlLyMKHZTas2cPLl++DMYYXr9+jaNHj2LPnj0q/wghhJACURWUmjmTX2B99pliUCoigjflE06ujh3jWQQ5TjqlQkN57rxc052MN0GwSQEqpQN3spOIEq5fks5/HvoA7d8A3V8Bn9RqA30dfdS0rImZbWfCpk5TAIBTnCzjKullIGIb1YHe0GG4ObA1MrIUgwSxKbFwDuIXxodcFX+K0x8/RPCa+cj6T43R2XIGpfIagS89XXZBGRQkbW6jJGe/SwEB2YXOzpQaPhx+Hi4AsoNSlrUwYgDw2f+AK92zL/Kzr5Zibj7HnIfvMdkf6PoKGPo0FXF3rsvWLXwGjRvz/2/eIP6ZYoZC2K0Lsify9UJolpCSgryEGmfiQHZn7KHmanZGLhLhnWE6MnSBUKFrmifZ/XzNmsXr3KBBvA+nLl14towaoo7zOnq+JtD1NeAQw090Q7Jb/z24WYiMGwBRiZE45MrfW2ZmOu9zLaf0dLBg/tkecrfk037+WXm5xERZoOzePZ6OAfALh8REnqkGYF/2R2bwOlh5HStX8voyalT+AxDEx8uy8QDgl1/yXh7gFzrDh/OAEABcv84zucaNy/NlUkJwTr4p0MGDvFfa9ev588hIWQZU9l38Z+dkwV6zoPv84kIIbBVkNMW3bwGJBFn6htBNS0JHXELCBTUDRtn7KqPL5zix8CZCxNWBr74CjhyBRKyD/+F3pMJIlnRnYsKDZgBEf/yhfhkFQUH8mCkQmu/p6fGL34QEfrFoZoboaKBqDA9i788OThgiDXFBik303r4FnMD35aN4J4VBxBT07w+4uABnz6qcHbxXlkm7G6OREZ79pnNmSmVlSQPxidXqYgVWIBjOqI43uNN7ucI6L/0ia251f59yttSH49dgCN7G5pMXx9TOcHv6lH91GjUCQgKzL0aNjXn26q+/8iZuqgQG8uO2qSn+wWfYjkk4/FsKHj/MwlW4g0EEr1fT+aE9S3YDJPPWXdz5/SkufTIFTw8/Uq+QOZgG89e90HeFgwNvYdwV57AT49DjYXZfOp9+Cjx+jOjdp3AgayhG4jc8RV0AQJ1bv/FlsgNuifdewAwJSIYR/OLrK23vwAH+vy9OwBkh6IZz0gCDy+PjqpslZjen+hz/YDh+gz7ScOhxA4yK3wonhML47yMKi6d26I79r9vh4UvF5v7X5hzHotDJWHS6nVqD3y640RcGSMdC/wFKQaywcBF80A1JMEYczJXq95szATAB/y3zQxs4x2Zv8KuvZAvJBaUyoIup2Iorcp2cZ0APup4jef93wvH6wwd+TJIfPMPICAgKgujxY9hAFsCJzzQuXP9c6pIfOXP4cJWLMCEoZWamkPXujXF4inoYi9045Si3TwIC+LrGj881KCV+JWtObu9fuN9TlbKDUlni7KDUu3fA+fOym3YqiINkzdzr4AV0b/ryTDYhYJ6UxG/KHT4M0d27iIcp+uMoeuAMblbuW3xlLyMKHZQKCgpS6++1NjsSJIQQUjapCkq5ufHR6WrWVAxKWWZfYIeH84sP+X6oVI3W1L8/vwCVH8UtO4jy1gx4mN0aQfeJ7ML+nf95iAFEGwGOLop3tPWr8wwSq1QgMjIILD4eH7q0hVU8v3j7svpdeOz1QHiCrD+U17GvUTs7qeqJpWIm1ZHlg1F90Xr4rf4K+SpIUOrZM1mAIT1ddps9p5ydfeTMlLKyQuZH/jjWEHAyd0KwJfBvbSDCMru/BSEo9YJng0SZAO+yAy/Bj2/I1j1zJr9rLYzklpCArLt3FDaf8OCW7Il8vRDecz5BqdfGafjfIN6J/czBpnkuKy8xndex15b8c48Jk+tH6epV3sTUz4+fmKrZ2fcTROGhHW+6d9YFmPo50GE0ML4P0PcL4Gr1wp2W3TOMxdBBDK6TgQHbPBQ7Is+mExICcZYEiXrA0ibZAUZ/f+VMvnv3AMaQZm+LeNscfWVlZkqbhezNDkrpfkxQbhYm39Rz8+a8Cx8Vhax27ZFhYsGfBwTk38zM0JAHoc+c4ceC1av5a3I27cmN8Hk5OMjKKvST1ayZdDRByb/8TvujL1YDANJeyIJSYibhdXfgQD6hIEGp7O9Yip0zAsEvzi0iAvN4QbasLLDsZkfu/pvQb1IV1K0nwrmQOmBiMfy9fsMt8CzGyEiAxcTy9yo0Rfzzz9yD0aokJvKgm7Oz7FgjnymVQ0hAPKqCH+ceohE+ZDfBSXymmEUWEpQFB/BjRH0E4tGtXL7DL1/yzyU+nndALzQ/znb0ZSPMwXeYii0Yi924WXUAbz7cpAlvavvVV0DbtvwYMWkS0KMHQuGIZJhgMrYBAD69uxnPrssyXBNOyILgmWHK/e1YHd8lfewGXzzIvZWfgou/voJ/RmP8gGkIe5l9HFMnKJC9AdakCXrgb8zHetxAOzw6GQR38ObIbin/ISICsIOsvBk798Bk7BB4PPkZjsPccg3s5SY2FniTaI2nqIuP1ZtAJOLF7Wp7H+PgLVuwWjUAiomCT8Cbnwv9IcHFhTeXy87AjIcZKoW/UPiaZ2QAd35/Cl1k4ITBUKzpdgGbnb7Ht7abAADDJAeQVbe+LGic7XWIrC/HFsaBGG5zFhb4iHjwY71j8jOkfL+ND3QxZw42buQtkjt0UEyytX4u+10KC8y7SRtjwHzxdwCAOJgptWwPCwMC4IpKSIQbrisFpTKu8Zsxj+AqnZZg7cwjlgK5ToUiYYdp+BFuuI4f4YXDGAQ3+EI38BE/Xu/dy/fvyJFA9eqyJpXNmvHvQfYNnP/hd7jgBQCmVlLp/ctxOOg0F/smXMt/4ZyE8whnZ5X9MKWnA8GP+AcQ8MYUaNcO12fI+l36AB50UhiUUgh0VamSa1DKOEQWVL7YYGrBy50LnzP8uPf0uQ7/yRQypnJkJceEp+GU+zqcmn0R+iEqMtL19fnvy4QJvK+89HQkzVwCANiAOTiO/vgHPfBJY/WbCZYXhQ5KOTs7q/1HCCGEFIiqoJQ8+aBU/fr8TltcHD9BE5oCyafCC96/5010AEQ620gn60fwk/m3ZsDrqvxk0O5NtLSPqIT7vFnVY1vgEztX+TXC2r4m4rOvz+JfPob/9EFwfhOHCBOgthcQZAVcD72Or/6WBZmCIp/BOfu896GZ4gXZIZNgAEDlxzyrRfLiOR74ncT51+fx6P0jabAEQMGCUjkzoOQ7q5bXvDmwaBHvrATgQSnGZBfvRkaI0ktHny+ALiMBR3NZ270w8+wLhOyg1IcgftcyyhgIy44HsRs3eTODuDhe7nbteIet2SeZxjcUB1FhT+Uu1guRKRWRGKHysUrx8TzoOWgQ0lP4fv5sOLCtBTD8lxu876N372SjF7q58f9qDqv9Y7MMNP6K90MGEfBTa+BKdcDHBThZD7jNcgkU5uNVDP8sH1cGXqWobkamm32T8Lk18MIKSNAH33c5s6pq1MDvwzthfqMoOK37BMExcmW6dQtgDK8txLjhCFjPA5rPq6HYrCojQ7ZOCwseFMhLrVr4suolGCRFowX80SjuKv46mk9Gm40NDygxBty7B5Z9RZy81zvv1wmEoNTw4bLRk4QmrS4u0qaK4jC+3gm72iA0FGBvFJvFSi5dxNma/BjBzp1Tv2Oo7CayidbOeAqeaeWc8lTxAkyV168hSk5GCgxxO45nK6amAt3+mYW1I57gkeswAAxH0R/3UuoifdNWPtrc5s2AtTVE799DryBN+AIC+NUjY7LMDflMqRzibvP9+h52iIMF3oEHLFJfKdbJD4/CoQceDP0V4xFx7hHPAOvRg9cxgdCxuaMjbzL755/SSEJyMnDinhM2Yg5+Ar/4PGg4hjdv7NiR33z46Segb1/+O/Hjj8CZM0hM5pc+Z/E5nqEOdJGFx3v4PmEMsH54Ubp5w/c5mkEnJKDKVd488T90xhjsxjkf9fqVSr5wE43xEC3hj4x4ueNYVhZvBhoTg/R0flhWiMlmB6Uy6jcGIPteBJ8OkD6uidd45vsBduCZYuOwE/H2dVEvnd9QMMlK4COQFiAw9fgxsBLLUR9P8a7TCOn0NNcczQyrVgUAhIVmwQUvYIgUaaBVqnNnoFMnGATwY3sVvMfWVE+F+n7eJwt/xXZEOOzxVYfHWPhvR8x4MxNVFo2FJPt9G795qjTgxqULsp1V6eu5WPO4L7Z/HYkJ9jx7tS6eIfZJOK9LKSl44p+EcdiJeR8XKgzcdlssy6xOuyPbt6okJwOnJHwENRGYUt9iNnd9sBir4ZYdNJRPGmIMsH7Bg1InRP2xFyMBAD/U/FFxI1u34l933jQsCrZ4BX5Muor2GILDCEYNGHzIvunWuDE/7qal8QOCEJT66iueyZb9W9kXJ3EPTSECQ1pMEjB2LER9+qgMVCckAA89vPBF6AY03jlF3Z84GeF8o3p1lbP37AGOpvXEHTTDqNO7MNZ/CR5bNwEApEMP8TCDEZJh9CFU9oWQD0oJ/WjlKJhlJP9Q52EdHugrdotw6RJvsa52/31yem3qhIZ4iK8yNvNDlBCUkrupwxIS8bJ+L/T2/T975x0nRbGu/2/PzM7mnHNiWVgyS85RJIMgmBAUMScwZ8wJMSuioggIgiBBECQjOSx5SQtszjnN7qT+/VE90zO7i3rOvefec3+H148fdqare6qrq6rrfep5n/dZus+/Fc2VFjarvLwEuvvVVzB/PoavfsCzIINigvmQ2cycKQ598Ddysvz/Zv80KHXdrtt1u27X7br9y6wlUOrMGcGEOHbMGZRycVEzgy1YABcvIut0wiHx9HQCaGQlNOhgJLQafRmjRThYnsWVAOT7Snh2FguZtsVWrlQIR16TLoCRsyHQLqSdU1XDvcPJVrCvhquXsOzeBcDzQ+Hum98iwD0AZDiZ9huNZhF/UHLxBDJQ6wJX3AxYrGJRaLKY+CNM1CmxxIK5rIQLj95Op17j2XLfMOY81ZHlA/w5tVoJu5o8WThzthXMPwJKXUtXqmdPwTx56y0holpaqoZIvvUWNDTw6ovbWfIL1LhBlE+U/dQcH2W1p4BShkLRfiWekBEgDnU+noMlNEQAFo5byMomVshRwcS56gdFnlBqcti1/idAKb/j6aTmgYcRahtrqa38k2xDx4+Ldjp8mAqr2Eo26iC6GiLKjGLR/8wzavl+/cS/ZWUtXMzZLFYLuzJ3ARDgEUCQR1CzMhfK/rn01nlZp9EqfkVOdQ5yC0wjrQJKXQoEWQPHw5QDaWlO5cwRYdwZv5+Pe0OVnEv7N8dx8aqyra4wDzN9waqBcg/IMZzHYHJ4BufOgdFIvZuO1Xu+EgLNf2KFhbBqSy5yn/kcC/Tm9BmJadP+5LEaDMg+PirT77ffkBTHfVD2q/Yxdk0rK3NmctlidWzjITFRAFMOFme9zIW159ArIMUxugKgeX8erxx4mxq9klr95EnhNP8VfUZhEVT6xdlBqSjySD/05/popjQBMpylHVa0DBqkHlt3PlmRT5JIIZ1kLiJvUMJK2wqRfjk0FI2tr5aWCgGeP2NO2cKChg1Tgcd77hFzgQ2QnTJFzL9ZWVw1RzOTb3iVV4iOhltZThxXyUoa5nTZunPOYE/D4VNk3vos/PYb9OyJXG8Q4JetrklJaoZLpQ/u2+dMUtDTSMkFFbCQZYFvNWWpODJEjtCdGryw5AlnNzMT3jDM4Qjd+JlJbDI16bsnTmBFw3mSGc5W9tGP37f+dUiwLIPvOQFEXCCZEksAfPghjBghgDZ/f+TJN/NAx330aFXG++87nPzyy7BnD2U33w9AMMX0Zw8JFSp4704Dl9Oq6M1+bmMZ33IPVYUGGnDlGd5hjWayeM7/gKSKY1SSI/HSa0BX+9/r3jorQOeJExk5VsclWlOBvxMoZe7RW/Sd4mKiTqnC8lHkOoE1Jz7aRTiFSMgMuKe1/fvuQ31Yzzi1YBN22WavySznFsawgbF3+hMSAg++HES/WaIOMWTTcFHRBgsOprZO4ivu4zneofyCmljiJ8tkNiKAJl26c5KTplZZCZdJxIIGH2ooPuW82dH60q+8wUuMRrC2HftgTg50bhB9wdCpF/eykCQuslEr7nH9hfX0/64/P5POjrDbmM18PuUROyiViNiA0GHCs055l0VEODGZ7eF7toQlDuuos7RDRkNVgyt89x3Sxo1ILSQxWXbLBu5EhF924hTF6f8gKmVjSu3eLRiOTd5J58/Dk3xAt9ZzSev1A9+d+I5TuSIzbSlBuGCiHk9+PhyjJtdwBKVSUwXbqMn7Za3rVN7jKXYz0Am/PHdOTFMzJ1dydsb7107ycQ0zoecMHdjDQNEFbaC8w3V2v76HblXbRRUpIiWvhSQOTZLznPtUlHmPp+lzgzdffy1u678ph8//Kfsvg1LLli1j+PDhBAcH4+rqSnBwMDfccAM/2gKDr9t1u27X7bpdt3/UWgKlli8XWlBLlghxyXPnREgGiNT1IMR/gT3+ASQ+vICGjFzBqrj5ZjAYMH3xKQCf9oQaYw0nCk8AEFAqPJW6UH/8u/QBILQOLl4Q+ke+V8ROf0aYC3F+cU5VjfCOsOsOVV04SYdc4Slpevfmuf7PcUv4DWR/CBfmNXL4otiFP+5eifuL0PZhQBJ1AahqrKLcQzBZAKr2bCXosPAOjkbALWdg1iEzpUsXigL+/sJjsIlQeyt0pKZi5aAuEseNE9vxd9/dctvbzN1ddc7PnBFhMc89Z/8t30bwbIQwrzA0klhOZHkpDq4NMCgXWjTFnrCiPTwyEo6Gg1ZZn1adcBD2HjECpk5FVy9AhbmDIOwpeGakA439GqBU2oaFHF7zaYu3cc/CYxz9Gr7aAGXvgjxr1rXvWWHRyamp1BlV7zVI+dlaH3dnDyNKAeT+ahs5M5OCV5+krlYs/gfHDeaGRFXA1bdRYvJZGL7t6l+DKi3YLS+txPAmjD8Hr2yoxdKjWzPBcK3CjLuobDAfEwQH6g45C5VvO38Qq7bB/rnO5zgj570gPkyZgvGD97j1ZnWr2YqF08UOHqwss729N+sTzUxeM5Wtl/8krM1i4dclFcgT74AbnoJbxwMyBoNM+lmlk1y9KtJo2bSpzpxBckCsZMWDPx0CR8zZnN7fXHjYyZqGWp48KQAQ25hp1aoZKLWc2/DcuhafSgGmLNbcaj+W6Qc745QPmzcLJ71LFzX7VUsWHw8jRpAb2o1K/ClEMBvydvw5KHmuIY6PpIdZ4dOX2+6wsHOnOuSrqlTf7RJCK8vNFvqanAzLlyPn59M4erT47vbbRaqy11679g/a7qGtCjIwapTIkmgLNbKFslZVkVEdwiJm8iUP0q4dnCOFLOIor3FmVZkynOcnt4un8ElX54Kv3y1Xx5mLi2BFKIwcW5zY1R/+YBo/EEoh9/MlBtx569Jk5LJysFj44gsY2rOG+a0XUHosy944jqDUQ3yOL1VsCZ8BCCbFQXrTgyPczM+sK+/vzKro358PnihgMj9jYy398UfLewCOdvUqdFKAiBksZkL6WyLUqndvO8hSX1jFRxdupIwgtn2Srvrwvr7Qvz8lymbICTqzh4HcgnOoatmxTA7Sm+XcBsDO1CdJ5gIf8TjfWO8ShRwyzpWWwPf3HWBUxAlSU5tLv6WfMIISfucISrXt7cdlEgDIP5ov5mEHJe88IikMEHUtIYi0T/fbx1NQmar3E0E+BbnifWG1QtAekXRhvX4yN45TQ0NTUmC6z1p+RIw52dPZW6/Bm9tYzkbGOEWUxnQNoowAconC7ZIyP4WEUGbwIJM4AIzH1fYoKoLTiBv1ymxZJ6i+XkwV0pdfcC8LMSH6teGE87j1q8wERLjcMboStn2puMnqao5vL6cNorznkJ64eruSQRKVlSDLMg9ufJC92Xt59LdHSW9I4CNms4iZdlDqAb5kDBv4WkkkgE4nEB5bGLG/v8qU2r1bdHjbuxL1HmsbdALAAhWoVuzQzzlM2+QcKmvdsavFNrmmOW6C/fRTMykFG15GmADwPYwwbN9aQIBSJvT2EEz7+9XGnAwPV1I0fgUzZjhd96eG8TzDe6TRldYZm8SaRZaVnCoyi7ibDkueFmvGv9jQurbJzcL3Skpg8qJRzOJrDuPM0LqF5bzCXAAsnu6sTl9NVWEWcnYOwwt+oAOnWOk+gwULmuVy+I+yfxqUslgsTJo0iTvvvJPt27dTV1dHREQEdXV1bNu2jWnTpjFp0iSs/wxH7rpdt+t23a7bf7atWiW2agcOVL+zhY80NAgnpU0bsWMGKiil2O8dikmUn0HulCIWHkVFsGED+qJSal1gVQq4meDirjWYrWZCK8VulzkinOTYVK76ieuUHtlNvameuDzhddS3jrcDMDYL9wonPRhOhUD9pXS8TIIBFdBJhC31aD8CGXCxwtXfxIbN5YrLmLWQq4BZNY0KKNUgWEGHRNQL8o8/ElzeSKMWDkbBFgV7anX0GnqNo8ROL4sXN9flsS0SR4wQIWrXSm28d6+a0eull2DpUmetC5sXDDx+3BWdRoeXXjgKVzyV0B4lK55rrXAsSzzA/PvHfBZwIwPu9yFyDvg/A5c6RqrXffNNWLGCY71iyfaBy4pU2JWKK6pQfI8eYgvRy0s8+169KNE20nXcfXS++VF2pzUBJGSZsFIBsBwPF7pfmlN/IvqraJ6Yu3bGIguHKaYSRis4Rr5rI+duFOEr+SnRqq7FXzClqp98lKjXPuJrJVnX4LghDLC8hndNN5INM5gSeiOrVsHHm2Qul/0Nfaomir/+RdW4WKHIC7oWgO5oWjO2TtFLz9DhAfhaITr81A7uHQMXbhqkFjp8mKuvv07bJmSyPDcFWHJ3p2jmLRQrfuG48/DrMtA/+6K9bH2btgybXMOtN4NkhRc+v5nipYp4uSzDgQNq/U+c4J6nA9izQxGsDrrAz7rRlBFI1pbzImlBQoIAQn19BUuniQqxpOxUH4yCnPnQbeCtqCrfLZiLixBInzJFMAGLioQ2mNUqnLfw8GagFABXrxJsEKDUvinzGXk7DJgBxV5CIwzAvGWbuDdZFmjFtWzGDNi8mQPthWNpY0vVHP5zXamtpV2ZPb6aD+Z8wrGU4ZitZic976aglN2Sk500agD4XehlydfKjAUqU+rQIQFgtdTPbUiA0egkU9feIcq5KRHDXODcwfpVrCcAQWvwoob7X49kz7fKOAgLE56aol1kc27b7F7AD0znYT5DHx2GBplB1p1IQYFw8CCrlhk5QWferX4At16dhLO+bJkTKFWNLzIau89ri8q1mcnUHG8urvfiLO3RYmY8a3nP+Bg7N/45KnV4t4HOnACgDg+htbRTCRNUQCnPc8fwppZy/NmW16YZkdX2bG19pRXO4dfm887zxpUrkE0sRlw5QG9Kl24WTDTgyO56DJ3Hc/c3/bin4DXS0sQr19Fab/2cKnx5i+ecnmXnznAMMQdqTyj6f4oGG0AO0UQPS+Y4nfmdG7h4utEJ1TIg+qEOC5UXxPshIwM6GwWAWtJxmFPiOa1WkHc9FcHzsgZnppQj4UWrykvROlkignxiyabK4mWvZ02NYAsBaC4I0LX+SiF+tTmcpBOXSaC40Y+mdua4ibW+01ntfw/+X73DpzyKFgVUO+cMSoUaMgEhRt6V43hknadm4jSsAYGYF/1ALZ5cJIkOgwLtmteVlZBRnkFejQBd258o4IbTc+mN2Bizuot7iCWbm1nFDBaLE8PDxYaTbZAFBIjQVRCi2rt2IbupoNQZRceqrg77c9M2Gdcffgie1HOeZB7jI57mXbKDuvIP2dix8MQT6uemIH1WFnoaIVC0nXcjjD8jwr7LCESSVF0p+yB0ZEq1YBaLOvXrMfJa+iQRnr1zJyVZ9YDEKm6mQeclxp9Ny/IvzGiEeTzBHD7At91XDNgYyNJziv6V0gFff11Mj4uYyac8Yj/3Ix7jJ6aSprBrLxkLmbxqMsa2SUixMcTWneUMHegwOIj4+L9Vnf9v7Z8GpT755BN++eUX+vbty759+6ivr+fq1avU19ezf/9++vXrx9q1a/n005Z3Lq/bdbtu/7lmefYFTP0G//303dftP8+io4VX46gJZXOqGhqal09MRE5IoFgfycgbE/m6K6xcBe71SjjMLbdg+X0LAO/2g6RyqHobxj3wIUVV+ZwIg/Qg0ERF0z6kPa8Mgttugj88SzlfnE6ujxC71rfv3Oynw7zCeHIEdHoQ3uhp5NZJ8NwwaBcugJzBCUPYFSfKSruE820LC7SZjSlV3Si2qw8pBJygnwX9/1AkhIcmsCMBrEBMbo1gDGzdKlZD2wVlnJkzhRDsH38033L7C40HQIzJ/v1Fmepqoblz++3Ced+xQ3VSFRt2VfyGt14AVcVSvShTXQ3e3vgYxEK5xBM4PwGW/UYv6XHyfaDSHUrqmoMHbz6QQuwc2KdIUpqtZq4q7XXoxbtYtuNjTN0UAdcDBziAYGPprXBx0xKna8kVFXg3CnBuvUgIhfvlrJb7ENiZUvUd2ti/qncgeWSby3kq5CTDpkHn8QU0+irOTktMqaoq5GefpbRNDD6rN2AFPuwN3i6+LH9lIvdPSaTmgyNcePc71u/uhlkCVwtknTvY/FqOtm2bcGTvvBNkGauxkbBKAdpl+sEZW+IlB1YEQG6DgTOhkOMnPh+Khq+7wUGNmwBk3n4b+vXjgRW/s2gdIj6vQYw/o5uqCVRYozowtXoB2HVeutXeBz9dqvbt0Do4/GEVQXfeL0RKPv9caIjNnSuaaKPQf6t2cEKDXTIJoILGPYeQvxRhqrINQF28mDIl0+F3nZ2bZX0ylNmIlbbx0JKlpsL69WL3vrUSJqRkpZMTE0GSkG+9jZTYOgZEvcU7SpSaPj+D49pWnAuC7OgCNifBH5FiTlrXBu4cq2dMxfcYJ04VJ/wNBWyb0PI52lJAGEXZ1+iXiu3bL0PnHwC4YNzJe/vecwKlqpRI1xZBKQeTS9T++vLAPQC88IJIJrl33kEV0LY5kocPiza6+24RTuZIq3EApRLSfmYAu3HDQIcOkMJZ3uI5kjbMd/r9T6XHcMPAYISoeByCOXWQntThhSzDxvmKo29zQB2ZUlYr7QpE2Mt2aTghvRKc79fTk0ZZzxKEFpKXWWmYhAT7ssMmSQNi+MoyhP36NeNZizfVtOYCQ9lGXq4zuG8LCZKR+JDZPMYnXHn5O6cyWWuOcfnbXfbP+RuP44KZQkJZhMJQff11ASQ0CUcrIpSXeJ0LH/wq2n32bFi3rhkoZbO1iCxdj+Y/y30sIFIRkHfMM1WJPwUdR9iZnQff3U1362Ea0VOBPyBzwKbz3dCAvGs3KTmb8aEGN2+9PZcICBKOi5sYj/deeVZ0FQdQKpco+o/woCvHuYNlnLviat/UOO/djcn8TA6iHoZLoq7HDxnpgNgscO/XRLMKMWX4Ip5hRpYz684RlHLcZ0lIAItWTCxu1QoIGhxMba0KSnleFXNk4ydfkUMMA9hDKy7zltdbzepw+rVfuM38A7fWf4t7aQ4WNAxjG6kc5Ve/O8jecJIrrW/kws+nibaK/mzLlueWfwXv9T+isZh5eu9Y/KhkKNvp3t05SeSerD3235ucDo9kvcqzvEO8bzl5Cf0BkYnPMTxSjohwan/8/QWKlyLE5vHwoMZNDRW3M6VqsZ8nNQGlDmeGsJBZjGITn/AY7/M0WdomY+yvbPx4mDdPzSrZBJR68dgEavBmaKMAI2sdWG51eBIZKcApwA6GV14QoJQxMEwM2KoqJ23MijN59LXuIYgS6vFkuftMceDuu3n49RA+4yFWcAtftFPAqHfeUSfNP7HCi9U8wXw+4Emk3vOoNlWw+tJ6jLhw6qwG2WgifafKoP6NkVgUiGU+cwAJHWbqNJ7kWsXvVWjEO9sGttrI7v/J9k+DUosXL6Z169Zs376d3k1ELHv16sW2bdto3bo133333TWucN2u23X7T7Taaivad9/CZd8u0l/5m5mSrtt1A5Up1dgIn34Kr7ziFIrz5bQDhFovsLlHJiVeUOHucO7NN/PbQyMYfRu83U+EMJm04FNjpPz4fm6cBu0ehiJDPPq6VvyUqmd5R9jfmMHZ0nMMmQFBT0NUUvMFs4vWhRBPgQRUucOKDvBZT2ivCKLH+MaQniIWhfGnc6hurObRnzL5YQ10VtjoNjCqqtGZKWWzXXEQ7xePJiiYI7Zjv/8uwoVeftnOesDNDZ56qrnAuyyroFRwsGi7GTOas6lsIUx+fmraYhACLkOHNgv5M7uLlaS3qwClaow1gsGmsKkmjw6my32wI9oFqkXFLTXqArqkvgkoZbFgLFABkFd3wNUPQfPc81wovcDA7wdyx6aZfHp8AQCnjmzkxj1qVsMLFc5sgdqLQrC2SNG0KnMHjcXaYmhVXUE2XBThJdXtVae+1kdFTDL0NRQ1lLI9EUpczVR56wX41wIrvHb+O0jvvkvQBQGavdMP8iOTMS7cxb7N4U5liy6l2ENAS9Odhd4tVgvrzq8jvUTUueClz8Fi4fLOLIwmiaJzR9HKYNBBoZfQPQNEyKWDXchxWHyb1MFxNqtQhDg8/zyYTPzSBsbdClJeb/TlIsWerK+yhzNeyVcdmB0JsMA2JKZPx1pYzM/f7bdF/VDoDdk+oJHBdOgAPKLsICvi4pXLhcbMHzFq1Q6FiL7je2YfV0ouYQWGP5tATkAymM0Erhd0s20JIsw13wteGgy7Y2Gr4jdZNv7W9HG0bJ07i6aqjOQJ7UesaJiILMOJkxLnsjz4Y+AeNiukKZ/ai4zqcCcpD0OpJ5DdFxacgLM3k+sLS1KNbCmoZkeFuKYNlDp30sipww5gk9Vq18SzYTuP8CkRFPB2ySx1SC5eDN262cetbGjAeOBXvB0uNXfXXHSR4nfq61WWgBMo5eoKMaKBpVtvJbhLF0o/+EEp14oPFvmze7eQi7vl0OP0e6o3G8Z/Iy5oC/m9/Xbx7/r1AkxZtky9vg2Uamjg6bN3sptBJHvkEhsLsWTxHO/Q9pgKFssyZGdDI27spw8mVCRhNwNpo2Auh2vaYG7VBh56SDRbuJg/jFfz4PRpAs3F1OJJVkRvAlKbUAw8PfH2hnd5hqtKqBaAtVVrOyjl7y9kqt7gBZYcTqbk0xU8V/4Ua5lIe85wjrZsYzgl6Uqjfv45dOxIn2Nis92Klk9cnwJg7Pn3OZ0mnMxTeyoJnDSQxHsG83OHVykukpEOCaD5IL3YhqKvdfKkmFebiMdEkM+rzCX4l4ViI+Cjj2D58hZBqTo82MpwGnDFjyoW8ABtEGyTpsnPHdlqnscEi+9HbuNezbeAxP79ysEbb0QaPIihZvFOqU3sRFPb0+Ux5fxbBXHNARTJk6JtwwpQ8HqFKWU2yWxiNLkKKGXOFKBUwdYzuGKkHH8ShzWni/TpA4MQGzp555zjDB0l0RxBKb0eO/PEp1F5hiEhTqBUYJEC3CsMWRvY01LS3g77BduzHjF3HiOVPQwkjVSuFHmimzyehEtbiLi5D76IOu5FaA52KxHznAkdV4nHgg4pOpqwMPU1azDAzqsqKNWo3Ms4NnCH6yoMHXtyA1tozUUK9HH2coaoJJWxC/aQPMdQ96MDn7SLxdtAKUemlKasTJR/7TXkP/aSW6znPhZyFRWI+jMy8I6FGWyKvo89y3KaH7SBY47v3Pp6WhlOo8fEhXglSYUD1vi17kHCw1VQSi4p5dgxmJw5j3v4mh/PdBKTp58ftGqFucZAdTU0/ryBPQzkO0S46ovmuci+vpCVhaupjjAKAYlVLrcLoL68HN57j5qa5pKbjlZxQIypfMKojBIUxrVtwTXsEJ1Kd3Dqi71sOxPGJkR24zKC+JnJfMn9aLASRAkhFPNyzDiGC117e8qCtUzAg7oWybn/afZPg1IXL15k3LhxuLSQfQPAxcWFsWPHcvHixRaPX7frdt3+M+3A8kz73+e2F1y74HX7z7ZXXhFaJ44raUem1DffiOMO2kmLfwuBiOOgEatUW0hNnXsgBAcz78BPbGoNFi2YTT4cUNhI8oIF9mtsXRPBoP4uJAeIxenFsoukFShC0BK0D3UQ13CwcC9nkEFCom2wupspDRoMQPdcmVVHf2DseZh2CnyUKKam4XsnwmDwdKj1ECvTXXEC3IrwjrDfl/z7782z7zmaySScGhAr96eegrvuEuyQN94QTm9TFWCbE+rIpsrKEnpSAP7+NJgbuHMCnAyFb24RTBNb+F6tsdYusm02y+SG5nAiHKrN8SCL2ApjuerAlNY7MIzOnAE3N5bMVRkmB6Mgrgpil27gnS9vp9EiGuy7E2LDq/jFx9FbYUccSHNhQeBVu2g8QNVFIVib6QdIos4A5iPOeksAuXdOAESGxT31KiMswCWa4dNg5ji4HO7mlP2wLClStLPCSsqvzrP/fvYqoW/2QW8IfRI2T7ib4jeO0pjV2d7EX3+t+GulyfaQUcMlZzbaJ7veZcKKCfT8pifZVzLwPygAl5tyP2H4cLh8SOw0Z/mKezxra15HptTFi3R89x3uUxKv6cqFU9a2GJ5+dq49zfr7kzpx01Qo8YJ40xg8rSo6mlutaPkUO3snT4yAC4FAXh6a8FCO7JtJznzQWAGrxs76K/7WObuUfPAgUecF22WlQ+6AY60EahBVcoj2k4uIfAK26y7yfZKzp3giDNo+BJFPwhsDhej+bwoWo136A+Ynn21Z7EeIt4i/OwmH+/TyM8y3PMZtGa+Rl6ckgNMaIXaP6DtAjKkQKdwhc932N6EsGfIdgOqIoxxpVJz4kyc5cdiIuUs3/Hq2ZucvleL77GwB2kZGUlMtQ6vNWHp/AjoDFRUODvGMGXDsGPm3zgEgf/Mpfi0YxwWHiBOT1cSVzneCsutumw6dQKmEBDWuKS8PbWEhuh8WAXAkxBWDPpufJq/iFeba2SiDN8zm6IoMGD1aMMtuvdX5ejNnqp8VUErOuIy7bMCEDnNUHPtqlpI35HMAvKvzWb9ekPsOHFBJ0pKrqxPIkhEx0J47YBeDObPqHEyfDsDqNIEw/LjOE9MmEU66m4GExeiJSvGh1MaqAPD0xGCABtyZzYcA5BLJ0auB9t/29BS+fAT5xJsuEvjEDPyoooAwCqN7UIhgaNWkK6LsBw/C6dNoq9V3Uvyrd1FECHFkcWC2COc59sxKvBT2w+Qzc9kcOZOsXA0XSeIgvdiNQ0i6wdCMKfUw4gF3Lf4Nw1uCYVbfunMzUKoSX4aynW+4B1+q7ODeBQQrrqmTbT14GF58kfpFK0guFVnhsmL7c1vb46xhIs+dm0bFmTzYvRtZktjKMN7laUp7jaGpVbXpSQxZTGexqJcDKFLjG+XErKqqws6USmw4iwYLOYiMrVKeAKUshwVDNY2udE1tLqqTlARP8R7H6MrmwNudjl0rfA/gxrAT7GQQgZRjSmprB6XSEUBJZOVZkGXclY2Ao3QDoKxMprHW5HStxb6PsomRdOYEj7t/xQy+tx/LyID3jLMB8Ea8H4oIsT8rP2Vc7WQwsuJ6jx0rznXc+9mTtdv+d6PDvZgDghk/HrZyA4bQeBKHCBpxJrGcfGKJU/tXxYVTWVmovsvd3SnelY4GmWKCKUHsWjQDpfbtg1deQb7lVkxKm9oi9cMoIHbvMjEGWjCXR+9nVO5CMu9/R0yttbWibFFRy6DU8ePosFAghZAbJMaKrBGyBwDFAW3w9lbD96S77+Lrr2E7w/iWe7jnpXCBKCso5KAOZYSGQtbvgl1pGwP5xiBMz7xk/9kveQCAghKdqqX31ltMTDpDQgJMnCBTP3ISTmkZgYY0Ufdz7k3CBoMEWFX/i2DhlxBsjzK+hZ94kC/JIo4QivmK+3kx72c7GpWkMC4DKacej+tMKf4LoJRer6fuL0Jv6urq0Duqzl2363bd/uOtdLfqKHlk/okQ7HX7z7a33hLAlKNT6QhKOWbfQ/iYFy8CkapY7jPD4P0+MCzuW6xWmT35YuFAbQgcvZ/5Csm346rdjLfhADUR5OaCa1FbhmfAvQfNnP/1ezvzY9/adnzxhYgOciQZtTMHkP4ZyHNh0FVI8kvAw0UVaW/Xayy53iI86+TPnxFXKb63ZaRrypQy6SDbF7zqzXY9qXOHogn1DFdBqa2/q1SLJqDU72fWcT41FmnECPQ7d4rF20svwaJFgkWlMCdswiV5eefZ9shoyn/6XnzvCEr9/LOqSurvT1VDFUs6Q+cHINsjnPvvh8oisXq1ylYa162B++4j7+PPQS+en7+srrjqShyYUo7he+HhYDYTUmPli18Bq4bfkoQwukuDie9ePsb5T8HPAAHaGPJO7WPY76L+rw5Srm2q43zpefslGzLE31kKC8kGkBz6QISNvbP3HXp904v9OftZPSySy/5w13hUIBLIvxDOtkRY1FUwwRxBqUpjtd0TWvr9HHyColg8KRG5tpZWF8W9LenjyXezNlG5+Fswiv764INCMu2ee+C774DyJDv4QabqTcqyTORzb3Poa+iQUcuWF+fhRiPnaMMpOrJnD/z8mujzpUp3szOlcnLs/UNatoyef2xnvLLWjtQLFt/sgxBbJIDB57pF83SHk2LRbNYzqc0UPK0R9rpcLRWgVG6pAyiV3Yd6PUydDJf91SXlpUAR/ReWOdvO+vNev8X+HACqb5uGFiv7ouFqgPr9wZRMAFJMZ5HqGyhUHKPve9bw2BDhwBt0AgizNHFCd8TDeyJPAboP3kX28aFi7rOqeLwsi77t5yfCPvr3p3D4LWxB1aQrL1dCtKIOgr6eXB9EaKVsIcxXccpkCQq7iL/zu6kViDjG4cYgrK56qKsj/dEFdJBPE0MOGc8LkNLuLHp6UtyYD7eNgRFPQF8BDJ4+DXm7HQSFjqUhy5CzUQCsp0NwshqPU9DrY/E4sgHJSo6rqvtmD58BOzgQWCQmPEvYWfa6dOaL0inM5VXO04YjdMOLOhq/XQobNsDRo8gDBmLWCI+x4aU3cVKUVv42HhPhV5dJpLbfXF44No28VMEQ8Wko5tjN77BkCYwfJ7OBMSziLsb2LeddnmE635PCWTzGDiXcAd8vcNi3+qxkKn3Zy12Fb1O7VoBSWxlOTIwIfbGxb2xta9MwXsd4JvALE1hLZqbQh1GKEBwsMvABaM2NlOPPBNYy7iYd2Yg50pihsD+OCEDSVt7LC+5+yJ2v3B4HYNCe1zl2wEibQ98DsJ0hWNBwp+U7dJhJ5iLv8gxV+LGW8Vg8vUUIsgMoVYUPWwJuI40uuGDGvUbMIV9fGNAMlPKgnmOkYsSVODJxwUwtnuQhBlxTHS/3tH3w5pvULVxKDxQB/L796NxJZiJrGcsG8hZsAKA8qRc3sJVneZfw2OZ+nI8P5BCDGReqq8Hsr87pjcFRTkTdqiogIQG5dWv2MABXGvmFibzOixyhO7IMP+f15nneZJ3fjBblgtzdYR5P0Y1jlMjOWUttoJQkiShzR4tK0DOI3VTjzd4FZ7H4B1FfLxhRViT8zaVw4gRuFYWY0XKCzrzI65QRSP1r85yu9UPVeEaziUu05mPDvZwjBR0mHuETnsl5iIXMohL1xjOJI4tYp2scpBcLF8KmTUK3CRxIzb5Z5NSom2wNjpKPQcFMnSoi48+fh6BuceL+yCXrstkJlIorf4mu7zkgHHo9h0sTmMJPPMs79q8dw/c0lZVIygZWTY+h2JCTdspmweN8xLQtd9jDrh2tfMcJ+jeKcOnOtX8IYPz4cSHi37evepHTp+1odMMfYiwdcktSKUOoIXxRfrV4eanMNVPbDk4Rwz4+iAeu3HdNVhkNDVB52BmUAiie8jCMHMkWz5vYwRDxXTHIkyZDV6HzdFORCBPXr1uJx+Y1FD3gfJ/SeTFfpvs3GQvB4vv4IwKQ/p0b6NGjWRPZ+4G/yYRPkwjtc54BgHQdlOK/AEp16dKFlStXkt8SxxEoKChg5cqVdO36DwqjXbfrdt3+v7bqsyq990R1glNK5+t23QDBPLGtNB2z7zmG7zUBpcrKFCHYKHUnr8odnr4BDvpe4dTFKmQXsSDSlXcgoK4/v7UWLBaAtT/BwvVAjXDCM/9ow+9L4fNN8Nvnlfy+BFyKu/Lm09E89JDIkH7bbWrUlldoNG0V0s/OxdAuxEEZFhgcr+pKDdhyAZ0M9TrIV3xHe/a9BjXEqsgTJk2B54aCQQ8Ht0RzYm84B6PEscbIUMULxQmUslgt3PrrXezTFSBZrfg98ADNVHNtXHHl+xdX3off6k0E/KCo3TqCUo7ZbS5coLKh0v7x8G5/vvoKMtLVEBTz4QOwcCGxTz7CwvUQXAuhrgmqdkaBuoB2Ct8LUJGJlBIgrydUR/OaA7EgqF5oUWVfdmNlzUFWpsD8XnCpvfBkfRrgRMZee3nrVRHDYgN8bM8g6vIuciryaDfzOQb8dIgPtsxlZ0QDbR6GI1FwtdKBZlCreklNQSkbiAgQ/OFCvExw99osDp74lTsnwLzeENapLwHlI+0p1nv3FpFAtqidDh1AjxdXPURn8MhVRaCPHFrDxKO19MgHqwQxu4WTv8KnLwHxgmXwaNlmQDCHQNHq8lMWz2fPCpbcYiGKu1gh8XSJFP1zRXswaiS+6dCNd0Yrc3OjF5pVvzDzpgR8JJUpdblEgFL5lQ6g1N5nIf0mToZDq8eshEzpS/9R7Zk0RRy+o/UjHIoQXke11kzc4/BZd9H3fa+KvrdU0dCP8hGgQlZAHSZ06LCSWoAAgIracyUAtrStY2UK/NoarDg7CG0YDxI8cwNM7TqEbKKRLBYePPMuA74fIMTyS0qEl1xdDRERHIrVEdN7I4vnvAhdFoFkobJScejjhaNl0WIPrcz/8RSv7ARNRWto9AEg0cNhndtqM1uSO3EsUCAfUw/Nth/Snz8tEsc5sBGL5DN2ZuearA/JIoac7RdJ31Foz8gXYc7m3KarGA4roJTC9ntpwEtINo9u0Fzwzaau3gp39cf6TChS++XcMFwWrEjFZIeEBfujYFMS9C1V0YtTkaOYq2SJSj30uR2M3pPmxTTrYp7hHRZWTnFqd9zcwNUV02nhoF0INpMVIzR5yhym71eNzzGNHzCVVTGGjdzF93Tu5caWoDv4gemc8wjB1G0JXqFq/3cEpfLrfNlPX1xpwCtNhDltYxjR0SJMq0hpLwA8PBwSa0msYwLH6OYkxG5jSu1iEFYkylxCGcQuDtOTgQOxg1JkZ4s+o7An/mgQoFRAgBjD8oMPUUgorbnIgYHPkiofxYyW9Tcv5fXUdWxgDJ/wKAChoeJ5TeQX9qwsEnpZPj72Oh2gN8+/pGUo27mBLYxiI904wubqPnZQKpco6vBAj4kRSVfRaCBZyeZ2kdZ2Jk5Ty/YRYz740EZcMVJIKIkjEokZ05E6PPCjiqqjFyEhgQtJKjsqMrL5tRxyXVBTA6VuKiBoiGvreEsClNJoqJz/HV/wIAY8WMGtvMzr7GrszZUrcLC2PW/zPFn972ix7o57Lk3lAG1LhZbydvh3S8SCBh9qyD1aaGfJGfCgH3uJ1hchbxAadWdphwEPjOgJoAJz2in7DdSVNajZ4hx/Gx1v8gIP8QWxZNlDM5dzC/ezgALCMaMi5wfozbBhMHKkiuvamVKxzokRGh3uRxcuwKM2bUT54A5hNKJHh4WyU3ng6SmAcMC32kSWi7qZV1rnzonsAFYxhe9semZAqTWDzJl388vSGq48+qadVZ2fMtRexkZy+or7hEbSli3NtPJM73xg/7s9Zzi0ucJZv7JtW7EJFhJiz8pbvkMwZA8HBDpdK0x5Ph315/Hygvd4mpFsovTJd+36e6D2P6ty/uu8hDv1jEKwiB1BqfI6V9i0iUmsVsaGjCH1bW5bPZ3SNcvYPWcdjyFAfRvgG7RzpZNWlWeW2EBPj3Qm4/j5nOISrQhThO23Mpzuzon3AKhDXR+9tBtuSLyBKTfDvmgYOS4CSeI/XuQc/gug1Jw5cygrK6Nbt2588MEHHD16lJycHI4ePcq8efNITU2lvLycOXPm/HfW97pdt+v2f9zeqX4Qj5hNhLSfz/Pya5w//9fnXLf/MHNkRzmCUj17wvffC+0bGyil7DLbpaWiBGtEctx+i9vNL9tUnaLEkEi2LuoFCMCnQlnw5viAvlGAUqW53ezhVCDCvky/v4Hjtt6KFSIiDiAkUBXFKXeDA792YNgwuPdeWL0afDWR7O8VwbddYJ+NpBSgXs7GlLL9C1DnCmtS4EOF+UFVNMUZEZi1MHAGTO43D4u/AvA4rNoLqospb6zgwdFwKEqHpqoKqUsXsdOvrOiro8QiN/PYdkwWE8vrDjFnBJhsq4K+fdWbDwzEHlNz661OoJSlTmmkRtVLqQ9VwaWbz4LBBZK9utl3wIuvXkNTykGYXRaVRLfyVzZEBmNWDm1SopJyiwyUNVYwdQo8cSPc1fkuFq2FindAXvmT/TrHByYzewRsUNao+6JhV7gXi63T2PHlAsZehJf2wLnKS2RXZWNW/AcnUKpGpW7UNNZQ06CCUp8srKRk6kMYBvZxStxQPP81fuoAT42Ayksd+OIL9XL33ouT6fVC2ihTEo6dztBoD2useftVXKywMw6q3GBEvgCOfpr2LeXTY9A/2JMRs6r4sJcQUbdZephGhFnV1MCOHUg5OVTpXVmrREoN6dgGrBp2JEDwQ114sI+rvS8+6Lmb/YtHkZwMATrVI80qF5uQxbVqyOW90wJpc+lrqBLhOCUp+9jXPZ0KD4j0jmTGhFjSrD0xSxBVAxE18MJQ6KtEf5k0InQvyD2YB7qJ0AokKHMTHXHuLuDCWIYXbUFrdeNCMEydIhLn9XN3bsiv73werSQe4Or++cSOvpHo2bAxCQ7nHebLo19S8YxgCuR4p2DRu7P4+I+YNDXgkw/jZ8IdI6mokAUolbDNfu1nh0GpIsMlSxClVUP27pjsT4K/or0SeAmTWyHLOsDP3SPRIlDrO1nMDL5n6VLUGLvYWKqtKuoS11BFDDnUHjnHurJ+hEeu54iXaP/LH66nzfm1ABxWHsmt7W9V20xfBwNfheB0iNkvgK7Uhc0daSVcsVDvSd97hP6do1196GF+j4jmCN1ws9TD++8DgoW6glt5j2c4e87Zdfhg3G76dG3gnFV0rgtJDlnhJChQ/LEMEvmFiXa2RonWm+U+E4kbtgV0DXD3AL7Mm8VnNYNF6CTOoJRNjziGbI57D6RE8ufsvdP4xW8gS9IXctbXARx0cWkx23uObU8s5AyVkSspj1/IufgCupJGF90ZTtMRnQ7ad60hRyfmVn1RNqQJ5qQcF0dGpfjeFqI2Z64P7wYIltsM00K6ksYkVvPAa+G8eHAM6+5ejwk9np4wbZraMIVVokNVGd2JkXK4i0X8EvM4d8xoQD96OVsH7+U3954co5u66QLIaNhPH47RlTYpGoKDhS4NiFDEa9llNzVG9iipbGcovftI9O6v4xA9AThYlQIZGaxPfspe9u+AUlcj+iIhIyGjadManU59ddueW35cH9Yrouw2Kyy0Ny1gJ640sz8DpWyaUi2BUkntXbmK8Parj1ywLxsADtCHAcatSK+8DMAXPAjAKQRw63HqgEgq0aMHxnsewE6XdjKJi4gQ9hd5g4OIdUUsWZygC1ExWjWDHHDcpaedpGwzFZTa4/S91WEJo48MdjoWG6/BFTFGKs4tYfAPQ8hzFZ+D6gVL9c7UPsxmPj8djHXKKaTRAMnrONyzNUmLO3DTK/sZ209rfxAZ0UPsZZOTBRH4Kgls979ZfPn++9TlXOGjgx8xZPEQbolcwYaoQCrxFSGC6w6owHt8vMh2+ttvImtq69bkPTKDsG0igcvBoetbaFPRv7y9wYwLmxlJUdeRDqCUTH2vlxj6w1A06SLyYhwb7KGX0ASUKhd91N4G7VbCsOdZcW4pDx5+mQPB4zAjWKCn6MQmRqLFSulzgilnsVrwLhPhrudaO2e8rAy/7JQFs5hQ2rZtIhPXZi2MVd9VQ6/CtI7TONYvgX4zISv+KlHRslPGyf9U+6dBqbFjxzJv3jxKS0t5+umn6dmzJ3FxcfTs2ZOnn36a0tJS5s2bx5gxzWORr9t1u27/mVZZCZmGUximj6Nk8hzo+x6nTv1v1+q6/duZDZTSap3DROLjhb5IeLhaRnn7X7oEeOeDr/A6+sf2x11WwJGYvWw/ooJS0X6RdG0TxNiEmzHpIOkReGgUfNoT1i2NEIvb4vZ2bR6LBJ9Gd4WMGwkMhHffVbUr5s8XfluwuxrmVOwJhSfbs3270AyaPFmw5DPjHuGe8WBW3rwZKnZj15SqdGBKNbPqaDtAciEYNu0vJvuSskJ3V4WrF/8i7tWog4lTzJiCg5Hq66FHD7uOwhqzEMH2WLSUK1+/R6OlkT/iIOAZOLltGUya5PTTTzzZkUlT4M32FU6gFA1+BAcLpo/NcrzUxfsX3aE2dzhPjriNWCWSoaFcXaQ7aUoBhkRRaEV78JBDeHdOR1i8hy53BPNNF3h6uCjnG2jAYFK9zt5RfSnyFIsarzRV4PtEnBsf9Ya9ym/XucLgW/x4hdfQ//oLILK2XazPIbsq237e1YqWmVJlhjIsqCImv+2oomDVPtz3HODDXjBZWbcP2nTOTtM/tKE9SxSdZ19fAag0te7d4ThdeX4ITLsJNl7ciPHwQfptFPSqd/pBD6ULHwkXzx/AGHKYjECYcyNc8dNCsdjavuEWE5ZLF+GGG5T4QFidkEijotnRKTEETYOIA6t2KcLkJ3aCXRsj+fyFrvQUPipBrqpHmlOVZ28Dmw3sHsjpwwFMj3jP/p0sCSAmOSiZlBRwqx7HFX8hMt+lAKrd4HwQ3HwzvDIIyj3goR4P0jtKRdVumWrkcIR43l5nH2PJFxHckqim2QZ4sP8dpAQK9ke0dwx947rTJVyE1Fn8z0P3r8n1FVpTAJnvPIf/9yJmZlbQKPbuhcMXsp2uSeJWLpZepriq2g5wA6xsD0eVIZ7tC5N6d8PXVxBd7r0XukV0c7rMx71hZ5BAhE7QiSUIdduNC/Mw7FZCp+LiqJVU1MXGdEs6+iPbT1yEGQNZ2TuPCz7uuOzZRrgphxI3HeuSBege7x/Pm0PfRGtjjEUehkAHHdfwYxQVNxHgb98eKxJhxjpCFAd9m7JD/0cMXDDuQTf1duYiHHXmzYNDh8jPl6H/W3DjY1zJUcddfT08+aTQiao4pITOKMM70lv0nYdHwRdBg0jlGGPZwLO8C0BBYA1nG37nRNsxhD82CYIE0yqnMR26fSnKOIBS1dWAWwVl+BNYkcGHnf0g4gSXzXu479f7+PTWjXwt3cU3zKS6uuUEm7m5QNs18GAHjsRN5UDQfTB9GCeT8sgxBEKbX9BPH0e7HwLJHiKErb0qcuyhe5bO3ezsbhux09sbRi67gzVM5CE+J50UqgeNp00bAZR8/Y3EgQNw6hR06aLWxSbnd/gw5MhRfM9d5E820/W71hR3fwgGvo7m3t4QkOEESgHsmvQZW9o8zsy3EgkJAY0CmJygs/MNu9SBdx4gk2UMR1aQtJl8y+OBi4mPFwn5znqLsRecsR+zRSK7QNULjoqimfn4ANpG6PQDL2cM57Wjj2ADbWxJEm3MWFvYVYnD/oMWM/FcIb7oIBe25zKJn4khi9TmeUQAnBz2azGlmupJgZBPtIEGD/082AmUAkhC7GZtaD2HhQjdxON0wYqEZ0kWDB8OFy/itnc7wTTPFAvYQanb+ZHcBNGHe0oH8AvfRteu0IPDLOZONjGSgFYBzepp8D4Dk24VTE1Ap9ExMHYg3o1qGa9of6dzQkJgHOv4TDOLtzq+z67MXfS8B7yeg2NK+y/pWcVHzKaqSpDLbe3o4WWGG54CScYs1cOt4+js8TGS1YolKZlMkzrnh4WpWSptov7yihVoElvx0zez2Zm5k11xZsbdU8bcuEE8z5v8eilZzdJrY1ynpICHB0fOlbDtyCo0MizsCjubsINSHoTp3Xpyrv3NTsBOba2aqZSkTZSmvMGOqzv4rqPop0u5nbd5zl7ekTVZXg55+VZAFn122LP2Y6vPreZ0nsoinz4d3kEc913zHWRm8u3hr6hxFWzS9PAmnS/oEs/zOgAvKv+2auWQ2dOzCCZPhdSv1bp5wojEEST6KjtE+jqi2uZx3f4LoBQIttT58+eZO3cuEyZMYMiQIUyYMIHXXnuN8+fPM3v27L++yH+Dff7558TFxeHm5kbPnj05fPjw/8jvXrfrdt3+MTt1CujyLWjFKkLb6RvOHan+85Ou23+eOWSNcWTP5FbnMmXVFLIn3QiAReuCxVPECVy6hJOeVO+o3sS4KTQAjzKOZarOWlKoWLV9P3kBMb4xlHnCFz1E2NOI/oE8/DBQFcPxYOHsrW4L2YfnARKLFsHTT4ODNjpPPw2vPx1uz0L2xAig2Dl8r6EBfnvrbjSyC60UgUtHUMrGkCqpuTYoNWFINB0THARXvPM5VykWZSaz2CU1m+HzJeoCp8AHvrv3afWcBMHoeDL8NOcDIaQermxZgV5Z2Ne6wulgqzNrSZaZf+IL1qTAiwffpKIJKPX22xARpG6df1a03f73J7Gd6HR+Nb176Hn1VYiOBqwuYPADIK/CeaG/5r3XmTQFvk6FKP8QZs4Er4Y2nFl1gVn1a+36QhZNA5cyVef49vFhnAwTzzX5fCnm776F8ePJKlKZA5JF8Wy8ipAwM+C0oGn+1A4ssoUGs7rgdAzLoz5YbD0DBTVNkjO4VVIiixVooAHWtBXMEN9G+G6tUqZYZSjceacz+c9m3bvD2ayHeHsAmLXw096FVI4eh6sF1reGbYkafugEN9wBN90izvF3c3ZUPEsGQoUQpjBiYfDYIj6cvA+WLwfgW4e+Ex0YhLtFQUF88sBdLLojXFKcrhnqrjoo+TWiX1UZVVAqMSIQnQ6+mTOZWF9n/ZTkwGQkCca0Hs2PHYTLetVXgvPjaXCBn9vB2wMgzqcVz/Z7ltQI1SPdHQ8974U0TSc+fnwwoaHw0aRnhBouoDH6Mal3Kksn/cAD3R5g5ZSfkCSJEYkjnBvWqoGCLny5AeavFfPK951gy/R5HLh8luzK5tmirlRmkCn/YQ+r89QK7zpG6RLZvjChRyr5+YJ5ExEBqeHNvel2JQK92BQ8gwEDgIBLpJbNw32nCMHclRVHvVbtnx/2Aiswpm4l/r5TwKWBD3tBmzkGNHpRz2876Wh0EaGObjo3/Nz8CNIqnp3/FQh0EOh1q6bEfNk5waanJ42SGAedRHZ1bp8E7/QVICFAg+8ZNqXUs56xNEYnQkoKR8q3wdAXoNcnnNR/br+cI6nVlinrguKQPddPOIlrUuChXq2p1rrxc7jqhSYoUYNm2UyB9ybnxhs0FzxKKVTqmF6YQeOUG+DZAMpvm0Gr4PW8Pd5ZyTsz7DT39k1iFt9w5YrQEEeyiP8VE6DUappZx6XQYTncchP10RswWU3k+AlAL8B80g5K1bZVY3Mcoo0ZcoOVDXf9zA9MR9bXI4+/i6k/T6W4rhhJgl69xNQb4qAHZmOx2cGmkDNs8plITrXaJ63+l2Bmb0o0p5xAqRd+SOb5c9NomyIRGgp92McqJnMfAkgjfjs82B6e94YnomDEE5RXSBgSxFzUnjOkdjPbp/n6zoKO29e8W2ia2V4hPrnMP/8I9224j6JaNSlGmf44PB4PE6eT3rCNzeWfQbwI/2oKStmYUr9eXgM9PwbPIiLI5wqJ7JIHYPn1N37mZhZx9zWZUpKksqVsDLjL5Zd5c8+b1LsJ0KklplREBJSjzpM1NYjNqzH3QafFvMpcTr67mQ9C37eXKeq1nFG3y2xOBFmSYPBglj5+1C4Q3tS0DpsUa25bxMc94f4xYJ54N20715JDDDNYzGg2kZTkfO6yU8v4pKEbdFhhn2+GJwynU2gn9jowqoJDnd11f3/YwDge6dEWg16sHXRR0Tw0+GkSAhTWZtA5cKmnocEZlNJ2WQaBapZaSdPI2kIBqJyQOzmxK0NDVbmqXTWp1A3ojWSx4G6SmdREEvbjqXt42+0B3C+fFjRyEB1fsTNnLfR8/xYeHFrP2FvhvnHY2bmSyRMJiXMh8ENn8PCUmoFS5eWAZIVhKvj03HATt471ZEbwEyzlDu7ha4ayDUdG+9HCQwz4JRaeiIApN4N/pv2YVbay16pqhz35JBzU9WcHg3GxNCLPupdvT39Pt3vh7nEiAYiT6Rp5x09o3dnArIQEh7khbjfoxNps4Az4NQnmDu9OsGcwIZKaCMev1fWQEfgvglIACQkJvPTSS6xevZqtW7eyevVqXnzxRRKUhe+/2n766SfmzJnDK6+8QlpaGp06dWLEiBEUtxT8e92u23X7X7WL2y6y5/QXfPgbPPMH1C64TNuND/5vV+u6/avMbIaPP4Zff/3HznMEpRzs4/1fsCp9FZ/G5LLJsyuTLCvZvFM4WJcu4cRs6BnZkygf1aFuCDhq/7tDnPg+wD2AFZNW2L9vE9QGSZKYOxdCQiQ+8L6NJ26A+5PGQeZg5syBceNE2XvugTffVOtWejWCR0YJ1tXm1i7knEyivBw2b3ZIVFUXgvXMZAzK4rnAMQRC0ZQqvRYoZfBjwkhvvpqnMrIIuMTGttvJ8If53oIdtHQpFNQ677otqnTB+MsG6iZPhylTkGWZMk/o9AA8PwT0p9OJrVTLZ5Q76085hdgBeaVq4cggP+66C2JC1Zv5jSzuHicAlKLdX/LQLG+7Y3b+PMyaBdSLlW5RrfO195aYWZMisISkyGB8fUXCQBr84cJ4MIvnbZINZBeoHnF1mTs7DWIB3LZERnf3PbB+PWE7VNZUCApQqDUxyu8LImstVLnClr9KxWz0sguUF9Q2AaXcq+xZv4LqBWYyd5A4ZNMYo0QFepqG7tmse3cgtxeUirCDASv2E1JawlU/mD4RrLtfBAm2toJcxdn7464/yHo8i423bWTJxCXc7rYcqlRP5o9T2ZSvFo6itV179geprJkgjyB8tc0VhVMcMkYChHup/a2oXvSrOqsCSskSrZUdfJ1Gx+xezhuRyYHiXmaO6cAbcX3pfD+k59zHnAH3O5VbOO4L3HRu+Lj60DbI4ferohhUuoK77hIORpBnIIuHbyZRGspHgxfhotXRJbwLX4z+gl5R4tk/0/cZ3hzyJrd3uJ0xSWNpn74alq/nVJAAbwu8YI6CW50pPkUVTZhSQFbtJUq0akzRtA53EVgHKcrzzPaBLmFd8PBQHeHBcYOd6g3w0BhI6PYUFfd2pXb0RHi0NfT6iDx3PZc1USzOGYpRr/an02GwLFmMo/2bTvLoQaFnFVoDgw0nsSKxoJcATlsFqJ021FUBevT1EKPqqQFYQo86gRn19bDDSzyXMIU1UuwFzw2HIof5iMGvMp41/PJeBnh7c9G4036ozHerHeiyiYYD5GpC2R0jcSQSQt2imd55uh1EJPYPuLsfpvv68JwiWfPqIPBz9XOqb4in4vi7V8KgVygogBVnVtD1m/aQKMTNab0Jbh1rP2dK8p1oJOV3BrwBPjlUVUFdyHZ4Oghe0cHzXjD1JrJzTRAmNHE0sgvukjKYkn6zC80D+Lj6cDwcXh4E7424QmGAJyQnU5rQQ4BcHZZxKe4pPjr4EZNXTsb9TXdO9OjOA8/m0PGlu9ld9T0rz65k/IrxdkanLMscM66ATosB2e78C/DMCmPuw6oAHEPjh9IuWAGzPUup6fs4pUr/c3FxIsYSEiJC0aawimxiIew43DoOQs6CpDyonp+QX5dNgYsAjttxltRUVdDT70YxfhK5wuWlB8jNk6H3fHgkma+Of8bCtIV0+aoL+7L3Icsyi0pngneTubCV0LZTtLPtoFRNDaxJX8sHuZNg5OPweBzFo9/BioQeE2PyxA7PeY9UO6DVkjnmOUkvSafHNz14ceeL5A4ZCi71LYJSkgRzkn6kQuPJXe4fU1ltgakTodtCmDgDQs5wNmoEhcVK/wk9BcOeZUsSjJwGz/58P2zfTnppy4AUwLKu4j10PEwkKHl8JHyTCrUhORzxec6prCMoNf/AfO745Q7MKIhRXTDDXV5hxeQVtA5szdEImD0CHo+aam9Tm3l7g0Zntic4ANh8x2beHf4ug2IHiS80Vgg9SWOjyi7Tu5uo6/aa/RyX0i7IGtHPGyQd75vnOCXkdQSl6urgnkG1bI+HWWPhy6nxpN2bhvsFwQLFvYJ2Pe9hCUqM6iOPwFBVn+qtX9Yix+2kXg+/RjrovwFSfShBemW95n8ZDw/nENHqaiUrafvlECrYwxISRd6wIrUOy6QZIFn5lnvYgfqbRBxhfskNlDTmgnchJAshf2QJvSTWlzmB34NXIS4ugtA1arTE/SzAgBvStq2kbDxCgwt85ygd6KEyY+Xgi+ynLxZ0hIeLZaudKeUQkrmnfCZj4+fgUSzWnJ4GNeuoS/h1UAr+G0Cp/22bP38+s2bN4q677iIlJYUFCxbg4eHBokWL/rerdt2u23VrYpnHFtM/z8ygTCGA6maBsKq9mEyqYDRASYUBk1n5wmmb9y+stlaIkhYWCuXrmhqwWp2pvyB482+9JdLcv/22EHi0ccwvXnS+ZkODAFeMRsE/t1iEOPQrr4g4HKcL/4k5cs5lWbxhL136W+cfPHGZT++4h0uDRgg+9YABOK0cWjKHdpNlGYOxsXmZvDzYv9/Zs3CwRpOJP9IvUmJrm0OHRKyaowiEoxUWCuqAxSLEym+7DR5/HCZO5MLe/TQYTaJ9myTIMFssbDt5lsOXLmO2WDh0QsR01mmdV5mfHxKL13l9YfRtGtYxwf64Ll4EwtV69YzqSXywwwo3Qk3l3jlBBat6R/fml6m/MDxhOB+OEKE9vr4iRK9qyyLmH8mgYsNqRo2C91SfBRDSVh99pHyoCceshYxASAlJJipcj78/jBgB33wDP/6oRCIeu5ddcfBje/i2jbqDu/rXatasgYr6a4BS1dF07QrhXg5MqS7f80X/WpIeg2fPf4ps0zT2dm7fkwWX6PbyaLx+/p4vlvrYWVlGnWCqDJtm5ZJDQqOmoFRmZabT56xiVRi5bbwfGg0kxqhbiCXGbL7rKgAUT0Kcssl7eMALLyDYR0ADlUKAWrGzWeqGUsdE4Qg8+qgDccssPBOLZMBgdhCNMbtTVN6fM8rivcjdF+sbb7HVX+nbVi1tAoST52aCXysfA0TIlLEFZ8bJjF5gFCtkRzYVQHybSjQKtf/jzeBhhIWpcMskmDgVKE/gsw89ue8+oTXevn3TiwtLTgYvLwmO341XI4y5KFKCT7kZKnNHwv6nwKrGffSM7Em7kHbE+MYwKmkUd3S8g0i/ELu2EwATZpAeXclmn5spfOkz8BAUPcnqgpfei2C35qBUn9bOoFSArx7qRKOWGgUo1aBRQKkGP/x81TrN7DoTPzc/9Z6CBPjRt69E7OFN5K08xDDj57w+cyCRnnEA3NF+OsMTh9vPmdV1FgAdQjqxYeJ+tv/UxpG0x519h5Px8jYeGTaxxXb0dvXm+f7Ps/SmpWy4bT27Fkyge3IUX1W+zb1jYPg0qFCw7qvVFzG6NA/JKWjMoMpNBTPv6X4H/bPUSlS6tsbbMbsd0D2yO+MsP8DWd2HZb/bvr/b7ifkuQ0gzrAXgo94Q9YyRVi/ms0d7AIu7s2P/ygj1fVDkCSHa1hR5Q/xjML1HN7KUKSPRX03VFO3psAkcr4JHAEQcc2I+ZGXB7YNaMfJ2WNIJWge2bt6IILJKdVzBWSVZbqHLPvsha9Q+cvPFmHV8dTzdaiiD7pYx6uCG+FF46b3wrm+vXi9SbAy800+E6XzaKYQzD55heqfpAHQN78rBmQfxdFGy0aUuJMtwhvt+vY9GS5P3V4BIYIDZlc/Hzueh7g+Jz/p6uOEp6urA1H2eALdAaG61/YWCwBX2NO5BtKWb70hx3K3KDlZFabpR9nQZsjSN1wfBzx3N3JxagHzuHGsDzHB/Z5h0B6e85zF7y2xWn1uN2WrmRFEaS33accqyyl7Ng7kHmbFuBsV1xUxeNZlnj9wqwJAen9mfS3090PUboQUGJAUk8ettv7L37r14NCjgY/xOLlcLaoqfnxORlVBH/96rUABSStZT6hXKhsbCJf/PONco+soYfiU1VX14HQcH8jkPsomR7KzqSlbMmyIjpINgdkFtAUN+GMLLO1/miuG4+LIsSYisAbQS2W1tYJQ9q5zWyFO/qxpVuDTQ2P1Lcj3EXJ6KeG+XtEtyuq+mZgOlanVXGb5kOOUGMZ+ZvbKg/1t2UOpI3hHG/DiGL458gVW2sm70uwS8VMf3D73JvNNzIMohmqbLtxQUKKw1XQPam++wM1sAlmf9KhiezqQ81YLOs37MZobcCcOmASfuhGUbwSRQw23Vn0GMKmDeWhlulQ2VvLjjRfU6x2bBh1n0qJ+Lj6sPrQPFuP+oN3zcNqYZKCVJ4NFtNfgJfbpRrUYx96EUEhIg2OLA2ow45sSUsrRbgtlbjB3p6jBcN4m48tcHgcfD0awp6Oa0PHMEpQg5wwrNaYZNh13DW7F/5gHi3btg2PS6fbNI23YNm2M8OeA9iLw5qgA6wB/FDvpR67+GC6q8j1QdQ4hemcc8S9G4VzsxpbKzwWgxwuCX7d992u8XKFQSN4Sdgk5LnBvJqwCmjaCRFqIxTsygpyTmDFnbCD0/ISpK6G3deSdcojWv8Co7/GPYYyMAK6HxVEUz1H+meq0gFVCy5Y+xM6Vid4v7kzVots6H3z+gKlPcp7VEBaUafa6DUgB/tRSz2549Au3r0aMHbm5u9s9/xwYMGPCP1+xvmNFo5NixYzz3nIpEazQahg0bxoEDB/6ha1mtVqyOXrGDaRxyjF6rzP9m2fJqA5GvpzLhYg3tSxtxFuNTZ/j3ewTQqBPXGXO5ls5FDdcs+1G3AGr1ouyIq7V0L7h22c+7+FPhLhamg7Pr6JtruGbZrzv5UeQpul2/3HoGZddfs+z3HXzJ9Ra7mz3zDQzPrLtm2WUpPlxVsg11KWpg9OVamosSivKr2nhzIUBMoO1LGphw6dplf0ny5mywKNumrJHJF2quWfbXRC9OhIq3ZkKlkdvSq69Z9vc4Tw5HiJdWdLWJ6Weqrll2Z4wH+6LEKjqs1sw9pyqvWXZvlDu7YjxBhoAGCw8er7hm2cPh7vweLxZ/3o0WHjt27bLHQ93YmCjeEG4mK08eKb9m2dPBrqxLEgt2jVXm+YNl9rJ9i8TLIT0EzoRKgMyg0iwyQnUYtRI+Ji1rklyYM6YWqdGXWKkb6e/vosTTlRwPV7LdXahzkUGyIkla0kID+L5tGGarkZ4VVnauPIS2CYhl1Ggoc3PlwzYJbOg8mZ6tE+juYmD2Cy84lbMicdXbh8SaKn55622CbxnMyQtV6L9ayrQNy9FbLGiQMUsadLI6Bs+8Pp/NJ06xZN8Ontu8lFbV1WhlGY1kxixZKdJriao1UhkUzsf3ziC7Kh/JIrPv3S9xURQ661y05HtqKPCUqHdxZ29CChU3Pcbliquk56/njx8P8IgjVlFUhCU8jEeH9+CPDv24aj5AgOk0K36xEmbQEGQw4dnYSK2/DztDXdFSxS/tTayNbkes1JfKxiusWnuYvnlVaIBKV1f2RHkTbIC46gaevuNeTnqZSdeuYFRWMU/vg4tWV/rmqY7B4XAX9of78fGAkQTqI/DUefHzZ/MIrq6kWu9CrrdESplY3C3qmsKs7f2RNoTy8bEOPLB9KwcjfMnzciGy1kxYXRX9a60UeEHfyVrOhlpJul9CMpewpqiMuFCx7RRSP4hsj7VCxDwyDVyrKS/3suOEmj55WAEPFw/CvcJpFRaGJl2ZO4PPY9uHifQJw2q1IkkSkiQxoc0ExiePR5Zl+/x6xx3www+we3c8KSnw448yWq3o47IsIyv97JFHhHbwsbQwvpRac7U6g9GtRtvbyVZ26lQhifXpZ/3ZopvF1ht+gx1vwIQZABRX1jB7tozPozVoWtgvkmqiSU6WkTVhymiTnMXcgeJiK1evgqZ9niI5K+rY6HWes2dlNBqZb7+F/jdlO/2GrPxnu+66Py6zyc3KjTcKTZd3v8pEo9XYy2aWqY50ZKAvVquVNvFeaPKUa0pWNGiQkZk6LkhkqHJos+ho8NUFU6PU4eSlElKTw5EkiavFJRANGjR0bxuE1WolIUFgyF9/DZkmD2S3aixSA40WA7iIsuvWuLLzRHfGZ0m0KYXtcjeeMz9Dhutnok61obTrFMEfpzUYXWBrjJ7h2Q28019Co7SjYzsA9jbS4oGl0QdQ79tWNr5NFf5uWdg2uxsK+6GJ2c8qJXJUc6E9d7xmxdf3z9/3kgTdusGeY7dTO/R5nhtmodwd0iI1uHz7OhazB+R3tztUd3W6C6vV6rQ28Pe3oinohn2/MegSa2d+xNoftvBNfV/wEFQLD4KQZZlI3zBO1zj3td6t2jhd18cHNNVR4FlGpbkQs8WMWVeOBg1aUxCybEVSWCpeei/m9JzD3N1zcde5kxqWqowz2LbRiz17unHzzRo89O4cmLWHU4WnGNFqhFN7PNbzMaa2m0qIZwg6B1D6n10j+fvD1q0wceJsvj0wBi5cgdtHAXDVsl8dR1cHQrxwIEotl2j0zkGDBqtFS8fQjhwNbAVcItcbgvTdW6zPiLA7WL9PvNekmnAk7yLwE9mmNGgI9wpHr9WTVZWFVWMlK2AReOc7jeWsALhrgkyvHJm1xjv5ZeQcRm/oSp6vlaWjjtjLJvol2usQ6xuHpkQZny4N9h4sISGFp1FYaLUzNNIu5VLTbju/u2lwlb15qs9TzNowy37dgbED2Z0l2oGBr3HqzBQaTTK1vqojL+nr2XLqKHeH96SxETRhJ0WYStxOUMb9pI5iDgwx9aAOFeCTrHpuS3qACwZvFg+/hQjvCL6f8D0vDniRCK8I3HRuPNn7SV7f8zporRQMHgWNtWI+uTAK2RAAnX+wt6l39lQC3P2ZO3Au3x3+iXpKof0qTuQ/D9GqH2Cf7/rMQ9LIgIYoTScGR9zA3sqfnMb9pIhH0aBhLAv4ovIP8Mtmf8E27vzlTpadXgahzecIm9UZ6+zfuWpdMVgMrDy7kpVnV6JR/hNt+zoFB6ax8vTvLChdiXTjb/YaLBizAL1Gj16vp13tQxxzewKAhnZfoMn5BH9/wTCtNdaS4J9ASIgsxKu1BrhlAvjmAxrI7QE//4j14TagM1ISs5C3L19in+TOGiaysaPR3oeiEmrp17E3Vv8QfI2PYBn4tb2uD3Z7kLMlZ9mdtRuzxcxbf7wlxgZW2PEGIRM+oNTlKISeBZ8cfHwisVqVuUMDdFvAlSplo6MiDo1nCegNPDShgUnbUqmJOcmVQAuf97iPjV8txNvNG5PVhNlqxkVyoUdkD/rH9EcX3AFNxA4Kb3gWairUOgD0eR8Kp3G+RObGJTdS2VjJb5d+42jeUar99oiyXsVsrvhEHRtI0GkpV7Lfoqpai2bidOSgs07XzanO4WjeUTIzU9E0fy3jOupFDBorOxOA7W/gmfY8BoMMO96EEU+KQqMegYVHAQ2tWkmAxLJTy2gwN6BBw5jIu/j1tS8BiaoqK1arM+hMwCWCgmSsVueNRnO3+fZnNCF0DvcqWOilXV3RBCqVDU+jocGK0QgajZW6TvOQlLWBvONV6nJT0FweBok7IDALS9xGjh0bY7/XwECJoCAxN0kdlyApv/dIt0cI9gjmwAErmpoo+O0T5DEP0LHIitG3iHGtR6Pvq+X33620bQsWq5V89y2ivkYP5MvDkYs6QfR+8ChHk3YvIe22cg7B9DS4XsbTsxMaDciyxIULEgx8DQKuoEGDlDmUrjeMRbPFB6aLjIcMeQn53ETkRl9cXMDU4zM07lWAhkhLf/IWvSfkQzRm2Po+yfENHAj4ELPVDO1XEGN5HatVYtw4eOYZWLb0UT6Y8jH4apAsWuTvdwnN0qoYYr+8rI7loPOClQYkJooN9sBAjXjfhp5Bg4YwulLv6kV1oxWDQZSpy2yNFC2eRYVGgFL/jhjDf1fZv2N/G5QaNGgQkiRx7tw5Wrdubf/8d8xiS43w32ylpaVYLBZCnbYJIDQ0lPPXSOnV2NhIY6PqWFUrDIATJ07g5SSXL8zHx4dWNuhTKXeth+Dl5UXr1uqu08mTJ6957x4eHrRpo6Kkp0+fxmQytVjWzc2NFFteTiA9PZ0GB9ZFrcFIBx8v7sos5sYzFS1dAoBtg6KpcxPg0bTsUiYcL7tm2X19Iij1ESDPrfkV3Hro2mWPdQ8j10eAMVMKq7j74LXLpncO4ZKPAFgml9TwwJ+UvZoSxCkf8UwmnK1jzp+ULUgK4LBSduxFAy/8SdnKOD/0StmRVxt56U/KNkT4oFHAmEF5pj8tS7AXliRRtmdx9Z+Wdfdzx9BGlO1UUfunZQM8XKlOEWWT6+r/tOy3/cMoay/Kxpga/rTsj71CKOgkxk5IlZGXDmZcs+yarkFkdxHOsLfBzEsHL12z7KYOAVxJFWwOndnKSwcvNitTFpRIQFAvLgevJrGkgeQK2zgxE6mkv5Jdq5Cq9uBushBTWU9MZT19m1zHT1fLFyFirB8L0mLSgkWW0FnUpMh6q5XYegODTJl8HPMqVxrg5zqJVp0CKfJ1IaaskXZ5dURWGkmsqcIKXN36HjcZBdi9KFMwumymk61YJDiY6MOhRB++XDGYDDIgEJJqIfUaBKa62louVXzLaZcM0MK5QGhVocHDZMXTZCGp0kJSJYCRDpXHuKHfK6RrLjCwHmKroMhbx8ZOQZyN9OSxrbnElDcyNfMCh/pYiMFAWU0tvZuy6SuqaaVMCSa/EC61d8XIfqLzTtNfifCqctPg19DIuMvqvOhfsx59mC/tCadfdjH9cgAaMWrgVIwXnbNr6VFgItBcw1K/s8BZarBSoavETwM+RhMpZWDUSjw1KZl9KS50oQt4wIWwK2iQ6ZNf2ayN4qrA178dbfQuoJA4ft26i/tvGY9Go8FshlhiCVTCpRixhLq6nuzaBa1bS+AXwEl0RHhHIMsyQSY/8bugYtiyRMHFAoo1xbRr1w5XRUE1Nze3Wdj3668LMltSEuh0bbFaBZBcUFBAgYMCr5cXDBwAXRsXkFOdw5juY+zvicLCQvKVrUedDmY/DrO5lwMH7uVHTyNn8aaGGnCtoaGhmCSDP662OjuYl39r6uoq8fX1JdA9EAwQR5z9eJR3FMeOpdGliwSRZq7gRwXi4fuF5JDQ5bi97PHjZ9V2ATLJpAwxV/jgQyt3PW++mUZjI3z7LRR6XKZLO1E+m2yyK8XurDfexHhVkpaWhletxemaALmWAh6Z5YXVaqWuro4LF1S9m8FhseQo5deuP0L47d0IDQ2nsLoYN9xoRztcampIU1h5w4aJ/x9Y1YFCtORrDDRaDejR04EOGGsymNrXlRP1IyjyL6E9lWzYtYGQAXqyAV1jGAnBwfY6vjvVxNIKIyVRnvZal1FGJpmAcDZtZcN7lFOgawuo4aQVVHCFK7j6VTB3SDAdtmXy4YgouhbMQo5RGVy+/h0oKsrA2/uv1xEjRkB+vjcXM0bya7IIeb0n4m6SHpZZufI47o0TMWDCz9WPFHMK58+fd1pH6HSn6eLvB0cWQMJWCFTYJBM+5YclodBXgFI+ukDS09Npo/enqGlfK5A5XXOaDh0EqublBa3lFDyVGXXb3p10cRM7vXpdPCdPnqSTktENYFLoJMJTwwnxCCHrfBZZZNmPdeigwc2tM1arEME2FBk4cfxEs3YAyCefrg4CM1euXKHSMQ6tiXXu3Nm+AM7MzKS8vNzp+FtvCU1DF28X7r2ow4yZYv0BookmmGDcXHoKFpzOiIuLmdAAd6ALGXVWtJIWSd+D7nNq8dCH0tujvb1fOlpwcFvAE5AIKxxBhPdp+7EekT2Y1kGEtTz665Ok605QH3gavAoJIYQoOdoeanW6M5yOi6HP2XsJspq4o83tLLkgWABBBBFDDP6V/vY6RJt97X01gwyqEDsYAQQQF9XI+fNH8fTUYLaaWXZmPl3chMPr7dqRwbEi7NAPPxJI4KHohwirCedi+QUIhOrKBazfFUGAzpMyxLrTBx+Ont1B52AXcvLMdLnrWXC1KUh3IdtSwJC4QQJQ1qTihzr3JFtu5tE2QxGZ1+soKCggLCyMBL8E6urqSDuVxmDXwWy0bEPWNoAPoGj55J+ZTUFGZ0j6DTfPGtrRjliXMfZ2mOLyOCdNQi9qT9EXgv0ERFSMI9y7RDBgQkUdATrrUmjvEkW0NYZsjeinuppI+vknkZaWRmIsdNn+LHQTIsXnTp8jllgxR+R1596UJ0mJLcBb702UTxSfH/mcPEV3bUTCCNpGt2X6nulYlU0sp/nREzS9p/HemgJ0QKJLBBlkMMh/GoNiB9nniH4eqVjNPUXduxyHwBdoDE8j7IPfxTXDutBfdw9duneEDkshyizur94f0p+jLqyB86dvhy7fYdVX0dD2TbYGtCdCd56Mq27sv1TMobxDHC88TpubqkgnHdv+Vxva0KZuGtNDh2EJtrDAsIDTxaJPGzFyurwOzt1EyJDTBARW44knDF5LYWFvGhpEPpIu3Q2Yh6zkpO2+V62iVceDePf6noLW8FlrADF/dAQshRZ2orL9WtGKXTm72HVwF6GTlMdHHBBHmGcYkcmRLExbCDoj3jc+wuzvtcQ3xtvPP3XylL3dj3PcDjbFWloRqPUBD7havYAuM89DxGXRdlYdJ4/2wNzjUwB+ObwWT0+JLj3qhUg+VijsKjSgEjI5jR5jTQAcfJxpM3M5cqQYjP3Q14/H6JEt1jKjFkFBKtHRbbBY3Pjq2FeEEUYEEYz3HUtelxMAWCwyaWnC2fey+lGrqYTAi9TXF5CWplKYdl7dSbsgi6hvZRRhBpUd5VoZQZeArmI+SShDazpE62QNRt9z4OtBBj5UZXaCnD4EBJYRV3obJCoLxZHfw94wIiO1eHrK1NTEExgYAJIVv07rSKALGklDR7kjaWlpHDmCWHOQSl+PdXzd9RaWdqrD17iJ2Jr9fPSRG/fdByczs+jiEQVEQVknsgOqKSmJgS/O4B2cTesAHfGNl6hWnpVFPkpjo4UuXSRycyM5WngV+r2NBx60tbaHzIe4cCGNLgE+UHgnhJ0GH8h/IpWCo+OJL3iF7G7f044uIGvoXP4SJ8K0UKDEz6dcxVwZQmrSQA6VbEfvn0d8h19JSxMs+smTIbn/GT4/Gg6EU5LThuz6YKgPRqcz41lrUsdzXLUYm0B8vExmZgD+/vEQs9e+jkjSDqG4axpVVRL+/uIZy3UQ39CJK24nyG04j9VqbfG9YrN/NR5htVqRZZkzZ85gtmUPaGJ/hUc4mouLi30d8Vfglc3+Nij18ssvI0kSQQqPz/b5/5q9/fbbvPrqq82+r6mpabHRrFark6NSXV19zcY1m81OZWtqaq75YE0mU7PrXguUamxsdCpbVVXlBKzVNRjB5MGhuCAq9XrKqbQf88MHnSQes9nqASbh8B+NCaJR0lHmUNYXb1wkwUxqkLxEcDRwIjIAbaqGUlkFvHzwRq+UrdV6gUkAWGfCA1iZKlEqqwtCb7xwlcTxKhdvMAkn8FyIPytT5SZlPXFVRDjL3LztFNiLQf6sTLVQJlfYd7S88MBNEmBYkYcPmITDcCXAj5WpJsrlSvsLyBMP3JWyeV6+9rLZvhZWpoZTIVdhQQxYD9zxkMTv5viqZfO9rKxMDadSrsKslHXHDU8lLjnTXy1b5AkrU8OpkqsxKRoBbrjiJSnp6wP97WVL3SWlbA0mRB9wRY+3JMCl8yFq2Uq9lpWp4VTLNRiVsnpc8JEEM+lMmFq2VqtjZWo4NXItjUrqWBdc8FXKnoxQ62uQXFiZGk6tXEeDsuXvgg5fyUeUjVLb1yiLNquT6zEoi1QdWvwUbYb0cG97WdkqszI1nHrZQD3CUatz8aBq8CxS/QK45YFzhFSbiC4BrNDgYSRDZ8K9LAiDazYF3mWMfrwDYdVGwqqMhFQbcTGLXU4kK2khRkDQy406idGzO1KlMPE0VhkXs4yfwUxwtZECfQ0gcsJatBKvTozD0QJqTSQX1FPgp+d4cAMoDv0942BDv3bUuGmpdtfhX2fCqNNQ7WGbPlUK01PDoXNjPEgarBLorDJ+9WaMOg37knxpdFGd1c73Q0dNB7wbJYJqTQRVWgmq0RBgqCYz2M2+a2rRwIwbwyhIGU2ZzwkATsR4cfORYi6HqMISFXIUkybnU+xtxcczEVw8aFVkILmwngbJi7NhISAbQAKjFp4cLkSZ3f2S6Jclk5JfR7G3njx/vXpdi47lrQZy0TMPb65wrH0s9b4BBFUb6XuhjkpP53dA8qNiw6hzIUzIDuJyZCBnopVQDBmQJfYn+TJ6dgfiz5/G1QK5PmD1SECr70pwTR1VGg1QaL9maUUVxcXFaDQaGsx1uDj+YPQBKiu7kplpBK0LKO0b5BpEcXExrjZhawfTy97U1Yp+UFJSgl7J7ldRUWHfpHC0mBhBfS8tLbUDWOXl5S2WBYhyjaKqogpjg/FPr9uuHcx5TMPMdKUNXauRZUnoj7SwueTn6ktpaSmNjY0EuwdTYnAOOzIYoLS0DvACt0rnk71KQFcPZmXeKyrkT821jkaLgXfeccdikaC9M7idX59pXz14uUrivWhs/l50xYewsBKKi8FgMDi1Q6i/KzlKNU9fqKK8vJxjx9wwuxarCxMjzdpOksXzkrUGGhvVPNdWs5HaWhODYvuw7vI68WWbdfYdTD9dMB5WdbxUerpQ6elChGs8+YYse7mWLMhfQ4HZrcVjpbWlFPQqY3SnjrjgyhBDItsNfvawoXCvUCorK//WOqJbN/D3l7BG3s/jx3/H19WXG6NvxD+xmthYDR4e3aiQw/Bz9cNkMFFFldN1Jake0AuHqbCLyJbmlw0+eRT7/AY6Mbf7uPhRVVWFv7ve6fd1Vg/kRplqa7X9uhaLHuoD7WXOZl+x/62XPaipqXG+t6pqEjwS7PfpaBqNxqlsZWUltU3TYTlY07LXGnO2sjZQ6lplW7UCqyzBOS1ozVh0NaCIIPu5+lNYFwK+uZhc1DWJV0MyxcXFJGn7ctFnN6FoifGIb/H6bm6VCFAKoQ+WJBz4tgFtmRg/EUOdmJ9cTRGgO2EPvQHwNrbC6plPnblOhFwdfpi4ZA01NdWMih5lB6Vs5omnvQ6+Os9rtgsujWSW5JJU7ce6y+sotSjPr96fSVEP42H0IME3gYqqCvxc/fCX/BkaNUSAUkBN2EaOXO3V7LJZNReoru5Nblm5AyAlzL2iG3WVddRRR5TciXKrBBoZStrQMaaPU9u5u7vbn5vjHBFaN5BCny32csG6GPJL24AhAFb/CKNnQ+VQgj0i7eeESGoYY7pps30jIrCmD3rrJYyBJ5zq6SOF4K6ToaQ9hCrPIm0WnkMNVFfLpKRA/L7OXC1LhECHVPC7XoHdL9PtqwoSfRW4xQT3tr+Xbdnb8NB5MDhiMH5efmycsJEl55bwe9bvRGmjGBE3gm9PfQ8aCxZPh12kRi84fS/Tb32e4uJi+xzhpnWFvB4QuxdcGiFxK0bUEM/jhcexshDdSNWdk6x65MMPQ6MSP3dgNnT5TlQzZgf6mL3UAC/ub/ZYVZMlODOVVokD7O17S9It1DbUcrVaiWU78ARYdXgUDKY68GfxXdRBvjt7GJPciJvbEOi2194/gvJvoTS/G3h7EtBvM+Vm9T0U4RmJVbaQX+8cen4t6xLchbGJY2mf0p6vd29C9s7F4nOZknr/lk/ITxXr0tg/oDIG0l6AIQJ0Kg5bpradrCU0ZxYn994I3T8DSWZbxnas5tHQ4ysIUjZWYps03u6XweRJ375ZuLs3cuWKlu6JI/ilQMm6lrweXVlndLpSNp85w+ni04QTTqx3LEGuvvbL1NSYqa4Wa1p9fTx4HYeADKqqS6mtEc8hqzqLVefUEFEuTOBSdB3gB0B1uQZ9ZDhGt3zwzeOw/Bj087OvywHx7GxW3AGqw8GnQLwvErZCQSokHea17WWkuWphbDV4FwNexLi25cp5ifp6A1u2uALCr+wW3pYqt8ksTl8MegNEHiIvrz/V1bXsvXTC4fccYthrw0HygoCLaBod2sFcgMWSDJIrtFvJyZQ31Xf0hbFQE0VRkQFwh3OT0IZewCIZRdhqn/nk129RwtXD8arqSm1pc9JJSYmJNgzjECIxS61XGtXValj2hgsO4YYZNzqdazLIaBr9sLpWipBZxby8DFRWViLpSyBZPT9IE0e5zgpoaWwU78aiIm/wjwa3E+TX5nEl94rT3FhnqlNDmfnX4xFWq5Wqqiqqq6uvWfav8AhHc3FxsZet+ZsyJ5Is/yOCLf9eZjQa8fDw4Oeff2bChAn276dPn05lZSXr1q1rdk5LTKno6GjKysrw8fFp8Xf+3Shw1wLPSkpKCA4ORueg9vfvWt//ibK20BxwDh35/72sY1/QaDT/1vVde+AUBnM9k/t0w9So49jJOlJaexIcrKG0VGb5hgIsGImLcqNDWzciQ91w0bggSRIWqwWD2YBep8dF48LZjGp+2ZZHUVkjOkmH3qcSnW8xbRJ8GNQ+GaPZxC+HjnM2s4Sc4ioKKiqprK/Bz9OTxAg/uifF0L9dIt//ksvms4eQtFZC/bxpHxtBtzYh1Dc2UlZdR4ifL1eLitl1ZR/l5gJcZR98dSGMaNuXKQM7YjKbaWiQcZG98dT5kBTrTUZ+GYu3pGE0ybSNikKnk7lYlIOhsYEwnxC6xMcyuldrXPVaagwNfPnbLjan7yfcO5xZg0cwuFMrZNnKvF/X8crhh9BZvXip5/t0iIrhQkEBo7t2ISkinPpGI3+kZ3C1qIjS2kqivHwZ1TOVIF/xor2YX8S+cxfp2boVVlnm651byCkvYEib7kzq1Z2C8mrO5eVxuagAi9XCrGHDiAkWDumVwhJeXPU96aXn6RPdnTem3oFWo2HX6fPkV1ZQUVdLdUMdNQ31pMa1pn10OGMWT6PC7RgA98d8zB29RvDp7+vx9/Rm+oBhtI4IpaCimrjgAFx0qjbNqLffYrtVbB48Fb2at2aMAyDgiSFU++1Rw9Zk6HP4MndOjOL+567AI22xYmVqu6n8eNOPXCy9SLsv1cxnADG6rlx65sD/Sn9vyYLnBVPZWAmlrZE+P4/uRT8s2lqw6OxZKgHu8PqGRY/fKTKMLRvB9ivbncL3/U7aaQAAZ2RJREFU/M1t+bH/CUaO1MBTQcjulU4hedLibVAdCRWtmPzJG/xc+pr9XHvYWlZ/pNi94rpfH4ACRcxz6nhI3mQvq7cE0KgVQNXukcX06erPrsxdjFjmnPmslV8y5x4502I7zD/wIc/tENlqpF+WUrxjCq+9puHjhlQIP44OF+qer1UFjBXzeaI3DQHHkK0avOs7UeOVhsbiQtGj9fj5Qa2xlviP46k2VjvdW6p2Bu/dNo3hS4Y7Xe/zkZ/z+KoPMHlduWb43su+l3jt0Bxos6FZm7UPbk9eTR5VDVUk+iey/7Z0Ih+9A3OycBo+Sk7jgcnt/uH3XGl9KTqNDh99y+sSx7I2O3DAyoABDu0VvRfuGqz+rrJJMzT8Jjbf/RM7r+zhxuVqe7T16MeJ2dudrnv4MPR97nUYJPrLw23e4rPzzwOQWHc76W8t+rd43/8jZd2eTcLinQmoYTxj61ezIXsptPnFqWy7krmc+OQFjp+00O+hxfjpwkhfd6OTCK/NcnMl4uPFPCZJZqTBc4mKkTn9xTN4uKgOYYdnH+S8t5oiXEKibeOdfHP/fWw8/ztr597F1ZORrF0rM3iw6GutP29NZmWmvb6lT5bada1ySqpotVCwiWz90tUcjFFXioTEBL7nrQd6kPKlssNt1sN3uzm5OZWUFInDeYf5Nu1bZnSeQc/IngDEvjCaQo9t9jrax4ZFh6S1oLf6UPVCEV/9vpvZx0Y6tYPn9m+o3CV0oubNk3lu6U8Qchr2P8merb707KmWvdZc+fhz5Xzp0gpcBfB8T+C3fP3odGSbfhEiHPmFF2Reflmcs+xHK3efjQCPCqexfEP2ATKqTpPZwVlg//OEPO6eGoR76iqsk2+DqigCVx+h8LIqsFdbC0NvP86JzkNA24h2y6eYDt8HwNatVgYN+sf7ZfwDs8mP+sL+/cCGD9j13kPIVhd277bSr59adsECeOzN03BfNwe2L3SN6IpVtpJWmOYcQijDzfJqVr0xzuF3NULcu+3aFkPDAXxdfYmpuZmTq0cL3b7yVmiq4vjsM6tITKFYVUMVr+15DT2ezBvzOshaBg42sa9PCFaXa4PGHlpfwtcd59LRWDw9Lfx0dAvjfhJi9Z0CerJj5ia89F7Um+rRarToNDq0Gi2ldaXszd7LkfwjfLPuPJVlGjj6IPVnB6PVivb1bX+A2pFTkXxEKGywRzDfjfuOm1behNFqxA1/Gt4/i9UQQNKIrVzak4pkCER6pDX4q8AwZj1TpdWQMYLly7Vw1wCI/UOMuPpAuyZfU3NvSKTuvbNIso7cXCshIaLfybLM0B+Gsi9X6LG1vfANJ5fcycwNM1l8cjESEt+M+YYpyXfaw7v79ZPZvl2cH/rILZSHCebf3un76RnVHZPFRIcFHbhaqQCDe5+EHW/z/PPwxhviGn36WLmQPJOK2B9arK+nMZGat8+DrEGSZCRJJqjzXkrHDBHgsdkFkEBnbBbaLyHBypVwfqLTNd3cZDIzId98hs4LO4uSxSn4LD9BSTHEzB1IkctBAIaeyWDb6rhmY/nO5w/wg07I/fT1uYV3ei6m/8e3IKesUd/LOb3QfL8bZB0vv2zltdfEPb/w0Wk+2PsZhuTFyFqV4KFBQ6vde3Ep7sG5cxJubjJWKxiNEu3awa33Z/N8iWDWxWq7kfGsWBuuObeGW9cIMcy2gW15LeooCxe4smWLqPOiRWYeOXwjhjCF1XdpBPz2MXt/jcccdoDRSydRYxUbhxpZw4JWBXw+L5DTpyVcXWVKSmR8fDTIY+5F7votAIdmHqJrmMoOHrJ4CCX1JczqOosHuj2Ai9blX/r+tPmOgYGBfxp298/Uobq6Gn9/f6qqqq6JtcA/wJRqatnZ2fj5+f3pxWtqaqioqCAmJuaf/Zk/Nb1eT2pqKtu3b7eDUlarle3bt/Pwww+3eI6rq6t9t9vRdDqdE5hzLftH4iP/J8tarVa0Wi06nc7p+L9rff+ny/4n2bX6wr+jTe6vTsDurjC4v7pTEhICj82Muua5OnS46tWx3LlNIJ3bBF6zPMBz45L/sk7DUwBu/atiwKN/o4ywoOQAeiUn/XVBwN/bi+enjOF5xjQ5ouHZCZN4atwENJLGvpAf7VDCy92Nkantgfb2XZUQf197P0iJiSQlRhX5/jzBYbUJRAcH0SM5gZasVUQoKx57ptn3E/t0a6G0sJzXdvPhthW0CYvhpi4iI0rvtk84lfHzar7L7+fpi7VGvOwq6uvt9TfLDc7AgQTZut1kZk7H6lUIitMd6R2JRqMh2i9a1ZxQLNIv4m/N9f9T5u3qLUAp12pkrJi0ysK+rBWEqDmXe7WLQ6sVDm+kd2QzAKXebKC2VodVWw/uzmHcMjLydCUjzW8fcfxyAVZf53Zxl3zR5I+iLvYPZGSkgMvIeT0AcA3NotGhHW2AFEC7VgHodFr8PPyatXWIz7UXN2E+oWp5fTmLF2tZvRq4WSzkgjyD0Lvom52nxVXct8aCSSPaymp2w9dXh04Hfjo/ZnWbxfv733c6b2DXcCJ8Ipzq2DG0I7O6zWLeb2u4TPPwZVvZDsm+sNe72f0BlBpKqWgQ7R3oGUhQkI45PZ7nnXMZ+FT15a4nOjXLCvV35uUQr2tne7rmOSEap4QRZA0gunY8OV7OQEtihNi8igmIdLqnzjFtmo0NPz+wVkVhG1tnSs7YzwlwD2xW/t/hff9XZT1M0dQoYZq2cZQUEofb+STqmzzjKJeOaDQaUrtoKN9+D3o9aLUtXBSIVKdWZFmHvOMNBt0JPu7O5eI8O+IoMCEj4+cSQe+Y3vSO6c3rw0VeDMcMazM6zWDu7rn2+vp7qoyQ2NBArPV+Tk5zR+0UjvA5MjKX60+wJ6dBfdZ7n4G8HsTHC82fXtG96BXtzIa6yf91Pmv83bnijV5w+QbklDU0aqo4U3qGgvo89bon7oSzU4j3GIVGI95PgYFgPX2b/RLt29NilrSmlhgRgnXVXBjxBNH6DqRItzg4sQASVqtEbKx6PR9vsGYNgLYO/d3kTpQmFaMxliuOz7Y6gij/MPR6CCy6lZJPu0KDP0kdQpzq5+cHP7zXnfY9L4NkwVqrJpoICtKg0/3j/bJr3UvkVq0Dn1ye6/YelZseZ6dSNS8vDRqNWjY4GKyFXeCnnyFmH+T1YFq/ofwwNxBZltmTtYfvDq9i8Y594JuNx8E3GHzbBH5qOlWt/hESton3pGcxnYedRxOcTrR/NHd0vIMxrcewYqkbd6kR1liBmBiNU3sEegXy8aiPkWWYL4FVhroaF/T5Q6iPXdPyjRs9eDJhE59nxSrtpmV0m1EsuWkJl8ou8Xivx/F1E2s/H52zTxnmE8bk9pOZ3H4yR96BnQoGYLGA3ZXL6QsfZhHTfx+PvnOUm9reRJxfHKumrmLR8UUkFD7BB3Ui8K86bRTUKcTtjV/AiDlg8Ifc3nBiOn1f7kCmjdC+7W2kO0cgu9QhK3p8ktUFefMHIrMh0L1NBM+NupN3drgwdixERDhPDm8Me4OB3w8EILPdo9y/cT+LTy4W9+rqwy0db8HDRYdeL8Z8RYXan70Kb7SDUusvraVvXG++O/kdlysFay/M2JfCHW+CVUNmpvqb1dUa5MKuWGO/b/FxdDbM5g8lK6YsS8iyRLewHmw6+Dj0+cDOqG1qMjJyvb8QKLeq/b5nT/jsM9FXg+lE/5j+/JH9B3LIWSoTv2bLpSQKdAcBKxS34+t58Qw7AZmZIh+PxSLGsmtlZ6xeXuBWzYGaVRypnYQ1ZbVagfPj4dcFWC1iXZCXp77v2oV0olPO1xy40E8kElDMmtOThsu9KRE5jwgLEzl4cnKEuH19QRyUdIHw42RZjrL5ymaKaot4fc/r9nnt3RveZXRrN0qKYIudvKnDPW8kdWFiE4ek3yDkNF6R+xi7ZpodkAKwZtxATO8QPDxEHQwGew4mKFETi1wsv0iPKLHmOl10mj9yhUD+opOLmN1ndrPotH/F+1OSpH/Id/xvL/e3SrVg8fHxfPzxx39a5pNPPiE+Pv5Py/xXbc6cOXz99dcsXryYc+fO8cADD1BXV8ddd931L/3d63bdrtt1+98wrUb7fyZ02t3FnedH3mUHpP6u+XuoNISKejU0xCwZmpWtNlWKRITeefbvIrxF1j1Pvaea8luxxJA/yTn9v2A+rsoi3LUG9A5hMNVRwglUbEBHdXPHKQOfYmYaqKrCqR2CPYKblaPrt2SW5TX7ekTyYH74UNUgGDM9g+Rk+PJLGW1gZsuVb/QhwF8swr31zakjge7XBomd6uZZwksvQW6uDJ6C7h3i1ULdAR2qp27S2gTT3HFxiOt8tt+z3JB4A3qtWLxKSIxsM4QwL+dscx+N+AitRkuv1on8mSVGe+GubU7/ByisVan7QR6CYfH24x058+hRrn7xMS1IVf7LzJ7xx8GG+d/X7LtgpZ5N26NbbEqzsj4+QI06Zi5Vn1Kv4xXUrPz/BfOl+UZp++gYvI3NNw7iPdVQE3f3awNSAC4uYjPF6fwWlsBtAjo0+y7IVR3TkuQMSAFM7zzd/nePyB5OxzQa0FY7byaMjFI3VjI12/gjW80ARsYIgoJkPP8k6m9kxx6Qdrfzl3k94eoQ+8fdWbvJr3NgmqRPhkujmfe+A4PTIZoqPNwhI9tfWFgYcGAOfHKJ+/X7MNS0HD4b7ZBs0sMDyBzkXCC3J57uLkR4h0O+uglGUSf7/QcFAWXJUBdCYgtTQZs24CGHiFAjB2tpvP0diw0Kgc/PwofZjAt6EoPDa63pc7enlj8/EX6fB2enEOYjvpQkiYFxA1kw7jP46ji8V0ZsyQNObW43sztcHAtps+CPF3iq1WI2TtzImilrmJwyGTedG+3aNT/NEWh1NEnCPrfV1ICUfrP92KS2k1gxaQUx+i5QFQUr1hHU0ItSgevYx8htHW7jlUGv2AGpvzI3hy7gKGNjNgOyFt/KAczpPYc4vzgAxrQew5qpa+gWqqqROiYt9i66ET5Ph0X7RNsWdyA0FLUdcvoif7PPKaPpaOkzOPwI/LoAfl3AMJeXmTg4jkOH4EWHZHo2GxA7gIltBKuozlzLN8e/sR97ovcTdgalbVw4yua5Z423gz+rz62m0dzIG3+8YT9+Ax+AVSBYjtkBq6rAcvomaPAFs56IM/OgUOh2uTZG0kWjziU2S0gw43n4NShVNm4tOroanmLn9J18kLoBjt0D2X1h7fdgcWXIELjnHlixQiRw7uawN/lg9wfVD2MeZMzK4SAJgMe/bBSxsZCeLpKoOAQ5UVPuCUdERjyzbOKZwyqYzcbPYcVaqFXfWbm56mFfX2WuPTldgO422/cU+fkC7AMxB9n6X0mJyEbKebUSY5eP5Z4N95BVJea1QXGDGJUkEmM4zv0WC3idmQNrlqj9wzeXgcs7288lPxVWrYAVa/H1VeYnxcps+3qlqibkuZJz9r8XHF1g//v+bvf/n1nz/1ftn94u/quQBFuZf7VNnTqVkpISXn75ZQoLC+ncuTObN29uJn5+3a7bdbtu1+3/hgV4eYOyeKwyqLHoFpoLKtaZq8Vi11vVooj0UVfSwW4RZBtU3a9WIddYZf8vmT21vL7OmeHU6EOwWyQlsti6TnSod7h3c1DKIhkEKOWjAk7DEoax/Mxy54KhpzEVKgsci45v+/1BlstvzEqdZU+xDeCfmMH581BhqOSB91rWA9CZ/ewpvL30zdGXPwOlbAAOAB4l1NUhhImVdNwtAmqAXlK9NouLaC/J6uzJBbgHsOWOLRgtRtJL0vFw8aB1YGtkWaZDSAdOF5/mtg63MThehLZ1iklgmZKPQYMWKw6CoFYtcdF6PF28qePPzfGeWnLw/tXm59f8u4HRQ9lcHE5BrapfY3suPq4+uOvcMZiFV5wS3LbZ+d7eQI3a93JMKigV7vvnzNR/VwvSR5Pr+IXRg7Zx/vjLrShy/N7kTpzfP7axGh6upJdXLC6ueZnUqA44yHkCEOrRfEw7WpxfHO8Pf58VZ1bw9tC3mx13NcRTz1HxwaJjZMcevHaoJ0QdosrtFL+cV7SkTO5QkEpMp2aXcLJ27YCt70HXReqXeT0ga6D9477sfdQaVEDhllExvPkbJDjgY44ASdvm3euaFm5rjvJWVBTiBDo7mmMghrs7zUGp7H64d1fqcXYMRChCwoWdnUEpxRKcsT1AOKOdOwvn29FaBH/+hoWEAEZvMHorentN7sHBAlsYYk3HuZsbDB0K27fDyJF/DyxrCXxLaY5JE3Vtsjo+PlBdLf43ZEyFOpmEaE9WvTwWSZJwuTiVSSLSl6tXBSsGBKPmn7FrgVI2/eZrMfBamhcBnnoKXn7Z+bvQUBg7VoAV27dDWlon6hYege5fQklbHv94Kr86lP87fWDZTcuYtHISv2X8BoBW0vLe8PeY3Wu2Ux2LigSgZL+vmmAx3uJ3crniMjPXzyS7KhuAUUmjaJ+nxsE2BaXq6iJhfi5ojbiFB0DufdDmF/q17ot/Owd0RDFvb5nkBHfSvt0PbVdD1gAmzUlmUBzEWOGJDSpzX6uFJUsg4hr7eze1vQlfSwJV2ivOB2SJvj5TATGeg4Kcn2lFBXDwcej1Ibg00GhRGFu1oXC8CUCOYDvZzNfXof9uf4u593di+TIXLpyfiKM6Ung41AvJLqxWOH4cKJoEg+baE03YLME/gS9Hf2kHhJqCUhazBKfugKuD0TzYGau7yprWa1wx/rwcypPs9XPcBCixEakcQalSAUrVGmtZckpoCHq4eDCt47Rm9/7/q/1LY3tyc3Pxbinw/r/ZHn744f/X3p2HOVXe7QO/T5LJMjPJLMy+sgy7LAKyiLKIAloFcSluRVCoC9QFkNa+RaSlxYVKxdrqr61gbcWlrri8igsqCLyIpYpFVGTfBoFZmBUm5/fHmSTnJCeZbCcny/25Li5mMpnkSebJmZx7vs/3wd69e9HS0oLNmzdjmHzBOhERJZQ8hyfgqG32BCJOo2+l1GmhDgcPQhFKuSqlAKDUoXznVOaIs1BKXmHkkJ0qt2Rh2hDpr8+Te06G1eR59za8zLfxsNPgWyl1Tsk5yLGqvGsuaN+i/VQxrh4xHIvHLkaZo0yxDfV3J6TlbO6/+qmwitmex2FRqZRKD1AplaGslAIAZO9xX1SRpb7sXx5KuRqfGtts6tc1mjGwaCB6dJIqwARBwEfTP8Lb17+NVZNXua/XLdfzuLvneJ2ZtWbC4RBUK8G8BQrhYsFo9K1EqSgz4fp+1ysuc4VngiAoqqV65/mmBhkZUIRScuVqZ8wJoCTDa27VVqC8XEChyatS6lgfdMoN7W2y94maWijVsyIXqFNesTiz4wrO+efOx2c//QwXdLnA52sZrbI05WRXlJemIXf/NPdFp1rbqzAPDAPazOioq0ZFBZBp7CT9pV8UpB53269B1ule0scAdh7bhaPN+9zf061TpU+oI3/8Z5/d4UN0K5ZldIcPK0/WzztP+r+gQFmJlp4OqYlyoyyV2T8SNlt7UPOfaUBrhjT+/16lGkqphTUAMHiw8nOTCWFXQcqr6ToKpdQCJrUg5K23pBPshx/2/XqxSt6pFr5lZCifT4tFPRRzcZ3eVVcDzjYB2H4tOrdMcp/Ey49F38o2bA43lJI/N/LnzNWT2V8o5S84uukmwLvTS2Gh9LgXLQI+/hg4cgR44veFuMBwP+66aCrGjpUqE138BV6KcafZ8Oo1r2LeiHm4oMsFWPuTtZg7Yq6i+sV1O3V1npCtpQXAf690X+efX3oasi8es1jxuA7J+sO7b6M1E2jKlV47rZnAFz9BrtBVtUIyM1NEVRWkjQQ+nwUc7wlXbUeeV0HspEn+AylA+r17Z+ZG4LW/AR//D0r23g2sfRB4aj0uOVv5QpJ30zl5EkBDAfDvm5U3uPlnUp8zL96VUrfeCkydCtwz34D7rrgWPc5c5fM9RUXK19/27QCO9YXtrX9ixsAZuHv43Xjwwgfx6U2fYuecneiVJ9/d1vN9bW2eeVeWVYo3Zyo3opg75FfuQAqQAlz58+6qGkRNZxhF6bG99e1b+Hjvx/jnF/9Efav0vve6s64LupIwGYRUKfXrX/9a8fm6detUr9fW1ob9+/fjueeew/Dhvm+eiYiI/CnI8gQAp1oDh1Kw1GHnTgDj1UOprgUl2Cgrf5B/LR64l+8BPqHUQxN/g9kjbkJldqXie4aWDsX7097HGecZXL7iV2jK3QKkNeFkjehTMfbQRQ/hoU8eQrOzGfvr2v+02B7mmJvLFA2bM8wZKMoswpFTR7D7pPSn1z01e/yOPcOY7fk4zfedbrDL93JKf5D2usz2/Lm3i58KFbPBN4AyiuqhlJocWw4mVil30hnfbTy65nRFdUM15o28Ez99Y6bntp0ZEAQgy9ZxKKWo/tJJbq7yBL6sDJjmmIZlG5e5L5OHhQOKBmB3zW5UZFWgzOFbFmEwAHZTLurPWHx6jVQWJGYo1TmnXFGpJNRVoLAQKMwskkILc3tNXPVZIVfDeAcAasv3Skog7Xjl8LxWy7ICV0p1JEvsAncXk+M9kJUFDDJfg/fO3O2uPgQA7JUaCVdW+tyEgiBI1VKbN08FTlQBbWaguh+GTwDeqa0Acr/HntrdsBvan6sWOxzZvidPXboAK1YA27ZJlSnB8g6l5KtX/vAH6faGD1ee1NpsAEQD8N3FQP9/Ssuf94+AzQaYzQBOdgOW7wOMrcCpIvdJonxhhb9QatAg5ee5ucoxhSKUUCqYSilAenwDB3rGJte1q/QcumRlSddxV2vInHWWp+qmpCTwY3T97pDvNC8fmzyU+k7Wsi+alVJOp6cCy9/SWn+vYbsd+P3vpTBvwwbp5+Id1mZmArfcIv2Tj9+1DDDY44PZaMay8cv8fl3+XNXVSbfb0gJp2eaPlMnZ4jGLMaRkCPYGed/y3wcWC/yEUk706KG8zPW68K4tkT8X/nQvKXBXNx1LA9o3C8cArwpNn1AKAD6dD+OwJ9AmtgGt6cBnyg0KXORLHbOypNfKc895LlMLdIuLlc+HS7ema/HU5MC9ZOXz68wZZYXexKqJ+M3Y32DhhwsxsnwkFl6wAA/Ivtd7+Z77tScaMeD0T/G5eQVa2lpw2erLYDF6npTbzrkt4JiSTUih1P333+/+WBAErFu3zm8wBQAlJSV48MEHwx0bERGloMJsz7ughtNSKHXmDACj9E7U0GbzBFSWOtTXQxHGyHsulXlVSpXGW6WUvMLI4alHtyILBgPQJUc9nHFVS6QJv4XrnObIsVbF8r0Sewmu6n0VLi25FJ8c/wQ//tePFbeRY/J9Ljpnd8aRU0dw+NRhNJ1uwt4a/5VSDnO2+2OjwYj0tHQ0nm50XxaoUirDnOFeOpZdegx1RqBNVinl73FbjL5/MTWFEEqpyTRn4ps536ClrQUnm5RN4s2QyiFyMhInlJIv5SgtBdLTlT2Msq3Z7o9XTFyBQUWDcFnPy/z2rchyCKivqQTyvlFc3q0kMUOp7gUVilAqo60cBgOQky1IAUzRf6QvhBFKySsIjEb1njyFhZBCqSp311xUdooslMoXerhb9QvHeyMjAxjYMxfvfXMZIG8WvO986f4qRXi2c1MnhVKQtodvN2IE8M73XYDc79Fwpg6NaK/Aqq2ApVD99n72s9Afj90uBTRNTVKgIq9KKivzrVwCZIHOu8uAms5S/6uWLNhsspP+Js+Zquvk/MYbgRdflAKZESPUx+N9f+H2kwJ8Q6lGzyHTJ5TKyJACp1ZZrthRdY73nO3aVQpdXLp18x829e0LrGnfZDTQ0j2gvd+cF3m4Iv/4G9mhw1+fqo6ohVLynetDrZTKyJBeo++8Iy1HGzFCeR/+FBR4QqlgKqWCIb+d2lppzM3NAOpLYD12LprzpbWjM8+eiYWjFgIIPhCTP0cWi3qFn90uIitLeUxwhVKCIL02tm+XArmLLvL9fm/y4+Bpz2Z46Om115DP8j0AqOmM+0c8gqf++wecevM+HGvq+PeMWq86tddoaakyCHPpKKQHfJfveVfo/WrUr3DL4FuQbc1GmjENWVnSz9JolOaa6vI9ABeblqGo+3d469u3UNfi2cFyWOkwDCr2SsOTXEih1Ift2x6IoogLLrgA06dPx403+jZMMxqNyM3NRa9eveJ+9y8iIoovRbmeAKCpTTrpaWgAkCbFL+bTBWg2tocllvZf4u2hVJYlCxlmz29/78qoUnt8hVIOs3qlVLoxuJJti8Hzrm7PgSagwBNKyR9rvwLf5solmb7PRZfsLth0QNq6eV/tvoDL93LTsxWfu7b0duloOVteeh721+1HI45h/Xrggf/sxmtHPONQYzP5BlDy5ufhMhqMSDekwygo/9xuNUjv4PPsdqhsvqcQD6GU/EQlN9fz19nnrnwO17x0Dbpkd8HgYs8ZdnlWORaOXhjwNh0OSH/1vugXissr8hIzlOpTVg7ITpJzTVJ5RHY2gN3yUKpvRJVSFRXqJ8omE+Bo6gf36UdTDjplBXE2HEBX42hs/PJaIGcXHDtvhyC091hZM80dShlggnP/CPfYOuLdFy0rq70v1NauAKRdp0TXi6K2wm/fp3AIgvRcfv+9tIRKXs3kb9NvdyXCqSLgA09DaJtN/QTedZI4fLgUMgRqYt+7t3QC7QpDwu0nBSjHf+qUp1LKZPLtnSUIUgWIvNKpoyDE4ZAqHF07k3lX66kt3XOR/8w7Co/UurP4q5SSByNnefYOCIlaKCWv0gqlp5R804KMDGnpV7DkoWIk80BOPkZXBVBLe2Fq6VcPw3zVTIzpPAYrLl7h/uNBOPftv1JK9Akh5a+5Z56R/t10k3L5oj9qy/s6dfKt/FOtlAJwx7A78KuL7sDbPYClzdLrMytLCsR+9zvlbbhCH2/eoZTFAkyYAKxd63vdmTN9L/PWUSgFKNsSFBVJoVSnTtLrWF4p5V6+B8CenoYXrnoBFz1zETYe2AgBAsZ3G4/lE5Z3PKgkE1IoNXq0p8HhokWLMHbsWIwaNSrqgyIiotRVmOP5U16zKFVK1dSfBgzSO1BbWyGaIQ+lPMvWvEMo+edWk1VRJRIPlJVSnkDJnhZkKCULafYebAaqPLchb4jeLacb0mDDaXjWinTLV6+Uctldszvg8r18R7bic7vZjuoGT5fnjkKa/Ix87K/bjx8af8DQYU607d4NuEIpP5VS1jTfACpNiDyUcrGYLLCIWWgRpBp/17LEgiw7cDLQd+rfUwpQvhGXn1Re3edq9LD1QPey7rCYVP5UHIDdDuDT+UCPN4DK9e7L8wJUwsWz7mXZ0tIuixR4l6TLQqlvL5FCnMZOwIEREVVKqfWTcik2ykKp+mK/QUuwsrMMwD+eBQB0ag8d+vQB8O3FQF0p4DiIouZROHRams/BVAZ4hwfFxe2P6aTKa7OmUloiF0WuUOrkSU/zeJPJfzWLd5WRi9Xqe4LqvcNhoEDKdb8DBrRXjiGySin5yWlDgyeU8jf+3NzQQimDQbrOifZ9K7xDKH9LFAEpoHMFWt5LrbyphVL+KqXkwt0EItxKqbQ0KbRokO1UEcmuqPLXTlGR/+uFQv5c1dRISxJdoVRuw7n4v9n/9fmeaIZSdrsT3b1a6snDt4EDPctDg6EWSnlXSbnG4yKvqHK9Fi6+WPrnsnatbyjlcKhX/nm/RmfO9O0pBQB3363cBdCfYEIpuV/+UmqkP3++9Lm/Sqn0dKlyfN30dfhw94foW9BXdSl9Kgh7971FixZFcxxEREQAAIcsqGmBFEodr/Vst2MRHEiDFafRLIVSljrALFXoeC/PUzQ9t5fG3da6yp5S+9UvD8Ama4B+5IdmdzjXydYJVpMVzvY/lxsNRnTO6ItvGz5zX/+sCt83PvIKpT01e/D1D1/7ve9ir7Mj72bngZbvAZ6+Um1iG2qba919rCxGi6IBt1x6mg3yzfEAwKLSZyoSuZYCHG6VQqksm3T2Upib2WEoFQ+VUvI34t5/+S7OKHZvQR4KhwOAaARe/gdwd2cAgLm1EDaVgDARFBUJQG0FUCCd6FXmSFt6Z2cD+PcM4Fgf6evN2SGf+Mmf80AVKV0ye2Nnc5a04+Sxvqon+KGQn9S6Xpa9ewNwpgH/eBsV419HxcmfwLXIOZhQyjs8KC5uf3w1KqFUbYUmoZSLqyeRvxNQQBn2yKlVSqWnh94TavDg6IRS8pPTxsaOQynv6pJglozl5npCKe8QKlAoVVUFvPACsGMHMHt24PtQC1LlY7NYfJce5uaGH+SoNTqXh1KBgsWcHGUoFcnrbd48aYn06NHhL0X05r18Tx7QqC03A8IPpdQCucxMEbm50lw7flz62QazlNEfu116jcmXpvbq5Xs9tftQqxiU3643f4G+9+NcsMAzDlfwOmIE8NBD6t+vNi6XYEKpadOkfy7+KqVcl5uNZkyomhDcYJJU2KGU3P79+3Ho0CG0uGJdL6ymIiKiYFlNVsBpBAxtOCNIodTJek+Fj9lgRbrJgdoz7aGUn533vD+PtybngP/d97JtwVVKpZtl7+rSGt3PhVrvrP6F/fDt955QakjPwJVSO47twM7jOwEAZxWche3V2xXXLcvLVnyeaVa+Cwxm+Z7LscZj2F0jhVKV2ZUwCOprBDLMNsiKvQAAFkPoQUsgnQvycfiAtF1UVaV0Blmcawd2Bf6+eAil5CcqHfWECZb7TX9tJfDXjcCI32Nkrm/rhkRhswGmxnKcgRRK9SiShVIQgAPSBj1GY+gVFYMGSbtTff45cFuAHrVlRVbg+ZeAnmuATXdGHEqpLZtyOKQ5cOBAP9S/2Q/V7StL0tOdQYUqJSVw90UBpDDBZgNwUiVti/LyPUAZSrmCDX/VN4B0Ims0Kpd0AfDsviejVi3SEXlfqWhVSslDKX+hWjihlPw4EMryPQC48srAX3fpqFLK9bm8KuSss8JvEB9upRQgPR/y3doiqZTq0wf44IPwv1+N9/I9+em0v1DKblcu0wyG1ep/+R4AzJoFPPAAMGNG8LepRhCk44e8wX1HlVIu/l4HQHBzzkUevo4d61myXFkpNUTfsQO4887A80bOX6PzjqosXQJVSpEkolBqzZo1uOeee/CtfK9PFW3evyGIiIj8EAQBxjN2tJlrcMboCqU8lVJWow1taXbUnqn2DaW8tlYvd5Sjb35ffHXsK1xcdTHijbJSyvM4OmUEF0plmG3unW2QeRgwSp+oVRqN6NYfL33v+bxXiUpPKdmyube+ewtOUXrHO6h4EP57+Hs4jZ4/fZZ6hVKKgA1Ari3wmZt8B77t1dvd/aj89ZMC2kM4r1DKaoxuxU5hpqe+PydDOnspKwicGggQkGOLUoORCASqlAqX4i/RB4YDL76IEb+Mzm3rJe/wDThSsRY4OAyDBkjrVrxP9sPZYc1gAF57TVp+E+h7S0oA7B4H7B4HgyHyExO1SilAOoE+cEBaAufq2VJa6oTgJ/SVczU4djXJLi5ur2BQW76nQaWUWkVNR8scbTapT5P3Zd5VJeGEUhdd5OkrFcnG4t7L91zVJMFUSpnNwVWwDBgAbNkiVfIUFiqXrwWqlApFRz2lAPVQKlzh9pQCfH/+kYRSWvBevhdMKOW9TDMY/pfvSaHU0qXAz38enQbueodSI0YAd90l9aT74x+VX7v6av/34Y/38j357nvBkD/vapVSFEEotW7dOkyZMgVFRUWYM2cOHnvsMYwePRq9evXC+vXr8dVXX+HSSy/FYLUtMoiIiAIwOe1oQw1gPoXmZqDmlCeJsJpsMFocONgEKZTy2nFOzmgwYvPMzfjm+DcYWDQwNoMPgfeSN5c8e5ChlNXqCaXSPe901Jb/DSxSNjtXq6Yqd5RDgAARIr474XlH2a+gHyziu2iCJ5TKtWUrvldeKeWwOJBmDFw6IQ/AXvn6Fc/lAUKpTIvvmZtVpfl5JORhmaunVEVh4FAqx5YDkyEqxecRkfcxUjsJCIdaEBCtwEsvPZtvwJFlE4GmXFTcrt44OJImxh2FWfKeK3Z7+NUjLoFCqXffVV63rKwNQHCbEPXtqwylzGYAjXmKnlwANF++59JRKJWerh5KWa3KRuXhhFLl5cDWrdJJ7tixoX+/i9EonYy3tAS3fE8eNGdnBzdXHnhACoDGjpVOmnNzpVDKZJIeRzR0tHwP8A0Moh1KhVIpJRdvoZT38r1gQilAelyhhlLej10QRKSni6pjiYT361ft95FawBoopOlox0c5gwFYHsVe4fJQSv7zCTaUkj8uVkqpC3trvAceeACZmZnYunUrHn30UQDA2LFj8ec//xlffvklfvvb3+L999/H5MmTozZYIiJKDWli+zsncz1qa4GaBk8oZUuzItvW/u7EeAbI8ZT/qC3RyzBn4Ozis+OunxTgv3dUoSO4M2KH/ExGFkp5L6UDgP6F/d0fu3pOebOYLH6W/vVHhkn57s+7aby8UiqYpt/nVZzn/vjlHS+7P/bX5BwAMlXO3KLd26ggw1Mp5Xoey70qpQxO5Rl4PDQ5B6SlYz/7GXDHHcAVV0TnNtX+Oh2tE1u9nHUWgMY8ZKQbUFUlXeZ9MhatnbXUeIdSkfLXYLpPH9/rdu9+xvdCP+R/V66qcvV6EZR9pZwGoL5U0+V7LsFUSvm7TB7uhBNKAdLzecEFkYeIrhPR2lpPsBJMpVSwgUGnTtLSpP7th/wf/Uj6f/Lk4JcbdSTY5XtyWoZSgR6X9/MWz6GUd6VUoMq4UI9RapVS0QjF1ciPcUaj+rLRUCul1H5ugZb0RlOkoZT8eZf3WWMo5RF2KLVlyxZcfvnlKJTtGemULWy99957cfbZZ+O+++6LbIRERJRyLEL7O17LKZw46URtg2f5XnqaDbkZsrOTXM8Scn8NsuOV95I3AMAPPVCWG1x/IrtN9o41w/Pnt8w033dv+Rn56JUndRs9u/hsv7cp7yvl0q+gH7KsyjNC71BKHoR11OQcAAYUDnA/ftfSPSBwpZTd6nvmlm7WvlIq3dze58x1n23K8DMe+kkBUiXLihXAo4/6bxYbqmSslFq4EPif/wFeftnz+GIZSskDl0h33gOAoUM9J2zjxnku925WnpEhYubMRgRr2jRp16rZs4FLL5VOXk0mKJfw1ZcCTlNMKqU6OgENFErJf57hhlLR4joRPX7cc1k0Qylvf/oTsH078Pzz4X2/mmCX78mFu/Me0HGj81AqpaIRBEeT9/K9Zs/bnQ4rpUKhFkpF4/ijRh5Kde0K1eNDqKGUyeT7OolVKCWfX5FWSgVzeSoKu9a8sbERpbJtBywWC+rq6hTXGT58OFauXBn+6IiIKCXZDJ53jUdONKC+yVMplW62eSqlACB7r/vDYMKQeKJaKbVzEnLO871YTXZG8JVSAPCvq/+Fl3e8jBv63+D3Nrtkd8H6fevdn+el56EoswgFWVnYJXuz7FMpZQmtUspoMGJkxUj873f/q7z/AJVSDpUzt4woh1Ly7Zhd80kQBBjO2OE010jjQBlOYY/7evESSmkhGUOpwkJgyRLlZd4nN4lUKZWbC+zaJS0LkZ/49+6tvN7vfieivDz4Pq9WK/CXvygvS0sDzsibnddKHYTjoaeU2gleNCulosV1//X1nsuCaXQebiglCJEFQmqCqZSS/7xKSiJrEJ/MPaUiWb4XCotFep5cy0cB7QI6+THO31LyUJfvAdJ4ZW8HE7JSSo6hlEfYlVJFRUU4JlsUWVpaiq+++kpxnePHj7PJORERhSzd5HmndPRkPeqaPe9CMixWZZiTvcf9YY5V/2bToVDtKbVzUtBvNrMyZe/qggil+hb0xcLRCwMGP96VSv0K+kEQBBTnBq6UUizfCzIcPL/i/A7vX86R7vsuVq3PVCR+1ONHuKT7JTi/4nz8uO+P3ZenOT3PaXZasWKHwFQKpaxW3x3BkoGr75CLlqFUYaGn/9eAAdG5zYIC3+AhJwc491zp41GjAu8IGCyzGcrle+2hVLSX7+Xn+y7JimT5XjxWSskFUyml5ZwMldrPwvsyeWAQydI9IHV6SgXb6Nz7+4Lhui35/NeqUkq+66O/n32olVKAb4imdygV7HJYVkp1LOxKqQEDBmD7ds/20GPHjsXTTz+N1atXY9KkSVi/fj1eeOEFNjonIqKQZabZgfa/aVTXnMKppmb3n1EyLTZlKCXbfS8edkALhU+lVGMucGBE0CcfOXZ5KCVbvucnlAqG9/I9Vy8q77F6f65Yvhdkj6VRlaMUn9vN9oC79ikqw1z3q7KkLxJWkxVvXvemz+Vm2OF6L2o325FlyMLJZmlLs3jpKaUF75OAsjJtepDEg+xsqZE1oG0AYDQC77wDfPRReDtBheKVV4CNG4GJE6PTTygtDcCJKs8FNZ0BRL9SymCQwrtDnsN70lVKyfkLpTp3ll5voqjcyEBv3seFzEzfYEgeGERaqRVJT6l4D6UyMqTxt7WFFkqFUynluj9Xg3Stnovhw4FbbpEqOOfMCTweuUQLpVgpFT1hh1KTJk3CnDlzsHfvXlRWVuKXv/wlXnrpJdxwg2dJgMlkwhLv+mgiIqIO2C2ZcG30dqyuHg0tTUD7m/ZMq1ellCDtHJORlgGzMcpnRhqzee8c9+2PAKcp+FAqM7Tle8HwrqLqVyDt2pdl8bz7c1gcMBqUZwGhLt8DgHNKzoHFaEFLm/Qur3N254AN6bMzfc/c7P7O5qLMZrTDtdomy5aJLMETSqVSpVSiNzkPJCcnNqEUAPToIf3TWkGB1OAaAGStX8NmNgPYdREsBy+EtWA/aj+/2XN5lBUXhxZKqR0KXGFGolZKlZcDTz4JfPaZtMV9vPAOB9SqduRVXnpWSnmPLd56SgmCNLdPntR++R4Qm0opQQCeeCLwddSW73X06zxRQylWSnUs7OV7N910ExobG1FZWQkA6NKlC7Zs2YJbb70V48ePx6xZs7B582aMGjWqg1siIiJSyrJ53nn8UFePhlZPMyNHuk21F1OgCpt45RPA7JwEm029n4qadLOfRucaV0p5L90DpMblLkNKhgR1XxaTBcPKhrk/D7SsEFAPpdT6TGlBsTwxM1PxHKRSKJXo/aQCkZ+8xtNSqXhiNgNwpiHrtbWYtO9r4GQ3ANFfvgf4NjsPtdG5yeQ5aYynSim1E9FAJ6ezZknBVLC/F2LB+7igFkpddZUUvA4eHHlFoPxnm2w9pQDPz7+pSftQSv74tQqlgpFIlVKRNjr3d8wJtLtiqgm7UkpNt27d8Pjjj0fzJomIKAVly0Kpkw31aGz19JRy2Gywq/xZPtGW7qmZOXYCLlkS/JtmRaVVlCqlyhxlMApGtIltECCgb4G07kJeKaUaShUNwDs3vIP6lnpc0v2SoO/v/Irz8fHejwEE7icFALl23wAqO0Z/aqyqsGNXe0/9vt0zcWi35/lgKJUcGEp1zBU+nT6t3Npci0op7xAm1OV78iAjniqlQlm+F6+8f0ephQOlpcDXX0dnua/85D3S3ffiMZRy/fy9Q6lAoUU0KqX0rBoLt9G5XKJUSlks0pJkebVqenryLoUPR9iVUkajEddff300x0JERAQAyM30vPOoaapH42lZKJVhTZpKKQB4+KKHYTVZcd+o+/CXP9oxZUrw32s1yd7VGU+7P4wklDIZTDi7+GwAUsVTepr0LrGjSikAGN9tPK7sc2XAJXje5AHW0NKhAa+r1ug8S6V6SgsFWZ456bBmIsuamqFUMi/fk4dSkewUlsxc4VNrqxRMeV8eTd6VUqEu35N/LtswHAUFkY0rUqEs34tXBoMy3PDXdDtaJ93J3FMK8B9KhVIp1VFAE8vle8FIpEqpSEMpQfB9bFy6pxR2pZTD4UB5Mr8zISIi3XSSvWusaz6F5tOe5Xs5mTY4LL7hRKLtvOcy/9z5uHv43T49moKhCKVkIgmlAOCZKc/g+e3P49p+17ovCyaUCse55efixatfxPHG44rd7tSkp/meueWoND/Xgnz5XqY5E8WZnjPmUkep2rckBbVG58mqvSMFAKCiQr9xxDN/lVKxWL4XSSh1ySXANdcAp05p31y+I8lQKQVIP4+GBuljrcOBZN59D/D8/JubPZVgQGihVEUF8OWX/q/veg6Vy/fE0AYaReGEUt7HgFiFapHuvgdIr/tTpzyfM5RSCjuUGjp0KP7zn/9EcyxEREQAgDyH50y4rqUezW2ed2lSKOVbc56olVIAwgqkAMCmEtIAkYdSvfJ6YdGYRYrL5JVB0QylAOCqPlcFdT21x5ujsqRPC/Ln1G6x445hd+CrY1/hvPLzfPpwJROLRaqCcQUQyfz3yDvukBprDxqk3NKcPOSVUlov3wu1p1Sg5XtmM7B6dXTGFalkqJQCpMD68GHpY3+VUtGiFkoF21PKapWOY64wId4anQPKOVFX5/k42FAqLU1a7hoolFKrlNIzoEul5XsAK6U6EnYodf/992PMmDH4+9//jmnTpkVzTERElOIKczzvPE6drkeL0xNKZVjUl+8laqVUJLSqlFKTn57v/rggXZ/1LwbBALSZAaPnbFitz5QW5MFTRVYF+uT3wSczPonJfevN4QB+aG9ZlsyVUsXFwNNP6z2K+CaviJJXdMRDT6lAlVLxJNRG5/FKHhDEc6UUoNxZM54rpQBpFz6XYEOp7GzlzyAzU1mVI7+tZFm+JwixCxgjbXQO+FZIJuJrXkthh1Jr167FmDFjMGPGDDz22GM455xzUFhY6NNHQhAELFy4MOKBEhFR6siTvdNoPFOP1jbP8j2bKXl234uUotG5jBah1KDiQbih/w34qvorzBo8K+q3HyxDmw1OWSiltiOfFn4y4Cf45vg3KMoswjkl58TkPuNFVpYUSlmtym3eKfXIwyf5SW88LN8LVCkVT5Jp+Z6L1pVSBoOnYlOt0XlHy6gSKZSqqfF8HCiUysqSghlRlJ5/+c+jsNB/KCV//HpWjUUaStnt0ryIBfn8ava8HWWlVBRFVCnlsnXrVmzdulX1egyliIgoVPLlec3OepyGJ4SwmvxUSiXB7nuh8lcplWGO/vZSgiDgmSnPRP12Q2VwWuFErftztT5TWsg0Z2L5xOUxua9485OfAPffD9x8M3cLSnXy8MnVT0gQQuutEix5pZTJ1PH26YlcKRWvYw0klpVSgPTzb20NffkeoKwqSpZQymAAhg0DNm2S/peHUgUFwK5dyuu7bmvECOn/tDRg8OCIhh0Ro1H6ucnDxY5eB7Gecy7y45t82TIrpaIn7FDqww8/jOY4iIiI3OSVPi3iKThFzz66tjQb0tPSYRAMistTslJKJZCxmqwwGcL+9R73TKINsvewfvtqUfQsWiT1Wwp1C3JKPvJKKVcoZTZrE1ZaLNIuiCdOSCfcHd0HQ6nYkgcEWldKAVIoVVcX3vK9KVOATz8Fxo7Vd8maP+GEUgDw+uvARx8BEyYAy5Z5LlfbYdJ1W5ddBnzyCZCfL+1KWV0d9rAjZrEof46hVErpFUqxp5Q2wn7XOnr06GiOg4iIyM0uq5RqFeoB0VOjbTPZIAgCHBYHappr3Jezp5REi6V78cQE2bt3pwFpBg3WDZEPBlIEqFdKabF0z+VHPwKeeUY66e5IIi/fS8QT1Fgu3wM8lXLhhFLz5wNXXhm/u2r6C6U6qg7Mzweuat8npKTEc7naRg2uQFkQgPPOkz52On2vF0sWi+c4AiReKBXq7ntyifia11KMVmISEREFz26WvfMw1wNpno66riBGcR2kZqWUxej7Z9RUCqUMTptPL0si0o6/SimtrFwJfP65FEx1hJVSsdWzp/S/IADdu2t/f4FCqWDCgS5dtFlmGg3hNDr3ds01UkXYjTcCkycrv6ZVNWOkvEO3eA2l2OhcexGFUmfOnMHy5csxdOhQOBwOmGQ/mW3btuH222/HN998E/EgiYgotVhNVghi+7tHcz1gkjU6b1+u5d1XKhV7SgmCALNB+a4u2UMpsyALpdr4ro4oluRVUadPS/9rGUoZjcDZZwcXJnif5HVUZaKXZGl0PnMm8LvfAS+8AHTtqv39uZ4jV6PzUHpKxTv53A1l+Z5cVhbw8svAqlW+cyyU24kl73F1FNTk5Xk+zs/3f71o83f8iWT5ntpxIJWF/RJuamrC+PHj8emnnyIvLw8OhwMNsvq7Ll26YOXKlcjNzcWSJUuiMlgiIkoNgiDA5MzEaWMtYPEs3xNEz3It71AqFSulAMBitKLV6Qntkj2UShM8Z5omMQHP5IgSmFoApeXyvVCwUiq2MjKAe++N3f25QsaWFmnHuVCW78W7cHtK+eMdyCZLKFVRAcyeDaxbB8yZo9mwfEQjlGKlVGBhV0r97ne/w4YNG7B06VIcOXIEM2fOVHw9KysLo0ePxjvvvBPxIImIKPVY0F6nbT7lXr5nFK3u5VryUEqAoLojXyrIMCvPZpI9lLIYPY9X0V+KiDSnFkBpWSkVCoZSyU0etLS0JG8oJe+xlOyhVKjL9wDgj38Etm8HhgzRZkxqtKiUYiilFHYo9fzzz2Ps2LFYsGABBEFQ7enQtWtX7Nu3L6IBEhFRanLYXKGUZ/mePISQh1DZ1mwYhNRsk2hLS63le1aGUkS6UQug4iWUYqPz5CYPMJqbQ+8pFc/8zdVwwyTv74vXUCrUSim9+JtfbHQePWG/g9+3bx+GdBBR2u121NbWhnsXRESUwkrz2kMpyykgrRGAcumWPJRK1aV7gO8OfKkUSsn7SxGR9tQqpbh8LzSslAqPdyiVTD2loh1KJUqllPe44vV1IAiAQSU1YaVU9IQdStntdlRXVwe8zq5du5Afyy5kRESUNBwW2TYr6T8AUPYQkodSqdjk3MXV+N0lMy3JQylZZZjZEKfvYImSVDxXSiVKKOVdMWE2q5/wkpL859nUlLzL9+SiFUrFa9N/+bjS0uL756hWFcWeUtET9iFw+PDhWLNmDWrk3dhk9u/fj7feegujRo0K9y6IiCiFKSp+jNI2T/J+QqyUkqRapVS6LISTV00RkfbiuadUoizf8w4I4nWc8SbQ8r14DjOC4S+gSKXle/Ee0jCU0lbYodQ999yDkydPYty4cdiwYQPOtB8ZGhsb8f7772PChAk4c+YM5s6dG7XBEhFR6rDLK6Xa5eeoL9/LsaZwpZQptRqdp5sZShHpJZ5337NYpGU2LvEa9giC8oSUJ6fBSbWeUiZT+I/L+3XKUCpykYZSXL4XWNi58qhRo/DHP/4Rd955p6Iaym6XTiKMRiP+9Kc/YfDgwZGPkoiIUo7d7BtK5dhtql9npZRHsodSXcttwAnp4+KCOD3rJEpS8bx8TxCkk/tGqQVh3IZSgFQ1kQjjjCep1lMqkiBJEKTvb2mJ/La0JP+ZxntIw0opbUX0Er7tttswZswYPPHEE9i8eTNOnDgBh8OBYcOG4fbbb0ffvn2jNU4iIkoxakGTvCqIlVISn55SSR5KleR7Hm+XUp7NEcVSPC/fAxInlJKfkMbzOONJMi/fi3YoBUjPV7yHUolUKaU2x0KpZGOlVGARv4R79+6NRx99NBpjISIichtaOtTnMnlV0NnFZ0OAABEizik9J5ZDiyupViklf7zpaXxXRxRL8bx8D1Ce3Mdz2MNQKnSp1ug8GqFUbW10bksriRRKsVJKWwn+EiYiomR1fsX57tDJRV4V1KNTD3wy4xP80PgDLut5mR5DjAtWY2qFUvI54F0lRkTaivdKqUQJe+QnqPE8zniSaj2lIg2S5N8fr6FUKi3fY6VUYEE/lfv27Qv7TioqKsL+XiIiSk05thwMKBqAbUe2uS/zbuo9smJkjEcVf1Jt+Z58DnjPByLSVjz3lAKUJ/feu9zFEzY6Dx17SoVG/nzFayglH1e8h7OslNJW0E9l586dIci3tAiSIAjunfmIiIhCMbpytCKU8l6qRqm3fK/UUar6MRFpT61SKp6W77FSKnklc08ptYAiFUIpVkqRS9BP5bRp08IKpYiIiMI1unI0Ht3s6VvIyhhf3s9JhjnDzzWTw6jKUfif8/8HNc01mNp3qt7DIUopiVQpFc9hT6KEZ/EkmUMpi0XaMU/0dCuIuNIvEZbvJVJPKbU5Fsq8836d83WvFPRTuWrVKg2HQURE5Ov8yvMVn7NSyleqVUoZBAOWXLBE72EQpaR47ylVWCj9n5YGZGfrOpSAGEqFTv48JVtPKUGQQqimJs9lqVAplUihlNocC2XeGQzSY2xslI5P8VRhGg8Meg8gXHv27MHNN9+MLl26wGazoVu3bli0aBFaW1v1HhoREUVJXnqe4vPWNh7jvaVaKEVE+on33fd+/nNgwgRg+XIgM44PhVy+Fzp5yNLUlFw9pQDfecBG5/El0uV7gOcxxvtj1UPEL+HW1la89957+Prrr9HQ0ICFCxcCAJqbm1FXV4e8vDwYDNHPvr7++ms4nU48+eSTqKqqwvbt2zFr1iw0NDRg2bJlUb8/IiLSR1FmEY6cOgIA2PHDDp1HE39SrdE5Eekn3iulBgwA/vd/9R5Fx9joPHTJvHwPiH4oxUqp6IpGKFVSAvzwA1BcHJ0xJZOI0qLXX38dFRUVuOyyyzB//nzcf//97q998cUXKC4uxnPPPRfpGFVNnDgRK1euxPjx49G1a1dMmjQJ8+fPx8svv6zJ/RERkT5WTFzh/njmoJk6jiQ+ySuljIIRFmOcvvskooQX7z2lEgUrpUIXKJRK9OV7gLahVLzuRJlqodTy5cDkycAf/hCVISWVsHPlDRs24KqrrkJxcTEeffRRbNq0CatXr3Z/fejQoaiqqsJLL72E6667LiqD7UhtbS1yc3MDXqelpQUtLS3uz+vq6gAATqcTTqdT0/Fpyel0QhTFhH4MFB2cCwQk1zy4otcV+Mtlf0HT6SZcUnVJUjymaJKHUJnmTIiiCLG9W2oyzQMKH+cBAdGZB9KJmfJv2iaTE5xaoZECCOl5tFpj+/wl6vFACj+l56ypSWwPpaRNuAyGxJ+D6ekCXI8HAMxmEU6n6P8bOmA2e27PbFZ/fvSeC336AK6fad++8f0zNJmUPx8g9Hk3Zoz0D0BcPVYt50Gwtxl2KPWb3/wG2dnZ2Lp1K/Ly8nD8+HGf6wwZMgSbN28O9y5C8t133+Gxxx7rcOne0qVLsXjxYp/Ljx07hubmZq2Gpzmn04na2lqIoqjJcklKHJwLBCTfPLi05FIAwIkfTug8kvjT0uD5Q0u6KR3V1dXuz5NtHlB4OA8IiM48OHXKBMCr119rA6qrG6IwwtTR1pYOwAEAOHPmFKqrG2N234l6PGhq8sy9kyeb0NAgAJDKi2pqfkB1dRyd5YfBZMoF4Ck7FMUmVFfXRXCLDgBS+VFLSz2qq5t8rqH3XCgqAv7xDzMaGgwYMqQZsrcvccfpVP58AKCu7gSqq8+of0MC0XIe1NfXB3W9sEOpzZs346qrrkJeXp7f65SXl+O1114L6XZ/8Ytf4MEHHwx4nR07dqBXr17uzw8ePIiJEyfi6quvxqxZswJ+77333ou5c+e6P6+rq0N5eTny8/PhcDhCGms8cTqdEAQB+fn5CfULhqKPc4EAzoNUUlRf5P7YYXWgoKDA/TnnAQGcBySJxjxw7W4nl5ubgYKCDN8vkF9dung+rqzMREFB7HoBJurxoE6Rz9gUy6mKivIg+9WXkBwOZRVOdrYNBQXhr7vLyvLcXl6eHQUFdp/rxMNcuPZa10fxfR5utQo+l+Xn5yb8vAO0nQfWINeOhh1KtbS0dBji1NTUhPzA5s2bh+nTpwe8TteuXd0fHzp0CGPHjsW5556L//f//l+Ht2+xWGBRWaRrMBgS6sCsRhCEpHgcFDnOBQI4D1JFutnTiCHTnOnz8+Y8IIDzgCSRzgO18wuz2QBOq9BMmQJMmgSIInDFFbF//hLxeCDvOdTSIih230tLS/w56N1TymoVYDD4BiHh3J7N5v/5ScS5oAe1nlLJdOzTah4Ee3thh1Jdu3bFli1bAl5n48aNioqmYOTn5yM/Pz+o6x48eBBjx47F4MGDsXLlSr6YiIgo5cgbnXPnPSLSUrzvvpco0tOBEBeTpDzvRueirN0Sd9/zlQi77yWSaDQ6J//CTnGuvPJKbNiwAStXrlT9+rJly7B9+3ZMnTo17MEFcvDgQYwZMwYVFRVYtmwZjh07hiNHjuDIkSOa3B8REVE8spk872QZShGRlrj7Hukl0O57yRAORDuUKitT/5jCozbHkmHexYuwn8p77rkHL730EmbOnIlnn33WvaPdggULsHHjRnz66acYOHAg5syZE7XByq1duxbfffcdvvvuO5R5vdJEMfydCoiIiBJJhtnTy8Vhie+eDESU2NQqpdQuI4o271BKHtokQzgQ7VDqhhuAb78FiouBQYMiuy1ipZTWwq6UyszMxCeffIJrrrkG69atw/r16yGKIpYtW4ZPP/0UP/7xj/Hee++p9m+KhunTp7u3vfb+R0RElCq6ZHfBxVUXw262Y/rA6XoPh4iSGCulSC8mkycEaGpSVkqpBQaJRt4zC4g8lLLbgUceAe65BxDCb01F7RhKaSuipzInJwf//Oc/sWLFCmzZsgUnTpyAw+HAOeecg0K17TmIiIgoqgRBwFvXv4XWtlaYjTw7JCLtsKcU6clikcKo5mZlZVEyhAPRrpSi6FILpZIhDI0XUXkJd+rUCRMnTozGTREREVEYGEgRkdbUAigu36NYsViAhgagpUVZKZUMe10xlIpv7CmlrbBfwgcOHMDrr7+Ompoa1a+fPHkSr7/+Og4ePBjuXRARERERUZxgpRTpyRXUyEMpkyk5lqd5h1LyHlqkPy7f01bYodSSJUswY8YM2LxfQe3S09Nx0003YenSpWEPjoiIiIiI4oPR6FuVwlCKYkUtlEqWJVSslIpvDKW0FXYo9cEHH2D8+PF+G5lbLBaMHz8e7733XtiDIyIiIiKi+OEdQnH5HsWK67SztRVoa5M+TpZggKFUfGMopa2wQ6mDBw+ic+fOAa9TWVnJ5XtEREREREnCO4RipRTFir/le8kg2rvvUXQxlNJW2KGU2WxGXV1dwOvU1dVBSIZFvkRERERE5BNCMZSiWHHNtZYW4PRp6eNkCQZYKRXf1OZZsiwdjQdhh1L9+vXDmjVr0NLSovr15uZmvP766+jXr1/YgyMiIiIiovjhXSnF5XsUK66gRhSlYApInmCAoVR8855nBkNyNNiPF2GHUjNmzMCBAwcwadIkfP/994qv7dq1C5MnT8ahQ4cwc+bMiAdJRERERET6Y6UU6UUe1DQ0SP+zUopiwTuUSpZ5Fy/CfjpnzJiBt956Cy+99BJ69eqFLl26oLS0FAcPHsTu3btx5swZTJ06FTNmzIjmeImIiIiISCeslCK9MJQivTCU0lbYlVIA8MILL2DFihWoqqrCt99+i3Xr1uHbb79Fjx498Pjjj2P16tXRGicREREREemMlVKkF3lQ09oq/Z8s4YB3KGW16jMOUsdQSlsRPZ2CIGDOnDmYM2cOGhoaUFtbi6ysLGRkZERrfEREREREFCe4+x7pRa16iD2lKBa8QyiGUtEVtaczIyODYRQRERERURLzDqG4fI9iRS2oSZZwID1d+TlDqfjiHX4mSxgaL8JevrdhwwbMnTsXR44cUf364cOHMXfuXGzatCnswRERERERUfxgpRTpJZlDKVZKxTcu39NW2KHUI488gjVr1qCoqEj168XFxXjjjTewfPnysAdHRERERETxwzuE4skZxQpDKdILQylthR1KbdmyBeedd17A64waNYqVUkRERERESUJeKZWWBgiCfmOh1KJWlZcsy6gsFuVriaFUfGEopa2wQ6nq6mqUlpYGvE5RURGqq6vDvQsiIiIiIooj8mCAS/colpK5UkoQPDvumUyAIeyzdNICG51rK+zpnp2djX379gW8zt69e5GZmRnuXRARERERURyRV0oxlKJYSuZQCvAs4WOVVPxhpZS2wg6lhg8fjldeeQX79+9X/fq+ffvw6quv4txzzw17cEREREREFD/kQRR33qNYSvZQyrUDH0Op+MPd97QVdig1d+5cNDY2YuTIkfj73/+Ow4cPA5B23Xv66acxcuRINDU1Yd68eVEbLBERERER6YeVUqQXtbAmmcKB0aOl/0eN0ncc5IuVUtoK++kcNWoUHnnkEcybNw8zZswAAAiCAFEUAQAGgwGPPvooRvFVRURERESUFNhTivSS7JVSK1cCt94KnHOO3iMhbwyltBXR03nnnXdi7NixeOKJJ7BlyxbU1tYiOzsbQ4cOxa233oqzzjorWuMkIiIiIiKdcfke6SXZQ6m0NKCDze1JJ2x0rq2In87+/fvjT3/6k9+vt7S0wMKFsURERERECY/L90gvyR5KUfxipZS2NNts8vPPP8fs2bNRUlKi1V0QEREREVEMcfke6UVtviVTTymKXwyltBXVp7Ompgb/+Mc/8Le//Q1ffPEFRFGEzbW3JRERERERJTR5pRSX71EssVKK9MLd97QVlZfxe++9h7/97W947bXX0NLSAlEUMWLECMyYMQNTp06Nxl0QEREREZHOWClFemEoRXphpZS2wn469+/fj5UrV2LlypXYt28fRFFEaWkpDh48iOnTp+Opp56K5jiJiIiIiEhn7ClFemEoRXpho3NthfR0nj59Gq+++ir+9re/4f3330dbWxsyMjJw/fXXY9q0abjgggtgMplg4k+JiIiIiCjpcPc90otaKMVlVBQLrJTSVkhPZ0lJCU6cOAFBEDB27FhMmzYNV1xxBTIyMrQaHxERERERxQlWSpFeWClFemEopa2Qns7jx4/DYDDg7rvvxoIFC5Cfn6/VuIiIiIiIKM6wpxTphaEU6YWhlLYMoVx5+vTpsNlseOSRR1BWVoZJkybhxRdfRGtrq1bjIyIiIiKiOMHd90gvDKVIL9x9T1shhVJPPfUUDh8+jCeffBKDBg3CG2+8gWuuuQaFhYW45ZZbsH79eq3GSUREREREOmOlFOmFPaVIL2x0rq2QQikAyMzMxMyZM7Fx40Z89dVXuOuuu2A2m/GXv/wFo0ePhiAI2LlzJ/bu3avFeImIiIiISCfsKUV6UZtvDAcoFrh8T1shh1JyvXv3xu9//3scPHgQL7zwAsaPHw9BEPDJJ5+gW7duGDduHJ555plojZWIiIiIiHTE3fdIL1y+R3phKKWtiEIpF5PJhKuuugpvv/029uzZg8WLF6OyshIffvghpk+fHo27ICIiIiIinbFSivTCUIr0wlBKW1EJpeTKysqwcOFC7Nq1C2vXrsU111wT7bsgIiIiIiIdsKcU6YU9pUgvDKW0penTOW7cOIwbN07LuyAiIiIiohjJyFD/mEhrRqP0r63NcxnDAYoF73nGMDS6ol4pRUREREREyem884DRo4Fu3QAuiKBY866WYihFscBKKW3x6SQiIiIioqCkpQHr1gGiCAiC3qOhVGOxAI2Nns8ZDlAsMJTSFiuliIiIiIgoJAykSA/elVJcRkWxwFBKWwyliIiIiIiIKO55N9dnOECxwFBKW0kRSrW0tGDgwIEQBAHbtm3TezhEREREREQUZewpRXrwnmecd9GVFKHUggULUFJSovcwiIiIiIiISCNcvkd68J5nnHfRlfCh1Ntvv413330Xy5Yt03soREREREREpBFWSpEeuHxPWwn9dB49ehSzZs3Cq6++ivT09KC+p6WlBS0tLe7P6+rqAABOpxNOp1OTccaC0+mEKIoJ/RgoOjgXCOA8IAnnAQGcByThPCAg8eeBxSIA8HTZNxicSNCHortEnwuxJG3s4KnnMRqTZ95pOQ+Cvc2EDaVEUcT06dNx6623YsiQIdizZ09Q37d06VIsXrzY5/Jjx46hubk5yqOMHafTidraWoiiCIMh4QvgKAKcCwRwHpCE84AAzgOScB4QkPjzQBByAHjKpRob61BdnbjncHpK9LkQSzU1RgD57s+bmk6hurpRvwFFkZbzoL6+PqjrxV0o9Ytf/AIPPvhgwOvs2LED7777Lurr63HvvfeGdPv33nsv5s6d6/68rq4O5eXlyM/Ph8PhCGvM8cDpdEIQBOTn5/OgkuI4FwjgPCAJ5wEBnAck4TwgIPHnQWamoPg8J8eBgoLEPYfTU6LPhVhq9MqfsrMzUVCQqc9gokzLeWC1WoO6XtyFUvPmzcP06dMDXqdr16744IMPsHHjRli8FhYPGTIE119/PZ5++mnV77VYLD7fAwAGgyHhX4yCICTF46DIcS4QwHlAEs4DAjgPSMJ5QEBizwPvc1yz2YAEfBhxI5HnQiylpSk/T7Z5p9U8CPb24i6Uys/PR35+fofXW7FiBZYsWeL+/NChQ5gwYQKef/55DBs2TMshEhERERERUYyx0TnpgbvvaSthX8YVFRWKzzMzpfK5bt26oaysTI8hERERERERkUbMZuXnDKUoFrj7nraSqOiMiIiIiIiIkpV3pRQrVigWGEppK2mezs6dO0MURb2HQURERERERBrg8j3Sg/c847yLLlZKERERERERUdxjKEV6YKWUthhKERERERERUdxjKEV6YCilLYZSREREREREFPfYU4r0wN33tMVQioiIiIiIiOIeK6VID6yU0hZDKSIiIiIiIop7DKVIDwyltMVQioiIiIiIiOIeQynSgyAABllywnkXXQyliIiIiIiIKO6ZzcrP2duHYkU+1xhKRRdDKSIiIiIiIop7rJQivTCU0g5DKSIiIiIiIop7DKVIL/JQihV60cVQioiIiIiIiOIeQynSi3yucd5FF0MpIiIiIiIiinveoRQrVihWuHxPOwyliIiIiIiIKO6xUor0wlBKOwyliIiIiIiIKO4xlCK9MJTSDkMpIiIiIiIiinsMpUgvDKW0w1CKiIiIiIiI4p7ZrPycPaUoVuRBFOdddDGUIiIiIiIiorjHSinSCyultMNQioiIiIiIiOIeQynSC0Mp7TCUIiIiIiIiorjnHUpxGRXFCkMp7TCUIiIiIiIiorgnD6UMBkAQ9BsLpRZ5EMVQKroYShEREREREVHck4dSDAYollgppR2GUkRERERERBT3GEqRXuShFJeNRhdDKSIiIiIiIop7JpO0bM/1MVGspKVJ/wsCQ6loYyhFRERERERECcFVLcVggGLp6qul/3/8Y/YyizaGUkRERERERJQQzGbpf1ZKUSzNmwdUVwOrV+s9kuTDlzIRERERERElBFelFEMpirX8fL1HkJxYKUVEREREREQJoU8f6f8ePfQdBxFFB/NlIiIiIiIiSgirVgEvvQRccYXeIyGiaGAoRURERERERAmhshKYO1fvURBRtHD5HhERERERERERxRxDKSIiIiIiIiIiijmGUkREREREREREFHMMpYiIiIiIiIiIKOYYShERERERERERUcwxlCIiIiIiIiIiophjKEVERERERERERDHHUIqIiIiIiIiIiGKOoRQREREREREREcUcQykiIiIiIiIiIoo5k94D0JsoigCAuro6nUcSGafTifr6elitVhgMzBpTGecCAZwHJOE8IIDzgCScBwRwHpAH5wIB2s4DV8biylz8SflQqr6+HgBQXl6u80iIiIiIiIiIiJJHfX09srKy/H5dEDuKrZKc0+nEoUOHYLfbIQiC3sMJW11dHcrLy7F//344HA69h0M64lwggPOAJJwHBHAekITzgADOA/LgXCBA23kgiiLq6+tRUlISsAor5SulDAYDysrK9B5G1DgcDh5UCADnAkk4DwjgPCAJ5wEBnAck4TwgF84FArSbB4EqpFy4eJSIiIiIiIiIiGKOoRQREREREREREcUcQ6kkYbFYsGjRIlgsFr2HQjrjXCCA84AknAcEcB6QhPOAAM4D8uBcICA+5kHKNzonIiIiIiIiIqLYY6UUERERERERERHFHEMpIiIiIiIiIiKKOYZSREREREREREQUcwylksTjjz+Ozp07w2q1YtiwYfi///s/vYdEMXT//fdDEATFv169euk9LNLYxx9/jMsuuwwlJSUQBAGvvvqq4uuiKOK+++5DcXExbDYbLrzwQnz77bf6DJY01dFcmD59us8xYuLEifoMljSxdOlSnHPOObDb7SgoKMDll1+OnTt3Kq7T3NyM2bNno1OnTsjMzMSVV16Jo0eP6jRi0kIw82DMmDE+x4Nbb71VpxGTVv785z+jf//+cDgccDgcGDFiBN5++23313k8SA0dzQMeD1LTAw88AEEQcNddd7kv0/OYwFAqCTz//POYO3cuFi1ahM8//xwDBgzAhAkTUF1drffQKIb69u2Lw4cPu/+tX79e7yGRxhoaGjBgwAA8/vjjql9/6KGHsGLFCjzxxBPYvHkzMjIyMGHCBDQ3N8d4pKS1juYCAEycOFFxjFi9enUMR0ha++ijjzB79mxs2rQJa9euxenTpzF+/Hg0NDS4r3P33XdjzZo1ePHFF/HRRx/h0KFDuOKKK3QcNUVbMPMAAGbNmqU4Hjz00EM6jZi0UlZWhgceeABbt27FZ599hgsuuACTJ0/GV199BYDHg1TR0TwAeDxINVu2bMGTTz6J/v37Ky7X9ZggUsIbOnSoOHv2bPfnbW1tYklJibh06VIdR0WxtGjRInHAgAF6D4N0BEB85ZVX3J87nU6xqKhIfPjhh92X1dTUiBaLRVy9erUOI6RY8Z4LoiiKN954ozh58mRdxkP6qK6uFgGIH330kSiK0us/LS1NfPHFF93X2bFjhwhA3Lhxo17DJI15zwNRFMXRo0eLd955p36DIt3k5OSIf/3rX3k8SHGueSCKPB6kmvr6erF79+7i2rVrFT97vY8JrJRKcK2trdi6dSsuvPBC92UGgwEXXnghNm7cqOPIKNa+/fZblJSUoGvXrrj++uuxb98+vYdEOtq9ezeOHDmiODZkZWVh2LBhPDakqHXr1qGgoAA9e/bEbbfdhuPHj+s9JNJQbW0tACA3NxcAsHXrVpw+fVpxTOjVqxcqKip4TEhi3vPA5Z///Cfy8vJw1lln4d5770VjY6Mew6MYaWtrw3PPPYeGhgaMGDGCx4MU5T0PXHg8SB2zZ8/Gj370I8VrH9D/PYJJ83sgTf3www9oa2tDYWGh4vLCwkJ8/fXXOo2KYm3YsGFYtWoVevbsicOHD2Px4sU4//zzsX37dtjtdr2HRzo4cuQIAKgeG1xfo9QxceJEXHHFFejSpQt27dqFX/7yl7j44ouxceNGGI1GvYdHUeZ0OnHXXXdh5MiROOusswBIxwSz2Yzs7GzFdXlMSF5q8wAArrvuOlRWVqKkpARffPEFfv7zn2Pnzp14+eWXdRwtaeHLL7/EiBEj0NzcjMzMTLzyyivo06cPtm3bxuNBCvE3DwAeD1LJc889h88//xxbtmzx+Zre7xEYShElgYsvvtj9cf/+/TFs2DBUVlbihRdewM0336zjyIgoHlxzzTXuj/v164f+/fujW7duWLduHcaNG6fjyEgLs2fPxvbt29lbMMX5mwc//elP3R/369cPxcXFGDduHHbt2oVu3brFepikoZ49e2Lbtm2ora3Fv/71L9x444346KOP9B4WxZi/edCnTx8eD1LE/v37ceedd2Lt2rWwWq16D8cHl+8luLy8PBiNRp/O+EePHkVRUZFOoyK9ZWdno0ePHvjuu+/0HgrpxPX657GB1HTt2hV5eXk8RiShOXPm4I033sCHH36IsrIy9+VFRUVobW1FTU2N4vo8JiQnf/NAzbBhwwCAx4MkZDabUVVVhcGDB2Pp0qUYMGAAHn30UR4PUoy/eaCGx4PktHXrVlRXV2PQoEEwmUwwmUz46KOPsGLFCphMJhQWFup6TGAoleDMZjMGDx6M999/332Z0+nE+++/r1grTKnl1KlT2LVrF4qLi/UeCumkS5cuKCoqUhwb6urqsHnzZh4bCAcOHMDx48d5jEgioihizpw5eOWVV/DBBx+gS5cuiq8PHjwYaWlpimPCzp07sW/fPh4TkkhH80DNtm3bAIDHgxTgdDrR0tLC40GKc80DNTweJKdx48bhyy+/xLZt29z/hgwZguuvv979sZ7HBC7fSwJz587FjTfeiCFDhmDo0KH4wx/+gIaGBsyYMUPvoVGMzJ8/H5dddhkqKytx6NAhLFq0CEajEddee63eQyMNnTp1SvGXrN27d2Pbtm3Izc1FRUUF7rrrLixZsgTdu3dHly5dsHDhQpSUlODyyy/Xb9CkiUBzITc3F4sXL8aVV16JoqIi7Nq1CwsWLEBVVRUmTJig46gpmmbPno1nn30Wr732Gux2u7sHRFZWFmw2G7KysnDzzTdj7ty5yM3NhcPhwM9+9jOMGDECw4cP13n0FC0dzYNdu3bh2WefxSWXXIJOnTrhiy++wN13341Ro0b5bA9Oie3ee+/FxRdfjIqKCtTX1+PZZ5/FunXr8M477/B4kEICzQMeD1KH3W5X9BYEgIyMDHTq1Ml9ua7HBM3396OYeOyxx8SKigrRbDaLQ4cOFTdt2qT3kCiGpk6dKhYXF4tms1ksLS0Vp06dKn733Xd6D4s09uGHH4oAfP7deOONoiiKotPpFBcuXCgWFhaKFotFHDdunLhz5059B02aCDQXGhsbxfHjx4v5+fliWlqaWFlZKc6aNUs8cuSI3sOmKFL7+QMQV65c6b5OU1OTePvtt4s5OTlienq6OGXKFPHw4cP6DZqirqN5sG/fPnHUqFFibm6uaLFYxKqqKvGee+4Ra2tr9R04Rd1NN90kVlZWimazWczPzxfHjRsnvvvuu+6v83iQGgLNAx4PUtvo0aPFO++80/25nscEQRRFUfvoi4iIiIiIiIiIyIM9pYiIiIiIiIiIKOYYShERERERERERUcwxlCIiIiIiIiIiophjKEVERERERERERDHHUIqIiIiIiIiIiGKOoRQREREREREREcUcQykiIiIiIiIiIoo5hlJERERERERERBRzDKWIiIiIiIiIiCjmGEoRERERRWjMmDEQBEHvYQRNFEUMHjwY48ePD+v7f/WrX8Fut+Po0aNRHhkRERGlEoZSRERERDKCIIT0LxH9/e9/x+eff45f//rXYX3/vHnzYDAYsGjRoiiPjIiIiFKJIIqiqPcgiIiIiOLF/fff73PZH/7wB9TW1qqGMPfffz/27duHxsZG9OrVKwYjjIzT6US3bt1QXl6Ojz/+OOzbmTdvHh599FHs2rULlZWVURwhERERpQqGUkREREQd6Ny5M/bu3YtkeNv05ptv4tJLL8Vf/vIXzJw5M+zb+fe//41BgwbhV7/6FX7zm99EcYRERESUKrh8j4iIiChCaj2lVq1aBUEQsGrVKqxZswbDhg1Deno6SktLsXDhQjidTgDA008/jQEDBsBms6GiogIPP/yw6n2IooinnnoKI0eOhMPhQHp6OoYMGYKnnnoqpLGuXLkSgiDgyiuv9Pna4cOHceedd6J79+6w2WzIzs5G7969ceutt6K2tlZx3bPPPhtVVVVYtWpVSPdPRERE5GLSewBEREREyeyVV17Bu+++i8svvxwjR47Em2++iSVLlkAURWRlZWHJkiWYPHkyxowZg5deegkLFixAYWEhpk2b5r4NURRx/fXXY/Xq1ejevTuuu+46mM1mrF27FjfffDP++9//YtmyZR2ORRRFfPjhh+jZsydycnIUX2tsbMTIkSOxZ88ejB8/HlOmTEFrayt2796NZ555BvPnz0dWVpbie0aMGIFnnnkG33zzDXr06BGdJ4yIiIhSBkMpIiIiIg29/fbb2LBhA8455xwAwOLFi1FVVYXly5fD4XDg3//+N7p27QoAmD9/PqqqqrBs2TJFKPXXv/4Vq1evxowZM/Dkk08iLS0NANDa2oqrrroKv//973Httddi8ODBAceyY8cOnDhxAhdffLHP195//33s3r0bd911F5YvX6742qlTp9z3KTdkyBA888wz2LBhA0MpIiIiChmX7xERERFp6IYbbnAHUgBgt9tx6aWXorGxEbfddps7kAKA8vJynHfeefjvf/+LM2fOuC//4x//iIyMDDz++OOKcMhsNuO3v/0tAGD16tUdjuXAgQMAgMLCQr/XsdlsPpdlZmbCYrH4XO66HdftEhEREYWClVJEREREGho4cKDPZcXFxQG/1tbWhqNHj6K0tBSNjY348ssvUVJSggcffNDn+qdPnwYAfP311x2O5fjx4wCA7Oxsn6+NGjUKxcXFeOCBB/Cf//wHl156KUaPHo3evXv79Mtyyc3NBQD88MMPHd43ERERkTeGUkREREQacjgcPpeZTKYOv+YKm06ePAlRFHHw4EEsXrzY7/00NDR0OBZXFVRzc7PP17KysrBp0ybcd999WLNmDd566y0AUvXWL37xC9x+++0+39PU1AQASE9P7/C+iYiIiLxx+R4RERFRHHMFV4MHD4Yoin7/ffjhhx3eVn5+PgDgxIkTql+vqKjAqlWrcOzYMfz73//Ggw8+CKfTidmzZ6suD3Tdjut2iYiIiELBUIqIiIgojtntdvTu3Rs7duxATU1NRLfVt29fGAwG7Ny5M+D1DAYDBg4ciAULFrjDqNdff93neq7b6devX0TjIiIiotTEUIqIiIgozt1xxx1obGzErFmzVJfp7d69G3v27OnwdrKzs9G/f3989tlncDqdiq999dVXOHr0qM/3uC6zWq0+X9u8eTNMJhPOPffcIB8JERERkQd7ShERERHFuVtuuQWbNm3C008/jQ0bNuDCCy9ESUkJjh49iq+//hqbN2/Gs88+i86dO3d4W1OmTMGiRYuwadMmRZi0du1a3HPPPRg5ciR69OiBTp064fvvv8frr78Oq9WK2bNnK27n1KlT2LRpEy666CJkZGRE+yETERFRCmClFBEREVGcEwQBq1atwvPPP4++ffvijTfewCOPPIK1a9fCarVi2bJluPDCC4O6rZkzZ8JkMuEf//iH4vIJEyZg9uzZqKurw8svv4zly5fjs88+w9SpU7F161YMGTJEcf2XXnoJTU1NuOWWW6L2OImIiCi1CKIoinoPgoiIiIhi5yc/+QnefPNN7N27F3a7PazbOP/883H06FHs2LEDRqMxyiMkIiKiVMBKKSIiIqIUs2TJEjQ1NeGxxx4L6/vff/99rF+/Hg8++CADKSIiIgobQykiIiKiFFNZWYmnn3467Cqp2tpaLFu2DFOmTInyyIiIiCiVcPkeERERERERERHFHCuliIiIiIiIiIgo5hhKERERERERERFRzDGUIiIiIiIiIiKimGMoRUREREREREREMcdQioiIiIiIiIiIYo6hFBERERERERERxRxDKSIiIiIiIiIiijmGUkREREREREREFHMMpYiIiIiIiIiIKOb+PwjW0Ml+Y0HxAAAAAElFTkSuQmCC", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# acceleration time series\n", + "import matplotlib.pyplot as plt\n", + "import pandas as pd\n", + "import numpy as np\n", + "plt.style.use(\"default\")\n", + "def plot_acceleration_time_series(df, output_file='acceleration_time_series'):\n", + " \"\"\"\n", + " Create a simple plot of acceleration components over time.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing acceleration data\n", + " output_file (str): Base filename for output (without extension)\n", + " \"\"\"\n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " time_label = 'Time (s)'\n", + " \n", + " # Create figure with acceleration plot\n", + " plt.figure(figsize=(12, 4))\n", + " \n", + " # Plot acceleration components\n", + " plt.plot(df[time_column], df['[Measured] AccelerationX ~ Ax(t) (m/s^2)'], 'b-', \n", + " linewidth=2, label=r'X Acceleration ~ $A_x(t)$ (m/s²)')\n", + " plt.plot(df[time_column], df['[Measured] AccelerationY ~ Ay(t) (m/s^2)'], 'g-', \n", + " linewidth=2, label=r'Y Acceleration ~ $A_y(t)$ (m/s²)')\n", + " \n", + " # Add horizontal line at y=0 for reference\n", + " plt.axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Set labels and title\n", + " plt.title('Acceleration Components Over Time', fontsize=14)\n", + " plt.xlabel(time_label, fontsize=14)\n", + " plt.ylabel('Acceleration (m/s²)', fontsize=14)\n", + " \n", + " \n", + " \n", + " # Add grid and improve appearance\n", + " plt.grid(True, alpha=0.3)\n", + " \n", + " # Calculate and display acceleration magnitude\n", + " acc_magnitude = np.sqrt(\n", + " df['[Measured] AccelerationX ~ Ax(t) (m/s^2)']**2 + \n", + " df['[Measured] AccelerationY ~ Ay(t) (m/s^2)']**2\n", + " )\n", + " plt.plot(df[time_column], acc_magnitude, 'r--', \n", + " linewidth=1.5, label=r'Magnitude of Acceleration $\\sqrt{A_x^2 + A_y^2}$ (m/s²)')\n", + " \n", + " # Adjust layout\n", + " plt.tight_layout()\n", + " plt.grid(True, alpha=0.3)\n", + " plt.legend(loc='best')\n", + " \n", + " # Save the figure as PDF\n", + " pdf_file = f\"{output_file}.pdf\"\n", + " plt.savefig(pdf_file, format='pdf', bbox_inches='tight')\n", + " print(f\"Plot saved as {pdf_file}\")\n", + " \n", + " # Show the plot\n", + " plt.show()\n", + "\n", + "# Load your data\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Create the plot\n", + "plot_acceleration_time_series(df, output_file=f'plots/{recorded_time}/acceleration_time_series')" + ] + }, + { + "cell_type": "code", + "execution_count": 39, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Plots saved as plots/2025-03-24_13-53-49/yaw_angle_time_series.pdf and plots/2025-03-24_13-53-49/yaw_angle_time_series.png\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# yaw angle time series\n", + "\n", + "import matplotlib.pyplot as plt\n", + "import pandas as pd\n", + "import numpy as np\n", + "\n", + "def plot_yaw_angle_time_series(df, output_file='yaw_angle_time_series'):\n", + " \"\"\"\n", + " Create simple time series plots for yaw angle and angular velocity,\n", + " including comparison between measured and calculated angular velocity.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the vehicle data\n", + " output_file (str): Base filename for output (without extension)\n", + " \"\"\"\n", + " # Set up plot style for clean presentation\n", + " plt.style.use('default')\n", + " plt.rcParams.update({'font.size': 12})\n", + " \n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " \n", + " # Calculate angular velocity from yaw angle changes\n", + " # First, convert yaw angle to a continuous value (unwrapped)\n", + " yaw_angles = df['[Measured] Current Yaw Angle ~ Phi(t) (deg)'].values\n", + " continuous_yaw = np.unwrap(np.radians(yaw_angles))\n", + " continuous_yaw_deg = np.degrees(continuous_yaw)\n", + " df['Unwrapped_Yaw'] = continuous_yaw_deg\n", + " \n", + " # Calculate the rate of change of yaw (derivative)\n", + " df['Calculated_Angular_Velocity'] = df['Unwrapped_Yaw'].diff() / df[time_column].diff()\n", + " \n", + " # Apply a small amount of smoothing to reduce noise in the derivative\n", + " window_size = 5\n", + " if len(df) > window_size * 2:\n", + " df['Calculated_Angular_Velocity'] = df['Calculated_Angular_Velocity'].rolling(\n", + " window=window_size, center=True).mean().fillna(method='bfill').fillna(method='ffill')\n", + " \n", + " # Create a figure with two subplots sharing x-axis\n", + " fig, (ax1, ax2) = plt.subplots(2, 1, figsize=(12, 8), sharex=True)\n", + " \n", + " # Plot 1: Yaw Angle\n", + " ax1.plot(df[time_column], df['[Measured] Current Yaw Angle ~ Phi(t) (deg)'], \n", + " 'b-', linewidth=2.5, label=r'Yaw Angle $\\Phi(t)$ (degrees)')\n", + " \n", + " # Add horizontal line at y=0\n", + " ax1.axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Set labels for first plot\n", + " ax1.set_ylabel('Yaw Angle (degrees)', fontsize=13)\n", + " ax1.grid(True, alpha=0.3)\n", + " ax1.legend(loc='best')\n", + " \n", + " # Plot 2: Angular Velocity comparison\n", + " ax2.plot(df[time_column], df['Calculated_Angular_Velocity'], \n", + " 'r-', linewidth=2.0, label=r'Calculated from Yaw $\\dot{\\Phi}(t)$ (deg/s)')\n", + " \n", + " if '[Measured] Angular VelocityZ ~ Phi_dot(t) (deg/s)' in df.columns:\n", + " # Convert to degrees per second for more intuitive reading\n", + " df['Measured_Angular_Velocity_deg_s'] = df['[Measured] Angular VelocityZ ~ Phi_dot(t) (deg/s)'] \n", + " ax2.plot(df[time_column], df['Measured_Angular_Velocity_deg_s'], \n", + " 'g--', linewidth=2.0, label=r'Measured $\\omega_{yaw}$ (deg/s)')\n", + " \n", + " # Add horizontal line at y=0\n", + " ax2.axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Set labels for second plot\n", + " ax2.set_xlabel('Time (s)', fontsize=13)\n", + " ax2.set_ylabel('Yaw Angular Velocity (°/s)', fontsize=13)\n", + " ax2.grid(True, alpha=0.3)\n", + " ax2.legend(loc='best')\n", + " \n", + " # Add a title for the overall figure\n", + " fig.suptitle('Vehicle Yaw Motion Analysis', fontsize=16, y=0.98)\n", + " \n", + " # Adjust layout\n", + " plt.tight_layout()\n", + " plt.subplots_adjust(top=0.93)\n", + " \n", + " # Save the figures\n", + " plt.savefig(f\"{output_file}.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{output_file}.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"Plots saved as {output_file}.pdf and {output_file}.png\")\n", + " \n", + "\n", + "# Load your data\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Create the yaw angle plots\n", + "plot_yaw_angle_time_series(df, output_file=f'plots/{recorded_time}/yaw_angle_time_series')" + ] + }, + { + "cell_type": "code", + "execution_count": 41, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Plots saved as plots/2025-03-24_13-53-49/steering_angles_time_series.pdf and plots/2025-03-24_13-53-49/steering_angles_time_series.png\n", + "Wheel angles comparison saved as plots/2025-03-24_13-53-49/steering_angles_time_series_wheel_angles_comparison.pdf and plots/2025-03-24_13-53-49/steering_angles_time_series_wheel_angles_comparison.png\n", + "Correlation plot saved as plots/2025-03-24_13-53-49/steering_angles_time_series_correlation.pdf and plots/2025-03-24_13-53-49/steering_angles_time_series_correlation.png\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# SWA on time series\n", + "import matplotlib.pyplot as plt\n", + "import pandas as pd\n", + "import numpy as np\n", + "\n", + "def plot_steering_angles_time_series(df, output_file='steering_angles_time_series'):\n", + " \"\"\"\n", + " Create simple time series plots for steering angles and vehicle turning angle.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the vehicle data\n", + " output_file (str): Base filename for output (without extension)\n", + " \"\"\"\n", + " # Set up plot style for clean presentation\n", + " plt.style.use('default')\n", + " plt.rcParams.update({'font.size': 12})\n", + " \n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " \n", + " # Create a figure with two subplots sharing x-axis\n", + " fig, (ax1, ax2) = plt.subplots(2, 1, figsize=(12, 8), sharex=True)\n", + " \n", + " # Plot 1: Steering Wheel Angle\n", + " ax1.plot(df[time_column], df['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'], \n", + " 'r-', linewidth=2.5, label=r'Steering Wheel Angle $\\Theta(t)$ (degrees)')\n", + " \n", + " # Add horizontal line at y=0\n", + " ax1.axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Set labels for first plot\n", + " ax1.set_ylabel('Steering Wheel Angle (degrees)', fontsize=13)\n", + " ax1.grid(True, alpha=0.3)\n", + " ax1.legend(loc='best')\n", + " \n", + " # Plot 2: Wheel Steering Angles and Vehicle Turning Angle\n", + " ax2.plot(df[time_column], df['[Measured] Steering Angle FL ~ delta_fl(t) (deg)'], \n", + " 'b-', linewidth=2.0, label=r'Front-Left Wheel $\\delta_{fl}(t)$ (deg)')\n", + " ax2.plot(df[time_column], df['[Measured] Steering Angle FR ~ delta_fr(t) (deg)'], \n", + " 'g-', linewidth=2.0, label=r'Front-Right Wheel $\\delta_{fr}(t)$ (deg)')\n", + " ax2.plot(df[time_column], df['[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)'], \n", + " 'r--', linewidth=2.0, label=r'Vehicle Turning Angle $\\delta_v(t)$ (deg)')\n", + " \n", + " # Add horizontal line at y=0\n", + " ax2.axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Set labels for second plot\n", + " ax2.set_xlabel('Time (s)', fontsize=13)\n", + " ax2.set_ylabel('Steering Angle (degrees)', fontsize=13)\n", + " ax2.grid(True, alpha=0.3)\n", + " ax2.legend(loc='best')\n", + " \n", + " # Add a title for the overall figure\n", + " fig.suptitle('Vehicle Steering Analysis', fontsize=16, y=0.98)\n", + " \n", + " # Adjust layout\n", + " plt.tight_layout()\n", + " plt.subplots_adjust(top=0.93)\n", + " \n", + " # Save the figures\n", + " plt.savefig(f\"{output_file}.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{output_file}.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"Plots saved as {output_file}.pdf and {output_file}.png\")\n", + " \n", + " \n", + " # Save the comparison plot\n", + " angles_filename = f\"{output_file}_wheel_angles_comparison\"\n", + " plt.savefig(f\"{angles_filename}.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{angles_filename}.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"Wheel angles comparison saved as {angles_filename}.pdf and {angles_filename}.png\")\n", + " \n", + " # Create a correlation plot between steering wheel angle and vehicle turning angle\n", + " plt.figure(figsize=(8, 8))\n", + " plt.scatter(df['[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)'],\n", + " df['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'],\n", + " alpha=0.6, c=df[time_column], cmap='viridis')\n", + " \n", + " # Add a best fit line\n", + " from scipy.stats import linregress\n", + " slope, intercept, r_value, p_value, std_err = linregress(\n", + " df['[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)'], df['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'])\n", + " \n", + " x = np.array([df['[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)'].min(),\n", + " df['[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)'].max()])\n", + " plt.plot(x, slope*x + intercept, 'r--', \n", + " label=f'y = {slope:.4f}x + {intercept:.4f}\\nR² = {r_value**2:.4f}')\n", + " \n", + " plt.axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " plt.axvline(x=0, color='gray', linestyle='--', alpha=0.4)\n", + " plt.xlabel('Vehicle Turning Angle (degrees)', fontsize=13)\n", + " plt.ylabel('Steering Wheel Angle (degrees)', fontsize=13)\n", + " plt.title('Correlation: Steering Wheel Angle vs Vehicle Turning Angle', fontsize=16)\n", + " plt.grid(True, alpha=0.3)\n", + " plt.legend(loc='best')\n", + " plt.colorbar(label='Time (s)')\n", + " plt.tight_layout()\n", + " \n", + " # Save the correlation plot\n", + " corr_filename = f\"{output_file}_correlation\"\n", + " plt.savefig(f\"{corr_filename}.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{corr_filename}.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"Correlation plot saved as {corr_filename}.pdf and {corr_filename}.png\")\n", + "\n", + "# Load your data\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Create the steering angle plots\n", + "plot_steering_angles_time_series(df, output_file=f'plots/{recorded_time}/steering_angles_time_series')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# predicted position on time series\n", + "import matplotlib.pyplot as plt\n", + "import numpy as np\n", + "import pandas as pd\n", + "\n", + "def plot_prediction_metrics_time_series(df, output_file='prediction_metrics_time_series'):\n", + " \"\"\"\n", + " Create time series plots for prediction metrics including predicted position,\n", + " predicted yaw angle, and desired steering wheel angle, with X and Y positions in separate plots.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the vehicle data\n", + " output_file (str): Base filename for output (without extension)\n", + " \"\"\"\n", + " # Set up plot style\n", + " plt.style.use('default')\n", + " plt.rcParams.update({'font.size': 12})\n", + " \n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " time_column = 'Normalized Time'\n", + " \n", + " # Create figure with subplots - now with 4 panels instead of 3\n", + " fig, axes = plt.subplots(4, 1, figsize=(12, 16), sharex=True)\n", + " \n", + " # Plot 1: X Position (Measured vs Predicted)\n", + " axes[0].plot(df[time_column], df['[Measured] Current Position ~ X(t) (m)'], 'b-', \n", + " linewidth=2, label=r'Measured X Position $X(t)$ (m)')\n", + " axes[0].plot(df[time_column], df['[Computed] Predicted Position ~ X_tp(t) (m)'], 'r--', \n", + " linewidth=2, label=r'Predicted X Position $X^{tp}(t)$ (m)')\n", + " \n", + " # Calculate X positional error\n", + " df['Position_Error_X'] = df['[Measured] Current Position ~ X(t) (m)'] - df['[Computed] Predicted Position ~ X_tp(t) (m)']\n", + " \n", + " # Add error as text annotation\n", + " mean_error_x = df['Position_Error_X'].mean()\n", + " max_error_x = df['Position_Error_X'].max()\n", + " axes[0].text(0.02, 0.8, f'Mean X Error: {mean_error_x:.4f} m\\nMax X Error: {max_error_x:.4f} m', \n", + " transform=axes[0].transAxes, bbox=dict(facecolor='white', alpha=0.7))\n", + " \n", + " axes[0].set_ylabel('X Position (m)', fontsize=14)\n", + " axes[0].set_title('Measured vs Predicted X Position', fontsize=16)\n", + " axes[0].grid(True, alpha=0.3)\n", + " axes[0].legend(loc='upper right')\n", + " \n", + " # Plot 2: Y Position (Measured vs Predicted)\n", + " axes[1].plot(df[time_column], df['[Measured] Current Position ~ Y(t) (m)'], 'g-', \n", + " linewidth=2, label=r'Measured Y Position $Y(t)$ (m)')\n", + " axes[1].plot(df[time_column], df['[Computed] Predicted Position ~ Y_tp(t) (m)'], 'r--', \n", + " linewidth=2, label=r'Predicted Y Position $Y^{tp}(t)$ (m)')\n", + " \n", + " # Calculate Y positional error\n", + " df['Position_Error_Y'] = df['[Measured] Current Position ~ Y(t) (m)'] - df['[Computed] Predicted Position ~ Y_tp(t) (m)']\n", + " \n", + " # Add error as text annotation\n", + " mean_error_y = df['Position_Error_Y'].mean()\n", + " max_error_y = df['Position_Error_Y'].max()\n", + " axes[1].text(0.02, 0.8, f'Mean Y Error: {mean_error_y:.4f} m\\nMax Y Error: {max_error_y:.4f} m', \n", + " transform=axes[1].transAxes, bbox=dict(facecolor='white', alpha=0.7))\n", + " \n", + " axes[1].set_ylabel('Y Position (m)', fontsize=14)\n", + " axes[1].set_title('Measured vs Predicted Y Position', fontsize=16)\n", + " axes[1].grid(True, alpha=0.3)\n", + " axes[1].legend(loc='upper right')\n", + " \n", + " # Calculate total positional error\n", + " df['Position_Error'] = np.sqrt(df['Position_Error_X']**2 + df['Position_Error_Y']**2)\n", + " \n", + " # Plot 3: Yaw Angle (Measured vs Predicted)\n", + " axes[2].plot(df[time_column], df['[Measured] Current Yaw Angle ~ Phi(t) (deg)'], 'b-', \n", + " linewidth=2.5, label=r'Measured Yaw Angle $\\phi(t)$ (deg)')\n", + " axes[2].plot(df[time_column], df['[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)'], 'r--', \n", + " linewidth=2, label=r'Predicted Yaw Angle $\\phi^{tp}(t)$ (deg)')\n", + " axes[2].plot(df[time_column], df['[Computed] Change of Yaw Angle ~ Delta_Phi(t) (deg)'], 'g:', \n", + " linewidth=1.5, label=r'Chang of Yaw Angle $\\Delta \\phi(t)$ (deg)')\n", + " \n", + " # Add horizontal line at y=0 for reference\n", + " axes[2].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Calculate yaw prediction error\n", + " df['Yaw_Error'] = df['[Measured] Current Yaw Angle ~ Phi(t) (deg)'] - df['[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)']\n", + " mean_yaw_error = np.abs(df['Yaw_Error']).mean()\n", + " max_yaw_error = np.abs(df['Yaw_Error']).max()\n", + " axes[2].text(0.02, 0.8, f'Mean Yaw Error: {mean_yaw_error:.4f}°\\nMax Yaw Error: {max_yaw_error:.4f}°', \n", + " transform=axes[2].transAxes, bbox=dict(facecolor='white', alpha=0.7))\n", + " \n", + " axes[2].set_ylabel('Yaw Angle (degrees)', fontsize=14)\n", + " axes[2].set_title('Measured vs Predicted Yaw Angle', fontsize=16)\n", + " axes[2].grid(True, alpha=0.3)\n", + " axes[2].legend(loc='upper right')\n", + " \n", + " # Plot 4: Steering Wheel Angle (Measured vs Desired)\n", + " axes[3].plot(df[time_column], df['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'], 'b-', \n", + " linewidth=2.5, label=r'Measured SWA $\\Theta(t)$ (deg)')\n", + " axes[3].plot(df[time_column], df['[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)'], 'r--', \n", + " linewidth=2, label=r'Desired SWA $\\Theta_d(t)$ (deg)')\n", + " \n", + " # Add horizontal line at y=0 for reference\n", + " axes[3].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Calculate steering error and torque correlation\n", + " df['Steering_Error'] = df['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'] - df['[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)']\n", + " mean_steering_error = np.abs(df['Steering_Error']).mean()\n", + " max_steering_error = np.abs(df['Steering_Error']).max()\n", + " \n", + " # Correlation between steering error and applied torque\n", + " correlation = df['Steering_Error'].corr(df['[Computed] Torque applied ~ Tau_das (N.m)'])\n", + " \n", + " axes[3].text(0.02, 0.8, \n", + " f'Mean Steering Error: {mean_steering_error:.4f}°\\nMax Steering Error: {max_steering_error:.4f}°\\nError-Torque Correlation: {correlation:.4f}', \n", + " transform=axes[3].transAxes, bbox=dict(facecolor='white', alpha=0.7))\n", + " \n", + " # Add torque on secondary y-axis\n", + " ax2 = axes[3].twinx()\n", + " ax2.plot(df[time_column], df['[Computed] Torque applied ~ Tau_das (N.m)'], 'g:', \n", + " linewidth=2, label=r'Applied Torque $\\tau_{das}(t)$ (N·m)')\n", + " ax2.set_ylabel('Torque (N·m)', color='g', fontsize=14)\n", + " ax2.tick_params(axis='y', labelcolor='g')\n", + " \n", + " # Combine legends\n", + " lines1, labels1 = axes[3].get_legend_handles_labels()\n", + " lines2, labels2 = ax2.get_legend_handles_labels()\n", + " axes[3].legend(lines1 + lines2, labels1 + labels2, loc='lower right')\n", + " \n", + " axes[3].set_xlabel('Time (s)', fontsize=14)\n", + " axes[3].set_ylabel('Steering Wheel Angle (degrees)', fontsize=14)\n", + " axes[3].set_title('Measured vs Desired Steering Wheel Angle and Applied Torque', fontsize=16)\n", + " axes[3].grid(True, alpha=0.3)\n", + " \n", + " # Adjust layout and save\n", + " plt.tight_layout()\n", + " plt.subplots_adjust(hspace=0.3)\n", + " \n", + " # Save the figure\n", + " plt.savefig(f\"{output_file}.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{output_file}.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"Plot saved as {output_file}.pdf and {output_file}.png\")\n", + " \n", + " # Also create a plot of position errors over time\n", + " plt.figure(figsize=(12, 6))\n", + " plt.plot(df[time_column], df['Position_Error_X'], 'b-', marker='o',\n", + " linewidth=2, label='X Position Error')\n", + " plt.plot(df[time_column], df['Position_Error_Y'], 'g-', marker='o',\n", + " linewidth=2, label='Y Position Error')\n", + " plt.plot(df[time_column], df['Position_Error'], 'r-', \n", + " linewidth=2, label='Total Error')\n", + " \n", + " plt.axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " plt.xlabel('Time (s)', fontsize=14)\n", + " plt.ylabel('Error (m)', fontsize=14)\n", + " plt.title('Position Prediction Errors Over Time', fontsize=16)\n", + " plt.grid(True, alpha=0.3)\n", + " plt.legend(loc='best')\n", + " \n", + " # Save the error plot\n", + " plt.savefig(f\"{output_file}_errors.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{output_file}_errors.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"Error plot saved as {output_file}_errors.pdf and {output_file}_errors.png\")\n", + " \n", + " # Create a 2D visualization of measured vs predicted positions (unchanged)\n", + " plt.figure()\n", + " \n", + " # Select a subset of points for better visualization (every Nth point)\n", + " skip = max(1, len(df) // 50) # Show about 50 points\n", + " subset = df.iloc[::skip].copy()\n", + " \n", + " plt.plot(subset['[Measured] Current Position ~ Y(t) (m)'], \n", + " subset['[Measured] Current Position ~ X(t) (m)'], \n", + " 'bo-', linewidth=1.5, markersize=4, label='Measured Path')\n", + " plt.plot(subset['[Computed] Predicted Position ~ Y_tp(t) (m)'], \n", + " subset['[Computed] Predicted Position ~ X_tp(t) (m)'], \n", + " 'ro-', linewidth=1.5, markersize=4, label='Predicted Path')\n", + " \n", + " # Connect measured and predicted points with thin lines\n", + " for i in range(len(subset)):\n", + " plt.plot([subset['[Measured] Current Position ~ Y(t) (m)'].iloc[i], \n", + " subset['[Computed] Predicted Position ~ Y_tp(t) (m)'].iloc[i]],\n", + " [subset['[Measured] Current Position ~ X(t) (m)'].iloc[i], \n", + " subset['[Computed] Predicted Position ~ X_tp(t) (m)'].iloc[i]],\n", + " 'k--', linewidth=0.5, alpha=0.3)\n", + " \n", + " # Add arrows to show direction of travel\n", + " for i in range(0, len(subset), 5):\n", + " # Measured direction arrow\n", + " plt.arrow(subset['[Measured] Current Position ~ Y(t) (m)'].iloc[i], \n", + " subset['[Measured] Current Position ~ X(t) (m)'].iloc[i],\n", + " 0.3*np.sin(np.radians(subset['[Measured] Current Yaw Angle ~ Phi(t) (deg)'].iloc[i])),\n", + " 0.3*np.cos(np.radians(subset['[Measured] Current Yaw Angle ~ Phi(t) (deg)'].iloc[i])),\n", + " head_width=0.1, head_length=0.2, fc='blue', ec='blue')\n", + " \n", + " # Predicted direction arrow\n", + " plt.arrow(subset['[Computed] Predicted Position ~ Y_tp(t) (m)'].iloc[i], \n", + " subset['[Computed] Predicted Position ~ X_tp(t) (m)'].iloc[i],\n", + " 0.3*np.sin(np.radians(subset['[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)'].iloc[i])),\n", + " 0.3*np.cos(np.radians(subset['[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)'].iloc[i])),\n", + " head_width=0.1, head_length=0.2, fc='red', ec='red')\n", + " \n", + " plt.grid(True, alpha=0.3)\n", + " plt.axis('equal')\n", + " plt.xlabel('Y Position (m)', fontsize=14)\n", + " plt.ylabel('X Position (m)', fontsize=14)\n", + " plt.title('2D Visualization of Measured vs Predicted Positions', fontsize=16)\n", + " plt.legend(loc='best')\n", + " \n", + " plt.savefig(f\"{output_file}_2D_path.pdf\", format='pdf', bbox_inches='tight')\n", + " plt.savefig(f\"{output_file}_2D_path.png\", format='png', dpi=300, bbox_inches='tight')\n", + " print(f\"2D path plot saved as {output_file}_2D_path.pdf and {output_file}_2D_path.png\")\n", + " \n", + " return df\n", + "\n", + "# Load the data and create the plots\n", + "# Load your data and call the function\n", + "df = pd.read_excel(f'../data/path_logs/data_{recorded_time}.xlsx')\n", + "\n", + "# Create the plots\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Generate the plots\n", + "df_processed = plot_prediction_metrics_time_series(df, trajectory=predefined, output_file=f'plots/{recorded_time}/prediction_metrics_time_series')" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [], + "source": [ + "import pandas as pd\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from matplotlib.backends.backend_pdf import PdfPages\n", + "import os\n", + "\n", + "def create_concise_time_series(df, output_file='concise_time_series.pdf', start_time=13):\n", + " \"\"\"\n", + " Create streamlined time series plots for parameters in the dataframe,\n", + " with 4 plots per page and combined plots with dual axes as specified.\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the haptic control data\n", + " output_file (str): Output PDF filename\n", + " start_time (float): Starting time in seconds for data filtering\n", + " \"\"\"\n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " \n", + " # Filter data starting from the specified time\n", + " df_filtered = df[df['Normalized Time'] >= start_time].copy()\n", + " df_filtered['Normalized Time'] = df_filtered['Normalized Time'] - start_time\n", + " time_column = 'Normalized Time'\n", + " time_label = 'Time (s)'\n", + " \n", + " # Set consistent plotting style for maximum compactness\n", + " plt.style.use('default')\n", + " plt.rcParams.update({\n", + " 'font.size': 14,\n", + " 'axes.titlesize': 14,\n", + " 'axes.labelsize': 13,\n", + " 'xtick.labelsize': 12,\n", + " 'ytick.labelsize': 12,\n", + " 'legend.fontsize': 12,\n", + " 'figure.titlesize': 14,\n", + " })\n", + " \n", + " # Create the PDF file\n", + " with PdfPages(output_file) as pdf:\n", + " # PAGE 1: 4 plots - X positions, Y positions, Yaw angle, Trajectory error\n", + " # fig = plt.figure(figsize=(12, 16)) # A4 size, portrait\n", + " fig, axes = plt.subplots(4, 1, figsize=(12, 16), sharex=True)\n", + " \n", + " # Define grid layout for the plots (4 panels)\n", + " # gs = plt.GridSpec(4, 1, figure=fig, height_ratios=[1, 1, 1, 1], hspace=0.3)\n", + " \n", + " # 1. POSITIONS X (measured vs predicted)\n", + " # ax1 = fig.add_subplot(gs[0])\n", + " axes[0].plot(df_filtered[time_column], df_filtered['[Measured] Current Position ~ X(t) (m)'], 'b-', linewidth=1, label=r'Current X Position $X(t)$ (m)')\n", + " axes[0].plot(df_filtered[time_column], df_filtered['[Computed] Predicted Position ~ X_tp(t) (m)'], 'r--', linewidth=1, label=r'Predicted X Position $X^{tp}(t)$ (m)')\n", + " axes[0].set_title('X Position (Measured vs Predicted)', fontsize=14)\n", + " axes[0].set_ylabel('X Position (m)', fontsize=14)\n", + " axes[0].grid(True, alpha=0.3)\n", + " axes[0].legend(loc='best')\n", + " \n", + " # 2. POSITIONS Y (measured vs predicted)\n", + " # axes[1] = fig.add_subplot(gs[1])\n", + " axes[1].plot(df_filtered[time_column], df_filtered['[Measured] Current Position ~ Y(t) (m)'], 'b-', linewidth=1, label=r'Current Y Position $Y(t)$ (m)')\n", + " axes[1].plot(df_filtered[time_column], df_filtered['[Computed] Predicted Position ~ Y_tp(t) (m)'], 'r--', linewidth=1, label=r'Predicted Y Position $Y^{tp}(t)$ (m)')\n", + " axes[1].set_title('Y Position (Measured vs Predicted)', fontsize=14)\n", + " axes[1].set_ylabel('Y Position (m)', fontsize=14)\n", + " axes[1].grid(True, alpha=0.3)\n", + " axes[1].legend(loc='best')\n", + " \n", + " # 3. YAW ANGLE (measured vs predicted) - SEPARATE\n", + " # axes[2] = fig.add_subplot(gs[2])\n", + " axes[2].plot(df_filtered[time_column], df_filtered['[Measured] Current Yaw Angle ~ Phi(t) (deg)'], 'b-', linewidth=1, label=r'Measured Yaw Angle $\\phi(t)$ (deg)')\n", + " axes[2].plot(df_filtered[time_column], df_filtered['[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)'], 'r--', linewidth=1, label=r'Predicted Yaw Angle $\\phi^{tp}(t)$ (deg)')\n", + " axes[2].set_title('Yaw Angle (Measured vs Predicted)', fontsize=14)\n", + " axes[2].set_ylabel('Yaw Angle (deg)', fontsize=14)\n", + " axes[2].grid(True, alpha=0.3)\n", + " axes[2].legend(loc='best')\n", + " \n", + " # 4. TRAJECTORY ERROR (current and predicted) - SEPARATE\n", + " # ax4 = fig.add_subplot(gs[3])\n", + " axes[3].plot(df_filtered[time_column], df_filtered['[Computed] Current Error to Trajectory ~ e(t) (m)'], 'b-', linewidth=1, label=r'Current Error to Trajectory $e(t)$ (m)')\n", + " axes[3].plot(df_filtered[time_column], df_filtered['[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)'], 'r--', linewidth=1, label=r'Predicted Error to Trajectory $\\epsilon^{tp}(t)$ (m)')\n", + " axes[3].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " axes[3].set_title('Trajectory Error', fontsize=14)\n", + " axes[3].set_xlabel(time_label, fontsize=14)\n", + " axes[3].set_ylabel('Error (m)', fontsize=14)\n", + " axes[3].grid(True, alpha=0.3)\n", + " axes[3].legend(loc='best')\n", + " \n", + " plt.tight_layout()\n", + " pdf.savefig()\n", + " plt.close()\n", + " \n", + " # PAGE 2: 4 plots with combined plots and dual axes\n", + " # fig = plt.figure(figsize=(12, 16)) # A4 size, portrait\n", + " # gs = plt.GridSpec(4, 1, figure=fig, height_ratios=[1, 1, 1, 1], hspace=0.3)\n", + " fig, axes = plt.subplots(4, 1, figsize=(12, 16), sharex=True)\n", + " \n", + " # 1. SPEED AND VELOCITY with ACCELERATION ON RIGHT AXIS\n", + " # ax1 = fig.add_subplot(gs[0])\n", + " axes[0].plot(df_filtered[time_column], df_filtered['[Measured] Speed ~ V(t) (m/s)'], 'k-', linewidth=1.5, label=r'Speed $V(t)$ (m/s)')\n", + " axes[0].plot(df_filtered[time_column], df_filtered['[Measured] VelocityX ~ Vx(t) (m/s)'], 'b-', linewidth=1, label=r'Velocity X $V_x(t)$ (m/s)')\n", + " axes[0].plot(df_filtered[time_column], df_filtered['[Measured] VelocityY ~ Vy(t) (m/s)'], 'g-', linewidth=1, label=r'Velocity Y $V_y(t)$ (m/s)')\n", + " axes[0].set_ylabel('Speed/Velocity (m/s)', fontsize=14)\n", + " axes[0].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Acceleration on right y-axis\n", + " ax1_right = axes[0].twinx()\n", + " ax1_right.plot(df_filtered[time_column], df_filtered['[Measured] AccelerationX ~ Ax(t) (m/s^2)'], 'b--', linewidth=1, label=r'Accel X $A_x(t)$ (m/s²)')\n", + " ax1_right.plot(df_filtered[time_column], df_filtered['[Measured] AccelerationY ~ Ay(t) (m/s^2)'], 'g--', linewidth=1, label=r'Accel Y $A_y(t)$ (m/s²)')\n", + " \n", + " # Calculate acceleration magnitude\n", + " df_filtered['Acceleration_magnitude'] = np.sqrt(\n", + " df_filtered['[Measured] AccelerationX ~ Ax(t) (m/s^2)']**2 + \n", + " df_filtered['[Measured] AccelerationY ~ Ay(t) (m/s^2)']**2\n", + " )\n", + " ax1_right.plot(df_filtered[time_column], df_filtered['Acceleration_magnitude'], 'r--', linewidth=1, label=r'|Accel| (m/s²)')\n", + " ax1_right.set_ylabel('Acceleration (m/s²)', color='r', fontsize=14)\n", + " ax1_right.tick_params(axis='y', colors='r')\n", + " \n", + " # Combine legends\n", + " lines1, labels1 = axes[0].get_legend_handles_labels()\n", + " lines1_right, labels1_right = ax1_right.get_legend_handles_labels()\n", + " axes[0].legend(lines1 + lines1_right, labels1 + labels1_right, loc='best', ncol=2)\n", + " \n", + " axes[0].set_title('Speed, Velocity, and Acceleration', fontsize=14)\n", + " axes[0].grid(True, alpha=0.3)\n", + " \n", + " # 2. CENTER OF ROTATION WITH TURNING RADIUS ON RIGHT AXIS\n", + " # ax2 = fig.add_subplot(gs[1])\n", + " \n", + " # Center of rotation with clipped values for better visualization\n", + " cor_x = df_filtered['[Computed] Center of Rotation to WORLD ~ X_c(t) (m)']\n", + " cor_y = df_filtered['[Computed] Center of Rotation to WORLD ~ Y_c(t) (m)']\n", + " \n", + " # Filter extreme values for better visualization\n", + " x_threshold = np.percentile(np.abs(cor_x[~np.isinf(cor_x)]), 95)\n", + " y_threshold = np.percentile(np.abs(cor_y[~np.isinf(cor_y)]), 95)\n", + " \n", + " cor_x_filtered = np.clip(cor_x, -x_threshold, x_threshold)\n", + " cor_y_filtered = np.clip(cor_y, -y_threshold, y_threshold)\n", + " \n", + " axes[1].plot(df_filtered[time_column], cor_x_filtered, 'b-', linewidth=1, label=r'CoR X $X_c(t)$ (m)')\n", + " axes[1].plot(df_filtered[time_column], cor_y_filtered, 'g-', linewidth=1, label=r'CoR Y $Y_c(t)$ (m)')\n", + " axes[1].set_ylabel('Center of Rotation (m)', fontsize=14)\n", + " axes[1].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Turning radius on right y-axis\n", + " ax2_right = axes[1].twinx()\n", + " radius_data = df_filtered['[Computed] Turning Radius ~ R(delta) (m)']\n", + " # Clip extreme radius values for better visualization\n", + " radius_threshold = np.percentile(np.abs(radius_data[~np.isinf(radius_data)]), 95)\n", + " clipped_radius = np.clip(radius_data, -radius_threshold, radius_threshold)\n", + " ax2_right.plot(df_filtered[time_column], clipped_radius, 'r-', linewidth=1, label=r'Turning Radius $R(\\delta)$ (m)')\n", + " ax2_right.set_ylabel('Turning Radius (m)', color='r', fontsize=14)\n", + " ax2_right.tick_params(axis='y', colors='r')\n", + " \n", + " # Combine legends\n", + " lines2, labels2 = axes[1].get_legend_handles_labels()\n", + " lines2_right, labels2_right = ax2_right.get_legend_handles_labels()\n", + " axes[1].legend(lines2 + lines2_right, labels2 + labels2_right, loc='best', ncol=2)\n", + " \n", + " axes[1].set_title('Center of Rotation and Turning Radius', fontsize=14)\n", + " axes[1].grid(True, alpha=0.3)\n", + " \n", + " # 3. STEERING WHEEL ANGLE AND ROTATION DIRECTION\n", + " # ax3 = fig.add_subplot(gs[2])\n", + " \n", + " # Steering wheel angle\n", + " axes[2].plot(df_filtered[time_column], df_filtered['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'], 'b-', linewidth=1, label=r'Measured SWA $\\Theta(t)$ (deg)')\n", + " axes[2].plot(df_filtered[time_column], df_filtered['[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)'], 'r--', linewidth=1, label=r'Desired SWA $\\Theta_d(t)$ (deg)')\n", + " axes[2].set_ylabel('Steering Wheel Angle (deg)', fontsize=14)\n", + " axes[2].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " \n", + " # Rotation direction on right y-axis\n", + " ax3_right = axes[2].twinx()\n", + " ax3_right.plot(df_filtered[time_column], df_filtered['[Computed] Rotation direction ~ rotate(t) (CW/CCW)'], 'k-', linewidth=1, label=r'Rotation Direction (CW/CCW)')\n", + " ax3_right.set_ylim(-1.1, 1.1)\n", + " ax3_right.set_yticks([-1, 0, 1])\n", + " ax3_right.set_yticklabels(['CW', '0', 'CCW'])\n", + " ax3_right.set_ylabel('Rotation Direction', color='k', fontsize=14)\n", + " ax3_right.tick_params(axis='y', colors='k')\n", + " \n", + " # Combine legends\n", + " lines3, labels3 = axes[2].get_legend_handles_labels()\n", + " lines3_right, labels3_right = ax3_right.get_legend_handles_labels()\n", + " axes[2].legend(lines3 + lines3_right, labels3 + labels3_right, loc='best', ncol=2)\n", + " \n", + " axes[2].set_title('Steering Wheel Angle and Rotation Direction', fontsize=14)\n", + " axes[2].grid(True, alpha=0.3)\n", + " \n", + " # 4. WHEEL STEERING ANGLES AND VEHICLE STEERING ANGLE WITH DIFFERENT SCALES\n", + " # ax4 = fig.add_subplot(gs[3])\n", + " \n", + " # Steering wheel angle on left axis\n", + " axes[3].plot(df_filtered[time_column], df_filtered['[Measured] Steering Wheel Angle SWA ~ Theta(t) (deg)'], 'b-', linewidth=1, label=r'Measured SWA $\\Theta(t)$ (deg)')\n", + " axes[3].set_ylabel('Steering Wheel Angle (deg)', fontsize=14)\n", + " axes[3].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " axes[3].set_xlabel(time_label, fontsize=14)\n", + " \n", + " # Wheel steering angles on right axis\n", + " ax4_right = axes[3].twinx()\n", + " ax4_right.plot(df_filtered[time_column], df_filtered['[Measured] Steering Angle FL ~ delta_fl(t) (deg)'], 'g-', linewidth=1, label=r'FL Wheel $\\delta_{fl}(t)$ (deg)')\n", + " ax4_right.plot(df_filtered[time_column], df_filtered['[Measured] Steering Angle FR ~ delta_fr(t) (deg)'], 'g--', linewidth=1, label=r'FR Wheel $\\delta_{fr}(t)$ (deg)')\n", + " ax4_right.plot(df_filtered[time_column], df_filtered['[Computed] Vehicle Steering Angle ~ Delta_v(t) (deg)'], 'r-', linewidth=1, label=r'Vehicle Angle $\\delta_v(t)$ (deg)')\n", + " ax4_right.set_ylabel('Wheel Angles (deg)', color='g', fontsize=14)\n", + " ax4_right.tick_params(axis='y', colors='g')\n", + " \n", + " # Combine legends\n", + " lines4, labels4 = axes[3].get_legend_handles_labels()\n", + " lines4_right, labels4_right = ax4_right.get_legend_handles_labels()\n", + " axes[3].legend(lines4 + lines4_right, labels4 + labels4_right, loc='best', ncol=2)\n", + " \n", + " axes[3].set_title('Steering Wheel Angle and Wheel/Vehicle Angles', fontsize=14)\n", + " axes[3].grid(True, alpha=0.3)\n", + " \n", + " plt.tight_layout()\n", + " pdf.savefig()\n", + " plt.close()\n", + " \n", + " print(f\"Time series plots with dual axes (starting at t={start_time}s) saved to {output_file}\")\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Time series plots with dual axes (starting at t=0s) saved to plots/2025-03-25_13-31-50/concise_time_series_updated.pdf\n" + ] + } + ], + "source": [ + "# Load the data and generate plots\n", + "import os\n", + "df = pd.read_excel(f\"../data/path_logs/data_{recorded_time}.xlsx\")\n", + "# Create output directory if needed\n", + "os.makedirs(f'plots/{recorded_time}', exist_ok=True)\n", + "\n", + "# Generate the plots starting from 13 seconds\n", + "create_concise_time_series(df, output_file=f'plots/{recorded_time}/concise_time_series_updated.pdf', start_time=0)" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Trajectory not found. Creating a dummy trajectory for demonstration.\n", + "Trajectory comparison plots saved to plots/trajectory_comparison.pdf\n" + ] + } + ], + "source": [ + "import pandas as pd\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from matplotlib.backends.backend_pdf import PdfPages\n", + "import os\n", + "from scipy.spatial import KDTree\n", + "\n", + "def find_closest_point(given_point, list_of_points, method=\"KDTree\"):\n", + " \"\"\"\n", + " Find the closest point in list_of_points to the given_point\n", + " \n", + " Parameters:\n", + " given_point: A point [x, y]\n", + " list_of_points: List of points [[x1, y1], [x2, y2], ...]\n", + " method: Method to use for finding closest point (\"KDTree\" or other)\n", + " \n", + " Returns:\n", + " closest_point: The closest point in list_of_points\n", + " idx: Index of the closest point in list_of_points\n", + " \"\"\"\n", + " # Convert list_of_points to a NumPy array for efficient processing\n", + " points = np.array(list_of_points)\n", + "\n", + " if method == \"KDTree\":\n", + " # Build a KD-Tree from the points\n", + " tree = KDTree(points)\n", + "\n", + " # Find the index of the nearest neighbor\n", + " _, nnidx = tree.query(given_point, k=1)\n", + " else:\n", + " # Find the index of the nearest neighbor\n", + " nnidx = np.argmin(np.linalg.norm(points - given_point, axis=1))\n", + " \n", + " # Return the closest point using the found index\n", + " return list_of_points[nnidx], nnidx\n", + "\n", + "def create_trajectory_comparison_plots(df, trajectory, output_file='trajectory_comparison.pdf', start_time=13):\n", + " \"\"\"\n", + " Create plots comparing current and predicted positions with closest points on trajectory\n", + " \n", + " Parameters:\n", + " df (DataFrame): The dataframe containing the haptic control data\n", + " trajectory: List of trajectory points [[x1, y1], [x2, y2], ...]\n", + " output_file (str): Output PDF filename\n", + " start_time (float): Starting time in seconds for data filtering\n", + " \"\"\"\n", + " # Normalize time to start from 0\n", + " time_col = 'Time (t)'\n", + " df = df.copy()\n", + " df['Normalized Time'] = df[time_col] - df[time_col].iloc[0]\n", + " \n", + " # Filter data starting from the specified time\n", + " df_filtered = df[df['Normalized Time'] >= start_time].copy()\n", + " df_filtered['Normalized Time'] = df_filtered['Normalized Time'] - start_time\n", + " time_column = 'Normalized Time'\n", + " time_label = 'Time (s)'\n", + " \n", + " # Set consistent plotting style\n", + " plt.style.use('default')\n", + " plt.rcParams.update({\n", + " 'font.size': 14,\n", + " 'axes.titlesize': 14,\n", + " 'axes.labelsize': 13,\n", + " 'xtick.labelsize': 12,\n", + " 'ytick.labelsize': 12,\n", + " 'legend.fontsize': 12,\n", + " 'figure.titlesize': 14,\n", + " })\n", + " \n", + " # Create arrays for closest points\n", + " # For current position\n", + " current_positions = np.array([\n", + " df_filtered['[Measured] Current Position ~ X(t) (m)'].values,\n", + " df_filtered['[Measured] Current Position ~ Y(t) (m)'].values\n", + " ]).T\n", + " \n", + " # For predicted position\n", + " predicted_positions = np.array([\n", + " df_filtered['[Computed] Predicted Position ~ X_tp(t) (m)'].values,\n", + " df_filtered['[Computed] Predicted Position ~ Y_tp(t) (m)'].values\n", + " ]).T\n", + " \n", + " # Find closest trajectory points for each position\n", + " closest_current_points = np.zeros_like(current_positions)\n", + " closest_predicted_points = np.zeros_like(predicted_positions)\n", + " \n", + " traj_array = np.array(trajectory)\n", + " \n", + " # Use KDTree for efficient closest point search\n", + " traj_tree = KDTree(traj_array)\n", + " \n", + " # Find closest points for current positions\n", + " _, current_indices = traj_tree.query(current_positions)\n", + " closest_current_points = traj_array[current_indices]\n", + " \n", + " # Find closest points for predicted positions\n", + " _, predicted_indices = traj_tree.query(predicted_positions)\n", + " closest_predicted_points = traj_array[predicted_indices]\n", + " \n", + " # Create DataFrame with closest points\n", + " df_filtered['closest_current_x'] = closest_current_points[:, 0]\n", + " df_filtered['closest_current_y'] = closest_current_points[:, 1]\n", + " df_filtered['closest_predicted_x'] = closest_predicted_points[:, 0]\n", + " df_filtered['closest_predicted_y'] = closest_predicted_points[:, 1]\n", + " \n", + " # Create the PDF file\n", + " with PdfPages(output_file) as pdf:\n", + " # PAGE 1: Current Position vs Closest Point + Current Error\n", + " # fig = plt.figure(figsize=(8.27, 11.69)) # A4 size\n", + " # gs = plt.GridSpec(3, 1, figure=fig, height_ratios=[1, 1, 1], hspace=0.3)\n", + " fig, axes = plt.subplots(3, 1, figsize=(12, 9), sharex=True)\n", + " \n", + " # 1. X position vs closest trajectory X\n", + " # ax1 = fig.add_subplot(gs[0])\n", + " axes[0].plot(df_filtered[time_column], df_filtered['[Measured] Current Position ~ X(t) (m)'], 'b-', linewidth=1.5, label=r'Current X Position $X(t)$ (m)')\n", + " axes[0].plot(df_filtered[time_column], df_filtered['closest_current_x'], 'r--', linewidth=1.5, label=r'Closest Trajectory X $p_{near}(r(t))_x$')\n", + " axes[0].set_title('Current X Position vs Closest Trajectory Point X', fontsize=14)\n", + " axes[0].set_ylabel('X Position (m)', fontsize=14)\n", + " axes[0].grid(True, alpha=0.3)\n", + " axes[0].legend(loc='best')\n", + " \n", + " # 2. Y position vs closest trajectory Y\n", + " # ax2 = fig.add_subplot(gs[1])\n", + " axes[1].plot(df_filtered[time_column], df_filtered['[Measured] Current Position ~ Y(t) (m)'], 'b-', linewidth=1.5, label=r'Current Y Position $Y(t)$ (m)')\n", + " axes[1].plot(df_filtered[time_column], df_filtered['closest_current_y'], 'r--', linewidth=1.5, label=r'Closest Trajectory Y $p_{near}(r(t))_y$')\n", + " axes[1].set_title('Current Y Position vs Closest Trajectory Point Y', fontsize=14)\n", + " axes[1].set_ylabel('Y Position (m)', fontsize=14)\n", + " axes[1].grid(True, alpha=0.3)\n", + " axes[1].legend(loc='best')\n", + " \n", + " # 3. Current error over time\n", + " # ax3 = fig.add_subplot(gs[2])\n", + " axes[2].plot(df_filtered[time_column], df_filtered['[Computed] Current Error to Trajectory ~ e(t) (m)'], 'b-', linewidth=1.5)\n", + " axes[2].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " axes[2].set_title('Current Error to Trajectory', fontsize=14)\n", + " axes[2].set_xlabel(time_label, fontsize=14)\n", + " axes[2].set_ylabel('Error (m)', fontsize=14)\n", + " axes[2].grid(True, alpha=0.3)\n", + " \n", + " # plt.suptitle('Current Position vs Trajectory Comparison', fontsize=14)\n", + " plt.tight_layout()\n", + " pdf.savefig()\n", + " plt.close()\n", + " \n", + " # PAGE 2: Predicted Position vs Closest Point + Predicted Error\n", + " # fig = plt.figure(figsize=(8.27, 11.69)) # A4 size\n", + " # gs = plt.GridSpec(3, 1, figure=fig, height_ratios=[1, 1, 1], hspace=0.3)\n", + " fig, axes = plt.subplots(3, 1, figsize=(12, 9), sharex=True)\n", + "\n", + " # 1. Predicted X position vs closest trajectory X\n", + " # ax1 = fig.add_subplot(gs[0])\n", + " axes[0].plot(df_filtered[time_column], df_filtered['[Computed] Predicted Position ~ X_tp(t) (m)'], 'b-', linewidth=1.5, label=r'Predicted X Position $X^{tp}(t)$ (m)')\n", + " axes[0].plot(df_filtered[time_column], df_filtered['closest_predicted_x'], 'r--', linewidth=1.5, label=r'Closest Trajectory X $p_{near}(r^{tp}(t))_x$')\n", + " axes[0].set_title('Predicted X Position vs Closest Trajectory Point X', fontsize=14)\n", + " axes[0].set_ylabel('X Position (m)', fontsize=14)\n", + " axes[0].grid(True, alpha=0.3)\n", + " axes[0].legend(loc='best')\n", + " \n", + " # 2. Predicted Y position vs closest trajectory Y\n", + " # ax2 = fig.add_subplot(gs[1])\n", + " axes[1].plot(df_filtered[time_column], df_filtered['[Computed] Predicted Position ~ Y_tp(t) (m)'], 'b-', linewidth=1.5, label=r'Predicted Y Position $Y^{tp}(t)$ (m)')\n", + " axes[1].plot(df_filtered[time_column], df_filtered['closest_predicted_y'], 'r--', linewidth=1.5, label=r'Closest Trajectory Y $p_{near}(r^{tp}(t))_y$')\n", + " axes[1].set_title('Predicted Y Position vs Closest Trajectory Point Y', fontsize=14)\n", + " axes[1].set_ylabel('Y Position (m)', fontsize=14)\n", + " axes[1].grid(True, alpha=0.3)\n", + " axes[1].legend(loc='best')\n", + " \n", + " # 3. Predicted error over time\n", + " # ax3 = fig.add_subplot(gs[2])\n", + " axes[2].plot(df_filtered[time_column], df_filtered['[Computed] Predicted Error to Trajectory ~ eps_tp(t) (m)'], 'r-', linewidth=1.5)\n", + " axes[2].axhline(y=0, color='gray', linestyle='--', alpha=0.4)\n", + " axes[2].set_title('Predicted Error to Trajectory', fontsize=14)\n", + " axes[2].set_xlabel(time_label, fontsize=14)\n", + " axes[2].set_ylabel('Error (m)', fontsize=14)\n", + " axes[2].grid(True, alpha=0.3)\n", + " \n", + " # plt.suptitle('Predicted Position vs Trajectory Comparison', fontsize=14)\n", + " plt.tight_layout()\n", + " pdf.savefig()\n", + " plt.close()\n", + " \n", + " print(f\"Trajectory comparison plots saved to {output_file}\")\n", + "\n", + "# Load the data\n", + "try:\n", + " # Try to load data from Excel\n", + " df = pd.read_excel('../data/path_logs/data_2025-03-12_21-04-31.xlsx')\n", + "except:\n", + " try:\n", + " # If Excel fails, try CSV\n", + " df = pd.read_csv('../data/path_logs/data_2025-03-12_21-04-31.csv')\n", + " except:\n", + " print(\"Error loading data file. Please check the path and format.\")\n", + "\n", + "# Load the trajectory data\n", + "# Using the snippet from your notebook to get the trajectory\n", + "# Note: In a real situation, you would need to ensure 'predefined_path' is properly loaded\n", + "try:\n", + " # Try to directly use the trajectory from the workspace\n", + " trajectory = predefined_path[\"2\"][\"backward paths\"][\"path\"]\n", + "except NameError:\n", + " print(\"Trajectory not found. Creating a dummy trajectory for demonstration.\")\n", + " # Create a dummy trajectory (a circle) for demonstration\n", + " # In a real situation, you would load the actual trajectory data\n", + " theta = np.linspace(0, 2*np.pi, 100)\n", + " radius = 10\n", + " x = radius * np.cos(theta)\n", + " y = radius * np.sin(theta)\n", + " trajectory = np.column_stack((x, y))\n", + "\n", + "# Create output directory if needed\n", + "os.makedirs('plots', exist_ok=True)\n", + "\n", + "# Generate the plots starting from 13 seconds\n", + "create_trajectory_comparison_plots(df, trajectory, output_file='plots/trajectory_comparison.pdf', start_time=0)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Steering wheel test" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "**First test**\n", + "\n", + ">for sat in range [0, 100]
\n", + ">> for coefficient in range [0, 100]
\n", + ">>> for offset in range [-100, 100]
\n", + ">>>> rotate to offset using spring force" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "import pandas as pd\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from pprint import pprint\n", + "\n", + "# lX: wheel rotation angle\n", + "# lY: acceleration\n", + "# lRZ: brake\n", + "# relation between wheel rotation and offset, saturation, and speed\n", + "\n", + "plt.style.use('default')\n", + "df = pd.read_excel('../data/wheel_logs/spin_test_offset_rename.xlsx')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plt.figure(figsize=(40, 40))\n", + "for i, sat in enumerate(df['saturation'].unique()):\n", + " for j, coef in enumerate(df['coef'].unique()):\n", + " plt.subplot(19, 19, i * 19 + j + 1)\n", + " df_sub = df[(df['saturation'] == sat) & (df['coef'] == coef)]\n", + " plt.plot(df_sub[\"offset\"], df_sub['lX'], label=f'saturation={sat}, coef={coef}')\n", + " plt.grid()\n", + "\n", + "plt.xlabel('coef')\n", + "plt.ylabel('saturation')\n", + "plt.tight_layout()\n", + "\n", + "plt.show()\n", + "plt.close()\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "**Second test**\n", + "\n", + ">for sat in range [0, 100]
\n", + ">> for coefficient in range [0, 100]
\n", + ">>> for offset in range [-100, 100]
\n", + ">>>> rotate to offset using spring force, then go back to the center point and go to next offset, measure each dt until reach the offset" + ] + }, + { + "cell_type": "code", + "execution_count": 53, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.microsoft.datawrangler.viewer.v0+json": { + "columns": [ + { + "name": "index", + "rawType": "int64", + "type": "integer" + }, + { + "name": "timestamp", + "rawType": "float64", + "type": "float" + }, + { + "name": "State", + "rawType": "object", + "type": "string" + }, + { + "name": "Offset", + "rawType": "int64", + "type": "integer" + }, + { + "name": "Saturation", + "rawType": "int64", + "type": "integer" + }, + { + "name": "Coefficient", + "rawType": "int64", + "type": "integer" + }, + { + "name": "SWA (Measured)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Offset Angle", + "rawType": "float64", + "type": "float" + } + ], + "conversionMethod": "pd.DataFrame", + "ref": "a176f97c-0dbd-42c5-88bb-4257b278ad5a", + "rows": [ + [ + "0", + "3.169951915740967", + "Waiting", + "0", + "10", + "-100", + "0.05493331705679495", + "0.0" + ], + [ + "1", + "3.18389105796814", + "Waiting", + "0", + "10", + "-100", + "0.05493331705679495", + "0.0" + ], + [ + "2", + "3.199071168899536", + "Waiting", + "0", + "10", + "-100", + "0.05493331705679495", + "0.0" + ], + [ + "3", + "3.2150235176086426", + "Waiting", + "0", + "10", + "-100", + "0.05493331705679495", + "0.0" + ], + [ + "4", + "3.230027914047241", + "Waiting", + "0", + "10", + "-100", + "0.05493331705679495", + "0.0" + ] + ], + "shape": { + "columns": 7, + "rows": 5 + } + }, + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
timestampStateOffsetSaturationCoefficientSWA (Measured)Offset Angle
03.169952Waiting010-1000.0549330.0
13.183891Waiting010-1000.0549330.0
23.199071Waiting010-1000.0549330.0
33.215024Waiting010-1000.0549330.0
43.230028Waiting010-1000.0549330.0
\n", + "
" + ], + "text/plain": [ + " timestamp State Offset Saturation Coefficient SWA (Measured) \\\n", + "0 3.169952 Waiting 0 10 -100 0.054933 \n", + "1 3.183891 Waiting 0 10 -100 0.054933 \n", + "2 3.199071 Waiting 0 10 -100 0.054933 \n", + "3 3.215024 Waiting 0 10 -100 0.054933 \n", + "4 3.230028 Waiting 0 10 -100 0.054933 \n", + "\n", + " Offset Angle \n", + "0 0.0 \n", + "1 0.0 \n", + "2 0.0 \n", + "3 0.0 \n", + "4 0.0 " + ] + }, + "execution_count": 53, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# wheel state\n", + "import pandas as pd\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from pprint import pprint\n", + "\n", + "plt.style.use('default')\n", + "\n", + "df = pd.read_excel('../data/wheel_logs/spin_test_state_new.xlsx')\n", + "# df[\"timestamp\"] = df[\"timestamp\"] - df[\"timestamp\"].iloc[0]\n", + "# df = df[df['Offset'] != 0]\n", + "df[\"Offset Angle\"] = df[\"Offset\"] * 450 / 100\n", + "df.head()" + ] + }, + { + "cell_type": "code", + "execution_count": 55, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAtAAAAGSCAYAAADKL/ZmAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMywgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/NK7nSAAAACXBIWXMAAA9hAAAPYQGoP6dpAACMqklEQVR4nOzdd1gUV9sG8HvpIE0RBBQBK4oFu7EhKFgjiliivvZO7N2o2EtiI3ZNoolGY2Is0djQiL2LRCN2UUDUWBEL9Xx/zLcbll0QFBhg7991cbE7c3b2mbO7s8+eOXOOQgghQEREREREWaIndwBERERERAUJE2giIiIiomxgAk1ERERElA1MoImIiIiIsoEJNBERERFRNjCBJiIiIiLKBibQRERERETZwASaiIiIiCgbmEATEREREWVDniTQjx49Qq9evVCqVCno6+tDoVDg5cuXAIC4uDgMHz4cLi4uMDAwgEKhwOXLl/MirDyjC/sol+nTp0OhUCA0NFTuUIioEFi/fj0UCgXOnTuXo9tNSkpCUFAQypcvD2NjYygUCuzcuVO1/ttvv0XlypVhamoKhUKBpUuX5ujzEwHAwYMH0aBBA1hbW0OhUKB9+/ZyhySb7du3Q6FQ4PDhwx/1+Gwn0AqF4oN/6ZOZ3r17Y+PGjfD09MSUKVMQFBQEExMTAMD48eOxbNkyVK1aFZMmTUJQUBDs7e0/ameyw8XFBS4uLrn+PMDH72NISAg6dOgAR0dHGBkZoWjRoqhQoQI6deqEb7/9Fp86C3vTpk2hUCg+aRu5bcOGDVAoFNiwYYPcoRQY79+/x8KFC1GvXj1YWVnByMgIDg4OqFWrFr788kscPXpUVXbYsGFQKBRYtWqV1m21aNECCoUCnp6eWtcrk42+fftqrDt58qTqmLB27dqP2hflezTtn7m5OTw8PDBjxgzEx8d/1Hbp00RGRmq8LgYGBrCzs0PLli2xa9euHHmevP6BHB8fj8mTJ+Pzzz9H3bp1tZa5efMmAgMD4ebmBnNzcxQpUgQVK1bE0KFDcePGjQy3vWjRIsycOROOjo4YO3YsgoKC4ObmBgD45ZdfMGLECJiYmGDkyJEICgpC/fr1c2UflUJDQ6FQKDB9+vRce45jx47hf//7H6pUqQIbGxuYmJjA1dUV7dq1+2DScvv2bQwYMACurq4wMTFB8eLFUb9+fSxatEhr+ejoaPTt2xeOjo4wNjaGi4sLRo4ciRcvXmgt/+TJE3Tv3h02NjZwcXHBnDlzkJKS8sn7rJSamopt27ahY8eOcHJygomJCYoUKYJKlSph4MCBOHnyZI49V1ZFRkbCz88P9+7dQ9++fREUFISuXbvm6HOcOHECfn5+cHFxgYmJCUqXLo3WrVtj//79GT7m2rVr6Ny5M+zs7GBiYoKKFSsiKCgI79690yibmJiIKVOmwNXVFVZWVvDy8sKlS5e0bvfQoUNQKBTYs2eP1vUdOnRAzZo1MXr0aKSmpmZ/Z0U2ARAARFBQUIZ/9+7dU5VPSEgQenp6wsfHR+v2SpYsKSpUqJDdMD6Zs7OzcHZ2zpPn+ph9nDNnjgAgDAwMRNu2bcWYMWPE+PHjRceOHYWtra0AIJKSkj4pLk9PT/ERb4E8tX79egFArF+/Xuv6f//9V0RERIg3b97kbWD51OvXr0XNmjUFAGFvby/69OkjJk2aJIYNGyaaNGkiDA0NRffu3VXld+zYIQCIgIAAjW0lJCQIMzMzoVAohJGRkXj79q1Gme7duwsA4ueff9ZY17NnTwFAKBQKUatWrY/aH+V7tFevXiIoKEhMmzZN9O/fXxQvXlwAEDVr1hQJCQkftW36ePfu3RMAhJWVleq4P3HiRPH5558LhUIhAIhvvvnmk58nKChIABBHjhz59KCzQHncPXnypNb1wcHBQl9fXygUCtG0aVMxZswYMXbsWOHl5SUUCoXQ19cXwcHBWh/bsGFDYW5urvX9qvwcxcTE5Oj+ZObIkSOq7/LcEhQUJBwdHUWHDh3EsGHDxMSJE0W3bt2Eubm5ACCmTJmi9XG///67MDY2Fubm5qJr165i0qRJYujQoaJZs2aiQYMGGuVv374t7OzsBADh5+cnJkyYILy8vAQAUbFiRfH06VO18qmpqaJhw4aiePHiYsSIEaJnz57C0NAwx+oiNjZWNGzYUAAQFhYWwt/fX4wbN06MHTtW+Pn5qfZ/2bJlOfJ8WbVu3boMj9c5YeXKlQKAKFKkiOjRo4eYOHGi6NGjhzAzMxMAxOzZszUec+bMGWFmZiYMDQ3FF198IcaPHy9q164tAIiGDRuK9+/fq5UfNWqUACA6duwoRowYIYoVKyYsLS3Fw4cP1cq9fv1auLi4qH3fabN169aPrpOPTqCz6v79+6ovQG0UCoXw9PTMbhifLC8T6OzuY2RkpNDX1xeWlpbi77//1lifkpIi9u/fL1JTUz8prsKQQJO6WbNmCQDC19dX6xf18+fP1ZKDFy9eCD09PVG8eHGN99PRo0cFANGpUycBQBw8eFBje46OjgKAiI2NVVv+4sULYWpqKsqXLy86duwoAIhLly5le3+U79H0CdTTp09Vz71hw4Zsb5c+jTKB1nYM3bJliwAgzMzMPvmHbV4m0MnJycLJySnDxo4ff/xRABDFihUTR48e1Vh/7NgxUaxYMQFA/PTTTxrrXV1dM/zOUSZ7eSkvEuh3795pXR4dHS3s7OyEnp6eRuJz5coVYWxsLGrUqKFxXBFCiMTERI1lvr6+AoD49ttv1ZYrk61BgwapLb9x44YAoPb9GhwcLEqWLJnlfcvImzdvRPXq1QUA0bVrV/H8+XONMq9evRJTp07VmlDmphkzZuTa5ykxMVFYWVkJExMTcf36dbV1165dE8bGxsLU1FQtIU5OThaVKlUSAMSuXbtUy1NSUlTfG/PmzVMtT01NFWZmZqJPnz6qZaGhoQKAWLBggdpzBgYGihIlSmj8eErv3bt3wtraWjRs2DDb+5yrCbSzs7OqfNq/Xr16qb4Y0/+lTzT3798vWrVqJWxsbISRkZEoU6aMGDt2rHjx4oXW54yKihLDhg0T5cqVEyYmJqJo0aKiTp06YubMmUKI/w4aGcWVFQ8fPhRDhw4Vzs7OwtDQUBQvXlx06NBBXLhwQa1cVvcxPeUvIj8/vyzFo7R+/Xrh7+8vXF1dhYmJibCwsBANGjQQGzduVCun/PL7UGyZxdqrVy8BQO1sg3K7vXr1Ejdu3BCdO3cWtra2QqFQqD6wFy5cEMOHDxfVqlUTRYsWFcbGxqJcuXJi9OjRGgeajOov7fNm9gV76NAh0aJFC1G0aFFhZGQkypcvLyZMmCBevnypUVb5XElJSWLOnDmiXLlywsjISJQqVUqMHz8+262cWX2PCKH+I+Gvv/4Snp6ewtzcXFhYWIjWrVuLa9euZfl5W7VqJQCIHTt2ZPkxyl/7ly9fVluurNurV68KPT09MXHiRLX1ERERAoBwd3fX2OayZcsEADFnzhyxe/duAUAMHjw4yzEpZZRACyHE0KFDBQARGBiosS4qKkoEBgYKV1dXYWRkJIoVKyY+//xzce7cOY2ycXFxYubMmcLd3V1YWFgIc3NzUaZMGdG5c2e11yvt+zsiIkL4+fmJokWLCjMzM9GwYUNx4MABrfvw/v17MW/ePFGlShVhamoqLCwsRKNGjcTWrVs1yqZ9jnv37okuXboIGxsbYWxsLGrVqiV2796t8ZiEhAQRHBwsatSoIaytrYWpqalwdnYW7dq1EyEhIRrlIyIiRK9evUSpUqWEoaGhsLOzE1988YXGl15mMkugU1NTRZEiRQQAcf78ebV1f/31lxgwYICoVKmSsLCwECYmJsLd3V1Mnz5dI9nK6Psj/ffPmzdvxNy5c0X16tWFmZmZKFKkiKhfv77YvHlzlvdHCCH27duXYatoXFycKFq0qAAg9u/f/8FtFCtWTMTFxQkh/jtWpv9zdnZWfcYy28djx46Jtm3bipIlSwojIyNRokQJUa9ePTF9+nSN589qXWQUU1629rdv314AECdOnFBbrjyLkdXj3u3btwUA4eLiIlJSUtTWxcXFiSJFiggzMzMRHx+vWn7t2jUBQPzzzz+qZStWrBD29vafsEeS2bNnq1pP08eTXvrW1ZcvX4qJEyeKChUqCGNjY2FtbS18fX21fo6VspIjZZb35NTr/ejRIwFAVKtWTev6qlWrCgBqCe3hw4cFANGkSRON8nfu3FF9TpSNO48fPxYAxKpVq1Tl3r59KwCIoUOHqpYdO3ZMKBQK8dtvv2Up9t69ewsAIiIiIkvllQyQi0aOHInIyEgEBwejevXqqs7qHh4eePnyJZo2bYoZM2bA2dkZvXv3BgC1fskzZszA9OnTUaxYMbRt2xZ2dnb4+++/sXDhQuzduxenT5+GpaWlqvyFCxfQokULPH/+HE2aNIG/vz/evn2La9euYfr06Zg6dSpcXFwQFBSkukBj5MiRqsd7eHh8cJ/u3buHRo0a4eHDh/D29sYXX3yBqKgo/Pbbb/jzzz/x+++/o23btgCkvt8f2kdtbGxsAAB3795FSkoK9PX1PxgXAAwZMgTu7u5o0qQJHBwc8OzZM+zduxf/+9//cOPGDcyaNQsAYG1tjaCgIGzYsAH3799HUFCQahs50S/8zp07qFevHipUqIDu3bvj3bt3qtdp3bp12LFjBzw9PdG8eXOkpqbi4sWLWLx4Mfbt24ezZ8/CwsICgFR/1tbW2LVrF/z8/NReH2tr60xjWLNmDYYMGYIiRYqgU6dOsLOzQ2hoKBYsWIDdu3fj5MmTWrfRrVs3HD9+HK1atYKlpSX27t2Lr7/+Gk+ePMH69euztP/ZeY+ktWfPHuzatQutWrXC4MGDce3aNezduxfnz5/HtWvXULx48Q8+t/K9c/PmzSzFCgDe3t64cOECDh8+jOrVq6uWHz58GBUqVIC7uztq1Kih0WdReb9Zs2Ya21y3bh309PTQs2dP2Nvbw97eHps3b8bChQtRpEiRLMeWFYaGhmr3L126BF9fXzx//hwtWrSAv78/nj59ip07d6JRo0bYsWMHWrduDQAQQqBly5Y4deoUPvvsM/Tv3x8GBgaIjo7GkSNH0LhxY9SqVUtt+/fu3cNnn32GqlWrYtCgQYiNjcXWrVvRqlUrbN68GV26dFGVTUxMRIsWLXD06FG4ubkhMDAQb9++xbZt29ClSxdcvnwZc+fO1din+/fvo27duihTpgz+97//4fnz59i6dSv8/Pxw6NAheHl5qcr27t0bW7ZsQZUqVdCzZ0+Ympri4cOHOHHiBPbv34/mzZuryu7fvx/+/v5ISkrC559/jnLlyiE6Ohrbt2/Hn3/+iSNHjqBmzZo58roAmq/NggULcP36dTRo0ABt2rTB+/fvcfLkSUyfPh2hoaE4dOiQ6ng3cuRI7Ny5E0ePHkWvXr20HptevnwJb29vhIWFoWbNmujbty9SU1Nx4MABdOvWDf/88w9mz56dpVgPHToEAGjUqJHGum3btuHFixeoW7cuWrRokeE2WrZsiTp16uD8+fPYtm0b+vTpg/bt28PFxUXjO8fa2lp1TNN2LAak16tNmzawtLREu3btULJkSTx//hwRERFYuXKlWvns1IXyu/jHH3+Ep6cnmjZtqtpOXlwb9OTJE5w9exbGxsaoWLGianlcXBz+/PNPVK9eHZUqVcK5c+dw4sQJpKSkoFKlSvD19YWRkZHato4cOQIA8PX1hZ6e+mVdFhYWaNiwIQ4ePIgzZ86ojlUVK1ZErVq1VMfnV69eYfPmzWr5wMdSXu8xdepUjXjSMzY2Vt1++fIlGjZsiGvXrqFOnToYOXIknj59il9//RW+vr5YtWoVBg0apPb4rOZIyrwnNDRU4/OUU6+3nZ0dbG1tcfPmTdy6dQvly5dXrVMu8/DwUH1HAcBff/0FQPrcpFemTBlUqFABN2/exN27d1G2bFkUL14cpqamuHjxoqrchQsXAADOzs4AgHfv3qFfv37w9/dHQEBAlmJv2LAhNmzYgEOHDqmuS8iSbKXb4sN9oNM2twuh3qKS0fa0tXL+9ddfAoD47LPPNFqblS12I0eOVC1LSEgQLi4uAtDelyUqKkrt/sd24VCeKkp/6uXkyZNCX19fFCtWTLx+/VptXUb7mJH4+HhV60vjxo3F999/L65evSqSk5Mzfdzt27c1liUkJAhvb29hYGAgoqOj1dZ9qAtHZnFn1gINQEyaNEnr4yIjI7Xux3fffScAiPnz56st/1AXDm0t0JGRkcLIyEhYWFho/KIcMmSIACAGDBigtlxZFzVr1hTPnj1TLY+Pjxdly5YVenp6Wk8napPd94hyH/X19cWhQ4fUHjNx4kStp6cyomztNTIyEkOGDBF79uzROEWa3oEDBwQA0aZNG9WyN2/eCENDQ9Wpz7Fjxwp9fX211nt/f3+BdKfehBDi9OnTApC6kSiNGTNGABDfffddlvZDKaMW6CdPnggHBwcBQGzbtk21PCkpSZQtW1YYGxuL0NBQtcfExMQIR0dHYW9vr2r5+fvvvwUA0b59e43nTklJUTsrkvb9PXbsWLWy58+fFwYGBsLa2lq8evVKtXzu3LkCgGjVqpXaNQuPHz9WfcbTdqlJ+xzpWxj379+v2pbSy5cvVX3MtX2u0rb2PH/+XFhbWwsbGxu1ljchpNPmRYoUETVq1NDYhjaZtUBv3LhRABC2trYarcp37tzR2vVsypQpAoD45Zdf1JZ/qAuH8jiU/vPx7t070aJFC6FQKERYWFiW9qlevXoaLWRKffv2FQDE5MmTP7idyZMnCwCiX79+assz+87J6Fis/IylPzskhHT9R1rZrYsPdeF48eJFptc6afvLqK7Pnz8vgoKCxFdffSV69eolihUrJvT19cXKlSvVyim/99u3b6/qOpb2r3Tp0hpnkcaOHSsAiIULF2p97sDAQAFA47mio6NFQECAsLa2FqVKlRJTp07V2j0kOx48eCAA6dqljLqvZGTgwIECgBg4cKDaZ+TmzZvC0tJSGBkZqX3fZjdHEiLzz9ORI0ey/Xqn9+uvv6q+e3v27CkmTpwo/ve//wlzc3NRq1YtcevWLbXyAQEBGsfwtNq0aSMAiL1796qWjRgxQigUCtGpUycxcuRIYWNjIywtLVX5zZgxY0SxYsXEo0ePtG5Tm8uXLwtA6q6YHR+dQGf0Z2VlpVb+YxNo5emdq1evan2ch4eHsLW1Vd3ftm2bACDatWuXpf34mAQ6KipK9SHW9kHr0aOHACB+/PFHteXZTaCFECI8PFx4eHio1a2pqalo0qSJWLFihcapn8z8/vvvWuPKrQS6RIkS2YpPCOm0r6WlpfDy8lJb/jEJtPIUmrYk/vnz56pTx2ljVNaFtlNl06ZNEwC0nj5P72PeI8p91Haxw927dwUgXTCRVcHBwcLKykrtvWNvby+6deumte/mmzdvhJGRkbC0tFQlYcpkTdnN4M8//1RLllNTU1Vfgum7xCiTjbSnja9cuSIAiLp162Z5P4TI+CJCGxsbAUB07txZ7TTpzp07tSa4SkuXLhUAxJ9//imE+C+B/uKLLz4YS9oL55Sn59NSfibS9skuV66cUCgUWk8NKn80pu3PlzYx1ZYQly5dWtjY2Kjuv3r1SgAQDRo0+OA1Ecp9X758udb1I0eOFAA0kmttMrqIsG3btqqLTrdv3/7B7Sg9e/ZMoy6EyPwL/+nTp0JfX1/Url1b6zaVX4rjxo3LUgwODg7C0NBQ6zpl16i0p44zsmrVKo0fOkJ8WgJ948aNTJ/zY+riQwl0Zl39MvrL6DitrBPln4WFhdZ+4r/88ouqMaFYsWJi8+bN4vnz5yIyMlKMGzdOABDFixdX+/EwYMAAAUCsW7dO63Mrf9DMnTs3g9rLOWfPnlV9B2aH8oJtc3NztQYcJeUPzBkzZqiWZTdHEiLzz1Nm3Yky+tPmxIkTwsnJSa1ciRIlxPLlyzW6tPj4+GT4vSuEEN26ddP4Lnn//r2YOHGicHZ2FhYWFqJJkyaqH1Vnz54V+vr6YuPGjSIlJUUEBQUJe3t7oa+vL2rWrKnRXUhJ2f2kXr16Wtdn5KO7cIhPHELtQ06fPg1DQ0P89ttv+O233zTWJyYm4t9//8WzZ89gY2ODM2fOAABatWqVazGFhYUBABo3bqxxahKQToVv2rQJYWFh6Nmz5yc9V7Vq1RAWFoYLFy7gyJEjuHTpEk6fPo1jx47h2LFjWLt2LY4cOYKiRYuqHvPgwQMsWLAAhw8fxoMHDzSGgImJifmkmLKqevXqaqem0kpKSsKaNWvwyy+/4Nq1a3j16pXa8DE5EaNySBtvb2+NdUWLFkWNGjVw7NgxXL9+Xa3LAgDUrl1b4zFOTk4AkOFwSGl9ynvkU59bafjw4ejfvz9CQkJw6tQphIWF4dSpU9i8eTM2b96MqVOnYubMmaryZmZmqF+/Po4dO4bz58+jfv36+Ouvv6BQKFSndhs3bgwDAwP89ddfaNeuHS5fvoznz5+rhspTiouLw9atW2FtbY0OHTqollepUgW1atXCuXPn8Pfff6NatWpZ3h9AOtWcXp8+ffDDDz+oLTt9+jQAqQuEtuG5bt26BQCIiIhA69atUblyZXh4eGDLli24f/8+/Pz80KhRI9SuXVvjVLFSzZo1Vd2M0mratCl+/PFHhIWFoVevXnj9+jVu376NkiVLaj0tqHx/Kt8zaXl4eGjtuuXk5KTaRwCwtLTE559/jt27d8PDwwMdO3ZE48aNUa9ePZiZmWmtm/DwcK11o+z2ExERgcqVK2vd9/RevXqFGTNmqC0zNjbGrl27tHZ1ePPmDYKDg7Fjxw7cvHkTr1+/Vvsuyc7n//z580hJSclwKLakpCTV/mTFs2fP1I6n+UH37t2xfft21KtXD126dIGXlxcaNmyIUqVKqZXL6boApFP7OfU9P3jwYAwePBjv37/HvXv3sHr1avTs2RMnT57E6tWrVeWU3wUpKSlYsWKFaoi1okWL4uuvv8adO3ewfft2rFu3DpMmTcqR2PKDGzdu4O3bt2jYsCGKFSumsd7b2xuzZ89WO1ZkN0f6kOnTp3/ykIabNm3CgAED4O/vj6lTp8LZ2Rn379/HrFmzVEOo/vrrr5/0HMbGxpg3bx7mzZuntjwxMRF9+vRBy5Yt0aNHDyxduhQzZsxAUFAQGjZsiDlz5qBly5a4ffs2SpQoofZYZZ0/ffo0W7Hkah/oT/Hs2TMkJydrHJzTi4+Ph42NjWpilpIlS+ZaTK9evQIAODg4aF2vXK6MJSfUrl1bLbE6d+4cevXqhfDwcMyYMUPVr+7u3buoW7cuXrx4gcaNG8PX1xdWVlbQ19dHZGQkfvzxRyQkJORYXJnJbIzrLl26YMeOHShTpgz8/Pxgb2+vSraXLl2aIzF+yuukrV+0gYH0McnKGKFyPndaZmZm8PPzg5+fHwDp4LJu3TqMGDECs2bNgr+/v1qf8mbNmuHYsWM4fPgw6tevj8OHD8Pd3R12dnYApL6ENWvWVPV7Vv5P278WAH7++We8efMGgwYNUo31rtS7d29cvHgRa9euxfLly7O1P0eOHEHTpk2RlJSEiIgIjBo1CuvXr0eZMmUwZcoUVblnz54BgNYvlLSU40fr6+vjr7/+wsyZM7Ft2zZMmDBBtb+9evXCvHnzYG5urvbY9AdfJeX7XvkeyOn3AiC9H9KPV7p161YsWLAAmzdvVvWJNTExQUBAABYuXKiKV1k369at07ptpeyMre3s7IzIyEgA0o+nkJAQ9O/fH507d8bp06fVEvGkpCR4e3vj3LlzqFKlCrp06QJbW1vVD80ZM2Zk6/Ov3J/z58/j/Pnzn7w/pqameP/+vdZ1ytc2Kirqg9tRlnF0dMzS82bG398fe/bswaJFi/DDDz9gzZo1AIBatWph3rx58PHxAZDzdZFbTExMUKlSJQQHByMhIQFr1qxB8+bNVX1Vle97hUKhOnal1aFDB2zfvl1tkhvlD3jl5y095fIPXTeTE5Sf6WfPnuH9+/cax8CMfMyxIrs5Um67efMm+vbti2rVqmHjxo2q/t9ubm7YuHEjbty4gd9++w2hoaGqhpmcfO1mzpyJmJgYHDx4EADwzTffoFmzZqofBRUrVoSLiwtWrFih1oAEQNXYaGpqmq19zrcJtJWVFVJTU/H8+fMslVdWcG62sipf7EePHmldHxsbq1YuN9StWxfLly9H8+bNVR3wAWDx4sV49uwZ1q9fr7pYUWnLli1aW/A+RKFQIDk5Weu6zH4kZDQ5y4ULF7Bjxw40b94c+/btUyWHgNTy8PXXX2c7Rm3Svk7u7u4a63PzdcoP7xFtjIyMEBgYiDNnzmDTpk3466+/1BJob29vBAUF4a+//kJgYCDCwsIQGBiotg0vLy/VBZXK9176CwiVydmaNWtUX/bp/fzzz/jmm2+yfbACpIvSqlWrht27d6Ny5coICgpCmzZtUKNGDQD/1euuXbvQrl27LG2zaNGiWLJkCZYsWYLbt2/j6NGjWLNmDZYvX46XL19i48aNauUfP36sdTvK11wZQ169F0xNTVWtR1FRUTh27Bg2bNiATZs2ITIyEsePH1d7nvDw8GyfAcgKS0tLdOzYESYmJmjbti169uyJ8+fPq44Hu3btwrlz59C7d2+NC3JjY2M/mAikp9yfUaNGYfHixZ8cv52dHW7duoWkpCSNs0eNGjXC+vXrcejQIcyZMyfT7SgvRmzYsOEnxwQAbdq0QZs2bfDmzRucPXsWe/bswapVq9C2bVuEhYWhcuXKOV4XgHSMz+5siO3bt8/SxfiAdLZ4zZo1CA0NVSXQygsKTUxMtB4flGcI0p5dVT4mowunlWedKlSokLWd+AROTk4oXbo0Hjx4gGPHjsHX1zdLj/uYY0V2c6QPCQ0NzfaERWlbrA8ePIikpCR4enpqXDypp6eHJk2a4OLFi7h48aIqgc6p1+7y5ctYsGABVq1ahZIlSyIuLg4PHz5E9+7dVWVKly6N4sWL459//tF4vPIHqLLBKKvybQJdv359/Pnnn/jnn3+0JkHaygPAvn37MHjw4A+W19fXR2JiYrZiUn5JnzhxAsnJyWoJIPDf1cA5eRW7NsrTx2lPr92+fRsA0LFjR43yaWeeS0t5ijijkT6KFi2qtcUlJSXlo6YiV8bYrl07jbo7d+6c1lmH0saYVTVq1MD27dsRGhqqkeC9fPkSly9fVrWE5LT88h7JiLb3DgDUq1cPRYoUwalTp7B//36kpqZqdIHx8vLCggULcPDgQRw/fhympqZo0KCBav2FCxcQFhYGR0fHDLtSnT9/Hn///Td+/fVX9OrV66P3w8zMDAsWLEDXrl0xfvx4hISEAPjvOHD8+PEsJ9BplStXDuXKlUO3bt1gZ2endUa9S5cu4fXr1xrdOJRfPsr3gIWFBcqWLYu7d+9qXJUO5M57wcnJCd27d8cXX3yBihUr4sSJE6pTuPXr18fvv/+O48eP50oCrdSmTRu0bNkS+/fvx+bNm1VfYsrPv7+/v8ZjsnKMSq9u3brQ09NT/UD4VNWqVcOtW7dw48YNVKlSRW1dQEAAxowZg3PnziEkJETV8pteSEgIzp07h2LFimV5BICsKlKkCLy9veHt7Y2iRYti2rRp2LdvHypXrvxRdfGhY+vLly+z/aPGxcUlywm0srEr7TGyTJkyKFOmDO7evYs7d+6gbNmyao+5evUqAMDV1VW1TDkizcGDB5GamqqWvL1+/RonT55UdVPLCwMHDsSUKVMwe/ZsNG/ePNOROBISElQjkZiZmSE8PBwvX77UaHHVdqzIbo70IaGhodl+vdMm0MqzR//++6/WssrlabvGeXt7Y86cOdi/f79Gl5y7d+/i5s2bcHZ2RpkyZTKMITk5GX369EHTpk3Rv39/tXXpz2hldIbp+vXrALI2EpuabPWYFtmfSOVjLyI8dOiQwP9fYaptdqb4+Hhx+vRp1f20o3BoG/8z/SgcderUEcbGxlpnV8uMstN7+lm2zpw5I/T19UXRokU1LjDKaB8zcvbsWbF+/XqtsSUmJqouLEk77uGgQYMEAPHHH3+old+/f7/Q19fXerGI8irnu3fvao2jZcuWAoDG+LbTp09XvQ8yGgdaG+XoDP7+/mrLHz9+rJo9L/1FNsqL16ZNm6Z1m9ouirh3754wNDQUVlZWGlf9fvnllwKA6N+/v9ryzC6ozO5kLtl9j3xo+9l5/6xatUrtc5FWRESEagY/beMhK1/vqlWrCj09PY1xuePj44WhoaFqPM/mzZurrVdezJPZiCHKz7W22cS0yWwc6NTUVFUsyvWJiYmibNmywtTUVHWhYHqnTp1STfBx9+5dcefOHY0yMTExqjGSlbIyCoeVlZXaKBzKme38/PzULgr8999/Vcer48ePazxHRp+h9O/TJ0+eaJ1sKS4uTtjb2wsDAwPVe+3p06fC2tpa2NrairNnz2o8JiUlJctjwmY2CocQUn0AEGXLllWNPqKcYGX06NFqZe/cuSNKly6t9X2+YsUKAUD88MMPWp/nf//7nwAgZs6cqfWiy9u3b2d4fEtPOXZ5Rhejff/996qL2LRdjHTy5EnV5yv9BdtCfNxFhEePHtU646y2kSWyWxf//POPACB69uypNaacoO19poylZMmSAtCcoGnx4sUCkC6cTrvvUVFRokSJEgKAxgg72Z1IJTsyOwZpk3Yile7du2uds+L169di+vTpaiM1KY+fX375pVrZ27dvCysrK2FoaKj2+mU3RxIidycmUl5AaWpqKsLDw9XWhYWFCRMTE6FQKNQuesxsIhXlCB3pR3ZLb9asWcLc3FwtFxHivxmgle8h5YQrU6dO1dhGdgYKSCtXpvJOO5TNxybQQggxf/58oVAohJmZmQgICBDjxo0TQ4YMEa1btxZFihQRLVq0UCt//vx51WD3np6eYsKECWLEiBHC19dX6Ovrq5VVDg/WpEkTMWXKFDFr1iyN5FObO3fuCHt7ewFA+Pj4iEmTJokePXoIY2NjYWhoKHbu3JmtfdRGOb2ych9HjRolJk2aJHr37q167nLlyqkN0xIeHi6MjIyEsbGx6N69uxg3bpxo1aqVUCgUokuXLloT6NWrVwsAwsPDQ0yePFnMmjVL7croQ4cOCYVCIUxMTESvXr3EqFGjRL169YSdnZ1o2rRpthPo5ORk1fSmn332mRg3bpzo2bOnsLW1FY0aNRKOjo4aXzDPnz8XZmZmwtLSUgQGBopZs2aJWbNmqUZ+yOiAoPzitbCwEP369RMTJ04Un332mQAg3NzcNK50zskEOrvvkZxMoP38/AQA1RSmEydOFKNGjRJt27YVhoaGAoAYPny41sd+8803qs93zZo1tZZp0KCBqkzaA9vr16+Fubm5MDQ0zHT4oNTUVFGmTBmBTK4eT+tDX17Kz8pnn32mWhYeHq6q/wYNGoihQ4eKsWPHii5duqieWzkk4Y4dO4RCoRB169YVvXr1EpMmTRL9+/cXtra2AoBYtGiRarvK93eTJk2EtbW1aNy4sZg4caLo1auXMDExEXp6ehrDsCUkJIhGjRoJQJpwZty4cSIwMFA17fD48ePVymc3gQ4LC1P96FG+3kOHDlUlpOlf60OHDgkLCwuhUChE8+bNxYgRI8TIkSNFx44dhaOjozA2Nv7ga5I2zsxGMlK+F1evXi2EkL7Qy5Urp/pcjB8/XnTt2lWYm5urjlHp3+fXrl0Tenp6okSJEmL06NGqz7/Sq1evRP369QUAUb58edGnTx8xceJE0bNnT1GnTh0BQGzZsiVL+/TgwQOhr6+vdVp7pUWLFqmm8vby8hJjx44V48aNE97e3qqpvJcuXar1sR+TQFevXl0UL15c+Pn5iREjRqieS1n3aX/kZrcukpOTVZOz9OvXT8ycOVPMmjVLREZGZqm+ssLKykqUL19edO7cWYwZM0aMGDFCtG3bVhgYGAgAYtiwYRqPSUpKUiXE7u7uYvjw4aJPnz6q7/b0P8CE0JzKe+LEiarZHStUqPDB2egy07hxY40fuh+SdipvS0tL0bFjRzF+/Hgxbtw40aFDB2FpaSkA9RFxnj17Jtzc3AQgjQYxceJE0b9/f2FpaSkUCoVYsWKFxvNkN0fKzQRaCCH69OkjAGkY1S5duojx48eLzp07CyMjIwFoDqsnhOZU3hMmTMh0Ku+0/vnnH2FkZKR1SvTg4GABQNSvX1+MGDFCFC9eXJibm2v9fqpfv76wtrbO9sypOT6MXfpE4FMSaCGEOH78uOjUqZNqiKHixYuL6tWri1GjRmnMciWENHX4kCFDhIuLizA0NBTFihUTdevWFXPmzFErFx8fLwYPHixKliypaqHN6kyE0dHRYvDgwaJ06dLC0NBQ2NjYCD8/P62telnZx/Ti4uLE5s2bRe/evUXVqlWFjY2NquXys88+E/PmzdMYa1oIqQXEy8tLWFtbC3Nzc9GwYUOxY8eODIcrSk5OFpMmTRKurq6qA1r6OHft2iVq1aoljI2NRbFixUSXLl1EZGTkB2cizMizZ8/EkCFDhLOzszA2NhZlypQRkyZNEm/evMnwC2bfvn2ifv36qtnN0j5vZgeEAwcOCB8fH2FtbS2MjIxE2bJlxbhx47S2CORkAi1E9t4jOZlA37hxQyxcuFC0bNlSlC1bVpiZmQkjIyPh5OQkOnTokOkv7EuXLqnqd8yYMVrLfPXVV6oyafdl7dq1AoDo0KHDB2NUtspmlMinlZXWn1q1aglA/ezL48ePxYQJE4S7u7swNTUVRYoUEeXKlRMdO3YUGzduVLVKREVFiUmTJokGDRqIEiVKCCMjI1GyZEnRsmVLtbFHhVB/f1+7dk20a9dONfNfgwYNMpyh7t27d2LOnDnC3d1dmJiYqD6b2s6UZTeBfvHihZgxY4bw8vISjo6OwsjISNjb2wtPT0+xefNmrUPb3bt3TwQGBopy5coJY2NjYWFhISpWrCh69OiR5Rkss5JAX758WSgUClGyZEnVmLgPHjwQ3bp1E46OjsLExERUrlxZLFiwQCQlJWX4Pt+4caOoXr26MDExUb330kpISBDLli0Tn332mWq8XCcnJ+Ht7S2WLFmSreSpffv2wtjYWOv0y0oRERFi8ODBokKFCsLU1FQ1Zf3gwYMzncnsYxLorVu3iq5du4py5cqJIkWKCAsLC+Hu7i4mT54snjx5olE+u3Vx7tw54e3trUrScjq5Cg4OFm3atBGlS5cWpqamqngCAgIyndExISFBfP3116JKlSof/MwoPXjwQNXIZGhoKEqXLi1GjBiR6Wv5IcrhOl1cXLSeCchMSkqK+PXXX0WHDh1EyZIlVVNZV6xYUfTr109t/HelFy9eiPHjx6tmwrWyshLNmzfPcJZTIbKXI+V2Ap2amirWr18vPD09hbW1tSpv8fb2zvSH7D///CMCAgJUsymWL19eTJs2LdMeAsnJyaJevXqicePGWo9zqampYtasWaofiXXq1NF65kg5rfuIESOyvb8KIXJ5PDoiokIgMjISrq6u6NWrFzZs2CB3OJQLTp06hYYNG2Lx4sUYNWqU3OGQzP7++29Ur14dK1aswNChQ+UOh3LBmDFjsHz5ckRERGTa11qbzOeZJCIi0hENGjRAp06dsGDBArx9+1bucEhmR48eRYkSJdC3b1+5Q6FcEBsbi1WrVmHYsGHZTp4BJtBEREQqCxcuxODBg3Hv3j25QyGZDRs2DI8ePcryeM5UsERGRmLChAlqcwlkB7twEBFlAbtwEBGREhNoIiIiIqJsYBcOIiIiIqJsYAJNRERERJQN+XYqb8p9qampePjwISwsLKBQKOQOh4iIqMAQQuD169dwdHTMdMpuKpyYQOuwhw8fwsnJSe4wiIiICqyoqCiUKlVK7jAojzGB1mEWFhYApA+/paWlzNHILykpCQcPHoSvry8MDQ3lDkdnsN7lwXqXB+tdHrlR73FxcXByclJ9l5JuYQKtw5TdNiwtLZlAQzrAmpmZwdLSkl9seYj1Lg/WuzxY7/LIzXpnF0jdxE47RERERETZwASaiIiIiCgbmEATEREREWUDE2giIiIiomxgAk1ERERElA1MoImIiIiIsoHD2FGOSUkBjh8HYmMBBwegcWNAX1/uqIiIiIhyFhNoyhHbtwMjRgDR0f8tK1UKCA4G/P3li4uIiIgop7ELB32y7duBgAD15BkAYmKk5du3yxMXERERUW5gAk2fJCVFankWQnOdctnIkVI5IiIiosKACTR9kuPHNVue0xICiIqSyhEREREVBkyg6ZPExuZsOSIiIqL8jgk0fRIHh5wtR0RERJTfMYGmT9K4sTTahkKhfb1CATg5SeWIiIiICgMm0PRJ9PWloeqAjJPopUs5HjQREREVHkyg6ZP5+wPbtgElS2qua9mS40ATERFR4cIEmnKEvz8QGQkcOQJs3gwsXiwtP3wYePBA1tCIiIiIchRnIqQco68PNG363/3du6WEevZsYO1a2cIiIiIiylFsgaZcM2uW9P+HH4A7d+SNhYiIiCinMIGmXNOwodQHOiUFmDlT7miIiIiIcgYTaMpVylboTZuA69fljYWIiIgoJzCBzidiY2MxceJEeHl5wcLCAgqFAqGhoRmWP3XqFBo1agQzMzPY29tj+PDhiI+Pz7uAs6h2baB9eyA1FZg+Xe5oiIiIiD4dE+h84saNG1iwYAFiYmJQtWrVTMtevnwZzZo1w9u3b7F48WL0798fa9euRadOnfIo2uyZMUP6v3Ur8Pff8sZCRERE9Kk4Ckc+UatWLTx79gzFihXDtm3bMk2GJ0+ejKJFiyI0NBSWlpYAABcXFwwYMAAHDx6Er69vXoWdJdWqAV26SAn0tGnAzp1yR0RERET08dgCnU9YWFigWLFiHywXFxeHkJAQ9OjRQ5U8A0DPnj1hbm6OX3/9NTfD/GjTpwN6esCuXcCFC3JHQ0RERPTx2AJdwFy5cgXJycmoXbu22nIjIyN4eHggLCwsw8cmJCQgISFBdT8uLg4AkJSUhKSkpNwJ+P+VLQt066aPTZv0MGVKKnbvTsnV5/sYyjrI7bogdax3ebDe5cF6l0du1DtfQ93GBLqAiY2NBQA4ODhorHNwcMDx48czfOy8efMwQ9khOY2DBw/CzMws54LMQMOGZtiypRkOHNDDokUnUanS81x/zo8REhIidwg6ifUuD9a7PFjv8sjJen/79m2ObYsKHibQuSA1NRWJiYlZKmtsbAyFQpHlbb979071uPRMTExU67WZNGkSRo8erbofFxcHJycn+Pr6qnUHyU0XLgDffw8cONAQY8bkr1bopKQkhISEwMfHB4aGhnKHozNY7/JgvcuD9S6P3Kh35Vlc0k1MoHPBsWPH4OXllaWyERERcHNzy/K2TU1NAUCtK4bS+/fvVeu1MTY21pp4Gxoa5tmBfNo0YONGIDRUD8eP68HbO0+eNlvysj7oP6x3ebDe5cF6l0dO1jtfP93GBDoXuLm5Yf369Vkqq60rRlbKK7typBUbGwtHR8dsbS+vlS4NDBwILF8OTJ0KeHkB2WiAJyIiIpIdE+hcYG9vj969e+fKtqtUqQIDAwNcuHABnTt3Vi1PTEzE5cuX1ZblV5MnA999B5w6BezfD7RqJXdERERERFnHYewKGCsrKzRv3hybNm3C69evVcs3btyI+Pj4fDuZSloODsCXX0q3p04FhJA3HiIiIqLsYAt0PjJ79mwAwD///ANASopPnDgBAJgyZYqq3Jw5c9CgQQN4enpi4MCBiI6OxqJFi+Dr64uWLVvmfeAfYfx4YNUq4OJFaWzo9u3ljoiIiIgoa5hA5yNTp05Vu//DDz+obqdNoGvWrIlDhw5hwoQJGDVqFCwsLNCvXz/Mmzcvz2L9VLa2wMiRwJw5Uit0u3bSRCtERERE+R0T6HxEZKMvQ6NGjXDy5MlcjCb3jRkjXUx49Srw22/SdN9ERERE+R3b/Eg2RYtKSTQABAUBycnyxkNERESUFUygSVYjRgDFigE3bgCbN8sdDREREdGHMYEmWVlaAhMmSLenTweSkmQNh4iIiOiDmECT7AIDgRIlgHv3gCzOP0NEREQkGybQJLsiRYBJk6Tbs2YB79/LGw8RERFRZphAU74waBBQsiQQHQ2sWyd3NEREREQZYwJN+YKJCaAc6nruXODtW3njISIiIsoIE2jKN/r2BVxcgEePgJUr5Y6GiIiISDsm0JRvGBlJ40EDwPz5wOvX8sZDREREpA0TaMpXevQAKlQAnj0Dvv1W7miIiIiINDGBpnzFwEAaDxoAFi4EXr6UMxoiIiIiTUygKd/p0gVwd5eS58WL5Y6GiIiISB0TaMp39PSAmTOl20uWAE+fyhsPERERUVpMoClf6tABqFEDiI8Hvv5a7miIiIiI/sMEmvIlhUKalRAAli+XhrYjIiIiyg+YQFO+1bo1UL8+8O4dMG+e3NEQERERSZhAU76VthV69WogKkreeIiIiIgAJtCUzzVrBnh6AomJwJw5ckdDRERExASa8rm0rdDffw/cvStvPERERERMoCnfa9wY8PUFkpP/S6aJiIiI5MIEmgoEZeL800/AjRvyxkJERES6jQk0FQh16wKffw6kpgIzZsgdDREREekyJtBUYChnJ/zlF+DKFXljISIiIt3FBJoKDA8PoFMnQAggKEjuaIiIiEhXMYGmAmX6dGlkjh07gIsX5Y6GiIiIdBETaCpQKlcGuneXbk+bJm8sREREpJuYQFOBExQE6OsDe/cCp0/LHQ0RERHpGibQVOCUKwf07i3dnjpV1lCIiIhIBzGBpgJp6lTA0BA4fBgIDZU7GiIiItIlTKCpQHJ2BgYMkG5PnSqNzEFERESUF5hAU4H11VeAiQlw4gRw8KDc0RAREZGuYAJNBZajIzBkiHSbrdBERESUV5hAU4E2cSJgZgacPw/s3i13NERERKQLmEBTgWZnBwwfLt2eNg1ITZU3HiIiIir8mEBTgTduHGBpCYSHA7//Lnc0REREVNgxgaYCr1gxYPRo6XZQEJCSIm88REREVLgZyB2AXN6+fYuQkBCcPHkS165dw9OnT6FQKFC8eHFUqlQJDRs2RPPmzVGkSBG5Q6UsGDkSCA4GIiKALVuAHj3kjoiIiIgKK51rgb5y5Qp69+4Ne3t7dOjQAStWrMDt27ehUCgghMDNmzexfPlydOjQAfb29ujduzeuXLkid9j0AVZWwPjx0u3p04GkJFnDISIiokJMpxLoLl26oEaNGrh+/TqmT5+O8PBwxMXF4fr16zh9+jTOnDmDGzdu4PXr1wgPD8f06dNx48YN1KhRA1988YXc4dMHfPklYGsL3LkD/PST3NEQERFRYaVTCbSenh4uXLiAM2fOYPTo0ahatSr09fU1yunr66Nq1aoYM2YMTp8+jQsXLuR6bIcPH0bfvn1RoUIFmJmZoUyZMujfvz9iY2O1lj916hQaNWoEMzMz2NvbY/jw4YiPj8/1OPMzc3Ng0iTp9syZQEKCvPEQERFR4aRTCfSWLVvg4eGR7cd5eHhgy5YtOR9QGhMmTEBoaCg6dOiAb7/9Fl27dsWvv/6KGjVq4NGjR2plL1++jGbNmuHt27dYvHgx+vfvj7Vr16JTp065GmNBMHiwNMHKgwfAd9/JHQ0REREVRjp7EWF+s3jxYjRq1Ah6ev/9pmnZsiU8PT2xfPlyzJ49W7V88uTJKFq0KEJDQ2FpaQkAcHFxwYABA3Dw4EH4+vrmefz5hampNMV3YCAwZw7Qt6+0jIiIiCin6FQLdHqXL1/WaFk+cOAAmjRpgnr16iE4ODjPYmnSpIla8qxcVqxYMURERKiWxcXFISQkBD169FAlzwDQs2dPmJub49dff82zmPOrfv0AZ2cgNhZYtUruaIiIiKiw0ekW6PHjx8PMzEx1geC9e/fQoUMH2NjYwNHREaNHj4apqSkGDhwoS3zx8fGIj49H8eLFVcuuXLmC5ORk1K5dW62skZERPDw8EBYWluH2EhISkJCmY3BcXBwAICkpCUmFaNgKPT1g8mQFBg0ywPz5An36JMPc/MOPU9ZBYaqLgoD1Lg/WuzxY7/LIjXrna6jbdDqBDg8Px7hx41T3f/rpJ+jr6yMsLAzFixdHly5dsHr1atkS6KVLlyIxMRFdunRRLVNeVOjg4KBR3sHBAcePH89we/PmzcOMGTM0lh88eBBmZmY5EHH+YWOjgIODN2JjzTF8+C0EBNzK8mNDQkJyMTLKCOtdHqx3ebDe5ZGT9f727dsc2xYVPDqdQL969Qo2Njaq+3v37oWPj4+qxdfHxwf79u3L9nZTU1ORmJiYpbLGxsZQKBQay48dO4YZM2agc+fO8Pb2Vi1/9+6d6nHpmZiYqNZrM2nSJIxWTtkHqQXayckJvr6+at1BCov4eAV69wb+/LMSliwpDyurzMsnJSUhJCQEPj4+MDQ0zJMYifUuF9a7PFjv8siNeleexSXdpNMJtIODg6p/cWxsLC5evIg+ffqo1sfHx2v0S86KY8eOwcvLK0tlIyIi4Obmprbs+vXr6NChA6pUqYLv0g0lYfr/V8QlaBmj7f3796r12hgbG2tNvA0NDQvlgbxHD+Drr4Fr1xRYvtwQ06dn7XGFtT7yO9a7PFjv8mC9yyMn652vn27T6QTaz88Py5Ytw/v373H27FkYGxujQ4cOqvXh4eEoU6ZMtrfr5uaG9evXZ6ls+q4YUVFR8PX1hZWVFfbu3QsLCwut5bWNDx0bGwtHR8dsx1tY6esDM2YAnToBixcDw4YBaU44EBEREX0UnU6gZ8+ejX///RcbN26EtbU1NmzYgBIlSgCQTs1s27YNgYGB2d6ucgrw7Hr27Bl8fX2RkJCAw4cPa+3nXKVKFRgYGODChQvo3LmzanliYiIuX76stowAf3+genUgPBxYuBCYN0/uiIiIiKig0+kE2tzcHD///HOG66Kjo/Ps4ro3b96gdevWiImJwZEjR1C+fHmt5aysrNC8eXNs2rQJU6dOVbVQb9y4EfHx8ZxMJR09PWDWLKBdO+Dbb4GRI4H//41ERERE9FF0LoGuUqUK2rZtizZt2qBhw4YZ9nHW09OD1YeuOstB3bt3x7lz59C3b19ERESojf1sbm6O9u3bq+7PmTMHDRo0gKenJwYOHIjo6GgsWrQIvr6+aNmyZZ7FXFC0bQvUrQucOwfMnw8sWSJ3RERERFSQ6VwC3aJFC+zatQtff/01rK2t4ePjgzZt2qBVq1awtbWVLa7Lly8DAH744Qf88MMPauucnZ3VEuiaNWvi0KFDmDBhAkaNGgULCwv069cP89g/QSuFQmqFbtFCmlhl7FigZEm5oyIiIqKCSucS6EWLFmHRokW4d+8e9uzZg3379mHw4MFITExE7dq10bp1a7Rp0wa1atXK07giIyOzVb5Ro0Y4efJk7gRTCPn4AI0bA8ePS1N8r1wpd0RERERUUOnsVN6urq4YNmwY9u7di2fPnmHnzp2oWbMmfvjhB9SpUweOjo7o168ftm/fjtevX8sdLn0iZSs0AHz3HZDN3ytEREREKjqbQKdlamqKtm3bYuXKlYiMjMTff/+NkSNH4s6dO+jatSuKFy+ONWvWyB0mfSJPT6B5cyAp6b9kmoiIiCi7mEBrUaVKFYwfPx6hoaF4+vQpNm3a9FHjQVP+o0ycf/wRuJX12b2JiIiIVJhAf4ClpSU6deoEHx8fuUOhHFC/PtCmDZCSIk2yQkRERJRdOpdAJycnY+HChfDz88PYsWPx7NkzuUOiPDZzpvR/82bgn3/kjYWIiIgKHp1LoAcOHIiNGzeiX79+uH79Onx8fJCamip3WJSHataUZigUApg+Xe5oiIiIqKDRqQQ6KSkJmzdvRlBQENq1a4dFixYhPDwcf//9t9yhUR6bMUMamWPbNiAsTO5oiIiIqCDRqQTa0NAQ5ubmePDgAQAgKioKQghYW1vLGxjluSpVgK5dpdvTpskbCxERERUsOpVAA8DSpUsxbdo0dOzYEV27dsWwYcPg4uIid1gkg+nTAT09YM8e4OxZuaMhIiKigkLnEugePXrgypUr6NatG0JCQhAcHCx3SCSTChWAXr2k21OmAEePKnDsWEkcPapASoq8sREREVH+pXNTeQOAs7MznJ2d5Q6D8oGpU6UxoQ8dAg4dMgBQG4sXA6VKAcHB0sWGRERERGnpXAs0UVphYYC2QVhiYoCAAGD79ryPiYiIiPI3nUqg582bh/j4+Gw/Li4uDvPmzcuFiEhOKSnAiBHa1wkh/R85EuzOQURERGp0KoHevHkznJycMHToUISGhiIlk8woKSkJhw4dwsCBA1G6dGls2bIlDyOlvHD8OBAdnfF6IYCoKKkcERERkZJO9YH++++/sXnzZixcuBCrV6+GsbExqlSpAldXVxQtWhRCCLx48QL37t3D1atXkZSUhKpVq2L58uXo3r273OFTDouNzdlyREREpBt0KoFWKBTo3r07unfvjrCwMOzcuROnT5/GmTNnVFN629jYwM3NDRMmTICfnx9q1qwpc9SUWxwccrYcERER6QadSqDTqlGjBmrUqCF3GCSjxo2l0TZiYv7r85yek5NUjoiIiEhJp/pAE6Wlry8NVQdI03prM3KkVI6IiIhIiQk06TR/f2DbNqBkSfXlxsbS/+Bg4PHjvI+LiIiI8i8m0KTz/P2ByEggJCQZo0dfQEhIMqKigPLlgQcPgA4dgPfv5Y6SiIiI8gsm0ESQuml4ego0aRIDT08BW1tgzx7A2ho4fRro3z/jftJERESkW5hAE2WgQgWpe4e+PvDzzwDn0iEiIiKACTRRppo1A1askG5/9RWn9iYiIiIm0ACAmJgYbNmyBcHBwYj+/6npUlJS8Pz580xnKyTdMGgQMHy4dPt//wMuXZI3HiIiIpKXTifQQgiMHj0arq6u6N69O0aPHo2bN28CAOLj4+Hi4oJly5bJHCXlB4sWAS1bAm/fAu3aAQ8fyh0RERERyUWnE+hvvvkGwcHBGDt2LEJCQiDSXCVmZWUFf39//P777zJGSPmFgQHwyy9ApUrSxCt+flIyTURERLpHpxPodevWoWfPnpg7dy48PDw01lerVk3VIk1kZQXs3g3Y2AAXLgC9ewOpqXJHRURERHlNpxPoqKgoNGjQIMP1RYoUQVxcXB5GRPld2bLShYSGhsBvvwEzZsgdEREREeU1nU6g7ezsEBUVleH6ixcvonTp0nkYERUETZoAa9ZIt2fOBLZskTceIiIiyls6nUD7+/tj9erVuHv3rmqZQqEAABw8eBAbNmxAp06d5AqP8rE+fYBx4/67ffasvPEQERFR3tHpBHrGjBlwcHCAh4cHevbsCYVCgQULFqBRo0Zo1aoVqlWrhsmTJ8sdJuVT8+ZJI3IkJEgXFWZyMoOIiIgKEZ1OoK2srHDmzBmMHz8eMTExMDExwdGjR/Hy5UsEBQXh+PHjMDMzkztMyqf09YFNm4Bq1YDHj4HPPwfi4+WOioiIiHKbgdwByM3U1BRTpkzBlClT5A6FCiALC+CPP4C6dYHwcGmild9/B/R0+qcpERFR4abTX/Pe3t44fPhwhuuPHDkCb2/vPIyICiJnZ2DnTsDYWPr/1VdyR0RERES5SacT6NDQUDx+/DjD9U+ePMHRo0fzMCIqqD77DPj+e+n2/PnAjz/KGw8RERHlHp1OoIH/Rt3Q5vbt27CwsMjDaKgg6979v9bnAQOAEyfkjYeIiIhyh871gf7xxx/xY5rmwdmzZ2PdunUa5V6+fIm///4brVu3zsvwqICbORO4fl3qB92hA3D+PODiIndURERElJN0LoF++/Yt/v33X9X9169fQy/dFV8KhQJFihTB4MGDMW3atLwOkQowPT2p+8a9e8ClS0DbtsCpU4ClpdyRERERUU7RuQR6yJAhGDJkCADA1dUVwcHBaNeuncxRUWFSpIg0MkedOsA//wBffCHd19eXOzIiIiLKCTrdB/revXv5Jnk+duwY2rVrBycnJ5iYmMDe3h4tW7bEyZMntZY/deoUGjVqBDMzM9jb22P48OGI5yDE+UbJklLSbGoK7N3736yFREREVPDpXAt0Rl6/fo1Xr14hNTVVY13p0qVz/flv3rwJPT09DB48GPb29njx4gU2bdqEJk2a4M8//0TLli1VZS9fvoxmzZqhUqVKWLx4MaKjo7Fw4ULcunUL+/bty/VYKWtq15a6c3TuDCxZAlSqJF1cSERERAWbzifQq1atwuLFi3H37t0My6SkpOR6HP3790f//v3Vlg0dOhRlypTB0qVL1RLoyZMno2jRoggNDYXl/3eudXFxwYABA3Dw4EH4+vrmeryUNZ06SRcWTpsGDB0KlCsHeHnJHRURERF9Cp3uwrF69WoEBgaiXLlymD17NoQQGDlyJCZOnAh7e3tUr14d3ysH95WBmZkZbG1t8fLlS9WyuLg4hISEoEePHqrkGQB69uwJc3Nz/PrrrzJESpmZMkXqB52cDHTsCNy6JXdERERE9Cl0ugV62bJlaNGiBfbt24dnz57hq6++Qps2beDt7Y3x48ejdu3aePbsWZ7GFBcXh8TERDx9+hQ//fQTrl69ismTJ6vWX7lyBcnJyahdu7ba44yMjODh4YGwsLAMt52QkICEhAS15wKApKQkJCUl5fCeFDzKOsiNuli9GrhzRx/nzumhbVuBEyeSYW2d409TIOVmvVPGWO/yYL3LIzfqna+hbtPpBPrOnTsIDAwEABgaGgIAEhMTAQBWVlbo378/Vq5ciTFjxuRZTJ07d8aBAwcASEnxoEGDMHXqVNX62NhYAICDg4PGYx0cHHD8+PEMtz1v3jzMmDFDY/nBgwdhZmb2qaEXGiEhIbmy3SFDjHH3bhPcvGkGH58XmDbtDPT1Ra48V0GUW/VOmWO9y4P1Lo+crPe3b9/m2Lao4NHpBNrKygrJyckAAEtLS5iZmSEqKkq13sLCAo8ePcr2dlNTU1WJ+IcYGxurzYY4f/58jBkzBlFRUfjxxx+RmJioihEA3r17p3pceiYmJqr12kyaNAmjR49W3Y+Li4OTkxN8fX3VuoPoqqSkJISEhMDHx0f1gyqnVakCNG0qEB5uh0OH2iA4WPOiVV2TF/VOmljv8mC9yyM36l15Fpd0k04n0FWqVEF4eLjqfv369bFq1Sq0bt0aqampWLNmDSpUqJDt7R47dgxeWbxSLCIiAm5ubqr7Hh4eqts9evRAzZo10bt3b2zbtg0AYGpqCgBqXTGU3r9/r1qvjbGxsdbE29DQkAfyNHKzPmrXBn7+WZqlcNUqfbi76+P/T4LoPL4P5cF6lwfrXR45We98/XSbTifQPXr0wOrVq5GQkABjY2PMmDEDzZs3Vw1bZ2hoiN9//z3b23Vzc8P69euzVFZbVwwlIyMjtGvXDvPnz8e7d+9gamqqKq/sypFWbGwsHB0dsx0v5S0/P2D+fGDCBGDECKB8eYADpxARERUcOp1A9+nTB3369FHdb9iwIf755x/s3r0b+vr68PX1/agWaHt7e/Tu3TtHYnz37h2EEHj9+jVMTU1RpUoVGBgY4MKFC+jcubOqXGJiIi5fvqy2jPKvceOAa9f+Gyf6zBkgzYkIIiIiysd0ehg7bcqUKYMRI0bgyy+/RIUKFXDv3r08ed4nT55oLHv58iV+//13ODk5wc7ODoDUb7t58+bYtGkTXr9+rSq7ceNGxMfHo1OnTnkSL30ahQJYswZo1Ah49Qpo2xbI4wFfiIiI6CPpdAt0Zv7++2/Mnz8f27Zty/IFgZ+iVatWKFWqFOrVqwc7Ozs8ePAA69evx8OHD7F161a1snPmzEGDBg3g6emJgQMHIjo6GosWLYKvr6/ahCuUvxkbA9u3A3XrAnfuSGNEHzwIGBnJHRkRERFlRidboP/55x98+eWXaNWqFbp164YdO3ao1l26dAmtW7dGjRo1sH37dvTo0SNPYurbty+eP3+OJUuWYMiQIVi9ejVq1KiB0NBQBAQEqJWtWbMmDh06BFNTU4waNQpr165Fv379VBcaUsFhawvs2QNYWABHjwKBgYDgyHZERET5ms61QJ85cwbe3t54//69atnWrVuxePFiJCcnY8KECbCwsMC4ceMwYsSITC/yy0mBgYGqMamzolGjRjh58mQuRkR5xd0d2LpV6sbx3XdA5crAqFFyR0VEREQZ0bkW6JkzZ8LExAT79u1DfHw8rly5glq1amHatGmqcZIjIyMxf/78PEueiVq1AhYtkm6PGQP8+ae88RAREVHGdC6BPnv2LAIDA9GiRQuYmZnB3d0dixcvxuvXrzF8+HB8/fXXsLKykjtM0kEjRgADB0pdOLp2Ba5elTsiIiIi0kbnEuiXL19qDE2nvO/t7S1HSEQApJE5li8HmjYF4uOlLh1aBmchIiIimelcAi2EgL6+vtoy5X0TExM5QiJSMTQEfv8dKFcOuH9fmrFQy6STREREJCOdu4gQAPbu3YtHjx6p7r99+xYKhQK//fYbLl++rFZWoVBgFK/oojxUrJg0Mke9esCpU1K3jg0bpBZqIiIikp9OJtCbN2/G5s2bNZavWbNGYxkTaJJDxYrAtm1Ay5bATz8BlSoBEyfKHRUREREBOphA59XMgkSfqnlzYNkyYOhQYNIkKanu0EHuqIiIiEjnEmhnZ2e5QyDKsiFDgGvXpIsLe/QATpwAatSQOyoiIiLdpnMXERIVNEuWAL6+wNu3QLt2QGys3BERERHpNibQRPmcgYE0U6GbGxAdDbRvD7x7J3dUREREuosJNFEBYG0N7N4tjdBx7hzQp4804QoRERHlPSbQRAVEuXLA9u3/tUjPmiV3RERERLqJCTRRAeLpCaxeLd0OCgJ+/RVISQFCQ4EtW6T/KSlyRkhERFT4MYFO49WrV0hh9kH5XL9+wJgx0u0ePQBHR8DLC+jWTfrv4iK1VBMREVHu0PkE+sKFC2jZsiXMzMxgY2ODo0ePAgCePn0KPz8/hIaGyhsgkRYLFgC1agFJScCTJ+rrYmKAgAAm0URERLlFpxPoU6dOoVGjRrh16xZ69OiB1NRU1brixYvj1atXWmcnJMoPMhrOTnlx4ciR7M5BRESUG3Q6gZ48eTIqVaqEa9euYe7cuRrrvby8cPbsWRkiI8rc8ePAw4cZrxcCiIqSyhEREVHO0ukE+vz58+jTpw+MjY2hUCg01pcsWRKPHj2SITKizGV1MhVOukJERJTzdDqBNjQ0VOu2kV5MTAzMzc3zMCKirHFwyFo5C4vcjYOIiEgX6XQCXb9+fWzbtk3rujdv3mD9+vXw9PTM46iIPqxxY6BUKUDLiRM1vXoBwcFAQkLexEVERKQLdDqBnjFjBi5cuIA2bdpg3759AIDw8HB89913qFWrFv79919MnTpV5iiJNOnrS4kxoJlEK++XLAk8fy5dTFipErB5M5DJCRciIiLKIp1OoOvVq4e9e/fi9u3b6NmzJwBgzJgxGDhwIFJSUrB3715Uq1ZN5iiJtPP3B7ZtkxLltEqVAn7/HYiMBNaulbp73LsHdO8O1K4NhITIEi4REVGhYSB3AHLz9vbGjRs3cPnyZdy6dQupqakoW7YsatWqpfXCQqL8xN8f8POTRtuIjZWS5caNpRZqABgwQJpgJThYGjs6LAzw9QV8fID584GaNeWNn4iIqCDS+QRaycPDAx4eHnKHQZRt+vpA06YZry9SBJg8GRg4EJgzB1ixQmqFDgmRkuvZswFX1zwLl4iIqMDT6S4cly9fxpYtW9SWHThwAE2aNEG9evUQrOxkSlQIFC8OLFkC3LghdecApH7RFStK/aT//VfW8IiIiAoMnU6gx48fj61bt6ru37t3Dx06dMC9e/cAAKNHj8batWvlCo8oV7i6Aps2AZcuSd05kpKkLh5ly0ot1G/eyB0hERFR/qbTCXR4eDgaNWqkuv/TTz9BX18fYWFhOHv2LAICArB69WoZIyTKPTVqAAcOSF05atQAXr8GpkwBypeXLj5MTpY7QiIiovxJpxPoV69ewcbGRnV/79698PHxQfHixQEAPj4+uH37tlzhEeWJ5s2BCxek7hyurtLFiIMGAVWqADt2SNOCExER0X90OoF2cHBAREQEACA2NhYXL16Er6+van18fDz09HS6ikhH6OkBX3wBRERI3TmKF5f6Svv7Aw0bAidOyB0hERFR/qHT2aGfnx+WLVuG4cOHo3379jA2NkaHDh1U68PDw1GmTBkZIyTKW8bGwPDhwJ07UncOMzPg9GlpaDw/P+DaNbkjJCIikp9OJ9CzZ8+Gv78/Nm7ciCdPnmDDhg0oUaIEACAuLg7btm1Ta5Em0hWWlsCsWcDt21J3Dn194I8/gKpVgf79gehouSMkIiKSj06PA21ubo6ff/45w3XR0dEwMzPL46iI8g8HB2D1ammYu8mTpT7R338P/PyztGzCBMDaWuYgiYiI8phOt0BnRk9PD1ZWVjA0NJQ7FCLZubkB27cDJ09KfaLfv5dmMixbFli8GEhIkDtCIiKivKPTLdAA8OLFC2zZsgV3797FixcvININOaBQKPD999/LFB1R/tKggTRt+O7dwMSJ0kWHY8YA334rdfno3l26IJGIiKgw0+kE+sCBAwgICMCbN29gaWmJokWLapRRKBQyREaUfykUQLt2QOvWwI8/AtOmAffvAz17AosWSS3TLVpI5YiIiAojnW4rGjNmDOzt7REeHo6XL1/i3r17Gn93796VO0yifMnAAOjXD7h1C5g3D7CyAsLDgVat/htbmoiIqDDS6QT69u3bGD58OKpWrSp3KEQFlpmZ1J3jzh1g9GjAyAj46y+gTh2ga1dpORERUWGi0wl0+fLl8fr1a7nDICoUbGykLhw3bgD/+5/UhWPrVukCxGHDgCdP5I6QiIgoZ+h0Aj179mysXLkSkZGRcodCVGi4uAA//QSEhQEtWwLJycDy5dKIHTNnAvHx/5VNSQGOHlXg2LGSOHpUgZQU2cImIiLKMp2+iPDw4cOwtbVFpUqV4OPjAycnJ+jr66uVUSgUCA4OzvPYBgwYgO+++w5t2rTBnj17NNb/8ccfmD59Oq5duwY7Ozv06dMHU6dOhYGBTr+klI9Urw7s2yd15xg/Hrh4EQgKAlaulP7b2EgjeERHGwCojcWLgVKlpKnE/f3ljp6IiChjOp1tLV++XHVbW5IKyJNAX7hwARs2bICJiYnW9fv27UP79u3RtGlTLFu2DFeuXMHs2bPx5MkTrFq1Kk9jJfoQb2/g3Dngt9+kyVju3gWGDtVeNiYGCAgAtm1jEk1ERPmXTifQqampcoegQQiB4cOHo2fPnjh8+LDWMmPHjkW1atVw8OBBVYuzpaUl5s6dixEjRsDNzS0vQyb6ID09oEsXoEMHaWbDUaMAbR8/IaS+0yNHAn5+0hTiRERE+Y1O94HOjzZu3IirV69izpw5Wtdfu3YN165dw8CBA9W6awwdOhRCCGzbti2vQiXKNiMjoFo17cmzkhBAVJQ0YQsREVF+pNMt0Er37t3Dvn37cP/+fQCAs7MzWrVqBVdX1zyN4/Xr15gwYQImT54Me3t7rWXCwsIAALVr11Zb7ujoiFKlSqnWa5OQkICENHMux8XFAQCSkpKQlJT0qeEXeMo6YF3krqgoBbJy6ImKSkZSkvhgOfo4fL/Lg/Uuj9yod76Guk3nE+gxY8YgODhYozuHnp4eRo4ciYULF+ZZLDNnzoSpqSlGjRqVYZnY2FgAgIODg8Y6BwcHPHz4MMPHzps3DzNmzNBYfvDgQZiZmX1ExIVTSEiI3CEUavfv2wBolIVyZ7B377PcD0jH8f0uD9a7PHKy3t++fZtj26KCR6cT6EWLFmHJkiUICAjAmDFjUKlSJQBAREQElixZgiVLlqBkyZKZJrTapKamIjExMUtljY2NoVAocPPmTQQHB2PLli0wNjbOsPy7d+9Uj0vPxMRE1aqszaRJkzB69GjV/bi4ODg5OcHX1xeWlpZZircwS0pKQkhICHx8fGBoaCh3OIVWixbA6tUCDx8CQmjO961QCJQsCYwdW499oHMR3+/yYL3LIzfqPbPvWyr8dDqBXrduHdq1a4dff/1VbXm9evXwyy+/4P3791izZk22E+hjx47By8srS2UjIiLg5uaGESNGoEGDBujYsWOm5U1NTQFArSuG0vv371XrtTE2NtaaeBsaGvJAngbrI3cZGgLffiuNtqFQSH2e0xJCgeBgwMSEr0Fe4PtdHqx3eeRkvfP10206nUBHRkZixIgRGa5v0aIF9u/fn+3turm5Yf369Vkq6+DggL/++gv79+/H9u3b1SZ1SU5Oxrt37xAZGYlixYrB0tJS1XUjNjYWTk5OatuKjY1F3bp1sx0vUV7z95eGqhsxAoiOVl9nYgLwbUxERPmZTifQdnZ2CA8Pz3B9eHg4bG1ts71de3t79O7dO8vlHzx4AADw1zLwbUxMDFxdXbFkyRKMHDkSHh4eAKSxotMmyw8fPkR0dDQGDhyY7XiJ5ODvLw1Vd+RIMvbtu4wWLTwQFGSAM2eA0aOBdCeGiIiI8g2dTqA7deqE4OBguLi4YNiwYShSpAgA4M2bN1i+fDm+++47jBw5Mtfj8Pb2xo4dOzSWDxw4EM7Ozvjqq69QtWpVAIC7uzvc3Nywdu1aDBo0SDVz4qpVq6BQKBAQEJDr8RLlFH19wNNT4M2bGHh5VUeJEkDNmtKkKwcPAr6+ckdIRESkSacT6FmzZuHy5cuYPHkypk2bBkdHRwBSa25ycjK8vLwwc+bMXI+jdOnSKF26tMbykSNHokSJEmjfvr3a8m+++Qbt2rWDr68vunbtiqtXr2L58uXo37+/6kJIooKoenVg+HBg6VIgMBC4ckXq0kFERJSf6PREKmZmZjh8+DB27NiBPn36oFKlSqhUqRL69u2LnTt34tChQ/lyeLe2bdti+/bteP78OYYNG4bt27dj8uTJWLFihdyhEX2yGTMABwfg9m3gm2/kjoaIiEiTTrdAK/n5+cHPz0/uMDSkvaAwvfbt22u0TBMVBpaWwOLFwBdfAHPnAt27A2XKyB0VERHRf5hAA3j+/DkOHTqkSlhdXV3h7e0NGxsbeQMj0lFdugDffQccPgwMGwbs2SMNeUdERJQf6HwCPX36dCxYsEBjXGUjIyOMHz8+T/pAE5E6hQJYsQKoWhXYuxfYtQvgCRciIsovdLoP9KxZszBz5kw0b94c+/btw507d3Dnzh3s3bsXzZs3x5w5czBr1iy5wyTSSRUrAuPGSbeHDwfevJE3HiIiIiWdTqBXr16Nzz//HLt370aLFi3g6uoKV1dXtGzZEnv27EHr1q2xatUqucMk0llffQU4OwNRUcDs2XJHQ0REJNHpBPrVq1do2bJlhutbt26N169f52FERJSWmZk07TcALFwIXLsmbzxERESAjifQDRs2xNmzZzNcf/bsWTRs2DAPIyKi9Nq1Az7/HEhOlsaGFkLuiIiISNfpdAK9evVqnD59GqNGjcLt27eRmpqK1NRU3L59GyNHjsSZM2ewevVqucMk0nnBwYCpKRAaCmzZInc0RESk63R6FI5q1aohNTUV3377Lb799lvo6Um/J1JTUwEAxsbGqFatmtpjFAoFXr16leexEukyV1epP/SUKcDo0UCbNoCVldxRERGRrtLpBLpjx45QcHBZogJh7Fjgp5+AmzeBqVP/6xtNRESU13Q6gd6wYYPcIRBRFhkbS2ND+/hI//v0AWrUkDsqIiLSRTrdB5qICpbmzaVZClNTgSFDpP9ERER5TacT6MOHD+Obb75RW/bDDz+gdOnSKFGiBEaNGoWUlBSZoiMibRYvBiwsgLNnge+/lzsaIiLSRTqdQE+fPh3h4eGq+1euXMGgQYNga2uLpk2b4ttvv8XChQtljJCI0nN0BGbOlG5PnAg8fSpvPEREpHt0OoGOiIhA7dq1Vfc3btwIS0tLHD9+HFu3bsWAAQPw008/yRghEWnz5ZdAtWrA8+dSEk1ERJSXdDqBfvPmDSwtLVX39+/fj5YtW8LMzAwAUKdOHdy/f1+u8IgoAwYGwMqV0u3vvwdOnZI3HiIi0i06nUA7OTnh/PnzAIDbt2/j6tWr8PX1Va1//vw5jI2N5QqPiDLRsCHQt690e+hQaaZCIiKivKDTCXT37t2xdu1atGvXDi1atEDRokXh5+enWn/x4kVUqFBBxgiJKDPz5wNFiwLh4dLQdkRERHlBpxPor776ChMnTkRUVBRKly6NnTt3wtraGoDU+hwaGop27drJGyQRZcjWVkqiAWlylYcP5Y2HiIh0g05PpGJgYIA5c+Zgzpw5GuuKFSuGR48eyRAVEWVH//5SP+hz56TZCjdvljsiIiIq7HS6BTqt2NhYhIeH482bN3KHQkTZoKcHrFol/d+yBTh8WO6IiIiosNP5BHrXrl1wc3NDqVKlULNmTZw9exYA8PTpU9SoUQM7duyQOUIi+pCaNaULCQEgMBBISJA3HiIiKtx0OoHevXs3/P39Ubx4cQQFBUEIoVpXvHhxlCxZEhs2bJAvQCLKslmzgBIlgBs3pNkKiYiIcotOJ9AzZ85EkyZNcOLECQQGBmqs/+yzzxAWFiZDZESUXdbWgHLi0FmzgMhIOaMhIqLCTKcT6KtXr6Jz584Zri9RogSePHmShxER0afo3h3w9ATevQNGjpQ7GiIiKqx0OoE2MzPL9KLBu3fvwsbGJg8jIqJPoVBIMxQaGAC7dgG7d8sdERERFUY6nUB7eXnhxx9/RLKWKcwePXqEdevWqc1MSET5X+XKwOjR0u3hw4G3b+WNh4iICh+dTqDnzJmD6Oho1KlTB2vWrIFCocCBAwcwZcoUVK1aFUIIBAUFyR0mEWXT1KmAk5PUD3rePLmjISKiwkanE+iKFSvixIkTsLGxwdSpUyGEwDfffIO5c+eiatWqOH78OFxcXOQOk4iyydwcCA6Wbn/9tTQyBxERUU7R6ZkIAcDd3R2HDh3CixcvcPv2baSmpqJMmTKwtbUFAAghoFAoZI6SiLKrfXugVStg3z7gyy+BgwelPtJERESfSqdboNMqWrQo6tSpg3r16sHW1haJiYlYu3YtKlasKHdoRPQRFApg2TLA2Bg4dAj47Te5IyIiosJCJxPoxMREbNu2DQsWLMDatWvx8OFD1bq3b9/i66+/houLCwYPHqw2uQoRFSxlywKTJ0u3R44E4uJkDYeIiAoJnevC8fDhQzRt2hR37txRJcempqb4448/YGRkhG7duiEmJgZ169bFsmXL4O/vL3PERPQpxo8HfvoJuHMHmD6dsxQSEdGn07kW6K+++gr37t3D+PHjsWfPHixbtgzm5uYYOHAg2rZtCycnJxw5cgRnzpxBx44d2f+ZqIAzMQGWL5duf/st8Pff8sZDREQFn861QIeEhKBPnz6Yl2ZsK3t7e3Tq1Alt2rTBrl27oKenc78riAq1li2BgABg2zZgyBDg+HGAH3MiIvpYOvcV8vjxY9SvX19tmfJ+3759mTwTFVJLlgBFigCnTgE//ih3NEREVJDpXLaYkpICExMTtWXK+1ZWVnKERER5oFQpqQ80IPWLfv5c1nCIiKgA07kuHAAQGRmJS5cuqe6/evUKAHDr1i1YW1trlK9Zs2ZehUZEuWjECGDDBuCff6TROVavljsiIiIqiHQygZ46dSqmTp2qsXzo0KFq95WTqKSkpORVaESUiwwNgZUrAU9PYO1aoG9foG5duaMiIqKCRucS6PXr18sdAhHJqEkToGdPaWi7IUOAc+cAfX25oyIiooJE5xLoXr16yR2CVhs2bECfPn20rouNjYW9vb3asj/++APTp0/HtWvXYGdnhz59+mDq1KkwMNC5l5Qo277+Gti1C7h0SerGERgod0RERFSQMNvKZ2bOnAlXV1e1Zen7Ze/btw/t27dH06ZNsWzZMly5cgWzZ8/GkydPsGrVqjyMlqhgKlECmDtXSpy/+koa4q5ECbmjIiKigoIJdD7TqlUr1K5dO9MyY8eORbVq1XDw4EFVi7OlpSXmzp2LESNGwM3NLS9CJSrQBg0CfvgBuHgRGDdO6tJBRESUFTo3jF1B8Pr16wwvXLx27RquXbuGgQMHqnXXGDp0KIQQ2LZtW16FSVSg6esDq1YBCgWwcSNw9KjcERERUUHBFuh8xsvLC/Hx8TAyMkKLFi2waNEilC9fXrU+LCwMADRaqR0dHVGqVCnVem0SEhKQkJCguh8XFwcASEpKQlJSUk7uRoGkrAPWRd6Ss949PIABA/Swdq0+hgwRuHAhGYaGeR6GLPh+lwfrXR65Ue98DXUbE+h8wszMDL1794aXlxcsLS1x8eJFLF68GA0aNMClS5fg5OQEQLqgEAAcHBw0tuHg4ICHDx9m+Bzz5s3DjBkzNJYfPHgQZmZmObQnBV9ISIjcIegkueq9SRNDbN3aDBERxhg69CY6dLgtSxxy4ftdHqx3eeRkvb99+zbHtkUFj0IIIeQOorBJTU1FYmJilsoaGxtDoVBoXXfixAk0adIEAwcOxOr/n/Fh1qxZmDZtGh4/fgw7Ozu18k2aNEFcXBwuX76sdXvaWqCdnJzw9OlTWFpaZinewiwpKQkhISHw8fGBoa40Q+YD+aHef/pJgf79DWBmJnDlSjL+//dqoZYf6l0Xsd7lkRv1HhcXh+LFi+PVq1f8DtVBbIHOBceOHYOXl1eWykZERGR40V+jRo1Qr149HDp0SLXM1NQUANQSYaX379+r1mtjbGwMY2NjjeWGhoY8kKfB+pCHnPXep480Q+GJEwqMG2eI33+XJQxZ8P0uD9a7PHKy3vn66TYm0LnAzc0tyxO2aOuKkZaTkxNu3LihUT42NlbVrUMpNjYWdTmtGlG26elJMxTWqAFs3w7s2we0aiV3VERElF8xgc4F9vb26N27d45s6+7du7C1tVXd9/DwAABcuHBBLVl++PAhoqOjMXDgwBx5XiJdU7UqMGIEsHgx8OWXwNWrQCYndIiISIdxGLt84t9//9VYtnfvXly8eBEtW7ZULXN3d4ebmxvWrl2rNtTdqlWroFAoEBAQkCfxEhVG06cDjo7A3bvAggVyR0NERPkVW6DziQYNGqBGjRqoXbs2rKyscOnSJfzwww9wcnLC5MmT1cp+8803aNeuHXx9fdG1a1dcvXoVy5cvR//+/VGpUiWZ9oCo4LOwAJYuBTp3BubPB3r0AMqVkzsqIiLKb9gCnU906dIFt27dwty5czFs2DDs378fAwYMwPnz51Ei3RzDbdu2xfbt2/H8+XMMGzYM27dvx+TJk7FixQqZoicqPAICAB8fICFB6srBcYqIiCg9tkDnE7Nnz8bs2bOzXL59+/Zo37597gVEpKMUCmD5cqlP9IED0kWFHTvKHRUREeUnbIEmIkqnQgVgwgTp9siRQHy8rOEQEVE+wwSaiEiLSZMAV1cgOhqYOVPuaIiIKD9hAk1EpIWpKfDtt9LtJUuAf/6RNx4iIso/mEATEWWgbVugfXsgORkYOpQXFBIRkYQJNBFRJpYulVqjjx0DNm2SOxoiIsoPmEATEWXC2RmYNk26PXYs8PKlrOEQEVE+wASaiOgDRo8G3NyAJ0+AKVPkjoaIiOTGBJqI6AOMjICVK6XbK1cCFy/KG8+nSkkBjh5V4Nixkjh6VIGUFLkjIiIqWJhAExFlgZcX0K2bdCHhkCEosEnn9u2Aiwvg42OAxYtrw8fHAC4u0nIiIsoaJtBERFm0cCFgaQmcPw+sXQuEhgJbtkj/C0JCvX27NFV5dLT68pgYaTmTaCKirGECTUSURQ4OwKxZ0u3AwP9apb28kO9bcVNSgBEjtA/Fp1w2cmTB+CFQULHrDFHhYSB3AEREBYmDg/Q/fSKqbMXdtg3w98/55xVCGo86IQF4/176U95O/1/bsmvXNFue028/Kgo4fhxo2jTn49d127dLP2Ciow0A1MbixUCpUkBwcO68X4godzGBJiLKopQUaUQObZQJ9cCBQFwckJj48cluRutSU3N/H2Njc/85dI2y60xe/+giotzDBJqIKIuOH8+8FRcAnj0D+vTJ/VgMDAATE8DYWPv/9MtevgQOHPjwdpUt7JQzPtR1RqGQus74+QH6+nkeHhF9JCbQRERZlNXW2WrVAFfXjJPbjJLcrK4zNs5+spWSIvXTjonJeEpyPb3/1isU2ds+afehH13sOkNUMDGBJiLKoqy2zgYH579kSF9fiisgQEqOtSXRqalAjx7Ad98By5cD7u55H2dhc/Vq1sqx6wxRwcJROIiIsqhxY+nCr4xaZxUKwMlJKpcf+ftL/W1LllRf7uQkDcc3a5bUwh0aClSvDowZI/XnpuyLiwO++kqqw6ywscndeIgoZzGBJiLKImUrLqCZRCvvL12av/uy+vsDkZFASEgyRo++gJCQZNy7B3TtKk1THhEBtG8vdflYvBioWBH4+eeMu32QusREqfW+bFlg7lzpvpHRhx/35ZfA4cO5Hx8R5Qwm0ERE2ZBRK26pUgVnNAV9fcDTU6BJkxh4egq1hN/FBdixA9i3DyhXDnj0SOrW0bQpcOWKXBHnf0IAv/8udXsZNgx4+lT68bFzJ7B5s/QDK6MfXdbWwK1bQPPmUl0/fpzX0RNRdjGBJiLKJmUr7pEjUnJ05Ahw717BSJ6zqmVLqf/u7NmAqSlw7BhQowYwahTw6pXc0eUvJ08CDRpI/ctv3wbs7IBVq6QfHH5+QMeOGf/o+v136b00bJh0EefPP0uJ96pVnNSGKD9jAk1E9BH09aVW2S++kP7n524bH8vYWOrHGxEh/ThISZG6qFSsCGzcyG4dN25I9dKoEXDmDGBmBkybJiXRgwcDhob/lc2o64y/P2BlBXz7LXD2LFCrlvQDZehQ4LPPgEuXZNs9IsoEE2giIsqUs7PUUnrgAFChgtTFoGdPoEkTIDxc7ujy3uPH0lTu7u5Sdxc9PWDAAClxnjEDsLDQ/rjMus4AQO3aUhK9fDlgaQmcPw/UqSONI82LOYnyFybQRESUJb6+wN9/A/PmSa2tJ04ANWtKCd7Ll3JHl/vevJFGKilXDli5UmqR//xzqavG2rU5MwmNvr6UnF+/Ll3YmZoqtU67uQG//cZWf6L8ggk0ERFlmbExMHGi1K0jIOC/BK9iReDHH/NmuvG8lpIijY1dvrzURSM+XmotPnIE+OMPoHLlnH9OBwdpaMGDB6WEPTYW6NwZaN0auHMn55+PiLKHCTQREWVb6dJSi+jBg1Ly/OQJ0Lu3NAb25ctyR5czhAD+/FMaE3vAACmJdXWVEtuzZ/NmshwfH6mFe/p0aTi8/fuBKlWkizsTEnL/+YlIOybQRET00Xx8pG4dCxYARYoAp05JF8ING1awu3VcuAA0awa0bQv88w9QtKg0LnZEhNS1Qi8Pvz1NTICgICmRbt4ceP8emDpVSuz/+ivv4iCi/zCBJiKiT2JkBIwfL/Xb7dxZ6saxfLl0weH69QWrW8e9e0C3btLFe0eOSF1Wxo2Tuk2MGiXdl0uFClKL/5YtgL29NApIs2YcO5pIDkygiYgoR5QqBWzdChw6BFSqBPz7L9C3L9CwYf4fju35c2nabTc3KUEFgP/9T0pSv/5aaoHODxQKqQX8+nVp9kKF4r+xo1evLlg/VogKMibQRESUo5o1k/pBf/211K3jzBmpRTcwEHjxQu7o1L1/DyxcKE29vXixNPV2s2ZSwv/TT9IQfvmRlRWwbBlw7pw0EsqrV8CQIdLY0WFhckdHVPgxgSYiohxnZCR1fbhx47/h2FaulLohfP+9/C2lqalSy62bmxTny5dA1arSFOYhIdKsiwVB7dpSEv3tt9L40+fOSctGjQJev5Y7OqLCiwk0ERHlmpIlpS4Rf/0lDff29CnQv7809fXFi/LE9NdfUot4jx7A/ftSjD/8ILXctmwpdYsoSPT1pYs2r18HunSRfhwsXSr9ONi2jWNHE+UGJtBERJTrvLykbh2LFkktpWfPSkns4MHAs2d5E8PVq9I4ysouGhYWwNy5wM2bQJ8+BX86dkdH4JdfpBkjy5YFHj4EOnWS9vnuXbmjk09KCnD0qALHjpXE0aMKpKTIHREVBkygiYgoTxgaAqNHSy2l3bpJLaNr1kgXwK1bl3vdOmJigH79pGHf9u0DDAykFts7d4BJk6RZFQsTX19pyLtp0/4bO9rdHZgzR/fGjt6+HXBxAXx8DLB4cW34+BjAxUVaTvQpmEATEVGecnSU+h+HhkqTgjx7BgwcCNSvD5w/n3PPExcHTJkizSD4ww9Sgh4QAFy7JvUZtrXNuefKb0xNgRkzpES6WTPpYskpU6QfEUeOyB1d3ti+XXq9o6PVl8fESMuZRNOnYAJNRESy8PSUulIsWSJ1pzh/HqhXDxg06NO6dSQlAStWSFNgz5kDvHsnDaV36pQ0e2L58jm3D/ldhQrSRZE//wyUKCFd1OntLQ3RV5jHjk5JAUaM0N7/W7ls5EiwOwd9NCbQREQkG0NDKZG5cUO6qE8IYO1aKfFbsyZ7CY4QUquiu7s0RvK//0rb2bEDOH5cGuJNFykUUpeZ69eBoUOl+5s2SRcZrlkj/4goueHgQc2W57SEAKKipPcF0cdgAk1ERLJzcAA2bgSOHZOGk3v+XLrAsF496YJDpZQUqevHli3Sf2WCfeqU1MrcsSNw6xZgZycNm3f1KtC+fcEbWSM3WFtLLfNnzkjD9L18KdVxgwbSBZ4FjRDAo0fS+2D1aumHWMuWUp/n1q2zto3Y2FwMkAo1A7kDICIiUmrcWOrWsXIlMHWqNNRd/frS0HcNG0rL0rYs2ttLk50ok2wzM2lGwXHjpG4hpKluXWm86JUrpX7RZ88CtWpJXR5mzMh/9ZaUJF3wef265t+rV5+2bQeHnImRdA8TaCIiylcMDIDhw6UxjSdMAH78EfjuO+kvvUePpD+FQhppY8YM6SJFypyyjgMCpElXfv1V6ov+669AcDDg75/3rfYvX0pdedImyBERUvKcnKz9MXp6gKur1B0l7V/58tKEMjEx2vtBKxTS1PONG+fqLlEhxgQ6nzl06BDmzp2LixcvIjU1FRUqVMD48ePRpUsXtXJ//PEHpk+fjmvXrsHOzg59+vTB1KlTYWDAl5SICocSJYANG4C+fYHmzaWWyMzKrl5d8MdyzmuOjsDWrVIdDx0qjRcdEAC0agUsXw6UKSOVS0mR+gvHxkqtto0bf1xdp6ZKfY+1tSY/epTx44oU0UyS3dykC0VNTLQ/JjhY2heFQj2JVv4wWLqU7xf6eMy28pH169ejX79+8PHxwdy5c6Gvr48bN24gKipKrdy+ffvQvn17NG3aFMuWLcOVK1cwe/ZsPHnyBKtWrZIpeiKi3JGamnnyDEjJ1/HjQNOmeRJSodOihdRffN48YP58abxsd3epi0e5csDYsepdZ0qV+q+lWpt376S+6Glbkq9fl1qY373LOA5HRykxrlRJPVEuWTL7LeL+/tJMjCNGaMa+dGnGsRNlBRPofCIyMhKBgYEYNmwYgoODMy07duxYVKtWDQcPHlS1OFtaWmLu3LkYMWIE3Nzc8iJkIqI8kdULvXhB2KcxNQVmzgS6d5dao//6S0qgtVGOpfz999Ksh+lbkyMjM55C3NBQ6mKRvjW5YkXA0jJn98nfH/DzA44cSca+fZfRqpUHvLwM2PJMn4wJdD6xevVqpKSkYObMmQCA+Ph4FClSBIp0P7mvXbuGa9euYcWKFWrdNYYOHYo5c+Zg27ZtmJLREY+IqADK6oVevCAsZ1SsCBw6JA1117u39mHulMlx374Zb6doUc2WZDc3qc9yXvY21NcHPD0F3ryJgadndSbPlCOYQOcThw4dgpubG/bu3Ytx48YhJiYGRYsWRWBgIGbMmAE9PWnEwbCwMABA7dq11R7v6OiIUqVKqdYTERUWjRtLp915QVjeUSgAJ6esjRFtby8Ni6dMkJVJc/HiHD6QCi8m0PnErVu3oK+vjz59+mD8+PGoXr06tm/fjtmzZyM5ORnz5s0DAMT+/zlKBy1NLQ4ODnj48GGGz5GQkICEhATV/bi4OABAUlISkj7UwVAHKOuAdZG3WO/yKGj1vmiRAl276v//BWH/ZWUKhZRRL1yYgtRUke8nBSlI9R4VpUBW0oSvv05G166av2wyGjlDDrlR7wXhNaTcwwQ6F6SmpiIxMTFLZY2NjaFQKBAfH4/U1FTMnz8fEyZMAAB07NgRz58/R3BwMCZPngwLCwu8+/+rL4yNjTW2ZWJiokqKtZk3bx5mzJihsfzgwYMwMzPLUry6ICQkRO4QdBLrXR4Fpd6NjYHx4x3w3XdV8eyZqWq5jc079Ot3FcbGsdi7V8YAs6kg1Pv9+zYAGmWh3Bns3fsJc6/noZys97dv3+bYtqjgUQiRUTd/+lihoaHw8vLKUtmIiAi4ubnB3Nwcb968wf3791G6dGnV+p9++gm9evXC0aNH0aRJEyxcuBDjxo3DgwcP4OTkpLatunXrQl9fH6dPn9b6XNpaoJ2cnPD06VNY5vSVGwVQUlISQkJC4OPjA0NDQ7nD0Rmsd3kU1HpPSQFOnFCohlNr1EgUqD6tBaneU1KAcuUM8PChequ/kkIhULIkcOtWcr5/DXKj3uPi4lC8eHG8evWK36E6iC3QucDNzQ3r16/PUlllVwxHR0fcunULJUqUUFtvZ2cHAHjx4oVa+djYWI0EOjY2FnXr1s3wuYyNjbW2XBsaGub7A3leYn3Ig/Uuj4JW74aG0pjQBV1BqHdDQ+DbbzMbS1mB4GDAxCR/70daOVnv+f31o9zFBDoX2Nvbo3fv3tl6TK1atXDr1i3ExMSgjHLkekDVp9nW1hYA4OHhAQC4cOGCWrL88OFDREdHY+DAgZ8WPBER0f/jWMpE2unJHQBJlDMNfv/996plqampWL9+PYoVK4ZatWoBANzd3eHm5oa1a9ciJSVFVXbVqlVQKBQICAjI28CJiKhQ8/eXxnU+cgTYvFn6f+8ek2fSbWyBzif8/PzQrFkzzJs3D0+fPkX16tWxc+dOnDhxAmvWrFHrevHNN9+gXbt28PX1RdeuXXH16lUsX74c/fv3R6VKlWTcCyIiKoz09TnLI1FabIHOJxQKBXbu3Inhw4fjjz/+wKhRo/Do0SNs2rRJo1tG27ZtsX37djx//hzDhg3D9u3bMXnyZKxYsUKm6ImIiIh0B1ug8xFzc3MsXboUS5cu/WDZ9u3bo3379rkeExERERGpYws0EREREVE2MIEmIiIiIsoGJtBERERERNnABJqIiIiIKBt4EaEOU87iHhcXJ3Mk+UNSUhLevn2LuLg4zjCVh1jv8mC9y4P1Lo/cqHfld6dIO0Uj6Qwm0Drs9evXAKAxJTgRERFlzevXr2FlZSV3GJTHFII/nXRWamoqHj58CAsLCygUCrnDkV1cXBycnJwQFRUFS0tLucPRGax3ebDe5cF6l0du1LsQAq9fv4ajoyP09NgjVtewBVqH6enpoVSpUnKHke9YWlryi00GrHd5sN7lwXqXR07XO1uedRd/MhERERERZQMTaCIiIiKibGACTfT/jI2NERQUBGNjY7lD0Smsd3mw3uXBepcH651yGi8iJCIiIiLKBrZAExERERFlAxNoIiIiIqJsYAJNRERERJQNTKCJiIiIiLKBCTTpjPPnz+PLL7+Eu7s7ihQpgtKlS6Nz5864efOmRtmIiAi0bNkS5ubmKFasGP73v//h33//lSHqwmfOnDlQKBSoUqWKxrpTp06hUaNGMDMzg729PYYPH474+HgZoiwcLl26hHbt2qFYsWIwMzNDlSpV8O2336qVYZ3nrFu3bqFr164oVaoUzMzM4ObmhpkzZ+Lt27dq5VjvHy8+Ph5BQUFo2bIlihUrBoVCgQ0bNmgtm9VjeWpqKr7++mu4urrCxMQE1apVw5YtW3J5T6gg40yEpDMWLFiAkydPolOnTqhWrRoePXqE5cuXo2bNmjhz5owqoYuOjkaTJk1gZWWFuXPnIj4+HgsXLsSVK1dw7tw5GBkZybwnBVd0dDTmzp2LIkWKaKy7fPkymjVrhkqVKmHx4sWIjo7GwoULcevWLezbt0+GaAu2gwcP4vPPP0eNGjUwdepUmJub486dO4iOjlaVYZ3nrKioKNStWxdWVlb48ssvUaxYMZw+fRpBQUG4ePEidu3aBYD1/qmePn2KmTNnonTp0qhevTpCQ0O1lsvOsfyrr77C/PnzMWDAANSpUwe7du1Ct27doFAo0LVr1zzaMypQBJGOOHnypEhISFBbdvPmTWFsbCy6d++uWjZkyBBhamoq7t+/r1oWEhIiAIg1a9bkWbyFUZcuXYS3t7fw9PQU7u7uautatWolHBwcxKtXr1TL1q1bJwCIAwcO5HWoBdqrV69EiRIlRIcOHURKSkqG5VjnOWvOnDkCgLh69ara8p49ewoA4vnz50II1vunev/+vYiNjRVCCHH+/HkBQKxfv16jXFaP5dHR0cLQ0FAEBgaqlqWmporGjRuLUqVKieTk5NzbGSqw2IWDdEaDBg00Wo/Lly8Pd3d3REREqJb9/vvvaNu2LUqXLq1a1rx5c1SoUAG//vprnsVb2Bw7dgzbtm3D0qVLNdbFxcUhJCQEPXr0gKWlpWp5z549YW5uznrPps2bN+Px48eYM2cO9PT08ObNG6SmpqqVYZ3nvLi4OABAiRIl1JY7ODhAT08PRkZGrPccYGxsDHt7+w+Wy+qxfNeuXUhKSsLQoUNVyxQKBYYMGYLo6GicPn06Z3eACgUm0KTThBB4/PgxihcvDgCIiYnBkydPULt2bY2ydevWRVhYWF6HWCikpKRg2LBh6N+/P6pWraqx/sqVK0hOTtaodyMjI3h4eLDes+nQoUOwtLRETEwMKlasCHNzc1haWmLIkCF4//49ANZ5bmjatCkAoF+/frh8+TKioqKwdetWrFq1CsOHD0eRIkVY73kkO8fysLAwFClSBJUqVdIop1xPlB4TaNJpP//8M2JiYtClSxcAQGxsLACpxSg9BwcHPH/+HAkJCXkaY2GwevVq3L9/H7NmzdK6/kP1/vDhw1yNr7C5desWkpOT4efnhxYtWuD3339H3759sXr1avTp0wcA6zw3tGzZErNmzUJISAhq1KiB0qVLo2vXrhg2bBiWLFkCgPWeV7JzLI+NjUWJEiWgUCg0ygHga0Ja8SJC0lnXr19HYGAgPvvsM/Tq1QsA8O7dOwDSKcL0TExMVGW0rSftnj17hmnTpmHq1KmwtbXVWuZD9a5cT1kTHx+Pt2/fYvDgwapRN/z9/ZGYmIg1a9Zg5syZrPNc4uLigiZNmqBjx46wsbHBn3/+iblz58Le3h5ffvkl6z2PZOdYntExPW05ovSYQJNOevToEdq0aQMrKyts27YN+vr6AABTU1MA0NrKrDz1rSxDWTNlyhQUK1YMw4YNy7DMh+qddZ49yvr64osv1JZ369YNa9aswenTp2FmZgaAdZ6TfvnlFwwcOBA3b95EqVKlAEg/XFJTUzFhwgR88cUXfK/nkewcy01NTXnMp2xjFw7SOa9evUKrVq3w8uVL7N+/H46Ojqp1ylN2ytN/acXGxqJYsWJsfc6GW7duYe3atRg+fDgePnyIyMhIREZG4v3790hKSkJkZCSeP3/+wXpP+xrRhynrK/3FbHZ2dgCAFy9esM5zwcqVK1GjRg1V8qzUrl07vH37FmFhYaz3PJKdY7mDgwMePXoEIYRGOQB8TUgrJtCkU96/f4/PP/8cN2/exJ49e1C5cmW19SVLloStrS0uXLig8dhz587Bw8MjjyItHGJiYpCamorhw4fD1dVV9Xf27FncvHkTrq6umDlzJqpUqQIDAwONek9MTMTly5dZ79lUq1YtAFL9p6Xsy2lra8s6zwWPHz9GSkqKxvKkpCQAQHJyMus9j2TnWO7h4YG3b9+qjcYEAGfPnlWtJ0qPCTTpjJSUFHTp0gWnT5/Gb7/9hs8++0xruY4dO2LPnj2IiopSLTt8+DBu3ryJTp065VW4hUKVKlWwY8cOjT93d3eULl0aO3bsQL9+/WBlZYXmzZtj06ZNeP36terxGzduRHx8POs9mzp37gwA+P7779WWf/fddzAwMEDTpk1Z57mgQoUKCAsL05jddMuWLdDT00O1atVY73koq8dyPz8/GBoaYuXKlaplQgisXr0aJUuWRIMGDfI0bioYFCL9OQuiQmrkyJEIDg7G559/rkow0urRowcAaTaxGjVqwNraGiNGjEB8fDy++eYblCpVCufPn2cXjhzQtGlTPH36FFevXlUtu3TpEho0aIDKlStj4MCBiI6OxqJFi9CkSRMcOHBAxmgLpn79+uGHH35A586d4enpidDQUPz222+YNGkS5s6dC4B1ntOOHTsGb29v2NjY4Msvv4SNjQ327NmDffv2oX///li3bh0A1ntOWL58OV6+fImHDx9i1apV8Pf3R40aNQAAw4YNg5WVVbaO5ePHj8c333yDgQMHok6dOti5cyf+/PNP/Pzzz+jWrZtcu0n5mazTuBDlIU9PTwEgw7+0rl69Knx9fYWZmZmwtrYW3bt3F48ePZIp8sJH20yEQghx/Phx0aBBA2FiYiJsbW1FYGCgiIuLkyHCgi8xMVFMnz5dODs7C0NDQ1GuXDmxZMkSjXKs85x19uxZ0apVK2Fvby8MDQ1FhQoVxJw5c0RSUpJaOdb7p3F2ds7wWH7v3j1Vuawey1NSUsTcuXOFs7OzMDIyEu7u7mLTpk15uEdU0LAFmoiIiIgoG9gHmoiIiIgoG5hAExERERFlAxNoIiIiIqJsYAJNRERERJQNTKCJiIiIiLKBCTQRERERUTYwgSYiIiIiygYm0ERERERE2cAEmoiIiIgoG5hAExHlc6GhoVAoFAgNDZXl+VNTU1GlShXMmTMnx7ZZv359jB8/Pse2R0SUl5hAE1GBc+XKFQQEBMDZ2RkmJiYoWbIkfHx8sGzZso/a3sqVK7Fhw4acDbIAx5Heli1bEBUVhS+//FK1LCYmBm3atIGlpSUqV66M3bt3azxu+/btsLOzw6tXrzTWTZgwAStWrMCjR49yNXYiotygEEIIuYMgIsqqU6dOwcvLC6VLl0avXr1gb2+PqKgonDlzBnfu3MHt27ezvc0qVaqgePHisrXwfiiO1NRUJCYmwsjICHp6ed/u4eHhgXr16mHNmjWqZc2bN0dMTAyGDx+OkydPYtu2bbh+/TpcXFwAAO/fv0flypUxceJEDBw4UGObqampKFmyJAYMGICZM2fm1a4QEeUIA7kDICLKjjlz5sDKygrnz5+HtbW12ronT57IE5QWQgi8f/8epqamn7wtPT09mJiY5EBU2RcWFobw8HAsWrRItezdu3f466+/EBoaiiZNmmDw4ME4deoUDhw4gEGDBgEAFi5cCCsrK/Tv31/rdvX09BAQEICffvoJM2bMgEKhyJP9ISLKCezCQUQFyp07d+Du7q6RPAOAnZ2d2v3169fD29sbdnZ2MDY2RuXKlbFq1Sq1Mi4uLvjnn39w9OhRKBQKKBQKNG3aFAAwffp0rYndhg0boFAoEBkZqbadtm3b4sCBA6hduzZMTU1VLbafGkdGfaB/++031KpVC6ampihevDh69OiBmJgYtTK9e/eGubk5YmJi0L59e5ibm8PW1hZjx45FSkpKRtWssnPnThgZGaFJkyaqZe/fv4cQAkWLFgUAKBQKWFtb4+3btwCk7h3z589HcHBwpi3mPj4+uH//Pi5fvvzBOIiI8hO2QBNRgeLs7IzTp0/j6tWrqFKlSqZlV61aBXd3d7Rr1w4GBgbYvXs3hg4ditTUVAQGBgIAli5dimHDhsHc3BxfffUVAKBEiRIfFduNGzfwxRdfYNCgQRgwYAAqVqyYa3Fs2LABffr0QZ06dTBv3jw8fvwYwcHBOHnyJMLCwtR+YKSkpKBFixaoV68eFi5ciEOHDmHRokUoW7YshgwZkuk+nTp1ClWqVIGhoaFqWdGiRVG2bFnMnTsXc+fOxalTp3D58mVVH/Tx48ejVatWakm3NrVq1QIAnDx5EjVq1Mi0LBFRviKIiAqQgwcPCn19faGvry8+++wzMX78eHHgwAGRmJioUfbt27cay1q0aCHKlCmjtszd3V14enpqlA0KChLaDpPr168XAMS9e/dUy5ydnQUAsX///hyP48iRIwKAOHLkiBBCiMTERGFnZyeqVKki3r17pyq3Z88eAUBMmzZNtaxXr14CgJg5c6baNmvUqCFq1aql8VzplSpVSnTs2FFj+eHDh0XRokUFAAFAjBw5UgghxMmTJ4WpqamIjIz84LaFEMLIyEgMGTIkS2WJiPILduEgogLFx8cHp0+fRrt27RAeHo6vv/4aLVq0QMmSJfHHH3+olU3b//jVq1d4+vQpPD09cffuXa0jQ3wqV1dXtGjRQmN5Tsdx4cIFPHnyBEOHDlXrG92mTRu4ubnhzz//1HjM4MGD1e43btwYd+/e/eBzPXv2TNVVIy1vb288ePAAZ86cwYMHD7BkyRKkpqZi+PDhGDNmDJydnbFq1Sq4ubmhYsWKWL16tdbtFy1aFE+fPv1gHERE+Qm7cBBRgVOnTh1s374diYmJCA8Px44dO7BkyRIEBATg8uXLqFy5MgCpa0BQUBBOnz6t6p+r9OrVK1hZWeVoXK6urlqX53Qc9+/fBwBVF5G03NzccOLECbVlJiYmsLW1VVtWtGhRvHjxIkvPJzIYrMnc3Bz16tVT3V+/fj0ePXqEiRMn4tChQxg3bhw2bdoEhUKBbt26oWLFivDy8tLYNi8gJKKChi3QRFRgGRkZoU6dOpg7dy5WrVqFpKQk/PbbbwCkiw2bNWuGp0+fYvHixfjzzz8REhKCUaNGAZCGUfuQjBK7jC6+0zbiRk7E8an09fU/+rE2NjZZSrTj4uLw1VdfYf78+ShSpAi2bNmCgIAAtG/fHn5+fggICMDPP/+s8biXL1+iePHiHx0fEZEc2AJNRIVC7dq1AQCxsbEAgN27dyMhIQF//PEHSpcurSp35MgRjcdmlCgruy68fPlS7aI8ZQtwVuREHOk5OzsDkC5a9Pb2Vlt348YN1fqc4Obmhnv37n2w3MyZM+Hq6oru3bsDAB4+fKh2YaCjo6PGaBsxMTFITExEpUqVcixeIqK8wBZoIipQjhw5orVLwd69ewH8161B2eqatuyrV6+wfv16jccWKVIEL1++1FhetmxZAMCxY8dUy968eYMff/wxy/HmRBzp1a5dG3Z2dli9ejUSEhJUy/ft24eIiAi0adMmy/F9yGeffYarV6+qPU96N2/exPLlyxEcHKz6EVCiRAlcv35dVSYiIgL29vZqj7t48SIAoEGDBjkWLxFRXmALNBEVKMOGDcPbt2/RoUMHuLm5ITExEadOncLWrVvh4uKCPn36AAB8fX1hZGSEzz//HIMGDUJ8fDzWrVsHOzs7VSu1Uq1atbBq1SrMnj0b5cqVg52dHby9veHr64vSpUujX79+GDduHPT19fHDDz/A1tYWDx48yFK8ORFHeoaGhliwYAH69OkDT09PfPHFF6ph7FxcXFTdQ3KCn58fZs2ahaNHj8LX11drmVGjRqFLly6oW7euallAQAD8/PwwefJkAFJL/J49e9QeFxISgtKlS3MIOyL6v/buGEVhIIzi+GwTBZPGbiyChYVVwMpD5AamELRUb2Av09jZ2ljZiSCewiPYiIgeQt5WW2SNy86u7Cr8f+0Mw1c+hsnL6/nXDhAA8LTdbtXr9dRsNhWGoYIgUKPR0Gg00uVyye1dr9dKkkTlcln1el3OOc3n85sKuvP5rDRNFUWRjDG5Krndbqd2u60gCBTHsabT6d0auzRNC2f+7Ryfa+w+LJdLtVotlUolVatVZVmm4/GY29PtdlWpVG5mulfRVyRJEvX7/cK1zWajMAx1Op1u1iaTiWq1mqy1cs7l1q7Xq6y1Go/H35oBAJ7Jm3Tn82oAAIwxi8XCDAYDczgcCv8A+ROr1cp0Oh2z3++NtfYhZwLAX+ENNADgS1mWmTiOzWw2e9iZzjkzHA4JzwBeEjfQAAAAgAduoAEAAAAPBGgAAADAAwEaAAAA8ECABgAAADwQoAEAAAAPBGgAAADAAwEaAAAA8ECABgAAADwQoAEAAAAPBGgAAADAwzu3H15r3obmXAAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "from scipy.stats import linregress\n", + "import matplotlib.pyplot as plt\n", + "import numpy as np\n", + "\n", + "plt.figure(figsize=(8, 6))\n", + "plt.rcParams.update({'font.size': 12})\n", + "colors = ['orange', 'blue', 'green', 'red', 'purple', 'brown', 'pink', 'gray', 'olive', 'cyan']\n", + "\n", + "offset = 360\n", + "coef = 80\n", + "\n", + "# Plot a horizontal line for the offset angle\n", + "plt.axhline(y=offset, color='black', linestyle='--', label=f'Offset angle ({offset}°)')\n", + "plt.axhline(y=0, color='black', linestyle='-')\n", + "plt.axvline(x=0, color='black', linestyle='-')\n", + "\n", + "# Create a list to store slopes for different saturation values\n", + "slopes = []\n", + "\n", + "# Plot each saturation value\n", + "for k, sat in enumerate(df['Saturation'].unique()):\n", + " df_sub = df[(df['Offset Angle'] == float(offset)) \n", + " & (df['Coefficient'] == int(coef)) \n", + " & (df['Saturation'] == int(sat))]\n", + " \n", + " if len(df_sub) > 0:\n", + " # Normalize timestamp to start from 0\n", + " df_sub = df_sub.copy() # Create a copy to avoid SettingWithCopyWarning\n", + " df_sub[\"timestamp\"] = df_sub[\"timestamp\"].astype(float) - float(df_sub[\"timestamp\"].iloc[0])\n", + " \n", + " # Calculate slope using linregress between time and SWA\n", + " x = df_sub['timestamp'].values\n", + " y = df_sub[\"SWA (Measured)\"].values\n", + " slope, intercept = np.polyfit(x, y, 1)\n", + " slopes.append((sat, slope))\n", + " \n", + " plt.plot(df_sub['timestamp'], df_sub[\"SWA (Measured)\"],\n", + " marker='.', color=colors[k % len(colors)], \n", + " label=f'Sat={sat}%: slope={slope:.2f}°/s')\n", + " \n", + "plt.xlabel(\"Time (s)\")\n", + "plt.ylabel(\"Steering Wheel Angle (degree)\")\n", + "plt.ylim(-460, 460)\n", + "plt.title(f\"SWA Measurements (Offset={offset}°, Coefficient={coef}%)\")\n", + "plt.tight_layout()\n", + "plt.legend(loc='best')\n", + "plt.grid(True)\n", + "\n", + "# Optional: Add a small subplot showing the relationship between saturation and slope\n", + "if len(slopes) > 1:\n", + " plt.figure(figsize=(6, 4))\n", + " sat_values = [s[0] for s in slopes]\n", + " slope_values = [s[1] for s in slopes]\n", + " plt.plot(sat_values, slope_values, 'o-', color='blue')\n", + " plt.xlabel('Saturation (%)')\n", + " plt.ylabel('Response Rate (°/s)')\n", + " plt.title(f'Effect of Saturation on SWA Response Rate (Offset={offset}°, Coef={coef}%)')\n", + " plt.grid(True)" + ] + }, + { + "cell_type": "code", + "execution_count": 56, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "from scipy.stats import linregress\n", + "\n", + "plt.figure(figsize=(40, 40))\n", + "plt.rcParams.update({'font.size': 10})\n", + "colors = ['orange', 'blue', 'green', 'red', 'purple', 'brown', 'pink', 'gray', 'olive', 'cyan']\n", + "\n", + "n_col = len(df['Coefficient'].unique())\n", + "n_row = len(df['Offset Angle'].unique())\n", + "\n", + "for i, offset in enumerate(df['Offset Angle'].unique()):\n", + " for j, coef in enumerate(df['Coefficient'].unique()):\n", + " plt.subplot(n_row, n_col, i * n_col + j + 1)\n", + "\n", + " # Plot a horizontal line for the offset angle\n", + " plt.axhline(y=offset, color='black', linestyle='--', label=f'Offset angle ({offset}°)')\n", + " plt.axhline(y=0, color='black', linestyle='-')\n", + " plt.axvline(x=0, color='black', linestyle='-')\n", + "\n", + " # Plot each saturation value\n", + " for k, sat in enumerate(df['Saturation'].unique()):\n", + " df_sub = df[(df['Offset Angle'] == float(offset)) \n", + " & (df['Coefficient'] == int(coef)) \n", + " & (df['Saturation'] == int(sat))]\n", + " \n", + " if len(df_sub) > 0:\n", + " # Normalize timestamp to start from 0\n", + " df_sub = df_sub.copy() # Create a copy to avoid SettingWithCopyWarning\n", + " df_sub[\"timestamp\"] = df_sub[\"timestamp\"].astype(float) - float(df_sub[\"timestamp\"].iloc[0])\n", + " \n", + " # Calculate slope using linregress between time and SWA\n", + " x = df_sub['timestamp'].values\n", + " y = df_sub[\"SWA (Measured)\"].values\n", + " slope, intercept = np.polyfit(x, y, 1)\n", + " \n", + " plt.plot(df_sub['timestamp'], df_sub[\"SWA (Measured)\"],\n", + " marker='.', color=colors[k % len(colors)], \n", + " label=f'Sat={sat}%: slope={slope:.2f}°/s')\n", + " \n", + " plt.xlabel(\"Time (s)\")\n", + " plt.ylabel(\"Steering Wheel Angle (degree)\")\n", + " plt.ylim(-500, 500)\n", + " plt.title(f\"Offset={offset}°, Coefficient={coef}%\")\n", + " plt.tight_layout()\n", + " plt.legend(loc='best', fancybox=True, framealpha=0.5)\n", + " plt.grid(True)\n", + "\n", + "\n", + "# plt.tight_layout()\n", + "plt.show()\n", + "plt.close()" + ] + }, + { + "cell_type": "code", + "execution_count": 70, + "metadata": {}, + "outputs": [], + "source": [ + "def lighten_color(color, amount=0.5):\n", + " \"\"\"\n", + " Lightens the given color by multiplying (1-luminosity) by the given amount.\n", + " Input can be matplotlib color string, hex string, or RGB tuple.\n", + "\n", + " Examples:\n", + " >> lighten_color('g', 0.3)\n", + " >> lighten_color('#F034A3', 0.6)\n", + " >> lighten_color((.3,.55,.1), 0.5)\n", + " \"\"\"\n", + " import matplotlib.colors as mc\n", + " import colorsys\n", + " try:\n", + " c = mc.cnames[color]\n", + " except:\n", + " c = color\n", + " c = colorsys.rgb_to_hls(*mc.to_rgb(c))\n", + " return colorsys.hls_to_rgb(c[0], 1 - amount * (1 - c[1]), c[2])" + ] + }, + { + "cell_type": "code", + "execution_count": 89, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "C:\\Users\\phuongnam-d\\AppData\\Local\\Temp\\ipykernel_28368\\384772607.py:13: SettingWithCopyWarning: \n", + "A value is trying to be set on a copy of a slice from a DataFrame.\n", + "Try using .loc[row_indexer,col_indexer] = value instead\n", + "\n", + "See the caveats in the documentation: https://pandas.pydata.org/pandas-docs/stable/user_guide/indexing.html#returning-a-view-versus-a-copy\n", + " df_sub[\"timestamp\"] = df_sub[\"timestamp\"] - df_sub[\"timestamp\"].iloc[0]\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "plt.figure(figsize=(80, 10))\n", + "plt.rcParams.update({'font.size': 20})\n", + "\n", + "n_row = len(df['Saturation'].unique())\n", + "n_col = len(df['Coefficient'].unique())\n", + "\n", + "colors = ['orange', 'blue', 'green', 'red', 'purple', 'brown', 'pink', 'gray', 'olive', 'cyan']\n", + "\n", + "for j, coef in enumerate(df['Coefficient'].unique()):\n", + " plt.subplot(1, n_col, j + 1)\n", + " for i, sat in enumerate(df['Saturation'].unique()):\n", + " df_sub = df[(df['Saturation'] == sat) & (df['Coefficient'] == coef)]\n", + " df_sub[\"timestamp\"] = df_sub[\"timestamp\"] - df_sub[\"timestamp\"].iloc[0]\n", + " \n", + " plt.plot(df_sub['timestamp'], df_sub[\"Offset Angle\"], \n", + " color=colors[i], marker='.', label=f'Offset angle at saturation={sat}%')\n", + " \n", + " plt.plot(df_sub['timestamp'], df_sub[\"SWA (Measured)\"],\n", + " color=lighten_color(colors[i], 0.5), marker='.', label=f'Measured SWA at saturation={sat}%')\n", + " \n", + " plt.xlabel(\"Time (s)\")\n", + " plt.ylabel(\"Angle (degree)\")\n", + " plt.title(f\"Coef={coef}\")\n", + " plt.tight_layout()\n", + " plt.legend(loc='upper center', bbox_to_anchor=(0.5, -0.05), fancybox=True, ncol=1)\n", + " plt.grid()\n", + " \n", + "\n", + "# plt.tight_layout()\n", + "\n", + "plt.show()\n", + "plt.close()" + ] + }, + { + "cell_type": "code", + "execution_count": 79, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "C:\\Users\\phuongnam-d\\AppData\\Local\\Temp\\ipykernel_28368\\1343865490.py:13: SettingWithCopyWarning: \n", + "A value is trying to be set on a copy of a slice from a DataFrame.\n", + "Try using .loc[row_indexer,col_indexer] = value instead\n", + "\n", + "See the caveats in the documentation: https://pandas.pydata.org/pandas-docs/stable/user_guide/indexing.html#returning-a-view-versus-a-copy\n", + " df_sub[\"timestamp\"] = df_sub[\"timestamp\"] - df_sub[\"timestamp\"].iloc[0]\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "plt.figure(figsize=(80, 20))\n", + "plt.rcParams.update({'font.size': 20})\n", + "\n", + "n_col = len(df['Saturation'].unique())\n", + "n_row = len(df['Coefficient'].unique())\n", + "\n", + "colors = ['orange', 'blue', 'green', 'red', 'purple', 'brown', 'pink', 'gray', 'olive', 'cyan']\n", + "\n", + "for i, sat in enumerate(df['Saturation'].unique()):\n", + " plt.subplot(1, n_col, i + 1)\n", + " for j, coef in enumerate(df['Coefficient'].unique()):\n", + " df_sub = df[(df['Saturation'] == sat) & (df['Coefficient'] == coef)]\n", + " df_sub[\"timestamp\"] = df_sub[\"timestamp\"] - df_sub[\"timestamp\"].iloc[0]\n", + " \n", + " plt.plot(df_sub['timestamp'], df_sub[\"Offset Angle\"], \n", + " color=colors[j], label=f'Offset angle at coef={coef}%')\n", + " \n", + " plt.plot(df_sub['timestamp'], df_sub[\"SWA (Measured)\"],\n", + " color=lighten_color(colors[j], 0.5), label=f'Measured SWA at coef={coef}%')\n", + " \n", + " plt.xlabel(\"Time (s)\")\n", + " plt.ylabel(\"Angle (degree)\")\n", + " plt.title(f\"Sat={sat}\")\n", + " plt.tight_layout()\n", + " plt.legend(loc='upper center', bbox_to_anchor=(0.5, -0.05), fancybox=True, ncol=1)\n", + " plt.grid()\n", + " \n", + "\n", + "# plt.tight_layout()\n", + "\n", + "plt.show()\n", + "plt.close()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Plots the relationship between measured data\n", + "1. Input: (logitech) steering wheel angle offset ~ Measured: (logitech) steering wheel angle\n", + "2. Input: (logitech) steering wheel angle ~ Measured: (carla) steering input\n", + "3. Input: (carla) steering input ~ Measured: (carla) steering angle \n", + "4. Input: (carla) steering angle ~ Measured: change of yaw angles (vehicle angle)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Linear Relation: Y = 5.071472 * X + -43.396379\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import pandas as pd\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from sklearn.linear_model import LinearRegression\n", + "\n", + "df = pd.read_excel('./data/vehicle_logs/forward_2.xlsx')\n", + "# df = df.iloc[410:410+42*30]\n", + "# df = df.iloc[310:310+42*30]\n", + "\n", + "# Extract X and Y\n", + "X = df[['LocationX']] # Feature must be 2D\n", + "Y = df['LocationY'] # Target can be 1D\n", + "# Linear Regression Model\n", + "model = LinearRegression()\n", + "model.fit(X, Y)\n", + "\n", + "# Coefficient and Intercept\n", + "slope = model.coef_[0]\n", + "intercept = model.intercept_\n", + "\n", + "print(f\"Linear Relation: Y = {slope:.6f} * X + {intercept:.6f}\")\n", + "\n", + "# Predicted Y values\n", + "Y_pred = model.predict(X)\n", + "\n", + "# Plot the data and linear fit\n", + "# show equation on the plot\n", + "\n", + "plt.scatter(X, Y, color='blue', label='Data Points')\n", + "plt.plot(X, Y_pred, color='red', label='Linear Fit')\n", + "plt.text(0, 0, f'Y = {slope:.6f} * X + {intercept:.6f}', fontsize=14, color='red')\n", + "plt.xlabel('steering_input')\n", + "plt.ylabel('changes of transformYaw')\n", + "plt.title('Linear Relationship')\n", + "plt.legend()\n", + "plt.grid(True)\n", + "plt.show()\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Plot the path from trial files" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Mean P_0= [ -2.28414266 -31.76363449] std: [0.69571586 1.59066774]\n", + "Mean P_d= [ 1.3190975 -17.71419983] std: [1.28412121 0.94453664]\n", + "Mean P_f= [ -7.52827587 -21.45773392] std: [0.24394655 0.18573103]\n", + "Mean yaw_0= 1.0251007000000016 std: 3.025966799170614\n", + "Mean yaw_d= 51.23525617400001 std: 9.297417441007045\n", + "Mean yaw_f= 91.296984836 std: 0.7554986672489944\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "\n", + "import numpy as np\n", + "import pandas as pd\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use('default')\n", + "\n", + "colors = ['b', 'g', 'r', 'c', 'm', 'y', 'k', 'w']\n", + "\n", + "plt.figure(figsize=(5,5))\n", + "plt.title('LocationX and LocationY in trials')\n", + "\n", + "backward_range = range(0, 6)\n", + "forward_range = range(7, 12)\n", + "\n", + "range_ = forward_range\n", + "\n", + "paths = {}\n", + "P_0 = []\n", + "P_d = []\n", + "P_f = []\n", + "yaw_0 = []\n", + "yaw_d = []\n", + "yaw_f = []\n", + "\n", + "for i in range_:\n", + " df = pd.read_excel(f'../data/trials/trial{i + 1}.xlsx')\n", + " x = df['LocationX'].to_list()\n", + " y = df['LocationY'].to_list()\n", + " yaw = df['RotationYaw'].to_list()\n", + " \n", + " paths[f'trial{i}'] = [(x_t, y_t) for x_t, y_t in zip(x, y)]\n", + " \n", + " P_0.append([x[0], y[0]])\n", + " P_d.append([max(x), y[x.index(max(x))]])\n", + " P_f.append([min(x), y[x.index(min(x))]])\n", + " yaw_0.append(90 - yaw[0])\n", + " yaw_d.append(90 - yaw[x.index(max(x))])\n", + " yaw_f.append(90 - yaw[x.index(min(x))])\n", + " \n", + " plt.plot(y, x, color=colors[i%len(range_)], label=f'trial{i}')\n", + " plt.plot(y[0], x[0], 'ro')\n", + " plt.plot(y[x.index(min(x))], min(x), 'go')\n", + " plt.plot(y[x.index(max(x))], max(x), 'bo') # turning point\n", + " \n", + "P_0 = np.array(P_0)\n", + "P_d = np.array(P_d)\n", + "P_f = np.array(P_f)\n", + "yaw_0 = np.array(yaw_0)\n", + "yaw_d = np.array(yaw_d)\n", + "yaw_f = np.array(yaw_f)\n", + "\n", + "print(\"Mean P_0= \", np.mean(P_0, axis=0), \"std: \", np.std(P_0, axis=0))\n", + "print(\"Mean P_d= \", np.mean(P_d, axis=0), \"std: \", np.std(P_d, axis=0))\n", + "print(\"Mean P_f= \", np.mean(P_f, axis=0), \"std: \", np.std(P_f, axis=0))\n", + "print(\"Mean yaw_0= \", np.mean(yaw_0), \"std: \", np.std(yaw_0))\n", + "print(\"Mean yaw_d= \", np.mean(yaw_d), \"std: \", np.std(yaw_d))\n", + "print(\"Mean yaw_f= \", np.mean(yaw_f), \"std: \", np.std(yaw_f))\n", + " \n", + "plt.xlabel('Y (m)')\n", + "plt.ylabel('X (m)')\n", + "\n", + "plt.legend()\n", + "\n", + "plt.grid()\n", + "plt.show()\n", + "plt.close()" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# preprocess paths, remove outliers,and duplicate points\n", + "from os import path\n", + "from scipy import interpolate\n", + "import numpy as np\n", + "import pandas as pd\n", + "\n", + "path_data = {}\n", + "\n", + "for i in range_:\n", + " df = pd.read_excel(f'../data/trials/trial{i + 1}.xlsx')\n", + " X = df['LocationX']\n", + " Y = df['LocationY']\n", + " \n", + " P_0 = [X[0], Y[0]]\n", + " P_d = [max(X), Y[X.idxmax()]]\n", + " P_f = [min(X), Y[X.idxmin()]]\n", + " \n", + " for j in range(1, X.idxmax()):\n", + " changes_x = X.diff().fillna(0)[j]\n", + " changes_y = Y.diff().fillna(0)[j]\n", + "\n", + " if (-1 if range_ == backward_range else 1) * changes_y > 0 and abs(changes_y) > 1e-3:\n", + " path_data.setdefault(f'trial{i + 1}', []).append([X[j], Y[j]])\n", + " \n", + " for j in range(X.idxmax(), X.idxmin()):\n", + " changes_x = X.diff().fillna(0)[j]\n", + " changes_y = Y.diff().fillna(0)[j]\n", + " \n", + " if changes_x < 0 and abs(changes_x) > 1e-3:\n", + " path_data.setdefault(f'trial{i + 1}', []).append([X[j], Y[j]]) \n", + "\n", + "plt.figure(figsize=(5,5))\n", + "for i in range(len(path_data)):\n", + " path = np.array(path_data[f'trial{i + 1 + list(range_)[0]}'])\n", + " # path = np.unique(path, axis=0)\n", + " x, y = path[:, 0], path[:, 1]\n", + " plt.plot(y, x, color=colors[i], label=f'trial{i + 1}')\n", + " plt.plot(y[0], x[0], 'ro')\n", + " plt.plot(y[np.argmin(x)], min(x), 'go')\n", + " plt.plot(y[np.argmax(x)], max(x), 'bo') \n", + " \n", + " \n", + "plt.xlabel('Y (m)')\n", + "plt.ylabel('X (m)')\n", + "\n", + "plt.legend()\n", + "\n", + "plt.grid()\n", + "plt.show()\n", + "plt.close()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "(142, 2)\n", + "46 141\n", + "Mean P_0= [-2.284308814, -31.734065629999996]\n", + "Mean P_d= [0.409550333177305, -18.459612079588652]\n", + "Mean P_f= [-7.449310874, -21.459648512]\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "\n", + "def resample_path(path, num_points):\n", + " \"\"\"Resample a path to a specified number of points using linear interpolation.\"\"\"\n", + " # Separate x and y coordinates\n", + " x = np.array([p[0] for p in path])\n", + " y = np.array([p[1] for p in path])\n", + " \n", + " # Create interpolation functions\n", + " t = np.linspace(0, 1, len(path)) # Parameterize original points\n", + " t_new = np.linspace(0, 1, num_points) # New parameterization\n", + " \n", + " # Interpolate x and y separately\n", + " fx = interpolate.interp1d(t, x, kind='linear')\n", + " fy = interpolate.interp1d(t, y, kind='linear')\n", + " \n", + " x_new = fx(t_new)\n", + " y_new = fy(t_new)\n", + " \n", + " return list(zip(x_new, y_new))\n", + "\n", + "def compute_mean_path(paths, num_points=None):\n", + " \"\"\"Compute the mean path by resampling all paths and averaging.\"\"\"\n", + " if num_points is None:\n", + " # Use the length of the longest path by default\n", + " num_points = min(len(path) for path in paths)\n", + " \n", + " # Resample all paths to the same number of points\n", + " resampled_paths = [resample_path(path, num_points) for path in paths]\n", + " \n", + " # Convert to numpy array for easier averaging\n", + " resampled_array = np.array(resampled_paths) # Shape: (n_paths, num_points, 2)\n", + " \n", + " # Compute mean across paths (axis 0)\n", + " mean_path = np.mean(resampled_array, axis=0) # Shape: (num_points, 2)\n", + " \n", + " return mean_path\n", + "\n", + "def plot_paths(original_paths, mean_path):\n", + " \"\"\"Plot original paths and the mean path.\"\"\"\n", + " plt.figure()\n", + " \n", + " # Plot original paths\n", + " for i, path in enumerate(original_paths):\n", + " x, y = zip(*path)\n", + " plt.plot(y, x, 'o-', label=f'Path {i+1}', alpha=0.5)\n", + " \n", + " # Plot mean path\n", + " x_mean, y_mean = zip(*mean_path)\n", + " P_0 = [x_mean[0], y_mean[0]]\n", + " P_d = [max(x_mean), y_mean[np.argmax(x_mean)]]\n", + " P_f = [min(x_mean), y_mean[np.argmin(x_mean)]]\n", + " print(np.argmax(x_mean), np.argmin(x_mean))\n", + " print(\"Mean P_0= \", P_0)\n", + " print(\"Mean P_d= \", P_d)\n", + " print(\"Mean P_f= \", P_f)\n", + " plt.plot(y_mean, x_mean, 'k*-', label='Mean Path', linewidth=2)\n", + " \n", + " plt.legend()\n", + " plt.xlabel('Y')\n", + " plt.ylabel('X')\n", + " plt.title('Original Paths and Mean Path')\n", + " plt.grid(True)\n", + " plt.show()\n", + " \n", + "# Compute the mean path\n", + "mean_path = compute_mean_path(path_data.values())\n", + "print(mean_path.shape)\n", + "# Display results\n", + "with open('../data/paths/driving_path_right2left.txt', 'w') as f:\n", + " for point in mean_path:\n", + " f.write(f\"{point[0]},{point[1]}\\n\")\n", + "\n", + "# Visualize\n", + "plot_paths(path_data.values(), mean_path)" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "with open('../PythonAPI/data/paths/hitachi.txt', 'r') as f:\n", + " lines = f.readlines()\n", + " hitachi_path = []\n", + " for line in lines:\n", + " x, y = line.strip().split(',')\n", + " hitachi_path.append([float(x), float(y)])\n", + " hitachi_path = np.array(hitachi_path)\n", + "\n", + "plt.figure(figsize=(3, 3))\n", + "x, y = hitachi_path[:, 0], hitachi_path[:, 1]\n", + "plt.plot(y, x, 'r', label='Hitachi')\n", + "# plt.plot(y[0], x[0], 'ro')\n", + "# plt.plot(y[np.argmin(x)], min(x), 'go')\n", + "# plt.plot(y[np.argmax(x)], max(x), 'bo')\n", + "plt.xlabel('Y (m)')\n", + "plt.ylabel('X (m)')\n", + "plt.legend()\n", + "plt.grid()\n", + "plt.show()\n", + "plt.close()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "\n", + "def compute_tangents(points):\n", + " tangents = []\n", + " n = len(points)\n", + "\n", + " for i in range(n):\n", + " if i == 0:\n", + " dx, dy = points[i + 1][0] - points[i][0], points[i + 1][1] - points[i][1]\n", + " elif i == n - 1:\n", + " dx, dy = points[i][0] - points[i - 1][0], points[i][1] - points[i - 1][1]\n", + " else:\n", + " dx, dy = points[i + 1][0] - points[i - 1][0], points[i + 1][1] - points[i - 1][1]\n", + "\n", + " scale = 1\n", + " p1 = (points[i][0] - scale * dx, points[i][1] - scale * dy)\n", + " p2 = (points[i][0] + scale * dx, points[i][1] + scale * dy)\n", + "\n", + " tangents.append((p1, p2))\n", + "\n", + " return tangents\n", + "\n", + "def process_exist_path(path):\n", + " \"\"\"\n", + " Process an existing path consisting of a series of points and compute\n", + " tangent vectors at each point along the path.\n", + "\n", + " Args:\n", + " path: A list or numpy array of [x,y] coordinates that form a path\n", + "\n", + " Returns:\n", + " param: Dictionary containing the original path and computed tangent vectors\n", + " \"\"\"\n", + " path = np.array(path)\n", + " param = {\n", + " \"path\": path,\n", + " \"start_x\": path[0][0],\n", + " \"start_y\": path[0][1],\n", + " \"end_x\": path[-1][0],\n", + " \"end_y\": path[-1][1],\n", + " \"tangent\": compute_tangents(path),\n", + " }\n", + "\n", + " return param\n", + "\n", + "with open(\"../data/paths/driving_path_left2right.txt\", \"r\") as f:\n", + " data_left2right = f.readlines()\n", + " data_left2right = [line.strip().split(\",\") for line in data_left2right]\n", + " data_left2right = [[float(val) for val in line] for line in data_left2right]\n", + " data_left2right = np.array(data_left2right)\n", + "\n", + "with open(\"../data/paths/driving_path_right2left.txt\", \"r\") as f:\n", + " data_right2left = f.readlines()\n", + " data_right2left = [line.strip().split(\",\") for line in data_right2left]\n", + " data_right2left = [[float(val) for val in line] for line in data_right2left]\n", + " data_right2left = np.array(data_right2left)\n", + "\n", + "with open(\"../data/paths/hitachi.txt\", \"r\") as f:\n", + " data_hitachi = f.readlines()\n", + " data_hitachi = [line.strip().split(\",\") for line in data_hitachi]\n", + " data_hitachi = [[float(val) for val in line] for line in data_hitachi]\n", + " data_hitachi = np.array(data_hitachi)\n", + "\n", + "\n", + "\n", + "predefined_path = {\n", + " \"0\": {\n", + " \"P_0\": [-1.47066772, -13.22415039],\n", + " \"P_d\": [-0.37066772, -29.02415039],\n", + " \"P_f\": [-6.87066772, -21.62415039],\n", + " \"yaw_0\": 90 - (-90),\n", + " \"yaw_d\": 90 - (-80),\n", + " \"yaw_f\": 90 - 0,\n", + " \"forward paths\": None,\n", + " \"backward paths\": None,\n", + " },\n", + " \"1\": {\n", + " \"P_0\": [-2.376371583333333, -13.749357381666668],\n", + " \"P_d\": [-0.566469992644628, -27.297582133636364],\n", + " \"P_f\": [-7.7486732, -21.271947543333333],\n", + " \"yaw_0\": 90 - (88.97628786666667),\n", + " \"yaw_d\": 90 - (62.168829599999995),\n", + " \"yaw_f\": 90 - (-1.9554259149999922),\n", + " \"forward paths\": process_exist_path(data_left2right[:40]),\n", + " \"backward paths\": process_exist_path(data_left2right[40:]),\n", + " },\n", + " \"2\": {\n", + " \"P_0\": [-2.284308814, -31.734065629999996],\n", + " \"P_d\": [0.409550333177305, -18.459612079588652],\n", + " \"P_f\": [-7.449310874, -21.459648512],\n", + " \"yaw_0\": 90 - (-88.9748993),\n", + " \"yaw_d\": 90 - (-38.76474382600003),\n", + " \"yaw_f\": 90 - (1.296984835999993),\n", + " \"forward paths\": process_exist_path(data_right2left[:46]),\n", + " \"backward paths\": process_exist_path(data_right2left[46:]),\n", + " },\n", + " \"3\": {\n", + " \"P_0\": [],\n", + " \"P_d\": [1.035116, -18.325821],\n", + " \"P_f\": [-7.685114, -21.214608],\n", + " \"yaw_0\": None,\n", + " \"yaw_d\": 90 - (50),\n", + " \"yaw_f\": 90 - (0),\n", + " \"forward paths\": [],\n", + " \"backward paths\": process_exist_path(data_hitachi),\n", + " },\n", + "}\n", + "# predefined_path[\"1\"][\"forward paths\"]" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import matplotlib.pyplot as plt\n", + "import pandas as pd\n", + "import numpy as np\n", + "\n", + "plt.style.use('default')\n", + "\n", + "df = pd.read_csv(\"./logs/haptic_shared_control_log_2025-03-11_16-32-46.csv\")\n", + "data = df[[\"[Measured] Current Position ~ r(t) (m)_X\", \n", + " \"[Measured] Current Position ~ r(t) (m)_Y\", \n", + " \"[Measured] Current Yaw Angle ~ Phi(t) (deg)\"]].to_numpy()\n", + " \n", + "\n", + "# plot the path and the trajectory\n", + "plt.figure()\n", + "trajectory = predefined_path[\"3\"][\"backward paths\"][\"path\"]\n", + "plt.plot(trajectory[:, 1], trajectory[:, 0], 'r', label='trajectory')\n", + "plt.plot(data[:, 1], data[:, 0], 'b', label='path')\n", + "# for i, (x, y) in enumerate(zip(data[:, 1], data[:, 0])):\n", + "# plt.arrow(x, y, \n", + "# 0.03 * np.cos(np.radians(90 - data[:, 2][i])), \n", + "# 0.03 * np.sin(np.radians(90 - data[:, 2][i])), \n", + "# head_width=0.1, head_length=0.1, fc='red', ec='red')\n", + "plt.xlabel('Y (m)')\n", + "plt.ylabel('X (m)')\n", + "plt.legend()\n", + "plt.axis('equal')\n", + "plt.grid()\n", + "plt.show()\n", + "plt.close()\n", + " " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Plot driving results" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "\"\\n['Time (t)', '[Measured] Current Position ~ r(t) (m)_X',\\n '[Measured] Current Position ~ r(t) (m)_Y',\\n '[Measured] Steering Angles ~ delta(t) (deg)_FL',\\n '[Measured] Steering Angles ~ delta(t) (deg)_FR',\\n '[Measured] Current Yaw Angle ~ Phi(t) (deg)',\\n '[Measured] Steering Wheel Angle ~ Theta(t) (deg)',\\n '[Computed] Rotation direction ~ (CW/CCW)',\\n '[Computed] Turning Radius ~ R(delta) (m)',\\n '[Computed] Vehicle Steering Angle ~ Delta(t) (deg)',\\n '[Computed] Center of Rotation to WORLD ~ r_c(t) (m)_X',\\n '[Computed] Center of Rotation to WORLD ~ r_c(t) (m)_Y',\\n '[Computed] Current Error to Trajectory ~ e(t)',\\n '[Computed] Predicted Position ~ r_tp(t) (m)_X',\\n '[Computed] Predicted Position ~ r_tp(t) (m)_Y',\\n '[Computed] Change of Yaw Angle ~ Delta_phi(t) (deg)',\\n '[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)',\\n '[Computed] Predicted Error to Trajectory ~ eps_tp(t)',\\n '[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)',\\n '[Computed] Torque applied ~ Tau_das (N.m)']\\n\"" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "\"\"\"\n", + "['Time (t)', '[Measured] Current Position ~ r(t) (m)_X',\n", + " '[Measured] Current Position ~ r(t) (m)_Y',\n", + " '[Measured] Steering Angles ~ delta(t) (deg)_FL',\n", + " '[Measured] Steering Angles ~ delta(t) (deg)_FR',\n", + " '[Measured] Current Yaw Angle ~ Phi(t) (deg)',\n", + " '[Measured] Steering Wheel Angle ~ Theta(t) (deg)',\n", + " '[Computed] Rotation direction ~ (CW/CCW)',\n", + " '[Computed] Turning Radius ~ R(delta) (m)',\n", + " '[Computed] Vehicle Steering Angle ~ Delta(t) (deg)',\n", + " '[Computed] Center of Rotation to WORLD ~ r_c(t) (m)_X',\n", + " '[Computed] Center of Rotation to WORLD ~ r_c(t) (m)_Y',\n", + " '[Computed] Current Error to Trajectory ~ e(t)',\n", + " '[Computed] Predicted Position ~ r_tp(t) (m)_X',\n", + " '[Computed] Predicted Position ~ r_tp(t) (m)_Y',\n", + " '[Computed] Change of Yaw Angle ~ Delta_phi(t) (deg)',\n", + " '[Computed] Predicted Yaw Angle ~ Phi_tp(t) (deg)',\n", + " '[Computed] Predicted Error to Trajectory ~ eps_tp(t)',\n", + " '[Computed] Desired Steering Wheel Angle ~ Theta_d(t) (deg)',\n", + " '[Computed] Torque applied ~ Tau_das (N.m)']\n", + "\"\"\"" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.microsoft.datawrangler.viewer.v0+json": { + "columns": [ + { + "name": "index", + "rawType": "int64", + "type": "integer" + }, + { + "name": "Time", + "rawType": "float64", + "type": "float" + }, + { + "name": "X (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Y (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "FL_angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "FR_angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Yaw Angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Steering Wheel Angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Turning Radius (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Vehicle Steering Angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Center of Rotation to WORLD X (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Center of Rotation to WORLD Y (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Current Error to Trajectory (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Predicted Position X (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Predicted Position Y (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Change of Yaw Angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Predicted Yaw Angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Predicted Error to Trajectory (m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Desired Steering Wheel Angle (degree)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Torque applied (N.m)", + "rawType": "float64", + "type": "float" + }, + { + "name": "Rotate", + "rawType": "float64", + "type": "float" + }, + { + "name": "Velocity x", + "rawType": "float64", + "type": "float" + }, + { + "name": "Velocity y", + "rawType": "float64", + "type": "float" + }, + { + "name": "Velocity", + "rawType": "float64", + "type": "float" + } + ], + "conversionMethod": "pd.DataFrame", + "ref": "dbc4245c-7fd8-4e6d-a11b-e903b4ec4a3e", + "rows": [ + [ + "0", + "0.0", + "-2.379270553588867", + "-21.96433067321777", + "29.93121528625488", + "40.22526931762695", + "51.83530807495117", + "450.0", + "5.390966365051421", + "14.52524995617131", + "3.267615844968404", + "-4.287797224546324", + "0.975754649304067", + "8.658280334649856", + "-4.230747169304031", + "-53.29628741907857", + "105.1315954940297", + "-16.02582683174884", + "-12820.33956976522", + "-112.9978127803078", + "1.0", + null, + null, + null + ], + [ + "1", + "0.04765605926513672", + "-2.337891101837158", + "-21.85563850402832", + "29.90572547912598", + "40.18490219116211", + "53.27362823486328", + "450.0", + "5.396168091336068", + "14.51094068251818", + "3.378520088944184", + "-4.207639727751667", + "0.8791844267799674", + "8.766503349841589", + "-3.910543025913853", + "-54.39344074035522", + "107.6670689752185", + "-16.35908290347093", + "-13096.05264941563", + "-103.9298063043933", + "1.0", + "0.8682936102939705", + "2.2807628424485458", + "-2.4404534286011907" + ], + [ + "2", + "0.09727907180786133", + "-2.297539710998535", + "-21.74085807800293", + "29.90071868896484", + "40.17857360839844", + "54.77773666381836", + "450.0", + "5.397190816363971", + "14.50813065204356", + "3.4886637898622", + "-4.118117733813337", + "0.7776747533029554", + "8.86603676001707", + "-3.656026132405816", + "-54.64190305607509", + "109.4196397198935", + "-16.63046482922157", + "-13320.32034671189", + "-93.45217544415026", + "1.0", + "0.8131588303688969", + "2.3130483246370126", + "-2.451819698818207" + ], + [ + "3", + "0.14232397079467773", + "-2.266965389251709", + "-21.64668846130371", + "29.90596199035645", + "40.18869400024414", + "56.00201034545898", + "450.0", + "5.396119787761729", + "14.51107342822723", + "3.574937829331812", + "-4.042020321607257", + "0.6968104943354722", + "8.942563081261234", + "-3.488208152434987", + "-54.39979051095084", + "110.4018008564098", + "-16.81455585199205", + "-13472.31176525866", + "-84.65905365008058", + "1.0", + "0.6787521436283954", + "2.090572269387928", + "-2.19799838171322" + ], + [ + "4", + "0.18637704849243164", + "-2.233272314071655", + "-21.53364944458008", + "29.91835021972656", + "40.21023178100586", + "57.4618034362793", + "450.0", + "5.393590702631133", + "14.51802717876655", + "3.674547427268995", + "-3.948230220270827", + "0.5994506937671811", + "9.030649199569252", + "-3.313411764118948", + "-53.8155286061394", + "111.2773320424187", + "-17.0102438805732", + "-13633.76772654715", + "-73.67492340868533", + "1.0", + "0.7648290866581617", + "2.565973199402426", + "-2.677532818071495" + ] + ], + "shape": { + "columns": 23, + "rows": 5 + } + }, + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
TimeX (m)Y (m)FL_angle (degree)FR_angle (degree)Yaw Angle (degree)Steering Wheel Angle (degree)Turning Radius (m)Vehicle Steering Angle (degree)Center of Rotation to WORLD X (m)...Predicted Position Y (m)Change of Yaw Angle (degree)Predicted Yaw Angle (degree)Predicted Error to Trajectory (m)Desired Steering Wheel Angle (degree)Torque applied (N.m)RotateVelocity xVelocity yVelocity
00.000000-2.379271-21.96433129.93121540.22526951.835308450.05.39096614.5252503.267616...-4.230747-53.296287105.131595-16.025827-12820.339570-112.9978131.0NaNNaNNaN
10.047656-2.337891-21.85563929.90572540.18490253.273628450.05.39616814.5109413.378520...-3.910543-54.393441107.667069-16.359083-13096.052649-103.9298061.00.8682942.280763-2.440453
20.097279-2.297540-21.74085829.90071940.17857454.777737450.05.39719114.5081313.488664...-3.656026-54.641903109.419640-16.630465-13320.320347-93.4521751.00.8131592.313048-2.451820
30.142324-2.266965-21.64668829.90596240.18869456.002010450.05.39612014.5110733.574938...-3.488208-54.399791110.401801-16.814556-13472.311765-84.6590541.00.6787522.090572-2.197998
40.186377-2.233272-21.53364929.91835040.21023257.461803450.05.39359114.5180273.674547...-3.313412-53.815529111.277332-17.010244-13633.767727-73.6749231.00.7648292.565973-2.677533
\n", + "

5 rows × 23 columns

\n", + "
" + ], + "text/plain": [ + " Time X (m) Y (m) FL_angle (degree) FR_angle (degree) \\\n", + "0 0.000000 -2.379271 -21.964331 29.931215 40.225269 \n", + "1 0.047656 -2.337891 -21.855639 29.905725 40.184902 \n", + "2 0.097279 -2.297540 -21.740858 29.900719 40.178574 \n", + "3 0.142324 -2.266965 -21.646688 29.905962 40.188694 \n", + "4 0.186377 -2.233272 -21.533649 29.918350 40.210232 \n", + "\n", + " Yaw Angle (degree) Steering Wheel Angle (degree) Turning Radius (m) \\\n", + "0 51.835308 450.0 5.390966 \n", + "1 53.273628 450.0 5.396168 \n", + "2 54.777737 450.0 5.397191 \n", + "3 56.002010 450.0 5.396120 \n", + "4 57.461803 450.0 5.393591 \n", + "\n", + " Vehicle Steering Angle (degree) Center of Rotation to WORLD X (m) ... \\\n", + "0 14.525250 3.267616 ... \n", + "1 14.510941 3.378520 ... \n", + "2 14.508131 3.488664 ... \n", + "3 14.511073 3.574938 ... \n", + "4 14.518027 3.674547 ... \n", + "\n", + " Predicted Position Y (m) Change of Yaw Angle (degree) \\\n", + "0 -4.230747 -53.296287 \n", + "1 -3.910543 -54.393441 \n", + "2 -3.656026 -54.641903 \n", + "3 -3.488208 -54.399791 \n", + "4 -3.313412 -53.815529 \n", + "\n", + " Predicted Yaw Angle (degree) Predicted Error to Trajectory (m) \\\n", + "0 105.131595 -16.025827 \n", + "1 107.667069 -16.359083 \n", + "2 109.419640 -16.630465 \n", + "3 110.401801 -16.814556 \n", + "4 111.277332 -17.010244 \n", + "\n", + " Desired Steering Wheel Angle (degree) Torque applied (N.m) Rotate \\\n", + "0 -12820.339570 -112.997813 1.0 \n", + "1 -13096.052649 -103.929806 1.0 \n", + "2 -13320.320347 -93.452175 1.0 \n", + "3 -13472.311765 -84.659054 1.0 \n", + "4 -13633.767727 -73.674923 1.0 \n", + "\n", + " Velocity x Velocity y Velocity \n", + "0 NaN NaN NaN \n", + "1 0.868294 2.280763 -2.440453 \n", + "2 0.813159 2.313048 -2.451820 \n", + "3 0.678752 2.090572 -2.197998 \n", + "4 0.764829 2.565973 -2.677533 \n", + "\n", + "[5 rows x 23 columns]" + ] + }, + "execution_count": 29, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "from pprint import pp\n", + "import pandas as pd\n", + "df = pd.read_csv(\"./logs/haptic_shared_control_log_2025-03-11_16-32-46.csv\")\n", + "\n", + "df['Time (t)'] = df['Time (t)'] - df['Time (t)'][0]\n", + "df[\"Velocity x\"] = df[\"X (m)\"].diff().fillna(0) / df[\"Time\"].diff().fillna(0)\n", + "df[\"Velocity y\"] = df[\"Y (m)\"].diff().fillna(0) / df[\"Time\"].diff().fillna(0)\n", + "df[\"Velocity\"] = np.sqrt(df[\"Velocity x\"] ** 2 + df[\"Velocity y\"] **2) * (np.deg2rad(df[\"Change of Yaw Angle (degree)\"]) / (df[\"Rotate\"])) / np.abs((np.deg2rad(df[\"Change of Yaw Angle (degree)\"]) / (df[\"Rotate\"])))\n", + "df.head()" + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# plot velocity, rotate, and change of yaw angle\n", + "plt.figure(figsize=(12, 9))\n", + "plt.subplot(311)\n", + "plt.plot(df[\"Time\"], df[\"Velocity\"], label='V (m/s)')\n", + "plt.xlabel('Time (s)')\n", + "plt.ylabel('Velocity (m/s)')\n", + "plt.grid()\n", + "plt.legend()\n", + "\n", + "plt.subplot(312)\n", + "plt.plot(df[\"Time\"], df[\"Rotate\"], label='Rotate')\n", + "plt.xlabel('Time (s)')\n", + "plt.ylabel('Rotate')\n", + "plt.grid()\n", + "plt.legend()\n", + "\n", + "plt.subplot(313)\n", + "plt.plot(df[\"Time\"], df[\"Change of Yaw Angle (degree)\"], label='Change of Yaw Angle (degree)')\n", + "plt.xlabel('Time (s)')\n", + "plt.ylabel('Change of Yaw Angle (degree)')\n", + "plt.grid()\n", + "plt.legend()\n", + "\n", + "plt.tight_layout()\n", + "plt.show()\n", + "plt.close()\n", + "\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# **Bezier curve**\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "(4.06345498866564, 3.00464477, 1.66682792)" + ] + }, + "execution_count": 5, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# load from json\n", + "import json\n", + "from pprint import pprint\n", + "import numpy as np\n", + "with open('./HapticSharedControl/wheel_setting.json', 'r') as f:\n", + " Wheel_setting = json.load(f)\n", + "# pprint(Wheel_setting)\n", + "L = abs(Wheel_setting['wheels'][0]['position']['y'] - Wheel_setting['wheels'][2]['position']['y']) / 100\n", + "T = abs(Wheel_setting['wheels'][0]['position']['x'] - Wheel_setting['wheels'][1]['position']['x']) / 100\n", + "theta1 = np.radians(69.99)\n", + "theta2 = np.radians(47.95)\n", + "\n", + "R = (L/np.sin(theta2) + np.sqrt((L/np.tan(theta1) + T)**2 + L**2))/2\n", + "R, L, T" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [], + "source": [ + "from HapticSharedControl.path_planning import *\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use('default')\n", + "\n", + "P_0 = [-1.47066772, -13.22415039] # [y, x]\n", + "P_f = [-6.87066772, -21.62415039]\n", + "P_d = [-0.37066772 , -29.02415039]\n", + "\n", + "yaw_0 = 0\n", + "yaw_d = 10\n", + "yaw_f = 90\n", + "\n", + "vel = 2.0 # km/h\n", + "\n", + "# #plot points\n", + "# plt.figure()\n", + "\n", + "# plt.plot(P_0[1], P_0[0], 'go')\n", + "# plt.plot(P_d[1], P_d[0], 'bo')\n", + "# plt.plot(P_f[1], P_f[0], 'ro')\n", + "# plt.grid()\n", + "\n", + "# plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "n_points = 100\n", + "path1, control_points1, params1 = calculate_bezier_trajectory(\n", + " start_pos=P_0[::-1],\n", + " end_pos=P_d[::-1],\n", + " start_yaw=yaw_0,\n", + " end_yaw=yaw_d,\n", + " n_points=n_points,\n", + " turning_radius=R,\n", + " show_animation=False,\n", + ")\n", + "# backward so reverse the yaw angle (+180)\n", + "path2, control_points2, params2 = calculate_bezier_trajectory(\n", + " start_pos=P_d[::-1],\n", + " end_pos=P_f[::-1],\n", + " start_yaw=180 + yaw_d,\n", + " end_yaw=180 + yaw_f,\n", + " n_points=n_points,\n", + " turning_radius=R,\n", + " show_animation=False,\n", + ")\n", + "\n", + "# show 2 path in same plot\n", + "plt.figure()\n", + "plt.plot(path1.T[0], path1.T[1], label=\"Bezier Path 1\")\n", + "plt.plot(control_points1.T[0], control_points1.T[1], \"--o\", label=\"Control Points 1\")\n", + "plt.plot(params1[\"x_target\"], params1[\"y_target\"])\n", + "plt.plot(params1[\"tangent\"][-1][:, 0], params1[\"tangent\"][-1][:, 1], label=\"Tangent 1\")\n", + "plt.plot(params1[\"normal\"][-1][:, 0], params1[\"normal\"][-1][:, 1], label=\"Normal 1\")\n", + "plt.gca().add_artist(params1[\"circle\"])\n", + "plot_arrow(\n", + " params1[\"start_x\"],\n", + " params1[\"start_y\"],\n", + " np.pi - params1[\"start_yaw\"],\n", + " length=0.1 * params1[\"dist\"],\n", + " width=0.02 * params1[\"dist\"],\n", + ")\n", + "plot_arrow(\n", + " params1[\"end_x\"],\n", + " params1[\"end_y\"],\n", + " np.pi - params1[\"end_yaw\"],\n", + " length=0.1 * params1[\"dist\"],\n", + " width=0.02 * params1[\"dist\"],\n", + ")\n", + "\n", + "plt.plot(path2.T[0], path2.T[1], label=\"Bezier Path 2\")\n", + "plt.plot(control_points2.T[0], control_points2.T[1], \"--o\", label=\"Control Points 2\")\n", + "plt.plot(params2[\"x_target\"], params2[\"y_target\"])\n", + "plt.plot(params2[\"tangent\"][-1][:, 0], params2[\"tangent\"][-1][:, 1], label=\"Tangent 2\")\n", + "plt.plot(params2[\"normal\"][-1][:, 0], params2[\"normal\"][-1][:, 1], label=\"Normal 2\")\n", + "plt.gca().add_artist(params2[\"circle\"])\n", + "plot_arrow(\n", + " params2[\"start_x\"],\n", + " params2[\"start_y\"],\n", + " np.pi - params2[\"start_yaw\"],\n", + " length=0.1 * params2[\"dist\"],\n", + " width=0.02 * params2[\"dist\"],\n", + ")\n", + "plot_arrow(\n", + " params2[\"end_x\"],\n", + " params2[\"end_y\"],\n", + " np.pi - params2[\"end_yaw\"],\n", + " length=0.1 * params2[\"dist\"],\n", + " width=0.02 * params2[\"dist\"],\n", + ")\n", + "\n", + "plt.legend()\n", + "plt.grid(True)\n", + "plt.show()\n", + "plt.axis('square')\n", + "plt.close()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Haptic shared control" + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "(4.06345498866564, 3.00464477, 1.66682792)" + ] + }, + "execution_count": 20, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "from HapticSharedControl.utils import *\n", + "from HapticSharedControl.haptic_algo import *\n", + "from HapticSharedControl.path_planning import *\n", + "\n", + "# load from json\n", + "import json\n", + "from pprint import pprint\n", + "import numpy as np\n", + "with open('./HapticSharedControl/wheel_setting.json', 'r') as f:\n", + " Wheel_setting = json.load(f)\n", + "# pprint(Wheel_setting)\n", + "L = abs(Wheel_setting['wheels'][0]['position']['y'] - Wheel_setting['wheels'][2]['position']['y']) / 100\n", + "T = abs(Wheel_setting['wheels'][0]['position']['x'] - Wheel_setting['wheels'][1]['position']['x']) / 100\n", + "theta1 = np.radians(69.99)\n", + "theta2 = np.radians(47.95)\n", + "\n", + "R = (L/np.sin(theta2) + np.sqrt((L/np.tan(theta1) + T)**2 + L**2))/2\n", + "R, L, T" + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": {}, + "outputs": [], + "source": [ + "\n", + "import matplotlib.pyplot as plt\n", + "\n", + "P_d = [-0.37066772 , -29.02415039]\n", + "P_f = [-6.87066772, -21.62415039]\n", + "\n", + "yaw_d = 10\n", + "yaw_f = 90\n", + "\n", + "n_points = 20\n", + "# backward so reverse the yaw angle (+180)\n", + "path2, control_points2, params2 = calculate_bezier_trajectory(\n", + " start_pos=P_d[::-1],\n", + " end_pos=P_f[::-1],\n", + " start_yaw=180 + yaw_d,\n", + " end_yaw=180 + yaw_f,\n", + " n_points=n_points,\n", + " turning_radius=R,\n", + " show_animation=False,\n", + ")\n" + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": {}, + "outputs": [], + "source": [ + "from scipy.spatial import KDTree\n", + "\n", + "def find_closest_point(given_point, list_of_points, method=\"KDTree\"):\n", + " # Convert list_of_points to a NumPy array for efficient processing\n", + " points = np.array(list_of_points)\n", + "\n", + " if method == \"KDTree\":\n", + " # Build a KD-Tree from the points\n", + " tree = KDTree(points)\n", + "\n", + " # Find the index of the nearest neighbor\n", + " _, nnidx = tree.query(given_point, k=1)\n", + " else:\n", + " # Find the index of the nearest neighbor\n", + " nnidx = np.argmin(np.linalg.norm(points - given_point, axis=1))\n", + " # Return the closest point using the found index\n", + " return list_of_points[nnidx], nnidx\n", + "\n", + "def distance_to_trajectory( position, trajectory):\n", + " # More robust distance calculation by checking multiple points\n", + " min_dist = float(\"inf\")\n", + " closest_point, idx = find_closest_point(position, trajectory)\n", + " return min(dist(position, closest_point), min_dist), closest_point, idx\n", + "\n", + "def get_sign_of_error(speed, position, trajectory_param):\n", + "\n", + " p1 = position\n", + " _, pt_index = find_closest_point(p1, trajectory_param[\"path\"])\n", + "\n", + " p2, p3 = trajectory_param[\"tangent\"][pt_index]\n", + " angle_rad = getAngle(p1, p2, p3, degrees=False)\n", + "\n", + " return (speed / np.abs(speed)) * (np.sin(angle_rad) / abs(np.sin(angle_rad)))\n" + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": {}, + "outputs": [], + "source": [ + "# test predict position\n", + "import numpy as np\n", + "import math\n", + "import matplotlib.pyplot as plt\n", + "\n", + "plt.style.use(\"default\")\n", + "\n", + "def rotation_matrix_cw(angle_rad):\n", + " return np.array(\n", + " [[np.cos(angle_rad), -np.sin(angle_rad)], [np.sin(angle_rad), np.cos(angle_rad)]]\n", + " )\n", + "\n", + "def getAngle(a, b, c, degrees=False):\n", + " angle_rad = math.atan2(c[1] - b[1], c[0] - b[0]) - math.atan2(a[1] - b[1], a[0] - b[0])\n", + " return math.degrees(angle_rad) if degrees else angle_rad\n", + "\n", + "def sign(x):\n", + " return x / np.abs(x) if x != 0 else 0\n", + "\n", + "def predict_position_(current_position, current_yaw_angle_deg, vehicle_steering_angle_deg, vel=2, tp=1):\n", + " wheelbase = 3 # meter\n", + " tire_width = 1.67 # meter\n", + " current_yaw_angle_rad = np.radians(current_yaw_angle_deg)\n", + " vehicle_steering_angle_rad = np.radians(vehicle_steering_angle_deg)\n", + "\n", + " center_of_mass = 0.45 * wheelbase\n", + "\n", + " # turning_radius = wheelbase / np.sin(abs(vehicle_steering_angle_rad)) # meter\n", + " turning_radius = np.sqrt(center_of_mass ** 2 + wheelbase ** 2 / np.tan(vehicle_steering_angle_rad) ** 2)\n", + " turning_angle_rad = np.arctan(0.45 * np.tan(vehicle_steering_angle_rad))\n", + " \n", + " print(\"Turning Radius:\", turning_radius)\n", + " # vehicle coordinates, origin at the center of mass\n", + " print(np.sin(current_yaw_angle_rad), np.cos(vehicle_steering_angle_rad))\n", + " rotating_direction = sign(np.sin(turning_angle_rad))\n", + " # -1 if clockwise, 1 if counter-clockwise\n", + " print(\"Rotating Direction:\", \"CW\" if rotating_direction == -1 else \"CCW\")\n", + " \n", + " center_of_rotation_with_vehicle = np.array(\n", + " [\n", + " wheelbase / np.tan(vehicle_steering_angle_rad),\n", + " -center_of_mass,\n", + " ]\n", + " )\n", + " print(\"[Vehicle] Center of Rotation in Vehicle:\", center_of_rotation_with_vehicle.round(3))\n", + " # transform the vehicle coordinates to the global coordinates, rotate and shift\n", + " center_of_rotation_with_world = rotation_matrix_cw(current_yaw_angle_rad - np.pi / 2).dot(\n", + " center_of_rotation_with_vehicle\n", + " ) + np.array(current_position)\n", + " print(\"[World] Center of Rotation:\", center_of_rotation_with_world.round(3))\n", + "\n", + " # # rotating around the center of rotation\n", + " # rotating_angle_rad = turning_angle_rad - np.pi / 2\n", + " print(\"Turning Angle:\", np.degrees(turning_angle_rad))\n", + " # calculate the predicted position\n", + " delta_phi_rad = - rotating_direction * vel * tp / turning_radius\n", + " # delta_phi_rad = - angular_speed * tp\n", + " delta_phi_deg = np.degrees(delta_phi_rad)\n", + " print(\"Delta Phi:\", delta_phi_deg)\n", + " \n", + " # predict_yaw_angle_deg = current_yaw_angle_deg + delta_phi_deg\n", + "\n", + " predict_yaw_angle_rad = current_yaw_angle_rad + delta_phi_rad\n", + " predict_yaw_angle_deg = np.degrees(predict_yaw_angle_rad)\n", + "\n", + " print(\"Predicted Yaw Angle:\", predict_yaw_angle_deg)\n", + " \n", + " predicted_position_in_world = center_of_rotation_with_world + turning_radius * np.array(\n", + " [\n", + " np.cos(predict_yaw_angle_rad - turning_angle_rad + rotating_direction * np.pi/2),\n", + " np.sin(predict_yaw_angle_rad - turning_angle_rad + rotating_direction * np.pi/2),\n", + " ]\n", + " )\n", + " \n", + " print(\"Predicted Position:\", predicted_position_in_world.round(3))\n", + " print(\"Delta phi (graph):\", getAngle(current_position, center_of_rotation_with_world, predicted_position_in_world, degrees=True))\n", + " \n", + " return predicted_position_in_world, center_of_rotation_with_world" + ] + }, + { + "cell_type": "code", + "execution_count": 60, + "metadata": {}, + "outputs": [], + "source": [ + "with open(\"../data/paths/hitachi.txt\", \"r\") as f:\n", + " data_hitachi = f.readlines()\n", + " data_hitachi = [line.strip().split(\",\") for line in data_hitachi]\n", + " data_hitachi = [[float(val) for val in line[::-1]] for line in data_hitachi]\n", + " data_hitachi = np.array(data_hitachi)\n", + " \n", + "with open(\"../data/paths/driving_path_left2right.txt\", \"r\") as f:\n", + " data_left2right = f.readlines()\n", + " data_left2right = [line.strip().split(\",\") for line in data_left2right]\n", + " data_left2right = [[float(val) for val in line] for line in data_left2right]\n", + " data_left2right = np.array(data_left2right)\n", + " data_left2right = process_exist_path(data_left2right[40:])[\"path\"]\n", + " " + ] + }, + { + "cell_type": "code", + "execution_count": 40, + "metadata": {}, + "outputs": [], + "source": [ + "def lighten_color(color, amount=0.5):\n", + " \"\"\"\n", + " Lightens the given color by multiplying (1-luminosity) by the given amount.\n", + " Input can be matplotlib color string, hex string, or RGB tuple.\n", + "\n", + " Examples:\n", + " >> lighten_color('g', 0.3)\n", + " >> lighten_color('#F034A3', 0.6)\n", + " >> lighten_color((.3,.55,.1), 0.5)\n", + " \"\"\"\n", + " import matplotlib.colors as mc\n", + " import colorsys\n", + " try:\n", + " c = mc.cnames[color]\n", + " except:\n", + " c = color\n", + " c = colorsys.rgb_to_hls(*mc.to_rgb(c))\n", + " return colorsys.hls_to_rgb(c[0], 1 - amount * (1 - c[1]), c[2])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Turning Radius: 5.368659050451984\n", + "0.03489949670250114 0.8660254037844387\n", + "Rotating Direction: CW\n", + "[Vehicle] Center of Rotation in Vehicle: [-5.196 -1.35 ]\n", + "[World] Center of Rotation: [ -6.581 -26.512]\n", + "Turning Angle: -14.56389115744601\n", + "Delta Phi: 10.67227010965776\n", + "Predicted Yaw Angle: 188.67227010965775\n", + "Predicted Position: [ -8.699 -21.579]\n", + "Delta phi (graph): 10.672270109657743\n", + "Turning Radius: 5.368659050451984\n", + "0.03489949670250114 0.8660254037844387\n", + "Rotating Direction: CW\n", + "[Vehicle] Center of Rotation in Vehicle: [-5.196 -1.35 ]\n", + "[World] Center of Rotation: [ -6.581 -26.512]\n", + "Turning Angle: -14.56389115744601\n", + "Delta Phi: 21.34454021931552\n", + "Predicted Yaw Angle: 199.34454021931552\n", + "Predicted Position: [ -9.576 -22.056]\n", + "Delta phi (graph): 21.344540219315512\n", + "Turning Radius: 5.368659050451984\n", + "0.03489949670250114 0.8660254037844387\n", + "Rotating Direction: CW\n", + "[Vehicle] Center of Rotation in Vehicle: [-5.196 -1.35 ]\n", + "[World] Center of Rotation: [ -6.581 -26.512]\n", + "Turning Angle: -14.56389115744601\n", + "Delta Phi: 32.016810328973285\n", + "Predicted Yaw Angle: 210.0168103289733\n", + "Predicted Position: [-10.349 -22.688]\n", + "Delta phi (graph): 32.01681032897329\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "curr_position = data_left2right[-1]\n", + "yaw = 178 # yaw angle to the x axis\n", + "steering_angle = -30\n", + "vel = 2.0\n", + "tp = 1\n", + "colors = [\"r\", \"g\", \"b\", \"c\", \"m\", \"y\", \"k\"]\n", + "plt.plot(data_left2right.T[0], data_left2right.T[1], label=\"Akhdan Path\", marker=\"o\", color='m')\n", + "plt.plot(curr_position[0], curr_position[1], \"ro\", label=\"Current Position\")\n", + "\n", + "for i, vel in enumerate([1.0, 2.0, 3.0]):\n", + " position_next, cow = predict_position_(curr_position, yaw, steering_angle, vel=vel, tp=tp)\n", + " # plot curve\n", + " plt.plot(cow[0], cow[1], marker='o', color='b', label=f\"Center of Rotation, vel={vel} m/s\")\n", + " plt.plot(position_next[0], position_next[1], marker='o', color=lighten_color('g', 1 - i/3) , label=f\"Predicted Position, vel={vel} m/s\")\n", + " circle = plt.Circle(\n", + " cow, math.hypot(cow[0] - curr_position[0], cow[1] - curr_position[1]), color=colors[i], fill=False\n", + " )\n", + " plt.gca().add_artist(circle)\n", + "plt.xlabel(\"Y (m)\")\n", + "plt.ylabel(\"X (m)\")\n", + "plt.grid()\n", + "plt.legend(loc='lower left')\n", + "plt.axis(\"square\")\n", + "plt.show()\n", + "plt.close()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "carla", + "language": "python", + "name": "carla" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.20" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/README.md b/README.md index 295c8e9..844a127 100644 --- a/README.md +++ b/README.md @@ -1,136 +1,136 @@ -# DReyeVR -### Welcome to DReyeVR, a VR driving simulator for behavioural and interactions research. - -[![Main Figure](Docs/Figures/demo.gif)](https://www.youtube.com/watch?v=yGIPSDOMGpY) - -[Submission Video Demonstration (YouTube)](https://www.youtube.com/watch?v=yGIPSDOMGpY) - - -[![Build Status](https://github.com/HARPLab/DReyeVR/actions/workflows/ci.yml/badge.svg)](https://github.com/HARPLab/DReyeVR/actions/workflows/ci.yml) - -This project extends the [`Carla`](https://github.com/carla-simulator/carla/tree/0.9.13) simulator to add virtual reality integration, a first-person maneuverable ego-vehicle, eye tracking support, and several immersion enhancements. - -If you have questions, hopefully our [F.A.Q. wiki page](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) and [issues page](https://github.com/HARPLab/DReyeVR/issues?q=is%3Aissue+is%3Aclosed) can answer some of them. - -**IMPORTANT:** Currently DReyeVR only supports Carla versions: [0.9.13](https://github.com/carla-simulator/carla/tree/0.9.13) with Unreal Engine 4.26 - -## Highlights -### Ego Vehicle -Fully drivable **virtual reality (VR) ego-vehicle** with [SteamVR integration](https://github.com/ValveSoftware/steamvr_unreal_plugin/tree/4.23) (see [EgoVehicle.h](DReyeVR/EgoVehicle.h)) -- SteamVR HMD head tracking (orientation & position) - - We have tested with the following devices: - | Device | VR Supported | Eye tracking | OS | - | --- | --- | --- | --- | - | [HTC Vive Pro Eye](https://business.vive.com/us/product/vive-pro-eye-office/) | :white_check_mark: | :white_check_mark: | Windows, Linux | - | [Quest 2](https://www.oculus.com/quest-2/) | :white_check_mark: | :x: | Windows | - - While we haven't tested other headsets, they should still work for basic VR usage (not eye tracking) if supported by SteamVR. - - Eye tracking is currently **ONLY** supported on the HTC Vive Pro Eye since we use [SRanipal](https://forum.htc.com/topic/5641-sranipal-faq/) for the eye-tracker SDK. We are happy to support more devices through contributions for adding other SDKs. -- Vehicle controls: - - Generic keyboard WASD + mouse - - Support for Logitech Steering wheel with this open source [LogitechWheelPlugin](https://github.com/HARPLab/LogitechWheelPlugin) - - Includes force-feedback with the steering wheel. - - We used a [Logitech G923 Racing Wheel & Pedals](https://www.logitechg.com/en-us/products/driving/driving-force-racing-wheel.html) - - Full list of supported devices can be found [here](https://github.com/HARPLab/LogitechWheelPlugin/blob/master/README.md) though we can't guarantee out-of-box functionality without testing. -- Realistic (and parameterizable) rear & side view mirrors - - WARNING: very performance intensive -- Vehicle dashboard: - - Speedometer (in miles-per-hour by default) - - Gear indicator - - Turn signals -- Dynamic steering wheel - - Adjustable parameters, responsive to steering input - - See our documentation on this [here](Docs/Model.md) -- "Ego-centric" audio - - Responsive engine revving (throttle-based) - - Turn signal clicks - - Gear switching - - Collisions -- Fully compatible with the existing Carla [PythonAPI](https://carla.readthedocs.io/en/0.9.13/python_api/) and [ScenarioRunner](https://github.com/carla-simulator/scenario_runner/tree/v0.9.13) - - Minor modifications were made. See [Usage.md](Docs/Usage.md) documentation. -- Fully compatible with the Carla [Recorder and Replayer](https://carla.readthedocs.io/en/0.9.13/adv_recorder/) - - Including HMD pose/orientation & sensor reenactment -- Ability to handoff/takeover control to/from Carla's AI wheeled vehicle controller -- Carla-based semantic segmentation camera (see [`Shaders/README.md`](Shaders/README.md)) -### Ego Sensor -Carla-compatible **ego-vehicle sensor** (see [EgoSensor.h](DReyeVR/EgoSensor.h)) is an "invisible sensor" that tracks the following: -- Real-time **Eye tracking** with the [HTC Vive Pro Eye](https://enterprise.vive.com/us/product/vive-pro-eye-office/) VR headset - - Eye tracker data includes: - - Timing information (based off headset, world, and eye-tracker) - - 3D Eye gaze ray (left, right, & combined) - - 2D Pupil position (left & right) - - Pupil diameter (left & right) - - Eye Openness (left & right) - - Focus point in the world & hit actor information - - See [DReyeVRData.h:EyeTracker](Carla/Sensor/DReyeVRData.h) for the complete list - - Eye reticle visualization in real time -- Real-time user inputs (throttle, steering, brake, turn signals, etc.) -- Image (screenshot) frame capture based on the camera - - Typically used in Replay rather than real-time because highly performance intensive. -- Fully compatible with the LibCarla data serialization for streaming to a PythonAPI client (see [LibCarla/Sensor](LibCarla/Sensor)) - - We have also tested and verified support for (`rospy`) ROS integration our sensor data streams - -### Other additions: -- Custom DReyeVR config file for one-time runtime params. See [DReyeVRConfig.ini](Configs/DReyeVRConfig.ini) - - Especially useful to change params without recompiling everything. - - Uses standard c++ io management to read the file with minimal performance impact. See [DReyeVRUtils.h](DReyeVR/DReyeVRUtils.h). -- World ambient audio - - Birdsong, wind, smoke, etc. (See [Docs/Sounds.md](Docs/Sounds.md)) -- Non-ego-centric audio (Engine revving from non-ego vehicles) -- Synchronized Replay with per-frame frame capture for post-hoc analysis (See [Docs/Usage.md](Docs/Usage.md)) -- Recorder/replayer media functions - - Added in-game keyboard commands Play/Pause/Forward/Backward/etc. -- Static in-environment directional signs for natural navigation (See [`Docs/Signs.md`](Docs/Signs.md)) -- Adding weather to the Carla recorder/replayer/query (See this [Carla PR](https://github.com/carla-simulator/carla/pull/5235)) -- Custom dynamic 3D actors with full recording support (eg. HUD indicators for direction, AR bounding boxes, visual targets, etc.). See [CustomActor.md](Docs/CustomActor.md) for more. -- (DEBUG ONLY) Foveated rendering for improved performance with gaze-aware (or fixed) variable rate shading - -## Install/Build -See [`Docs/Install.md`](Docs/Install.md) to: -- Install and build `DReyeVR` on top of a working `Carla` repository. -- Download plugins for `DReyeVR` required for fancy features such as: - - Eye tracking (SRanipal) - - Steering wheel/pedals (Logitech) -- Set up a `conda` environment for DReyeVR PythonAPI - -## OS compatibility -| OS | VR | Eye tracking | Audio | Keyboard+Mouse | Racing wheel | Foveated Rendering (Editor) | -| --- | --- | --- | --- | --- | --- | --- | -| Windows | :white_check_mark: | :white_check_mark: | :white_check_mark: | :white_check_mark: | :white_check_mark: | :white_check_mark: | -| Linux | :white_check_mark: | :x: | :white_check_mark: | :white_check_mark: | :x: | :x: | -| MacOS | :x: | :x: | :white_check_mark: | :white_check_mark: | :x: | :x: | -- While Windows (10) is recommended for optimized VR support, all our work translates to Linux systems except for the eye tracking and hardware integration which have Windows-only dependencies. - - Unfortunately the eye-tracking firmware is proprietary & does not work on Linux - - This is (currently) only supported on Windows because of some proprietary dependencies between [HTC SRanipal SDK](https://developer.vive.com/resources/knowledgebase/vive-sranipal-sdk/) and Tobii's SDK. Those interested in the Linux discussion for HTC's Vive Pro Eye Tracking can follow the subject [here (Vive)](https://forum.vive.com/topic/6994-eye-tracking-in-linux/), [here (Vive)](https://forum.vive.com/topic/7012-vive-pro-eye-on-ubuntu-16-or-18/), and [here (Tobii)](https://developer.tobii.com/community/forums/topic/vive-pro-eye-with-stream-engine/). - - Additionally, the [LogitechWheelPlugin](https://github.com/HARPLab/LogitechWheelPlugin) we use only has Windows support currently. Though it should be possible to use the G923 on Linux as per the [Arch Wiki](https://wiki.archlinux.org/title/Logitech_Racing_Wheel). -- Also, although MacOS is not officially supported by CARLA, we have development happening on an Apple Silicon machine and have active forks of CARLA + UE4.26 with MacOS 12+ support. Note that this is primarily for development, as it is the most limited system by far. - -## Documentation & Guides -- See [`F.A.Q. wiki`](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) for our Frequently Asked Questions wiki page. -- See [`Install.md`](Docs/Install.md) to install and build DReyeVR -- See [`Usage.md`](Docs/Usage.md) to learn how to use our provided DReyeVR features -- See [`Development.md`](Docs/Development.md) to get started with DReyeVR development and add new features -- See [`Docs/Tutorials/`](Docs/Tutorials/) to view several DReyeVR tutorials such as customizing the EgoVehicle, adding custom signs/props and more. - -## Citation -If you use our work, please cite the corresponding [paper](https://arxiv.org/abs/2201.01931): -```bibtex -@inproceedings{silvera2022dreyevr, - title={DReyeVR: Democratizing Virtual Reality Driving Simulation for Behavioural \& Interaction Research}, - author={Silvera, Gustavo and Biswas, Abhijat and Admoni, Henny}, - booktitle={Proceedings of the 2022 ACM/IEEE International Conference on Human-Robot Interaction}, - pages={639--643}, - year={2022} -} -``` - -## Acknowledgements - -- This project builds upon and extends the [CARLA simulator](https://carla.org/) -- This repo includes some code from CARLA: Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB) & Intel Corporation. -- This repo includes some code from Hewlett-Packard Development Company, LP. See [nvidia.ph](Tools/Diagnostics/collectl/nvidia.ph). This is a modified diagnostic tool used during development. - -## Licenses -- Custom DReyeVR code is distributed under the MIT License. -- Unreal Engine 4 follows its [own license terms](https://www.unrealengine.com/en-US/faq). -- Code used from other sources that is prefixed with a Copyright header belongs to those individuals/organizations. -- CARLA specific licenses (and dependencies) are described on their [GitHub](https://github.com/carla-simulator/carla#licenses) +# DReyeVR +### Welcome to DReyeVR, a VR driving simulator for behavioural and interactions research. + +[![Main Figure](Docs/Figures/demo.gif)](https://www.youtube.com/watch?v=yGIPSDOMGpY) + +[Submission Video Demonstration (YouTube)](https://www.youtube.com/watch?v=yGIPSDOMGpY) + + +[![Build Status](https://github.com/HARPLab/DReyeVR/actions/workflows/ci.yml/badge.svg)](https://github.com/HARPLab/DReyeVR/actions/workflows/ci.yml) + +This project extends the [`Carla`](https://github.com/carla-simulator/carla/tree/0.9.13) simulator to add virtual reality integration, a first-person maneuverable ego-vehicle, eye tracking support, and several immersion enhancements. + +If you have questions, hopefully our [F.A.Q. wiki page](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) and [issues page](https://github.com/HARPLab/DReyeVR/issues?q=is%3Aissue+is%3Aclosed) can answer some of them. + +**IMPORTANT:** Currently DReyeVR only supports Carla versions: [0.9.13](https://github.com/carla-simulator/carla/tree/0.9.13) with Unreal Engine 4.26 + +## Highlights +### Ego Vehicle +Fully drivable **virtual reality (VR) ego-vehicle** with [SteamVR integration](https://github.com/ValveSoftware/steamvr_unreal_plugin/tree/4.23) (see [EgoVehicle.h](DReyeVR/EgoVehicle.h)) +- SteamVR HMD head tracking (orientation & position) + - We have tested with the following devices: + | Device | VR Supported | Eye tracking | OS | + | --- | --- | --- | --- | + | [HTC Vive Pro Eye](https://business.vive.com/us/product/vive-pro-eye-office/) | :white_check_mark: | :white_check_mark: | Windows, Linux | + | [Quest 2](https://www.oculus.com/quest-2/) | :white_check_mark: | :x: | Windows | + - While we haven't tested other headsets, they should still work for basic VR usage (not eye tracking) if supported by SteamVR. + - Eye tracking is currently **ONLY** supported on the HTC Vive Pro Eye since we use [SRanipal](https://forum.htc.com/topic/5641-sranipal-faq/) for the eye-tracker SDK. We are happy to support more devices through contributions for adding other SDKs. +- Vehicle controls: + - Generic keyboard WASD + mouse + - Support for Logitech Steering wheel with this open source [LogitechWheelPlugin](https://github.com/HARPLab/LogitechWheelPlugin) + - Includes force-feedback with the steering wheel. + - We used a [Logitech G923 Racing Wheel & Pedals](https://www.logitechg.com/en-us/products/driving/driving-force-racing-wheel.html) + - Full list of supported devices can be found [here](https://github.com/HARPLab/LogitechWheelPlugin/blob/master/README.md) though we can't guarantee out-of-box functionality without testing. +- Realistic (and parameterizable) rear & side view mirrors + - WARNING: very performance intensive +- Vehicle dashboard: + - Speedometer (in miles-per-hour by default) + - Gear indicator + - Turn signals +- Dynamic steering wheel + - Adjustable parameters, responsive to steering input + - See our documentation on this [here](Docs/Model.md) +- "Ego-centric" audio + - Responsive engine revving (throttle-based) + - Turn signal clicks + - Gear switching + - Collisions +- Fully compatible with the existing Carla [PythonAPI](https://carla.readthedocs.io/en/0.9.13/python_api/) and [ScenarioRunner](https://github.com/carla-simulator/scenario_runner/tree/v0.9.13) + - Minor modifications were made. See [Usage.md](Docs/Usage.md) documentation. +- Fully compatible with the Carla [Recorder and Replayer](https://carla.readthedocs.io/en/0.9.13/adv_recorder/) + - Including HMD pose/orientation & sensor reenactment +- Ability to handoff/takeover control to/from Carla's AI wheeled vehicle controller +- Carla-based semantic segmentation camera (see [`Shaders/README.md`](Shaders/README.md)) +### Ego Sensor +Carla-compatible **ego-vehicle sensor** (see [EgoSensor.h](DReyeVR/EgoSensor.h)) is an "invisible sensor" that tracks the following: +- Real-time **Eye tracking** with the [HTC Vive Pro Eye](https://enterprise.vive.com/us/product/vive-pro-eye-office/) VR headset + - Eye tracker data includes: + - Timing information (based off headset, world, and eye-tracker) + - 3D Eye gaze ray (left, right, & combined) + - 2D Pupil position (left & right) + - Pupil diameter (left & right) + - Eye Openness (left & right) + - Focus point in the world & hit actor information + - See [DReyeVRData.h:EyeTracker](Carla/Sensor/DReyeVRData.h) for the complete list + - Eye reticle visualization in real time +- Real-time user inputs (throttle, steering, brake, turn signals, etc.) +- Image (screenshot) frame capture based on the camera + - Typically used in Replay rather than real-time because highly performance intensive. +- Fully compatible with the LibCarla data serialization for streaming to a PythonAPI client (see [LibCarla/Sensor](LibCarla/Sensor)) + - We have also tested and verified support for (`rospy`) ROS integration our sensor data streams + +### Other additions: +- Custom DReyeVR config file for one-time runtime params. See [DReyeVRConfig.ini](Configs/DReyeVRConfig.ini) + - Especially useful to change params without recompiling everything. + - Uses standard c++ io management to read the file with minimal performance impact. See [DReyeVRUtils.h](DReyeVR/DReyeVRUtils.h). +- World ambient audio + - Birdsong, wind, smoke, etc. (See [Docs/Sounds.md](Docs/Sounds.md)) +- Non-ego-centric audio (Engine revving from non-ego vehicles) +- Synchronized Replay with per-frame frame capture for post-hoc analysis (See [Docs/Usage.md](Docs/Usage.md)) +- Recorder/replayer media functions + - Added in-game keyboard commands Play/Pause/Forward/Backward/etc. +- Static in-environment directional signs for natural navigation (See [`Docs/Signs.md`](Docs/Signs.md)) +- Adding weather to the Carla recorder/replayer/query (See this [Carla PR](https://github.com/carla-simulator/carla/pull/5235)) +- Custom dynamic 3D actors with full recording support (eg. HUD indicators for direction, AR bounding boxes, visual targets, etc.). See [CustomActor.md](Docs/CustomActor.md) for more. +- (DEBUG ONLY) Foveated rendering for improved performance with gaze-aware (or fixed) variable rate shading + +## Install/Build +See [`Docs/Install.md`](Docs/Install.md) to: +- Install and build `DReyeVR` on top of a working `Carla` repository. +- Download plugins for `DReyeVR` required for fancy features such as: + - Eye tracking (SRanipal) + - Steering wheel/pedals (Logitech) +- Set up a `conda` environment for DReyeVR PythonAPI + +## OS compatibility +| OS | VR | Eye tracking | Audio | Keyboard+Mouse | Racing wheel | Foveated Rendering (Editor) | +| --- | --- | --- | --- | --- | --- | --- | +| Windows | :white_check_mark: | :white_check_mark: | :white_check_mark: | :white_check_mark: | :white_check_mark: | :white_check_mark: | +| Linux | :white_check_mark: | :x: | :white_check_mark: | :white_check_mark: | :x: | :x: | +| MacOS | :x: | :x: | :white_check_mark: | :white_check_mark: | :x: | :x: | +- While Windows (10) is recommended for optimized VR support, all our work translates to Linux systems except for the eye tracking and hardware integration which have Windows-only dependencies. + - Unfortunately the eye-tracking firmware is proprietary & does not work on Linux + - This is (currently) only supported on Windows because of some proprietary dependencies between [HTC SRanipal SDK](https://developer.vive.com/resources/knowledgebase/vive-sranipal-sdk/) and Tobii's SDK. Those interested in the Linux discussion for HTC's Vive Pro Eye Tracking can follow the subject [here (Vive)](https://forum.vive.com/topic/6994-eye-tracking-in-linux/), [here (Vive)](https://forum.vive.com/topic/7012-vive-pro-eye-on-ubuntu-16-or-18/), and [here (Tobii)](https://developer.tobii.com/community/forums/topic/vive-pro-eye-with-stream-engine/). + - Additionally, the [LogitechWheelPlugin](https://github.com/HARPLab/LogitechWheelPlugin) we use only has Windows support currently. Though it should be possible to use the G923 on Linux as per the [Arch Wiki](https://wiki.archlinux.org/title/Logitech_Racing_Wheel). +- Also, although MacOS is not officially supported by CARLA, we have development happening on an Apple Silicon machine and have active forks of CARLA + UE4.26 with MacOS 12+ support. Note that this is primarily for development, as it is the most limited system by far. + +## Documentation & Guides +- See [`F.A.Q. wiki`](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) for our Frequently Asked Questions wiki page. +- See [`Install.md`](Docs/Install.md) to install and build DReyeVR +- See [`Usage.md`](Docs/Usage.md) to learn how to use our provided DReyeVR features +- See [`Development.md`](Docs/Development.md) to get started with DReyeVR development and add new features +- See [`Docs/Tutorials/`](Docs/Tutorials/) to view several DReyeVR tutorials such as customizing the EgoVehicle, adding custom signs/props and more. + +## Citation +If you use our work, please cite the corresponding [paper](https://arxiv.org/abs/2201.01931): +```bibtex +@inproceedings{silvera2022dreyevr, + title={DReyeVR: Democratizing Virtual Reality Driving Simulation for Behavioural \& Interaction Research}, + author={Silvera, Gustavo and Biswas, Abhijat and Admoni, Henny}, + booktitle={Proceedings of the 2022 ACM/IEEE International Conference on Human-Robot Interaction}, + pages={639--643}, + year={2022} +} +``` + +## Acknowledgements + +- This project builds upon and extends the [CARLA simulator](https://carla.org/) +- This repo includes some code from CARLA: Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB) & Intel Corporation. +- This repo includes some code from Hewlett-Packard Development Company, LP. See [nvidia.ph](Tools/Diagnostics/collectl/nvidia.ph). This is a modified diagnostic tool used during development. + +## Licenses +- Custom DReyeVR code is distributed under the MIT License. +- Unreal Engine 4 follows its [own license terms](https://www.unrealengine.com/en-US/faq). +- Code used from other sources that is prefixed with a Copyright header belongs to those individuals/organizations. +- CARLA specific licenses (and dependencies) are described on their [GitHub](https://github.com/carla-simulator/carla#licenses) diff --git a/ROS-bridge/README.md b/ROS-bridge/README.md index 0efd2d3..3f6824c 100644 --- a/ROS-bridge/README.md +++ b/ROS-bridge/README.md @@ -1,201 +1,201 @@ -# Using Carla ROS bridge - -## Our (Software) Adventure -It would be great if we could do everything on a single machine, but unfortunately software dependencies and limitations make it very difficult to accomplish this. In particular we can note the following impmortant dependencies: -- [`SRanipal`](https://developer.vive.com/resources/vive-sense/sdk/vive-eye-tracking-sdk-sranipal/) requires Windows. HTC only provides precompiled Windows (`.dll`) binaries for important libraries. - - Reverse engineering the HTC Vive Pro's Eye tracker to work on Linux is possible but out of scope for this project. -- [`ROS`](http://wiki.ros.org/ROS/Installation) (basically) requires Linux for a proper [`ROS master`](http://wiki.ros.org/Installation) and `ROS` environment - - However, unless you want to go through several flaming hoops compiling `ROS` from source for a [custom distro](http://wiki.ros.org/Distributions), you'll need to use **exactly** [`Ubuntu 20.04 LTS`](https://releases.ubuntu.com/20.04/) for `ROS Noetic` (which supports Python3) and the other `Ubuntu` flavours for corresponding ros builds - - In our case we had already set up a Linux machine running [`Pop!_OS 20.10`](https://pop.system76.com/) (`Ubuntu` derivative) and did not want to dual boot/reinstall, so we instead took the approach of running our `ROS master` on a vanilla [`Ubuntu 20.04 LTS`](https://releases.ubuntu.com/20.04/) virtual machine. For explanations on how we managed to set this up (using `qemu`) see our [VM-guide](../ROS-bridge/README.md). - - [ROS Windows support](http://wiki.ros.org/Installation/Windows) is still in beta stage, we'd rather not use it. - -Long story short... we'll need at least one Windows machine for `CarlaVR` + `SRanipal` Eye tracking, and at least one Linux machine (possibly with the exact `Ubuntu 20.04 LTS` virtual machine) for the `ROS master`. - -We'd also like to use the compiled `PythonAPI` on the Windows build to interact with our (remote) `ROS master`, but this becomes difficult as well. The two major `ROS` python libraries are: -- [`rospy`](http://wiki.ros.org/rospy) which requires a fully functional "local `ROS` environment" which as described earlier is **not supported** on Windows -- [`roslibpy`](https://github.com/gramaziokohler/roslibpy) which only uses `WebSockets` and connects to `rosbridge 2.0` which both have **incompatibility** issues with `carla-ros-bridge` - -The only option now is to use a `PythonAPI` that was compiled on `Linux` to use `rospy` and publish our custom topics. -It is also highly reccomended to install the Windows Subsystem for Linux ([`WSL`](https://docs.microsoft.com/en-us/windows/wsl/install-win10)) to get proper ssh features and Linux commands. - -### Prerequisites: -- Windows machine for `SRanipal` eye tracking -- Linux machine (`Ubuntu 20.05 LTS`) for `ROS` master and python scripts - - Technically the python scripts do not need to be on the same machine as the `ROS master` (`Ubuntu 20.04 LTS` machine) - -### Our pipeline outlined -Our configuration is as follows -- **Machine A**: our primary physical Linux machine running `Pop!_OS 20.10` -- **Machine B**: our primary physical Windows machine running our `Carla` build with `SRanipal` installed -- **Machine C**: our virtual Linux machine running `Ubuntu 20.04 LTS` for `ROS` with a `tap` network backend - -**IMPORTANT:** We must first ensure that all machines are `ssh`-able to and from each other. - -For our case, giving **Machine C** a proper DHCP-assigned IP-address required a `tap` network backend as described in our VM-guide. Note that this passes through the `ethernet` (ex. `enp5s0`) from **Machine A** so it is no longer usable by **Machine A** which now defaults to using `Wifi` (ex. `wlp4s0`). - -Running `ifconfig` on **Machine A** gives us: - -```properties -# (cleaned up for brevity) -br0: flags=4163 mtu 1500 - inet 192.168.86.42 ... - ... - ... - -enp5s0: flags=4163 mtu 1500 - ... - ... - -lo: flags=73 mtu 65536 - inet 127.0.0.1 ... - ... - ... - -tap0: flags=4163 mtu 1500 - ... - ... - -wlp4s0: flags=4163 mtu 1500 - inet 192.168.86.123 ... - ... - ... - -``` -Note the important `IP` addresses we care about: `192.168.86.42`(the bridge ip address [`tap0` + `enp5s0`]) for `ssh`ing from **Machine C** to **Machine A** and `192.168.86.123`(the wifi ip address [`wlp4s0`]) for `ssh`ing from anywhere else to **Machine A**. - -Running `ifconfig` on **Machine B** gives us: - -```properties -enp5s0: flags=4163 mtu 1500 - inet 192.168.86.182 ... - ... - ... - -lo: flags=73 mtu 65536 - inet 127.0.0.1 ... - ... - ... -``` - -This is the simplest setup since `192.168.86.182` is the ip address for `ssh`ing from anywhere to **Machine B** - -Running `ifconfig` on **Machine C** gives us: - -```properties -ens3: flags=4163 mtu 1500 - inet 10.0.2.15 ... - ... - ... - -ens5: flags=4163 mtu 1500 - inet 192.168.86.33 ... - ... - ... - -lo: flags=73 mtu 65536 - inet 127.0.0.1 ... - ... - ... -``` - -And as expected we have yet another IP address for `ssh`ing into **Machine C**, `192.168.86.33`. Feel free to ignore the `10.0.2.15` as that's a dummy network used in the default `qemu` vm's that we aren't using. - -#### Summary of our IP addresses: - -We have: -- `192.168.86.42` for **Machine C** -> **Machine A** (use with `rosbridge`) -- `192.168.86.123` for **X** -> **Machine A** (use with `ssh` and as `SELF_IP` in `python` scripts) -- `192.168.86.182` for **X** -> **Machine B** (use with `python` scripts to connect to Windows `Carla` simulator instance) -- `192.168.86.33` for **X** -> **Machine C** (use with `IP_ROSMASTER` in `python` scripts to connect to `ROS master`) - -Recall that the VM IP addressess (**Machine C**) can be completely avoided if the secondary Linux machine is `Ubuntu 20.04 LTS`. - -### Sourcing - -Additionally, before any `roslaunch` you'll need to source the `setup.bash` (or `.zsh` or `.sh`) and update the `PYTHONPATH` for the `ROS` setup. To do this in your shell you'll need to `source` the script as following: -```bash -source ./setup.sh -``` - -### Roslaunch - -In order to run our custom ROS launchfile you can run the following: -```properties -# in our case we have 192.168.86.182:2000 as the Windows Carla instance -roslaunch carla_ros_bridge_DReyeVR.launch host:=192.168.86.182 port:=2000 fixed_delta_seconds:=0.0 -``` -This runs with a baseline asynchronous config with no fixed timestep. -- This keeps the framerate from affecting the speed of the simulator, but is not reproducable accurately. -- It would be better to run with a fixed timestep which would be fine if our simulator ran at a consistent fixed framerate. - - For now since we are still debugging it is fine to just let it run at variable framerates. - -### Rostopic/rosbag - -To see the published messages, simply use `rostopic` as per usual: -```properties -# list rostopic topics -$ rostopic list - -/carla/debug_marker -/carla/status -/carla/weather_control -/carla/world_info -/clock -/rosout -/rosout_agg -``` - -To record into a `rosbag`, you can also simply use `rosbag record -a` as usual. The output of a `rosbag info` should look something like this (as you can see it includes the `/dreyevr_pub` topic). - -```properties -$ rosbag info 2021-01-21-16-42-36.bag - -path: 2021-01-21-16-42-36.bag -version: 2.0 -duration: 6.0s -start: Dec 31 1969 16:51:58.84 (3118.84) -end: Dec 31 1969 16:52:04.87 (3124.87) -size: 4.7 MB -messages: 2972 -compression: none [2/2 chunks] -types: carla_msgs/CarlaStatus [0a6e668a0d517dead8f5c68762fc1dab] - carla_msgs/CarlaWorldInfo [7a3a7a7fc8c213a8bec2ce7928b0a46c] - rosgraph_msgs/Clock [a9c97c1d230cfc112e270351a944ee47] - rosgraph_msgs/Log [acffd30cd6b6de30f120938c17c593fb] - std_msgs/String [992ce8a1687cec8c8bd883ec73ca41d1] -topics: /carla/status 979 msgs : carla_msgs/CarlaStatus - /carla/world_info 1 msg : carla_msgs/CarlaWorldInfo - /clock 1007 msgs : rosgraph_msgs/Clock - /dreyevr_pub 980 msgs : std_msgs/String - /rosout 5 msgs : rosgraph_msgs/Log (2 connections) - -``` - -To echo any message, similarly can use `rostopic echo /` as usual. - - -## Troubleshooting - -### [WARN] 0 bytes were received -If you are not getting any data from the `rostopic echo /dreyevr_pub` output, and then also see a warning from the `ROS master` such as this: - -`[WARN] [1611557662.983417, 172.775030]: Inbound TCP/IP connection failed: connection from sender terminated before handshake header received. 0 bytes were received. Please check sender for additional details.` - -Then this is likely the case that your `IP_SELF` is incorrect in the python script. This is used to set the `ROS_IP` of the local machine in the environment, and should just be your machine's ip address from the local network. -- NOTE FOR VM USERS: This can be different than usual if using the `tap0` network backend from our VM-guides since it will send one network (your ethernet) to the VM and the host machine may be left with a secondary network. - -### NameError: name 'Sensor' is not defined -This occurs because you did not apply the patch to the `actor_factory.py` located at `carla-ros-bridge/ros-bridge/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py` which includes the proper `Sensor` import. - -### RuntimeError: resolve: Host not found (authoritative) -It is very likely that either the wrong Host/port is being used to connect to the remote (Windows) machine, or the `ssh` configuration is not set up correctly. Double check the IP address is correct by testing via `ssh` to and from the remote machine, if (in WSL) the `systemctl ssh status` is not running then enable it. - -### RospyError: Could not initialize rospy connection -This generally happens when you do not have the correct IP address and port of the `ROS master`. Double check that you are using the correct `IP_ROSMASTER` and `PORT_ROSMASTER` in your script for your setup. - -### IndexError: list index out of range -Our implementation of sourcing the python .egg file (adding to system path) depends on calling `./test_ros_publish.py` from within the `examples/` directory in the packaged `PythonAPI`. You can tweak this to be whatever `cwd` you want, simply change the glob query on line 12 of `test_ros_publish.py`. - -### ImportError: No module named carla -This occurs because of a faulty import for the python `.egg` file. As described above you should primarily be working in a `Linux` environment (not necessarily `Ubuntu 20.04 LTS` like for `ROS`) to use `rospy`. Double check that the `carla/dist/carla-0.9.10-...-linux-x86_64.egg` file exists. - +# Using Carla ROS bridge + +## Our (Software) Adventure +It would be great if we could do everything on a single machine, but unfortunately software dependencies and limitations make it very difficult to accomplish this. In particular we can note the following impmortant dependencies: +- [`SRanipal`](https://developer.vive.com/resources/vive-sense/sdk/vive-eye-tracking-sdk-sranipal/) requires Windows. HTC only provides precompiled Windows (`.dll`) binaries for important libraries. + - Reverse engineering the HTC Vive Pro's Eye tracker to work on Linux is possible but out of scope for this project. +- [`ROS`](http://wiki.ros.org/ROS/Installation) (basically) requires Linux for a proper [`ROS master`](http://wiki.ros.org/Installation) and `ROS` environment + - However, unless you want to go through several flaming hoops compiling `ROS` from source for a [custom distro](http://wiki.ros.org/Distributions), you'll need to use **exactly** [`Ubuntu 20.04 LTS`](https://releases.ubuntu.com/20.04/) for `ROS Noetic` (which supports Python3) and the other `Ubuntu` flavours for corresponding ros builds + - In our case we had already set up a Linux machine running [`Pop!_OS 20.10`](https://pop.system76.com/) (`Ubuntu` derivative) and did not want to dual boot/reinstall, so we instead took the approach of running our `ROS master` on a vanilla [`Ubuntu 20.04 LTS`](https://releases.ubuntu.com/20.04/) virtual machine. For explanations on how we managed to set this up (using `qemu`) see our [VM-guide](../ROS-bridge/README.md). + - [ROS Windows support](http://wiki.ros.org/Installation/Windows) is still in beta stage, we'd rather not use it. + +Long story short... we'll need at least one Windows machine for `CarlaVR` + `SRanipal` Eye tracking, and at least one Linux machine (possibly with the exact `Ubuntu 20.04 LTS` virtual machine) for the `ROS master`. + +We'd also like to use the compiled `PythonAPI` on the Windows build to interact with our (remote) `ROS master`, but this becomes difficult as well. The two major `ROS` python libraries are: +- [`rospy`](http://wiki.ros.org/rospy) which requires a fully functional "local `ROS` environment" which as described earlier is **not supported** on Windows +- [`roslibpy`](https://github.com/gramaziokohler/roslibpy) which only uses `WebSockets` and connects to `rosbridge 2.0` which both have **incompatibility** issues with `carla-ros-bridge` + +The only option now is to use a `PythonAPI` that was compiled on `Linux` to use `rospy` and publish our custom topics. +It is also highly reccomended to install the Windows Subsystem for Linux ([`WSL`](https://docs.microsoft.com/en-us/windows/wsl/install-win10)) to get proper ssh features and Linux commands. + +### Prerequisites: +- Windows machine for `SRanipal` eye tracking +- Linux machine (`Ubuntu 20.05 LTS`) for `ROS` master and python scripts + - Technically the python scripts do not need to be on the same machine as the `ROS master` (`Ubuntu 20.04 LTS` machine) + +### Our pipeline outlined +Our configuration is as follows +- **Machine A**: our primary physical Linux machine running `Pop!_OS 20.10` +- **Machine B**: our primary physical Windows machine running our `Carla` build with `SRanipal` installed +- **Machine C**: our virtual Linux machine running `Ubuntu 20.04 LTS` for `ROS` with a `tap` network backend + +**IMPORTANT:** We must first ensure that all machines are `ssh`-able to and from each other. + +For our case, giving **Machine C** a proper DHCP-assigned IP-address required a `tap` network backend as described in our VM-guide. Note that this passes through the `ethernet` (ex. `enp5s0`) from **Machine A** so it is no longer usable by **Machine A** which now defaults to using `Wifi` (ex. `wlp4s0`). + +Running `ifconfig` on **Machine A** gives us: + +```properties +# (cleaned up for brevity) +br0: flags=4163 mtu 1500 + inet 192.168.86.42 ... + ... + ... + +enp5s0: flags=4163 mtu 1500 + ... + ... + +lo: flags=73 mtu 65536 + inet 127.0.0.1 ... + ... + ... + +tap0: flags=4163 mtu 1500 + ... + ... + +wlp4s0: flags=4163 mtu 1500 + inet 192.168.86.123 ... + ... + ... + +``` +Note the important `IP` addresses we care about: `192.168.86.42`(the bridge ip address [`tap0` + `enp5s0`]) for `ssh`ing from **Machine C** to **Machine A** and `192.168.86.123`(the wifi ip address [`wlp4s0`]) for `ssh`ing from anywhere else to **Machine A**. + +Running `ifconfig` on **Machine B** gives us: + +```properties +enp5s0: flags=4163 mtu 1500 + inet 192.168.86.182 ... + ... + ... + +lo: flags=73 mtu 65536 + inet 127.0.0.1 ... + ... + ... +``` + +This is the simplest setup since `192.168.86.182` is the ip address for `ssh`ing from anywhere to **Machine B** + +Running `ifconfig` on **Machine C** gives us: + +```properties +ens3: flags=4163 mtu 1500 + inet 10.0.2.15 ... + ... + ... + +ens5: flags=4163 mtu 1500 + inet 192.168.86.33 ... + ... + ... + +lo: flags=73 mtu 65536 + inet 127.0.0.1 ... + ... + ... +``` + +And as expected we have yet another IP address for `ssh`ing into **Machine C**, `192.168.86.33`. Feel free to ignore the `10.0.2.15` as that's a dummy network used in the default `qemu` vm's that we aren't using. + +#### Summary of our IP addresses: + +We have: +- `192.168.86.42` for **Machine C** -> **Machine A** (use with `rosbridge`) +- `192.168.86.123` for **X** -> **Machine A** (use with `ssh` and as `SELF_IP` in `python` scripts) +- `192.168.86.182` for **X** -> **Machine B** (use with `python` scripts to connect to Windows `Carla` simulator instance) +- `192.168.86.33` for **X** -> **Machine C** (use with `IP_ROSMASTER` in `python` scripts to connect to `ROS master`) + +Recall that the VM IP addressess (**Machine C**) can be completely avoided if the secondary Linux machine is `Ubuntu 20.04 LTS`. + +### Sourcing + +Additionally, before any `roslaunch` you'll need to source the `setup.bash` (or `.zsh` or `.sh`) and update the `PYTHONPATH` for the `ROS` setup. To do this in your shell you'll need to `source` the script as following: +```bash +source ./setup.sh +``` + +### Roslaunch + +In order to run our custom ROS launchfile you can run the following: +```properties +# in our case we have 192.168.86.182:2000 as the Windows Carla instance +roslaunch carla_ros_bridge_DReyeVR.launch host:=192.168.86.182 port:=2000 fixed_delta_seconds:=0.0 +``` +This runs with a baseline asynchronous config with no fixed timestep. +- This keeps the framerate from affecting the speed of the simulator, but is not reproducable accurately. +- It would be better to run with a fixed timestep which would be fine if our simulator ran at a consistent fixed framerate. + - For now since we are still debugging it is fine to just let it run at variable framerates. + +### Rostopic/rosbag + +To see the published messages, simply use `rostopic` as per usual: +```properties +# list rostopic topics +$ rostopic list + +/carla/debug_marker +/carla/status +/carla/weather_control +/carla/world_info +/clock +/rosout +/rosout_agg +``` + +To record into a `rosbag`, you can also simply use `rosbag record -a` as usual. The output of a `rosbag info` should look something like this (as you can see it includes the `/dreyevr_pub` topic). + +```properties +$ rosbag info 2021-01-21-16-42-36.bag + +path: 2021-01-21-16-42-36.bag +version: 2.0 +duration: 6.0s +start: Dec 31 1969 16:51:58.84 (3118.84) +end: Dec 31 1969 16:52:04.87 (3124.87) +size: 4.7 MB +messages: 2972 +compression: none [2/2 chunks] +types: carla_msgs/CarlaStatus [0a6e668a0d517dead8f5c68762fc1dab] + carla_msgs/CarlaWorldInfo [7a3a7a7fc8c213a8bec2ce7928b0a46c] + rosgraph_msgs/Clock [a9c97c1d230cfc112e270351a944ee47] + rosgraph_msgs/Log [acffd30cd6b6de30f120938c17c593fb] + std_msgs/String [992ce8a1687cec8c8bd883ec73ca41d1] +topics: /carla/status 979 msgs : carla_msgs/CarlaStatus + /carla/world_info 1 msg : carla_msgs/CarlaWorldInfo + /clock 1007 msgs : rosgraph_msgs/Clock + /dreyevr_pub 980 msgs : std_msgs/String + /rosout 5 msgs : rosgraph_msgs/Log (2 connections) + +``` + +To echo any message, similarly can use `rostopic echo /` as usual. + + +## Troubleshooting + +### [WARN] 0 bytes were received +If you are not getting any data from the `rostopic echo /dreyevr_pub` output, and then also see a warning from the `ROS master` such as this: + +`[WARN] [1611557662.983417, 172.775030]: Inbound TCP/IP connection failed: connection from sender terminated before handshake header received. 0 bytes were received. Please check sender for additional details.` + +Then this is likely the case that your `IP_SELF` is incorrect in the python script. This is used to set the `ROS_IP` of the local machine in the environment, and should just be your machine's ip address from the local network. +- NOTE FOR VM USERS: This can be different than usual if using the `tap0` network backend from our VM-guides since it will send one network (your ethernet) to the VM and the host machine may be left with a secondary network. + +### NameError: name 'Sensor' is not defined +This occurs because you did not apply the patch to the `actor_factory.py` located at `carla-ros-bridge/ros-bridge/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py` which includes the proper `Sensor` import. + +### RuntimeError: resolve: Host not found (authoritative) +It is very likely that either the wrong Host/port is being used to connect to the remote (Windows) machine, or the `ssh` configuration is not set up correctly. Double check the IP address is correct by testing via `ssh` to and from the remote machine, if (in WSL) the `systemctl ssh status` is not running then enable it. + +### RospyError: Could not initialize rospy connection +This generally happens when you do not have the correct IP address and port of the `ROS master`. Double check that you are using the correct `IP_ROSMASTER` and `PORT_ROSMASTER` in your script for your setup. + +### IndexError: list index out of range +Our implementation of sourcing the python .egg file (adding to system path) depends on calling `./test_ros_publish.py` from within the `examples/` directory in the packaged `PythonAPI`. You can tweak this to be whatever `cwd` you want, simply change the glob query on line 12 of `test_ros_publish.py`. + +### ImportError: No module named carla +This occurs because of a faulty import for the python `.egg` file. As described above you should primarily be working in a `Linux` environment (not necessarily `Ubuntu 20.04 LTS` like for `ROS`) to use `rospy`. Double check that the `carla/dist/carla-0.9.10-...-linux-x86_64.egg` file exists. + diff --git a/ROS-bridge/actor_factory.py b/ROS-bridge/actor_factory.py index 34949f7..60df0b4 100644 --- a/ROS-bridge/actor_factory.py +++ b/ROS-bridge/actor_factory.py @@ -1,305 +1,305 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -import rospy - -try: - import queue -except ImportError: - import Queue as queue - -import time -from threading import Thread, Lock -import itertools - -import carla - -import carla_common.transforms as trans - -from carla_ros_bridge.actor import Actor -from carla_ros_bridge.spectator import Spectator -from carla_ros_bridge.traffic import Traffic, TrafficLight -from carla_ros_bridge.vehicle import Vehicle -from carla_ros_bridge.lidar import Lidar, SemanticLidar -from carla_ros_bridge.radar import Radar -from carla_ros_bridge.gnss import Gnss -from carla_ros_bridge.pseudo_actor import PseudoActor -from carla_ros_bridge.imu import ImuSensor -from carla_ros_bridge.ego_vehicle import EgoVehicle -from carla_ros_bridge.collision_sensor import CollisionSensor -from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera -from carla_ros_bridge.object_sensor import ObjectSensor -from carla_ros_bridge.rss_sensor import RssSensor -from carla_ros_bridge.walker import Walker -from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor -from carla_ros_bridge.odom_sensor import OdometrySensor -from carla_ros_bridge.speedometer_sensor import SpeedometerSensor -from carla_ros_bridge.tf_sensor import TFSensor -from carla_ros_bridge.marker_sensor import MarkerSensor -from carla_ros_bridge.actor_list_sensor import ActorListSensor -from carla_ros_bridge.opendrive_sensor import OpenDriveSensor -from carla_ros_bridge.actor_control import ActorControl -from carla_ros_bridge.sensor import Sensor # for custom sensors - - -class ActorFactory(object): - - TIME_BETWEEN_UPDATES = 0.1 - - def __init__(self, node, world, sync_mode=False): - self.node = node - self.world = world - self.sync_mode = sync_mode - - self.actors = {} - - self.lock = Lock() - self.spawn_lock = Lock() - - # id generator for pseudo sensors - self.id_gen = itertools.count(10000) - - def start(self): - # create initially existing actors - self.update() - - self.thread = Thread(target=self._update_thread) - self.thread.start() - - def _update_thread(self): - """ - execution loop for async mode actor discovery - """ - while not self.node.shutdown.is_set(): - time.sleep(ActorFactory.TIME_BETWEEN_UPDATES) - with self.spawn_lock: - self.world.wait_for_tick() - self.update() - - def update(self): - """ - update the available actors - """ - # get only carla actors - previous_actors = set( - [x.uid for x in self.actors.values() if isinstance(x, Actor)]) - current_actors = set([x.id for x in self.world.get_actors()]) - - new_actors = current_actors - previous_actors - for actor_id in new_actors: - carla_actor = self.world.get_actor(actor_id) - self._create_carla_actor(carla_actor) - - deleted_actors = previous_actors - current_actors - for actor_id in deleted_actors: - self.destroy(actor_id) - - def clear(self): - ids = self.actors.keys() - for id_ in list(ids): - self.destroy(id_) - - def _create_carla_actor(self, carla_actor): - parent = None - if carla_actor.parent: - if carla_actor.parent.id in self.actors: - parent = self.actors[carla_actor.parent.id] - else: - parent = self._create_carla_actor(carla_actor.parent) - - parent_id = 0 - if parent is not None: - parent_id = parent.uid - - name = carla_actor.attributes.get("role_name", "") - if not name: - name = str(carla_actor.id) - return self.create(carla_actor.type_id, name, parent_id, None, carla_actor) - - def create(self, type_id, name, attach_to, spawn_pose, carla_actor=None): - with self.lock: - # check that the actor is not already created. - if carla_actor is not None and carla_actor.id in self.actors: - return None - - if attach_to != 0: - if attach_to not in self.actors: - raise IndexError( - "Parent object {} not found".format(attach_to)) - parent = self.actors[attach_to] - else: - parent = None - - if carla_actor is not None: - uid = carla_actor.id - else: - uid = next(self.id_gen) - - actor = self._create_object( - uid, type_id, name, parent, spawn_pose, carla_actor) - self.actors[actor.uid] = actor - - rospy.loginfo("Created {}(id={})".format( - actor.__class__.__name__, actor.uid)) - - return actor - - def destroy(self, actor_id): - with self.lock: - # check that the actor is not already removed. - if actor_id not in self.actors: - return - - actor = self.actors.pop(actor_id) - actor.destroy() - - rospy.loginfo("Removed {}(id={})".format( - actor.__class__.__name__, actor.uid)) - - def get_pseudo_sensor_types(self): - pseudo_sensors = [] - for cls in PseudoActor.__subclasses__(): - if cls.__name__ != "Actor": - pseudo_sensors.append(cls.get_blueprint_name()) - return pseudo_sensors - - def _create_object(self, uid, type_id, name, parent, spawn_pose, carla_actor=None): - - if type_id == TFSensor.get_blueprint_name(): - actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) - - elif type_id == OdometrySensor.get_blueprint_name(): - actor = OdometrySensor(uid=uid, - name=name, - parent=parent, - node=self.node) - - elif type_id == SpeedometerSensor.get_blueprint_name(): - actor = SpeedometerSensor(uid=uid, - name=name, - parent=parent, - node=self.node) - - elif type_id == MarkerSensor.get_blueprint_name(): - actor = MarkerSensor(uid=uid, - name=name, - parent=parent, - node=self.node, - actor_list=self.actors) - - elif type_id == ActorListSensor.get_blueprint_name(): - actor = ActorListSensor(uid=uid, - name=name, - parent=parent, - node=self.node, - actor_list=self.actors) - - elif type_id == ObjectSensor.get_blueprint_name(): - actor = ObjectSensor( - uid=uid, - name=name, - parent=parent, - node=self.node, - actor_list=self.actors, - ) - - elif type_id == TrafficLightsSensor.get_blueprint_name(): - actor = TrafficLightsSensor( - uid=uid, - name=name, - parent=parent, - node=self.node, - actor_list=self.actors, - ) - - elif type_id == OpenDriveSensor.get_blueprint_name(): - actor = OpenDriveSensor(uid=uid, - name=name, - parent=parent, - node=self.node, - carla_map=self.world.get_map()) - - elif type_id == ActorControl.get_blueprint_name(): - actor = ActorControl(uid=uid, - name=name, - parent=parent, - node=self.node) - - elif carla_actor.type_id.startswith('traffic'): - if carla_actor.type_id == "traffic.traffic_light": - actor = TrafficLight(uid, name, parent, self.node, carla_actor) - else: - actor = Traffic(uid, name, parent, self.node, carla_actor) - elif carla_actor.type_id.startswith("vehicle"): - if carla_actor.attributes.get('role_name')\ - in self.node.parameters['ego_vehicle']['role_name']: - actor = EgoVehicle( - uid, name, parent, self.node, carla_actor, - self.node._ego_vehicle_control_applied_callback) - else: - actor = Vehicle(uid, name, parent, self.node, carla_actor) - elif carla_actor.type_id.startswith("sensor"): - if carla_actor.type_id.startswith("sensor.camera"): - if carla_actor.type_id.startswith("sensor.camera.rgb"): - actor = RgbCamera(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.camera.depth"): - actor = DepthCamera(uid, name, parent, spawn_pose, - self.node, carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith( - "sensor.camera.semantic_segmentation"): - actor = SemanticSegmentationCamera(uid, name, parent, - spawn_pose, self.node, - carla_actor, - self.sync_mode) - elif carla_actor.type_id.startswith("sensor.camera.dvs"): - actor = DVSCamera(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - else: - actor = Camera(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.lidar"): - if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): - actor = Lidar(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.endswith( - "sensor.lidar.ray_cast_semantic"): - actor = SemanticLidar(uid, name, parent, spawn_pose, - self.node, carla_actor, - self.sync_mode) - elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.other.gnss"): - actor = Gnss(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.other.imu"): - actor = ImuSensor(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.other.collision"): - actor = CollisionSensor(uid, name, parent, spawn_pose, - self.node, carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.other.rss"): - actor = RssSensor(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): - actor = LaneInvasionSensor(uid, name, parent, spawn_pose, - self.node, carla_actor, - self.sync_mode) - else: - actor = Sensor(uid, name, parent, spawn_pose, self.node, - carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("spectator"): - actor = Spectator(uid, name, parent, self.node, carla_actor) - elif carla_actor.type_id.startswith("walker"): - actor = Walker(uid, name, parent, self.node, carla_actor) - else: - actor = Actor(uid, name, parent, self.node, carla_actor) - - return actor +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +import rospy + +try: + import queue +except ImportError: + import Queue as queue + +import time +from threading import Thread, Lock +import itertools + +import carla + +import carla_common.transforms as trans + +from carla_ros_bridge.actor import Actor +from carla_ros_bridge.spectator import Spectator +from carla_ros_bridge.traffic import Traffic, TrafficLight +from carla_ros_bridge.vehicle import Vehicle +from carla_ros_bridge.lidar import Lidar, SemanticLidar +from carla_ros_bridge.radar import Radar +from carla_ros_bridge.gnss import Gnss +from carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.imu import ImuSensor +from carla_ros_bridge.ego_vehicle import EgoVehicle +from carla_ros_bridge.collision_sensor import CollisionSensor +from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor +from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera +from carla_ros_bridge.object_sensor import ObjectSensor +from carla_ros_bridge.rss_sensor import RssSensor +from carla_ros_bridge.walker import Walker +from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +from carla_ros_bridge.odom_sensor import OdometrySensor +from carla_ros_bridge.speedometer_sensor import SpeedometerSensor +from carla_ros_bridge.tf_sensor import TFSensor +from carla_ros_bridge.marker_sensor import MarkerSensor +from carla_ros_bridge.actor_list_sensor import ActorListSensor +from carla_ros_bridge.opendrive_sensor import OpenDriveSensor +from carla_ros_bridge.actor_control import ActorControl +from carla_ros_bridge.sensor import Sensor # for custom sensors + + +class ActorFactory(object): + + TIME_BETWEEN_UPDATES = 0.1 + + def __init__(self, node, world, sync_mode=False): + self.node = node + self.world = world + self.sync_mode = sync_mode + + self.actors = {} + + self.lock = Lock() + self.spawn_lock = Lock() + + # id generator for pseudo sensors + self.id_gen = itertools.count(10000) + + def start(self): + # create initially existing actors + self.update() + + self.thread = Thread(target=self._update_thread) + self.thread.start() + + def _update_thread(self): + """ + execution loop for async mode actor discovery + """ + while not self.node.shutdown.is_set(): + time.sleep(ActorFactory.TIME_BETWEEN_UPDATES) + with self.spawn_lock: + self.world.wait_for_tick() + self.update() + + def update(self): + """ + update the available actors + """ + # get only carla actors + previous_actors = set( + [x.uid for x in self.actors.values() if isinstance(x, Actor)]) + current_actors = set([x.id for x in self.world.get_actors()]) + + new_actors = current_actors - previous_actors + for actor_id in new_actors: + carla_actor = self.world.get_actor(actor_id) + self._create_carla_actor(carla_actor) + + deleted_actors = previous_actors - current_actors + for actor_id in deleted_actors: + self.destroy(actor_id) + + def clear(self): + ids = self.actors.keys() + for id_ in list(ids): + self.destroy(id_) + + def _create_carla_actor(self, carla_actor): + parent = None + if carla_actor.parent: + if carla_actor.parent.id in self.actors: + parent = self.actors[carla_actor.parent.id] + else: + parent = self._create_carla_actor(carla_actor.parent) + + parent_id = 0 + if parent is not None: + parent_id = parent.uid + + name = carla_actor.attributes.get("role_name", "") + if not name: + name = str(carla_actor.id) + return self.create(carla_actor.type_id, name, parent_id, None, carla_actor) + + def create(self, type_id, name, attach_to, spawn_pose, carla_actor=None): + with self.lock: + # check that the actor is not already created. + if carla_actor is not None and carla_actor.id in self.actors: + return None + + if attach_to != 0: + if attach_to not in self.actors: + raise IndexError( + "Parent object {} not found".format(attach_to)) + parent = self.actors[attach_to] + else: + parent = None + + if carla_actor is not None: + uid = carla_actor.id + else: + uid = next(self.id_gen) + + actor = self._create_object( + uid, type_id, name, parent, spawn_pose, carla_actor) + self.actors[actor.uid] = actor + + rospy.loginfo("Created {}(id={})".format( + actor.__class__.__name__, actor.uid)) + + return actor + + def destroy(self, actor_id): + with self.lock: + # check that the actor is not already removed. + if actor_id not in self.actors: + return + + actor = self.actors.pop(actor_id) + actor.destroy() + + rospy.loginfo("Removed {}(id={})".format( + actor.__class__.__name__, actor.uid)) + + def get_pseudo_sensor_types(self): + pseudo_sensors = [] + for cls in PseudoActor.__subclasses__(): + if cls.__name__ != "Actor": + pseudo_sensors.append(cls.get_blueprint_name()) + return pseudo_sensors + + def _create_object(self, uid, type_id, name, parent, spawn_pose, carla_actor=None): + + if type_id == TFSensor.get_blueprint_name(): + actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) + + elif type_id == OdometrySensor.get_blueprint_name(): + actor = OdometrySensor(uid=uid, + name=name, + parent=parent, + node=self.node) + + elif type_id == SpeedometerSensor.get_blueprint_name(): + actor = SpeedometerSensor(uid=uid, + name=name, + parent=parent, + node=self.node) + + elif type_id == MarkerSensor.get_blueprint_name(): + actor = MarkerSensor(uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors) + + elif type_id == ActorListSensor.get_blueprint_name(): + actor = ActorListSensor(uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors) + + elif type_id == ObjectSensor.get_blueprint_name(): + actor = ObjectSensor( + uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors, + ) + + elif type_id == TrafficLightsSensor.get_blueprint_name(): + actor = TrafficLightsSensor( + uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors, + ) + + elif type_id == OpenDriveSensor.get_blueprint_name(): + actor = OpenDriveSensor(uid=uid, + name=name, + parent=parent, + node=self.node, + carla_map=self.world.get_map()) + + elif type_id == ActorControl.get_blueprint_name(): + actor = ActorControl(uid=uid, + name=name, + parent=parent, + node=self.node) + + elif carla_actor.type_id.startswith('traffic'): + if carla_actor.type_id == "traffic.traffic_light": + actor = TrafficLight(uid, name, parent, self.node, carla_actor) + else: + actor = Traffic(uid, name, parent, self.node, carla_actor) + elif carla_actor.type_id.startswith("vehicle"): + if carla_actor.attributes.get('role_name')\ + in self.node.parameters['ego_vehicle']['role_name']: + actor = EgoVehicle( + uid, name, parent, self.node, carla_actor, + self.node._ego_vehicle_control_applied_callback) + else: + actor = Vehicle(uid, name, parent, self.node, carla_actor) + elif carla_actor.type_id.startswith("sensor"): + if carla_actor.type_id.startswith("sensor.camera"): + if carla_actor.type_id.startswith("sensor.camera.rgb"): + actor = RgbCamera(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.camera.depth"): + actor = DepthCamera(uid, name, parent, spawn_pose, + self.node, carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith( + "sensor.camera.semantic_segmentation"): + actor = SemanticSegmentationCamera(uid, name, parent, + spawn_pose, self.node, + carla_actor, + self.sync_mode) + elif carla_actor.type_id.startswith("sensor.camera.dvs"): + actor = DVSCamera(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + else: + actor = Camera(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.lidar"): + if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): + actor = Lidar(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.endswith( + "sensor.lidar.ray_cast_semantic"): + actor = SemanticLidar(uid, name, parent, spawn_pose, + self.node, carla_actor, + self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.radar"): + actor = Radar(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.gnss"): + actor = Gnss(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.imu"): + actor = ImuSensor(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.collision"): + actor = CollisionSensor(uid, name, parent, spawn_pose, + self.node, carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.rss"): + actor = RssSensor(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): + actor = LaneInvasionSensor(uid, name, parent, spawn_pose, + self.node, carla_actor, + self.sync_mode) + else: + actor = Sensor(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith("spectator"): + actor = Spectator(uid, name, parent, self.node, carla_actor) + elif carla_actor.type_id.startswith("walker"): + actor = Walker(uid, name, parent, self.node, carla_actor) + else: + actor = Actor(uid, name, parent, self.node, carla_actor) + + return actor diff --git a/ROS-bridge/carla_ros_bridge_DReyeVR.launch b/ROS-bridge/carla_ros_bridge_DReyeVR.launch index 8e769fd..995785d 100644 --- a/ROS-bridge/carla_ros_bridge_DReyeVR.launch +++ b/ROS-bridge/carla_ros_bridge_DReyeVR.launch @@ -1,37 +1,37 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ROS-bridge/setup.sh b/ROS-bridge/setup.sh index 7b885ad..75a1f54 100755 --- a/ROS-bridge/setup.sh +++ b/ROS-bridge/setup.sh @@ -1,17 +1,17 @@ -#!/bin/bash - -# Export the pythonpath to include the Carla python module -# NOTE: this requires the PythonAPI to be built on the machine this script is run -export PYTHONPATH=$PYTHONPATH:~/carla/PythonAPI/carla/dist/carla-0.9.10-py3.8-linux-x86_64.egg && - -# Source the main ROS setup, in our case we're using ROS Noetic -source /opt/ros/noetic/setup.bash && - -# Source the Carla ROS bridge setup file -source ~/carla-ros-bridge/catkin_ws/devel/setup.bash && - -# Ensure that the Carla python module is available (via the first command) -python -c 'import carla;print("Success")' - -# launch the carla ROS bridge with our DReyeVR launch file -# roslaunch carla_ros_bridge_DReyeVR.launch +#!/bin/bash + +# Export the pythonpath to include the Carla python module +# NOTE: this requires the PythonAPI to be built on the machine this script is run +export PYTHONPATH=$PYTHONPATH:~/carla/PythonAPI/carla/dist/carla-0.9.13-py3.8-linux-x86_64.egg && + +# Source the main ROS setup, in our case we're using ROS Noetic +source /opt/ros/noetic/setup.bash && + +# Source the Carla ROS bridge setup file +source ~/carla-ros-bridge/catkin_ws/devel/setup.bash && + +# Ensure that the Carla python module is available (via the first command) +python -c 'import carla;print("Success")' + +# launch the carla ROS bridge with our DReyeVR launch file +# roslaunch carla_ros_bridge_DReyeVR.launch diff --git a/ScenarioRunner/carla_data_provider.py b/ScenarioRunner/carla_data_provider.py index 94dc494..6ee3582 100644 --- a/ScenarioRunner/carla_data_provider.py +++ b/ScenarioRunner/carla_data_provider.py @@ -1,832 +1,832 @@ -#!/usr/bin/env python - -# Copyright (c) 2018-2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . - -""" -This module provides all frequently used data from CARLA via -local buffers to avoid blocking calls to CARLA -""" - -from __future__ import print_function - -import math -import re -from numpy import random -from six import iteritems - -import carla - - -def calculate_velocity(actor): - """ - Method to calculate the velocity of a actor - """ - velocity_squared = actor.get_velocity().x**2 - velocity_squared += actor.get_velocity().y**2 - return math.sqrt(velocity_squared) - - -class CarlaDataProvider(object): # pylint: disable=too-many-public-methods - - """ - This class provides access to various data of all registered actors - It buffers the data and updates it on every CARLA tick - - Currently available data: - - Absolute velocity - - Location - - Transform - - Potential additions: - - Acceleration - - In addition it provides access to the map and the transform of all traffic lights - """ - - _actor_velocity_map = {} - _actor_location_map = {} - _actor_transform_map = {} - _traffic_light_map = {} - _carla_actor_pool = {} - _global_osc_parameters = {} - _client = None - _world = None - _map = None - _sync_flag = False - _spawn_points = None - _spawn_index = 0 - _blueprint_library = None - _ego_vehicle_route = None - _traffic_manager_port = 8000 - _random_seed = 2000 - _rng = random.RandomState(_random_seed) - - @staticmethod - def register_actor(actor): - """ - Add new actor to dictionaries - If actor already exists, throw an exception - """ - if actor in CarlaDataProvider._actor_velocity_map: - raise KeyError( - "Vehicle '{}' already registered. Cannot register twice!".format(actor.id)) - else: - CarlaDataProvider._actor_velocity_map[actor] = 0.0 - - if actor in CarlaDataProvider._actor_location_map: - raise KeyError( - "Vehicle '{}' already registered. Cannot register twice!".format(actor.id)) - else: - CarlaDataProvider._actor_location_map[actor] = None - - if actor in CarlaDataProvider._actor_transform_map: - raise KeyError( - "Vehicle '{}' already registered. Cannot register twice!".format(actor.id)) - else: - CarlaDataProvider._actor_transform_map[actor] = None - - @staticmethod - def update_osc_global_params(parameters): - """ - updates/initializes global osc parameters. - """ - CarlaDataProvider._global_osc_parameters.update(parameters) - - @staticmethod - def get_osc_global_param_value(ref): - """ - returns updated global osc parameter value. - """ - return CarlaDataProvider._global_osc_parameters.get(ref.replace("$", "")) - - @staticmethod - def register_actors(actors): - """ - Add new set of actors to dictionaries - """ - for actor in actors: - CarlaDataProvider.register_actor(actor) - - @staticmethod - def on_carla_tick(): - """ - Callback from CARLA - """ - for actor in CarlaDataProvider._actor_velocity_map: - if actor is not None and actor.is_alive: - CarlaDataProvider._actor_velocity_map[actor] = calculate_velocity(actor) - - for actor in CarlaDataProvider._actor_location_map: - if actor is not None and actor.is_alive: - CarlaDataProvider._actor_location_map[actor] = actor.get_location() - - for actor in CarlaDataProvider._actor_transform_map: - if actor is not None and actor.is_alive: - CarlaDataProvider._actor_transform_map[actor] = actor.get_transform() - - world = CarlaDataProvider._world - if world is None: - print("WARNING: CarlaDataProvider couldn't find the world") - - @staticmethod - def get_velocity(actor): - """ - returns the absolute velocity for the given actor - """ - for key in CarlaDataProvider._actor_velocity_map: - if key.id == actor.id: - return CarlaDataProvider._actor_velocity_map[key] - - # We are intentionally not throwing here - # This may cause exception loops in py_trees - print('{}.get_velocity: {} not found!' .format(__name__, actor)) - return 0.0 - - @staticmethod - def get_location(actor): - """ - returns the location for the given actor - """ - for key in CarlaDataProvider._actor_location_map: - if key.id == actor.id: - return CarlaDataProvider._actor_location_map[key] - - # We are intentionally not throwing here - # This may cause exception loops in py_trees - print('{}.get_location: {} not found!' .format(__name__, actor)) - return None - - @staticmethod - def get_transform(actor): - """ - returns the transform for the given actor - """ - for key in CarlaDataProvider._actor_transform_map: - if key.id == actor.id: - return CarlaDataProvider._actor_transform_map[key] - - # We are intentionally not throwing here - # This may cause exception loops in py_trees - print('{}.get_transform: {} not found!' .format(__name__, actor)) - return None - - @staticmethod - def set_client(client): - """ - Set the CARLA client - """ - CarlaDataProvider._client = client - - @staticmethod - def get_client(): - """ - Get the CARLA client - """ - return CarlaDataProvider._client - - @staticmethod - def set_world(world): - """ - Set the world and world settings - """ - CarlaDataProvider._world = world - CarlaDataProvider._sync_flag = world.get_settings().synchronous_mode - CarlaDataProvider._map = world.get_map() - CarlaDataProvider._blueprint_library = world.get_blueprint_library() - CarlaDataProvider.generate_spawn_points() - CarlaDataProvider.prepare_map() - - @staticmethod - def get_world(): - """ - Return world - """ - return CarlaDataProvider._world - - @staticmethod - def get_map(world=None): - """ - Get the current map - """ - if CarlaDataProvider._map is None: - if world is None: - if CarlaDataProvider._world is None: - raise ValueError("class member \'world'\' not initialized yet") - else: - CarlaDataProvider._map = CarlaDataProvider._world.get_map() - else: - CarlaDataProvider._map = world.get_map() - - return CarlaDataProvider._map - - @staticmethod - def get_random_seed(): - """ - @return true if syncronuous mode is used - """ - return CarlaDataProvider._rng - - @staticmethod - def is_sync_mode(): - """ - @return true if syncronuous mode is used - """ - return CarlaDataProvider._sync_flag - - @staticmethod - def find_weather_presets(): - """ - Get weather presets from CARLA - """ - rgx = re.compile('.+?(?:(?<=[a-z])(?=[A-Z])|(?<=[A-Z])(?=[A-Z][a-z])|$)') - def name(x:str) -> str: - return ' '.join(m.group(0) for m in rgx.finditer(x)) - presets = [x for x in dir(carla.WeatherParameters) if re.match('[A-Z].+', x)] - return [(getattr(carla.WeatherParameters, x), name(x)) for x in presets] - - @staticmethod - def prepare_map(): - """ - This function set the current map and loads all traffic lights for this map to - _traffic_light_map - """ - if CarlaDataProvider._map is None: - CarlaDataProvider._map = CarlaDataProvider._world.get_map() - - # Parse all traffic lights - CarlaDataProvider._traffic_light_map.clear() - for traffic_light in CarlaDataProvider._world.get_actors().filter('*traffic_light*'): - if traffic_light not in list(CarlaDataProvider._traffic_light_map): - CarlaDataProvider._traffic_light_map[traffic_light] = traffic_light.get_transform() - else: - raise KeyError( - "Traffic light '{}' already registered. Cannot register twice!".format(traffic_light.id)) - - @staticmethod - def annotate_trafficlight_in_group(traffic_light): - """ - Get dictionary with traffic light group info for a given traffic light - """ - dict_annotations = {'ref': [], 'opposite': [], 'left': [], 'right': []} - - # Get the waypoints - ref_location = CarlaDataProvider.get_trafficlight_trigger_location(traffic_light) - ref_waypoint = CarlaDataProvider.get_map().get_waypoint(ref_location) - ref_yaw = ref_waypoint.transform.rotation.yaw - - group_tl = traffic_light.get_group_traffic_lights() - - for target_tl in group_tl: - if traffic_light.id == target_tl.id: - dict_annotations['ref'].append(target_tl) - else: - # Get the angle between yaws - target_location = CarlaDataProvider.get_trafficlight_trigger_location(target_tl) - target_waypoint = CarlaDataProvider.get_map().get_waypoint(target_location) - target_yaw = target_waypoint.transform.rotation.yaw - - diff = (target_yaw - ref_yaw) % 360 - - if diff > 330: - continue - elif diff > 225: - dict_annotations['right'].append(target_tl) - elif diff > 135.0: - dict_annotations['opposite'].append(target_tl) - elif diff > 30: - dict_annotations['left'].append(target_tl) - - return dict_annotations - - @staticmethod - def get_trafficlight_trigger_location(traffic_light): # pylint: disable=invalid-name - """ - Calculates the yaw of the waypoint that represents the trigger volume of the traffic light - """ - def rotate_point(point, angle): - """ - rotate a given point by a given angle - """ - x_ = math.cos(math.radians(angle)) * point.x - math.sin(math.radians(angle)) * point.y - y_ = math.sin(math.radians(angle)) * point.x - math.cos(math.radians(angle)) * point.y - - return carla.Vector3D(x_, y_, point.z) - - base_transform = traffic_light.get_transform() - base_rot = base_transform.rotation.yaw - area_loc = base_transform.transform(traffic_light.trigger_volume.location) - area_ext = traffic_light.trigger_volume.extent - - point = rotate_point(carla.Vector3D(0, 0, area_ext.z), base_rot) - point_location = area_loc + carla.Location(x=point.x, y=point.y) - - return carla.Location(point_location.x, point_location.y, point_location.z) - - @staticmethod - def update_light_states(ego_light, annotations, states, freeze=False, timeout=1000000000): - """ - Update traffic light states - """ - reset_params = [] - - for state in states: - relevant_lights = [] - if state == 'ego': - relevant_lights = [ego_light] - else: - relevant_lights = annotations[state] - for light in relevant_lights: - prev_state = light.get_state() - prev_green_time = light.get_green_time() - prev_red_time = light.get_red_time() - prev_yellow_time = light.get_yellow_time() - reset_params.append({'light': light, - 'state': prev_state, - 'green_time': prev_green_time, - 'red_time': prev_red_time, - 'yellow_time': prev_yellow_time}) - - light.set_state(states[state]) - if freeze: - light.set_green_time(timeout) - light.set_red_time(timeout) - light.set_yellow_time(timeout) - - return reset_params - - @staticmethod - def reset_lights(reset_params): - """ - Reset traffic lights - """ - for param in reset_params: - param['light'].set_state(param['state']) - param['light'].set_green_time(param['green_time']) - param['light'].set_red_time(param['red_time']) - param['light'].set_yellow_time(param['yellow_time']) - - @staticmethod - def get_next_traffic_light(actor, use_cached_location=True): - """ - returns the next relevant traffic light for the provided actor - """ - - if not use_cached_location: - location = actor.get_transform().location - else: - location = CarlaDataProvider.get_location(actor) - - waypoint = CarlaDataProvider.get_map().get_waypoint(location) - # Create list of all waypoints until next intersection - list_of_waypoints = [] - while waypoint and not waypoint.is_intersection: - list_of_waypoints.append(waypoint) - waypoint = waypoint.next(2.0)[0] - - # If the list is empty, the actor is in an intersection - if not list_of_waypoints: - return None - - relevant_traffic_light = None - distance_to_relevant_traffic_light = float("inf") - - for traffic_light in CarlaDataProvider._traffic_light_map: - if hasattr(traffic_light, 'trigger_volume'): - tl_t = CarlaDataProvider._traffic_light_map[traffic_light] - transformed_tv = tl_t.transform(traffic_light.trigger_volume.location) - distance = carla.Location(transformed_tv).distance(list_of_waypoints[-1].transform.location) - - if distance < distance_to_relevant_traffic_light: - relevant_traffic_light = traffic_light - distance_to_relevant_traffic_light = distance - - return relevant_traffic_light - - @staticmethod - def set_ego_vehicle_route(route): - """ - Set the route of the ego vehicle - - @todo extend ego_vehicle_route concept to support multi ego_vehicle scenarios - """ - CarlaDataProvider._ego_vehicle_route = route - - @staticmethod - def get_ego_vehicle_route(): - """ - returns the currently set route of the ego vehicle - Note: Can be None - """ - return CarlaDataProvider._ego_vehicle_route - - @staticmethod - def generate_spawn_points(): - """ - Generate spawn points for the current map - """ - spawn_points = list(CarlaDataProvider.get_map(CarlaDataProvider._world).get_spawn_points()) - CarlaDataProvider._rng.shuffle(spawn_points) - CarlaDataProvider._spawn_points = spawn_points - CarlaDataProvider._spawn_index = 0 - - @staticmethod - def create_blueprint(model, rolename='scenario', color=None, actor_category="car", safe=False): - """ - Function to setup the blueprint of an actor given its model and other relevant parameters - """ - - _actor_blueprint_categories = { - 'car': 'vehicle.tesla.model3', - 'van': 'vehicle.volkswagen.t2', - 'truck': 'vehicle.carlamotors.carlacola', - 'trailer': '', - 'semitrailer': '', - 'bus': 'vehicle.volkswagen.t2', - 'motorbike': 'vehicle.kawasaki.ninja', - 'bicycle': 'vehicle.diamondback.century', - 'train': '', - 'tram': '', - 'pedestrian': 'walker.pedestrian.0001', - } - - # Set the model - try: - blueprints = CarlaDataProvider._blueprint_library.filter(model) - blueprints_ = [] - if safe: - for bp in blueprints: - if bp.id.endswith('firetruck') or bp.id.endswith('ambulance') \ - or int(bp.get_attribute('number_of_wheels')) != 4: - # Two wheeled vehicles take much longer to render + bicicles shouldn't behave like cars - continue - blueprints_.append(bp) - else: - blueprints_ = blueprints - - blueprint = CarlaDataProvider._rng.choice(blueprints_) - except ValueError: - # The model is not part of the blueprint library. Let's take a default one for the given category - bp_filter = "vehicle.*" - new_model = _actor_blueprint_categories[actor_category] - if new_model != '': - bp_filter = new_model - print("WARNING: Actor model {} not available. Using instead {}".format(model, new_model)) - blueprint = CarlaDataProvider._rng.choice(CarlaDataProvider._blueprint_library.filter(bp_filter)) - - # Set the color - if color: - if not blueprint.has_attribute('color'): - print( - "WARNING: Cannot set Color ({}) for actor {} due to missing blueprint attribute".format( - color, blueprint.id)) - else: - default_color_rgba = blueprint.get_attribute('color').as_color() - default_color = '({}, {}, {})'.format(default_color_rgba.r, default_color_rgba.g, default_color_rgba.b) - try: - blueprint.set_attribute('color', color) - except ValueError: - # Color can't be set for this vehicle - print("WARNING: Color ({}) cannot be set for actor {}. Using instead: ({})".format( - color, blueprint.id, default_color)) - blueprint.set_attribute('color', default_color) - else: - if blueprint.has_attribute('color') and rolename != 'hero': - color = CarlaDataProvider._rng.choice(blueprint.get_attribute('color').recommended_values) - blueprint.set_attribute('color', color) - - # Make pedestrians mortal - if blueprint.has_attribute('is_invincible'): - blueprint.set_attribute('is_invincible', 'false') - - # Set the rolename - if blueprint.has_attribute('role_name'): - blueprint.set_attribute('role_name', rolename) - - return blueprint - - @staticmethod - def handle_actor_batch(batch, tick=True): - """ - Forward a CARLA command batch to spawn actors to CARLA, and gather the responses. - Returns list of actors on success, none otherwise - """ - sync_mode = CarlaDataProvider.is_sync_mode() - actors = [] - - if CarlaDataProvider._client: - responses = CarlaDataProvider._client.apply_batch_sync(batch, sync_mode and tick) - else: - raise ValueError("class member \'client'\' not initialized yet") - - # Wait (or not) for the actors to be spawned properly before we do anything - if not tick: - pass - elif sync_mode: - CarlaDataProvider._world.tick() - else: - CarlaDataProvider._world.wait_for_tick() - - actor_ids = [r.actor_id for r in responses if not r.error] - for r in responses: - if r.error: - print("WARNING: Not all actors were spawned") - break - actors = list(CarlaDataProvider._world.get_actors(actor_ids)) - return actors - - @staticmethod - def request_new_actor(model, spawn_point, rolename='scenario', autopilot=False, - random_location=False, color=None, actor_category="car", - safe_blueprint=False, tick=True): - """ - This method tries to create a new actor, returning it if successful (None otherwise). - """ - blueprint = CarlaDataProvider.create_blueprint(model, rolename, color, actor_category, safe_blueprint) - - if random_location: - actor = None - while not actor: - spawn_point = CarlaDataProvider._rng.choice(CarlaDataProvider._spawn_points) - actor = CarlaDataProvider._world.try_spawn_actor(blueprint, spawn_point) - - else: - # slightly lift the actor to avoid collisions with ground when spawning the actor - # DO NOT USE spawn_point directly, as this will modify spawn_point permanently - _spawn_point = carla.Transform(carla.Location(), spawn_point.rotation) - _spawn_point.location.x = spawn_point.location.x - _spawn_point.location.y = spawn_point.location.y - _spawn_point.location.z = spawn_point.location.z + 0.2 - actor = CarlaDataProvider._world.try_spawn_actor(blueprint, _spawn_point) - - if actor is None: - print("WARNING: Cannot spawn actor {} at position {}".format(model, spawn_point.location)) - return None - - # De/activate the autopilot of the actor if it belongs to vehicle - if autopilot: - if actor.type_id.startswith('vehicle.'): - actor.set_autopilot(autopilot, CarlaDataProvider._traffic_manager_port) - else: - print("WARNING: Tried to set the autopilot of a non vehicle actor") - - # Wait for the actor to be spawned properly before we do anything - if not tick: - pass - elif CarlaDataProvider.is_sync_mode(): - CarlaDataProvider._world.tick() - else: - CarlaDataProvider._world.wait_for_tick() - - CarlaDataProvider._carla_actor_pool[actor.id] = actor - CarlaDataProvider.register_actor(actor) - return actor - - @staticmethod - def request_new_actors(actor_list, safe_blueprint=False, tick=True): - """ - This method tries to series of actor in batch. If this was successful, - the new actors are returned, None otherwise. - - param: - - actor_list: list of ActorConfigurationData - """ - - SpawnActor = carla.command.SpawnActor # pylint: disable=invalid-name - PhysicsCommand = carla.command.SetSimulatePhysics # pylint: disable=invalid-name - FutureActor = carla.command.FutureActor # pylint: disable=invalid-name - ApplyTransform = carla.command.ApplyTransform # pylint: disable=invalid-name - SetAutopilot = carla.command.SetAutopilot # pylint: disable=invalid-name - SetVehicleLightState = carla.command.SetVehicleLightState # pylint: disable=invalid-name - - batch = [] - - CarlaDataProvider.generate_spawn_points() - - for actor in actor_list: - - # Get the blueprint - blueprint = CarlaDataProvider.create_blueprint( - actor.model, actor.rolename, actor.color, actor.category, safe_blueprint) - - # Get the spawn point - transform = actor.transform - if actor.random_location: - if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points): - print("No more spawn points to use") - break - else: - _spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index] # pylint: disable=unsubscriptable-object - CarlaDataProvider._spawn_index += 1 - - else: - _spawn_point = carla.Transform() - _spawn_point.rotation = transform.rotation - _spawn_point.location.x = transform.location.x - _spawn_point.location.y = transform.location.y - if blueprint.has_tag('walker'): - # On imported OpenDRIVE maps, spawning of pedestrians can fail. - # By increasing the z-value the chances of success are increased. - map_name = CarlaDataProvider._map.name.split("/")[-1] - if not map_name.startswith('OpenDrive'): - _spawn_point.location.z = transform.location.z + 0.2 - else: - _spawn_point.location.z = transform.location.z + 0.8 - else: - _spawn_point.location.z = transform.location.z + 0.2 - - # Get the command - command = SpawnActor(blueprint, _spawn_point) - command.then(SetAutopilot(FutureActor, actor.autopilot, CarlaDataProvider._traffic_manager_port)) - - if actor.args is not None and 'physics' in actor.args and actor.args['physics'] == "off": - command.then(ApplyTransform(FutureActor, _spawn_point)).then(PhysicsCommand(FutureActor, False)) - elif actor.category == 'misc': - command.then(PhysicsCommand(FutureActor, True)) - if actor.args is not None and 'lights' in actor.args and actor.args['lights'] == "on": - command.then(SetVehicleLightState(FutureActor, carla.VehicleLightState.All)) - - batch.append(command) - - actors = CarlaDataProvider.handle_actor_batch(batch, tick) - for actor in actors: - if actor is None: - continue - CarlaDataProvider._carla_actor_pool[actor.id] = actor - CarlaDataProvider.register_actor(actor) - - return actors - - @staticmethod - def request_new_batch_actors(model, amount, spawn_points, autopilot=False, - random_location=False, rolename='scenario', - safe_blueprint=False, tick=True): - """ - Simplified version of "request_new_actors". This method also create several actors in batch. - - Instead of needing a list of ActorConfigurationData, an "amount" parameter is used. - This makes actor spawning easier but reduces the amount of configurability. - - Some parameters are the same for all actors (rolename, autopilot and random location) - while others are randomized (color) - """ - - SpawnActor = carla.command.SpawnActor # pylint: disable=invalid-name - SetAutopilot = carla.command.SetAutopilot # pylint: disable=invalid-name - FutureActor = carla.command.FutureActor # pylint: disable=invalid-name - - CarlaDataProvider.generate_spawn_points() - - batch = [] - - for i in range(amount): - # Get vehicle by model - blueprint = CarlaDataProvider.create_blueprint(model, rolename, safe=safe_blueprint) - - if random_location: - if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points): - print("No more spawn points to use. Spawned {} actors out of {}".format(i + 1, amount)) - break - else: - spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index] # pylint: disable=unsubscriptable-object - CarlaDataProvider._spawn_index += 1 - else: - try: - spawn_point = spawn_points[i] - except IndexError: - print("The amount of spawn points is lower than the amount of vehicles spawned") - break - - if spawn_point: - batch.append(SpawnActor(blueprint, spawn_point).then( - SetAutopilot(FutureActor, autopilot, - CarlaDataProvider._traffic_manager_port))) - - actors = CarlaDataProvider.handle_actor_batch(batch, tick) - for actor in actors: - if actor is None: - continue - CarlaDataProvider._carla_actor_pool[actor.id] = actor - CarlaDataProvider.register_actor(actor) - - return actors - - @staticmethod - def get_actors(): - """ - Return list of actors and their ids - - Note: iteritems from six is used to allow compatibility with Python 2 and 3 - """ - return iteritems(CarlaDataProvider._carla_actor_pool) - - @staticmethod - def actor_id_exists(actor_id): - """ - Check if a certain id is still at the simulation - """ - if actor_id in CarlaDataProvider._carla_actor_pool: - return True - - return False - - @staticmethod - def get_hero_actor(): - """ - Get the actor object of the hero actor if it exists, returns none otherwise. - """ - for actor_id in CarlaDataProvider._carla_actor_pool: - if CarlaDataProvider._carla_actor_pool[actor_id].attributes['role_name'] == 'hero': - return CarlaDataProvider._carla_actor_pool[actor_id] - return None - - @staticmethod - def get_actor_by_id(actor_id): - """ - Get an actor from the pool by using its ID. If the actor - does not exist, None is returned. - """ - if actor_id in CarlaDataProvider._carla_actor_pool: - return CarlaDataProvider._carla_actor_pool[actor_id] - - print("Non-existing actor id {}".format(actor_id)) - return None - - @staticmethod - def remove_actor_by_id(actor_id): - """ - Remove an actor from the pool using its ID - """ - if actor_id in CarlaDataProvider._carla_actor_pool: - CarlaDataProvider._carla_actor_pool[actor_id].destroy() - CarlaDataProvider._carla_actor_pool[actor_id] = None - CarlaDataProvider._carla_actor_pool.pop(actor_id) - else: - print("Trying to remove a non-existing actor id {}".format(actor_id)) - - @staticmethod - def remove_actors_in_surrounding(location, distance): - """ - Remove all actors from the pool that are closer than distance to the - provided location - """ - for actor_id in CarlaDataProvider._carla_actor_pool.copy(): - if CarlaDataProvider._carla_actor_pool[actor_id].get_location().distance(location) < distance: - CarlaDataProvider._carla_actor_pool[actor_id].destroy() - CarlaDataProvider._carla_actor_pool.pop(actor_id) - - # Remove all keys with None values - CarlaDataProvider._carla_actor_pool = dict({k: v for k, v in CarlaDataProvider._carla_actor_pool.items() if v}) - - @staticmethod - def get_traffic_manager_port(): - """ - Get the port of the traffic manager. - """ - return CarlaDataProvider._traffic_manager_port - - @staticmethod - def set_traffic_manager_port(tm_port): - """ - Set the port to use for the traffic manager. - """ - CarlaDataProvider._traffic_manager_port = tm_port - - @staticmethod - def cleanup(): - """ - Cleanup and remove all entries from all dictionaries - """ - DestroyActor = carla.command.DestroyActor # pylint: disable=invalid-name - batch = [] - - for actor_id in CarlaDataProvider._carla_actor_pool.copy(): - actor = CarlaDataProvider._carla_actor_pool[actor_id] - # don't delete the DReyeVR ego vehicle bc it becomes awkward to continue playing - if actor is not None and actor.is_alive and "dreyevr" not in actor.type_id: - batch.append(DestroyActor(actor)) - - if CarlaDataProvider._client: - try: - CarlaDataProvider._client.apply_batch_sync(batch) - except RuntimeError as e: - if "time-out" in str(e): - pass - else: - raise e - - CarlaDataProvider._actor_velocity_map.clear() - CarlaDataProvider._actor_location_map.clear() - CarlaDataProvider._actor_transform_map.clear() - CarlaDataProvider._traffic_light_map.clear() - CarlaDataProvider._map = None - CarlaDataProvider._world = None - CarlaDataProvider._sync_flag = False - CarlaDataProvider._ego_vehicle_route = None - CarlaDataProvider._carla_actor_pool = {} - CarlaDataProvider._client = None - CarlaDataProvider._spawn_points = None - CarlaDataProvider._spawn_index = 0 - CarlaDataProvider._rng = random.RandomState(CarlaDataProvider._random_seed) +#!/usr/bin/env python + +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +""" +This module provides all frequently used data from CARLA via +local buffers to avoid blocking calls to CARLA +""" + +from __future__ import print_function + +import math +import re +from numpy import random +from six import iteritems + +import carla + + +def calculate_velocity(actor): + """ + Method to calculate the velocity of a actor + """ + velocity_squared = actor.get_velocity().x**2 + velocity_squared += actor.get_velocity().y**2 + return math.sqrt(velocity_squared) + + +class CarlaDataProvider(object): # pylint: disable=too-many-public-methods + + """ + This class provides access to various data of all registered actors + It buffers the data and updates it on every CARLA tick + + Currently available data: + - Absolute velocity + - Location + - Transform + + Potential additions: + - Acceleration + + In addition it provides access to the map and the transform of all traffic lights + """ + + _actor_velocity_map = {} + _actor_location_map = {} + _actor_transform_map = {} + _traffic_light_map = {} + _carla_actor_pool = {} + _global_osc_parameters = {} + _client = None + _world = None + _map = None + _sync_flag = False + _spawn_points = None + _spawn_index = 0 + _blueprint_library = None + _ego_vehicle_route = None + _traffic_manager_port = 8000 + _random_seed = 2000 + _rng = random.RandomState(_random_seed) + + @staticmethod + def register_actor(actor): + """ + Add new actor to dictionaries + If actor already exists, throw an exception + """ + if actor in CarlaDataProvider._actor_velocity_map: + raise KeyError( + "Vehicle '{}' already registered. Cannot register twice!".format(actor.id)) + else: + CarlaDataProvider._actor_velocity_map[actor] = 0.0 + + if actor in CarlaDataProvider._actor_location_map: + raise KeyError( + "Vehicle '{}' already registered. Cannot register twice!".format(actor.id)) + else: + CarlaDataProvider._actor_location_map[actor] = None + + if actor in CarlaDataProvider._actor_transform_map: + raise KeyError( + "Vehicle '{}' already registered. Cannot register twice!".format(actor.id)) + else: + CarlaDataProvider._actor_transform_map[actor] = None + + @staticmethod + def update_osc_global_params(parameters): + """ + updates/initializes global osc parameters. + """ + CarlaDataProvider._global_osc_parameters.update(parameters) + + @staticmethod + def get_osc_global_param_value(ref): + """ + returns updated global osc parameter value. + """ + return CarlaDataProvider._global_osc_parameters.get(ref.replace("$", "")) + + @staticmethod + def register_actors(actors): + """ + Add new set of actors to dictionaries + """ + for actor in actors: + CarlaDataProvider.register_actor(actor) + + @staticmethod + def on_carla_tick(): + """ + Callback from CARLA + """ + for actor in CarlaDataProvider._actor_velocity_map: + if actor is not None and actor.is_alive: + CarlaDataProvider._actor_velocity_map[actor] = calculate_velocity(actor) + + for actor in CarlaDataProvider._actor_location_map: + if actor is not None and actor.is_alive: + CarlaDataProvider._actor_location_map[actor] = actor.get_location() + + for actor in CarlaDataProvider._actor_transform_map: + if actor is not None and actor.is_alive: + CarlaDataProvider._actor_transform_map[actor] = actor.get_transform() + + world = CarlaDataProvider._world + if world is None: + print("WARNING: CarlaDataProvider couldn't find the world") + + @staticmethod + def get_velocity(actor): + """ + returns the absolute velocity for the given actor + """ + for key in CarlaDataProvider._actor_velocity_map: + if key.id == actor.id: + return CarlaDataProvider._actor_velocity_map[key] + + # We are intentionally not throwing here + # This may cause exception loops in py_trees + print('{}.get_velocity: {} not found!' .format(__name__, actor)) + return 0.0 + + @staticmethod + def get_location(actor): + """ + returns the location for the given actor + """ + for key in CarlaDataProvider._actor_location_map: + if key.id == actor.id: + return CarlaDataProvider._actor_location_map[key] + + # We are intentionally not throwing here + # This may cause exception loops in py_trees + print('{}.get_location: {} not found!' .format(__name__, actor)) + return None + + @staticmethod + def get_transform(actor): + """ + returns the transform for the given actor + """ + for key in CarlaDataProvider._actor_transform_map: + if key.id == actor.id: + return CarlaDataProvider._actor_transform_map[key] + + # We are intentionally not throwing here + # This may cause exception loops in py_trees + print('{}.get_transform: {} not found!' .format(__name__, actor)) + return None + + @staticmethod + def set_client(client): + """ + Set the CARLA client + """ + CarlaDataProvider._client = client + + @staticmethod + def get_client(): + """ + Get the CARLA client + """ + return CarlaDataProvider._client + + @staticmethod + def set_world(world): + """ + Set the world and world settings + """ + CarlaDataProvider._world = world + CarlaDataProvider._sync_flag = world.get_settings().synchronous_mode + CarlaDataProvider._map = world.get_map() + CarlaDataProvider._blueprint_library = world.get_blueprint_library() + CarlaDataProvider.generate_spawn_points() + CarlaDataProvider.prepare_map() + + @staticmethod + def get_world(): + """ + Return world + """ + return CarlaDataProvider._world + + @staticmethod + def get_map(world=None): + """ + Get the current map + """ + if CarlaDataProvider._map is None: + if world is None: + if CarlaDataProvider._world is None: + raise ValueError("class member \'world'\' not initialized yet") + else: + CarlaDataProvider._map = CarlaDataProvider._world.get_map() + else: + CarlaDataProvider._map = world.get_map() + + return CarlaDataProvider._map + + @staticmethod + def get_random_seed(): + """ + @return true if syncronuous mode is used + """ + return CarlaDataProvider._rng + + @staticmethod + def is_sync_mode(): + """ + @return true if syncronuous mode is used + """ + return CarlaDataProvider._sync_flag + + @staticmethod + def find_weather_presets(): + """ + Get weather presets from CARLA + """ + rgx = re.compile('.+?(?:(?<=[a-z])(?=[A-Z])|(?<=[A-Z])(?=[A-Z][a-z])|$)') + def name(x:str) -> str: + return ' '.join(m.group(0) for m in rgx.finditer(x)) + presets = [x for x in dir(carla.WeatherParameters) if re.match('[A-Z].+', x)] + return [(getattr(carla.WeatherParameters, x), name(x)) for x in presets] + + @staticmethod + def prepare_map(): + """ + This function set the current map and loads all traffic lights for this map to + _traffic_light_map + """ + if CarlaDataProvider._map is None: + CarlaDataProvider._map = CarlaDataProvider._world.get_map() + + # Parse all traffic lights + CarlaDataProvider._traffic_light_map.clear() + for traffic_light in CarlaDataProvider._world.get_actors().filter('*traffic_light*'): + if traffic_light not in list(CarlaDataProvider._traffic_light_map): + CarlaDataProvider._traffic_light_map[traffic_light] = traffic_light.get_transform() + else: + raise KeyError( + "Traffic light '{}' already registered. Cannot register twice!".format(traffic_light.id)) + + @staticmethod + def annotate_trafficlight_in_group(traffic_light): + """ + Get dictionary with traffic light group info for a given traffic light + """ + dict_annotations = {'ref': [], 'opposite': [], 'left': [], 'right': []} + + # Get the waypoints + ref_location = CarlaDataProvider.get_trafficlight_trigger_location(traffic_light) + ref_waypoint = CarlaDataProvider.get_map().get_waypoint(ref_location) + ref_yaw = ref_waypoint.transform.rotation.yaw + + group_tl = traffic_light.get_group_traffic_lights() + + for target_tl in group_tl: + if traffic_light.id == target_tl.id: + dict_annotations['ref'].append(target_tl) + else: + # Get the angle between yaws + target_location = CarlaDataProvider.get_trafficlight_trigger_location(target_tl) + target_waypoint = CarlaDataProvider.get_map().get_waypoint(target_location) + target_yaw = target_waypoint.transform.rotation.yaw + + diff = (target_yaw - ref_yaw) % 360 + + if diff > 330: + continue + elif diff > 225: + dict_annotations['right'].append(target_tl) + elif diff > 135.0: + dict_annotations['opposite'].append(target_tl) + elif diff > 30: + dict_annotations['left'].append(target_tl) + + return dict_annotations + + @staticmethod + def get_trafficlight_trigger_location(traffic_light): # pylint: disable=invalid-name + """ + Calculates the yaw of the waypoint that represents the trigger volume of the traffic light + """ + def rotate_point(point, angle): + """ + rotate a given point by a given angle + """ + x_ = math.cos(math.radians(angle)) * point.x - math.sin(math.radians(angle)) * point.y + y_ = math.sin(math.radians(angle)) * point.x - math.cos(math.radians(angle)) * point.y + + return carla.Vector3D(x_, y_, point.z) + + base_transform = traffic_light.get_transform() + base_rot = base_transform.rotation.yaw + area_loc = base_transform.transform(traffic_light.trigger_volume.location) + area_ext = traffic_light.trigger_volume.extent + + point = rotate_point(carla.Vector3D(0, 0, area_ext.z), base_rot) + point_location = area_loc + carla.Location(x=point.x, y=point.y) + + return carla.Location(point_location.x, point_location.y, point_location.z) + + @staticmethod + def update_light_states(ego_light, annotations, states, freeze=False, timeout=1000000000): + """ + Update traffic light states + """ + reset_params = [] + + for state in states: + relevant_lights = [] + if state == 'ego': + relevant_lights = [ego_light] + else: + relevant_lights = annotations[state] + for light in relevant_lights: + prev_state = light.get_state() + prev_green_time = light.get_green_time() + prev_red_time = light.get_red_time() + prev_yellow_time = light.get_yellow_time() + reset_params.append({'light': light, + 'state': prev_state, + 'green_time': prev_green_time, + 'red_time': prev_red_time, + 'yellow_time': prev_yellow_time}) + + light.set_state(states[state]) + if freeze: + light.set_green_time(timeout) + light.set_red_time(timeout) + light.set_yellow_time(timeout) + + return reset_params + + @staticmethod + def reset_lights(reset_params): + """ + Reset traffic lights + """ + for param in reset_params: + param['light'].set_state(param['state']) + param['light'].set_green_time(param['green_time']) + param['light'].set_red_time(param['red_time']) + param['light'].set_yellow_time(param['yellow_time']) + + @staticmethod + def get_next_traffic_light(actor, use_cached_location=True): + """ + returns the next relevant traffic light for the provided actor + """ + + if not use_cached_location: + location = actor.get_transform().location + else: + location = CarlaDataProvider.get_location(actor) + + waypoint = CarlaDataProvider.get_map().get_waypoint(location) + # Create list of all waypoints until next intersection + list_of_waypoints = [] + while waypoint and not waypoint.is_intersection: + list_of_waypoints.append(waypoint) + waypoint = waypoint.next(2.0)[0] + + # If the list is empty, the actor is in an intersection + if not list_of_waypoints: + return None + + relevant_traffic_light = None + distance_to_relevant_traffic_light = float("inf") + + for traffic_light in CarlaDataProvider._traffic_light_map: + if hasattr(traffic_light, 'trigger_volume'): + tl_t = CarlaDataProvider._traffic_light_map[traffic_light] + transformed_tv = tl_t.transform(traffic_light.trigger_volume.location) + distance = carla.Location(transformed_tv).distance(list_of_waypoints[-1].transform.location) + + if distance < distance_to_relevant_traffic_light: + relevant_traffic_light = traffic_light + distance_to_relevant_traffic_light = distance + + return relevant_traffic_light + + @staticmethod + def set_ego_vehicle_route(route): + """ + Set the route of the ego vehicle + + @todo extend ego_vehicle_route concept to support multi ego_vehicle scenarios + """ + CarlaDataProvider._ego_vehicle_route = route + + @staticmethod + def get_ego_vehicle_route(): + """ + returns the currently set route of the ego vehicle + Note: Can be None + """ + return CarlaDataProvider._ego_vehicle_route + + @staticmethod + def generate_spawn_points(): + """ + Generate spawn points for the current map + """ + spawn_points = list(CarlaDataProvider.get_map(CarlaDataProvider._world).get_spawn_points()) + CarlaDataProvider._rng.shuffle(spawn_points) + CarlaDataProvider._spawn_points = spawn_points + CarlaDataProvider._spawn_index = 0 + + @staticmethod + def create_blueprint(model, rolename='scenario', color=None, actor_category="car", safe=False): + """ + Function to setup the blueprint of an actor given its model and other relevant parameters + """ + + _actor_blueprint_categories = { + 'car': 'vehicle.tesla.model3', + 'van': 'vehicle.volkswagen.t2', + 'truck': 'vehicle.carlamotors.carlacola', + 'trailer': '', + 'semitrailer': '', + 'bus': 'vehicle.volkswagen.t2', + 'motorbike': 'vehicle.kawasaki.ninja', + 'bicycle': 'vehicle.diamondback.century', + 'train': '', + 'tram': '', + 'pedestrian': 'walker.pedestrian.0001', + } + + # Set the model + try: + blueprints = CarlaDataProvider._blueprint_library.filter(model) + blueprints_ = [] + if safe: + for bp in blueprints: + if bp.id.endswith('firetruck') or bp.id.endswith('ambulance') \ + or int(bp.get_attribute('number_of_wheels')) != 4: + # Two wheeled vehicles take much longer to render + bicicles shouldn't behave like cars + continue + blueprints_.append(bp) + else: + blueprints_ = blueprints + + blueprint = CarlaDataProvider._rng.choice(blueprints_) + except ValueError: + # The model is not part of the blueprint library. Let's take a default one for the given category + bp_filter = "vehicle.*" + new_model = _actor_blueprint_categories[actor_category] + if new_model != '': + bp_filter = new_model + print("WARNING: Actor model {} not available. Using instead {}".format(model, new_model)) + blueprint = CarlaDataProvider._rng.choice(CarlaDataProvider._blueprint_library.filter(bp_filter)) + + # Set the color + if color: + if not blueprint.has_attribute('color'): + print( + "WARNING: Cannot set Color ({}) for actor {} due to missing blueprint attribute".format( + color, blueprint.id)) + else: + default_color_rgba = blueprint.get_attribute('color').as_color() + default_color = '({}, {}, {})'.format(default_color_rgba.r, default_color_rgba.g, default_color_rgba.b) + try: + blueprint.set_attribute('color', color) + except ValueError: + # Color can't be set for this vehicle + print("WARNING: Color ({}) cannot be set for actor {}. Using instead: ({})".format( + color, blueprint.id, default_color)) + blueprint.set_attribute('color', default_color) + else: + if blueprint.has_attribute('color') and rolename != 'hero': + color = CarlaDataProvider._rng.choice(blueprint.get_attribute('color').recommended_values) + blueprint.set_attribute('color', color) + + # Make pedestrians mortal + if blueprint.has_attribute('is_invincible'): + blueprint.set_attribute('is_invincible', 'false') + + # Set the rolename + if blueprint.has_attribute('role_name'): + blueprint.set_attribute('role_name', rolename) + + return blueprint + + @staticmethod + def handle_actor_batch(batch, tick=True): + """ + Forward a CARLA command batch to spawn actors to CARLA, and gather the responses. + Returns list of actors on success, none otherwise + """ + sync_mode = CarlaDataProvider.is_sync_mode() + actors = [] + + if CarlaDataProvider._client: + responses = CarlaDataProvider._client.apply_batch_sync(batch, sync_mode and tick) + else: + raise ValueError("class member \'client'\' not initialized yet") + + # Wait (or not) for the actors to be spawned properly before we do anything + if not tick: + pass + elif sync_mode: + CarlaDataProvider._world.tick() + else: + CarlaDataProvider._world.wait_for_tick() + + actor_ids = [r.actor_id for r in responses if not r.error] + for r in responses: + if r.error: + print("WARNING: Not all actors were spawned") + break + actors = list(CarlaDataProvider._world.get_actors(actor_ids)) + return actors + + @staticmethod + def request_new_actor(model, spawn_point, rolename='scenario', autopilot=False, + random_location=False, color=None, actor_category="car", + safe_blueprint=False, tick=True): + """ + This method tries to create a new actor, returning it if successful (None otherwise). + """ + blueprint = CarlaDataProvider.create_blueprint(model, rolename, color, actor_category, safe_blueprint) + + if random_location: + actor = None + while not actor: + spawn_point = CarlaDataProvider._rng.choice(CarlaDataProvider._spawn_points) + actor = CarlaDataProvider._world.try_spawn_actor(blueprint, spawn_point) + + else: + # slightly lift the actor to avoid collisions with ground when spawning the actor + # DO NOT USE spawn_point directly, as this will modify spawn_point permanently + _spawn_point = carla.Transform(carla.Location(), spawn_point.rotation) + _spawn_point.location.x = spawn_point.location.x + _spawn_point.location.y = spawn_point.location.y + _spawn_point.location.z = spawn_point.location.z + 0.2 + actor = CarlaDataProvider._world.try_spawn_actor(blueprint, _spawn_point) + + if actor is None: + print("WARNING: Cannot spawn actor {} at position {}".format(model, spawn_point.location)) + return None + + # De/activate the autopilot of the actor if it belongs to vehicle + if autopilot: + if actor.type_id.startswith('vehicle.'): + actor.set_autopilot(autopilot, CarlaDataProvider._traffic_manager_port) + else: + print("WARNING: Tried to set the autopilot of a non vehicle actor") + + # Wait for the actor to be spawned properly before we do anything + if not tick: + pass + elif CarlaDataProvider.is_sync_mode(): + CarlaDataProvider._world.tick() + else: + CarlaDataProvider._world.wait_for_tick() + + CarlaDataProvider._carla_actor_pool[actor.id] = actor + CarlaDataProvider.register_actor(actor) + return actor + + @staticmethod + def request_new_actors(actor_list, safe_blueprint=False, tick=True): + """ + This method tries to series of actor in batch. If this was successful, + the new actors are returned, None otherwise. + + param: + - actor_list: list of ActorConfigurationData + """ + + SpawnActor = carla.command.SpawnActor # pylint: disable=invalid-name + PhysicsCommand = carla.command.SetSimulatePhysics # pylint: disable=invalid-name + FutureActor = carla.command.FutureActor # pylint: disable=invalid-name + ApplyTransform = carla.command.ApplyTransform # pylint: disable=invalid-name + SetAutopilot = carla.command.SetAutopilot # pylint: disable=invalid-name + SetVehicleLightState = carla.command.SetVehicleLightState # pylint: disable=invalid-name + + batch = [] + + CarlaDataProvider.generate_spawn_points() + + for actor in actor_list: + + # Get the blueprint + blueprint = CarlaDataProvider.create_blueprint( + actor.model, actor.rolename, actor.color, actor.category, safe_blueprint) + + # Get the spawn point + transform = actor.transform + if actor.random_location: + if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points): + print("No more spawn points to use") + break + else: + _spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index] # pylint: disable=unsubscriptable-object + CarlaDataProvider._spawn_index += 1 + + else: + _spawn_point = carla.Transform() + _spawn_point.rotation = transform.rotation + _spawn_point.location.x = transform.location.x + _spawn_point.location.y = transform.location.y + if blueprint.has_tag('walker'): + # On imported OpenDRIVE maps, spawning of pedestrians can fail. + # By increasing the z-value the chances of success are increased. + map_name = CarlaDataProvider._map.name.split("/")[-1] + if not map_name.startswith('OpenDrive'): + _spawn_point.location.z = transform.location.z + 0.2 + else: + _spawn_point.location.z = transform.location.z + 0.8 + else: + _spawn_point.location.z = transform.location.z + 0.2 + + # Get the command + command = SpawnActor(blueprint, _spawn_point) + command.then(SetAutopilot(FutureActor, actor.autopilot, CarlaDataProvider._traffic_manager_port)) + + if actor.args is not None and 'physics' in actor.args and actor.args['physics'] == "off": + command.then(ApplyTransform(FutureActor, _spawn_point)).then(PhysicsCommand(FutureActor, False)) + elif actor.category == 'misc': + command.then(PhysicsCommand(FutureActor, True)) + if actor.args is not None and 'lights' in actor.args and actor.args['lights'] == "on": + command.then(SetVehicleLightState(FutureActor, carla.VehicleLightState.All)) + + batch.append(command) + + actors = CarlaDataProvider.handle_actor_batch(batch, tick) + for actor in actors: + if actor is None: + continue + CarlaDataProvider._carla_actor_pool[actor.id] = actor + CarlaDataProvider.register_actor(actor) + + return actors + + @staticmethod + def request_new_batch_actors(model, amount, spawn_points, autopilot=False, + random_location=False, rolename='scenario', + safe_blueprint=False, tick=True): + """ + Simplified version of "request_new_actors". This method also create several actors in batch. + + Instead of needing a list of ActorConfigurationData, an "amount" parameter is used. + This makes actor spawning easier but reduces the amount of configurability. + + Some parameters are the same for all actors (rolename, autopilot and random location) + while others are randomized (color) + """ + + SpawnActor = carla.command.SpawnActor # pylint: disable=invalid-name + SetAutopilot = carla.command.SetAutopilot # pylint: disable=invalid-name + FutureActor = carla.command.FutureActor # pylint: disable=invalid-name + + CarlaDataProvider.generate_spawn_points() + + batch = [] + + for i in range(amount): + # Get vehicle by model + blueprint = CarlaDataProvider.create_blueprint(model, rolename, safe=safe_blueprint) + + if random_location: + if CarlaDataProvider._spawn_index >= len(CarlaDataProvider._spawn_points): + print("No more spawn points to use. Spawned {} actors out of {}".format(i + 1, amount)) + break + else: + spawn_point = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index] # pylint: disable=unsubscriptable-object + CarlaDataProvider._spawn_index += 1 + else: + try: + spawn_point = spawn_points[i] + except IndexError: + print("The amount of spawn points is lower than the amount of vehicles spawned") + break + + if spawn_point: + batch.append(SpawnActor(blueprint, spawn_point).then( + SetAutopilot(FutureActor, autopilot, + CarlaDataProvider._traffic_manager_port))) + + actors = CarlaDataProvider.handle_actor_batch(batch, tick) + for actor in actors: + if actor is None: + continue + CarlaDataProvider._carla_actor_pool[actor.id] = actor + CarlaDataProvider.register_actor(actor) + + return actors + + @staticmethod + def get_actors(): + """ + Return list of actors and their ids + + Note: iteritems from six is used to allow compatibility with Python 2 and 3 + """ + return iteritems(CarlaDataProvider._carla_actor_pool) + + @staticmethod + def actor_id_exists(actor_id): + """ + Check if a certain id is still at the simulation + """ + if actor_id in CarlaDataProvider._carla_actor_pool: + return True + + return False + + @staticmethod + def get_hero_actor(): + """ + Get the actor object of the hero actor if it exists, returns none otherwise. + """ + for actor_id in CarlaDataProvider._carla_actor_pool: + if CarlaDataProvider._carla_actor_pool[actor_id].attributes['role_name'] == 'hero': + return CarlaDataProvider._carla_actor_pool[actor_id] + return None + + @staticmethod + def get_actor_by_id(actor_id): + """ + Get an actor from the pool by using its ID. If the actor + does not exist, None is returned. + """ + if actor_id in CarlaDataProvider._carla_actor_pool: + return CarlaDataProvider._carla_actor_pool[actor_id] + + print("Non-existing actor id {}".format(actor_id)) + return None + + @staticmethod + def remove_actor_by_id(actor_id): + """ + Remove an actor from the pool using its ID + """ + if actor_id in CarlaDataProvider._carla_actor_pool: + CarlaDataProvider._carla_actor_pool[actor_id].destroy() + CarlaDataProvider._carla_actor_pool[actor_id] = None + CarlaDataProvider._carla_actor_pool.pop(actor_id) + else: + print("Trying to remove a non-existing actor id {}".format(actor_id)) + + @staticmethod + def remove_actors_in_surrounding(location, distance): + """ + Remove all actors from the pool that are closer than distance to the + provided location + """ + for actor_id in CarlaDataProvider._carla_actor_pool.copy(): + if CarlaDataProvider._carla_actor_pool[actor_id].get_location().distance(location) < distance: + CarlaDataProvider._carla_actor_pool[actor_id].destroy() + CarlaDataProvider._carla_actor_pool.pop(actor_id) + + # Remove all keys with None values + CarlaDataProvider._carla_actor_pool = dict({k: v for k, v in CarlaDataProvider._carla_actor_pool.items() if v}) + + @staticmethod + def get_traffic_manager_port(): + """ + Get the port of the traffic manager. + """ + return CarlaDataProvider._traffic_manager_port + + @staticmethod + def set_traffic_manager_port(tm_port): + """ + Set the port to use for the traffic manager. + """ + CarlaDataProvider._traffic_manager_port = tm_port + + @staticmethod + def cleanup(): + """ + Cleanup and remove all entries from all dictionaries + """ + DestroyActor = carla.command.DestroyActor # pylint: disable=invalid-name + batch = [] + + for actor_id in CarlaDataProvider._carla_actor_pool.copy(): + actor = CarlaDataProvider._carla_actor_pool[actor_id] + # don't delete the DReyeVR ego vehicle bc it becomes awkward to continue playing + if actor is not None and actor.is_alive and "dreyevr" not in actor.type_id: + batch.append(DestroyActor(actor)) + + if CarlaDataProvider._client: + try: + CarlaDataProvider._client.apply_batch_sync(batch) + except RuntimeError as e: + if "time-out" in str(e): + pass + else: + raise e + + CarlaDataProvider._actor_velocity_map.clear() + CarlaDataProvider._actor_location_map.clear() + CarlaDataProvider._actor_transform_map.clear() + CarlaDataProvider._traffic_light_map.clear() + CarlaDataProvider._map = None + CarlaDataProvider._world = None + CarlaDataProvider._sync_flag = False + CarlaDataProvider._ego_vehicle_route = None + CarlaDataProvider._carla_actor_pool = {} + CarlaDataProvider._client = None + CarlaDataProvider._spawn_points = None + CarlaDataProvider._spawn_index = 0 + CarlaDataProvider._rng = random.RandomState(CarlaDataProvider._random_seed) diff --git a/ScenarioRunner/route_parser.py b/ScenarioRunner/route_parser.py index c553792..bd42204 100644 --- a/ScenarioRunner/route_parser.py +++ b/ScenarioRunner/route_parser.py @@ -1,358 +1,358 @@ -#!/usr/bin/env python - -# This work is licensed under the terms of the MIT license. -# For a copy, see . - -""" -Module used to parse all the route and scenario configuration parameters. -""" - -import os -import json -import math -import xml.etree.ElementTree as ET - -import carla -from agents.navigation.local_planner import RoadOption -from srunner.scenarioconfigs.route_scenario_configuration import RouteScenarioConfiguration - -# TODO check this threshold, it could be a bit larger but not so large that we cluster scenarios. -TRIGGER_THRESHOLD = 2.0 # Threshold to say if a trigger position is new or repeated, works for matching positions -TRIGGER_ANGLE_THRESHOLD = 10 # Threshold to say if two angles can be considering matching when matching transforms. - - -class RouteParser(object): - - """ - Pure static class used to parse all the route and scenario configuration parameters. - """ - - @staticmethod - def parse_annotations_file(annotation_filename): - """ - Return the annotations of which positions where the scenarios are going to happen. - :param annotation_filename: the filename for the anotations file - :return: - """ - - with open(annotation_filename, 'r', encoding='utf-8') as f: - annotation_dict = json.loads(f.read()) - - final_dict = {} - - for town_dict in annotation_dict['available_scenarios']: - final_dict.update(town_dict) - - return final_dict # the file has a current maps name that is an one element vec - - @staticmethod - def parse_routes_file(route_filename, scenario_file, single_route=None): - """ - Returns a list of route elements. - :param route_filename: the path to a set of routes. - :param single_route: If set, only this route shall be returned - :return: List of dicts containing the waypoints, id and town of the routes - """ - - list_route_descriptions = [] - tree = ET.parse(route_filename) - for route in tree.iter("route"): - - route_id = route.attrib['id'] - if single_route and route_id != single_route: - continue - - new_config = RouteScenarioConfiguration() - new_config.town = route.attrib['town'] - new_config.name = "RouteScenario_{}".format(route_id) - new_config.weather = RouteParser.parse_weather(route) - new_config.scenario_file = scenario_file - new_config.scenario_number = single_route - - waypoint_list = [] # the list of waypoints that can be found on this route - for waypoint in route.iter('waypoint'): - waypoint_list.append(carla.Location(x=float(waypoint.attrib['x']), - y=float(waypoint.attrib['y']), - z=float(waypoint.attrib['z']))) - - new_config.trajectory = waypoint_list - - list_route_descriptions.append(new_config) - - return list_route_descriptions - - @staticmethod - def parse_weather(route): - """ - Returns a carla.WeatherParameters with the corresponding weather for that route. If the route - has no weather attribute, the default one is triggered. - """ - - route_weather = route.find("weather") - if route_weather is None: - - weather = carla.WeatherParameters(sun_altitude_angle=70) - - else: - weather = carla.WeatherParameters() - for weather_attrib in route.iter("weather"): - - if 'cloudiness' in weather_attrib.attrib: - weather.cloudiness = float(weather_attrib.attrib['cloudiness']) - if 'precipitation' in weather_attrib.attrib: - weather.precipitation = float(weather_attrib.attrib['precipitation']) - if 'precipitation_deposits' in weather_attrib.attrib: - weather.precipitation_deposits = float(weather_attrib.attrib['precipitation_deposits']) - if 'wind_intensity' in weather_attrib.attrib: - weather.wind_intensity = float(weather_attrib.attrib['wind_intensity']) - if 'sun_azimuth_angle' in weather_attrib.attrib: - weather.sun_azimuth_angle = float(weather_attrib.attrib['sun_azimuth_angle']) - if 'sun_altitude_angle' in weather_attrib.attrib: - weather.sun_altitude_angle = float(weather_attrib.attrib['sun_altitude_angle']) - if 'wetness' in weather_attrib.attrib: - weather.wetness = float(weather_attrib.attrib['wetness']) - if 'fog_distance' in weather_attrib.attrib: - weather.fog_distance = float(weather_attrib.attrib['fog_distance']) - if 'fog_density' in weather_attrib.attrib: - weather.fog_density = float(weather_attrib.attrib['fog_density']) - - return weather - - @staticmethod - def parse_direction_signs_file(signs_filename, single_route=None): - """ - Return the annotations of where to place which signs to give human users - directions when driving in the simulator. - :param signs_filename: the filename for the sign placement data file - :param single_route: the route id (int) to specify which sign route - :return: dictionary of sign types and transforms - """ - if not os.path.exists(signs_filename): - return None - with open(signs_filename, 'r', encoding='UTF-8') as f: - signs_dict = json.loads(f.read()) - - routes_dict = signs_dict['available_routes'][0] - - for route_name in routes_dict.keys(): - route_num = route_name.strip("Route") - if int(route_num) == int(single_route): - return routes_dict[route_name] - - return None - - @staticmethod - def check_trigger_position(new_trigger, existing_triggers): - """ - Check if this trigger position already exists or if it is a new one. - :param new_trigger: - :param existing_triggers: - :return: - """ - - for trigger_id in existing_triggers.keys(): - trigger = existing_triggers[trigger_id] - dx = trigger['x'] - new_trigger['x'] - dy = trigger['y'] - new_trigger['y'] - distance = math.sqrt(dx * dx + dy * dy) - - dyaw = (trigger['yaw'] - new_trigger['yaw']) % 360 - if distance < TRIGGER_THRESHOLD \ - and (dyaw < TRIGGER_ANGLE_THRESHOLD or dyaw > (360 - TRIGGER_ANGLE_THRESHOLD)): - return trigger_id - - return None - - @staticmethod - def convert_waypoint_float(waypoint): - """ - Convert waypoint values to float - """ - waypoint['x'] = float(waypoint['x']) - waypoint['y'] = float(waypoint['y']) - waypoint['z'] = float(waypoint['z']) - waypoint['yaw'] = float(waypoint['yaw']) - - @staticmethod - def convert_dict2transform(waypoint): - """ - Convert waypoint values to Carla.transform - """ - transform = carla.Transform() - transform.location.x = float(waypoint['x']) - transform.location.y = float(waypoint['y']) - transform.location.z = float(waypoint['z']) - transform.rotation.yaw = float(waypoint['yaw']) - return transform - - @staticmethod - def match_world_location_to_route(world_location, route_description): - """ - We match this location to a given route. - world_location: - route_description: - """ - def match_waypoints(waypoint1, wtransform): - """ - Check if waypoint1 and wtransform are similar - """ - dx = float(waypoint1['x']) - wtransform.location.x - dy = float(waypoint1['y']) - wtransform.location.y - dz = float(waypoint1['z']) - wtransform.location.z - dpos = math.sqrt(dx * dx + dy * dy + dz * dz) - - dyaw = (float(waypoint1['yaw']) - wtransform.rotation.yaw) % 360 - - return dpos < TRIGGER_THRESHOLD \ - and (dyaw < TRIGGER_ANGLE_THRESHOLD or dyaw > (360 - TRIGGER_ANGLE_THRESHOLD)) - - match_position = 0 - # TODO this function can be optimized to run on Log(N) time - for route_waypoint in route_description: - if match_waypoints(world_location, route_waypoint[0]): - return match_position - match_position += 1 - - return None - - @staticmethod - def get_scenario_type(scenario, match_position, trajectory): - """ - Some scenarios have different types depending on the route. - :param scenario: the scenario name - :param match_position: the matching position for the scenarion - :param trajectory: the route trajectory the ego is following - :return: tag representing this subtype - - Also used to check which are not viable (Such as an scenario - that triggers when turning but the route doesnt') - WARNING: These tags are used at: - - VehicleTurningRoute - - SignalJunctionCrossingRoute - and changes to these tags will affect them - """ - - def check_this_waypoint(tuple_wp_turn): - """ - Decides whether or not the waypoint will define the scenario behavior - """ - if RoadOption.LANEFOLLOW == tuple_wp_turn[1]: - return False - elif RoadOption.CHANGELANELEFT == tuple_wp_turn[1]: - return False - elif RoadOption.CHANGELANERIGHT == tuple_wp_turn[1]: - return False - return True - - # Unused tag for the rest of scenarios, - # can't be None as they are still valid scenarios - subtype = 'valid' - - if scenario == 'Scenario4': - for tuple_wp_turn in trajectory[match_position:]: - if check_this_waypoint(tuple_wp_turn): - if RoadOption.LEFT == tuple_wp_turn[1]: - subtype = 'S4left' - elif RoadOption.RIGHT == tuple_wp_turn[1]: - subtype = 'S4right' - else: - subtype = None - break # Avoid checking all of them - subtype = None - - if scenario == 'Scenario7': - for tuple_wp_turn in trajectory[match_position:]: - if check_this_waypoint(tuple_wp_turn): - if RoadOption.STRAIGHT == tuple_wp_turn[1]: - subtype = 'S7opposite' - else: - subtype = None - break # Avoid checking all of them - subtype = None - - if scenario == 'Scenario8': - for tuple_wp_turn in trajectory[match_position:]: - if check_this_waypoint(tuple_wp_turn): - if RoadOption.LEFT == tuple_wp_turn[1]: - subtype = 'S8left' - else: - subtype = None - break # Avoid checking all of them - subtype = None - - if scenario == 'Scenario9': - for tuple_wp_turn in trajectory[match_position:]: - if check_this_waypoint(tuple_wp_turn): - if RoadOption.RIGHT == tuple_wp_turn[1]: - subtype = 'S9right' - else: - subtype = None - break # Avoid checking all of them - subtype = None - - return subtype - - @staticmethod - def scan_route_for_scenarios(route_name, trajectory, world_annotations): - """ - Just returns a plain list of possible scenarios that can happen in this route by matching - the locations from the scenario into the route description - - :return: A list of scenario definitions with their correspondent parameters - """ - - # the triggers dictionaries: - existent_triggers = {} - # We have a table of IDs and trigger positions associated - possible_scenarios = {} - - # Keep track of the trigger ids being added - latest_trigger_id = 0 - - for town_name in world_annotations.keys(): - if town_name != route_name: - continue - - scenarios = world_annotations[town_name] - for scenario in scenarios: # For each existent scenario - if "scenario_type" not in scenario: - break - scenario_name = scenario["scenario_type"] - for event in scenario["available_event_configurations"]: - waypoint = event['transform'] # trigger point of this scenario - RouteParser.convert_waypoint_float(waypoint) - # We match trigger point to the route, now we need to check if the route affects - match_position = RouteParser.match_world_location_to_route( - waypoint, trajectory) - if match_position is not None: - # We match a location for this scenario, create a scenario object so this scenario - # can be instantiated later - - if 'other_actors' in event: - other_vehicles = event['other_actors'] - else: - other_vehicles = None - scenario_subtype = RouteParser.get_scenario_type(scenario_name, match_position, - trajectory) - if scenario_subtype is None: - continue - scenario_description = { - 'name': scenario_name, - 'other_actors': other_vehicles, - 'trigger_position': waypoint, - 'scenario_type': scenario_subtype, # some scenarios have route dependent configs - } - - trigger_id = RouteParser.check_trigger_position(waypoint, existent_triggers) - if trigger_id is None: - # This trigger does not exist create a new reference on existent triggers - existent_triggers.update({latest_trigger_id: waypoint}) - # Update a reference for this trigger on the possible scenarios - possible_scenarios.update({latest_trigger_id: []}) - trigger_id = latest_trigger_id - # Increment the latest trigger - latest_trigger_id += 1 - - possible_scenarios[trigger_id].append(scenario_description) - - return possible_scenarios, existent_triggers +#!/usr/bin/env python + +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +""" +Module used to parse all the route and scenario configuration parameters. +""" + +import os +import json +import math +import xml.etree.ElementTree as ET + +import carla +from agents.navigation.local_planner import RoadOption +from srunner.scenarioconfigs.route_scenario_configuration import RouteScenarioConfiguration + +# TODO check this threshold, it could be a bit larger but not so large that we cluster scenarios. +TRIGGER_THRESHOLD = 2.0 # Threshold to say if a trigger position is new or repeated, works for matching positions +TRIGGER_ANGLE_THRESHOLD = 10 # Threshold to say if two angles can be considering matching when matching transforms. + + +class RouteParser(object): + + """ + Pure static class used to parse all the route and scenario configuration parameters. + """ + + @staticmethod + def parse_annotations_file(annotation_filename): + """ + Return the annotations of which positions where the scenarios are going to happen. + :param annotation_filename: the filename for the anotations file + :return: + """ + + with open(annotation_filename, 'r', encoding='utf-8') as f: + annotation_dict = json.loads(f.read()) + + final_dict = {} + + for town_dict in annotation_dict['available_scenarios']: + final_dict.update(town_dict) + + return final_dict # the file has a current maps name that is an one element vec + + @staticmethod + def parse_routes_file(route_filename, scenario_file, single_route=None): + """ + Returns a list of route elements. + :param route_filename: the path to a set of routes. + :param single_route: If set, only this route shall be returned + :return: List of dicts containing the waypoints, id and town of the routes + """ + + list_route_descriptions = [] + tree = ET.parse(route_filename) + for route in tree.iter("route"): + + route_id = route.attrib['id'] + if single_route and route_id != single_route: + continue + + new_config = RouteScenarioConfiguration() + new_config.town = route.attrib['town'] + new_config.name = "RouteScenario_{}".format(route_id) + new_config.weather = RouteParser.parse_weather(route) + new_config.scenario_file = scenario_file + new_config.scenario_number = single_route + + waypoint_list = [] # the list of waypoints that can be found on this route + for waypoint in route.iter('waypoint'): + waypoint_list.append(carla.Location(x=float(waypoint.attrib['x']), + y=float(waypoint.attrib['y']), + z=float(waypoint.attrib['z']))) + + new_config.trajectory = waypoint_list + + list_route_descriptions.append(new_config) + + return list_route_descriptions + + @staticmethod + def parse_weather(route): + """ + Returns a carla.WeatherParameters with the corresponding weather for that route. If the route + has no weather attribute, the default one is triggered. + """ + + route_weather = route.find("weather") + if route_weather is None: + + weather = carla.WeatherParameters(sun_altitude_angle=70) + + else: + weather = carla.WeatherParameters() + for weather_attrib in route.iter("weather"): + + if 'cloudiness' in weather_attrib.attrib: + weather.cloudiness = float(weather_attrib.attrib['cloudiness']) + if 'precipitation' in weather_attrib.attrib: + weather.precipitation = float(weather_attrib.attrib['precipitation']) + if 'precipitation_deposits' in weather_attrib.attrib: + weather.precipitation_deposits = float(weather_attrib.attrib['precipitation_deposits']) + if 'wind_intensity' in weather_attrib.attrib: + weather.wind_intensity = float(weather_attrib.attrib['wind_intensity']) + if 'sun_azimuth_angle' in weather_attrib.attrib: + weather.sun_azimuth_angle = float(weather_attrib.attrib['sun_azimuth_angle']) + if 'sun_altitude_angle' in weather_attrib.attrib: + weather.sun_altitude_angle = float(weather_attrib.attrib['sun_altitude_angle']) + if 'wetness' in weather_attrib.attrib: + weather.wetness = float(weather_attrib.attrib['wetness']) + if 'fog_distance' in weather_attrib.attrib: + weather.fog_distance = float(weather_attrib.attrib['fog_distance']) + if 'fog_density' in weather_attrib.attrib: + weather.fog_density = float(weather_attrib.attrib['fog_density']) + + return weather + + @staticmethod + def parse_direction_signs_file(signs_filename, single_route=None): + """ + Return the annotations of where to place which signs to give human users + directions when driving in the simulator. + :param signs_filename: the filename for the sign placement data file + :param single_route: the route id (int) to specify which sign route + :return: dictionary of sign types and transforms + """ + if not os.path.exists(signs_filename): + return None + with open(signs_filename, 'r', encoding='UTF-8') as f: + signs_dict = json.loads(f.read()) + + routes_dict = signs_dict['available_routes'][0] + + for route_name in routes_dict.keys(): + route_num = route_name.strip("Route") + if int(route_num) == int(single_route): + return routes_dict[route_name] + + return None + + @staticmethod + def check_trigger_position(new_trigger, existing_triggers): + """ + Check if this trigger position already exists or if it is a new one. + :param new_trigger: + :param existing_triggers: + :return: + """ + + for trigger_id in existing_triggers.keys(): + trigger = existing_triggers[trigger_id] + dx = trigger['x'] - new_trigger['x'] + dy = trigger['y'] - new_trigger['y'] + distance = math.sqrt(dx * dx + dy * dy) + + dyaw = (trigger['yaw'] - new_trigger['yaw']) % 360 + if distance < TRIGGER_THRESHOLD \ + and (dyaw < TRIGGER_ANGLE_THRESHOLD or dyaw > (360 - TRIGGER_ANGLE_THRESHOLD)): + return trigger_id + + return None + + @staticmethod + def convert_waypoint_float(waypoint): + """ + Convert waypoint values to float + """ + waypoint['x'] = float(waypoint['x']) + waypoint['y'] = float(waypoint['y']) + waypoint['z'] = float(waypoint['z']) + waypoint['yaw'] = float(waypoint['yaw']) + + @staticmethod + def convert_dict2transform(waypoint): + """ + Convert waypoint values to Carla.transform + """ + transform = carla.Transform() + transform.location.x = float(waypoint['x']) + transform.location.y = float(waypoint['y']) + transform.location.z = float(waypoint['z']) + transform.rotation.yaw = float(waypoint['yaw']) + return transform + + @staticmethod + def match_world_location_to_route(world_location, route_description): + """ + We match this location to a given route. + world_location: + route_description: + """ + def match_waypoints(waypoint1, wtransform): + """ + Check if waypoint1 and wtransform are similar + """ + dx = float(waypoint1['x']) - wtransform.location.x + dy = float(waypoint1['y']) - wtransform.location.y + dz = float(waypoint1['z']) - wtransform.location.z + dpos = math.sqrt(dx * dx + dy * dy + dz * dz) + + dyaw = (float(waypoint1['yaw']) - wtransform.rotation.yaw) % 360 + + return dpos < TRIGGER_THRESHOLD \ + and (dyaw < TRIGGER_ANGLE_THRESHOLD or dyaw > (360 - TRIGGER_ANGLE_THRESHOLD)) + + match_position = 0 + # TODO this function can be optimized to run on Log(N) time + for route_waypoint in route_description: + if match_waypoints(world_location, route_waypoint[0]): + return match_position + match_position += 1 + + return None + + @staticmethod + def get_scenario_type(scenario, match_position, trajectory): + """ + Some scenarios have different types depending on the route. + :param scenario: the scenario name + :param match_position: the matching position for the scenarion + :param trajectory: the route trajectory the ego is following + :return: tag representing this subtype + + Also used to check which are not viable (Such as an scenario + that triggers when turning but the route doesnt') + WARNING: These tags are used at: + - VehicleTurningRoute + - SignalJunctionCrossingRoute + and changes to these tags will affect them + """ + + def check_this_waypoint(tuple_wp_turn): + """ + Decides whether or not the waypoint will define the scenario behavior + """ + if RoadOption.LANEFOLLOW == tuple_wp_turn[1]: + return False + elif RoadOption.CHANGELANELEFT == tuple_wp_turn[1]: + return False + elif RoadOption.CHANGELANERIGHT == tuple_wp_turn[1]: + return False + return True + + # Unused tag for the rest of scenarios, + # can't be None as they are still valid scenarios + subtype = 'valid' + + if scenario == 'Scenario4': + for tuple_wp_turn in trajectory[match_position:]: + if check_this_waypoint(tuple_wp_turn): + if RoadOption.LEFT == tuple_wp_turn[1]: + subtype = 'S4left' + elif RoadOption.RIGHT == tuple_wp_turn[1]: + subtype = 'S4right' + else: + subtype = None + break # Avoid checking all of them + subtype = None + + if scenario == 'Scenario7': + for tuple_wp_turn in trajectory[match_position:]: + if check_this_waypoint(tuple_wp_turn): + if RoadOption.STRAIGHT == tuple_wp_turn[1]: + subtype = 'S7opposite' + else: + subtype = None + break # Avoid checking all of them + subtype = None + + if scenario == 'Scenario8': + for tuple_wp_turn in trajectory[match_position:]: + if check_this_waypoint(tuple_wp_turn): + if RoadOption.LEFT == tuple_wp_turn[1]: + subtype = 'S8left' + else: + subtype = None + break # Avoid checking all of them + subtype = None + + if scenario == 'Scenario9': + for tuple_wp_turn in trajectory[match_position:]: + if check_this_waypoint(tuple_wp_turn): + if RoadOption.RIGHT == tuple_wp_turn[1]: + subtype = 'S9right' + else: + subtype = None + break # Avoid checking all of them + subtype = None + + return subtype + + @staticmethod + def scan_route_for_scenarios(route_name, trajectory, world_annotations): + """ + Just returns a plain list of possible scenarios that can happen in this route by matching + the locations from the scenario into the route description + + :return: A list of scenario definitions with their correspondent parameters + """ + + # the triggers dictionaries: + existent_triggers = {} + # We have a table of IDs and trigger positions associated + possible_scenarios = {} + + # Keep track of the trigger ids being added + latest_trigger_id = 0 + + for town_name in world_annotations.keys(): + if town_name != route_name: + continue + + scenarios = world_annotations[town_name] + for scenario in scenarios: # For each existent scenario + if "scenario_type" not in scenario: + break + scenario_name = scenario["scenario_type"] + for event in scenario["available_event_configurations"]: + waypoint = event['transform'] # trigger point of this scenario + RouteParser.convert_waypoint_float(waypoint) + # We match trigger point to the route, now we need to check if the route affects + match_position = RouteParser.match_world_location_to_route( + waypoint, trajectory) + if match_position is not None: + # We match a location for this scenario, create a scenario object so this scenario + # can be instantiated later + + if 'other_actors' in event: + other_vehicles = event['other_actors'] + else: + other_vehicles = None + scenario_subtype = RouteParser.get_scenario_type(scenario_name, match_position, + trajectory) + if scenario_subtype is None: + continue + scenario_description = { + 'name': scenario_name, + 'other_actors': other_vehicles, + 'trigger_position': waypoint, + 'scenario_type': scenario_subtype, # some scenarios have route dependent configs + } + + trigger_id = RouteParser.check_trigger_position(waypoint, existent_triggers) + if trigger_id is None: + # This trigger does not exist create a new reference on existent triggers + existent_triggers.update({latest_trigger_id: waypoint}) + # Update a reference for this trigger on the possible scenarios + possible_scenarios.update({latest_trigger_id: []}) + trigger_id = latest_trigger_id + # Increment the latest trigger + latest_trigger_id += 1 + + possible_scenarios[trigger_id].append(scenario_description) + + return possible_scenarios, existent_triggers diff --git a/ScenarioRunner/route_scenario.py b/ScenarioRunner/route_scenario.py index 021f46a..4302582 100644 --- a/ScenarioRunner/route_scenario.py +++ b/ScenarioRunner/route_scenario.py @@ -1,611 +1,611 @@ -#!/usr/bin/env python - -# Copyright (c) 2019-2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . - -""" -This module provides Challenge routes as standalone scenarios -""" - -from __future__ import print_function - -import math -import traceback -import xml.etree.ElementTree as ET - -import py_trees - -import carla - -from agents.navigation.local_planner import RoadOption - -# DReyeVR import -from examples.DReyeVR_utils import find_ego_vehicle - -# pylint: disable=line-too-long -from srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData -# pylint: enable=line-too-long -from srunner.scenariomanager.carla_data_provider import CarlaDataProvider -from srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle, ScenarioTriggerer -from srunner.scenarios.basic_scenario import BasicScenario -from srunner.tools.route_parser import RouteParser, TRIGGER_THRESHOLD, TRIGGER_ANGLE_THRESHOLD -from srunner.tools.route_manipulation import interpolate_trajectory -from srunner.tools.py_trees_port import oneshot_behavior - -from srunner.scenarios.control_loss import ControlLoss -from srunner.scenarios.follow_leading_vehicle import FollowLeadingVehicleRoute -from srunner.scenarios.object_crash_vehicle import DynamicObjectCrossing -from srunner.scenarios.object_crash_intersection import VehicleTurningRoute -from srunner.scenarios.other_leading_vehicle import OtherLeadingVehicle -from srunner.scenarios.maneuver_opposite_direction import ManeuverOppositeDirection -from srunner.scenarios.junction_crossing_route import NoSignalJunctionCrossingRoute -from srunner.scenarios.signalized_junction_left_turn import SignalizedJunctionLeftTurn -from srunner.scenarios.signalized_junction_right_turn import SignalizedJunctionRightTurn -from srunner.scenarios.opposite_vehicle_taking_priority import OppositeVehicleRunningRedLight -from srunner.scenarios.background_activity import BackgroundActivity - -from srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest, - InRouteTest, - RouteCompletionTest, - OutsideRouteLanesTest, - RunningRedLightTest, - RunningStopTest, - ActorSpeedAboveThresholdTest) - -SECONDS_GIVEN_PER_METERS = 0.4 - -NUMBER_CLASS_TRANSLATION = { - "Scenario1": ControlLoss, - "Scenario2": FollowLeadingVehicleRoute, - "Scenario3": DynamicObjectCrossing, - "Scenario4": VehicleTurningRoute, - "Scenario5": OtherLeadingVehicle, - "Scenario6": ManeuverOppositeDirection, - "Scenario7": OppositeVehicleRunningRedLight, - "Scenario8": SignalizedJunctionLeftTurn, - "Scenario9": SignalizedJunctionRightTurn, - "Scenario10": NoSignalJunctionCrossingRoute -} - - -def convert_json_to_transform(actor_dict): - """ - Convert a JSON string to a CARLA transform - """ - return carla.Transform(location=carla.Location(x=float(actor_dict['x']), y=float(actor_dict['y']), - z=float(actor_dict['z'])), - rotation=carla.Rotation(roll=0.0, pitch=0.0, yaw=float(actor_dict['yaw']))) - - -def convert_json_to_actor(actor_dict): - """ - Convert a JSON string to an ActorConfigurationData dictionary - """ - node = ET.Element('waypoint') - node.set('x', actor_dict['x']) - node.set('y', actor_dict['y']) - node.set('z', actor_dict['z']) - node.set('yaw', actor_dict['yaw']) - - return ActorConfigurationData.parse_from_node(node, 'simulation') - - -def convert_transform_to_location(transform_vec): - """ - Convert a vector of transforms to a vector of locations - """ - location_vec = [] - for transform_tuple in transform_vec: - location_vec.append((transform_tuple[0].location, transform_tuple[1])) - - return location_vec - - -def compare_scenarios(scenario_choice, existent_scenario): - """ - Compare function for scenarios based on distance of the scenario start position - """ - def transform_to_pos_vec(scenario): - """ - Convert left/right/front to a meaningful CARLA position - """ - position_vec = [scenario['trigger_position']] - if scenario['other_actors'] is not None: - if 'left' in scenario['other_actors']: - position_vec += scenario['other_actors']['left'] - if 'front' in scenario['other_actors']: - position_vec += scenario['other_actors']['front'] - if 'right' in scenario['other_actors']: - position_vec += scenario['other_actors']['right'] - - return position_vec - - # put the positions of the scenario choice into a vec of positions to be able to compare - - choice_vec = transform_to_pos_vec(scenario_choice) - existent_vec = transform_to_pos_vec(existent_scenario) - for pos_choice in choice_vec: - for pos_existent in existent_vec: - - dx = float(pos_choice['x']) - float(pos_existent['x']) - dy = float(pos_choice['y']) - float(pos_existent['y']) - dz = float(pos_choice['z']) - float(pos_existent['z']) - dist_position = math.sqrt(dx * dx + dy * dy + dz * dz) - dyaw = float(pos_choice['yaw']) - float(pos_choice['yaw']) - dist_angle = math.sqrt(dyaw * dyaw) - if dist_position < TRIGGER_THRESHOLD and dist_angle < TRIGGER_ANGLE_THRESHOLD: - return True - - return False - - -class RouteScenario(BasicScenario): - - """ - Implementation of a RouteScenario, i.e. a scenario that consists of driving along a pre-defined route, - along which several smaller scenarios are triggered - """ - - def __init__(self, world, config, debug_mode=False, criteria_enable=True, timeout=300): - """ - Setup all relevant parameters and create scenarios along route - """ - - self.config = config - self.route = None - self.sampled_scenarios_definitions = None - - self._update_route(world, config, debug_mode) - - self.ego_vehicle = self._initialize_ego_vehicle_dreyevr(find_ego_vehicle(world)) - - self.list_scenarios = self._build_scenario_instances(world, - self.ego_vehicle, - self.sampled_scenarios_definitions, - scenarios_per_tick=5, - timeout=self.timeout, - debug_mode=debug_mode) - - self.list_scenarios.append(BackgroundActivity( - world, self.ego_vehicle, self.config, self.route, timeout=self.timeout)) - - super(RouteScenario, self).__init__(name=config.name, - ego_vehicles=[self.ego_vehicle], - config=config, - world=world, - debug_mode=False, - terminate_on_failure=False, - criteria_enable=criteria_enable) - - def _update_route(self, world, config, debug_mode): - """ - Update the input route, i.e. refine waypoint list, and extract possible scenario locations - - Parameters: - - world: CARLA world - - config: Scenario configuration (RouteConfiguration) - """ - - # Transform the scenario file into a dictionary - world_annotations = RouteParser.parse_annotations_file(config.scenario_file) - - # prepare route's trajectory (interpolate and add the GPS route) - gps_route, route = interpolate_trajectory(config.trajectory) - - potential_scenarios_definitions, _ = RouteParser.scan_route_for_scenarios(config.town, route, world_annotations) - - self.route = route - CarlaDataProvider.set_ego_vehicle_route(convert_transform_to_location(self.route)) - - if config.agent is not None: - config.agent.set_global_plan(gps_route, self.route) - - # Sample the scenarios to be used for this route instance. - self.sampled_scenarios_definitions = self._scenario_sampling(potential_scenarios_definitions) - - # Timeout of scenario in seconds - self.timeout = self._estimate_route_timeout() - - # Print route in debug mode - if debug_mode: - self._draw_waypoints(world, self.route, vertical_shift=0.1, persistency=50000.0) - - self._setup_nav_signs(self.route) - - def _initialize_ego_vehicle_dreyevr(self, ego_vehicle): - """ - Set/Update the start position of the ego_vehicle (instead of _update_ego_vehicle below) - """ - # move ego to correct position - elevate_transform = self.route[0][0] - elevate_transform.location.z += 0.5 - ego_vehicle.set_transform(elevate_transform) - CarlaDataProvider.register_actor(ego_vehicle) - return ego_vehicle - - def _update_ego_vehicle(self): - """ - Set/Update the start position of the ego_vehicle - """ - # move ego to correct position - elevate_transform = self.route[0][0] - elevate_transform.location.z += 0.5 - - ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz2017', - elevate_transform, - rolename='hero') - - return ego_vehicle - - def _estimate_route_timeout(self): - """ - Estimate the duration of the route - """ - route_length = 0.0 # in meters - - prev_point = self.route[0][0] - for current_point, _ in self.route[1:]: - dist = current_point.location.distance(prev_point.location) - route_length += dist - prev_point = current_point - - return int(SECONDS_GIVEN_PER_METERS * route_length) - - # pylint: disable=no-self-use - def _draw_waypoints(self, world, waypoints, vertical_shift, persistency=-1): - """ - Draw a list of waypoints at a certain height given in vertical_shift. - """ - for w in waypoints: - wp = w[0].location + carla.Location(z=vertical_shift) - - if w[1] == RoadOption.LEFT: # Yellow - color = carla.Color(255, 255, 0) - elif w[1] == RoadOption.RIGHT: # Cyan - color = carla.Color(0, 255, 255) - elif w[1] == RoadOption.CHANGELANELEFT: # Orange - color = carla.Color(255, 64, 0) - elif w[1] == RoadOption.CHANGELANERIGHT: # Dark Cyan - color = carla.Color(0, 64, 255) - elif w[1] == RoadOption.STRAIGHT: # Gray - color = carla.Color(128, 128, 128) - else: # LANEFOLLOW - color = carla.Color(0, 255, 0) # Green - - world.debug.draw_point(wp, size=0.1, color=color, life_time=persistency) - - world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=0.2, - color=carla.Color(0, 0, 255), life_time=persistency) - world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=0.2, - color=carla.Color(255, 0, 0), life_time=persistency) - - def _get_valid_sign_transform(self, wp_transform): - # use the original waypoint location as long as it is on a sidewalk - _wp = CarlaDataProvider.get_map().get_waypoint(wp_transform.location, - project_to_road=False, - lane_type=carla.LaneType.Any) - if _wp is None: - return None - # find the first non-road waypoint so our drivers can read it (with a limit) - max_tries: int = 100 - valid_sign_lanes = [ - carla.LaneType.Sidewalk, - # carla.LaneType.Shoulder, # disable shoulder - ] - while max_tries > 0 and _wp.lane_type not in valid_sign_lanes: - max_tries -= 1 - right_wp = _wp.get_right_lane() - if right_wp is not None: - _wp = right_wp - else: - continue # skip this one - # carla transforms don't have a native assignment operator :/ - t = carla.Transform(_wp.transform.location, _wp.transform.rotation) - if max_tries == 0: # didn't find a sidewalk, so push it slightly right by the road lane width - push = t.get_right_vector() * _wp.lane_width * 1.1 # 10% more just to be safe - # carla locations don't have a native += operator - t.location = carla.Location(x=t.location.x + push.x, - y=t.location.y + push.y, - z=t.location.z + push.z) - t.location.z += 2.0 # go up slightly (for the height of the road sign) - t.rotation.yaw += 90.0 # rotate another 90 degrees - return t - - def _setup_nav_signs(self, waypoints: list): - """ - Draw the signs along the waypoints of a route automatically - """ - prev_sign_type = None # only request new actor if nav type changes - for i, w in enumerate(waypoints): - wp_transform, sign_type = w - if prev_sign_type is not None and prev_sign_type == sign_type: - continue # only spawn a sign when the waypoint type changes - prev_sign_type = sign_type - sign_transform = self._get_valid_sign_transform(wp_transform) - if sign_transform is None: - continue # invalid - # now we can finally go about spawning the sign in this location - dreyevr_sign_type: str = "dreyevr_sign_straight" - if sign_type == RoadOption.LEFT: - dreyevr_sign_type = "dreyevr_sign_left" - elif sign_type == RoadOption.RIGHT: - dreyevr_sign_type = "dreyevr_sign_right" - elif sign_type == RoadOption.CHANGELANELEFT: - continue - elif sign_type == RoadOption.CHANGELANERIGHT: - continue - elif sign_type == RoadOption.STRAIGHT: - dreyevr_sign_type = "dreyevr_sign_straight" - else: - continue - sign_type: str = f"static.prop.{dreyevr_sign_type}" - print(f"Spawning ({sign_type}) sign {i} at {sign_transform}") - CarlaDataProvider.request_new_actor(sign_type, sign_transform, - rolename='navigation_sign') - # plot the final goal waypoint (at the end) - wp_transform_final = waypoints[-1][0] - goal_sign_transform = self._get_valid_sign_transform(wp_transform_final) - if goal_sign_transform is not None: - sign_type: str = "static.prop.dreyevr_sign_goal" - print(f"Spawning ({sign_type}) sign {len(waypoints) - 1} at {goal_sign_transform}") - CarlaDataProvider.request_new_actor(sign_type, - goal_sign_transform, - rolename='navigation_sign') - - def _scenario_sampling(self, potential_scenarios_definitions, random_seed=0): - """ - The function used to sample the scenarios that are going to happen for this route. - """ - - # fix the random seed for reproducibility - rng = CarlaDataProvider.get_random_seed() - - def position_sampled(scenario_choice, sampled_scenarios): - """ - Check if a position was already sampled, i.e. used for another scenario - """ - for existent_scenario in sampled_scenarios: - # If the scenarios have equal positions then it is true. - if compare_scenarios(scenario_choice, existent_scenario): - return True - - return False - - # The idea is to randomly sample a scenario per trigger position. - sampled_scenarios = [] - for trigger in potential_scenarios_definitions.keys(): - possible_scenarios = potential_scenarios_definitions[trigger] - - scenario_choice = rng.choice(possible_scenarios) - del possible_scenarios[possible_scenarios.index(scenario_choice)] - # We keep sampling and testing if this position is present on any of the scenarios. - while position_sampled(scenario_choice, sampled_scenarios): - if possible_scenarios is None or not possible_scenarios: - scenario_choice = None - break - scenario_choice = rng.choice(possible_scenarios) - del possible_scenarios[possible_scenarios.index(scenario_choice)] - - if scenario_choice is not None: - sampled_scenarios.append(scenario_choice) - - return sampled_scenarios - - def _build_scenario_instances(self, world, ego_vehicle, scenario_definitions, - scenarios_per_tick=5, timeout=300, debug_mode=False): - """ - Based on the parsed route and possible scenarios, build all the scenario classes. - """ - scenario_instance_vec = [] - - if debug_mode: - for scenario in scenario_definitions: - loc = carla.Location(scenario['trigger_position']['x'], - scenario['trigger_position']['y'], - scenario['trigger_position']['z']) + carla.Location(z=2.0) - world.debug.draw_point(loc, size=0.3, color=carla.Color(255, 0, 0), life_time=100000) - world.debug.draw_string(loc, str(scenario['name']), draw_shadow=False, - color=carla.Color(0, 0, 255), life_time=100000, persistent_lines=True) - - for scenario_number, definition in enumerate(scenario_definitions): - # Get the class possibilities for this scenario number - scenario_class = NUMBER_CLASS_TRANSLATION[definition['name']] - - # Create the other actors that are going to appear - if definition['other_actors'] is not None: - list_of_actor_conf_instances = self._get_actors_instances(definition['other_actors']) - else: - list_of_actor_conf_instances = [] - # Create an actor configuration for the ego-vehicle trigger position - - egoactor_trigger_position = convert_json_to_transform(definition['trigger_position']) - scenario_configuration = ScenarioConfiguration() - scenario_configuration.other_actors = list_of_actor_conf_instances - scenario_configuration.trigger_points = [egoactor_trigger_position] - scenario_configuration.subtype = definition['scenario_type'] - scenario_configuration.ego_vehicles = [ActorConfigurationData(ego_vehicle.type_id, - ego_vehicle.get_transform(), - 'hero')] - route_var_name = "ScenarioRouteNumber{}".format(scenario_number) - scenario_configuration.route_var_name = route_var_name - - try: - scenario_instance = scenario_class(world, [ego_vehicle], scenario_configuration, - criteria_enable=False, timeout=timeout) - # Do a tick every once in a while to avoid spawning everything at the same time - if scenario_number % scenarios_per_tick == 0: - if CarlaDataProvider.is_sync_mode(): - world.tick() - else: - world.wait_for_tick() - - scenario_number += 1 - except Exception as e: # pylint: disable=broad-except - if debug_mode: - traceback.print_exc() - print("Skipping scenario '{}' due to setup error: {}".format(definition['name'], e)) - continue - - scenario_instance_vec.append(scenario_instance) - - return scenario_instance_vec - - def _get_actors_instances(self, list_of_antagonist_actors): - """ - Get the full list of actor instances. - """ - - def get_actors_from_list(list_of_actor_def): - """ - Receives a list of actor definitions and creates an actual list of ActorConfigurationObjects - """ - sublist_of_actors = [] - for actor_def in list_of_actor_def: - sublist_of_actors.append(convert_json_to_actor(actor_def)) - - return sublist_of_actors - - list_of_actors = [] - # Parse vehicles to the left - if 'front' in list_of_antagonist_actors: - list_of_actors += get_actors_from_list(list_of_antagonist_actors['front']) - - if 'left' in list_of_antagonist_actors: - list_of_actors += get_actors_from_list(list_of_antagonist_actors['left']) - - if 'right' in list_of_antagonist_actors: - list_of_actors += get_actors_from_list(list_of_antagonist_actors['right']) - - return list_of_actors - - # pylint: enable=no-self-use - - def _initialize_actors(self, config): - """ - Set other_actors to the superset of all scenario actors - """ - # Create the background activity of the route - town_amount = { - 'Town01': 0, - 'Town02': 0, - 'Town03': 0, - 'Town04': 0, - 'Town05': 0, - 'Town06': 0, - 'Town07': 0, - 'Town08': 0, - 'Town09': 0, - 'Town10': 0, - } - - amount = town_amount[config.town] if config.town in town_amount else 0 - - new_actors = CarlaDataProvider.request_new_batch_actors('vehicle.*', - amount, - carla.Transform(), - autopilot=True, - random_location=True, - rolename='background') - - if new_actors is None: - raise RuntimeError("Error: Unable to add the background activity, all spawn points were occupied") - - if not hasattr(self, "other_actors"): - self.other_actors = [] - - for _actor in new_actors: - self.other_actors.append(_actor) - - # Add all the actors of the specific scenarios to self.other_actors - for scenario in self.list_scenarios: - self.other_actors.extend(scenario.other_actors) - - def _create_behavior(self): - """ - Basic behavior do nothing, i.e. Idle - """ - scenario_trigger_distance = 1.5 # Max trigger distance between route and scenario - - behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) - - subbehavior = py_trees.composites.Parallel(name="Behavior", - policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL) - - scenario_behaviors = [] - blackboard_list = [] - - for i, scenario in enumerate(self.list_scenarios): - if scenario.scenario.behavior is not None: - route_var_name = scenario.config.route_var_name - if route_var_name is not None: - scenario_behaviors.append(scenario.scenario.behavior) - blackboard_list.append([scenario.config.route_var_name, - scenario.config.trigger_points[0].location]) - else: - name = "{} - {}".format(i, scenario.scenario.behavior.name) - oneshot_idiom = oneshot_behavior(name, - behaviour=scenario.scenario.behavior, - name=name) - scenario_behaviors.append(oneshot_idiom) - - # Add behavior that manages the scenarios trigger conditions - scenario_triggerer = ScenarioTriggerer( - self.ego_vehicles[0], - self.route, - blackboard_list, - scenario_trigger_distance, - repeat_scenarios=False - ) - - subbehavior.add_child(scenario_triggerer) # make ScenarioTriggerer the first thing to be checked - subbehavior.add_children(scenario_behaviors) - subbehavior.add_child(Idle()) # The behaviours cannot make the route scenario stop - behavior.add_child(subbehavior) - - return behavior - - def _create_test_criteria(self): - """ - """ - - criteria = [] - - route = convert_transform_to_location(self.route) - - collision_criterion = CollisionTest(self.ego_vehicles[0], terminate_on_failure=False) - - route_criterion = InRouteTest(self.ego_vehicles[0], - route=route, - offroad_max=30, - terminate_on_failure=True) - - completion_criterion = RouteCompletionTest(self.ego_vehicles[0], route=route) - - outsidelane_criterion = OutsideRouteLanesTest(self.ego_vehicles[0], route=route) - - red_light_criterion = RunningRedLightTest(self.ego_vehicles[0]) - - stop_criterion = RunningStopTest(self.ego_vehicles[0]) - - blocked_criterion = ActorSpeedAboveThresholdTest(self.ego_vehicles[0], - speed_threshold=0.1, - below_threshold_max_time=90.0, - terminate_on_failure=True) - - criteria.append(completion_criterion) - criteria.append(collision_criterion) - criteria.append(route_criterion) - criteria.append(outsidelane_criterion) - criteria.append(red_light_criterion) - criteria.append(stop_criterion) - criteria.append(blocked_criterion) - - return criteria - - def __del__(self): - """ - Remove all actors upon deletion - """ - self.remove_all_actors() +#!/usr/bin/env python + +# Copyright (c) 2019-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +""" +This module provides Challenge routes as standalone scenarios +""" + +from __future__ import print_function + +import math +import traceback +import xml.etree.ElementTree as ET + +import py_trees + +import carla + +from agents.navigation.local_planner import RoadOption + +# DReyeVR import +from examples.DReyeVR_utils import find_ego_vehicle + +# pylint: disable=line-too-long +from srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData +# pylint: enable=line-too-long +from srunner.scenariomanager.carla_data_provider import CarlaDataProvider +from srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle, ScenarioTriggerer +from srunner.scenarios.basic_scenario import BasicScenario +from srunner.tools.route_parser import RouteParser, TRIGGER_THRESHOLD, TRIGGER_ANGLE_THRESHOLD +from srunner.tools.route_manipulation import interpolate_trajectory +from srunner.tools.py_trees_port import oneshot_behavior + +from srunner.scenarios.control_loss import ControlLoss +from srunner.scenarios.follow_leading_vehicle import FollowLeadingVehicleRoute +from srunner.scenarios.object_crash_vehicle import DynamicObjectCrossing +from srunner.scenarios.object_crash_intersection import VehicleTurningRoute +from srunner.scenarios.other_leading_vehicle import OtherLeadingVehicle +from srunner.scenarios.maneuver_opposite_direction import ManeuverOppositeDirection +from srunner.scenarios.junction_crossing_route import NoSignalJunctionCrossingRoute +from srunner.scenarios.signalized_junction_left_turn import SignalizedJunctionLeftTurn +from srunner.scenarios.signalized_junction_right_turn import SignalizedJunctionRightTurn +from srunner.scenarios.opposite_vehicle_taking_priority import OppositeVehicleRunningRedLight +from srunner.scenarios.background_activity import BackgroundActivity + +from srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest, + InRouteTest, + RouteCompletionTest, + OutsideRouteLanesTest, + RunningRedLightTest, + RunningStopTest, + ActorSpeedAboveThresholdTest) + +SECONDS_GIVEN_PER_METERS = 0.4 + +NUMBER_CLASS_TRANSLATION = { + "Scenario1": ControlLoss, + "Scenario2": FollowLeadingVehicleRoute, + "Scenario3": DynamicObjectCrossing, + "Scenario4": VehicleTurningRoute, + "Scenario5": OtherLeadingVehicle, + "Scenario6": ManeuverOppositeDirection, + "Scenario7": OppositeVehicleRunningRedLight, + "Scenario8": SignalizedJunctionLeftTurn, + "Scenario9": SignalizedJunctionRightTurn, + "Scenario10": NoSignalJunctionCrossingRoute +} + + +def convert_json_to_transform(actor_dict): + """ + Convert a JSON string to a CARLA transform + """ + return carla.Transform(location=carla.Location(x=float(actor_dict['x']), y=float(actor_dict['y']), + z=float(actor_dict['z'])), + rotation=carla.Rotation(roll=0.0, pitch=0.0, yaw=float(actor_dict['yaw']))) + + +def convert_json_to_actor(actor_dict): + """ + Convert a JSON string to an ActorConfigurationData dictionary + """ + node = ET.Element('waypoint') + node.set('x', actor_dict['x']) + node.set('y', actor_dict['y']) + node.set('z', actor_dict['z']) + node.set('yaw', actor_dict['yaw']) + + return ActorConfigurationData.parse_from_node(node, 'simulation') + + +def convert_transform_to_location(transform_vec): + """ + Convert a vector of transforms to a vector of locations + """ + location_vec = [] + for transform_tuple in transform_vec: + location_vec.append((transform_tuple[0].location, transform_tuple[1])) + + return location_vec + + +def compare_scenarios(scenario_choice, existent_scenario): + """ + Compare function for scenarios based on distance of the scenario start position + """ + def transform_to_pos_vec(scenario): + """ + Convert left/right/front to a meaningful CARLA position + """ + position_vec = [scenario['trigger_position']] + if scenario['other_actors'] is not None: + if 'left' in scenario['other_actors']: + position_vec += scenario['other_actors']['left'] + if 'front' in scenario['other_actors']: + position_vec += scenario['other_actors']['front'] + if 'right' in scenario['other_actors']: + position_vec += scenario['other_actors']['right'] + + return position_vec + + # put the positions of the scenario choice into a vec of positions to be able to compare + + choice_vec = transform_to_pos_vec(scenario_choice) + existent_vec = transform_to_pos_vec(existent_scenario) + for pos_choice in choice_vec: + for pos_existent in existent_vec: + + dx = float(pos_choice['x']) - float(pos_existent['x']) + dy = float(pos_choice['y']) - float(pos_existent['y']) + dz = float(pos_choice['z']) - float(pos_existent['z']) + dist_position = math.sqrt(dx * dx + dy * dy + dz * dz) + dyaw = float(pos_choice['yaw']) - float(pos_choice['yaw']) + dist_angle = math.sqrt(dyaw * dyaw) + if dist_position < TRIGGER_THRESHOLD and dist_angle < TRIGGER_ANGLE_THRESHOLD: + return True + + return False + + +class RouteScenario(BasicScenario): + + """ + Implementation of a RouteScenario, i.e. a scenario that consists of driving along a pre-defined route, + along which several smaller scenarios are triggered + """ + + def __init__(self, world, config, debug_mode=False, criteria_enable=True, timeout=300): + """ + Setup all relevant parameters and create scenarios along route + """ + + self.config = config + self.route = None + self.sampled_scenarios_definitions = None + + self._update_route(world, config, debug_mode) + + self.ego_vehicle = self._initialize_ego_vehicle_dreyevr(find_ego_vehicle(world)) + + self.list_scenarios = self._build_scenario_instances(world, + self.ego_vehicle, + self.sampled_scenarios_definitions, + scenarios_per_tick=5, + timeout=self.timeout, + debug_mode=debug_mode) + + self.list_scenarios.append(BackgroundActivity( + world, self.ego_vehicle, self.config, self.route, timeout=self.timeout)) + + super(RouteScenario, self).__init__(name=config.name, + ego_vehicles=[self.ego_vehicle], + config=config, + world=world, + debug_mode=False, + terminate_on_failure=False, + criteria_enable=criteria_enable) + + def _update_route(self, world, config, debug_mode): + """ + Update the input route, i.e. refine waypoint list, and extract possible scenario locations + + Parameters: + - world: CARLA world + - config: Scenario configuration (RouteConfiguration) + """ + + # Transform the scenario file into a dictionary + world_annotations = RouteParser.parse_annotations_file(config.scenario_file) + + # prepare route's trajectory (interpolate and add the GPS route) + gps_route, route = interpolate_trajectory(config.trajectory) + + potential_scenarios_definitions, _ = RouteParser.scan_route_for_scenarios(config.town, route, world_annotations) + + self.route = route + CarlaDataProvider.set_ego_vehicle_route(convert_transform_to_location(self.route)) + + if config.agent is not None: + config.agent.set_global_plan(gps_route, self.route) + + # Sample the scenarios to be used for this route instance. + self.sampled_scenarios_definitions = self._scenario_sampling(potential_scenarios_definitions) + + # Timeout of scenario in seconds + self.timeout = self._estimate_route_timeout() + + # Print route in debug mode + if debug_mode: + self._draw_waypoints(world, self.route, vertical_shift=0.1, persistency=50000.0) + + self._setup_nav_signs(self.route) + + def _initialize_ego_vehicle_dreyevr(self, ego_vehicle): + """ + Set/Update the start position of the ego_vehicle (instead of _update_ego_vehicle below) + """ + # move ego to correct position + elevate_transform = self.route[0][0] + elevate_transform.location.z += 0.5 + ego_vehicle.set_transform(elevate_transform) + CarlaDataProvider.register_actor(ego_vehicle) + return ego_vehicle + + def _update_ego_vehicle(self): + """ + Set/Update the start position of the ego_vehicle + """ + # move ego to correct position + elevate_transform = self.route[0][0] + elevate_transform.location.z += 0.5 + + ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz2017', + elevate_transform, + rolename='hero') + + return ego_vehicle + + def _estimate_route_timeout(self): + """ + Estimate the duration of the route + """ + route_length = 0.0 # in meters + + prev_point = self.route[0][0] + for current_point, _ in self.route[1:]: + dist = current_point.location.distance(prev_point.location) + route_length += dist + prev_point = current_point + + return int(SECONDS_GIVEN_PER_METERS * route_length) + + # pylint: disable=no-self-use + def _draw_waypoints(self, world, waypoints, vertical_shift, persistency=-1): + """ + Draw a list of waypoints at a certain height given in vertical_shift. + """ + for w in waypoints: + wp = w[0].location + carla.Location(z=vertical_shift) + + if w[1] == RoadOption.LEFT: # Yellow + color = carla.Color(255, 255, 0) + elif w[1] == RoadOption.RIGHT: # Cyan + color = carla.Color(0, 255, 255) + elif w[1] == RoadOption.CHANGELANELEFT: # Orange + color = carla.Color(255, 64, 0) + elif w[1] == RoadOption.CHANGELANERIGHT: # Dark Cyan + color = carla.Color(0, 64, 255) + elif w[1] == RoadOption.STRAIGHT: # Gray + color = carla.Color(128, 128, 128) + else: # LANEFOLLOW + color = carla.Color(0, 255, 0) # Green + + world.debug.draw_point(wp, size=0.1, color=color, life_time=persistency) + + world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=0.2, + color=carla.Color(0, 0, 255), life_time=persistency) + world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=0.2, + color=carla.Color(255, 0, 0), life_time=persistency) + + def _get_valid_sign_transform(self, wp_transform): + # use the original waypoint location as long as it is on a sidewalk + _wp = CarlaDataProvider.get_map().get_waypoint(wp_transform.location, + project_to_road=False, + lane_type=carla.LaneType.Any) + if _wp is None: + return None + # find the first non-road waypoint so our drivers can read it (with a limit) + max_tries: int = 100 + valid_sign_lanes = [ + carla.LaneType.Sidewalk, + # carla.LaneType.Shoulder, # disable shoulder + ] + while max_tries > 0 and _wp.lane_type not in valid_sign_lanes: + max_tries -= 1 + right_wp = _wp.get_right_lane() + if right_wp is not None: + _wp = right_wp + else: + continue # skip this one + # carla transforms don't have a native assignment operator :/ + t = carla.Transform(_wp.transform.location, _wp.transform.rotation) + if max_tries == 0: # didn't find a sidewalk, so push it slightly right by the road lane width + push = t.get_right_vector() * _wp.lane_width * 1.1 # 10% more just to be safe + # carla locations don't have a native += operator + t.location = carla.Location(x=t.location.x + push.x, + y=t.location.y + push.y, + z=t.location.z + push.z) + t.location.z += 2.0 # go up slightly (for the height of the road sign) + t.rotation.yaw += 90.0 # rotate another 90 degrees + return t + + def _setup_nav_signs(self, waypoints: list): + """ + Draw the signs along the waypoints of a route automatically + """ + prev_sign_type = None # only request new actor if nav type changes + for i, w in enumerate(waypoints): + wp_transform, sign_type = w + if prev_sign_type is not None and prev_sign_type == sign_type: + continue # only spawn a sign when the waypoint type changes + prev_sign_type = sign_type + sign_transform = self._get_valid_sign_transform(wp_transform) + if sign_transform is None: + continue # invalid + # now we can finally go about spawning the sign in this location + dreyevr_sign_type: str = "dreyevr_sign_straight" + if sign_type == RoadOption.LEFT: + dreyevr_sign_type = "dreyevr_sign_left" + elif sign_type == RoadOption.RIGHT: + dreyevr_sign_type = "dreyevr_sign_right" + elif sign_type == RoadOption.CHANGELANELEFT: + continue + elif sign_type == RoadOption.CHANGELANERIGHT: + continue + elif sign_type == RoadOption.STRAIGHT: + dreyevr_sign_type = "dreyevr_sign_straight" + else: + continue + sign_type: str = f"static.prop.{dreyevr_sign_type}" + print(f"Spawning ({sign_type}) sign {i} at {sign_transform}") + CarlaDataProvider.request_new_actor(sign_type, sign_transform, + rolename='navigation_sign') + # plot the final goal waypoint (at the end) + wp_transform_final = waypoints[-1][0] + goal_sign_transform = self._get_valid_sign_transform(wp_transform_final) + if goal_sign_transform is not None: + sign_type: str = "static.prop.dreyevr_sign_goal" + print(f"Spawning ({sign_type}) sign {len(waypoints) - 1} at {goal_sign_transform}") + CarlaDataProvider.request_new_actor(sign_type, + goal_sign_transform, + rolename='navigation_sign') + + def _scenario_sampling(self, potential_scenarios_definitions, random_seed=0): + """ + The function used to sample the scenarios that are going to happen for this route. + """ + + # fix the random seed for reproducibility + rng = CarlaDataProvider.get_random_seed() + + def position_sampled(scenario_choice, sampled_scenarios): + """ + Check if a position was already sampled, i.e. used for another scenario + """ + for existent_scenario in sampled_scenarios: + # If the scenarios have equal positions then it is true. + if compare_scenarios(scenario_choice, existent_scenario): + return True + + return False + + # The idea is to randomly sample a scenario per trigger position. + sampled_scenarios = [] + for trigger in potential_scenarios_definitions.keys(): + possible_scenarios = potential_scenarios_definitions[trigger] + + scenario_choice = rng.choice(possible_scenarios) + del possible_scenarios[possible_scenarios.index(scenario_choice)] + # We keep sampling and testing if this position is present on any of the scenarios. + while position_sampled(scenario_choice, sampled_scenarios): + if possible_scenarios is None or not possible_scenarios: + scenario_choice = None + break + scenario_choice = rng.choice(possible_scenarios) + del possible_scenarios[possible_scenarios.index(scenario_choice)] + + if scenario_choice is not None: + sampled_scenarios.append(scenario_choice) + + return sampled_scenarios + + def _build_scenario_instances(self, world, ego_vehicle, scenario_definitions, + scenarios_per_tick=5, timeout=300, debug_mode=False): + """ + Based on the parsed route and possible scenarios, build all the scenario classes. + """ + scenario_instance_vec = [] + + if debug_mode: + for scenario in scenario_definitions: + loc = carla.Location(scenario['trigger_position']['x'], + scenario['trigger_position']['y'], + scenario['trigger_position']['z']) + carla.Location(z=2.0) + world.debug.draw_point(loc, size=0.3, color=carla.Color(255, 0, 0), life_time=100000) + world.debug.draw_string(loc, str(scenario['name']), draw_shadow=False, + color=carla.Color(0, 0, 255), life_time=100000, persistent_lines=True) + + for scenario_number, definition in enumerate(scenario_definitions): + # Get the class possibilities for this scenario number + scenario_class = NUMBER_CLASS_TRANSLATION[definition['name']] + + # Create the other actors that are going to appear + if definition['other_actors'] is not None: + list_of_actor_conf_instances = self._get_actors_instances(definition['other_actors']) + else: + list_of_actor_conf_instances = [] + # Create an actor configuration for the ego-vehicle trigger position + + egoactor_trigger_position = convert_json_to_transform(definition['trigger_position']) + scenario_configuration = ScenarioConfiguration() + scenario_configuration.other_actors = list_of_actor_conf_instances + scenario_configuration.trigger_points = [egoactor_trigger_position] + scenario_configuration.subtype = definition['scenario_type'] + scenario_configuration.ego_vehicles = [ActorConfigurationData(ego_vehicle.type_id, + ego_vehicle.get_transform(), + 'hero')] + route_var_name = "ScenarioRouteNumber{}".format(scenario_number) + scenario_configuration.route_var_name = route_var_name + + try: + scenario_instance = scenario_class(world, [ego_vehicle], scenario_configuration, + criteria_enable=False, timeout=timeout) + # Do a tick every once in a while to avoid spawning everything at the same time + if scenario_number % scenarios_per_tick == 0: + if CarlaDataProvider.is_sync_mode(): + world.tick() + else: + world.wait_for_tick() + + scenario_number += 1 + except Exception as e: # pylint: disable=broad-except + if debug_mode: + traceback.print_exc() + print("Skipping scenario '{}' due to setup error: {}".format(definition['name'], e)) + continue + + scenario_instance_vec.append(scenario_instance) + + return scenario_instance_vec + + def _get_actors_instances(self, list_of_antagonist_actors): + """ + Get the full list of actor instances. + """ + + def get_actors_from_list(list_of_actor_def): + """ + Receives a list of actor definitions and creates an actual list of ActorConfigurationObjects + """ + sublist_of_actors = [] + for actor_def in list_of_actor_def: + sublist_of_actors.append(convert_json_to_actor(actor_def)) + + return sublist_of_actors + + list_of_actors = [] + # Parse vehicles to the left + if 'front' in list_of_antagonist_actors: + list_of_actors += get_actors_from_list(list_of_antagonist_actors['front']) + + if 'left' in list_of_antagonist_actors: + list_of_actors += get_actors_from_list(list_of_antagonist_actors['left']) + + if 'right' in list_of_antagonist_actors: + list_of_actors += get_actors_from_list(list_of_antagonist_actors['right']) + + return list_of_actors + + # pylint: enable=no-self-use + + def _initialize_actors(self, config): + """ + Set other_actors to the superset of all scenario actors + """ + # Create the background activity of the route + town_amount = { + 'Town01': 0, + 'Town02': 0, + 'Town03': 0, + 'Town04': 0, + 'Town05': 0, + 'Town06': 0, + 'Town07': 0, + 'Town08': 0, + 'Town09': 0, + 'Town10': 0, + } + + amount = town_amount[config.town] if config.town in town_amount else 0 + + new_actors = CarlaDataProvider.request_new_batch_actors('vehicle.*', + amount, + carla.Transform(), + autopilot=True, + random_location=True, + rolename='background') + + if new_actors is None: + raise RuntimeError("Error: Unable to add the background activity, all spawn points were occupied") + + if not hasattr(self, "other_actors"): + self.other_actors = [] + + for _actor in new_actors: + self.other_actors.append(_actor) + + # Add all the actors of the specific scenarios to self.other_actors + for scenario in self.list_scenarios: + self.other_actors.extend(scenario.other_actors) + + def _create_behavior(self): + """ + Basic behavior do nothing, i.e. Idle + """ + scenario_trigger_distance = 1.5 # Max trigger distance between route and scenario + + behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) + + subbehavior = py_trees.composites.Parallel(name="Behavior", + policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL) + + scenario_behaviors = [] + blackboard_list = [] + + for i, scenario in enumerate(self.list_scenarios): + if scenario.scenario.behavior is not None: + route_var_name = scenario.config.route_var_name + if route_var_name is not None: + scenario_behaviors.append(scenario.scenario.behavior) + blackboard_list.append([scenario.config.route_var_name, + scenario.config.trigger_points[0].location]) + else: + name = "{} - {}".format(i, scenario.scenario.behavior.name) + oneshot_idiom = oneshot_behavior(name, + behaviour=scenario.scenario.behavior, + name=name) + scenario_behaviors.append(oneshot_idiom) + + # Add behavior that manages the scenarios trigger conditions + scenario_triggerer = ScenarioTriggerer( + self.ego_vehicles[0], + self.route, + blackboard_list, + scenario_trigger_distance, + repeat_scenarios=False + ) + + subbehavior.add_child(scenario_triggerer) # make ScenarioTriggerer the first thing to be checked + subbehavior.add_children(scenario_behaviors) + subbehavior.add_child(Idle()) # The behaviours cannot make the route scenario stop + behavior.add_child(subbehavior) + + return behavior + + def _create_test_criteria(self): + """ + """ + + criteria = [] + + route = convert_transform_to_location(self.route) + + collision_criterion = CollisionTest(self.ego_vehicles[0], terminate_on_failure=False) + + route_criterion = InRouteTest(self.ego_vehicles[0], + route=route, + offroad_max=30, + terminate_on_failure=True) + + completion_criterion = RouteCompletionTest(self.ego_vehicles[0], route=route) + + outsidelane_criterion = OutsideRouteLanesTest(self.ego_vehicles[0], route=route) + + red_light_criterion = RunningRedLightTest(self.ego_vehicles[0]) + + stop_criterion = RunningStopTest(self.ego_vehicles[0]) + + blocked_criterion = ActorSpeedAboveThresholdTest(self.ego_vehicles[0], + speed_threshold=0.1, + below_threshold_max_time=90.0, + terminate_on_failure=True) + + criteria.append(completion_criterion) + criteria.append(collision_criterion) + criteria.append(route_criterion) + criteria.append(outsidelane_criterion) + criteria.append(red_light_criterion) + criteria.append(stop_criterion) + criteria.append(blocked_criterion) + + return criteria + + def __del__(self): + """ + Remove all actors upon deletion + """ + self.remove_all_actors() diff --git a/ScenarioRunner/run_experiment.py b/ScenarioRunner/run_experiment.py index 43f5b7d..70aac5b 100755 --- a/ScenarioRunner/run_experiment.py +++ b/ScenarioRunner/run_experiment.py @@ -1,171 +1,171 @@ -#!/usr/bin/env python3 - -import time -import glob -import os -import argparse -import sys -from threading import Thread -from datetime import datetime -import argparse - -try: - CARLA_ROOT: str = os.getenv("CARLA_ROOT") - egg_dir = os.path.join(CARLA_ROOT, "PythonAPI", "carla", "dist") - sys.path.extend([glob.glob(os.path.join(egg_dir, f"carla-*.egg"))[0], - os.path.join(CARLA_ROOT, "PythonAPI"), - os.path.join(CARLA_ROOT, "PythonAPI", "carla"), - os.path.join(CARLA_ROOT, "PythonAPI", "examples")]) -except IndexError: - print(f"Unable to find Carla PythonAPI file in {egg_dir}") - -import carla - -from scenario_runner import ScenarioRunner - -recorder_file = None - - -def start_scenario_runner(scenario_runner_instance): - try: - print("Starting scenario runner") - result = scenario_runner_instance.run() - finally: - if scenario_runner_instance is not None: - scenario_runner_instance.destroy() - del scenario_runner_instance - print("Stopped scenario runner, Result:", result) - - -def wait_until_SR_loaded(scenario_runner_instance, ping_freq_s=0.5): - # wait until scenario_runner world has been loaded - while scenario_runner_instance.world is None: - time.sleep(ping_freq_s) - - -def run_schematic(argparser, scenario_runner_instance): - wait_until_SR_loaded(scenario_runner_instance) - print(10 * "=" + "schematic mode" + 10 * "=") - - # can be completely avoided if --visualize is False - # NOTE: this import uses export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/examples - raise NotImplementedError - from dreyevr.examples.schematic_mode import schematic_run - - # for full definitions of these args see no_rendering_mode.py - args = argparser.parse_known_args( - [ - "-v", - "--verbose", - "--host", - "-p", - "-port", - "--res", - "--filter", - "--map", - "--no-rendering", - "--show-triggers", - "--show-connections", - "--show-spawn-points", - ] - ) - # TODO: figure out why this is not working - schematic_run(args) - - -def start_recording(client, args, scenario_runner_instance): - wait_until_SR_loaded(scenario_runner_instance) - time_str: str = datetime.now().strftime("%m_%d_%Y_%H_%M_%S") - filename: str = f"exp_{args.title}_{time_str}.rec" - - global recorder_file # to "return" from this thread - recorder_file = client.start_recorder(filename) - print("Recording on file: %s" % recorder_file) - - -def stop_recording(client): - global recorder_file - print(f"Stopping recording, file saved to \"{recorder_file}\"") - client.stop_recorder() - - -def scenario_runner_args(parser): - # NOTE: see scenario_runner.py for a better explanation of these - parser.add_argument("-v", "--version", action="version", version="0.9.13") - parser.add_argument("--host", default="127.0.0.1") - parser.add_argument("--port", default=2000) - parser.add_argument("--timeout", default="10.0") - parser.add_argument("--trafficManagerPort", default="8000") - parser.add_argument("--trafficManagerSeed", default="0") - parser.add_argument("--sync", action="store_true") - parser.add_argument("--list", action="store_true") - parser.add_argument("--route", nargs="+", type=str) - parser.add_argument("--agent") - parser.add_argument("--agentConfig", type=str, default="") - parser.add_argument("--output", action="store_true", default=True) - parser.add_argument("--junit", action="store_true") - parser.add_argument("--json", action="store_true") - parser.add_argument("--configFile", default="") - parser.add_argument("--additionalScenario", default="") - parser.add_argument("--debug", action="store_true", default=False) - parser.add_argument("--reloadWorld", action="store_true", default=True) - parser.add_argument("--record", type=str, default="") - parser.add_argument("--randomize", action="store_true") - parser.add_argument("--repetitions", default=1, type=int) - parser.add_argument("--waitForEgo", action="store_true") - parser.add_argument("--outputDir", default="") - - # arguments we're ignoring - parser.add_argument("--file", action="store_true") - parser.add_argument("--scenario", default=None) - parser.add_argument("--openscenario", default=None) - - -def main(): - # Define arguments that will be received and parsed - - description = ( - "DReyeVR Scenario Runner & Experiment Runner\n" "Current version: 0.9.13" - ) - - argparser = argparse.ArgumentParser( - description=description, formatter_class=argparse.RawTextHelpFormatter - ) - - argparser.add_argument("-t", "--title", default="anonymous") - argparser.add_argument("--visualize", action="store_true", default=False) - - # also add all requisite scenario_runner arguments - scenario_runner_args(argparser) - - args = argparser.parse_args() - - if not args.route: - print("Please specify the route mode, other modes are not supported\n\n") - argparser.print_help(sys.stdout) - exit(1) - - client = carla.Client(args.host, args.port) - - scenario_runner_instance = ScenarioRunner(args) - - # start the listening recorder thread (background, waits for scenario to begin) - recording_thread = Thread( - target=start_recording, args=(client, args, scenario_runner_instance,) - ) - recording_thread.start() # run in background - - if args.visualize is True: - schematic_thread = Thread( - target=run_schematic, args=(argparser, scenario_runner_instance,) - ) - schematic_thread.start() - - start_scenario_runner(scenario_runner_instance) - - # finish recording - stop_recording(client) - - -if __name__ == "__main__": - main() +#!/usr/bin/env python3 + +import time +import glob +import os +import argparse +import sys +from threading import Thread +from datetime import datetime +import argparse + +try: + CARLA_ROOT: str = os.getenv("CARLA_ROOT") + egg_dir = os.path.join(CARLA_ROOT, "PythonAPI", "carla", "dist") + sys.path.extend([glob.glob(os.path.join(egg_dir, f"carla-*.egg"))[0], + os.path.join(CARLA_ROOT, "PythonAPI"), + os.path.join(CARLA_ROOT, "PythonAPI", "carla"), + os.path.join(CARLA_ROOT, "PythonAPI", "examples")]) +except IndexError: + print(f"Unable to find Carla PythonAPI file in {egg_dir}") + +import carla + +from scenario_runner import ScenarioRunner + +recorder_file = None + + +def start_scenario_runner(scenario_runner_instance): + try: + print("Starting scenario runner") + result = scenario_runner_instance.run() + finally: + if scenario_runner_instance is not None: + scenario_runner_instance.destroy() + del scenario_runner_instance + print("Stopped scenario runner, Result:", result) + + +def wait_until_SR_loaded(scenario_runner_instance, ping_freq_s=0.5): + # wait until scenario_runner world has been loaded + while scenario_runner_instance.world is None: + time.sleep(ping_freq_s) + + +def run_schematic(argparser, scenario_runner_instance): + wait_until_SR_loaded(scenario_runner_instance) + print(10 * "=" + "schematic mode" + 10 * "=") + + # can be completely avoided if --visualize is False + # NOTE: this import uses export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/examples + raise NotImplementedError + from dreyevr.examples.schematic_mode import schematic_run + + # for full definitions of these args see no_rendering_mode.py + args = argparser.parse_known_args( + [ + "-v", + "--verbose", + "--host", + "-p", + "-port", + "--res", + "--filter", + "--map", + "--no-rendering", + "--show-triggers", + "--show-connections", + "--show-spawn-points", + ] + ) + # TODO: figure out why this is not working + schematic_run(args) + + +def start_recording(client, args, scenario_runner_instance): + wait_until_SR_loaded(scenario_runner_instance) + time_str: str = datetime.now().strftime("%m_%d_%Y_%H_%M_%S") + filename: str = f"exp_{args.title}_{time_str}.rec" + + global recorder_file # to "return" from this thread + recorder_file = client.start_recorder(filename) + print("Recording on file: %s" % recorder_file) + + +def stop_recording(client): + global recorder_file + print(f"Stopping recording, file saved to \"{recorder_file}\"") + client.stop_recorder() + + +def scenario_runner_args(parser): + # NOTE: see scenario_runner.py for a better explanation of these + parser.add_argument("-v", "--version", action="version", version="0.9.13") + parser.add_argument("--host", default="127.0.0.1") + parser.add_argument("--port", default=2000) + parser.add_argument("--timeout", default="10.0") + parser.add_argument("--trafficManagerPort", default="8000") + parser.add_argument("--trafficManagerSeed", default="0") + parser.add_argument("--sync", action="store_true") + parser.add_argument("--list", action="store_true") + parser.add_argument("--route", nargs="+", type=str) + parser.add_argument("--agent") + parser.add_argument("--agentConfig", type=str, default="") + parser.add_argument("--output", action="store_true", default=True) + parser.add_argument("--junit", action="store_true") + parser.add_argument("--json", action="store_true") + parser.add_argument("--configFile", default="") + parser.add_argument("--additionalScenario", default="") + parser.add_argument("--debug", action="store_true", default=False) + parser.add_argument("--reloadWorld", action="store_true", default=True) + parser.add_argument("--record", type=str, default="") + parser.add_argument("--randomize", action="store_true") + parser.add_argument("--repetitions", default=1, type=int) + parser.add_argument("--waitForEgo", action="store_true") + parser.add_argument("--outputDir", default="") + + # arguments we're ignoring + parser.add_argument("--file", action="store_true") + parser.add_argument("--scenario", default=None) + parser.add_argument("--openscenario", default=None) + + +def main(): + # Define arguments that will be received and parsed + + description = ( + "DReyeVR Scenario Runner & Experiment Runner\n" "Current version: 0.9.13" + ) + + argparser = argparse.ArgumentParser( + description=description, formatter_class=argparse.RawTextHelpFormatter + ) + + argparser.add_argument("-t", "--title", default="anonymous") + argparser.add_argument("--visualize", action="store_true", default=False) + + # also add all requisite scenario_runner arguments + scenario_runner_args(argparser) + + args = argparser.parse_args() + + if not args.route: + print("Please specify the route mode, other modes are not supported\n\n") + argparser.print_help(sys.stdout) + exit(1) + + client = carla.Client(args.host, args.port) + + scenario_runner_instance = ScenarioRunner(args) + + # start the listening recorder thread (background, waits for scenario to begin) + recording_thread = Thread( + target=start_recording, args=(client, args, scenario_runner_instance,) + ) + recording_thread.start() # run in background + + if args.visualize is True: + schematic_thread = Thread( + target=run_schematic, args=(argparser, scenario_runner_instance,) + ) + schematic_thread.start() + + start_scenario_runner(scenario_runner_instance) + + # finish recording + stop_recording(client) + + +if __name__ == "__main__": + main() diff --git a/ScenarioRunner/scenario_manager.py b/ScenarioRunner/scenario_manager.py index 1973e62..45cf4af 100644 --- a/ScenarioRunner/scenario_manager.py +++ b/ScenarioRunner/scenario_manager.py @@ -1,263 +1,263 @@ -#!/usr/bin/env python - -# Copyright (c) 2018-2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . - -""" -This module provides the ScenarioManager implementation. -It must not be modified and is for reference only! -""" - -from __future__ import print_function -import sys -import time -import os -import py_trees - -from srunner.autoagents.agent_wrapper import AgentWrapper -from srunner.scenariomanager.carla_data_provider import CarlaDataProvider -from srunner.scenariomanager.result_writer import ResultOutputProvider -from srunner.scenariomanager.timer import GameTime -from srunner.scenariomanager.watchdog import Watchdog -from srunner.tools.route_parser import RouteParser - - -class ScenarioManager(object): - - """ - Basic scenario manager class. This class holds all functionality - required to start, and analyze a scenario. - - The user must not modify this class. - - To use the ScenarioManager: - 1. Create an object via manager = ScenarioManager() - 2. Load a scenario via manager.load_scenario() - 3. Trigger the execution of the scenario manager.run_scenario() - This function is designed to explicitly control start and end of - the scenario execution - 4. Trigger a result evaluation with manager.analyze_scenario() - 5. If needed, cleanup with manager.stop_scenario() - """ - - def __init__(self, debug_mode=False, sync_mode=False, timeout=2.0): - """ - Setups up the parameters, which will be filled at load_scenario() - - """ - self.scenario = None - self.scenario_tree = None - self.scenario_class = None - self.ego_vehicles = None - self.other_actors = None - - self._debug_mode = debug_mode - self._agent = None - self._sync_mode = sync_mode - self._watchdog = None - self._timeout = timeout - - self._running = False - self._timestamp_last_run = 0.0 - self.scenario_duration_system = 0.0 - self.scenario_duration_game = 0.0 - self.start_system_time = None - self.end_system_time = None - self.route_id = None - - def _reset(self): - """ - Reset all parameters - """ - self._running = False - self._timestamp_last_run = 0.0 - self.scenario_duration_system = 0.0 - self.scenario_duration_game = 0.0 - self.start_system_time = None - self.end_system_time = None - GameTime.restart() - - def cleanup(self): - """ - This function triggers a proper termination of a scenario - """ - - if self._watchdog is not None: - self._watchdog.stop() - self._watchdog = None - - if self.scenario is not None: - self.scenario.terminate() - - if self._agent is not None: - self._agent.cleanup() - self._agent = None - - CarlaDataProvider.cleanup() - - def load_scenario(self, scenario, agent=None, route_id=None): - """ - Load a new scenario - """ - self._reset() - self._agent = AgentWrapper(agent) if agent else None - if self._agent is not None: - self._sync_mode = True - self.scenario_class = scenario - self.scenario = scenario.scenario - self.scenario_tree = self.scenario.scenario_tree - self.ego_vehicles = scenario.ego_vehicles - self.other_actors = scenario.other_actors - - # To print the scenario tree uncomment the next line - # py_trees.display.render_dot_tree(self.scenario_tree) - - if self._agent is not None: - self._agent.setup_sensors(self.ego_vehicles[0], self._debug_mode) - - self.route_id = route_id - self.load_dreyevr_signs() - - def load_dreyevr_signs(self): - """ - retrieve and place direction signs for route if they exist - """ - - signs_file = os.path.join(os.getenv("SCENARIO_RUNNER_ROOT"), "srunner", "data", "all_routes_signs.json") - route_signs_list = RouteParser.parse_direction_signs_file(signs_file, self.route_id) - - if route_signs_list is None: - print(f"No route_signs_dict (json) for route {self.route_id} in \"{signs_file}\"") - return - - # place directional signs from json in world - assert len(route_signs_list) == 1 - route_signs_dict = route_signs_list[0] - print("Spawning DReyeVR signs for route", self.route_id) - for sign in route_signs_dict['sign_configurations']: - sign_type = sign['type'] - sign_waypoint = sign['transform'] - sign_transform = RouteParser.convert_dict2transform(sign_waypoint) - print(f"Loading \"{sign_type}\" @ {sign_transform}") - # TODO: keep track of these signs somewhere? - CarlaDataProvider.request_new_actor(sign_type, sign_transform, rolename='navigation_sign') - - def run_scenario(self): - """ - Trigger the start of the scenario and wait for it to finish/fail - """ - print("ScenarioManager: Running scenario {}".format(self.scenario_tree.name)) - self.start_system_time = time.time() - start_game_time = GameTime.get_time() - - self._watchdog = Watchdog(float(self._timeout)) - self._watchdog.start() - self._running = True - - while self._running: - timestamp = None - world = CarlaDataProvider.get_world() - if world: - snapshot = world.get_snapshot() - if snapshot: - timestamp = snapshot.timestamp - if timestamp: - self._tick_scenario(timestamp) - - self.cleanup() - - self.end_system_time = time.time() - end_game_time = GameTime.get_time() - - self.scenario_duration_system = self.end_system_time - \ - self.start_system_time - self.scenario_duration_game = end_game_time - start_game_time - - if self.scenario_tree.status == py_trees.common.Status.FAILURE: - print("ScenarioManager: Terminated due to failure") - - def _tick_scenario(self, timestamp): - """ - Run next tick of scenario and the agent. - If running synchornously, it also handles the ticking of the world. - """ - - if self._timestamp_last_run < timestamp.elapsed_seconds and self._running: - self._timestamp_last_run = timestamp.elapsed_seconds - - self._watchdog.update() - - if self._debug_mode: - print("\n--------- Tick ---------\n") - - # Update game time and actor information - GameTime.on_carla_tick(timestamp) - CarlaDataProvider.on_carla_tick() - - if self._agent is not None: - ego_action = self._agent() # pylint: disable=not-callable - - if self._agent is not None: - self.ego_vehicles[0].apply_control(ego_action) - - # Tick scenario - self.scenario_tree.tick_once() - - if self._debug_mode: - print("\n") - py_trees.display.print_ascii_tree(self.scenario_tree, show_status=True) - sys.stdout.flush() - - if self.scenario_tree.status != py_trees.common.Status.RUNNING: - self._running = False - - if self._sync_mode and self._running and self._watchdog.get_status(): - CarlaDataProvider.get_world().tick() - - def get_running_status(self): - """ - returns: - bool: False if watchdog exception occured, True otherwise - """ - return self._watchdog.get_status() - - def stop_scenario(self): - """ - This function is used by the overall signal handler to terminate the scenario execution - """ - self._running = False - - def analyze_scenario(self, stdout, filename, junit, json): - """ - This function is intended to be called from outside and provide - the final statistics about the scenario (human-readable, in form of a junit - report, etc.) - """ - - failure = False - timeout = False - result = "SUCCESS" - - if self.scenario.test_criteria is None: - print("Nothing to analyze, this scenario has no criteria") - return True - - for criterion in self.scenario.get_criteria(): - if (not criterion.optional and - criterion.test_status != "SUCCESS" and - criterion.test_status != "ACCEPTABLE"): - failure = True - result = "FAILURE" - elif criterion.test_status == "ACCEPTABLE": - result = "ACCEPTABLE" - - if self.scenario.timeout_node.timeout and not failure: - timeout = True - result = "TIMEOUT" - - output = ResultOutputProvider(self, result, stdout, filename, junit, json) - output.write() - - return failure or timeout +#!/usr/bin/env python + +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +""" +This module provides the ScenarioManager implementation. +It must not be modified and is for reference only! +""" + +from __future__ import print_function +import sys +import time +import os +import py_trees + +from srunner.autoagents.agent_wrapper import AgentWrapper +from srunner.scenariomanager.carla_data_provider import CarlaDataProvider +from srunner.scenariomanager.result_writer import ResultOutputProvider +from srunner.scenariomanager.timer import GameTime +from srunner.scenariomanager.watchdog import Watchdog +from srunner.tools.route_parser import RouteParser + + +class ScenarioManager(object): + + """ + Basic scenario manager class. This class holds all functionality + required to start, and analyze a scenario. + + The user must not modify this class. + + To use the ScenarioManager: + 1. Create an object via manager = ScenarioManager() + 2. Load a scenario via manager.load_scenario() + 3. Trigger the execution of the scenario manager.run_scenario() + This function is designed to explicitly control start and end of + the scenario execution + 4. Trigger a result evaluation with manager.analyze_scenario() + 5. If needed, cleanup with manager.stop_scenario() + """ + + def __init__(self, debug_mode=False, sync_mode=False, timeout=2.0): + """ + Setups up the parameters, which will be filled at load_scenario() + + """ + self.scenario = None + self.scenario_tree = None + self.scenario_class = None + self.ego_vehicles = None + self.other_actors = None + + self._debug_mode = debug_mode + self._agent = None + self._sync_mode = sync_mode + self._watchdog = None + self._timeout = timeout + + self._running = False + self._timestamp_last_run = 0.0 + self.scenario_duration_system = 0.0 + self.scenario_duration_game = 0.0 + self.start_system_time = None + self.end_system_time = None + self.route_id = None + + def _reset(self): + """ + Reset all parameters + """ + self._running = False + self._timestamp_last_run = 0.0 + self.scenario_duration_system = 0.0 + self.scenario_duration_game = 0.0 + self.start_system_time = None + self.end_system_time = None + GameTime.restart() + + def cleanup(self): + """ + This function triggers a proper termination of a scenario + """ + + if self._watchdog is not None: + self._watchdog.stop() + self._watchdog = None + + if self.scenario is not None: + self.scenario.terminate() + + if self._agent is not None: + self._agent.cleanup() + self._agent = None + + CarlaDataProvider.cleanup() + + def load_scenario(self, scenario, agent=None, route_id=None): + """ + Load a new scenario + """ + self._reset() + self._agent = AgentWrapper(agent) if agent else None + if self._agent is not None: + self._sync_mode = True + self.scenario_class = scenario + self.scenario = scenario.scenario + self.scenario_tree = self.scenario.scenario_tree + self.ego_vehicles = scenario.ego_vehicles + self.other_actors = scenario.other_actors + + # To print the scenario tree uncomment the next line + # py_trees.display.render_dot_tree(self.scenario_tree) + + if self._agent is not None: + self._agent.setup_sensors(self.ego_vehicles[0], self._debug_mode) + + self.route_id = route_id + self.load_dreyevr_signs() + + def load_dreyevr_signs(self): + """ + retrieve and place direction signs for route if they exist + """ + + signs_file = os.path.join(os.getenv("SCENARIO_RUNNER_ROOT"), "srunner", "data", "all_routes_signs.json") + route_signs_list = RouteParser.parse_direction_signs_file(signs_file, self.route_id) + + if route_signs_list is None: + print(f"No route_signs_dict (json) for route {self.route_id} in \"{signs_file}\"") + return + + # place directional signs from json in world + assert len(route_signs_list) == 1 + route_signs_dict = route_signs_list[0] + print("Spawning DReyeVR signs for route", self.route_id) + for sign in route_signs_dict['sign_configurations']: + sign_type = sign['type'] + sign_waypoint = sign['transform'] + sign_transform = RouteParser.convert_dict2transform(sign_waypoint) + print(f"Loading \"{sign_type}\" @ {sign_transform}") + # TODO: keep track of these signs somewhere? + CarlaDataProvider.request_new_actor(sign_type, sign_transform, rolename='navigation_sign') + + def run_scenario(self): + """ + Trigger the start of the scenario and wait for it to finish/fail + """ + print("ScenarioManager: Running scenario {}".format(self.scenario_tree.name)) + self.start_system_time = time.time() + start_game_time = GameTime.get_time() + + self._watchdog = Watchdog(float(self._timeout)) + self._watchdog.start() + self._running = True + + while self._running: + timestamp = None + world = CarlaDataProvider.get_world() + if world: + snapshot = world.get_snapshot() + if snapshot: + timestamp = snapshot.timestamp + if timestamp: + self._tick_scenario(timestamp) + + self.cleanup() + + self.end_system_time = time.time() + end_game_time = GameTime.get_time() + + self.scenario_duration_system = self.end_system_time - \ + self.start_system_time + self.scenario_duration_game = end_game_time - start_game_time + + if self.scenario_tree.status == py_trees.common.Status.FAILURE: + print("ScenarioManager: Terminated due to failure") + + def _tick_scenario(self, timestamp): + """ + Run next tick of scenario and the agent. + If running synchornously, it also handles the ticking of the world. + """ + + if self._timestamp_last_run < timestamp.elapsed_seconds and self._running: + self._timestamp_last_run = timestamp.elapsed_seconds + + self._watchdog.update() + + if self._debug_mode: + print("\n--------- Tick ---------\n") + + # Update game time and actor information + GameTime.on_carla_tick(timestamp) + CarlaDataProvider.on_carla_tick() + + if self._agent is not None: + ego_action = self._agent() # pylint: disable=not-callable + + if self._agent is not None: + self.ego_vehicles[0].apply_control(ego_action) + + # Tick scenario + self.scenario_tree.tick_once() + + if self._debug_mode: + print("\n") + py_trees.display.print_ascii_tree(self.scenario_tree, show_status=True) + sys.stdout.flush() + + if self.scenario_tree.status != py_trees.common.Status.RUNNING: + self._running = False + + if self._sync_mode and self._running and self._watchdog.get_status(): + CarlaDataProvider.get_world().tick() + + def get_running_status(self): + """ + returns: + bool: False if watchdog exception occured, True otherwise + """ + return self._watchdog.get_status() + + def stop_scenario(self): + """ + This function is used by the overall signal handler to terminate the scenario execution + """ + self._running = False + + def analyze_scenario(self, stdout, filename, junit, json): + """ + This function is intended to be called from outside and provide + the final statistics about the scenario (human-readable, in form of a junit + report, etc.) + """ + + failure = False + timeout = False + result = "SUCCESS" + + if self.scenario.test_criteria is None: + print("Nothing to analyze, this scenario has no criteria") + return True + + for criterion in self.scenario.get_criteria(): + if (not criterion.optional and + criterion.test_status != "SUCCESS" and + criterion.test_status != "ACCEPTABLE"): + failure = True + result = "FAILURE" + elif criterion.test_status == "ACCEPTABLE": + result = "ACCEPTABLE" + + if self.scenario.timeout_node.timeout and not failure: + timeout = True + result = "TIMEOUT" + + output = ResultOutputProvider(self, result, stdout, filename, junit, json) + output.write() + + return failure or timeout diff --git a/ScenarioRunner/scenario_runner.py b/ScenarioRunner/scenario_runner.py index 7e507d5..12eeacc 100755 --- a/ScenarioRunner/scenario_runner.py +++ b/ScenarioRunner/scenario_runner.py @@ -1,619 +1,619 @@ -#!/usr/bin/env python - -# Copyright (c) 2018-2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . - -""" -Welcome to CARLA scenario_runner - -This is the main script to be executed when running a scenario. -It loads the scenario configuration, loads the scenario and manager, -and finally triggers the scenario execution. -""" - -from __future__ import print_function - -import glob -import traceback -import argparse -from argparse import RawTextHelpFormatter -from datetime import datetime -from distutils.version import LooseVersion -import importlib -import inspect -import os -import signal -import sys -import time -import json -import pkg_resources - -import carla - -from srunner.tools.route_parser import RouteParser -from srunner.tools.scenario_parser import ScenarioConfigurationParser -from srunner.scenarios.route_scenario import RouteScenario -from srunner.scenarios.open_scenario import OpenScenario -from srunner.scenariomanager.scenario_manager import ScenarioManager -from srunner.scenariomanager.carla_data_provider import CarlaDataProvider -from srunner.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration - -# Version of scenario_runner -VERSION = '0.9.13' - - -class ScenarioRunner(object): - - """ - This is the core scenario runner module. It is responsible for - running (and repeating) a single scenario or a list of scenarios. - - Usage: - scenario_runner = ScenarioRunner(args) - scenario_runner.run() - del scenario_runner - """ - - ego_vehicles = [] - - # Tunable parameters - client_timeout = 10.0 # in seconds - wait_for_world = 20.0 # in seconds - frame_rate = 20.0 # in Hz - - # CARLA world and scenario handlers - world = None - manager = None - - finished = False - - additional_scenario_module = None - - agent_instance = None - module_agent = None - - def __init__(self, args): - """ - Setup CARLA client and world - Setup ScenarioManager - """ - self._args = args - - if args.timeout: - self.client_timeout = float(args.timeout) - - # First of all, we need to create the client that will send the requests - # to the simulator. Here we'll assume the simulator is accepting - # requests in the localhost at port 2000. - self.client = carla.Client(args.host, int(args.port)) - self.client.set_timeout(self.client_timeout) - - dist = pkg_resources.get_distribution("carla") - if LooseVersion(dist.version) < LooseVersion('0.9.12'): - raise ImportError("CARLA version 0.9.12 or newer required. CARLA version found: {}".format(dist)) - - # Load agent if requested via command line args - # If something goes wrong an exception will be thrown by importlib (ok here) - if self._args.agent is not None: - module_name = os.path.basename(args.agent).split('.')[0] - sys.path.insert(0, os.path.dirname(args.agent)) - self.module_agent = importlib.import_module(module_name) - - # Create the ScenarioManager - self.manager = ScenarioManager(self._args.debug, self._args.sync, self._args.timeout) - - # Create signal handler for SIGINT - self._shutdown_requested = False - if sys.platform != 'win32': - signal.signal(signal.SIGHUP, self._signal_handler) - signal.signal(signal.SIGINT, self._signal_handler) - signal.signal(signal.SIGTERM, self._signal_handler) - - self._start_wall_time = datetime.now() - - def destroy(self): - """ - Cleanup and delete actors, ScenarioManager and CARLA world - """ - - self._cleanup() - if self.manager is not None: - del self.manager - if self.world is not None: - del self.world - if self.client is not None: - del self.client - - def _signal_handler(self, signum, frame): - """ - Terminate scenario ticking when receiving a signal interrupt - """ - self._shutdown_requested = True - if self.manager: - self.manager.stop_scenario() - - def _get_scenario_class_or_fail(self, scenario): - """ - Get scenario class by scenario name - If scenario is not supported or not found, exit script - """ - - # Path of all scenario at "srunner/scenarios" folder + the path of the additional scenario argument - scenarios_list = glob.glob("{}/srunner/scenarios/*.py".format(os.getenv('SCENARIO_RUNNER_ROOT', "./"))) - scenarios_list.append(self._args.additionalScenario) - - for scenario_file in scenarios_list: - - # Get their module - module_name = os.path.basename(scenario_file).split('.')[0] - sys.path.insert(0, os.path.dirname(scenario_file)) - scenario_module = importlib.import_module(module_name) - - # And their members of type class - for member in inspect.getmembers(scenario_module, inspect.isclass): - if scenario in member: - return member[1] - - # Remove unused Python paths - sys.path.pop(0) - - print("Scenario '{}' not supported ... Exiting".format(scenario)) - sys.exit(-1) - - def _cleanup(self): - """ - Remove and destroy all actors - """ - if self.finished: - return - - self.finished = True - - # Simulation still running and in synchronous mode? - if self.world is not None and self._args.sync: - try: - # Reset to asynchronous mode - settings = self.world.get_settings() - settings.synchronous_mode = False - settings.fixed_delta_seconds = None - self.world.apply_settings(settings) - self.client.get_trafficmanager(int(self._args.trafficManagerPort)).set_synchronous_mode(False) - except RuntimeError: - sys.exit(-1) - - self.manager.cleanup() - - CarlaDataProvider.cleanup() - - for i, _ in enumerate(self.ego_vehicles): - if self.ego_vehicles[i]: - if not self._args.waitForEgo and self.ego_vehicles[i] is not None and self.ego_vehicles[i].is_alive: - print("Destroying ego vehicle {}".format(self.ego_vehicles[i].id)) - self.ego_vehicles[i].destroy() - self.ego_vehicles[i] = None - self.ego_vehicles = [] - - if self.agent_instance: - self.agent_instance.destroy() - self.agent_instance = None - - def _prepare_ego_vehicles(self, ego_vehicles): - """ - Spawn or update the ego vehicles - """ - - if not self._args.waitForEgo: - for vehicle in ego_vehicles: - self.ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model, - vehicle.transform, - vehicle.rolename, - color=vehicle.color, - actor_category=vehicle.category)) - else: - ego_vehicle_missing = True - while ego_vehicle_missing: - self.ego_vehicles = [] - ego_vehicle_missing = False - for ego_vehicle in ego_vehicles: - ego_vehicle_found = False - carla_vehicles = CarlaDataProvider.get_world().get_actors().filter('vehicle.*') - for carla_vehicle in carla_vehicles: - if carla_vehicle.attributes['role_name'] == ego_vehicle.rolename: - ego_vehicle_found = True - self.ego_vehicles.append(carla_vehicle) - break - if not ego_vehicle_found: - ego_vehicle_missing = True - break - - for i, _ in enumerate(self.ego_vehicles): - self.ego_vehicles[i].set_transform(ego_vehicles[i].transform) - CarlaDataProvider.register_actor(self.ego_vehicles[i]) - - # sync state - if CarlaDataProvider.is_sync_mode(): - self.world.tick() - else: - self.world.wait_for_tick() - - def _analyze_scenario(self, config): - """ - Provide feedback about success/failure of a scenario - """ - - # Create the filename - current_time = str(datetime.now().strftime('%Y-%m-%d-%H-%M-%S')) - junit_filename = None - json_filename = None - config_name = config.name - if self._args.outputDir != '': - config_name = os.path.join(self._args.outputDir, config_name) - - if self._args.junit: - junit_filename = config_name + current_time + ".xml" - if self._args.json: - json_filename = config_name + current_time + ".json" - filename = None - if self._args.file: - filename = config_name + current_time + ".txt" - - if not self.manager.analyze_scenario(self._args.output, filename, junit_filename, json_filename): - print("All scenario tests were passed successfully!") - else: - print("Not all scenario tests were successful") - if not (self._args.output or filename or junit_filename): - print("Please run with --output for further information") - - def _record_criteria(self, criteria, name): - """ - Filter the JSON serializable attributes of the criterias and - dumps them into a file. This will be used by the metrics manager, - in case the user wants specific information about the criterias. - """ - file_name = name[:-4] + ".json" - - # Filter the attributes that aren't JSON serializable - with open('temp.json', 'w', encoding='utf-8') as fp: - - criteria_dict = {} - for criterion in criteria: - - criterion_dict = criterion.__dict__ - criteria_dict[criterion.name] = {} - - for key in criterion_dict: - if key != "name": - try: - key_dict = {key: criterion_dict[key]} - json.dump(key_dict, fp, sort_keys=False, indent=4) - criteria_dict[criterion.name].update(key_dict) - except TypeError: - pass - - os.remove('temp.json') - - # Save the criteria dictionary into a .json file - with open(file_name, 'w', encoding='utf-8') as fp: - json.dump(criteria_dict, fp, sort_keys=False, indent=4) - - def _load_and_wait_for_world(self, town, ego_vehicles=None): - """ - Load a new CARLA world and provide data to CarlaDataProvider - """ - - if self._args.reloadWorld: - self.world = self.client.load_world(town) - else: - # if the world should not be reloaded, wait at least until all ego vehicles are ready - ego_vehicle_found = False - if self._args.waitForEgo: - while not ego_vehicle_found and not self._shutdown_requested: - vehicles = self.client.get_world().get_actors().filter('vehicle.*') - for ego_vehicle in ego_vehicles: - ego_vehicle_found = False - for vehicle in vehicles: - if vehicle.attributes['role_name'] == ego_vehicle.rolename: - ego_vehicle_found = True - break - if not ego_vehicle_found: - print("Not all ego vehicles ready. Waiting ... ") - time.sleep(1) - break - - self.world = self.client.get_world() - - if self._args.sync: - settings = self.world.get_settings() - settings.synchronous_mode = True - settings.fixed_delta_seconds = 1.0 / self.frame_rate - self.world.apply_settings(settings) - - CarlaDataProvider.set_client(self.client) - CarlaDataProvider.set_world(self.world) - - # Wait for the world to be ready - if CarlaDataProvider.is_sync_mode(): - self.world.tick() - else: - self.world.wait_for_tick() - - map_name = CarlaDataProvider.get_map().name.split('/')[-1] - if map_name not in (town, "OpenDriveMap"): - print("The CARLA server uses the wrong map: {}".format(map_name)) - print("This scenario requires to use map: {}".format(town)) - return False - - return True - - def _load_and_run_scenario(self, config): - """ - Load and run the scenario given by config - """ - result = False - if not self._load_and_wait_for_world(config.town, config.ego_vehicles): - self._cleanup() - return False - - if self._args.agent: - agent_class_name = self.module_agent.__name__.title().replace('_', '') - try: - self.agent_instance = getattr(self.module_agent, agent_class_name)(self._args.agentConfig) - config.agent = self.agent_instance - except Exception as e: # pylint: disable=broad-except - traceback.print_exc() - print("Could not setup required agent due to {}".format(e)) - self._cleanup() - return False - - CarlaDataProvider.set_traffic_manager_port(int(self._args.trafficManagerPort)) - tm = self.client.get_trafficmanager(int(self._args.trafficManagerPort)) - tm.set_random_device_seed(int(self._args.trafficManagerSeed)) - if self._args.sync: - tm.set_synchronous_mode(True) - - # Prepare scenario - print("Preparing scenario: " + config.name) - try: - self._prepare_ego_vehicles(config.ego_vehicles) - if self._args.openscenario: - scenario = OpenScenario(world=self.world, - ego_vehicles=self.ego_vehicles, - config=config, - config_file=self._args.openscenario, - timeout=100000) - elif self._args.route: - scenario = RouteScenario(world=self.world, - config=config, - debug_mode=self._args.debug) - else: - scenario_class = self._get_scenario_class_or_fail(config.type) - scenario = scenario_class(self.world, - self.ego_vehicles, - config, - self._args.randomize, - self._args.debug) - except Exception as exception: # pylint: disable=broad-except - print("The scenario cannot be loaded") - traceback.print_exc() - print(exception) - self._cleanup() - return False - - try: - if self._args.record: - recorder_name = "{}/{}/{}.log".format( - os.getenv('SCENARIO_RUNNER_ROOT', "./"), self._args.record, config.name) - self.client.start_recorder(recorder_name, True) - - # Load scenario and run it - self.manager.load_scenario(scenario, self.agent_instance, config.scenario_number) - self.manager.run_scenario() - - # Provide outputs if required - self._analyze_scenario(config) - - # Remove all actors, stop the recorder and save all criterias (if needed) - scenario.remove_all_actors() - if self._args.record: - self.client.stop_recorder() - self._record_criteria(self.manager.scenario.get_criteria(), recorder_name) - - result = True - - except Exception as e: # pylint: disable=broad-except - traceback.print_exc() - print(e) - result = False - - self._cleanup() - return result - - def _run_scenarios(self): - """ - Run conventional scenarios (e.g. implemented using the Python API of ScenarioRunner) - """ - result = False - - # Load the scenario configurations provided in the config file - scenario_configurations = ScenarioConfigurationParser.parse_scenario_configuration( - self._args.scenario, - self._args.configFile) - if not scenario_configurations: - print("Configuration for scenario {} cannot be found!".format(self._args.scenario)) - return result - - # Execute each configuration - for config in scenario_configurations: - for _ in range(self._args.repetitions): - self.finished = False - result = self._load_and_run_scenario(config) - - self._cleanup() - return result - - def _run_route(self): - """ - Run the route scenario - """ - result = False - - if self._args.route: - routes = self._args.route[0] - scenario_file = self._args.route[1] - single_route = None - if len(self._args.route) > 2: - single_route = self._args.route[2] - - # retrieve routes - route_configurations = RouteParser.parse_routes_file(routes, scenario_file, single_route) - - for config in route_configurations: - for _ in range(self._args.repetitions): - result = self._load_and_run_scenario(config) - - self._cleanup() - return result - - def _run_openscenario(self): - """ - Run a scenario based on OpenSCENARIO - """ - - # Load the scenario configurations provided in the config file - if not os.path.isfile(self._args.openscenario): - print("File does not exist") - self._cleanup() - return False - - openscenario_params = {} - if self._args.openscenarioparams is not None: - for entry in self._args.openscenarioparams.split(','): - [key, val] = [m.strip() for m in entry.split(':')] - openscenario_params[key] = val - config = OpenScenarioConfiguration(self._args.openscenario, self.client, openscenario_params) - - result = self._load_and_run_scenario(config) - self._cleanup() - return result - - def run(self): - """ - Run all scenarios according to provided commandline args - """ - result = True - if self._args.openscenario: - result = self._run_openscenario() - elif self._args.route: - result = self._run_route() - else: - result = self._run_scenarios() - - print("No more scenarios .... Exiting") - return result - - -def main(): - """ - main function - """ - description = ("CARLA Scenario Runner: Setup, Run and Evaluate scenarios using CARLA\n" - "Current version: " + VERSION) - - # pylint: disable=line-too-long - parser = argparse.ArgumentParser(description=description, - formatter_class=RawTextHelpFormatter) - parser.add_argument('-v', '--version', action='version', version='%(prog)s ' + VERSION) - parser.add_argument('--host', default='127.0.0.1', - help='IP of the host server (default: localhost)') - parser.add_argument('--port', default='2000', - help='TCP port to listen to (default: 2000)') - parser.add_argument('--timeout', default="10.0", - help='Set the CARLA client timeout value in seconds') - parser.add_argument('--trafficManagerPort', default='8000', - help='Port to use for the TrafficManager (default: 8000)') - parser.add_argument('--trafficManagerSeed', default='0', - help='Seed used by the TrafficManager (default: 0)') - parser.add_argument('--sync', action='store_true', - help='Forces the simulation to run synchronously') - parser.add_argument('--list', action="store_true", help='List all supported scenarios and exit') - - parser.add_argument( - '--scenario', help='Name of the scenario to be executed. Use the preposition \'group:\' to run all scenarios of one class, e.g. ControlLoss or FollowLeadingVehicle') - parser.add_argument('--openscenario', help='Provide an OpenSCENARIO definition') - parser.add_argument('--openscenarioparams', help='Overwrited for OpenSCENARIO ParameterDeclaration') - parser.add_argument( - '--route', help='Run a route as a scenario (input: (route_file,scenario_file,[route id]))', nargs='+', type=str) - - parser.add_argument( - '--agent', help="Agent used to execute the scenario. Currently only compatible with route-based scenarios.") - parser.add_argument('--agentConfig', type=str, help="Path to Agent's configuration file", default="") - - parser.add_argument('--output', action="store_true", help='Provide results on stdout') - parser.add_argument('--file', action="store_true", help='Write results into a txt file') - parser.add_argument('--junit', action="store_true", help='Write results into a junit file') - parser.add_argument('--json', action="store_true", help='Write results into a JSON file') - parser.add_argument('--outputDir', default='', help='Directory for output files (default: this directory)') - - parser.add_argument('--configFile', default='', help='Provide an additional scenario configuration file (*.xml)') - parser.add_argument('--additionalScenario', default='', help='Provide additional scenario implementations (*.py)') - - parser.add_argument('--debug', action="store_true", help='Run with debug output') - parser.add_argument('--reloadWorld', action="store_true", - help='Reload the CARLA world before starting a scenario (default=True)') - parser.add_argument('--record', type=str, default='', - help='Path were the files will be saved, relative to SCENARIO_RUNNER_ROOT.\nActivates the CARLA recording feature and saves to file all the criteria information.') - parser.add_argument('--randomize', action="store_true", help='Scenario parameters are randomized') - parser.add_argument('--repetitions', default=1, type=int, help='Number of scenario executions') - parser.add_argument('--waitForEgo', action="store_true", help='Connect the scenario to an existing ego vehicle') - - arguments = parser.parse_args() - # pylint: enable=line-too-long - - if arguments.list: - print("Currently the following scenarios are supported:") - print(*ScenarioConfigurationParser.get_list_of_scenarios(arguments.configFile), sep='\n') - return 1 - - if not arguments.scenario and not arguments.openscenario and not arguments.route: - print("Please specify either a scenario or use the route mode\n\n") - parser.print_help(sys.stdout) - return 1 - - if arguments.route and (arguments.openscenario or arguments.scenario): - print("The route mode cannot be used together with a scenario (incl. OpenSCENARIO)'\n\n") - parser.print_help(sys.stdout) - return 1 - - if arguments.agent and (arguments.openscenario or arguments.scenario): - print("Agents are currently only compatible with route scenarios'\n\n") - parser.print_help(sys.stdout) - return 1 - - if arguments.openscenarioparams and not arguments.openscenario: - print("WARN: Ignoring --openscenarioparams when --openscenario is not specified") - - if arguments.route: - arguments.reloadWorld = True - - if arguments.agent: - arguments.sync = True - - scenario_runner = None - result = True - try: - scenario_runner = ScenarioRunner(arguments) - result = scenario_runner.run() - except Exception: # pylint: disable=broad-except - traceback.print_exc() - - finally: - if scenario_runner is not None: - scenario_runner.destroy() - del scenario_runner - return not result - - -if __name__ == "__main__": - sys.exit(main()) +#!/usr/bin/env python + +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +""" +Welcome to CARLA scenario_runner + +This is the main script to be executed when running a scenario. +It loads the scenario configuration, loads the scenario and manager, +and finally triggers the scenario execution. +""" + +from __future__ import print_function + +import glob +import traceback +import argparse +from argparse import RawTextHelpFormatter +from datetime import datetime +from distutils.version import LooseVersion +import importlib +import inspect +import os +import signal +import sys +import time +import json +import pkg_resources + +import carla + +from srunner.tools.route_parser import RouteParser +from srunner.tools.scenario_parser import ScenarioConfigurationParser +from srunner.scenarios.route_scenario import RouteScenario +from srunner.scenarios.open_scenario import OpenScenario +from srunner.scenariomanager.scenario_manager import ScenarioManager +from srunner.scenariomanager.carla_data_provider import CarlaDataProvider +from srunner.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration + +# Version of scenario_runner +VERSION = '0.9.13' + + +class ScenarioRunner(object): + + """ + This is the core scenario runner module. It is responsible for + running (and repeating) a single scenario or a list of scenarios. + + Usage: + scenario_runner = ScenarioRunner(args) + scenario_runner.run() + del scenario_runner + """ + + ego_vehicles = [] + + # Tunable parameters + client_timeout = 10.0 # in seconds + wait_for_world = 20.0 # in seconds + frame_rate = 20.0 # in Hz + + # CARLA world and scenario handlers + world = None + manager = None + + finished = False + + additional_scenario_module = None + + agent_instance = None + module_agent = None + + def __init__(self, args): + """ + Setup CARLA client and world + Setup ScenarioManager + """ + self._args = args + + if args.timeout: + self.client_timeout = float(args.timeout) + + # First of all, we need to create the client that will send the requests + # to the simulator. Here we'll assume the simulator is accepting + # requests in the localhost at port 2000. + self.client = carla.Client(args.host, int(args.port)) + self.client.set_timeout(self.client_timeout) + + dist = pkg_resources.get_distribution("carla") + if LooseVersion(dist.version) < LooseVersion('0.9.12'): + raise ImportError("CARLA version 0.9.12 or newer required. CARLA version found: {}".format(dist)) + + # Load agent if requested via command line args + # If something goes wrong an exception will be thrown by importlib (ok here) + if self._args.agent is not None: + module_name = os.path.basename(args.agent).split('.')[0] + sys.path.insert(0, os.path.dirname(args.agent)) + self.module_agent = importlib.import_module(module_name) + + # Create the ScenarioManager + self.manager = ScenarioManager(self._args.debug, self._args.sync, self._args.timeout) + + # Create signal handler for SIGINT + self._shutdown_requested = False + if sys.platform != 'win32': + signal.signal(signal.SIGHUP, self._signal_handler) + signal.signal(signal.SIGINT, self._signal_handler) + signal.signal(signal.SIGTERM, self._signal_handler) + + self._start_wall_time = datetime.now() + + def destroy(self): + """ + Cleanup and delete actors, ScenarioManager and CARLA world + """ + + self._cleanup() + if self.manager is not None: + del self.manager + if self.world is not None: + del self.world + if self.client is not None: + del self.client + + def _signal_handler(self, signum, frame): + """ + Terminate scenario ticking when receiving a signal interrupt + """ + self._shutdown_requested = True + if self.manager: + self.manager.stop_scenario() + + def _get_scenario_class_or_fail(self, scenario): + """ + Get scenario class by scenario name + If scenario is not supported or not found, exit script + """ + + # Path of all scenario at "srunner/scenarios" folder + the path of the additional scenario argument + scenarios_list = glob.glob("{}/srunner/scenarios/*.py".format(os.getenv('SCENARIO_RUNNER_ROOT', "./"))) + scenarios_list.append(self._args.additionalScenario) + + for scenario_file in scenarios_list: + + # Get their module + module_name = os.path.basename(scenario_file).split('.')[0] + sys.path.insert(0, os.path.dirname(scenario_file)) + scenario_module = importlib.import_module(module_name) + + # And their members of type class + for member in inspect.getmembers(scenario_module, inspect.isclass): + if scenario in member: + return member[1] + + # Remove unused Python paths + sys.path.pop(0) + + print("Scenario '{}' not supported ... Exiting".format(scenario)) + sys.exit(-1) + + def _cleanup(self): + """ + Remove and destroy all actors + """ + if self.finished: + return + + self.finished = True + + # Simulation still running and in synchronous mode? + if self.world is not None and self._args.sync: + try: + # Reset to asynchronous mode + settings = self.world.get_settings() + settings.synchronous_mode = False + settings.fixed_delta_seconds = None + self.world.apply_settings(settings) + self.client.get_trafficmanager(int(self._args.trafficManagerPort)).set_synchronous_mode(False) + except RuntimeError: + sys.exit(-1) + + self.manager.cleanup() + + CarlaDataProvider.cleanup() + + for i, _ in enumerate(self.ego_vehicles): + if self.ego_vehicles[i]: + if not self._args.waitForEgo and self.ego_vehicles[i] is not None and self.ego_vehicles[i].is_alive: + print("Destroying ego vehicle {}".format(self.ego_vehicles[i].id)) + self.ego_vehicles[i].destroy() + self.ego_vehicles[i] = None + self.ego_vehicles = [] + + if self.agent_instance: + self.agent_instance.destroy() + self.agent_instance = None + + def _prepare_ego_vehicles(self, ego_vehicles): + """ + Spawn or update the ego vehicles + """ + + if not self._args.waitForEgo: + for vehicle in ego_vehicles: + self.ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model, + vehicle.transform, + vehicle.rolename, + color=vehicle.color, + actor_category=vehicle.category)) + else: + ego_vehicle_missing = True + while ego_vehicle_missing: + self.ego_vehicles = [] + ego_vehicle_missing = False + for ego_vehicle in ego_vehicles: + ego_vehicle_found = False + carla_vehicles = CarlaDataProvider.get_world().get_actors().filter('vehicle.*') + for carla_vehicle in carla_vehicles: + if carla_vehicle.attributes['role_name'] == ego_vehicle.rolename: + ego_vehicle_found = True + self.ego_vehicles.append(carla_vehicle) + break + if not ego_vehicle_found: + ego_vehicle_missing = True + break + + for i, _ in enumerate(self.ego_vehicles): + self.ego_vehicles[i].set_transform(ego_vehicles[i].transform) + CarlaDataProvider.register_actor(self.ego_vehicles[i]) + + # sync state + if CarlaDataProvider.is_sync_mode(): + self.world.tick() + else: + self.world.wait_for_tick() + + def _analyze_scenario(self, config): + """ + Provide feedback about success/failure of a scenario + """ + + # Create the filename + current_time = str(datetime.now().strftime('%Y-%m-%d-%H-%M-%S')) + junit_filename = None + json_filename = None + config_name = config.name + if self._args.outputDir != '': + config_name = os.path.join(self._args.outputDir, config_name) + + if self._args.junit: + junit_filename = config_name + current_time + ".xml" + if self._args.json: + json_filename = config_name + current_time + ".json" + filename = None + if self._args.file: + filename = config_name + current_time + ".txt" + + if not self.manager.analyze_scenario(self._args.output, filename, junit_filename, json_filename): + print("All scenario tests were passed successfully!") + else: + print("Not all scenario tests were successful") + if not (self._args.output or filename or junit_filename): + print("Please run with --output for further information") + + def _record_criteria(self, criteria, name): + """ + Filter the JSON serializable attributes of the criterias and + dumps them into a file. This will be used by the metrics manager, + in case the user wants specific information about the criterias. + """ + file_name = name[:-4] + ".json" + + # Filter the attributes that aren't JSON serializable + with open('temp.json', 'w', encoding='utf-8') as fp: + + criteria_dict = {} + for criterion in criteria: + + criterion_dict = criterion.__dict__ + criteria_dict[criterion.name] = {} + + for key in criterion_dict: + if key != "name": + try: + key_dict = {key: criterion_dict[key]} + json.dump(key_dict, fp, sort_keys=False, indent=4) + criteria_dict[criterion.name].update(key_dict) + except TypeError: + pass + + os.remove('temp.json') + + # Save the criteria dictionary into a .json file + with open(file_name, 'w', encoding='utf-8') as fp: + json.dump(criteria_dict, fp, sort_keys=False, indent=4) + + def _load_and_wait_for_world(self, town, ego_vehicles=None): + """ + Load a new CARLA world and provide data to CarlaDataProvider + """ + + if self._args.reloadWorld: + self.world = self.client.load_world(town) + else: + # if the world should not be reloaded, wait at least until all ego vehicles are ready + ego_vehicle_found = False + if self._args.waitForEgo: + while not ego_vehicle_found and not self._shutdown_requested: + vehicles = self.client.get_world().get_actors().filter('vehicle.*') + for ego_vehicle in ego_vehicles: + ego_vehicle_found = False + for vehicle in vehicles: + if vehicle.attributes['role_name'] == ego_vehicle.rolename: + ego_vehicle_found = True + break + if not ego_vehicle_found: + print("Not all ego vehicles ready. Waiting ... ") + time.sleep(1) + break + + self.world = self.client.get_world() + + if self._args.sync: + settings = self.world.get_settings() + settings.synchronous_mode = True + settings.fixed_delta_seconds = 1.0 / self.frame_rate + self.world.apply_settings(settings) + + CarlaDataProvider.set_client(self.client) + CarlaDataProvider.set_world(self.world) + + # Wait for the world to be ready + if CarlaDataProvider.is_sync_mode(): + self.world.tick() + else: + self.world.wait_for_tick() + + map_name = CarlaDataProvider.get_map().name.split('/')[-1] + if map_name not in (town, "OpenDriveMap"): + print("The CARLA server uses the wrong map: {}".format(map_name)) + print("This scenario requires to use map: {}".format(town)) + return False + + return True + + def _load_and_run_scenario(self, config): + """ + Load and run the scenario given by config + """ + result = False + if not self._load_and_wait_for_world(config.town, config.ego_vehicles): + self._cleanup() + return False + + if self._args.agent: + agent_class_name = self.module_agent.__name__.title().replace('_', '') + try: + self.agent_instance = getattr(self.module_agent, agent_class_name)(self._args.agentConfig) + config.agent = self.agent_instance + except Exception as e: # pylint: disable=broad-except + traceback.print_exc() + print("Could not setup required agent due to {}".format(e)) + self._cleanup() + return False + + CarlaDataProvider.set_traffic_manager_port(int(self._args.trafficManagerPort)) + tm = self.client.get_trafficmanager(int(self._args.trafficManagerPort)) + tm.set_random_device_seed(int(self._args.trafficManagerSeed)) + if self._args.sync: + tm.set_synchronous_mode(True) + + # Prepare scenario + print("Preparing scenario: " + config.name) + try: + self._prepare_ego_vehicles(config.ego_vehicles) + if self._args.openscenario: + scenario = OpenScenario(world=self.world, + ego_vehicles=self.ego_vehicles, + config=config, + config_file=self._args.openscenario, + timeout=100000) + elif self._args.route: + scenario = RouteScenario(world=self.world, + config=config, + debug_mode=self._args.debug) + else: + scenario_class = self._get_scenario_class_or_fail(config.type) + scenario = scenario_class(self.world, + self.ego_vehicles, + config, + self._args.randomize, + self._args.debug) + except Exception as exception: # pylint: disable=broad-except + print("The scenario cannot be loaded") + traceback.print_exc() + print(exception) + self._cleanup() + return False + + try: + if self._args.record: + recorder_name = "{}/{}/{}.log".format( + os.getenv('SCENARIO_RUNNER_ROOT', "./"), self._args.record, config.name) + self.client.start_recorder(recorder_name, True) + + # Load scenario and run it + self.manager.load_scenario(scenario, self.agent_instance, config.scenario_number) + self.manager.run_scenario() + + # Provide outputs if required + self._analyze_scenario(config) + + # Remove all actors, stop the recorder and save all criterias (if needed) + scenario.remove_all_actors() + if self._args.record: + self.client.stop_recorder() + self._record_criteria(self.manager.scenario.get_criteria(), recorder_name) + + result = True + + except Exception as e: # pylint: disable=broad-except + traceback.print_exc() + print(e) + result = False + + self._cleanup() + return result + + def _run_scenarios(self): + """ + Run conventional scenarios (e.g. implemented using the Python API of ScenarioRunner) + """ + result = False + + # Load the scenario configurations provided in the config file + scenario_configurations = ScenarioConfigurationParser.parse_scenario_configuration( + self._args.scenario, + self._args.configFile) + if not scenario_configurations: + print("Configuration for scenario {} cannot be found!".format(self._args.scenario)) + return result + + # Execute each configuration + for config in scenario_configurations: + for _ in range(self._args.repetitions): + self.finished = False + result = self._load_and_run_scenario(config) + + self._cleanup() + return result + + def _run_route(self): + """ + Run the route scenario + """ + result = False + + if self._args.route: + routes = self._args.route[0] + scenario_file = self._args.route[1] + single_route = None + if len(self._args.route) > 2: + single_route = self._args.route[2] + + # retrieve routes + route_configurations = RouteParser.parse_routes_file(routes, scenario_file, single_route) + + for config in route_configurations: + for _ in range(self._args.repetitions): + result = self._load_and_run_scenario(config) + + self._cleanup() + return result + + def _run_openscenario(self): + """ + Run a scenario based on OpenSCENARIO + """ + + # Load the scenario configurations provided in the config file + if not os.path.isfile(self._args.openscenario): + print("File does not exist") + self._cleanup() + return False + + openscenario_params = {} + if self._args.openscenarioparams is not None: + for entry in self._args.openscenarioparams.split(','): + [key, val] = [m.strip() for m in entry.split(':')] + openscenario_params[key] = val + config = OpenScenarioConfiguration(self._args.openscenario, self.client, openscenario_params) + + result = self._load_and_run_scenario(config) + self._cleanup() + return result + + def run(self): + """ + Run all scenarios according to provided commandline args + """ + result = True + if self._args.openscenario: + result = self._run_openscenario() + elif self._args.route: + result = self._run_route() + else: + result = self._run_scenarios() + + print("No more scenarios .... Exiting") + return result + + +def main(): + """ + main function + """ + description = ("CARLA Scenario Runner: Setup, Run and Evaluate scenarios using CARLA\n" + "Current version: " + VERSION) + + # pylint: disable=line-too-long + parser = argparse.ArgumentParser(description=description, + formatter_class=RawTextHelpFormatter) + parser.add_argument('-v', '--version', action='version', version='%(prog)s ' + VERSION) + parser.add_argument('--host', default='127.0.0.1', + help='IP of the host server (default: localhost)') + parser.add_argument('--port', default='2000', + help='TCP port to listen to (default: 2000)') + parser.add_argument('--timeout', default="10.0", + help='Set the CARLA client timeout value in seconds') + parser.add_argument('--trafficManagerPort', default='8000', + help='Port to use for the TrafficManager (default: 8000)') + parser.add_argument('--trafficManagerSeed', default='0', + help='Seed used by the TrafficManager (default: 0)') + parser.add_argument('--sync', action='store_true', + help='Forces the simulation to run synchronously') + parser.add_argument('--list', action="store_true", help='List all supported scenarios and exit') + + parser.add_argument( + '--scenario', help='Name of the scenario to be executed. Use the preposition \'group:\' to run all scenarios of one class, e.g. ControlLoss or FollowLeadingVehicle') + parser.add_argument('--openscenario', help='Provide an OpenSCENARIO definition') + parser.add_argument('--openscenarioparams', help='Overwrited for OpenSCENARIO ParameterDeclaration') + parser.add_argument( + '--route', help='Run a route as a scenario (input: (route_file,scenario_file,[route id]))', nargs='+', type=str) + + parser.add_argument( + '--agent', help="Agent used to execute the scenario. Currently only compatible with route-based scenarios.") + parser.add_argument('--agentConfig', type=str, help="Path to Agent's configuration file", default="") + + parser.add_argument('--output', action="store_true", help='Provide results on stdout') + parser.add_argument('--file', action="store_true", help='Write results into a txt file') + parser.add_argument('--junit', action="store_true", help='Write results into a junit file') + parser.add_argument('--json', action="store_true", help='Write results into a JSON file') + parser.add_argument('--outputDir', default='', help='Directory for output files (default: this directory)') + + parser.add_argument('--configFile', default='', help='Provide an additional scenario configuration file (*.xml)') + parser.add_argument('--additionalScenario', default='', help='Provide additional scenario implementations (*.py)') + + parser.add_argument('--debug', action="store_true", help='Run with debug output') + parser.add_argument('--reloadWorld', action="store_true", + help='Reload the CARLA world before starting a scenario (default=True)') + parser.add_argument('--record', type=str, default='', + help='Path were the files will be saved, relative to SCENARIO_RUNNER_ROOT.\nActivates the CARLA recording feature and saves to file all the criteria information.') + parser.add_argument('--randomize', action="store_true", help='Scenario parameters are randomized') + parser.add_argument('--repetitions', default=1, type=int, help='Number of scenario executions') + parser.add_argument('--waitForEgo', action="store_true", help='Connect the scenario to an existing ego vehicle') + + arguments = parser.parse_args() + # pylint: enable=line-too-long + + if arguments.list: + print("Currently the following scenarios are supported:") + print(*ScenarioConfigurationParser.get_list_of_scenarios(arguments.configFile), sep='\n') + return 1 + + if not arguments.scenario and not arguments.openscenario and not arguments.route: + print("Please specify either a scenario or use the route mode\n\n") + parser.print_help(sys.stdout) + return 1 + + if arguments.route and (arguments.openscenario or arguments.scenario): + print("The route mode cannot be used together with a scenario (incl. OpenSCENARIO)'\n\n") + parser.print_help(sys.stdout) + return 1 + + if arguments.agent and (arguments.openscenario or arguments.scenario): + print("Agents are currently only compatible with route scenarios'\n\n") + parser.print_help(sys.stdout) + return 1 + + if arguments.openscenarioparams and not arguments.openscenario: + print("WARN: Ignoring --openscenarioparams when --openscenario is not specified") + + if arguments.route: + arguments.reloadWorld = True + + if arguments.agent: + arguments.sync = True + + scenario_runner = None + result = True + try: + scenario_runner = ScenarioRunner(arguments) + result = scenario_runner.run() + except Exception: # pylint: disable=broad-except + traceback.print_exc() + + finally: + if scenario_runner is not None: + scenario_runner.destroy() + del scenario_runner + return not result + + +if __name__ == "__main__": + sys.exit(main()) diff --git a/Scripts/DReyeVR.mk.help b/Scripts/DReyeVR.mk.help index 3eefe81..507205c 100644 --- a/Scripts/DReyeVR.mk.help +++ b/Scripts/DReyeVR.mk.help @@ -1,44 +1,44 @@ -Welcome to DReyeVR Codebase! -============================ - -This Makefile will help you install the different DReyeVR utilities. - -Use the following commands: - - help: - - Display this help message. - - DReyeVR | install: - - Install necessary DReyeVR files to a working compatible CARLA/ScenarioRunner installation. - Can specify Carla path with CARLA=/PATH/TO/CARLA - Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER - - check: - - Check a Carla/ScenarioRunner directory for the expected files in Scripts/Paths. - Can specify Carla path with CARLA=/PATH/TO/CARLA - Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER - - clean: - - Clean a Carla/ScenarioRunner directory by replacing overwritten files with those in Backups/ - Also provides the option to hard-clean (use git to reset/clean) if desired. - Can specify Carla path with CARLA=/PATH/TO/CARLA - Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER - - rev | r-install: - - Copy files from the Carla/ScenarioRunner directory into DReyeVR. Useful for DReyeVR development. - Can specify Carla path with CARLA=/PATH/TO/CARLA - Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER - - test: - - Run the DReyeVR script unit tests - - all: - - Runs the carla installation, then scenario-runner, then the patche(s). - Requires both CARLA=/PATH/TO/CARLA and SR=/PATH/TO/SCENARIO_RUNNER +Welcome to DReyeVR Codebase! +============================ + +This Makefile will help you install the different DReyeVR utilities. + +Use the following commands: + + help: + + Display this help message. + + DReyeVR | install: + + Install necessary DReyeVR files to a working compatible CARLA/ScenarioRunner installation. + Can specify Carla path with CARLA=/PATH/TO/CARLA + Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER + + check: + + Check a Carla/ScenarioRunner directory for the expected files in Scripts/Paths. + Can specify Carla path with CARLA=/PATH/TO/CARLA + Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER + + clean: + + Clean a Carla/ScenarioRunner directory by replacing overwritten files with those in Backups/ + Also provides the option to hard-clean (use git to reset/clean) if desired. + Can specify Carla path with CARLA=/PATH/TO/CARLA + Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER + + rev | r-install: + + Copy files from the Carla/ScenarioRunner directory into DReyeVR. Useful for DReyeVR development. + Can specify Carla path with CARLA=/PATH/TO/CARLA + Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER + + test: + + Run the DReyeVR script unit tests + + all: + + Runs the carla installation, then scenario-runner, then the patche(s). + Requires both CARLA=/PATH/TO/CARLA and SR=/PATH/TO/SCENARIO_RUNNER diff --git a/Scripts/Other/.gitignore b/Scripts/Other/.gitignore index 888c885..f9fb896 100644 --- a/Scripts/Other/.gitignore +++ b/Scripts/Other/.gitignore @@ -1,72 +1,72 @@ -Build -Dist -Doxygen -Deprecated/PythonClient/dist -TrafficManager/build -Util/Build -Install -Plugins -# added by DReyeVR so only Carla plugins are tracked -!Unreal/CarlaUE4/Plugins/Carla* - -# added by DReyeVR so old builds can be ignored -Build* - -# added by DReyeVR so the frame captures are ignored -Unreal/CarlaUE4/FrameCap - -# added by DReyeVR to ignore plugins -Unreal/CarlaUE4/Config/steamvr_ue_editor_app.json -Unreal/CarlaUE4/Config/SteamVRBindings/ -Unreal/CarlaUE4/Plugins/LogitechWheelPlugin/ -Unreal/CarlaUE4/Plugins/SRanipal - -# added by DReyeVR to MacOS builds don't track the .xcworkspace -Unreal/CarlaUE4/CarlaUE4.xcworkspace - -# added by DReyeVR to ignore this auto-generated file -Unreal/CarlaUE4/Config/OptionalModules.ini -!Unreal/CarlaUE4/Plugins -cmake-build-debug - -/ExportedMaps -/Import/* -!/Import/README.md - -*.VC.db -*.VC.opendb -*.a -*.egg-info -*.kdev4 -*.log -*.o -*.pb.cc -*.pb.h -*.pid -*.pri -*.pro -*.py[cod] -*.sln -*.so -*.stackdump -*.sublime-workspace -*.workspace -*CodeCompletionFolders.txt -*CodeLitePreProcessor.txt -.aria2c.input -.codelite -.gdb_history -.gtest -.idea -.tags* -.vs -.vscode -__pycache__ -_benchmarks_results -_images* -_out* -_site -core -profiler.csv -CarlaUE4.xcworkspace +Build +Dist +Doxygen +Deprecated/PythonClient/dist +TrafficManager/build +Util/Build +Install +Plugins +# added by DReyeVR so only Carla plugins are tracked +!Unreal/CarlaUE4/Plugins/Carla* + +# added by DReyeVR so old builds can be ignored +Build* + +# added by DReyeVR so the frame captures are ignored +Unreal/CarlaUE4/FrameCap + +# added by DReyeVR to ignore plugins +Unreal/CarlaUE4/Config/steamvr_ue_editor_app.json +Unreal/CarlaUE4/Config/SteamVRBindings/ +Unreal/CarlaUE4/Plugins/LogitechWheelPlugin/ +Unreal/CarlaUE4/Plugins/SRanipal + +# added by DReyeVR to MacOS builds don't track the .xcworkspace +Unreal/CarlaUE4/CarlaUE4.xcworkspace + +# added by DReyeVR to ignore this auto-generated file +Unreal/CarlaUE4/Config/OptionalModules.ini +!Unreal/CarlaUE4/Plugins +cmake-build-debug + +/ExportedMaps +/Import/* +!/Import/README.md + +*.VC.db +*.VC.opendb +*.a +*.egg-info +*.kdev4 +*.log +*.o +*.pb.cc +*.pb.h +*.pid +*.pri +*.pro +*.py[cod] +*.sln +*.so +*.stackdump +*.sublime-workspace +*.workspace +*CodeCompletionFolders.txt +*CodeLitePreProcessor.txt +.aria2c.input +.codelite +.gdb_history +.gtest +.idea +.tags* +.vs +.vscode +__pycache__ +_benchmarks_results +_images* +_out* +_site +core +profiler.csv +CarlaUE4.xcworkspace OptionalModules.ini \ No newline at end of file diff --git a/Scripts/Paths/DReyeVR.csv b/Scripts/Paths/DReyeVR.csv deleted file mode 100644 index 71d0ceb..0000000 --- a/Scripts/Paths/DReyeVR.csv +++ /dev/null @@ -1,15 +0,0 @@ -DReyeVR,Unreal/CarlaUE4/Source/CarlaUE4/ -CarlaUE4,Unreal/CarlaUE4/Source/ -Config/CarlaUE4.Build.cs,Unreal/CarlaUE4/Source/CarlaUE4 -Config/Default*.ini,Unreal/CarlaUE4/Config/ -Config/DReyeVRConfig.ini,Unreal/CarlaUE4/Config/ -Config/EgoVehicles/*,Unreal/CarlaUE4/Config/EgoVehicles/ -Config/Default.Package.json,Unreal/CarlaUE4/Content/Carla/Config/ -Config/CarlaUE4.uproject,Unreal/CarlaUE4/ -Content,Unreal/CarlaUE4/ -LibCarla,/ -PythonAPI,/ -Carla,Unreal/CarlaUE4/Plugins/Carla/Source/ -Util,/ -Scripts/Other/.gitignore,/ -Shaders/*.uasset,Unreal/CarlaUE4/Plugins/Carla/Content/PostProcessingMaterials/ diff --git a/Scripts/Paths/README.md b/Scripts/Paths/README.md index 51b37ca..4e221c9 100644 --- a/Scripts/Paths/README.md +++ b/Scripts/Paths/README.md @@ -1,37 +1,37 @@ -# DReyeVR-CARLA Path correspondences - -Since `DReyeVR` is a simulator that builds upon the CARLA simulator, the installation process is to copy and overwrite each file in the Carla directory with the "new" DReyeVR files. - -This is somewhat tedious and unorthodox but if you are aware of a better way then we'd be happy to hear it! (And yes, we do use forks of Carla for development which is fast, but keeping all the standalone DReyeVR changes in one clean repository is a big plus) - -Therefore, when installing to/from DReyeVR <--> Carla, we need to have some kind of path-to-path correspondences between the two directories. In this case, we use a `.csv` file to map the `DReyeVR path, Carla path` variables together in a code-agnostic manner. - -This is used in the python `utils.py` script to read the correspondences and generate a mapping from `DReyeVR -> Carla` (and equivalently `Carla -> DReyeVR`, since the mappings are bijective) which makes it simple to have a script copy over all the requisite files from one directory to another. - -## Our Mapping -The formatting we use is as follows: -```bash -# copying one DReyeVR file to a specific directory in Carla -Path/To/DReyeVR/File,Path/In/Carla/ - -# copying one DReyeVR directory to a specific directory in Carla -Path/To/DReyeVR/Directory,Path/In/Carla/ - -# copying one DReyeVR file to a specific file in Carla -# NOTE: including the path separator '/' at the end denotes directory, else file -Path/To/DReyeVR/File,Path/To/File/In/Carla - -# glob-selecting some subset of a DReyeVR repository to a specific location in Carla -Path/To/DReyeVR/Directory/*.ini,Path/In/Carla/ # example for selecting only the .ini files -``` -Notice that (as with regular `.csv`'s), there is a `,` (comma) delimiter to separate the left (DReyeVR) from the right (Carla) paths. - -Note that all the `Path/InCarla/` directories are relative to the carla root variable. - -## Add New Mappings - -Adding new mappings is simple and code-agnostic, simply add a new entry to the bottom of the `.csv` files. - -Notice that we use the [`DReyeVR.csv`](DReyeVR.csv) file for installing over a `CARLA` directory, and we use a [`ScenarioRunner.csv`](ScenarioRunner.csv) file for installing (different files) over a `ScenarioRunner` directory. - +# DReyeVR-CARLA Path correspondences + +Since `DReyeVR` is a simulator that builds upon the CARLA simulator, the installation process is to copy and overwrite each file in the Carla directory with the "new" DReyeVR files. + +This is somewhat tedious and unorthodox but if you are aware of a better way then we'd be happy to hear it! (And yes, we do use forks of Carla for development which is fast, but keeping all the standalone DReyeVR changes in one clean repository is a big plus) + +Therefore, when installing to/from DReyeVR <--> Carla, we need to have some kind of path-to-path correspondences between the two directories. In this case, we use a `.csv` file to map the `DReyeVR path, Carla path` variables together in a code-agnostic manner. + +This is used in the python `utils.py` script to read the correspondences and generate a mapping from `DReyeVR -> Carla` (and equivalently `Carla -> DReyeVR`, since the mappings are bijective) which makes it simple to have a script copy over all the requisite files from one directory to another. + +## Our Mapping +The formatting we use is as follows: +```bash +# copying one DReyeVR file to a specific directory in Carla +Path/To/DReyeVR/File,Path/In/Carla/ + +# copying one DReyeVR directory to a specific directory in Carla +Path/To/DReyeVR/Directory,Path/In/Carla/ + +# copying one DReyeVR file to a specific file in Carla +# NOTE: including the path separator '/' at the end denotes directory, else file +Path/To/DReyeVR/File,Path/To/File/In/Carla + +# glob-selecting some subset of a DReyeVR repository to a specific location in Carla +Path/To/DReyeVR/Directory/*.ini,Path/In/Carla/ # example for selecting only the .ini files +``` +Notice that (as with regular `.csv`'s), there is a `,` (comma) delimiter to separate the left (DReyeVR) from the right (Carla) paths. + +Note that all the `Path/InCarla/` directories are relative to the carla root variable. + +## Add New Mappings + +Adding new mappings is simple and code-agnostic, simply add a new entry to the bottom of the `.csv` files. + +Notice that we use the [`DReyeVR.csv`](DReyeVR.csv) file for installing over a `CARLA` directory, and we use a [`ScenarioRunner.csv`](ScenarioRunner.csv) file for installing (different files) over a `ScenarioRunner` directory. + You will need to edit the appropriate file to match your desired installation type (`make install CARLA=...` vs `make install SR=...`) \ No newline at end of file diff --git a/Scripts/Paths/ScenarioRunner.csv b/Scripts/Paths/ScenarioRunner.csv deleted file mode 100644 index 78cedec..0000000 --- a/Scripts/Paths/ScenarioRunner.csv +++ /dev/null @@ -1,6 +0,0 @@ -ScenarioRunner/run_experiment.py,/ -ScenarioRunner/scenario_runner.py,/ -ScenarioRunner/route_scenario.py,srunner/scenarios -ScenarioRunner/route_parser.py,srunner/tools -ScenarioRunner/carla_data_provider.py,srunner/scenariomanager -ScenarioRunner/scenario_manager.py,srunner/scenariomanager \ No newline at end of file diff --git a/Scripts/README.md b/Scripts/README.md index 0fc5be5..76b19d4 100644 --- a/Scripts/README.md +++ b/Scripts/README.md @@ -1,189 +1,189 @@ -# Use Our Makefile System - -How to use the DReyeVR [`Makefile`](../Makefile) - -## `make install` -```bash -# automatically install over $CARLA_ROOT and $SCENARIO_RUNNER_ROOT -make install - -# optionally, try to install on a specific directory (relative or abs) -make install CARLA=../carla -make install SR=../scenario_runner -make install CARLA=../carla SR=../scenario_runner -``` - -Additionally, a backup of all overwritten files is created in `Backups/` which should look like this: - -
- - Show expected file tree for first-time backup - -``` -# this tree holds all the files in CARLA that have been overwritten by the DReyeVR install -Backups -└── PATH - └── TO - └── YOUR - └── carla - ├── LibCarla - │   └── source - │   ├── carla - │   │   └── sensor - │   │   └── SensorRegistry.h - │   └── test - │   └── common - │   └── test_streaming.cpp - ├── PythonAPI - │   ├── carla - │   │   └── source - │   │   └── libcarla - │   │   └── SensorData.cpp - │   └── examples - │   └── start_recording.py - ├── Unreal - │   └── CarlaUE4 - │   ├── CarlaUE4.uproject - │   ├── Config - │   │   ├── DefaultEngine.ini - │   │   ├── DefaultGame.ini - │   │   └── DefaultInput.ini - │   ├── Content - │   │   └── Carla - │   │   ├── Blueprints - │   │   │   └── Game - │   │   │   └── CarlaGameMode.uasset - │   │   ├── Config - │   │   │   └── Default.Package.json - │   │   └── Maps - │   │   ├── Town01.umap - │   │   ├── Town02.umap - │   │   ├── Town03.umap - │   │   ├── Town04.umap - │   │   ├── Town05.umap - │   │   ├── Town06.umap - │   │   ├── Town07.umap - │   │   └── Town10HD.umap - │   ├── Plugins - │   │   └── Carla - │   │   └── Source - │   │   └── Carla - │   │   ├── Actor - │   │   │   └── ActorRegistry.cpp - │   │   ├── Game - │   │   │   └── CarlaEpisode.h - │   │   ├── Recorder - │   │   │   ├── CarlaRecorder.cpp - │   │   │   ├── CarlaRecorder.h - │   │   │   ├── CarlaRecorderHelpers.cpp - │   │   │   ├── CarlaRecorderHelpers.h - │   │   │   ├── CarlaRecorderQuery.cpp - │   │   │   ├── CarlaRecorderQuery.h - │   │   │   ├── CarlaReplayer.cpp - │   │   │   ├── CarlaReplayer.h - │   │   │   ├── CarlaReplayerHelper.cpp - │   │   │   └── CarlaReplayerHelper.h - │   │   ├── Settings - │   │   │   └── CarlaSettingsDelegate.cpp - │   │   ├── Traffic - │   │   │   ├── TrafficLightManager.cpp - │   │   │   └── YieldSignComponent.cpp - │   │   ├── Vehicle - │   │   │   ├── CarlaWheeledVehicle.cpp - │   │   │   └── CarlaWheeledVehicle.h - │   │   └── Weather - │   │   ├── Weather.cpp - │   │   ├── Weather.h - │   │   └── WeatherParameters.h - │   └── Source - │   └── CarlaUE4 - │   └── CarlaUE4.Build.cs - └── Util - └── BuildTools - ├── BuildOSM2ODR.sh - ├── BuildPythonAPI.sh - └── Setup.sh -``` -
- -## `make clean` - -Cleaning DReyeVR out of Carla is a good step to take when updating DReyeVR versions and/or reverting to a vanilla CARLA installation. - -The approach we use to "clean" carla is to first replace all the overwritten files from `make install` with the backups made in `Backups/`. Then, there is an option to perform a `hard-clean` where `git` is used to `reset --hard HEAD && clean -fd` which will reset all files to the `git HEAD` and then delete all untracked files/directories (`clean -fd`). - -**WARNING** the `hard-clean` step is irreversible and hence requires confirmation that looks like: -```bash -WARNING: Performing hard-clean, this irreversible action will reset all tracked CARLA files and remove untracked ones. Are you sure you want to continue? (y/n) -``` - -And you are free to skip this step by pressing `n`. - -```bash -# automatically clean $CARLA_ROOT and $SCENARIO_RUNNER_ROOT -make clean - -# optionally, try to clean on a specific directory -make clean CARLA=../carla -make clean SR=../scenario_runner -make clean CARLA=../carla SR=../scenario_runner - -# then it is recommended to go to your CARLA dir and clean from there -cd /PATH/TO/CARLA -make clean # this is the CARLA clean! -``` - -## `make check` -Check the filesystem tree after installation -```bash -# automatically check $CARLA_ROOT and $SCENARIO_RUNNER_ROOT -make check - -# optionally, try to check on a specific directory -make check CARLA=../carla -make check SR=../scenario_runner -make check CARLA=../carla SR=../scenario_runner -``` - -Expected output after installation -``` -************************************************** -Summary: -Carla [OK] -ScenarioRunner [OK] - -Done check -************************************************** -``` - -## `make r-install` - -```bash -# automatically check $CARLA_ROOT and $SCENARIO_RUNNER_ROOT -make r-install - -# optionally, try to check on a specific directory -make r-install CARLA=../carla -make r-install SR=../scenario_runner -make r-install CARLA=../carla SR=../scenario_runner -``` - -## `make test` - -This runs the unit tests for the DReyeVR scripts provided in [`tests.py`](tests.py). This is primarily for development purposes, to ensure that the low level filesystem functions work across various platforms (Windows, Linux, MacOS) - -The expected output you should get is as follows: -``` -Unit tests for installation scripts -************************************************** -Summary: -leaf: [OK] -is_dir: [OK] -create: [OK] -cp: [OK] -join: [OK] -rm: [OK] - -Done check -************************************************** +# Use Our Makefile System + +How to use the DReyeVR [`Makefile`](../Makefile) + +## `make install` +```bash +# automatically install over $CARLA_ROOT and $SCENARIO_RUNNER_ROOT +make install + +# optionally, try to install on a specific directory (relative or abs) +make install CARLA=../carla +make install SR=../scenario_runner +make install CARLA=../carla SR=../scenario_runner +``` + +Additionally, a backup of all overwritten files is created in `Backups/` which should look like this: + +
+ + Show expected file tree for first-time backup + +``` +# this tree holds all the files in CARLA that have been overwritten by the DReyeVR install +Backups +└── PATH + └── TO + └── YOUR + └── carla + ├── LibCarla + │   └── source + │   ├── carla + │   │   └── sensor + │   │   └── SensorRegistry.h + │   └── test + │   └── common + │   └── test_streaming.cpp + ├── PythonAPI + │   ├── carla + │   │   └── source + │   │   └── libcarla + │   │   └── SensorData.cpp + │   └── examples + │   └── start_recording.py + ├── Unreal + │   └── CarlaUE4 + │   ├── CarlaUE4.uproject + │   ├── Config + │   │   ├── DefaultEngine.ini + │   │   ├── DefaultGame.ini + │   │   └── DefaultInput.ini + │   ├── Content + │   │   └── Carla + │   │   ├── Blueprints + │   │   │   └── Game + │   │   │   └── CarlaGameMode.uasset + │   │   ├── Config + │   │   │   └── Default.Package.json + │   │   └── Maps + │   │   ├── Town01.umap + │   │   ├── Town02.umap + │   │   ├── Town03.umap + │   │   ├── Town04.umap + │   │   ├── Town05.umap + │   │   ├── Town06.umap + │   │   ├── Town07.umap + │   │   └── Town10HD.umap + │   ├── Plugins + │   │   └── Carla + │   │   └── Source + │   │   └── Carla + │   │   ├── Actor + │   │   │   └── ActorRegistry.cpp + │   │   ├── Game + │   │   │   └── CarlaEpisode.h + │   │   ├── Recorder + │   │   │   ├── CarlaRecorder.cpp + │   │   │   ├── CarlaRecorder.h + │   │   │   ├── CarlaRecorderHelpers.cpp + │   │   │   ├── CarlaRecorderHelpers.h + │   │   │   ├── CarlaRecorderQuery.cpp + │   │   │   ├── CarlaRecorderQuery.h + │   │   │   ├── CarlaReplayer.cpp + │   │   │   ├── CarlaReplayer.h + │   │   │   ├── CarlaReplayerHelper.cpp + │   │   │   └── CarlaReplayerHelper.h + │   │   ├── Settings + │   │   │   └── CarlaSettingsDelegate.cpp + │   │   ├── Traffic + │   │   │   ├── TrafficLightManager.cpp + │   │   │   └── YieldSignComponent.cpp + │   │   ├── Vehicle + │   │   │   ├── CarlaWheeledVehicle.cpp + │   │   │   └── CarlaWheeledVehicle.h + │   │   └── Weather + │   │   ├── Weather.cpp + │   │   ├── Weather.h + │   │   └── WeatherParameters.h + │   └── Source + │   └── CarlaUE4 + │   └── CarlaUE4.Build.cs + └── Util + └── BuildTools + ├── BuildOSM2ODR.sh + ├── BuildPythonAPI.sh + └── Setup.sh +``` +
+ +## `make clean` + +Cleaning DReyeVR out of Carla is a good step to take when updating DReyeVR versions and/or reverting to a vanilla CARLA installation. + +The approach we use to "clean" carla is to first replace all the overwritten files from `make install` with the backups made in `Backups/`. Then, there is an option to perform a `hard-clean` where `git` is used to `reset --hard HEAD && clean -fd` which will reset all files to the `git HEAD` and then delete all untracked files/directories (`clean -fd`). + +**WARNING** the `hard-clean` step is irreversible and hence requires confirmation that looks like: +```bash +WARNING: Performing hard-clean, this irreversible action will reset all tracked CARLA files and remove untracked ones. Are you sure you want to continue? (y/n) +``` + +And you are free to skip this step by pressing `n`. + +```bash +# automatically clean $CARLA_ROOT and $SCENARIO_RUNNER_ROOT +make clean + +# optionally, try to clean on a specific directory +make clean CARLA=../carla +make clean SR=../scenario_runner +make clean CARLA=../carla SR=../scenario_runner + +# then it is recommended to go to your CARLA dir and clean from there +cd /PATH/TO/CARLA +make clean # this is the CARLA clean! +``` + +## `make check` +Check the filesystem tree after installation +```bash +# automatically check $CARLA_ROOT and $SCENARIO_RUNNER_ROOT +make check + +# optionally, try to check on a specific directory +make check CARLA=../carla +make check SR=../scenario_runner +make check CARLA=../carla SR=../scenario_runner +``` + +Expected output after installation +``` +************************************************** +Summary: +Carla [OK] +ScenarioRunner [OK] + +Done check +************************************************** +``` + +## `make r-install` + +```bash +# automatically check $CARLA_ROOT and $SCENARIO_RUNNER_ROOT +make r-install + +# optionally, try to check on a specific directory +make r-install CARLA=../carla +make r-install SR=../scenario_runner +make r-install CARLA=../carla SR=../scenario_runner +``` + +## `make test` + +This runs the unit tests for the DReyeVR scripts provided in [`tests.py`](tests.py). This is primarily for development purposes, to ensure that the low level filesystem functions work across various platforms (Windows, Linux, MacOS) + +The expected output you should get is as follows: +``` +Unit tests for installation scripts +************************************************** +Summary: +leaf: [OK] +is_dir: [OK] +create: [OK] +cp: [OK] +join: [OK] +rm: [OK] + +Done check +************************************************** ``` \ No newline at end of file diff --git a/Scripts/Scripts/install.sh b/Scripts/Scripts/install.sh index d65c364..7380078 100755 --- a/Scripts/Scripts/install.sh +++ b/Scripts/Scripts/install.sh @@ -1,58 +1,58 @@ -#!/bin/bash - -DOC_STRING="Install DReyeVR atop working (1) Carla and/or (2) SRanipal installations" -USAGE_STRING="Usage: $0 [-h|--help, --carla=/PATH/TO/CARLA, --scenario-runner=/PATH/TO/SCENARIO_RUNNER]" - -INSTALL_CARLA=false -INSTALL_CARLA_ROOT= -INSTALL_SCENARIO_RUNNER=false -INSTALL_SCENARIO_RUNNER_ROOT= - -while [[ $# -gt 0 ]]; do - case "$1" in - --carla ) - INSTALL_CARLA=true; - INSTALL_CARLA_ROOT="$2"; - shift ;; - --scenario-runner ) - INSTALL_SCENARIO_RUNNER=true; - INSTALL_SCENARIO_RUNNER_ROOT="$2"; - shift ;; - -h | --help ) - echo "$DOC_STRING" - echo "$USAGE_STRING" - exit 1 - ;; - * ) - shift ;; - esac -done - -set -e # fail on error - -# current version of CARLA supported -SUPPORTED_CARLA="0.9.13" -SUPPORTED_SCENARIO_RUNNER="v0.9.13" - -source $(dirname "$0")/utils.sh -source $(dirname "$0")/installers.sh - -if ${INSTALL_CARLA}; then - CARLA_ROOT=$(update_root $CARLA_ROOT $INSTALL_CARLA_ROOT) - - verify_root "Carla" $CARLA_ROOT - - verify_installation $CARLA_ROOT CHANGELOG.md "Carla" - - verify_version $CARLA_ROOT $SUPPORTED_CARLA "Carla" carla_install -fi - -if ${INSTALL_SCENARIO_RUNNER}; then - SCENARIO_RUNNER_ROOT=$(update_root $SCENARIO_RUNNER_ROOT $INSTALL_SCENARIO_RUNNER_ROOT) - - verify_root "ScenarioRunner" $SCENARIO_RUNNER_ROOT - - verify_installation $SCENARIO_RUNNER_ROOT scenario_runner.py "ScenarioRunner" - - verify_version $SCENARIO_RUNNER_ROOT $SUPPORTED_SCENARIO_RUNNER "ScenarioRunner" scenario_runner_install +#!/bin/bash + +DOC_STRING="Install DReyeVR atop working (1) Carla and/or (2) SRanipal installations" +USAGE_STRING="Usage: $0 [-h|--help, --carla=/PATH/TO/CARLA, --scenario-runner=/PATH/TO/SCENARIO_RUNNER]" + +INSTALL_CARLA=false +INSTALL_CARLA_ROOT= +INSTALL_SCENARIO_RUNNER=false +INSTALL_SCENARIO_RUNNER_ROOT= + +while [[ $# -gt 0 ]]; do + case "$1" in + --carla ) + INSTALL_CARLA=true; + INSTALL_CARLA_ROOT="$2"; + shift ;; + --scenario-runner ) + INSTALL_SCENARIO_RUNNER=true; + INSTALL_SCENARIO_RUNNER_ROOT="$2"; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + shift ;; + esac +done + +set -e # fail on error + +# current version of CARLA supported +SUPPORTED_CARLA="0.9.13" +SUPPORTED_SCENARIO_RUNNER="v0.9.13" + +source $(dirname "$0")/utils.sh +source $(dirname "$0")/installers.sh + +if ${INSTALL_CARLA}; then + CARLA_ROOT=$(update_root $CARLA_ROOT $INSTALL_CARLA_ROOT) + + verify_root "Carla" $CARLA_ROOT + + verify_installation $CARLA_ROOT CHANGELOG.md "Carla" + + verify_version $CARLA_ROOT $SUPPORTED_CARLA "Carla" carla_install +fi + +if ${INSTALL_SCENARIO_RUNNER}; then + SCENARIO_RUNNER_ROOT=$(update_root $SCENARIO_RUNNER_ROOT $INSTALL_SCENARIO_RUNNER_ROOT) + + verify_root "ScenarioRunner" $SCENARIO_RUNNER_ROOT + + verify_installation $SCENARIO_RUNNER_ROOT scenario_runner.py "ScenarioRunner" + + verify_version $SCENARIO_RUNNER_ROOT $SUPPORTED_SCENARIO_RUNNER "ScenarioRunner" scenario_runner_install fi \ No newline at end of file diff --git a/Scripts/Scripts/installers.sh b/Scripts/Scripts/installers.sh index f1ccd5c..1334caa 100644 --- a/Scripts/Scripts/installers.sh +++ b/Scripts/Scripts/installers.sh @@ -1,57 +1,57 @@ -#!/bin/bash - -source $(dirname "$0")/utils.sh - -carla_install() { - ROOT=$1 - # this function denotes the specific files that get copied over from DReyeVR to a compatible Carla directory - echo -e "\nInstalling DReyeVR to ${ROOT}" - cp -v -r DReyeVR $ROOT/Unreal/CarlaUE4/Source/CarlaUE4/ - # configs - cp -v Configs/CarlaUE4.Build.cs $ROOT/Unreal/CarlaUE4/Source/CarlaUE4/ - cp -v Configs/CarlaGameMode.uasset $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Game/ - cp -v Configs/Default*.ini $ROOT/Unreal/CarlaUE4/Config/ - cp -v Configs/DReyeVRConfig.ini $ROOT/Unreal/CarlaUE4/Config/ - cp -v Configs/CarlaUE4.uproject $ROOT/Unreal/CarlaUE4/ - # blueprints - cp -v -r Blueprints/DReyeVR $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/ - cp -v -r Blueprints/2Wheeled $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/ - cp -v -r Blueprints/Game $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/ - # content - mkdir -p $ROOT/Unreal/CarlaUE4/Content/DReyeVR/ # new DReyeVR content folder - cp -v -r Content/DReyeVR_Signs $ROOT/Unreal/CarlaUE4/Content/DReyeVR/ - cp -v -r Content/Custom $ROOT/Unreal/CarlaUE4/Content/DReyeVR/ - cp -v Content/Default.Package.json $ROOT/Unreal/CarlaUE4/Content/Carla/Config/ - # maps - cp -v Maps/* $ROOT/Unreal/CarlaUE4/Content/Carla/Maps/ - # LibCarla - cp -v LibCarla/Sensor/data/* $ROOT/LibCarla/source/carla/sensor/data/ - cp -v LibCarla/Sensor/s11n/* $ROOT/LibCarla/source/carla/sensor/s11n/ - cp -v LibCarla/SensorRegistry.h $ROOT/LibCarla/source/carla/sensor/ - cp -v LibCarla/SensorData.cpp $ROOT/PythonAPI/carla/source/libcarla/ - # PythonAPI - cp -v PythonAPI/*.py $ROOT/PythonAPI/examples/ - # Carla - cp -v Carla/Vehicle/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/ - cp -v Carla/Sensor/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ - cp -v Carla/Game/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/ - cp -v Carla/Settings/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/ - cp -v Carla/Traffic/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Traffic/ - cp -v Carla/Actor/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ - cp -v Carla/Recorder/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/ - cp -v Carla/Weather/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Weather/ - # BuildTools - cp -v Tools/BuildTools/*.sh $ROOT/Util/BuildTools/ - cp -v Tools/BuildTools/test_streaming.cpp $ROOT/LibCarla/source/test/common/ - echo -e "${G}Installation of DReyeVR to Carla successful!${NC}" -} - -scenario_runner_install() { - ROOT=$1 - # this function denotes the specific files that get copied over from DReyeVR to a compatible ScenarioRunner directory - echo -e "\nInstalling ScenarioRunner to ${ROOT}" - cp -v ScenarioRunner/run_experiment.py $ROOT/ - cp -v ScenarioRunner/route_scenario.py $ROOT/srunner/scenarios/ - cp -v ScenarioRunner/carla_data_provider.py $ROOT/srunner/scenariomanager/ - echo -e "${G}Installation of DReyeVR to ScenarioRunner successful!${NC}" +#!/bin/bash + +source $(dirname "$0")/utils.sh + +carla_install() { + ROOT=$1 + # this function denotes the specific files that get copied over from DReyeVR to a compatible Carla directory + echo -e "\nInstalling DReyeVR to ${ROOT}" + cp -v -r DReyeVR $ROOT/Unreal/CarlaUE4/Source/CarlaUE4/ + # configs + cp -v Configs/CarlaUE4.Build.cs $ROOT/Unreal/CarlaUE4/Source/CarlaUE4/ + cp -v Configs/CarlaGameMode.uasset $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Game/ + cp -v Configs/Default*.ini $ROOT/Unreal/CarlaUE4/Config/ + cp -v Configs/DReyeVRConfig.ini $ROOT/Unreal/CarlaUE4/Config/ + cp -v Configs/CarlaUE4.uproject $ROOT/Unreal/CarlaUE4/ + # blueprints + cp -v -r Blueprints/DReyeVR $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/ + cp -v -r Blueprints/2Wheeled $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/ + cp -v -r Blueprints/Game $ROOT/Unreal/CarlaUE4/Content/Carla/Blueprints/ + # content + mkdir -p $ROOT/Unreal/CarlaUE4/Content/DReyeVR/ # new DReyeVR content folder + cp -v -r Content/DReyeVR_Signs $ROOT/Unreal/CarlaUE4/Content/DReyeVR/ + cp -v -r Content/Custom $ROOT/Unreal/CarlaUE4/Content/DReyeVR/ + cp -v Content/Default.Package.json $ROOT/Unreal/CarlaUE4/Content/Carla/Config/ + # maps + cp -v Maps/* $ROOT/Unreal/CarlaUE4/Content/Carla/Maps/ + # LibCarla + cp -v LibCarla/Sensor/data/* $ROOT/LibCarla/source/carla/sensor/data/ + cp -v LibCarla/Sensor/s11n/* $ROOT/LibCarla/source/carla/sensor/s11n/ + cp -v LibCarla/SensorRegistry.h $ROOT/LibCarla/source/carla/sensor/ + cp -v LibCarla/SensorData.cpp $ROOT/PythonAPI/carla/source/libcarla/ + # PythonAPI + cp -v PythonAPI/*.py $ROOT/PythonAPI/examples/ + # Carla + cp -v Carla/Vehicle/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/ + cp -v Carla/Sensor/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ + cp -v Carla/Game/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/ + cp -v Carla/Settings/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/ + cp -v Carla/Traffic/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Traffic/ + cp -v Carla/Actor/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ + cp -v Carla/Recorder/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/ + cp -v Carla/Weather/* $ROOT/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Weather/ + # BuildTools + cp -v Tools/BuildTools/*.sh $ROOT/Util/BuildTools/ + cp -v Tools/BuildTools/test_streaming.cpp $ROOT/LibCarla/source/test/common/ + echo -e "${G}Installation of DReyeVR to Carla successful!${NC}" +} + +scenario_runner_install() { + ROOT=$1 + # this function denotes the specific files that get copied over from DReyeVR to a compatible ScenarioRunner directory + echo -e "\nInstalling ScenarioRunner to ${ROOT}" + cp -v ScenarioRunner/run_experiment.py $ROOT/ + cp -v ScenarioRunner/route_scenario.py $ROOT/srunner/scenarios/ + cp -v ScenarioRunner/carla_data_provider.py $ROOT/srunner/scenariomanager/ + echo -e "${G}Installation of DReyeVR to ScenarioRunner successful!${NC}" } \ No newline at end of file diff --git a/Scripts/Scripts/patch_sranipal.sh b/Scripts/Scripts/patch_sranipal.sh index e11ffb5..4e2e2b5 100755 --- a/Scripts/Scripts/patch_sranipal.sh +++ b/Scripts/Scripts/patch_sranipal.sh @@ -1,41 +1,41 @@ -#!/bin/bash - -# the reason for this patch's existance is that the latest (at time of writing) SRanipal plugin -# source code has an enum "FrameworkStatus::ERROR" in Source/SRanipalEye/Public/SRanipalEye_Framework.h -# which directly conflicts with some lingering #defines from UE4's WebRTC or CEF3 code which include a -# #define ERROR 0, this unfortunately gets propogated through the build and causes syntax errors when -# trying to compile SRanipal directly. The easiest fix with least ramifications is to simply rename the -# SRanipal's FrameworkStatus::ERROR variable to something specific like FrameworkStatus::ERROR_SRANIPAL - -set -e - -source $(dirname "$0")/utils.sh - -CARLA_ROOT=$(update_root $CARLA_ROOT $1) # see if we need to override the carla root - -cd $CARLA_ROOT - -# where the plugin should be installed -PLUGIN_DIR="Unreal/CarlaUE4/Plugins" -PLUGIN_DIR=$(to_abs_path $PLUGIN_DIR) # convert to absolute path - -# which files need to be modified -HEADER_FILE="SRanipal/Source/SRanipalEye/Public/SRanipalEye_Framework.h" -SOURCE_FILE="SRanipal/Source/SRanipalEye/Private/SRanipalEye_Framework.cpp" - -verify_installation $PLUGIN_DIR $HEADER_FILE "SRanipal" - -NEW_ERROR="ERROR_SRANIPAL" # make sure this matches with EgoSensor.cpp - -if grep -q $NEW_ERROR "$PLUGIN_DIR/$HEADER_FILE"; then # check if already been applied - echo -e "${Y}Patch has already been applied!${NC}" - exit 0 -fi - -sed -i "s/ERROR/${NEW_ERROR}/g" $PLUGIN_DIR/$HEADER_FILE -sed -i "s/ERROR/${NEW_ERROR}/g" $PLUGIN_DIR/$SOURCE_FILE - -echo -e "${G}Completed SRanipal patching${NC}" - -# back to original working directory +#!/bin/bash + +# the reason for this patch's existance is that the latest (at time of writing) SRanipal plugin +# source code has an enum "FrameworkStatus::ERROR" in Source/SRanipalEye/Public/SRanipalEye_Framework.h +# which directly conflicts with some lingering #defines from UE4's WebRTC or CEF3 code which include a +# #define ERROR 0, this unfortunately gets propogated through the build and causes syntax errors when +# trying to compile SRanipal directly. The easiest fix with least ramifications is to simply rename the +# SRanipal's FrameworkStatus::ERROR variable to something specific like FrameworkStatus::ERROR_SRANIPAL + +set -e + +source $(dirname "$0")/utils.sh + +CARLA_ROOT=$(update_root $CARLA_ROOT $1) # see if we need to override the carla root + +cd $CARLA_ROOT + +# where the plugin should be installed +PLUGIN_DIR="Unreal/CarlaUE4/Plugins" +PLUGIN_DIR=$(to_abs_path $PLUGIN_DIR) # convert to absolute path + +# which files need to be modified +HEADER_FILE="SRanipal/Source/SRanipalEye/Public/SRanipalEye_Framework.h" +SOURCE_FILE="SRanipal/Source/SRanipalEye/Private/SRanipalEye_Framework.cpp" + +verify_installation $PLUGIN_DIR $HEADER_FILE "SRanipal" + +NEW_ERROR="ERROR_SRANIPAL" # make sure this matches with EgoSensor.cpp + +if grep -q $NEW_ERROR "$PLUGIN_DIR/$HEADER_FILE"; then # check if already been applied + echo -e "${Y}Patch has already been applied!${NC}" + exit 0 +fi + +sed -i "s/ERROR/${NEW_ERROR}/g" $PLUGIN_DIR/$HEADER_FILE +sed -i "s/ERROR/${NEW_ERROR}/g" $PLUGIN_DIR/$SOURCE_FILE + +echo -e "${G}Completed SRanipal patching${NC}" + +# back to original working directory cd $OLDPWD \ No newline at end of file diff --git a/Scripts/Scripts/utils.sh b/Scripts/Scripts/utils.sh index 54b7f99..88d0eba 100644 --- a/Scripts/Scripts/utils.sh +++ b/Scripts/Scripts/utils.sh @@ -1,78 +1,78 @@ -#!/bin/bash - -R='\033[0;31m' # Red -G='\033[0;32m' # Green -Y='\033[0;33m' # Yellow -B='\033[0;34m' # Blue -NC='\033[0m' # No Color - -update_root() { - # override ROOT with NEW_ROOT if provided, else throw an error - ROOT=$1 - NEW_ROOT=$2 - if [ -z ${NEW_ROOT} ]; then - if [ -z $ROOT ]; then - echo -e "${R}ERROR: Unable to access ${ROOT}${NC}" >&2 - exit 1 - fi - else - ROOT=$NEW_ROOT - fi - # verify directory exists - if [ -d $ROOT ]; then - to_abs_path $ROOT # output of function - else - echo -e "${R}Unable to locate directory: ${ROOT}${NC}" >&2 - exit 1 - fi -} - -to_abs_path() { - # source: https://stackoverflow.com/a/31605674 - echo "$(cd "$(dirname "$1")"; pwd)/$(basename "$1")" -} - -verify_root() { - NAME=$1 - ROOT=$2 - if [ -z "${ROOT}" ]; then - echo -e "${R}ERROR: No ${NAME} root path provided${NC}" - exit 1 - fi -} - -verify_installation() { - ROOT=$1 - FILE=$2 - NAME=$3 - if [ ! -f ${ROOT}/${FILE} ] - then - echo -e "${R}Could not verify a correct ${NAME} installation at ${ROOT}${NC}" - exit 1 - else - echo -e "${G}Found a ${NAME} installation at ${ROOT}${NC}" - fi -} - -verify_version() { - ROOT=$1 - SUPPORTED=$2 - NAME=$3 - INSTALL_FN=$4 - # getting version from branch/tag from: https://stackoverflow.com/questions/18659425/get-git-current-branch-tag-name - version=$(cd ${ROOT} && git symbolic-ref -q --short HEAD || git describe --tags --exact-match && cd $OLDPWD) - if [ "${version}" == "${SUPPORTED}" ] ; then - echo -e "${G}Verified compatible ${NAME} version${NC}" - $INSTALL_FN ${ROOT} # run the install script to this root - else - echo -e "${R}Only ${NAME} version ${SUPPORTED} is supported! Detected version: ${version}${NC}" - read -p "$(echo -e ${Y}"Do you want to continue anyways? (y/n) "${NC})" -n 1 -r CONFIRM - echo # move cursor to a new line - if [[ ${CONFIRM} =~ ^[Yy]$ ]]; then - echo -e "${B}Attempting to install to ${ROOT} (${version})${NC}" - $INSTALL_FN ${ROOT} # run the install script to this root - else - echo -e "${B}Skipping install${NC}" - fi - fi +#!/bin/bash + +R='\033[0;31m' # Red +G='\033[0;32m' # Green +Y='\033[0;33m' # Yellow +B='\033[0;34m' # Blue +NC='\033[0m' # No Color + +update_root() { + # override ROOT with NEW_ROOT if provided, else throw an error + ROOT=$1 + NEW_ROOT=$2 + if [ -z ${NEW_ROOT} ]; then + if [ -z $ROOT ]; then + echo -e "${R}ERROR: Unable to access ${ROOT}${NC}" >&2 + exit 1 + fi + else + ROOT=$NEW_ROOT + fi + # verify directory exists + if [ -d $ROOT ]; then + to_abs_path $ROOT # output of function + else + echo -e "${R}Unable to locate directory: ${ROOT}${NC}" >&2 + exit 1 + fi +} + +to_abs_path() { + # source: https://stackoverflow.com/a/31605674 + echo "$(cd "$(dirname "$1")"; pwd)/$(basename "$1")" +} + +verify_root() { + NAME=$1 + ROOT=$2 + if [ -z "${ROOT}" ]; then + echo -e "${R}ERROR: No ${NAME} root path provided${NC}" + exit 1 + fi +} + +verify_installation() { + ROOT=$1 + FILE=$2 + NAME=$3 + if [ ! -f ${ROOT}/${FILE} ] + then + echo -e "${R}Could not verify a correct ${NAME} installation at ${ROOT}${NC}" + exit 1 + else + echo -e "${G}Found a ${NAME} installation at ${ROOT}${NC}" + fi +} + +verify_version() { + ROOT=$1 + SUPPORTED=$2 + NAME=$3 + INSTALL_FN=$4 + # getting version from branch/tag from: https://stackoverflow.com/questions/18659425/get-git-current-branch-tag-name + version=$(cd ${ROOT} && git symbolic-ref -q --short HEAD || git describe --tags --exact-match && cd $OLDPWD) + if [ "${version}" == "${SUPPORTED}" ] ; then + echo -e "${G}Verified compatible ${NAME} version${NC}" + $INSTALL_FN ${ROOT} # run the install script to this root + else + echo -e "${R}Only ${NAME} version ${SUPPORTED} is supported! Detected version: ${version}${NC}" + read -p "$(echo -e ${Y}"Do you want to continue anyways? (y/n) "${NC})" -n 1 -r CONFIRM + echo # move cursor to a new line + if [[ ${CONFIRM} =~ ^[Yy]$ ]]; then + echo -e "${B}Attempting to install to ${ROOT} (${version})${NC}" + $INSTALL_FN ${ROOT} # run the install script to this root + else + echo -e "${B}Skipping install${NC}" + fi + fi } \ No newline at end of file diff --git a/Scripts/check_install.py b/Scripts/check_install.py index ef826e6..309445e 100644 --- a/Scripts/check_install.py +++ b/Scripts/check_install.py @@ -1,144 +1,144 @@ -#!/usr/bin/env python - -import os -from typing import List, Optional -import filecmp - -from utils import ( - CARLA_PATH_FILE, - SR_PATH_FILE, - SUPPORTED_CARLA, - SUPPORTED_SCENARIO_RUNNER, - advanced_join, - advanced_is_dir, - default_args, - expand_correspondences_glob, - generate_correspondences, - get_all_files, - get_leaf_from_path, - print_line, - print_status, - verify_installation, - verify_version, -) - -DOC_STRING = "Simple script to check correspondences are present" - - -def check_repo( - ROOT: str = None, - corr_file: str = CARLA_PATH_FILE, - verify_files: List[str] = [], - git_tag: Optional[str] = None, - verbose: Optional[bool] = True, -) -> bool: - if ROOT is None: - return True - # begin check process - ROOT = os.path.abspath(ROOT) # convert to absolute path - verify_installation(ROOT, verify_files) - if verify_version(ROOT, git_tag) == False: - return True - print_line() - print(f"Checking root ({ROOT})") - - corr = generate_correspondences(corr_file) - all_corr = expand_correspondences_glob(corr) - all_files = get_all_files(all_corr) - - def found(filepath: str) -> None: - if verbose: - print(f"{filepath} -- found") - - def check(filepath: str, local_file: str = None) -> None: - # make sure the files have the same content - if filecmp.cmp(filepath, local_file) is False: - if verbose: - print(f"{filepath} -- modified") - modified_files.append(filepath) - else: - found(filepath) - - def not_found(filepath: str) -> None: - if verbose: - print(f"{filepath} -- not found") - - missing_files: List[str] = [] - modified_files: List[str] = [] - for k in all_corr.keys(): - leafname = get_leaf_from_path(k) - expected_path: str = advanced_join([ROOT, all_corr[k], leafname]) - if os.path.exists(expected_path): - if advanced_is_dir(expected_path): - found(expected_path) - for inner_f in all_files[k]: - inner_f_relative: str = inner_f[inner_f.find(leafname) :] - file_path = advanced_join([ROOT, all_corr[k], inner_f_relative]) - if os.path.exists(file_path): - check(file_path, local_file=inner_f) - else: - not_found(file_path) - missing_files.append(file_path) - else: - check(expected_path, local_file=k) - else: - not_found(expected_path) - missing_files.append(expected_path) - # raise Exception(f"Failed to find {expected_path}") - - if len(missing_files) > 0: - print() - print("ERROR: the following files are missing:") - for m in missing_files: - print(m) - return False - - if len(modified_files) > 0: - print() - print("ERROR: the following files are modified:") - for m in modified_files: - print(m) - return False - - print("Success!") - return True - - -if __name__ == "__main__": - args = default_args( - DOC_STRING, - other_args=[ - {"name": "--verbose", "action": "store_true"}, - {"name": "--hard", "action": "store_true"}, - ], - ) - - print_line() - check_carla = check_repo( - args.carla, - corr_file=CARLA_PATH_FILE, - git_tag=SUPPORTED_CARLA, - verify_files=["CHANGELOG.md"], - verbose=args.verbose, - ) - print() - check_sr = check_repo( - args.scenario_runner, - corr_file=SR_PATH_FILE, - git_tag=SUPPORTED_SCENARIO_RUNNER, - verify_files=["scenario_runner.py"], - verbose=args.verbose, - ) - - print() - - print_line() - print(f"Summary:") - if args.carla: - print(f"Carla [{print_status(check_carla)}]") - if args.scenario_runner: - print(f"ScenarioRunner [{print_status(check_sr)}]") - - print() - print("Done check") - print_line() +#!/usr/bin/env python + +import os +from typing import List, Optional +import filecmp + +from utils import ( + CARLA_PATH_FILE, + SR_PATH_FILE, + SUPPORTED_CARLA, + SUPPORTED_SCENARIO_RUNNER, + advanced_join, + advanced_is_dir, + default_args, + expand_correspondences_glob, + generate_correspondences, + get_all_files, + get_leaf_from_path, + print_line, + print_status, + verify_installation, + verify_version, +) + +DOC_STRING = "Simple script to check correspondences are present" + + +def check_repo( + ROOT: str = None, + corr_file: str = CARLA_PATH_FILE, + verify_files: List[str] = [], + git_tag: Optional[str] = None, + verbose: Optional[bool] = True, +) -> bool: + if ROOT is None: + return True + # begin check process + ROOT = os.path.abspath(ROOT) # convert to absolute path + verify_installation(ROOT, verify_files) + if verify_version(ROOT, git_tag) == False: + return True + print_line() + print(f"Checking root ({ROOT})") + + corr = generate_correspondences(corr_file) + all_corr = expand_correspondences_glob(corr) + all_files = get_all_files(all_corr) + + def found(filepath: str) -> None: + if verbose: + print(f"{filepath} -- found") + + def check(filepath: str, local_file: str = None) -> None: + # make sure the files have the same content + if filecmp.cmp(filepath, local_file) is False: + if verbose: + print(f"{filepath} -- modified") + modified_files.append(filepath) + else: + found(filepath) + + def not_found(filepath: str) -> None: + if verbose: + print(f"{filepath} -- not found") + + missing_files: List[str] = [] + modified_files: List[str] = [] + for k in all_corr.keys(): + leafname = get_leaf_from_path(k) + expected_path: str = advanced_join([ROOT, all_corr[k], leafname]) + if os.path.exists(expected_path): + if advanced_is_dir(expected_path): + found(expected_path) + for inner_f in all_files[k]: + inner_f_relative: str = inner_f[inner_f.find(leafname) :] + file_path = advanced_join([ROOT, all_corr[k], inner_f_relative]) + if os.path.exists(file_path): + check(file_path, local_file=inner_f) + else: + not_found(file_path) + missing_files.append(file_path) + else: + check(expected_path, local_file=k) + else: + not_found(expected_path) + missing_files.append(expected_path) + # raise Exception(f"Failed to find {expected_path}") + + if len(missing_files) > 0: + print() + print("ERROR: the following files are missing:") + for m in missing_files: + print(m) + return False + + if len(modified_files) > 0: + print() + print("ERROR: the following files are modified:") + for m in modified_files: + print(m) + return False + + print("Success!") + return True + + +if __name__ == "__main__": + args = default_args( + DOC_STRING, + other_args=[ + {"name": "--verbose", "action": "store_true"}, + {"name": "--hard", "action": "store_true"}, + ], + ) + + print_line() + check_carla = check_repo( + args.carla, + corr_file=CARLA_PATH_FILE, + git_tag=SUPPORTED_CARLA, + verify_files=["CHANGELOG.md"], + verbose=args.verbose, + ) + print() + check_sr = check_repo( + args.scenario_runner, + corr_file=SR_PATH_FILE, + git_tag=SUPPORTED_SCENARIO_RUNNER, + verify_files=["scenario_runner.py"], + verbose=args.verbose, + ) + + print() + + print_line() + print(f"Summary:") + if args.carla: + print(f"Carla [{print_status(check_carla)}]") + if args.scenario_runner: + print(f"ScenarioRunner [{print_status(check_sr)}]") + + print() + print("Done check") + print_line() diff --git a/Scripts/clean.py b/Scripts/clean.py index 0d7723f..a634510 100644 --- a/Scripts/clean.py +++ b/Scripts/clean.py @@ -1,136 +1,136 @@ -#!/usr/bin/env python - -import os -import subprocess -from typing import List, Optional - -from utils import ( - BACKUPS_DIR, - CARLA_PATH_FILE, - SR_PATH_FILE, - SUPPORTED_CARLA, - SUPPORTED_SCENARIO_RUNNER, - advanced_cp, - advanced_join, - advanced_rm, - default_args, - expand_correspondences_glob, - generate_correspondences, - get_leaf_from_path, - print_line, - verify_installation, - verify_version, -) - -DOC_STRING = "Script to clean original repository with backups and/or hard-clean" - - -def clean_replace( - ROOT: str = None, - corr_file: str = CARLA_PATH_FILE, - verify_files: List[str] = [], - git_tag: Optional[str] = None, - verbose: Optional[bool] = True, -) -> None: - if ROOT is None: - return - if not os.path.exists(BACKUPS_DIR): - print("No backups made! Unable to clean-replace...") - print("To make a backup, first run the installer script") - return - # begin clean process - ROOT = os.path.abspath(ROOT) # convert to absolute path - verify_installation(ROOT, verify_files) - if verify_version(ROOT, git_tag) == False: - return - print_line() - print(f'Cleaning root "{ROOT}"') - - corr = generate_correspondences(corr_file) - all_corr = expand_correspondences_glob(corr) - - for k in all_corr.keys(): - leafname = get_leaf_from_path(k) - rel_dest: str = all_corr[k] - expected_path: str = advanced_join([ROOT, rel_dest, leafname]) - # by virtue of the latest backup dir not having a timestamp suffix, this is the - # default backup dir we use to replace files - backup_path: str = advanced_join([BACKUPS_DIR, ROOT, rel_dest, leafname]) - if os.path.exists(expected_path): - if os.path.exists(backup_path): - if verbose: - print(f'Replacing "{expected_path}" with backup "{backup_path}"') - # only append leaf if not a directory - # cp -r A B should result in B/A, not B/{contents of A} or B/A/A - if os.path.isdir(k): - expected_path = advanced_join([ROOT, rel_dest]) - advanced_cp(backup_path, expected_path, verbose=False) - else: - if verbose: - print(f"Removing {expected_path} as there is no backup entry") - advanced_rm(expected_path) - else: - if verbose: - print(f"{leafname} not found, nothing to clean") - - print("Success!") - - -def hard_clean(repo: Optional[str], force: Optional[bool] = False) -> None: - if repo is None: - return - if force is False: - warning: str = ( - "WARNING: Performing hard-clean, this irreversible action " - "will reset all tracked CARLA files and remove untracked ones. " - "Are you sure you want to continue? (y/n)" - ) - proceed = input(warning) - if proceed.lower() != "y": - print(f"Skipping hard clean of {repo}") - return - # performs a deep clean through git - # TODO: make sure this is robust - cwd = os.getcwd() - os.chdir(repo) - git_status_cmd = "git status" - status = subprocess.check_call(git_status_cmd.split(" ")) - git_reset_cmd = "git reset --hard HEAD" - status = subprocess.check_call(git_reset_cmd.split(" ")) - git_clean_cmd = "git clean -fd" # delete untracked files and directories - status = subprocess.check_call(git_clean_cmd.split(" ")) - os.chdir(cwd) - - -if __name__ == "__main__": - args = default_args( - DOC_STRING, - other_args=[ - {"name": "--verbose", "action": "store_true"}, - {"name": "--hard", "action": "store_true"}, - ], - ) - - print_line() - clean_replace( - args.carla, - corr_file=CARLA_PATH_FILE, - git_tag=SUPPORTED_CARLA, - verify_files=["CHANGELOG.md"], - verbose=args.verbose, - ) - hard_clean(args.carla, force=args.hard) - print() - - print_line() - clean_replace( - args.scenario_runner, - corr_file=SR_PATH_FILE, - git_tag=SUPPORTED_SCENARIO_RUNNER, - verify_files=["scenario_runner.py"], - verbose=args.verbose, - ) - hard_clean(args.scenario_runner, force=args.hard) - print() - print("Done clean") - print_line() +#!/usr/bin/env python + +import os +import subprocess +from typing import List, Optional + +from utils import ( + BACKUPS_DIR, + CARLA_PATH_FILE, + SR_PATH_FILE, + SUPPORTED_CARLA, + SUPPORTED_SCENARIO_RUNNER, + advanced_cp, + advanced_join, + advanced_rm, + default_args, + expand_correspondences_glob, + generate_correspondences, + get_leaf_from_path, + print_line, + verify_installation, + verify_version, +) + +DOC_STRING = "Script to clean original repository with backups and/or hard-clean" + + +def clean_replace( + ROOT: str = None, + corr_file: str = CARLA_PATH_FILE, + verify_files: List[str] = [], + git_tag: Optional[str] = None, + verbose: Optional[bool] = True, +) -> None: + if ROOT is None: + return + if not os.path.exists(BACKUPS_DIR): + print("No backups made! Unable to clean-replace...") + print("To make a backup, first run the installer script") + return + # begin clean process + ROOT = os.path.abspath(ROOT) # convert to absolute path + verify_installation(ROOT, verify_files) + if verify_version(ROOT, git_tag) == False: + return + print_line() + print(f'Cleaning root "{ROOT}"') + + corr = generate_correspondences(corr_file) + all_corr = expand_correspondences_glob(corr) + + for k in all_corr.keys(): + leafname = get_leaf_from_path(k) + rel_dest: str = all_corr[k] + expected_path: str = advanced_join([ROOT, rel_dest, leafname]) + # by virtue of the latest backup dir not having a timestamp suffix, this is the + # default backup dir we use to replace files + backup_path: str = advanced_join([BACKUPS_DIR, ROOT, rel_dest, leafname]) + if os.path.exists(expected_path): + if os.path.exists(backup_path): + if verbose: + print(f'Replacing "{expected_path}" with backup "{backup_path}"') + # only append leaf if not a directory + # cp -r A B should result in B/A, not B/{contents of A} or B/A/A + if os.path.isdir(k): + expected_path = advanced_join([ROOT, rel_dest]) + advanced_cp(backup_path, expected_path, verbose=False) + else: + if verbose: + print(f"Removing {expected_path} as there is no backup entry") + advanced_rm(expected_path) + else: + if verbose: + print(f"{leafname} not found, nothing to clean") + + print("Success!") + + +def hard_clean(repo: Optional[str], force: Optional[bool] = False) -> None: + if repo is None: + return + if force is False: + warning: str = ( + "WARNING: Performing hard-clean, this irreversible action " + "will reset all tracked CARLA files and remove untracked ones. " + "Are you sure you want to continue? (y/n)" + ) + proceed = input(warning) + if proceed.lower() != "y": + print(f"Skipping hard clean of {repo}") + return + # performs a deep clean through git + # TODO: make sure this is robust + cwd = os.getcwd() + os.chdir(repo) + git_status_cmd = "git status" + status = subprocess.check_call(git_status_cmd.split(" ")) + git_reset_cmd = "git reset --hard HEAD" + status = subprocess.check_call(git_reset_cmd.split(" ")) + git_clean_cmd = "git clean -fd" # delete untracked files and directories + status = subprocess.check_call(git_clean_cmd.split(" ")) + os.chdir(cwd) + + +if __name__ == "__main__": + args = default_args( + DOC_STRING, + other_args=[ + {"name": "--verbose", "action": "store_true"}, + {"name": "--hard", "action": "store_true"}, + ], + ) + + print_line() + clean_replace( + args.carla, + corr_file=CARLA_PATH_FILE, + git_tag=SUPPORTED_CARLA, + verify_files=["CHANGELOG.md"], + verbose=args.verbose, + ) + hard_clean(args.carla, force=args.hard) + print() + + print_line() + clean_replace( + args.scenario_runner, + corr_file=SR_PATH_FILE, + git_tag=SUPPORTED_SCENARIO_RUNNER, + verify_files=["scenario_runner.py"], + verbose=args.verbose, + ) + hard_clean(args.scenario_runner, force=args.hard) + print() + print("Done clean") + print_line() diff --git a/Scripts/install.py b/Scripts/install.py index 87aaa32..d9a3f35 100755 --- a/Scripts/install.py +++ b/Scripts/install.py @@ -1,87 +1,87 @@ -#!/usr/bin/env python - -import os -from typing import Optional - -from utils import ( - BACKUPS_DIR, - CARLA_PATH_FILE, - SR_PATH_FILE, - SUPPORTED_CARLA, - SUPPORTED_SCENARIO_RUNNER, - advanced_cp, - advanced_join, - advanced_is_dir, - get_leaf_from_path, - get_all_files, - default_args, - generate_correspondences, - expand_correspondences_glob, - print_line, - update_backups, - verify_installation, - verify_version, -) - -DOC_STRING: str = "Install DReyeVR atop a working Carla and/or ScenarioRunner directory" - - -def install_over( - ROOT: Optional[str], - correspondences_file: str, - git_tag: str, - check_files: Optional[str] = None, -) -> None: - if ROOT is None: - return - # begin installation process - ROOT_ABS = os.path.abspath(ROOT) # convert to absolute path - # verify that the root exists and files in "check_files" exist - verify_installation(ROOT_ABS, check_files) - # verify the git version of this repository matches - if verify_version(ROOT_ABS, git_tag) == False: - return - print_line() - print(f"Installing DReyeVR over {ROOT_ABS}") - update_backups(ROOT_ABS) - # generate the DReyeVR -> root path correspondences - corr = generate_correspondences(correspondences_file) - all_corr = expand_correspondences_glob(corr) - all_files_within = get_all_files(all_corr) - for DReyeVR_path, CARLA_path in all_corr.items(): - if advanced_is_dir(DReyeVR_path): - # installing a directory (many files within) - for local_file in all_files_within[DReyeVR_path]: - dest_path: str = advanced_join([ROOT, CARLA_path, local_file]) - advanced_cp(local_file, dest_path, verbose=True) - else: - # installing an individual file - assert os.path.isfile(DReyeVR_path) - file_leafname: str = get_leaf_from_path(DReyeVR_path) - dest_path: str = advanced_join([ROOT, CARLA_path, file_leafname]) - advanced_cp(DReyeVR_path, dest_path, verbose=True) - print() - print(f"Installation success!") - print(f"Backups created in {advanced_join([BACKUPS_DIR, ROOT_ABS])}") - - -if __name__ == "__main__": - args = default_args(DOC_STRING) - - print_line() - install_over( - ROOT=args.carla, - correspondences_file=CARLA_PATH_FILE, - git_tag=SUPPORTED_CARLA, - check_files=["CHANGELOG.md"], - ) - print() - install_over( - ROOT=args.scenario_runner, - correspondences_file=SR_PATH_FILE, - git_tag=SUPPORTED_SCENARIO_RUNNER, - check_files=["scenario_runner.py"], - ) - print() - print("Done installation") - print_line() +#!/usr/bin/env python + +import os +from typing import Optional + +from utils import ( + BACKUPS_DIR, + CARLA_PATH_FILE, + SR_PATH_FILE, + SUPPORTED_CARLA, + SUPPORTED_SCENARIO_RUNNER, + advanced_cp, + advanced_join, + advanced_is_dir, + get_leaf_from_path, + get_all_files, + default_args, + generate_correspondences, + expand_correspondences_glob, + print_line, + update_backups, + verify_installation, + verify_version, +) + +DOC_STRING: str = "Install DReyeVR atop a working Carla and/or ScenarioRunner directory" + + +def install_over( + ROOT: Optional[str], + correspondences_file: str, + git_tag: str, + check_files: Optional[str] = None, +) -> None: + if ROOT is None: + return + # begin installation process + ROOT_ABS = os.path.abspath(ROOT) # convert to absolute path + # verify that the root exists and files in "check_files" exist + verify_installation(ROOT_ABS, check_files) + # verify the git version of this repository matches + if verify_version(ROOT_ABS, git_tag) == False: + return + print_line() + print(f"Installing DReyeVR over {ROOT_ABS}") + update_backups(ROOT_ABS) + # generate the DReyeVR -> root path correspondences + corr = generate_correspondences(correspondences_file) + all_corr = expand_correspondences_glob(corr) + all_files_within = get_all_files(all_corr) + for DReyeVR_path, CARLA_path in all_corr.items(): + if advanced_is_dir(DReyeVR_path): + # installing a directory (many files within) + for local_file in all_files_within[DReyeVR_path]: + dest_path: str = advanced_join([ROOT, CARLA_path, local_file]) + advanced_cp(local_file, dest_path, verbose=True) + else: + # installing an individual file + assert os.path.isfile(DReyeVR_path) + file_leafname: str = get_leaf_from_path(DReyeVR_path) + dest_path: str = advanced_join([ROOT, CARLA_path, file_leafname]) + advanced_cp(DReyeVR_path, dest_path, verbose=True) + print() + print(f"Installation success!") + print(f"Backups created in {advanced_join([BACKUPS_DIR, ROOT_ABS])}") + + +if __name__ == "__main__": + args = default_args(DOC_STRING) + + print_line() + install_over( + ROOT=args.carla, + correspondences_file=CARLA_PATH_FILE, + git_tag=SUPPORTED_CARLA, + check_files=["CHANGELOG.md"], + ) + print() + install_over( + ROOT=args.scenario_runner, + correspondences_file=SR_PATH_FILE, + git_tag=SUPPORTED_SCENARIO_RUNNER, + check_files=["scenario_runner.py"], + ) + print() + print("Done installation") + print_line() diff --git a/Scripts/r-install.py b/Scripts/r-install.py index 3594aad..7ad514b 100644 --- a/Scripts/r-install.py +++ b/Scripts/r-install.py @@ -1,107 +1,107 @@ -#!/usr/bin/env python - -import glob -import os -from typing import List, Optional - -from utils import ( - CARLA_PATH_FILE, - SR_PATH_FILE, - SUPPORTED_CARLA, - SUPPORTED_SCENARIO_RUNNER, - advanced_cp, - advanced_join, - default_args, - expand_correspondences_glob, - generate_correspondences, - get_leaf_from_path, - print_line, - update_backups, - verify_installation, - verify_version, -) - -DOC_STRING = "Simple script to update the DReyeVR repository (reverse-install) with Carla changes" - - -def r_install(src: str, dest: str, ROOT: str, verbose: Optional[bool] = False) -> None: - # copy from dest into src (reverse install) - leafname = get_leaf_from_path(src) - if not os.path.exists(src): - raise Exception(f"Unable to locate src: \"{src}\"") - dest_is_root: bool = dest == os.path.dirname(dest) - if (not os.path.exists(dest) or dest_is_root) and ROOT not in dest: - dest: str = advanced_join([ROOT, dest, leafname]) - if os.path.exists(dest): - if verbose: - print(f"{dest} -- found") - if os.path.isdir(src): - # if src is a directory, we only want to r-install files it contains - # not the entire directory (which could contain things we don't need) - all_DReyeVR_files: List[str] = glob.glob(os.path.join(src, "*")) - all_CARLA_files: List[str] = glob.glob(os.path.join(dest, "*")) - for CARLA_file in all_CARLA_files: - # check if DReyeVR_file is in a substring of all_files - for DReyeVR_file in all_DReyeVR_files: - if DReyeVR_file in CARLA_file: - r_install(DReyeVR_file, CARLA_file, ROOT, verbose=verbose) - break # shouldn't be any more files that satisfy this - return - elif os.path.isdir(dest): - dest = os.path.join(dest, "*") - advanced_cp(dest, src, verbose=verbose) - else: - print(f"{dest} -- not found") - - -def update_DReyeVR_repo( - ROOT: str = None, - corr_file: str = CARLA_PATH_FILE, - verify_files: List[str] = [], - git_tag: Optional[str] = None, - verbose: Optional[bool] = True, -) -> None: - if ROOT is None: - return - # begin r-install process - ROOT = os.path.abspath(ROOT) # convert to absolute path - verify_installation(ROOT, verify_files) - if verify_version(ROOT, git_tag) == False: - return - print_line() - print(f"Reverse-installing from ({ROOT})") - update_backups(os.path.abspath(os.getcwd())) - - corr = generate_correspondences(corr_file) - all_corr = expand_correspondences_glob(corr) - - for src in all_corr.keys(): - r_install(src, all_corr[src], ROOT, verbose) - - print("Success!") - - -if __name__ == "__main__": - args = default_args(DOC_STRING) - - print(DOC_STRING) - print_line() - update_DReyeVR_repo( - args.carla, - corr_file=CARLA_PATH_FILE, - git_tag=SUPPORTED_CARLA, - verify_files=["CHANGELOG.md"], - verbose=True, - ) - print() - update_DReyeVR_repo( - args.scenario_runner, - corr_file=SR_PATH_FILE, - git_tag=SUPPORTED_SCENARIO_RUNNER, - verify_files=["scenario_runner.py"], - verbose=True, - ) - - print() - print("Done reverse-install") - print_line() +#!/usr/bin/env python + +import glob +import os +from typing import List, Optional + +from utils import ( + CARLA_PATH_FILE, + SR_PATH_FILE, + SUPPORTED_CARLA, + SUPPORTED_SCENARIO_RUNNER, + advanced_cp, + advanced_join, + default_args, + expand_correspondences_glob, + generate_correspondences, + get_leaf_from_path, + print_line, + update_backups, + verify_installation, + verify_version, +) + +DOC_STRING = "Simple script to update the DReyeVR repository (reverse-install) with Carla changes" + + +def r_install(src: str, dest: str, ROOT: str, verbose: Optional[bool] = False) -> None: + # copy from dest into src (reverse install) + leafname = get_leaf_from_path(src) + if not os.path.exists(src): + raise Exception(f"Unable to locate src: \"{src}\"") + dest_is_root: bool = dest == os.path.dirname(dest) + if (not os.path.exists(dest) or dest_is_root) and ROOT not in dest: + dest: str = advanced_join([ROOT, dest, leafname]) + if os.path.exists(dest): + if verbose: + print(f"{dest} -- found") + if os.path.isdir(src): + # if src is a directory, we only want to r-install files it contains + # not the entire directory (which could contain things we don't need) + all_DReyeVR_files: List[str] = glob.glob(os.path.join(src, "*")) + all_CARLA_files: List[str] = glob.glob(os.path.join(dest, "*")) + for CARLA_file in all_CARLA_files: + # check if DReyeVR_file is in a substring of all_files + for DReyeVR_file in all_DReyeVR_files: + if DReyeVR_file in CARLA_file: + r_install(DReyeVR_file, CARLA_file, ROOT, verbose=verbose) + break # shouldn't be any more files that satisfy this + return + elif os.path.isdir(dest): + dest = os.path.join(dest, "*") + advanced_cp(dest, src, verbose=verbose) + else: + print(f"{dest} -- not found") + + +def update_DReyeVR_repo( + ROOT: str = None, + corr_file: str = CARLA_PATH_FILE, + verify_files: List[str] = [], + git_tag: Optional[str] = None, + verbose: Optional[bool] = True, +) -> None: + if ROOT is None: + return + # begin r-install process + ROOT = os.path.abspath(ROOT) # convert to absolute path + verify_installation(ROOT, verify_files) + if verify_version(ROOT, git_tag) == False: + return + print_line() + print(f"Reverse-installing from ({ROOT})") + update_backups(os.path.abspath(os.getcwd())) + + corr = generate_correspondences(corr_file) + all_corr = expand_correspondences_glob(corr) + + for src in all_corr.keys(): + r_install(src, all_corr[src], ROOT, verbose) + + print("Success!") + + +if __name__ == "__main__": + args = default_args(DOC_STRING) + + print(DOC_STRING) + print_line() + update_DReyeVR_repo( + args.carla, + corr_file=CARLA_PATH_FILE, + git_tag=SUPPORTED_CARLA, + verify_files=["CHANGELOG.md"], + verbose=True, + ) + print() + update_DReyeVR_repo( + args.scenario_runner, + corr_file=SR_PATH_FILE, + git_tag=SUPPORTED_SCENARIO_RUNNER, + verify_files=["scenario_runner.py"], + verbose=True, + ) + + print() + print("Done reverse-install") + print_line() diff --git a/Scripts/tests.py b/Scripts/tests.py index 75cf3d0..388248d 100644 --- a/Scripts/tests.py +++ b/Scripts/tests.py @@ -1,329 +1,329 @@ -#!/usr/bin/env python - -import os -import shutil -import glob -from typing import Callable, List, Optional, Tuple - -from utils import ( - advanced_is_dir, - advanced_create, - advanced_cp, - advanced_join, - advanced_rm, - get_leaf_from_path, - print_line, - print_status, -) - -DOC_STRING = "Unit tests for installation scripts" - -UNIT_TEST_DIR: str = "Tests" - - -def clear_dir() -> None: - # shutil.rmtree(os.getcwd()) - for f in glob.glob(os.path.join(os.getcwd(), "*")): - if os.path.isdir(f): - shutil.rmtree(f) - else: - os.remove(f) - - -def run_get_leaf_tests() -> bool: - tests: List[Tuple[str, str]] = [ - (os.path.join("test1", "test2", "file.txt"), "file.txt"), - (os.path.join("file.txt"), "file.txt"), - (os.path.join("test1", "file.txt"), "file.txt"), - (os.path.join("test1", "test2", "something_else"), "something_else"), - (os.sep, os.sep), - (os.path.join("heres", "a", "directory") + os.sep, "directory" + os.sep), - (os.path.join("another", "dir") + os.sep, "dir" + os.sep), - ] - for name, expected in tests: - if get_leaf_from_path(name) != expected: - print(f'ERROR: expected get_leaf to return "{expected}" for "{name}"') - return False - return True - - -def run_is_dir_tests() -> bool: - name_and_exp = [ - ("test", False), - ("test" + os.sep, True), - (os.sep, True), - (os.path.join(os.sep, "dir", "file.txt"), False), - (os.path.join(os.sep, "dir", "dir2" + os.sep), True), - # often directories in DReyeVR are labeled with '/' sep - (os.path.join("testing", "linuxsep/"), True), - ] - for name, expected in name_and_exp: - if advanced_is_dir(name) != expected: - print(f'ERROR: expected is_dir to return "{expected}" for "{name}"') - return False - return True - - -def create_test(filename: str, contents: str) -> bool: - # test creation - advanced_create(filename, contents) - if not os.path.exists(filename): - raise Exception(f'expected file "{filename}" missing') - - if advanced_is_dir(filename): - if not os.path.isdir(filename): - raise Exception(f"Expected a directory for {filename}") - else: - # test contents - exp_contents: str = "" - with open(filename, "r") as f: - exp_contents = f.read() - if exp_contents != contents: - raise Exception(f'expected contents in "{filename}" incorrect!') - return True - - -def run_create_tests(): - clear_dir() # ensure the working directory is clear - test_args: List[Tuple[str, str]] = [ - ("dummy.txt", "hello"), - ("dummy.csv", "hello"), - ("dummy.png", "hello"), - ("dummy.txt", ""), - ("dummy.csv", 5000 * "this is a long string"), - ("dummy..", ".."), - (os.path.join("directory1", "directory2", "file.txt"), "hello there"), - (os.path.join("directory1", "file.txt"), "hello there"), - ("test_dir" + os.sep, ""), - ("test_dir" + os.sep, None), - ("test_dir" + os.sep, "content shouldn't matter"), - (os.path.join("test_dir2", "test_file"), "content shouldn't matter"), - ] - for args in test_args: - try: - if create_test(*args) == False: - return False - except Exception as e: - print(f"ERROR: {e}") - return False - return True - - -def cp_test(filename: str, contents: str) -> bool: - # make a dummy file, fill it, test copying - advanced_create(filename, contents) - - def check_cp(og_file: str, new_file: str, contents: str) -> None: - if not os.path.exists(og_file): - raise Exception(f'original file "{og_file}" missing') - - if not os.path.exists(new_file): - raise Exception(f'new file "{new_file}" missing') - - # check contents match - with open(new_file, "r") as f: - new_contents = f.read() - if new_contents != contents: - raise Exception( - f"New contents ({new_contents}) don't match expected ({contents})" - ) - - # test copying to a completely new file - new_file: str = f"new_file.txt" - advanced_cp(filename, new_file) - check_cp(filename, new_file, contents) - - existing_file: str = f"existing_file" - # test copying to an existing (empty) file - advanced_create(existing_file, "") - advanced_cp(filename, existing_file) - - # test copying to an existing (full) file - advanced_create(existing_file, "test in existing file") - advanced_cp(filename, existing_file) - check_cp(filename, existing_file, contents) - - # test copying to an empty directory - empty_dir: str = "tmp" + os.sep - assert advanced_is_dir(empty_dir) - advanced_cp(filename, empty_dir) - new_file: str = os.path.join(empty_dir, get_leaf_from_path(filename)) - check_cp(filename, new_file, contents) - - # test copying to a directory with existing file - full_dir: str = "tmp" + os.sep - assert advanced_is_dir(full_dir) - existing_file_in_dir: str = os.path.join(full_dir, existing_file) - advanced_create(existing_file_in_dir, "some other content") - advanced_cp(filename, full_dir) # should overwrite the existing_file_in_dir - new_file: str = os.path.join(full_dir, get_leaf_from_path(filename)) - check_cp(filename, new_file, contents) - advanced_cp(filename, existing_file_in_dir) # file to file directly - check_cp(filename, new_file, contents) - - # ensure no additional files are created - tmp_files = ["tmp1.txt", "tmp2.txt", "tmp3.txt"] - tmp_dir: str = "tmp_dir" - for tmp_file in tmp_files: - advanced_cp(filename, os.path.join(tmp_dir, tmp_file)) - - dir_data = list(os.walk(tmp_dir)) - assert len(dir_data) == 1 - - root_name, subdirs, files = dir_data[0] - assert root_name == tmp_dir - assert subdirs == [] - if sorted(files) != sorted(tmp_files): # sort so order doesn't matter - raise Exception( - f"Expected files in {tmp_dir} to be {tmp_files}, instead got {files}" - ) - - return True - - -def run_cp_tests() -> bool: - clear_dir() # ensure the working directory is clear - """test for advanced_cp""" - test_args: List[Tuple[str, str]] = [ - ("dummy.txt", "hello"), - ("dummy.csv", "hello"), - ("dummy.png", "hello"), - ("dummy.txt", ""), - ("dummy.csv", 5000 * "this is a long string"), - ("dummy..", ".."), - (os.path.join("directory1", "directory2", "file.txt"), "hello there"), - (os.path.join("directory1", "file.txt"), "hello there"), - ] - for args in test_args: - try: - if cp_test(*args) == False: - return False - except Exception as e: - print(f"ERROR: {e}") - return False - return True - - -def run_join_tests() -> bool: - clear_dir() # ensure the working directory is clear - tests: List[Tuple[List[str], str]] = [ - (["this", "is", "a", "path"], os.path.join("this", "is", "a", "path")), - ( - ["this", "is", "a", "dir" + os.sep], - os.path.join("this", "is", "a", "dir") + os.sep, - ), - (["one_line_path"], os.path.join("one_line_path")), - ( - ["this", "is", "a"] + 500 * ["long"] + ["path"], - os.path.join("this", "is", "a", *(500 * ["long"]), "path"), - ), - ([os.pardir, os.curdir, "one"], os.path.join(os.pardir, os.curdir, "one")), - ( - ["relative", "path", os.sep + "absolute", "path" + os.sep], - os.path.join("relative", "path") - + os.sep - + os.path.splitdrive(os.path.join("absolute", "path"))[-1] - + os.sep, - ), - ( - [os.pardir, "test", os.path.abspath(os.getcwd())], # NOTE: known dir - os.path.join(os.pardir, "test") - + os.path.splitdrive(os.path.abspath(os.getcwd()))[-1] - + os.sep, - ), - ( - [os.path.abspath(os.getcwd()), "nonexistant_dir" + os.sep], - os.path.join(os.path.splitdrive(os.getcwd())[-1], "nonexistant_dir") - + os.sep, - ), - ] - for args, expected in tests: - actual: str = advanced_join(args) - if actual != expected: - print(f'ERROR: expected join to return "{expected}" for "{args}"') - print(f'instead got "{actual}"') - return False - return True - - -def rm_test(filename: str) -> bool: - # test creation - advanced_create(filename, "some content") - advanced_rm(filename) - if os.path.exists(filename): - raise Exception(f'expected file "{filename}" to be removed') - return True - - -def run_rm_tests() -> bool: - clear_dir() # ensure the working directory is clear - test_args: List[Tuple[str, str]] = [ - "dummy.txt", - "dummy.csv", - "dummy.png", - "dummy.txt", - "dummy.csv", - os.path.join("directory1", "directory2", "file.txt"), - os.path.join("directory1", "file.txt"), - "test_dir" + os.sep, - os.path.join("test_dir2", "test_file"), - os.path.join("test_dir2", "test_dir" + os.sep), - ] - for args in test_args: - try: - if rm_test(args) == False: - return False - except Exception as e: - print(f"ERROR: {e}") - return False - - # ensure no lingering things in this dir - advanced_rm(os.path.join(os.getcwd(), "*")) - dir_data = list(os.walk(os.getcwd())) - assert len(dir_data) == 1 - - root_name, subdirs, files = dir_data[0] - assert root_name == os.getcwd() - if len(subdirs) > 0: - print( - f"ERROR: found {len(subdirs)} subdirectories remaining in {os.getcwd()}. Expected none." - ) - return False - if len(files) > 0: - print( - f"ERROR: found {len(files)} files remaining in {os.getcwd()}. Expected none." - ) - return False - - return True - - -if __name__ == "__main__": - print(DOC_STRING) - print_line() - tests: List[Tuple[str, Callable[[None], bool]]] = [ - ("leaf", run_get_leaf_tests), - ("is_dir", run_is_dir_tests), - ("create", run_create_tests), - ("cp", run_cp_tests), - ("join", run_join_tests), - ("rm", run_rm_tests), - ] - - # create the unit test dir and go to it. This will be the working directory - og_dir: str = os.getcwd() - os.makedirs(UNIT_TEST_DIR, exist_ok=True) - os.chdir(UNIT_TEST_DIR) - - print(f"Summary:") - - for name, test in tests: - print(f"{name}:\t\t[{print_status(test())}]") - - # delete the unit test dir - os.chdir(og_dir) - if os.path.exists(UNIT_TEST_DIR): - shutil.rmtree(UNIT_TEST_DIR) - print() - print("Done check") - print_line() +#!/usr/bin/env python + +import os +import shutil +import glob +from typing import Callable, List, Optional, Tuple + +from utils import ( + advanced_is_dir, + advanced_create, + advanced_cp, + advanced_join, + advanced_rm, + get_leaf_from_path, + print_line, + print_status, +) + +DOC_STRING = "Unit tests for installation scripts" + +UNIT_TEST_DIR: str = "Tests" + + +def clear_dir() -> None: + # shutil.rmtree(os.getcwd()) + for f in glob.glob(os.path.join(os.getcwd(), "*")): + if os.path.isdir(f): + shutil.rmtree(f) + else: + os.remove(f) + + +def run_get_leaf_tests() -> bool: + tests: List[Tuple[str, str]] = [ + (os.path.join("test1", "test2", "file.txt"), "file.txt"), + (os.path.join("file.txt"), "file.txt"), + (os.path.join("test1", "file.txt"), "file.txt"), + (os.path.join("test1", "test2", "something_else"), "something_else"), + (os.sep, os.sep), + (os.path.join("heres", "a", "directory") + os.sep, "directory" + os.sep), + (os.path.join("another", "dir") + os.sep, "dir" + os.sep), + ] + for name, expected in tests: + if get_leaf_from_path(name) != expected: + print(f'ERROR: expected get_leaf to return "{expected}" for "{name}"') + return False + return True + + +def run_is_dir_tests() -> bool: + name_and_exp = [ + ("test", False), + ("test" + os.sep, True), + (os.sep, True), + (os.path.join(os.sep, "dir", "file.txt"), False), + (os.path.join(os.sep, "dir", "dir2" + os.sep), True), + # often directories in DReyeVR are labeled with '/' sep + (os.path.join("testing", "linuxsep/"), True), + ] + for name, expected in name_and_exp: + if advanced_is_dir(name) != expected: + print(f'ERROR: expected is_dir to return "{expected}" for "{name}"') + return False + return True + + +def create_test(filename: str, contents: str) -> bool: + # test creation + advanced_create(filename, contents) + if not os.path.exists(filename): + raise Exception(f'expected file "{filename}" missing') + + if advanced_is_dir(filename): + if not os.path.isdir(filename): + raise Exception(f"Expected a directory for {filename}") + else: + # test contents + exp_contents: str = "" + with open(filename, "r") as f: + exp_contents = f.read() + if exp_contents != contents: + raise Exception(f'expected contents in "{filename}" incorrect!') + return True + + +def run_create_tests(): + clear_dir() # ensure the working directory is clear + test_args: List[Tuple[str, str]] = [ + ("dummy.txt", "hello"), + ("dummy.csv", "hello"), + ("dummy.png", "hello"), + ("dummy.txt", ""), + ("dummy.csv", 5000 * "this is a long string"), + ("dummy..", ".."), + (os.path.join("directory1", "directory2", "file.txt"), "hello there"), + (os.path.join("directory1", "file.txt"), "hello there"), + ("test_dir" + os.sep, ""), + ("test_dir" + os.sep, None), + ("test_dir" + os.sep, "content shouldn't matter"), + (os.path.join("test_dir2", "test_file"), "content shouldn't matter"), + ] + for args in test_args: + try: + if create_test(*args) == False: + return False + except Exception as e: + print(f"ERROR: {e}") + return False + return True + + +def cp_test(filename: str, contents: str) -> bool: + # make a dummy file, fill it, test copying + advanced_create(filename, contents) + + def check_cp(og_file: str, new_file: str, contents: str) -> None: + if not os.path.exists(og_file): + raise Exception(f'original file "{og_file}" missing') + + if not os.path.exists(new_file): + raise Exception(f'new file "{new_file}" missing') + + # check contents match + with open(new_file, "r") as f: + new_contents = f.read() + if new_contents != contents: + raise Exception( + f"New contents ({new_contents}) don't match expected ({contents})" + ) + + # test copying to a completely new file + new_file: str = f"new_file.txt" + advanced_cp(filename, new_file) + check_cp(filename, new_file, contents) + + existing_file: str = f"existing_file" + # test copying to an existing (empty) file + advanced_create(existing_file, "") + advanced_cp(filename, existing_file) + + # test copying to an existing (full) file + advanced_create(existing_file, "test in existing file") + advanced_cp(filename, existing_file) + check_cp(filename, existing_file, contents) + + # test copying to an empty directory + empty_dir: str = "tmp" + os.sep + assert advanced_is_dir(empty_dir) + advanced_cp(filename, empty_dir) + new_file: str = os.path.join(empty_dir, get_leaf_from_path(filename)) + check_cp(filename, new_file, contents) + + # test copying to a directory with existing file + full_dir: str = "tmp" + os.sep + assert advanced_is_dir(full_dir) + existing_file_in_dir: str = os.path.join(full_dir, existing_file) + advanced_create(existing_file_in_dir, "some other content") + advanced_cp(filename, full_dir) # should overwrite the existing_file_in_dir + new_file: str = os.path.join(full_dir, get_leaf_from_path(filename)) + check_cp(filename, new_file, contents) + advanced_cp(filename, existing_file_in_dir) # file to file directly + check_cp(filename, new_file, contents) + + # ensure no additional files are created + tmp_files = ["tmp1.txt", "tmp2.txt", "tmp3.txt"] + tmp_dir: str = "tmp_dir" + for tmp_file in tmp_files: + advanced_cp(filename, os.path.join(tmp_dir, tmp_file)) + + dir_data = list(os.walk(tmp_dir)) + assert len(dir_data) == 1 + + root_name, subdirs, files = dir_data[0] + assert root_name == tmp_dir + assert subdirs == [] + if sorted(files) != sorted(tmp_files): # sort so order doesn't matter + raise Exception( + f"Expected files in {tmp_dir} to be {tmp_files}, instead got {files}" + ) + + return True + + +def run_cp_tests() -> bool: + clear_dir() # ensure the working directory is clear + """test for advanced_cp""" + test_args: List[Tuple[str, str]] = [ + ("dummy.txt", "hello"), + ("dummy.csv", "hello"), + ("dummy.png", "hello"), + ("dummy.txt", ""), + ("dummy.csv", 5000 * "this is a long string"), + ("dummy..", ".."), + (os.path.join("directory1", "directory2", "file.txt"), "hello there"), + (os.path.join("directory1", "file.txt"), "hello there"), + ] + for args in test_args: + try: + if cp_test(*args) == False: + return False + except Exception as e: + print(f"ERROR: {e}") + return False + return True + + +def run_join_tests() -> bool: + clear_dir() # ensure the working directory is clear + tests: List[Tuple[List[str], str]] = [ + (["this", "is", "a", "path"], os.path.join("this", "is", "a", "path")), + ( + ["this", "is", "a", "dir" + os.sep], + os.path.join("this", "is", "a", "dir") + os.sep, + ), + (["one_line_path"], os.path.join("one_line_path")), + ( + ["this", "is", "a"] + 500 * ["long"] + ["path"], + os.path.join("this", "is", "a", *(500 * ["long"]), "path"), + ), + ([os.pardir, os.curdir, "one"], os.path.join(os.pardir, os.curdir, "one")), + ( + ["relative", "path", os.sep + "absolute", "path" + os.sep], + os.path.join("relative", "path") + + os.sep + + os.path.splitdrive(os.path.join("absolute", "path"))[-1] + + os.sep, + ), + ( + [os.pardir, "test", os.path.abspath(os.getcwd())], # NOTE: known dir + os.path.join(os.pardir, "test") + + os.path.splitdrive(os.path.abspath(os.getcwd()))[-1] + + os.sep, + ), + ( + [os.path.abspath(os.getcwd()), "nonexistant_dir" + os.sep], + os.path.join(os.path.splitdrive(os.getcwd())[-1], "nonexistant_dir") + + os.sep, + ), + ] + for args, expected in tests: + actual: str = advanced_join(args) + if actual != expected: + print(f'ERROR: expected join to return "{expected}" for "{args}"') + print(f'instead got "{actual}"') + return False + return True + + +def rm_test(filename: str) -> bool: + # test creation + advanced_create(filename, "some content") + advanced_rm(filename) + if os.path.exists(filename): + raise Exception(f'expected file "{filename}" to be removed') + return True + + +def run_rm_tests() -> bool: + clear_dir() # ensure the working directory is clear + test_args: List[Tuple[str, str]] = [ + "dummy.txt", + "dummy.csv", + "dummy.png", + "dummy.txt", + "dummy.csv", + os.path.join("directory1", "directory2", "file.txt"), + os.path.join("directory1", "file.txt"), + "test_dir" + os.sep, + os.path.join("test_dir2", "test_file"), + os.path.join("test_dir2", "test_dir" + os.sep), + ] + for args in test_args: + try: + if rm_test(args) == False: + return False + except Exception as e: + print(f"ERROR: {e}") + return False + + # ensure no lingering things in this dir + advanced_rm(os.path.join(os.getcwd(), "*")) + dir_data = list(os.walk(os.getcwd())) + assert len(dir_data) == 1 + + root_name, subdirs, files = dir_data[0] + assert root_name == os.getcwd() + if len(subdirs) > 0: + print( + f"ERROR: found {len(subdirs)} subdirectories remaining in {os.getcwd()}. Expected none." + ) + return False + if len(files) > 0: + print( + f"ERROR: found {len(files)} files remaining in {os.getcwd()}. Expected none." + ) + return False + + return True + + +if __name__ == "__main__": + print(DOC_STRING) + print_line() + tests: List[Tuple[str, Callable[[None], bool]]] = [ + ("leaf", run_get_leaf_tests), + ("is_dir", run_is_dir_tests), + ("create", run_create_tests), + ("cp", run_cp_tests), + ("join", run_join_tests), + ("rm", run_rm_tests), + ] + + # create the unit test dir and go to it. This will be the working directory + og_dir: str = os.getcwd() + os.makedirs(UNIT_TEST_DIR, exist_ok=True) + os.chdir(UNIT_TEST_DIR) + + print(f"Summary:") + + for name, test in tests: + print(f"{name}:\t\t[{print_status(test())}]") + + # delete the unit test dir + os.chdir(og_dir) + if os.path.exists(UNIT_TEST_DIR): + shutil.rmtree(UNIT_TEST_DIR) + print() + print("Done check") + print_line() diff --git a/Scripts/utils.py b/Scripts/utils.py index 8fd0386..26085df 100644 --- a/Scripts/utils.py +++ b/Scripts/utils.py @@ -1,389 +1,389 @@ -import argparse -import csv -import glob -import os -import shutil -import subprocess -from datetime import datetime -from typing import Any, Dict, List, Optional, Tuple - -# current version of CARLA supported (git tag) -SUPPORTED_CARLA: str = "0.9.13" -SUPPORTED_SCENARIO_RUNNER: str = "v0.9.13" - -# backup directory for overwritten files -BACKUPS_DIR: str = "Backups" -os.makedirs(BACKUPS_DIR, exist_ok=True) - -CARLA_PATH_FILE: str = os.path.join("Scripts", "Paths", "DReyeVR.csv") -SR_PATH_FILE: str = os.path.join("Scripts", "Paths", "ScenarioRunner.csv") - - -def print_line() -> None: - print("*" * 50) - - -def print_subtitle(title: str): - print() - print("*" * 25 + title + "*" * 25) - - -def print_cp(src: str, dest: str, verbose: Optional[bool] = True) -> None: - if verbose: - print(f"{src} -> {dest}") - - -def print_status(b: bool) -> str: - return "OK" if b else "FAILED" - - -def verify_installation(root_dir: str, check_files: List[str] = []) -> None: - assert os.path.exists(root_dir) - # check that all these files are in root_dir - for f in check_files: - if not os.path.exists(os.path.join(root_dir, f)): - raise Exception(f'Expected file "{f}" not present in "{root_dir}"') - print(f"Verified installation ({root_dir})") - - -def get_leaf_from_path(path: str) -> str: - if advanced_is_dir(path): - # include the path separator to ensure it is still recognized as a directory - return os.path.basename(os.path.normpath(path)) + os.sep - return os.path.basename(path) - - -def get_git_tag(root_dir: str) -> str: - # TODO: make this more robust - current = os.getcwd() - os.chdir(root_dir) - # this command works well on vanilla repos - git_tag_cmd: str = "git describe --tags --exact-match" - # this command works well when on repo forks - git_tag_cmd_fork: str = "git symbolic-ref -q --short HEAD" - try: - detected: bytes = subprocess.check_output(git_tag_cmd.split(" ")) - except Exception as e: - try: - print("...Attempting backup git tag cmd...") - detected_backup: bytes = subprocess.check_output( - git_tag_cmd_fork.split(" ") - ) - detected = detected_backup - except Exception as e2: - print(f'First try: {type(e).__name__}: "{e}"') - print(f'Second try: {type(e2).__name__}: "{e2}"') - detected: bytes = b"Unknown" - os.chdir(current) - return detected.decode("ascii").strip() - - -def verify_version(root_dir: str, expected: str) -> bool: - assert os.path.exists(root_dir) - detected = get_git_tag(root_dir) - if detected != expected: - print(f"Only {expected} version is supported! Detected version: {detected}") - progress = input("Do you want to continue anyways? (y/n) ") - print() - if progress.lower() == "y": - print(f"Proceeding on {root_dir} ({detected})") - return True - print(f"Skipping install") - return False - - print(f"Verified version ({detected})") - return True - - -def update_backups(root_type: str) -> None: - # keep a backup of the backups (rename latest root to timestamp) - old_name: str = advanced_join([BACKUPS_DIR, root_type]) - if os.path.exists(old_name): - timestamp: str = datetime.now().strftime("%m.%d.%Y_%H.%M.%S") - backup_path: str = os.path.normpath(advanced_join([BACKUPS_DIR, root_type])) - new_name: str = f"{backup_path}.{timestamp}" - os.rename(old_name, new_name) - # new backups (latest) - os.makedirs(old_name, exist_ok=True) - - -def copy_file(src: str, dest: str, verbose: Optional[bool] = False) -> None: - if os.path.exists(dest): # overwriting an existing file - if os.path.isfile(dest): - final_file: str = dest # final output - else: - final_file: str = os.path.join( - dest, get_leaf_from_path(src) - ) # final output - else: - advanced_create(dest) - assert os.path.exists(dest) - copy_file(src, dest, verbose) # now the dest should exist - return - - assert os.path.exists(dest) - if os.path.exists(final_file): - backup_path = advanced_join([BACKUPS_DIR, dest]) - if os.path.isdir(dest): - # create the backup directory if it doesn't exist - os.makedirs(backup_path, exist_ok=True) - else: - # create the directory to the destination FILE if it doesn't exist - path_to_backup_file: str = os.path.split(backup_path)[0] - try: - os.makedirs(path_to_backup_file, exist_ok=True) - except NotADirectoryError: - # for some reason Windows requires that making directories - # must include the path separator at the end else its a "file" - # and raises NotADirectoryErr, so I must append os.sep >:( - os.makedirs(path_to_backup_file + os.sep, exist_ok=True) - shutil.copy(final_file, backup_path) - shutil.copy(src, dest) - print_cp(src, final_file, verbose) - # ensure the actual files/dirs exist! - assert os.path.exists(src) - assert os.path.exists(final_file) - if advanced_is_dir(dest): - assert get_leaf_from_path(src) == get_leaf_from_path(final_file) - - -def copy_dir(src: str, dest: str, verbose: Optional[bool] = True) -> None: - raise NotImplementedError("Not using copy_dir, instead copying files recursively") - import distutils.dir_util - - print_cp(src, dest) - # shutil.copytree(src, dest) # raises exception if dest exists! - if os.path.exists(dest): - backup_path = advanced_join([BACKUPS_DIR, dest]) - distutils.dir_util.copy_tree(dest, backup_path) # always make a backup - distutils.dir_util.copy_tree(src, dest) # overwrites instead of exception! - for f in os.listdir(src): - print_cp(os.path.join(src, f), os.path.join(dest, f), verbose) - - -def make_platform_indep(src: str, dest: str) -> Tuple[str, str]: - # convert the src/dest to platform-independent paths (not just '/') - if False: - src: str = os.path.join(*src.split("/")) - if os.path.isabs(dest): # absolute path - dest: str = os.path.join("/", *dest.split("/")) - else: - dest: str = os.path.join(*dest.split("/")) - # TODO: check that this works on Windows, MacOS, Linux - _src = os.path.abspath(src) - _dest = os.path.abspath(dest) - if advanced_is_dir(src): - _src += os.sep - if advanced_is_dir(dest): - _dest += os.sep - return _src, _dest - - -def advanced_is_dir(name: str) -> bool: - # assuming something like "A" is a file, "A/" is a directory - # how to decide what kind of file (file, dir) dest is? - if os.path.exists(name) and os.path.isdir(name): - # easy case, this alr exists - return True - # if not, we'll need to just analyze the string itself - # check if the last character is the os separator - # https://docs.python.org/3/library/os.html#os.sep - return name[-1] == os.sep or name[-1] == "/" # check OS sep or linux sep - - -def advanced_create( - name: str, contents: str = "", hard_replace: Optional[bool] = False -) -> None: - # create a file or directory (if advanced_is_dir(name) == True) with requested content - # hard_replace always deletes existing files in favour of new one - norm_name: str = os.path.normpath(name) - if os.path.exists(norm_name) and ( - advanced_is_dir(norm_name) != advanced_is_dir(norm_name) - ): - # if an existing file has been found that conflicts - if hard_replace: # always replace - advanced_rm(os.path.normpath(name)) - else: - remove = input(f"Found existing {name}, should delete? (y/n) ") - if remove.lower() == "y": - os.remove(os.path.normpath(name)) - else: - # path already exists - return - if advanced_is_dir(name): - # already exists a file with this name - os.makedirs(name, exist_ok=True) - else: - path, filename = os.path.split(name) - if len(path) > 0: - os.makedirs(path, exist_ok=True) - open(name, "a").close() - with open(name, "w") as f: - f.write(contents) - - assert os.path.exists(name) - - -def advanced_cp(src: str, dest: str, verbose: Optional[bool] = False) -> None: - leaf = get_leaf_from_path(src) - src, dest = make_platform_indep(src, dest) - if os.path.isfile(src): - copy_file(src, dest, verbose=verbose) - elif advanced_is_dir(src): - if os.path.isfile(dest): - raise Exception("Cannot copy a directory to a file") - # copy_dir(src, os.path.join(dest, leaf), verbose=verbose) - # recursively copy files as a * glob - advanced_cp(os.path.join(src, "*"), advanced_join([dest, leaf]), verbose) - else: - try: - files = glob.glob(src) - for f in files: - if advanced_is_dir(f): - f += os.sep - advanced_cp(f, dest, verbose=verbose) - except Exception as e: - print(f"Unknown filetype: {src}") - raise e - # raise NotImplementedError - - -def advanced_rm(path: str) -> None: - if os.path.isfile(path): - os.remove(path) - elif os.path.isdir(path): - shutil.rmtree(path) - else: - try: - files = glob.glob(path) - for f in files: - advanced_rm(f) - except Exception as e: - print(f"Unknown filetype: {path}") - raise e - # raise NotImplementedError - - -def advanced_join(paths: List[str]) -> str: - # effectively same as os.path.join but does not truncate - # if an entry in path is an absolute path - assert len(paths) > 0 - path_names: List[str] = [] - for p in paths: - # since these were initially written for linux which uses - # forward slash ('/') as the path separator - path_without_sep: List[str] = p.split("/") - path_sep: str = os.path.join(*path_without_sep) - drive, path_sep = os.path.splitdrive(path_sep) - # only include path with separators, strip first sep to not truncate - path_names.append(path_sep.strip(os.sep)) - if os.path.isabs(paths[0]): # absolute path - path_names = [os.sep] + path_names # add absolute path marker - joined_str: str = os.path.join(*path_names) - if advanced_is_dir(paths[-1]): - joined_str += os.sep # keep the fact that this is a directory - return joined_str - - -def generate_correspondences(csv_file: str) -> Dict[str, str]: - assert os.path.exists(csv_file) - corr: Dict[str, str] = {} - with open(csv_file, "r") as f: - for row in csv.reader(f, delimiter=","): - assert len(row) == 2 - DReyeVR_path, CARLA_path = row - # print(" --> ".join(row)) - corr[DReyeVR_path] = CARLA_path - return corr - - -def expand_correspondences_glob(corr: Dict[str, str]) -> Dict[str, str]: - # expands regex in LHS (DReyeVR paths) to absolute files - # NOTE: this only supports expanding globs on the LHS (DReyeVR paths) - expanded = {} - for k in corr.keys(): - for expanded_k in glob.glob(k): - expanded[expanded_k] = corr[k] - return expanded - - -def get_all_files(corr: Dict[str, str]) -> Dict[str, str]: - files_map = {} - for k in corr.keys(): - if advanced_is_dir(k): - only_files = [] - for root, _, files in os.walk(k): - for f in files: - filepath = advanced_join([root, f]) - if os.path.isfile(filepath): - only_files.append(filepath) - assert os.path.exists(filepath) - - files_map[k] = list(sorted(only_files)) - else: - files_map[k] = [k] # already a file - for group in files_map.values(): - for f in group: - assert not advanced_is_dir(f) - return files_map - - -def check_env_var(user_in: str, env_var: str) -> Optional[str]: - if user_in is not None: - # just use the path provided to us - return user_in - - if env_var not in os.environ or len(os.environ[env_var]) == 0: - print(f"Unable to find installation or user input for {env_var}") - return None - - alternatie_path = os.environ[env_var] - print( - f'No user input, defaulting to environment variable: "{env_var}" == "{alternatie_path}"' - ) - use_alt_path = input(f"Should proceed on {alternatie_path}? (y/n) ") - if use_alt_path.lower() == "y": - return alternatie_path - return None - - -def default_args( - DOC_STRING: str = "", with_sr: bool = True, other_args: List[Tuple[Any]] = [] -) -> dict: - print(DOC_STRING) - print() - argparser = argparse.ArgumentParser(description=DOC_STRING) - argparser.add_argument( - "--carla", - metavar="C", - default=None, - type=str, - nargs="?", # 0 or 1 argument - help="Path for Carla root (can be relative or absolute)", - ) - argparser.add_argument( - "--scenario-runner", - metavar="SR", - default=None, - type=str, - nargs="?", # 0 or 1 argument - help="Path for Scenario Runner root (can be relative or absolute)", - ) - argparser.add_argument( - "--env", - action="store_true", - help="Whether or not to check the environment variables", - ) - for args in other_args: - name: str = args.pop("name") - argparser.add_argument(name, **args) - args = argparser.parse_args() - if args.env or (args.carla is None and args.scenario_runner is None): - args.carla = check_env_var(args.carla, "CARLA_ROOT") - print() - if with_sr: - args.scenario_runner = check_env_var( - args.scenario_runner, "SCENARIO_RUNNER_ROOT" - ) - - return args +import argparse +import csv +import glob +import os +import shutil +import subprocess +from datetime import datetime +from typing import Any, Dict, List, Optional, Tuple + +# current version of CARLA supported (git tag) +SUPPORTED_CARLA: str = "0.9.13" +SUPPORTED_SCENARIO_RUNNER: str = "v0.9.13" + +# backup directory for overwritten files +BACKUPS_DIR: str = "Backups" +os.makedirs(BACKUPS_DIR, exist_ok=True) + +CARLA_PATH_FILE: str = os.path.join("Scripts", "Paths", "DReyeVR.csv") +SR_PATH_FILE: str = os.path.join("Scripts", "Paths", "ScenarioRunner.csv") + + +def print_line() -> None: + print("*" * 50) + + +def print_subtitle(title: str): + print() + print("*" * 25 + title + "*" * 25) + + +def print_cp(src: str, dest: str, verbose: Optional[bool] = True) -> None: + if verbose: + print(f"{src} -> {dest}") + + +def print_status(b: bool) -> str: + return "OK" if b else "FAILED" + + +def verify_installation(root_dir: str, check_files: List[str] = []) -> None: + assert os.path.exists(root_dir) + # check that all these files are in root_dir + for f in check_files: + if not os.path.exists(os.path.join(root_dir, f)): + raise Exception(f'Expected file "{f}" not present in "{root_dir}"') + print(f"Verified installation ({root_dir})") + + +def get_leaf_from_path(path: str) -> str: + if advanced_is_dir(path): + # include the path separator to ensure it is still recognized as a directory + return os.path.basename(os.path.normpath(path)) + os.sep + return os.path.basename(path) + + +def get_git_tag(root_dir: str) -> str: + # TODO: make this more robust + current = os.getcwd() + os.chdir(root_dir) + # this command works well on vanilla repos + git_tag_cmd: str = "git describe --tags --exact-match" + # this command works well when on repo forks + git_tag_cmd_fork: str = "git symbolic-ref -q --short HEAD" + try: + detected: bytes = subprocess.check_output(git_tag_cmd.split(" ")) + except Exception as e: + try: + print("...Attempting backup git tag cmd...") + detected_backup: bytes = subprocess.check_output( + git_tag_cmd_fork.split(" ") + ) + detected = detected_backup + except Exception as e2: + print(f'First try: {type(e).__name__}: "{e}"') + print(f'Second try: {type(e2).__name__}: "{e2}"') + detected: bytes = b"Unknown" + os.chdir(current) + return detected.decode("ascii").strip() + + +def verify_version(root_dir: str, expected: str) -> bool: + assert os.path.exists(root_dir) + detected = get_git_tag(root_dir) + if detected != expected: + print(f"Only {expected} version is supported! Detected version: {detected}") + progress = input("Do you want to continue anyways? (y/n) ") + print() + if progress.lower() == "y": + print(f"Proceeding on {root_dir} ({detected})") + return True + print(f"Skipping install") + return False + + print(f"Verified version ({detected})") + return True + + +def update_backups(root_type: str) -> None: + # keep a backup of the backups (rename latest root to timestamp) + old_name: str = advanced_join([BACKUPS_DIR, root_type]) + if os.path.exists(old_name): + timestamp: str = datetime.now().strftime("%m.%d.%Y_%H.%M.%S") + backup_path: str = os.path.normpath(advanced_join([BACKUPS_DIR, root_type])) + new_name: str = f"{backup_path}.{timestamp}" + os.rename(old_name, new_name) + # new backups (latest) + os.makedirs(old_name, exist_ok=True) + + +def copy_file(src: str, dest: str, verbose: Optional[bool] = False) -> None: + if os.path.exists(dest): # overwriting an existing file + if os.path.isfile(dest): + final_file: str = dest # final output + else: + final_file: str = os.path.join( + dest, get_leaf_from_path(src) + ) # final output + else: + advanced_create(dest) + assert os.path.exists(dest) + copy_file(src, dest, verbose) # now the dest should exist + return + + assert os.path.exists(dest) + if os.path.exists(final_file): + backup_path = advanced_join([BACKUPS_DIR, dest]) + if os.path.isdir(dest): + # create the backup directory if it doesn't exist + os.makedirs(backup_path, exist_ok=True) + else: + # create the directory to the destination FILE if it doesn't exist + path_to_backup_file: str = os.path.split(backup_path)[0] + try: + os.makedirs(path_to_backup_file, exist_ok=True) + except NotADirectoryError: + # for some reason Windows requires that making directories + # must include the path separator at the end else its a "file" + # and raises NotADirectoryErr, so I must append os.sep >:( + os.makedirs(path_to_backup_file + os.sep, exist_ok=True) + shutil.copy(final_file, backup_path) + shutil.copy(src, dest) + print_cp(src, final_file, verbose) + # ensure the actual files/dirs exist! + assert os.path.exists(src) + assert os.path.exists(final_file) + if advanced_is_dir(dest): + assert get_leaf_from_path(src) == get_leaf_from_path(final_file) + + +def copy_dir(src: str, dest: str, verbose: Optional[bool] = True) -> None: + raise NotImplementedError("Not using copy_dir, instead copying files recursively") + import distutils.dir_util + + print_cp(src, dest) + # shutil.copytree(src, dest) # raises exception if dest exists! + if os.path.exists(dest): + backup_path = advanced_join([BACKUPS_DIR, dest]) + distutils.dir_util.copy_tree(dest, backup_path) # always make a backup + distutils.dir_util.copy_tree(src, dest) # overwrites instead of exception! + for f in os.listdir(src): + print_cp(os.path.join(src, f), os.path.join(dest, f), verbose) + + +def make_platform_indep(src: str, dest: str) -> Tuple[str, str]: + # convert the src/dest to platform-independent paths (not just '/') + if False: + src: str = os.path.join(*src.split("/")) + if os.path.isabs(dest): # absolute path + dest: str = os.path.join("/", *dest.split("/")) + else: + dest: str = os.path.join(*dest.split("/")) + # TODO: check that this works on Windows, MacOS, Linux + _src = os.path.abspath(src) + _dest = os.path.abspath(dest) + if advanced_is_dir(src): + _src += os.sep + if advanced_is_dir(dest): + _dest += os.sep + return _src, _dest + + +def advanced_is_dir(name: str) -> bool: + # assuming something like "A" is a file, "A/" is a directory + # how to decide what kind of file (file, dir) dest is? + if os.path.exists(name) and os.path.isdir(name): + # easy case, this alr exists + return True + # if not, we'll need to just analyze the string itself + # check if the last character is the os separator + # https://docs.python.org/3/library/os.html#os.sep + return name[-1] == os.sep or name[-1] == "/" # check OS sep or linux sep + + +def advanced_create( + name: str, contents: str = "", hard_replace: Optional[bool] = False +) -> None: + # create a file or directory (if advanced_is_dir(name) == True) with requested content + # hard_replace always deletes existing files in favour of new one + norm_name: str = os.path.normpath(name) + if os.path.exists(norm_name) and ( + advanced_is_dir(norm_name) != advanced_is_dir(norm_name) + ): + # if an existing file has been found that conflicts + if hard_replace: # always replace + advanced_rm(os.path.normpath(name)) + else: + remove = input(f"Found existing {name}, should delete? (y/n) ") + if remove.lower() == "y": + os.remove(os.path.normpath(name)) + else: + # path already exists + return + if advanced_is_dir(name): + # already exists a file with this name + os.makedirs(name, exist_ok=True) + else: + path, filename = os.path.split(name) + if len(path) > 0: + os.makedirs(path, exist_ok=True) + open(name, "a").close() + with open(name, "w") as f: + f.write(contents) + + assert os.path.exists(name) + + +def advanced_cp(src: str, dest: str, verbose: Optional[bool] = False) -> None: + leaf = get_leaf_from_path(src) + src, dest = make_platform_indep(src, dest) + if os.path.isfile(src): + copy_file(src, dest, verbose=verbose) + elif advanced_is_dir(src): + if os.path.isfile(dest): + raise Exception("Cannot copy a directory to a file") + # copy_dir(src, os.path.join(dest, leaf), verbose=verbose) + # recursively copy files as a * glob + advanced_cp(os.path.join(src, "*"), advanced_join([dest, leaf]), verbose) + else: + try: + files = glob.glob(src) + for f in files: + if advanced_is_dir(f): + f += os.sep + advanced_cp(f, dest, verbose=verbose) + except Exception as e: + print(f"Unknown filetype: {src}") + raise e + # raise NotImplementedError + + +def advanced_rm(path: str) -> None: + if os.path.isfile(path): + os.remove(path) + elif os.path.isdir(path): + shutil.rmtree(path) + else: + try: + files = glob.glob(path) + for f in files: + advanced_rm(f) + except Exception as e: + print(f"Unknown filetype: {path}") + raise e + # raise NotImplementedError + + +def advanced_join(paths: List[str]) -> str: + # effectively same as os.path.join but does not truncate + # if an entry in path is an absolute path + assert len(paths) > 0 + path_names: List[str] = [] + for p in paths: + # since these were initially written for linux which uses + # forward slash ('/') as the path separator + path_without_sep: List[str] = p.split("/") + path_sep: str = os.path.join(*path_without_sep) + drive, path_sep = os.path.splitdrive(path_sep) + # only include path with separators, strip first sep to not truncate + path_names.append(path_sep.strip(os.sep)) + if os.path.isabs(paths[0]): # absolute path + path_names = [os.sep] + path_names # add absolute path marker + joined_str: str = os.path.join(*path_names) + if advanced_is_dir(paths[-1]): + joined_str += os.sep # keep the fact that this is a directory + return joined_str + + +def generate_correspondences(csv_file: str) -> Dict[str, str]: + assert os.path.exists(csv_file) + corr: Dict[str, str] = {} + with open(csv_file, "r") as f: + for row in csv.reader(f, delimiter=","): + assert len(row) == 2 + DReyeVR_path, CARLA_path = row + # print(" --> ".join(row)) + corr[DReyeVR_path] = CARLA_path + return corr + + +def expand_correspondences_glob(corr: Dict[str, str]) -> Dict[str, str]: + # expands regex in LHS (DReyeVR paths) to absolute files + # NOTE: this only supports expanding globs on the LHS (DReyeVR paths) + expanded = {} + for k in corr.keys(): + for expanded_k in glob.glob(k): + expanded[expanded_k] = corr[k] + return expanded + + +def get_all_files(corr: Dict[str, str]) -> Dict[str, str]: + files_map = {} + for k in corr.keys(): + if advanced_is_dir(k): + only_files = [] + for root, _, files in os.walk(k): + for f in files: + filepath = advanced_join([root, f]) + if os.path.isfile(filepath): + only_files.append(filepath) + assert os.path.exists(filepath) + + files_map[k] = list(sorted(only_files)) + else: + files_map[k] = [k] # already a file + for group in files_map.values(): + for f in group: + assert not advanced_is_dir(f) + return files_map + + +def check_env_var(user_in: str, env_var: str) -> Optional[str]: + if user_in is not None: + # just use the path provided to us + return user_in + + if env_var not in os.environ or len(os.environ[env_var]) == 0: + print(f"Unable to find installation or user input for {env_var}") + return None + + alternatie_path = os.environ[env_var] + print( + f'No user input, defaulting to environment variable: "{env_var}" == "{alternatie_path}"' + ) + use_alt_path = input(f"Should proceed on {alternatie_path}? (y/n) ") + if use_alt_path.lower() == "y": + return alternatie_path + return None + + +def default_args( + DOC_STRING: str = "", with_sr: bool = True, other_args: List[Tuple[Any]] = [] +) -> dict: + print(DOC_STRING) + print() + argparser = argparse.ArgumentParser(description=DOC_STRING) + argparser.add_argument( + "--carla", + metavar="C", + default=None, + type=str, + nargs="?", # 0 or 1 argument + help="Path for Carla root (can be relative or absolute)", + ) + argparser.add_argument( + "--scenario-runner", + metavar="SR", + default=None, + type=str, + nargs="?", # 0 or 1 argument + help="Path for Scenario Runner root (can be relative or absolute)", + ) + argparser.add_argument( + "--env", + action="store_true", + help="Whether or not to check the environment variables", + ) + for args in other_args: + name: str = args.pop("name") + argparser.add_argument(name, **args) + args = argparser.parse_args() + if args.env or (args.carla is None and args.scenario_runner is None): + args.carla = check_env_var(args.carla, "CARLA_ROOT") + print() + if with_sr: + args.scenario_runner = check_env_var( + args.scenario_runner, "SCENARIO_RUNNER_ROOT" + ) + + return args diff --git a/Shaders/README.md b/Shaders/README.md index 2e60fe3..88d4641 100644 --- a/Shaders/README.md +++ b/Shaders/README.md @@ -1,16 +1,16 @@ -# UE4 Scene Capture Shaders - -For fancy sensors such as the [Semantic Segmentation camera](https://carla.readthedocs.io/en/0.9.13/ref_sensors/#semantic-segmentation-camera), Carla uses [post-processing materials](https://github.com/carla-simulator/carla/tree/master/Unreal/CarlaUE4/Plugins/Carla/Content/PostProcessingMaterials) to act as shaders and produce high-quality results with minimal cost to performance. - -An excellent tutorial by UE4 on the subject can be found [here (youtube)](https://www.youtube.com/watch?v=PiQ_JLJKi0M) - -Without getting too much into the details, the post-processing effect materials held here serve as shaders that can take information such as custom stencil/depth buffers and produce pixel-wise computations very efficiently. - -| Description | Demo | -| --- | --- | -| For example, Carla's `GTMaterial.uasset` shader is used to encode custom stencil information into the **red** channel of the output images, producing an image such as this (colours exaggerated for viewing). Then in the PythonAPI client, the LibCarla definitions for [City Palettes](https://github.com/carla-simulator/carla/blob/master/LibCarla/source/carla/image/CityScapesPalette.h) is applied to convert the image to user-desired colours by index. | ![red_encode](../Docs/Figures/Shaders/red_encode.jpg) | -| By contrast, our `DReyeVR_SemanticSegmentation` shader builds on the fundamentals of the Carla GTMaterial but directly indexes the array of colours in the shader itself, so you can effortlessly obtain semantic colour information straight into the first-person-camera. | ![rgb_encode](../Docs/Figures/Shaders/semantic_seg.jpg) | - -We are interested in including the various shader outputs in our replay functionality. - +# UE4 Scene Capture Shaders + +For fancy sensors such as the [Semantic Segmentation camera](https://carla.readthedocs.io/en/0.9.13/ref_sensors/#semantic-segmentation-camera), Carla uses [post-processing materials](https://github.com/carla-simulator/carla/tree/master/Unreal/CarlaUE4/Plugins/Carla/Content/PostProcessingMaterials) to act as shaders and produce high-quality results with minimal cost to performance. + +An excellent tutorial by UE4 on the subject can be found [here (youtube)](https://www.youtube.com/watch?v=PiQ_JLJKi0M) + +Without getting too much into the details, the post-processing effect materials held here serve as shaders that can take information such as custom stencil/depth buffers and produce pixel-wise computations very efficiently. + +| Description | Demo | +| --- | --- | +| For example, Carla's `GTMaterial.uasset` shader is used to encode custom stencil information into the **red** channel of the output images, producing an image such as this (colours exaggerated for viewing). Then in the PythonAPI client, the LibCarla definitions for [City Palettes](https://github.com/carla-simulator/carla/blob/master/LibCarla/source/carla/image/CityScapesPalette.h) is applied to convert the image to user-desired colours by index. | ![red_encode](../Docs/Figures/Shaders/red_encode.jpg) | +| By contrast, our `DReyeVR_SemanticSegmentation` shader builds on the fundamentals of the Carla GTMaterial but directly indexes the array of colours in the shader itself, so you can effortlessly obtain semantic colour information straight into the first-person-camera. | ![rgb_encode](../Docs/Figures/Shaders/semantic_seg.jpg) | + +We are interested in including the various shader outputs in our replay functionality. + To demo the shaders we include in DReyeVR in real time, press `.` (period) for the next and `,` (comma) for the previous shaders. \ No newline at end of file diff --git a/Tools/Diagnostics/README.md b/Tools/Diagnostics/README.md index 08612f7..e3997be 100644 --- a/Tools/Diagnostics/README.md +++ b/Tools/Diagnostics/README.md @@ -1,10 +1,10 @@ -# Diagnostics - -## Note: Mostly for development/WIP - -This section highlights debug tools used to ensure all CARLA/DReyeVR performance was going as expected. As a general overview: -- [collectl/](collectl) uses [`collectl`](http://collectl.sourceforge.net/) on Linux (Or WSL) to gather and query system information so we can see how the computer was doing during the running of CARLA (kinda like a terminal task-manager/msi-afterburner) - - Generally, you'll need to first setup collectl, and thats what the setup script does for you -- [python/](python) contains a bunch of python scripts for handling the `collectl` data but also some simpler ones to simply measure and record carla stats (such as FPS), see `stat_carla.py` - +# Diagnostics + +## Note: Mostly for development/WIP + +This section highlights debug tools used to ensure all CARLA/DReyeVR performance was going as expected. As a general overview: +- [collectl/](collectl) uses [`collectl`](http://collectl.sourceforge.net/) on Linux (Or WSL) to gather and query system information so we can see how the computer was doing during the running of CARLA (kinda like a terminal task-manager/msi-afterburner) + - Generally, you'll need to first setup collectl, and thats what the setup script does for you +- [python/](python) contains a bunch of python scripts for handling the `collectl` data but also some simpler ones to simply measure and record carla stats (such as FPS), see `stat_carla.py` + WARNING: Not all of these scripts have been tested on the latest version of DReyeVR/Carla. \ No newline at end of file diff --git a/Tools/Diagnostics/collectl/nvidia.ph b/Tools/Diagnostics/collectl/nvidia.ph index e5e5738..3062e15 100644 --- a/Tools/Diagnostics/collectl/nvidia.ph +++ b/Tools/Diagnostics/collectl/nvidia.ph @@ -1,454 +1,454 @@ -# copyright, 2003-2009 Hewlett-Packard Development Company, LP - -# NOTE - by default, this module only collects data once a minute, which you can change -# with the i=x parameter (eg --import nvidia,i=x). Regardless of the collection interval, -# date will be reported every interval in brief/verbose formats to provide a consisent -# set of output each monitoring cycle. - -# n v d i a m o n i t o r i n g - -use strict; - -# Allow reference to collectl variables, but be CAREFUL as these should be treated as readonly -our ($Version, $miniFiller, $rate, $SEP, $datetime, $miniInstances, $interval, $showColFlag, $playback); - -my ($nvidiaInterval, $nvidiaImportCount, $nvidiaSampleCounter, $nvidiaAllFlag); -my ($nvidiaOpts, $nvidiaNumGpus,$nvidiaProdName, $nvidiaDriverVer); -my (@nvidiaTemp, @nvidiaFan, @nvidiaGpuUtil, @nvidiaMemUtil); -my ($nvidiaTempTot, $nvidiaFanTot, $nvidiaGpuUtilTot, $nvidiaMemUtilTot); -my ($nvidiaTempTOT, $nvidiaFanTOT, $nvidiaGpuUtilTOT, $nvidiaMemUtilTOT); - -my $nvidiaGpuFirst; -my $nvidiaGpuNum=-1; -my $nvidiaSection=0; -my $nvidiaLastValFlag; -my $nvidiaCommand='/usr/bin/nvidia-smi'; -my $nvidiaFullCmd="$nvidiaCommand -q -a"; - -sub nvidiaInit -{ - my $impOptsref=shift; - my $impKeyref= shift; - - # If we ever run with a ':' in the interval, we need to be sure we're - # only looking at the main one. - my $nvidiaInterval1=(split(/:/, $interval))[0]; - - # For now, only options are a, 'i=, d, s and sd - $nvidiaOpts=''; - $nvidiaInterval=60; - if (defined($$impOptsref)) - { - foreach my $option (split(/,/,$$impOptsref)) - { - my ($name, $value)=split(/=/, $option); - error("invalid misc option: '$name'") if $name ne 'a' && $name ne 'i' && $name!~/^[ds]+$/; - - $nvidiaInterval=$value if $name eq 'i'; - $nvidiaAllFlag=1 if $name eq 'a'; - $nvidiaOpts=$name if $name=~/^[ds]+$/; - } - } - - # Special case: if --showcowheaders, we're called with -i0 and need to reset so the - # division below doesn't bomb out. - $nvidiaInterval1=1 if $showColFlag; - $nvidiaImportCount=int($nvidiaInterval/$nvidiaInterval1); - error("nvidia interval option not a multiple of '$nvidiaInterval1' seconds") - if $nvidiaInterval1*$nvidiaImportCount != $nvidiaInterval; - - $nvidiaOpts='s' if $nvidiaOpts eq ''; - $$impOptsref=$nvidiaOpts; - $$impKeyref='nvid'; - - # since totals only initialized in 'analyze' routine, do it here too in case no data - # in raw file during playback. - $nvidiaTempTot=$nvidiaFanTot=$nvidiaGpuUtilTot=$nvidiaMemUtilTot=0; - - # R u n C o m m a n d I n R e a l t i m e M o d e - - # when running in collection mode only, we need to make sure we're nvidia enabled - if ($playback eq '') - { - if ($playback eq '' && !-e $nvidiaCommand || $Version lt '3.5.0-3') - { - my $message="cannot find '$nvidiaCommand'" if !-e $nvidiaCommand; - $message="this nvidia.ph requires at least collectl V3.5.1" if $Version lt '3.5.1'; - pushmsg('W', "$message. GPU monitoring disabled"); - $$impOptsref=$$impKeyref=''; - return(-1); - } - - # Now run command once to get a get a few constants for header AND number of GPUs - # NOTE: if it returns its names its probably a help message and the desired commands - # are not suppoted, hence not a GPU we can monitor. - my $output=`$nvidiaFullCmd`; - if ($output=~/nvidia-smi/) - { - pushmsg('W', "nvidia GPU doesn' support '$nvidiaFullCmd'. GPU monitoring disabled"); - $$impOptsref=$$impKeyref=''; - return(-1); - } - - $nvidiaNumGpus=0; - foreach my $line ((split(/\n/, $output))) - { - chomp $line; - $nvidiaDriverVer=$1 if $line=~/Driver Version\s+:\s+(.*)/; - - if ($line=~/Product Name\s+:\s+(.*)/) - { - $nvidiaProdName=$1; - $nvidiaNumGpus++; - } - } - $nvidiaSampleCounter=-1; - } - - return(1); -} - -# Nothing to add to header -sub nvidiaUpdateHeader -{ - my $lineref=shift; - $$lineref.="# GPU: Type: nvidia $nvidiaProdName Version: $nvidiaDriverVer NumGPU: $nvidiaNumGpus\n"; -} - -sub nvidiaGetHeader -{ - my $headerref=shift; - - # Make sure playback file contains nvidia gpu data and if not, just set number - # of gpus to 1 to make display logic work because maybe this is intended. - if ($$headerref!~/GPU:(.*)Version/ || $1!~/nvidia/) - { - logmsg('W', "playback file does not contain nvidia data"); - $nvidiaNumGpus=1; - } - else - { - # Now parse header for real - $$headerref=~/GPU:.*Type: (.*).*Version: (.*)\s+NumGPU: (\d+)/; - $nvidiaDriverVer=$2; - $nvidiaNumGpus=$3; - } -} - -sub nvidiaGetData -{ - # only read counters when OUR interval directs us to. - return if ($nvidiaSampleCounter++ % $nvidiaImportCount)!=0; - - getExec(0, $nvidiaFullCmd, 'nvid'); -} - -sub nvidiaInitInterval -{ - # all initialization totals MUST be done in Analyze() because this not called - # each pass when writing to a raw file. -} - -sub nvidiaAnalyze -{ - my $type= shift; - my $dataref=shift; - - # we need to know when last counter seen AND we can't use InitInterval() - $nvidiaLastValFlag=0; - - # This is a mess! Difference drivers generate different output - if ($nvidiaDriverVer lt '270.41.19') # until I know better - { - # GPU number always preceeds data - $nvidiaGpuNum=$1 if $$dataref=~/^GPU (\d+)/; - - my $i=$nvidiaGpuNum; - $nvidiaTemp[$i]=$1 if $$dataref=~/^Temp.*?(\d+)/; - $nvidiaFan[$i]=$1 if $$dataref=~/^Fan.*?(\d+)/; - $nvidiaGpuUtil[$i]=$1 if $$dataref=~/^GPU.*: (\d+)/; - - # This indicates the end of a set of data. If more data elements - # are ever added, we'll need a different 'last' variable test - if ($$dataref=~/^Memory.*?(\d+)/) - { - $nvidiaMemUtil[$i]=$1; - $nvidiaLastValFlag=1; - } - } - elsif ($nvidiaDriverVer ge '270.41.19') - { - # for this driver version this isn't a number but a string so just bump index - # and make a note of it so we recognize the start of a new interval - if ($$dataref=~/^GPU (.*)/ && $$dataref!~/UUID/) - { - $nvidiaGpuFirst=$1 if !defined($nvidiaGpuFirst); - $nvidiaGpuNum=-1 if $1 eq $nvidiaGpuFirst; - $nvidiaGpuNum++; - } - - $nvidiaSection=10 if $$dataref=~/^PCI/; - $nvidiaSection=20 if $$dataref=~/^Fan/; - $nvidiaSection=30 if $$dataref=~/^Memory Usage/; - $nvidiaSection=40 if $$dataref=~/^Utilization/; - $nvidiaSection=50 if $$dataref=~/^Ecc Mode/; - $nvidiaSection=60 if $$dataref=~/^ECC Errors/; - $nvidiaSection=70 if $$dataref=~/^Temperature/; - $nvidiaSection=80 if $$dataref=~/^Power Readings/; - $nvidiaSection=90 if $$dataref=~/^Clocks/; - - # for now we only care about Fan, Utiliztion and Temp - return if $nvidiaSection!=20 && $nvidiaSection!=40 && $nvidiaSection!=70; - - my $i=$nvidiaGpuNum; - $nvidiaFan[$i]=$1 if $nvidiaSection==20 && $$dataref=~/^Fan.*?(\d+)/; - $nvidiaGpuUtil[$i]=$1 if $nvidiaSection==40 && $$dataref=~/^Gpu.*: (\d+)/; - $nvidiaMemUtil[$i]=$1 if $nvidiaSection==40 && $$dataref=~/^Memory.*?(\d+)/; - - if ($nvidiaSection==70 && $$dataref=~/^Gpu.*?(\d+)/) - { - $nvidiaTemp[$i]=$1; - $nvidiaLastValFlag=1; - } - } - - # We can only do initialization and update totals when we see last data element (actually - # we could have updated the totals as each element seen but this is a little easier. - if ($nvidiaLastValFlag) - { - my $i=$nvidiaGpuNum; - - # These only done once/interval, not per GPU - $nvidiaTempTot=$nvidiaFanTot=$nvidiaGpuUtilTot=$nvidiaMemUtilTot=0 if $i==0; - - $nvidiaTempTot+= $nvidiaTemp[$i]; - $nvidiaFanTot+= $nvidiaFan[$i]; - # $nvidiaGpuUtilTot+=$nvidiaGpuUtil[$i]; - # $nvidiaMemUtilTot+=$nvidiaMemUtil[$i]; - } -} - -sub nvidiaPrintBrief -{ - my $type=shift; - my $lineref=shift; - - # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization - $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; - $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; - - if ($type==1) # header line 1 - { - $$lineref.="<------nvidia------->"; - } - elsif ($type==2) # header line 2 - { - $$lineref.=" Temp Fan% Gpu% Mem% "; - } - elsif ($type==3) # data - { - my $num=$nvidiaNumGpus; - $$lineref.=sprintf(" %4d %4d %4d %4d ", - $nvidiaTempTot/$num, $nvidiaFanTot/$num, $nvidiaGpuUtilTot/$num, $nvidiaMemUtilTot/$num); - } - elsif ($type==4) # reset 'total' counters - { - $nvidiaTempTOT=$nvidiaFanTOT=$nvidiaGpuUtilTOT=$nvidiaMemUtilTOT=0; - } - elsif ($type==5) # increment 'total' counters - { - $nvidiaTempTOT+= $nvidiaTempTot; - $nvidiaFanTOT+= $nvidiaFanTot; - $nvidiaGpuUtilTOT+=$nvidiaGpuUtilTot; - $nvidiaMemUtilTOT+=$nvidiaMemUtilTot; - } - elsif ($type==6) # print 'total' counters - { - my $num=$nvidiaNumGpus; - printf(" %4d %4d %4d %4d ", - int($nvidiaTempTOT/$num/$miniInstances), int($nvidiaFanTOT/$num/$miniInstances), - int($nvidiaGpuUtilTOT/$num/$miniInstances), int($nvidiaMemUtilTOT/$num/$miniInstances)); - } -} - -sub nvidiaPrintVerbose -{ - my $printHeader=shift; - my $homeFlag= shift; - my $lineref= shift; - - # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization - $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; - $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; - - if ($nvidiaOpts=~/s/) - { - my $line=''; - if ($printHeader) - { - $line.="\n" if !$homeFlag; - $line.="# GPU STATISTICS\n"; - $line.="#$miniFiller Temp Fan% GPU% Mem%\n"; - } - - my $num=$nvidiaNumGpus; - $$lineref=$line; - $$lineref.=sprintf("$datetime %3d %3d %3d %3d\n", - int($nvidiaTempTot/$num), int($nvidiaFanTot/$num), - int($nvidiaGpuUtilTot/$num), int($nvidiaMemUtilTot/$num)); - } - - if ($nvidiaOpts=~/d/) - { - my $line=''; - if ($printHeader) - { - $line.="\n" if !$homeFlag; - $line.="# GPU DETAIL\n"; - $line.="#$miniFiller Num Temp Fan% GPU% Mem%\n"; - } - - $$lineref=$line; - for (my $i=0; $i<$nvidiaNumGpus; $i++) - { - $$lineref.=sprintf("$datetime %3d %3d %3d %3d %3d\n", - $i, $nvidiaTemp[$i], $nvidiaFan[$i], $nvidiaGpuUtil[$i], $nvidiaMemUtil[$i]) - } - } -} - -sub nvidiaPrintPlot -{ - my $type= shift; - my $ref1= shift; - - # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization - $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; - $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; - - # H e a d e r s - - # Summary - if ($type==1 && $nvidiaOpts=~/s/) - { - $$ref1.="[NVIDIA]Temp${SEP}[NVIDIA]Fan${SEP}[NVIDIA]Gpu${SEP}[NVIDIA]Mem${SEP}" - } - - # Detail - if ($type==2 && $nvidiaOpts=~/d/) - { - for (my $i=0; $i<$nvidiaNumGpus; $i++) - { - $$ref1.="[NVIDIA:$i]Temp${SEP}[NVIDIA:$i]Fan${SEP}[NVIDIA:$i]Gpu${SEP}[NVIDIA:$i]Mem${SEP}" - } - } - - # D a t a - - # Summary - if ($type==3 && $nvidiaOpts=~/s/) - { - my $num=$nvidiaNumGpus; - $$ref1.=sprintf("$SEP%d$SEP%d$SEP%d$SEP%d", - $nvidiaTempTot/$num, $nvidiaFanTot/$num, $nvidiaGpuUtilTot/$num, $nvidiaMemUtilTot/$num) - } - - # Detail - if ($type==4 && $nvidiaOpts=~/d/) - { - for (my $i=0; $i<$nvidiaNumGpus; $i++) - { - $$ref1.=sprintf("$SEP%d$SEP%d$SEP%d$SEP%d", - $nvidiaTemp[$i], $nvidiaFan[$i], $nvidiaGpuUtil[$i], $nvidiaMemUtil[$i]); - } - } -} - -sub nvidiaPrintExport -{ - my $type= shift; - my $ref1= shift; - my $ref2= shift; - my $ref3= shift; - - # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization - $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; - $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; - - # counters are only returned based on "i=" or default of 60 seconds - return if !$nvidiaAllFlag && (($nvidiaSampleCounter-1) % $nvidiaImportCount)!=0; - - if ($nvidiaOpts=~/s/) - { - if ($type eq 'l') - { - push @$ref1, "nvidia.temp"; push @$ref2, sprintf("%d", $nvidiaTempTot/$nvidiaNumGpus); - push @$ref1, "nvidia.fan"; push @$ref2, sprintf("%d", $nvidiaFanTot/$nvidiaNumGpus); - push @$ref1, "nvidia.gpu"; push @$ref2, sprintf("%d", $nvidiaGpuUtilTot/$nvidiaNumGpus); - push @$ref1, "nvidia.mem"; push @$ref2, sprintf("%d", $nvidiaMemUtilTot/$nvidiaNumGpus); - } - elsif ($type eq 's') - { - my $num=$nvidiaNumGpus; - $$ref1.=sprintf("(nvidiatot (temp %d)(fan %d)(gpu %d)(mem %d))\n", - $nvidiaTempTot/$num, $nvidiaFanTot/$num, $nvidiaGpuUtilTot/$num, $nvidiaMemUtilTot/$num); - } - elsif ($type eq 'g') - { - push @$ref2, 'pct', 'pct', 'pct', 'pct'; - push @$ref1, "nvidia.temp"; push @$ref3, sprintf("%d", $nvidiaTempTot/$nvidiaNumGpus); - push @$ref1, "nvidia.fan"; push @$ref3, sprintf("%d", $nvidiaFanTot/$nvidiaNumGpus); - push @$ref1, "nvidia.gpu"; push @$ref3, sprintf("%d", $nvidiaGpuUtilTot/$nvidiaNumGpus); - push @$ref1, "nvidia.mem"; push @$ref3, sprintf("%d", $nvidiaMemUtilTot/$nvidiaNumGpus); - } - } - - if ($nvidiaOpts=~/d/) - { - if ($type=~/[gl]/) - { - for (my $i=0; $i<$nvidiaNumGpus; $i++) - { - if ($type eq 'l') - { - push @$ref1, "nvidia.temp$i"; push @$ref2, sprintf("%d", $nvidiaTemp[$i]); - push @$ref1, "nvidia.fan$i"; push @$ref2, sprintf("%d", $nvidiaFan[$i]); - push @$ref1, "nvidia.gpu$i"; push @$ref2, sprintf("%d", $nvidiaGpuUtil[$i]); - push @$ref1, "nvidia.mem$i"; push @$ref2, sprintf("%d", $nvidiaMemUtil[$i]); - } - elsif ($type eq 'g') - { - push @$ref2, 'pct', 'pct', 'pct', 'pct'; - push @$ref1, "nvidia.temp$i"; push @$ref3, sprintf("%d", $nvidiaTemp[$i]); - push @$ref1, "nvidia.fan$i"; push @$ref3, sprintf("%d", $nvidiaFan[$i]); - push @$ref1, "nvidia.gpu$i"; push @$ref3, sprintf("%d", $nvidiaGpuUtil[$i]); - push @$ref1, "nvidia.mem$i"; push @$ref3, sprintf("%d", $nvidiaMemUtil[$i]); - } - } - } - elsif ($type eq 's') - { - $$ref2.="(nvidiainfo\n"; - $$ref2.=" (num"; - for (my $i=0; $i<$nvidiaNumGpus; $i++) - { $$ref2.=" $i"; } - $$ref2.=")\n"; - - my ($temp, $fan, $gpu, $mem)=('','','',''); - for (my $i=0; $i<$nvidiaNumGpus; $i++) - { - $temp.=" $nvidiaTemp[$i]"; - $fan.= " $nvidiaFan[$i]"; - $gpu.= " $nvidiaGpuUtil[$i]"; - $mem.= " $nvidiaMemUtil[$i]"; - } - - $$ref2.=" (temp$temp)\n"; - $$ref2.=" (fan$fan)\n"; - $$ref2.=" (gpu$gpu)\n"; - $$ref2.=" (mem$mem))\n"; - } - } -} - -1; +# copyright, 2003-2009 Hewlett-Packard Development Company, LP + +# NOTE - by default, this module only collects data once a minute, which you can change +# with the i=x parameter (eg --import nvidia,i=x). Regardless of the collection interval, +# date will be reported every interval in brief/verbose formats to provide a consisent +# set of output each monitoring cycle. + +# n v d i a m o n i t o r i n g + +use strict; + +# Allow reference to collectl variables, but be CAREFUL as these should be treated as readonly +our ($Version, $miniFiller, $rate, $SEP, $datetime, $miniInstances, $interval, $showColFlag, $playback); + +my ($nvidiaInterval, $nvidiaImportCount, $nvidiaSampleCounter, $nvidiaAllFlag); +my ($nvidiaOpts, $nvidiaNumGpus,$nvidiaProdName, $nvidiaDriverVer); +my (@nvidiaTemp, @nvidiaFan, @nvidiaGpuUtil, @nvidiaMemUtil); +my ($nvidiaTempTot, $nvidiaFanTot, $nvidiaGpuUtilTot, $nvidiaMemUtilTot); +my ($nvidiaTempTOT, $nvidiaFanTOT, $nvidiaGpuUtilTOT, $nvidiaMemUtilTOT); + +my $nvidiaGpuFirst; +my $nvidiaGpuNum=-1; +my $nvidiaSection=0; +my $nvidiaLastValFlag; +my $nvidiaCommand='/usr/bin/nvidia-smi'; +my $nvidiaFullCmd="$nvidiaCommand -q -a"; + +sub nvidiaInit +{ + my $impOptsref=shift; + my $impKeyref= shift; + + # If we ever run with a ':' in the interval, we need to be sure we're + # only looking at the main one. + my $nvidiaInterval1=(split(/:/, $interval))[0]; + + # For now, only options are a, 'i=, d, s and sd + $nvidiaOpts=''; + $nvidiaInterval=60; + if (defined($$impOptsref)) + { + foreach my $option (split(/,/,$$impOptsref)) + { + my ($name, $value)=split(/=/, $option); + error("invalid misc option: '$name'") if $name ne 'a' && $name ne 'i' && $name!~/^[ds]+$/; + + $nvidiaInterval=$value if $name eq 'i'; + $nvidiaAllFlag=1 if $name eq 'a'; + $nvidiaOpts=$name if $name=~/^[ds]+$/; + } + } + + # Special case: if --showcowheaders, we're called with -i0 and need to reset so the + # division below doesn't bomb out. + $nvidiaInterval1=1 if $showColFlag; + $nvidiaImportCount=int($nvidiaInterval/$nvidiaInterval1); + error("nvidia interval option not a multiple of '$nvidiaInterval1' seconds") + if $nvidiaInterval1*$nvidiaImportCount != $nvidiaInterval; + + $nvidiaOpts='s' if $nvidiaOpts eq ''; + $$impOptsref=$nvidiaOpts; + $$impKeyref='nvid'; + + # since totals only initialized in 'analyze' routine, do it here too in case no data + # in raw file during playback. + $nvidiaTempTot=$nvidiaFanTot=$nvidiaGpuUtilTot=$nvidiaMemUtilTot=0; + + # R u n C o m m a n d I n R e a l t i m e M o d e + + # when running in collection mode only, we need to make sure we're nvidia enabled + if ($playback eq '') + { + if ($playback eq '' && !-e $nvidiaCommand || $Version lt '3.5.0-3') + { + my $message="cannot find '$nvidiaCommand'" if !-e $nvidiaCommand; + $message="this nvidia.ph requires at least collectl V3.5.1" if $Version lt '3.5.1'; + pushmsg('W', "$message. GPU monitoring disabled"); + $$impOptsref=$$impKeyref=''; + return(-1); + } + + # Now run command once to get a get a few constants for header AND number of GPUs + # NOTE: if it returns its names its probably a help message and the desired commands + # are not suppoted, hence not a GPU we can monitor. + my $output=`$nvidiaFullCmd`; + if ($output=~/nvidia-smi/) + { + pushmsg('W', "nvidia GPU doesn' support '$nvidiaFullCmd'. GPU monitoring disabled"); + $$impOptsref=$$impKeyref=''; + return(-1); + } + + $nvidiaNumGpus=0; + foreach my $line ((split(/\n/, $output))) + { + chomp $line; + $nvidiaDriverVer=$1 if $line=~/Driver Version\s+:\s+(.*)/; + + if ($line=~/Product Name\s+:\s+(.*)/) + { + $nvidiaProdName=$1; + $nvidiaNumGpus++; + } + } + $nvidiaSampleCounter=-1; + } + + return(1); +} + +# Nothing to add to header +sub nvidiaUpdateHeader +{ + my $lineref=shift; + $$lineref.="# GPU: Type: nvidia $nvidiaProdName Version: $nvidiaDriverVer NumGPU: $nvidiaNumGpus\n"; +} + +sub nvidiaGetHeader +{ + my $headerref=shift; + + # Make sure playback file contains nvidia gpu data and if not, just set number + # of gpus to 1 to make display logic work because maybe this is intended. + if ($$headerref!~/GPU:(.*)Version/ || $1!~/nvidia/) + { + logmsg('W', "playback file does not contain nvidia data"); + $nvidiaNumGpus=1; + } + else + { + # Now parse header for real + $$headerref=~/GPU:.*Type: (.*).*Version: (.*)\s+NumGPU: (\d+)/; + $nvidiaDriverVer=$2; + $nvidiaNumGpus=$3; + } +} + +sub nvidiaGetData +{ + # only read counters when OUR interval directs us to. + return if ($nvidiaSampleCounter++ % $nvidiaImportCount)!=0; + + getExec(0, $nvidiaFullCmd, 'nvid'); +} + +sub nvidiaInitInterval +{ + # all initialization totals MUST be done in Analyze() because this not called + # each pass when writing to a raw file. +} + +sub nvidiaAnalyze +{ + my $type= shift; + my $dataref=shift; + + # we need to know when last counter seen AND we can't use InitInterval() + $nvidiaLastValFlag=0; + + # This is a mess! Difference drivers generate different output + if ($nvidiaDriverVer lt '270.41.19') # until I know better + { + # GPU number always preceeds data + $nvidiaGpuNum=$1 if $$dataref=~/^GPU (\d+)/; + + my $i=$nvidiaGpuNum; + $nvidiaTemp[$i]=$1 if $$dataref=~/^Temp.*?(\d+)/; + $nvidiaFan[$i]=$1 if $$dataref=~/^Fan.*?(\d+)/; + $nvidiaGpuUtil[$i]=$1 if $$dataref=~/^GPU.*: (\d+)/; + + # This indicates the end of a set of data. If more data elements + # are ever added, we'll need a different 'last' variable test + if ($$dataref=~/^Memory.*?(\d+)/) + { + $nvidiaMemUtil[$i]=$1; + $nvidiaLastValFlag=1; + } + } + elsif ($nvidiaDriverVer ge '270.41.19') + { + # for this driver version this isn't a number but a string so just bump index + # and make a note of it so we recognize the start of a new interval + if ($$dataref=~/^GPU (.*)/ && $$dataref!~/UUID/) + { + $nvidiaGpuFirst=$1 if !defined($nvidiaGpuFirst); + $nvidiaGpuNum=-1 if $1 eq $nvidiaGpuFirst; + $nvidiaGpuNum++; + } + + $nvidiaSection=10 if $$dataref=~/^PCI/; + $nvidiaSection=20 if $$dataref=~/^Fan/; + $nvidiaSection=30 if $$dataref=~/^Memory Usage/; + $nvidiaSection=40 if $$dataref=~/^Utilization/; + $nvidiaSection=50 if $$dataref=~/^Ecc Mode/; + $nvidiaSection=60 if $$dataref=~/^ECC Errors/; + $nvidiaSection=70 if $$dataref=~/^Temperature/; + $nvidiaSection=80 if $$dataref=~/^Power Readings/; + $nvidiaSection=90 if $$dataref=~/^Clocks/; + + # for now we only care about Fan, Utiliztion and Temp + return if $nvidiaSection!=20 && $nvidiaSection!=40 && $nvidiaSection!=70; + + my $i=$nvidiaGpuNum; + $nvidiaFan[$i]=$1 if $nvidiaSection==20 && $$dataref=~/^Fan.*?(\d+)/; + $nvidiaGpuUtil[$i]=$1 if $nvidiaSection==40 && $$dataref=~/^Gpu.*: (\d+)/; + $nvidiaMemUtil[$i]=$1 if $nvidiaSection==40 && $$dataref=~/^Memory.*?(\d+)/; + + if ($nvidiaSection==70 && $$dataref=~/^Gpu.*?(\d+)/) + { + $nvidiaTemp[$i]=$1; + $nvidiaLastValFlag=1; + } + } + + # We can only do initialization and update totals when we see last data element (actually + # we could have updated the totals as each element seen but this is a little easier. + if ($nvidiaLastValFlag) + { + my $i=$nvidiaGpuNum; + + # These only done once/interval, not per GPU + $nvidiaTempTot=$nvidiaFanTot=$nvidiaGpuUtilTot=$nvidiaMemUtilTot=0 if $i==0; + + $nvidiaTempTot+= $nvidiaTemp[$i]; + $nvidiaFanTot+= $nvidiaFan[$i]; + # $nvidiaGpuUtilTot+=$nvidiaGpuUtil[$i]; + # $nvidiaMemUtilTot+=$nvidiaMemUtil[$i]; + } +} + +sub nvidiaPrintBrief +{ + my $type=shift; + my $lineref=shift; + + # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization + $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; + $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; + + if ($type==1) # header line 1 + { + $$lineref.="<------nvidia------->"; + } + elsif ($type==2) # header line 2 + { + $$lineref.=" Temp Fan% Gpu% Mem% "; + } + elsif ($type==3) # data + { + my $num=$nvidiaNumGpus; + $$lineref.=sprintf(" %4d %4d %4d %4d ", + $nvidiaTempTot/$num, $nvidiaFanTot/$num, $nvidiaGpuUtilTot/$num, $nvidiaMemUtilTot/$num); + } + elsif ($type==4) # reset 'total' counters + { + $nvidiaTempTOT=$nvidiaFanTOT=$nvidiaGpuUtilTOT=$nvidiaMemUtilTOT=0; + } + elsif ($type==5) # increment 'total' counters + { + $nvidiaTempTOT+= $nvidiaTempTot; + $nvidiaFanTOT+= $nvidiaFanTot; + $nvidiaGpuUtilTOT+=$nvidiaGpuUtilTot; + $nvidiaMemUtilTOT+=$nvidiaMemUtilTot; + } + elsif ($type==6) # print 'total' counters + { + my $num=$nvidiaNumGpus; + printf(" %4d %4d %4d %4d ", + int($nvidiaTempTOT/$num/$miniInstances), int($nvidiaFanTOT/$num/$miniInstances), + int($nvidiaGpuUtilTOT/$num/$miniInstances), int($nvidiaMemUtilTOT/$num/$miniInstances)); + } +} + +sub nvidiaPrintVerbose +{ + my $printHeader=shift; + my $homeFlag= shift; + my $lineref= shift; + + # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization + $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; + $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; + + if ($nvidiaOpts=~/s/) + { + my $line=''; + if ($printHeader) + { + $line.="\n" if !$homeFlag; + $line.="# GPU STATISTICS\n"; + $line.="#$miniFiller Temp Fan% GPU% Mem%\n"; + } + + my $num=$nvidiaNumGpus; + $$lineref=$line; + $$lineref.=sprintf("$datetime %3d %3d %3d %3d\n", + int($nvidiaTempTot/$num), int($nvidiaFanTot/$num), + int($nvidiaGpuUtilTot/$num), int($nvidiaMemUtilTot/$num)); + } + + if ($nvidiaOpts=~/d/) + { + my $line=''; + if ($printHeader) + { + $line.="\n" if !$homeFlag; + $line.="# GPU DETAIL\n"; + $line.="#$miniFiller Num Temp Fan% GPU% Mem%\n"; + } + + $$lineref=$line; + for (my $i=0; $i<$nvidiaNumGpus; $i++) + { + $$lineref.=sprintf("$datetime %3d %3d %3d %3d %3d\n", + $i, $nvidiaTemp[$i], $nvidiaFan[$i], $nvidiaGpuUtil[$i], $nvidiaMemUtil[$i]) + } + } +} + +sub nvidiaPrintPlot +{ + my $type= shift; + my $ref1= shift; + + # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization + $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; + $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; + + # H e a d e r s + + # Summary + if ($type==1 && $nvidiaOpts=~/s/) + { + $$ref1.="[NVIDIA]Temp${SEP}[NVIDIA]Fan${SEP}[NVIDIA]Gpu${SEP}[NVIDIA]Mem${SEP}" + } + + # Detail + if ($type==2 && $nvidiaOpts=~/d/) + { + for (my $i=0; $i<$nvidiaNumGpus; $i++) + { + $$ref1.="[NVIDIA:$i]Temp${SEP}[NVIDIA:$i]Fan${SEP}[NVIDIA:$i]Gpu${SEP}[NVIDIA:$i]Mem${SEP}" + } + } + + # D a t a + + # Summary + if ($type==3 && $nvidiaOpts=~/s/) + { + my $num=$nvidiaNumGpus; + $$ref1.=sprintf("$SEP%d$SEP%d$SEP%d$SEP%d", + $nvidiaTempTot/$num, $nvidiaFanTot/$num, $nvidiaGpuUtilTot/$num, $nvidiaMemUtilTot/$num) + } + + # Detail + if ($type==4 && $nvidiaOpts=~/d/) + { + for (my $i=0; $i<$nvidiaNumGpus; $i++) + { + $$ref1.=sprintf("$SEP%d$SEP%d$SEP%d$SEP%d", + $nvidiaTemp[$i], $nvidiaFan[$i], $nvidiaGpuUtil[$i], $nvidiaMemUtil[$i]); + } + } +} + +sub nvidiaPrintExport +{ + my $type= shift; + my $ref1= shift; + my $ref2= shift; + my $ref3= shift; + + # DReyeVR edits here, added explicit call to nvidia-smi querying gpu/memory utilization + $nvidiaGpuUtilTot=`nvidia-smi --query-gpu=utilization.gpu --format=csv,noheader,nounits`; + $nvidiaMemUtilTot=`nvidia-smi --query-gpu=utilization.memory --format=csv,noheader,nounits`; + + # counters are only returned based on "i=" or default of 60 seconds + return if !$nvidiaAllFlag && (($nvidiaSampleCounter-1) % $nvidiaImportCount)!=0; + + if ($nvidiaOpts=~/s/) + { + if ($type eq 'l') + { + push @$ref1, "nvidia.temp"; push @$ref2, sprintf("%d", $nvidiaTempTot/$nvidiaNumGpus); + push @$ref1, "nvidia.fan"; push @$ref2, sprintf("%d", $nvidiaFanTot/$nvidiaNumGpus); + push @$ref1, "nvidia.gpu"; push @$ref2, sprintf("%d", $nvidiaGpuUtilTot/$nvidiaNumGpus); + push @$ref1, "nvidia.mem"; push @$ref2, sprintf("%d", $nvidiaMemUtilTot/$nvidiaNumGpus); + } + elsif ($type eq 's') + { + my $num=$nvidiaNumGpus; + $$ref1.=sprintf("(nvidiatot (temp %d)(fan %d)(gpu %d)(mem %d))\n", + $nvidiaTempTot/$num, $nvidiaFanTot/$num, $nvidiaGpuUtilTot/$num, $nvidiaMemUtilTot/$num); + } + elsif ($type eq 'g') + { + push @$ref2, 'pct', 'pct', 'pct', 'pct'; + push @$ref1, "nvidia.temp"; push @$ref3, sprintf("%d", $nvidiaTempTot/$nvidiaNumGpus); + push @$ref1, "nvidia.fan"; push @$ref3, sprintf("%d", $nvidiaFanTot/$nvidiaNumGpus); + push @$ref1, "nvidia.gpu"; push @$ref3, sprintf("%d", $nvidiaGpuUtilTot/$nvidiaNumGpus); + push @$ref1, "nvidia.mem"; push @$ref3, sprintf("%d", $nvidiaMemUtilTot/$nvidiaNumGpus); + } + } + + if ($nvidiaOpts=~/d/) + { + if ($type=~/[gl]/) + { + for (my $i=0; $i<$nvidiaNumGpus; $i++) + { + if ($type eq 'l') + { + push @$ref1, "nvidia.temp$i"; push @$ref2, sprintf("%d", $nvidiaTemp[$i]); + push @$ref1, "nvidia.fan$i"; push @$ref2, sprintf("%d", $nvidiaFan[$i]); + push @$ref1, "nvidia.gpu$i"; push @$ref2, sprintf("%d", $nvidiaGpuUtil[$i]); + push @$ref1, "nvidia.mem$i"; push @$ref2, sprintf("%d", $nvidiaMemUtil[$i]); + } + elsif ($type eq 'g') + { + push @$ref2, 'pct', 'pct', 'pct', 'pct'; + push @$ref1, "nvidia.temp$i"; push @$ref3, sprintf("%d", $nvidiaTemp[$i]); + push @$ref1, "nvidia.fan$i"; push @$ref3, sprintf("%d", $nvidiaFan[$i]); + push @$ref1, "nvidia.gpu$i"; push @$ref3, sprintf("%d", $nvidiaGpuUtil[$i]); + push @$ref1, "nvidia.mem$i"; push @$ref3, sprintf("%d", $nvidiaMemUtil[$i]); + } + } + } + elsif ($type eq 's') + { + $$ref2.="(nvidiainfo\n"; + $$ref2.=" (num"; + for (my $i=0; $i<$nvidiaNumGpus; $i++) + { $$ref2.=" $i"; } + $$ref2.=")\n"; + + my ($temp, $fan, $gpu, $mem)=('','','',''); + for (my $i=0; $i<$nvidiaNumGpus; $i++) + { + $temp.=" $nvidiaTemp[$i]"; + $fan.= " $nvidiaFan[$i]"; + $gpu.= " $nvidiaGpuUtil[$i]"; + $mem.= " $nvidiaMemUtil[$i]"; + } + + $$ref2.=" (temp$temp)\n"; + $$ref2.=" (fan$fan)\n"; + $$ref2.=" (gpu$gpu)\n"; + $$ref2.=" (mem$mem))\n"; + } + } +} + +1; diff --git a/Tools/Diagnostics/collectl/run_collectl.sh b/Tools/Diagnostics/collectl/run_collectl.sh index 6642596..d969b2b 100755 --- a/Tools/Diagnostics/collectl/run_collectl.sh +++ b/Tools/Diagnostics/collectl/run_collectl.sh @@ -1,161 +1,161 @@ -#!/bin/bash - -R='\033[0;31m' # Red -G='\033[0;32m' # Green -Y='\033[0;33m' # Yellow -B='\033[0;34m' # Blue -NC='\033[0m' # No Color - -system="$(uname -a)" # used to check if running on Windows or Linux - -# first the prerequisite environment variables -if [[ $system == *"Microsoft"* ]]; # Running on WSL (Windows benchmark) -then - # Edit this string if on Windows! - # (Note that this calls the windows python.exe, and it is a WINDOWS directory, so start with Disk:/) - CARLA_DIR="C:/Users/PATH/TO/CARLA/" -else - # Edit this string if on Linux! - CARLA_DIR="PATH/TO/CARLA/" -fi -# interval (s) between refreshes -INTERVAL=0.5 - -# other variables -collectl_data="collectl_data.csv" -carla_data="carla_metadata.csv" -out_directory="collectl" - -# signal catching -trap ctrl_c INT -function ctrl_c() { - if [ $completed == 1 ]; - then - echo -e "\nwrote ${collectl_data} in ${out_directory}" - echo -e "wrote ${carla_data} in ${out_directory}" - if [[ $system == *"Microsoft"* ]]; # Windows only! - then - python.exe ../python/combine_collectl.py -d "$out_directory" -c1 "$collectl_data" -c2 "$carla_data" -s $time_start -e $time_end - python.exe ../python/graph_sys_diagnostics.py -d "$folder_name" - else - python3 ../python/combine_collectl.py -d "$out_directory" -c1 "$collectl_data" -c2 "$carla_data" -s $time_start -e $time_end - python3 ../python/graph_sys_diagnostics.py -d "$folder_name" - fi - else - echo -e "goodbye." - exit 1 - fi -} -# flag that everything succeeded, gets set at the bottom of the script -completed=0 - -# pass in the file to write to -if [ "$1" != "" ]; -then - echo -e "${Y}Using custom directory ${1}${NC}" - out_directory="$1" -fi - -# get timestamp to encode time of execution into results -timestamp=$(date +"%F-%H-%M-%S.%1N" ) # gets date as yyyy-mm-dd-hh-mm-ss.ms - -#name of the folder -out_directory="${out_directory}_${timestamp}" -folder_name="${out_directory}" - -# output always goes in ./data/ -out_directory="data/${out_directory}" - -mkdir -p "$out_directory" - -collectl_file="${out_directory}/${collectl_data}" -touch $collectl_file -# run collectl in background -# includes nvidia monitoring (requires our nvidia.ph patch) -# monitors cpu cores and memory (-sCm) -# prints data in a graph style "-P" timestamped with ms (-oTm) -# outputs data at intervals (-i) of 0.5s -# comma-separated (--sep ",") -collectl --import nvidia, -sCm -oTm -P -i 0.5 --sep "," --quiet > "$collectl_file" & -echo -e "${G}Started collecting system data to $out_directory${NC}" - -# run timing script -# NOTE: assumes carla is terminated before this script -echo -e "Waiting for Carla to run..." -# inspired from https://stackoverflow.com/questions/7708715/check-if-program-is-running-with-bash-shell-script -PROC_NUM="0" - -# NOTE: there is also CarlaUE4-Win64-Shipping which runs with the release build -# to see all running processes on Windows check ps on powershell - -if [[ $system == *"Microsoft"* ]]; # Windows only! -then - # powershell.exe Set-ExecutionPolicy -Scope CurrentUser -ExecutionPolicy Unrestricted - while [ $PROC_NUM -eq 0 ]; do - PROC_NUM=$(powershell.exe -command 'if((get-process "CarlaUE4" -ea SilentlyContinue) -eq $Null){ return 0 } else { return 1 }') - PROC_NUM="${PROC_NUM//[!0-9]/}" # trim weird Windows characters - sleep 0.5 # resolution of 0.5s (slower than bash bc using ps1) - done -else # Linux only! - while [ $PROC_NUM -eq 0 ]; do - PROC_NUM=$(ps -ef | grep "carla" | grep -v "grep" | wc -l) - sleep 0.05 # resolution of 0.05s - done -fi - -echo -e "Found Carla script running... Waiting 10s to let Carla initialize" - -# # get quality information if available -# if [ $(ps -ef | grep "carla") == "*--quality-level*=*Low*" ]; -# then -# CarlaQuality="Low" -# else -# CarlaQuality="Epic" -# fi - -# slight delay to let carla initialize -sleep 10 - -# get when started -time_start=$(date +"%T.%3N") - -# run the fps monitor script -echo -e "${G}Starting carla framerate capture python client${NC}" -if [[ $system == *"Microsoft"* ]]; # Running on WSL (Windows benchmark) -then - # assumes you have pyhon3 installed on Windows - python.exe ../python/record_carla_fps.py -c $CARLA_DIR -i $INTERVAL -d "$out_directory" -f "$carla_data" & -else - # python3 on linux - python3 ../python/record_carla_fps.py -c $CARLA_DIR -i $INTERVAL -d "$out_directory" -f "$carla_data" & -fi - -# wait for carla termination -echo -e "Waiting for Carla to terminate..." -if [[ $system == *"Microsoft"* ]]; # Windows only! -then - # powershell.exe Set-ExecutionPolicy -Scope CurrentUser -ExecutionPolicy Unrestricted - while [ $PROC_NUM -ge 1 ]; do - PROC_NUM=$(powershell.exe -command 'if((get-process "CarlaUE4" -ea SilentlyContinue) -eq $Null){ return 0 } else { return 1 }') - PROC_NUM="${PROC_NUM//[!0-9]/}" # trim non-digit characters - sleep 0.5 # resolution of 0.5s (slower than bash bc using ps1) - done -else # Linux only! - while [ $PROC_NUM -ge 1 ]; do - PROC_NUM=$(ps -ef | grep "carla" | grep -v "grep" | wc -l) - sleep 0.1 # resolution of 0.1s - done -fi -time_end=$(date +"%T.%3N") -echo -e "${G}Finished carla script\n${NC}" - -echo -e "Carla started at: $time_start" -echo -e "Carla finished at: $time_end" - -echo -e "\nCtrl+C to end the collectl process" -completed=1 - -# move collectl process to foreground -wait - - +#!/bin/bash + +R='\033[0;31m' # Red +G='\033[0;32m' # Green +Y='\033[0;33m' # Yellow +B='\033[0;34m' # Blue +NC='\033[0m' # No Color + +system="$(uname -a)" # used to check if running on Windows or Linux + +# first the prerequisite environment variables +if [[ $system == *"Microsoft"* ]]; # Running on WSL (Windows benchmark) +then + # Edit this string if on Windows! + # (Note that this calls the windows python.exe, and it is a WINDOWS directory, so start with Disk:/) + CARLA_DIR="C:/Users/PATH/TO/CARLA/" +else + # Edit this string if on Linux! + CARLA_DIR="PATH/TO/CARLA/" +fi +# interval (s) between refreshes +INTERVAL=0.5 + +# other variables +collectl_data="collectl_data.csv" +carla_data="carla_metadata.csv" +out_directory="collectl" + +# signal catching +trap ctrl_c INT +function ctrl_c() { + if [ $completed == 1 ]; + then + echo -e "\nwrote ${collectl_data} in ${out_directory}" + echo -e "wrote ${carla_data} in ${out_directory}" + if [[ $system == *"Microsoft"* ]]; # Windows only! + then + python.exe ../python/combine_collectl.py -d "$out_directory" -c1 "$collectl_data" -c2 "$carla_data" -s $time_start -e $time_end + python.exe ../python/graph_sys_diagnostics.py -d "$folder_name" + else + python3 ../python/combine_collectl.py -d "$out_directory" -c1 "$collectl_data" -c2 "$carla_data" -s $time_start -e $time_end + python3 ../python/graph_sys_diagnostics.py -d "$folder_name" + fi + else + echo -e "goodbye." + exit 1 + fi +} +# flag that everything succeeded, gets set at the bottom of the script +completed=0 + +# pass in the file to write to +if [ "$1" != "" ]; +then + echo -e "${Y}Using custom directory ${1}${NC}" + out_directory="$1" +fi + +# get timestamp to encode time of execution into results +timestamp=$(date +"%F-%H-%M-%S.%1N" ) # gets date as yyyy-mm-dd-hh-mm-ss.ms + +#name of the folder +out_directory="${out_directory}_${timestamp}" +folder_name="${out_directory}" + +# output always goes in ./data/ +out_directory="data/${out_directory}" + +mkdir -p "$out_directory" + +collectl_file="${out_directory}/${collectl_data}" +touch $collectl_file +# run collectl in background +# includes nvidia monitoring (requires our nvidia.ph patch) +# monitors cpu cores and memory (-sCm) +# prints data in a graph style "-P" timestamped with ms (-oTm) +# outputs data at intervals (-i) of 0.5s +# comma-separated (--sep ",") +collectl --import nvidia, -sCm -oTm -P -i 0.5 --sep "," --quiet > "$collectl_file" & +echo -e "${G}Started collecting system data to $out_directory${NC}" + +# run timing script +# NOTE: assumes carla is terminated before this script +echo -e "Waiting for Carla to run..." +# inspired from https://stackoverflow.com/questions/7708715/check-if-program-is-running-with-bash-shell-script +PROC_NUM="0" + +# NOTE: there is also CarlaUE4-Win64-Shipping which runs with the release build +# to see all running processes on Windows check ps on powershell + +if [[ $system == *"Microsoft"* ]]; # Windows only! +then + # powershell.exe Set-ExecutionPolicy -Scope CurrentUser -ExecutionPolicy Unrestricted + while [ $PROC_NUM -eq 0 ]; do + PROC_NUM=$(powershell.exe -command 'if((get-process "CarlaUE4" -ea SilentlyContinue) -eq $Null){ return 0 } else { return 1 }') + PROC_NUM="${PROC_NUM//[!0-9]/}" # trim weird Windows characters + sleep 0.5 # resolution of 0.5s (slower than bash bc using ps1) + done +else # Linux only! + while [ $PROC_NUM -eq 0 ]; do + PROC_NUM=$(ps -ef | grep "carla" | grep -v "grep" | wc -l) + sleep 0.05 # resolution of 0.05s + done +fi + +echo -e "Found Carla script running... Waiting 10s to let Carla initialize" + +# # get quality information if available +# if [ $(ps -ef | grep "carla") == "*--quality-level*=*Low*" ]; +# then +# CarlaQuality="Low" +# else +# CarlaQuality="Epic" +# fi + +# slight delay to let carla initialize +sleep 10 + +# get when started +time_start=$(date +"%T.%3N") + +# run the fps monitor script +echo -e "${G}Starting carla framerate capture python client${NC}" +if [[ $system == *"Microsoft"* ]]; # Running on WSL (Windows benchmark) +then + # assumes you have pyhon3 installed on Windows + python.exe ../python/record_carla_fps.py -c $CARLA_DIR -i $INTERVAL -d "$out_directory" -f "$carla_data" & +else + # python3 on linux + python3 ../python/record_carla_fps.py -c $CARLA_DIR -i $INTERVAL -d "$out_directory" -f "$carla_data" & +fi + +# wait for carla termination +echo -e "Waiting for Carla to terminate..." +if [[ $system == *"Microsoft"* ]]; # Windows only! +then + # powershell.exe Set-ExecutionPolicy -Scope CurrentUser -ExecutionPolicy Unrestricted + while [ $PROC_NUM -ge 1 ]; do + PROC_NUM=$(powershell.exe -command 'if((get-process "CarlaUE4" -ea SilentlyContinue) -eq $Null){ return 0 } else { return 1 }') + PROC_NUM="${PROC_NUM//[!0-9]/}" # trim non-digit characters + sleep 0.5 # resolution of 0.5s (slower than bash bc using ps1) + done +else # Linux only! + while [ $PROC_NUM -ge 1 ]; do + PROC_NUM=$(ps -ef | grep "carla" | grep -v "grep" | wc -l) + sleep 0.1 # resolution of 0.1s + done +fi +time_end=$(date +"%T.%3N") +echo -e "${G}Finished carla script\n${NC}" + +echo -e "Carla started at: $time_start" +echo -e "Carla finished at: $time_end" + +echo -e "\nCtrl+C to end the collectl process" +completed=1 + +# move collectl process to foreground +wait + + diff --git a/Tools/Diagnostics/collectl/setup_collectl.sh b/Tools/Diagnostics/collectl/setup_collectl.sh index 6a96f57..c10e6f3 100755 --- a/Tools/Diagnostics/collectl/setup_collectl.sh +++ b/Tools/Diagnostics/collectl/setup_collectl.sh @@ -1,36 +1,36 @@ -#!/bin/bash - -R='\033[0;31m' # Red -G='\033[0;32m' # Green -Y='\033[0;33m' # Yellow -B='\033[0;34m' # Blue -NC='\033[0m' # No Color - -# first install collectl (native on Linux, or WSL on Windows) -# apache works fine for the Web stuff -sudo apt install collectl && echo -e "${G}Successfully installed collectl${NC}" - -# in order to monitor Nvidia cards (gpu usage & memory) we need to pass the --import nvidia flag to collectl -# however, this requires nvidia.ph which does not work natively, our patched version does as it directly -# calls nvidia-smi to query the gpu -sudo cp ./nvidia.ph /usr/share/collectl/ -sudo cp ./nvidia.ph /etc/perl/ - -# Windows only! -system="$(uname -a)" -if [[ $system == *"Microsoft"* ]]; -then - # make a symlink to the Windows nvidia-smi executable: - # as per this question https://stackoverflow.com/questions/57100015/how-do-i-run-nvidia-smi-on-windows - # the executable is stored somewhere like: C:\Windows\System32\DriverStore\FileRepository\nvdm*\nvidia-smi.exe - ln -s /mnt/c/Windows/System32/DriverStore/FileRepository/nv_dispi.inf_*/nvidia-smi.exe nvidia-smi - - # then move it to /usr/bin/ in order to be callable from anywhere in WSL. - # As per this https://stackoverflow.com/questions/38920710/how-can-i-run-a-windows-executable-from-wsl-ubuntu-bash - # windows executables should be natively runnable from WSL - sudo mv nvidia-smi /usr/bin/ - - echo -e "${G}Successfully created nvidia-smi symlink for Windows${NC}" -fi -# ready to go! +#!/bin/bash + +R='\033[0;31m' # Red +G='\033[0;32m' # Green +Y='\033[0;33m' # Yellow +B='\033[0;34m' # Blue +NC='\033[0m' # No Color + +# first install collectl (native on Linux, or WSL on Windows) +# apache works fine for the Web stuff +sudo apt install collectl && echo -e "${G}Successfully installed collectl${NC}" + +# in order to monitor Nvidia cards (gpu usage & memory) we need to pass the --import nvidia flag to collectl +# however, this requires nvidia.ph which does not work natively, our patched version does as it directly +# calls nvidia-smi to query the gpu +sudo cp ./nvidia.ph /usr/share/collectl/ +sudo cp ./nvidia.ph /etc/perl/ + +# Windows only! +system="$(uname -a)" +if [[ $system == *"Microsoft"* ]]; +then + # make a symlink to the Windows nvidia-smi executable: + # as per this question https://stackoverflow.com/questions/57100015/how-do-i-run-nvidia-smi-on-windows + # the executable is stored somewhere like: C:\Windows\System32\DriverStore\FileRepository\nvdm*\nvidia-smi.exe + ln -s /mnt/c/Windows/System32/DriverStore/FileRepository/nv_dispi.inf_*/nvidia-smi.exe nvidia-smi + + # then move it to /usr/bin/ in order to be callable from anywhere in WSL. + # As per this https://stackoverflow.com/questions/38920710/how-can-i-run-a-windows-executable-from-wsl-ubuntu-bash + # windows executables should be natively runnable from WSL + sudo mv nvidia-smi /usr/bin/ + + echo -e "${G}Successfully created nvidia-smi symlink for Windows${NC}" +fi +# ready to go! echo "Ready!" \ No newline at end of file diff --git a/Tools/Diagnostics/python/combine_collectl.py b/Tools/Diagnostics/python/combine_collectl.py index f44b6e4..fa2481b 100755 --- a/Tools/Diagnostics/python/combine_collectl.py +++ b/Tools/Diagnostics/python/combine_collectl.py @@ -1,82 +1,82 @@ -#!/usr/bin/env python - -import argparse -import csv # writing fps data -import time -import pandas as pd -import os - -"""IMPORTANT""" -# NOTE: this script assumes it is run in DReyeVR/Diagnostics/python -# So it does NOT need to be in carla's PythonAPI - - -def main(): - argparser = argparse.ArgumentParser(description=__doc__) - argparser.add_argument( - '-d', '--dir', - metavar='D', - default="results/collectl", # cwd - type=str, - help='data directory for outputs') - argparser.add_argument( - '-c1', '--collectl', - metavar='C1', - default="collectl_data.csv", - type=str, - help='csv file for collectl data', - required=False) - argparser.add_argument( - '-c2', '--carla', - metavar='C2', - default="carla_metadata.csv", - type=str, - help='csv file for carla metadata', - required=False) - argparser.add_argument( - '-s', '--start', - metavar='S', - default="00:00:00.00", - type=str, - help='timestamp when carla starts hh:mm:ss.ms', - required=False) - argparser.add_argument( - '-e', '--end', - metavar='E', - default="00:00:00.00", - type=str, - help='timestamp when carla ends hh:mm:ss.ms', - required=False) - - args = argparser.parse_args() - output_dir = args.dir - collectl_data = args.collectl - carla_data = args.carla - carla_start = args.start - carla_end = args.end - - # read and write files - path = os.path.join(os.getcwd(), output_dir) - collectl_path = os.path.join(path, collectl_data) - carla_path = os.path.join(path, carla_data) - result = os.path.join(path, "combined.csv") - with open(collectl_path, 'r') as collectl: - with open(carla_path, 'r') as carla: - df_collectl = pd.read_csv(collectl) - df_carla = pd.read_csv(carla) - df_carla = df_carla.dropna(axis=1) - df_combined = df_collectl.join(df_carla) - # add start/end to csv - df_timestamps = pd.DataFrame({"[CARLA]t_start": [carla_start], - "[CARLA]t_end": [carla_end]}) - df_combined = df_combined.join(df_timestamps) - df_combined.to_csv(result, index=False) - - print("combined", collectl_data,"and", carla_data, "in", output_dir) - - -if __name__ == '__main__': - try: - main() - except KeyboardInterrupt: - pass +#!/usr/bin/env python + +import argparse +import csv # writing fps data +import time +import pandas as pd +import os + +"""IMPORTANT""" +# NOTE: this script assumes it is run in DReyeVR/Diagnostics/python +# So it does NOT need to be in carla's PythonAPI + + +def main(): + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + '-d', '--dir', + metavar='D', + default="results/collectl", # cwd + type=str, + help='data directory for outputs') + argparser.add_argument( + '-c1', '--collectl', + metavar='C1', + default="collectl_data.csv", + type=str, + help='csv file for collectl data', + required=False) + argparser.add_argument( + '-c2', '--carla', + metavar='C2', + default="carla_metadata.csv", + type=str, + help='csv file for carla metadata', + required=False) + argparser.add_argument( + '-s', '--start', + metavar='S', + default="00:00:00.00", + type=str, + help='timestamp when carla starts hh:mm:ss.ms', + required=False) + argparser.add_argument( + '-e', '--end', + metavar='E', + default="00:00:00.00", + type=str, + help='timestamp when carla ends hh:mm:ss.ms', + required=False) + + args = argparser.parse_args() + output_dir = args.dir + collectl_data = args.collectl + carla_data = args.carla + carla_start = args.start + carla_end = args.end + + # read and write files + path = os.path.join(os.getcwd(), output_dir) + collectl_path = os.path.join(path, collectl_data) + carla_path = os.path.join(path, carla_data) + result = os.path.join(path, "combined.csv") + with open(collectl_path, 'r') as collectl: + with open(carla_path, 'r') as carla: + df_collectl = pd.read_csv(collectl) + df_carla = pd.read_csv(carla) + df_carla = df_carla.dropna(axis=1) + df_combined = df_collectl.join(df_carla) + # add start/end to csv + df_timestamps = pd.DataFrame({"[CARLA]t_start": [carla_start], + "[CARLA]t_end": [carla_end]}) + df_combined = df_combined.join(df_timestamps) + df_combined.to_csv(result, index=False) + + print("combined", collectl_data,"and", carla_data, "in", output_dir) + + +if __name__ == '__main__': + try: + main() + except KeyboardInterrupt: + pass diff --git a/Tools/Diagnostics/python/graph_data.py b/Tools/Diagnostics/python/graph_data.py index 5dbf9e0..765771e 100755 --- a/Tools/Diagnostics/python/graph_data.py +++ b/Tools/Diagnostics/python/graph_data.py @@ -1,306 +1,306 @@ -import numpy as np -import os -import matplotlib.pyplot as plt -import matplotlib as mpl - -mpl.use("Agg") - -"""IMPORTANT""" -# NOTE: this script assumes it is run in DReyeVR/Diagnostics/python - - -def plot_versus( - data_x, - data_y, - units="", - name_x="X", - name_y="Y", - trim=(0, 0), - lines=False, - colour="r", - dir_path="results", -): - # trim the starts and end of data - trim_start, trim_end = trim - max_size = min(len(data_x), len(data_y)) - data_x = data_x[trim_start : max_size - trim_end] - data_y = data_y[trim_start : max_size - trim_end] - - # create a figure that is 6in x 6in - fig = plt.figure() - - # the axis limits and grid lines - plt.grid(True) - - units_str = " (" + units + ")" if units != "" else "" - trim_str = " [" + str(trim_start) + ", " + str(trim_end) + "]" - - # label your graph, axes, and ticks on each axis - plt.xlabel(name_x + units_str, fontsize=16) - plt.ylabel(name_y + units_str, fontsize=16) - plt.xticks() - plt.yticks() - plt.tick_params(labelsize=15) - if name_x == "": - plt.title(name_y + trim_str, fontsize=18) - else: - plt.title(name_x + " versus " + name_y + trim_str, fontsize=18) - - # plot dots - plt.plot(data_x, data_y, colour + "o") - if lines: - plt.plot(data_x, data_y, color=colour, linewidth=1) - - # complete the layout, save figure, and show the figure for you to see - plt.tight_layout() - # make file and save to disk - if not os.path.exists(os.path.join(os.getcwd(), dir_path)): - os.mkdir(dir_path) - filename = name_x + "_vs_" + name_y + ".png" if name_x != "" else name_y + ".png" - fig.savefig(os.path.join(dir_path, filename)) - plt.close(fig) - - -def plot_diff( - subA, - subB, - units="", - name_A="A", - name_B="B", - trim=(0, 0), - lines=False, - colour="r", - dir_path="results", -): - # trim the starts and end of data - trim_start, trim_end = trim - max_size = min(len(subA), len(subB)) - subA = subA[trim_start : max_size - trim_end] - subB = subB[trim_start : max_size - trim_end] - - # create a figure that is 6in x 6in - fig = plt.figure() - - # the axis limits and grid lines - plt.grid(True) - - units_str = " (" + units + ")" if units != "" else "" - trim_str = " [" + str(trim_start) + ", " + str(trim_end) + "]" - - # label your graph, axes, and ticks on each axis - plt.xlabel("Points", fontsize=16) - plt.ylabel("Difference" + units_str, fontsize=16) - plt.xticks() - plt.yticks() - plt.tick_params(labelsize=15) - plt.title("Difference (" + name_A + " - " + name_B + ")" + trim_str, fontsize=18) - - # generate data - x_data = np.arange(len(subA)) - y_data = subA - subB - plt.plot(x_data, y_data, colour + "o") - if lines: - plt.plot(x_data, y_data, color=colour, linewidth=1) - - # complete the layout, save figure, and show the figure for you to see - plt.tight_layout() - - # make file and save to disk - if not os.path.exists(os.path.join(os.getcwd(), dir_path)): - os.mkdir(dir_path) - filename = name_A + "_minus_" + name_B + ".png" - fig.savefig(os.path.join(dir_path, filename)) - plt.close(fig) - - -def plot_alone( - data, units="", name="Y", trim=(0, 0), lines=False, colour="r", dir_path="results" -): - x_values = np.arange(len(data)) - plot_versus( - x_values, - data, - units=units, - name_x="", - name_y=name, - trim=trim, - lines=lines, - colour=colour, - dir_path=dir_path, - ) - - -def read_from_file(datadir, name, delimiter=" "): - filename = name + ".txt" # TODO: arbitrary filetypes - if not os.path.exists(os.path.join(os.getcwd(), datadir)): - print("ERROR: could not find", datadir, "in cwd") - os._exit(1) - filepath = os.path.join(os.getcwd(), datadir, filename) - with open(filepath, "r") as file: - return np.loadtxt(file, delimiter=delimiter) - - -def framerates(data, name="", trim=(0, 0), dir_path="results"): - trim_start, trim_end = trim - diffs = np.diff(data[trim_start : len(data) - trim_end]) - avg_frametime = np.average(diffs) - median_frametime = np.median(diffs) - avg_framerate = 1 / avg_frametime - median_framerate = 1 / median_frametime - print("Average " + name + " framerate:", avg_framerate, "fps") - print("Median " + name + " framerate:", median_framerate, "fps") - plot_alone(diffs, name="diff_" + name, trim=trim, dir_path=dir_path) - - -def sr_no_carla(folder="without_carla", delimiter=" "): - output_path = os.path.join("results", folder) - datadir = os.path.join(os.getcwd(), "data", "no_carla") - ue4 = read_from_file(datadir, "ue4", delimiter=delimiter) - sranipal = read_from_file(datadir, "sranipal", delimiter=delimiter) - frameseq = read_from_file(datadir, "frameseq", delimiter=delimiter) - assert len(ue4) == len(sranipal) and len(sranipal) == len(frameseq) - # plot ue4 (x) vs sranipal (y) - plot_versus( - ue4, sranipal, units="s", name_x="ue4", name_y="sranipal", dir_path=output_path - ) - # plot ue4 - sranipal on the y - plot_diff( - ue4, - sranipal, - units="s", - name_A="ue4", - name_B="sranipal", - trim=(5, 0), - dir_path=output_path, - ) - # plot framseq on the y - plot_alone(frameseq, name="frameseq", dir_path=output_path) - # plot ue4 (x) vs frameseq (y) - plot_versus( - ue4, - frameseq, - name_x="ue4", - name_y="frameseq", - trim=(5, 0), - dir_path=output_path, - ) - # plot framerate of frameseq over time - frameseq_fps = np.diff(frameseq) / np.diff(ue4) - plot_alone(frameseq_fps, name="frameseq_fps", dir_path=output_path) - - """Derivatives""" - # plot differences between sranipal points - framerates(sranipal, name="sranipal", trim=(0, 10), dir_path=output_path) - # plot differences between ue4 points - framerates(ue4, name="ue4", trim=(10, 10), dir_path=output_path) - # plot differences between frameseq points - framerates(frameseq, name="frameseq", trim=(10, 10), dir_path=output_path) - """Metadata""" - total_time = ue4[-1] - ue4[0] - num_sr_frames = frameseq[-1] - frameseq[0] - frameseq_framerate = num_sr_frames / total_time - print("Total test duration (s):", total_time) - print("Frameseq framerates:", frameseq_framerate) - - -def sr_with_carla(data_folders=[], output_folder="with_carla", delimiter=", "): - output_path = os.path.join("results", output_folder) - if not os.path.exists(os.path.join(os.getcwd(), output_path)): - os.mkdir(output_path) - for folder in data_folders: - print("\nFound data folder", folder) - specific_output_path = os.path.join(output_path, folder) - datadir = os.path.join(os.getcwd(), "..", "data", folder) - carla = read_from_file(datadir, "carla", delimiter=delimiter) - sranipal = read_from_file(datadir, "sranipal", delimiter=delimiter) - carla_stream = read_from_file(datadir, "carla_stream", delimiter=delimiter) - frameseq = read_from_file(datadir, "frame_seq", delimiter=delimiter) - # ensure all lengths are the same - max_len = min(len(carla), len(sranipal), len(carla_stream), len(frameseq)) - carla = carla[:max_len] - sranipal = sranipal[:max_len] - carla_stream = carla_stream[:max_len] - frameseq = frameseq[:max_len] - - # plot carla (x) vs sranipal (y) - plot_versus( - carla, - sranipal, - units="s", - name_x="carla", - name_y="sranipal", - dir_path=specific_output_path, - ) - # plot carla - sranipal on the y - plot_diff( - carla, - sranipal, - units="s", - name_A="carla", - name_B="sranipal", - trim=(5, 0), - dir_path=specific_output_path, - ) - # plot carla stream on the y - plot_alone(carla_stream, name="carla_stream", dir_path=specific_output_path) - # plot carla (x) vs carla_stream (y) - plot_versus( - carla, - carla_stream, - name_x="carla", - name_y="carla_stream", - trim=(5, 0), - dir_path=specific_output_path, - ) - # plot framseq on the y - plot_alone(frameseq, name="frame_seq", dir_path=specific_output_path) - # plot ue4 (x) vs frameseq (y) - plot_versus( - carla, - frameseq, - name_x="carla", - name_y="frame_seq", - trim=(5, 0), - dir_path=specific_output_path, - ) - # plot framerate of frameseq over time - frameseq_fps = np.diff(frameseq) / np.diff(carla) - plot_alone(frameseq_fps, name="frameseq_fps", dir_path=specific_output_path) - """Derivatives""" - # plot differences between sranipal points - framerates( - sranipal, name="sranipal", trim=(0, 10), dir_path=specific_output_path - ) - # plot differences between carla points - framerates(carla, name="carla", trim=(10, 10), dir_path=specific_output_path) - # plot differences between carla_stream points - framerates( - carla_stream, - name="carla_stream", - trim=(10, 10), - dir_path=specific_output_path, - ) - # plot differences between frameseq points - framerates( - frameseq, name="frame_seq", trim=(10, 10), dir_path=specific_output_path - ) - """Metadata""" - # plot framerates wrt carla_stream (time between tick and stream) - plot_alone( - 1 / np.diff(carla_stream), - name="fps_carla_stream", - dir_path=specific_output_path, - ) - # plot framerates wrt sranipal time (time between tick and stream) - plot_alone( - 1 / np.diff(sranipal), name="fps_sranipal", dir_path=specific_output_path - ) - # plot framerates wrt carla time (time between tick and stream) - plot_alone(1 / np.diff(carla), name="fps_carla", dir_path=specific_output_path) - - total_time = carla[-1] - carla[0] # same as sranipal time - num_sr_frames = frameseq[-1] - frameseq[0] - frameseq_framerate = num_sr_frames / total_time - print("Total test duration (s):", total_time) - print("Frameseq framerates:", frameseq_framerate) - +import numpy as np +import os +import matplotlib.pyplot as plt +import matplotlib as mpl + +mpl.use("Agg") + +"""IMPORTANT""" +# NOTE: this script assumes it is run in DReyeVR/Diagnostics/python + + +def plot_versus( + data_x, + data_y, + units="", + name_x="X", + name_y="Y", + trim=(0, 0), + lines=False, + colour="r", + dir_path="results", +): + # trim the starts and end of data + trim_start, trim_end = trim + max_size = min(len(data_x), len(data_y)) + data_x = data_x[trim_start : max_size - trim_end] + data_y = data_y[trim_start : max_size - trim_end] + + # create a figure that is 6in x 6in + fig = plt.figure() + + # the axis limits and grid lines + plt.grid(True) + + units_str = " (" + units + ")" if units != "" else "" + trim_str = " [" + str(trim_start) + ", " + str(trim_end) + "]" + + # label your graph, axes, and ticks on each axis + plt.xlabel(name_x + units_str, fontsize=16) + plt.ylabel(name_y + units_str, fontsize=16) + plt.xticks() + plt.yticks() + plt.tick_params(labelsize=15) + if name_x == "": + plt.title(name_y + trim_str, fontsize=18) + else: + plt.title(name_x + " versus " + name_y + trim_str, fontsize=18) + + # plot dots + plt.plot(data_x, data_y, colour + "o") + if lines: + plt.plot(data_x, data_y, color=colour, linewidth=1) + + # complete the layout, save figure, and show the figure for you to see + plt.tight_layout() + # make file and save to disk + if not os.path.exists(os.path.join(os.getcwd(), dir_path)): + os.mkdir(dir_path) + filename = name_x + "_vs_" + name_y + ".png" if name_x != "" else name_y + ".png" + fig.savefig(os.path.join(dir_path, filename)) + plt.close(fig) + + +def plot_diff( + subA, + subB, + units="", + name_A="A", + name_B="B", + trim=(0, 0), + lines=False, + colour="r", + dir_path="results", +): + # trim the starts and end of data + trim_start, trim_end = trim + max_size = min(len(subA), len(subB)) + subA = subA[trim_start : max_size - trim_end] + subB = subB[trim_start : max_size - trim_end] + + # create a figure that is 6in x 6in + fig = plt.figure() + + # the axis limits and grid lines + plt.grid(True) + + units_str = " (" + units + ")" if units != "" else "" + trim_str = " [" + str(trim_start) + ", " + str(trim_end) + "]" + + # label your graph, axes, and ticks on each axis + plt.xlabel("Points", fontsize=16) + plt.ylabel("Difference" + units_str, fontsize=16) + plt.xticks() + plt.yticks() + plt.tick_params(labelsize=15) + plt.title("Difference (" + name_A + " - " + name_B + ")" + trim_str, fontsize=18) + + # generate data + x_data = np.arange(len(subA)) + y_data = subA - subB + plt.plot(x_data, y_data, colour + "o") + if lines: + plt.plot(x_data, y_data, color=colour, linewidth=1) + + # complete the layout, save figure, and show the figure for you to see + plt.tight_layout() + + # make file and save to disk + if not os.path.exists(os.path.join(os.getcwd(), dir_path)): + os.mkdir(dir_path) + filename = name_A + "_minus_" + name_B + ".png" + fig.savefig(os.path.join(dir_path, filename)) + plt.close(fig) + + +def plot_alone( + data, units="", name="Y", trim=(0, 0), lines=False, colour="r", dir_path="results" +): + x_values = np.arange(len(data)) + plot_versus( + x_values, + data, + units=units, + name_x="", + name_y=name, + trim=trim, + lines=lines, + colour=colour, + dir_path=dir_path, + ) + + +def read_from_file(datadir, name, delimiter=" "): + filename = name + ".txt" # TODO: arbitrary filetypes + if not os.path.exists(os.path.join(os.getcwd(), datadir)): + print("ERROR: could not find", datadir, "in cwd") + os._exit(1) + filepath = os.path.join(os.getcwd(), datadir, filename) + with open(filepath, "r") as file: + return np.loadtxt(file, delimiter=delimiter) + + +def framerates(data, name="", trim=(0, 0), dir_path="results"): + trim_start, trim_end = trim + diffs = np.diff(data[trim_start : len(data) - trim_end]) + avg_frametime = np.average(diffs) + median_frametime = np.median(diffs) + avg_framerate = 1 / avg_frametime + median_framerate = 1 / median_frametime + print("Average " + name + " framerate:", avg_framerate, "fps") + print("Median " + name + " framerate:", median_framerate, "fps") + plot_alone(diffs, name="diff_" + name, trim=trim, dir_path=dir_path) + + +def sr_no_carla(folder="without_carla", delimiter=" "): + output_path = os.path.join("results", folder) + datadir = os.path.join(os.getcwd(), "data", "no_carla") + ue4 = read_from_file(datadir, "ue4", delimiter=delimiter) + sranipal = read_from_file(datadir, "sranipal", delimiter=delimiter) + frameseq = read_from_file(datadir, "frameseq", delimiter=delimiter) + assert len(ue4) == len(sranipal) and len(sranipal) == len(frameseq) + # plot ue4 (x) vs sranipal (y) + plot_versus( + ue4, sranipal, units="s", name_x="ue4", name_y="sranipal", dir_path=output_path + ) + # plot ue4 - sranipal on the y + plot_diff( + ue4, + sranipal, + units="s", + name_A="ue4", + name_B="sranipal", + trim=(5, 0), + dir_path=output_path, + ) + # plot framseq on the y + plot_alone(frameseq, name="frameseq", dir_path=output_path) + # plot ue4 (x) vs frameseq (y) + plot_versus( + ue4, + frameseq, + name_x="ue4", + name_y="frameseq", + trim=(5, 0), + dir_path=output_path, + ) + # plot framerate of frameseq over time + frameseq_fps = np.diff(frameseq) / np.diff(ue4) + plot_alone(frameseq_fps, name="frameseq_fps", dir_path=output_path) + + """Derivatives""" + # plot differences between sranipal points + framerates(sranipal, name="sranipal", trim=(0, 10), dir_path=output_path) + # plot differences between ue4 points + framerates(ue4, name="ue4", trim=(10, 10), dir_path=output_path) + # plot differences between frameseq points + framerates(frameseq, name="frameseq", trim=(10, 10), dir_path=output_path) + """Metadata""" + total_time = ue4[-1] - ue4[0] + num_sr_frames = frameseq[-1] - frameseq[0] + frameseq_framerate = num_sr_frames / total_time + print("Total test duration (s):", total_time) + print("Frameseq framerates:", frameseq_framerate) + + +def sr_with_carla(data_folders=[], output_folder="with_carla", delimiter=", "): + output_path = os.path.join("results", output_folder) + if not os.path.exists(os.path.join(os.getcwd(), output_path)): + os.mkdir(output_path) + for folder in data_folders: + print("\nFound data folder", folder) + specific_output_path = os.path.join(output_path, folder) + datadir = os.path.join(os.getcwd(), "..", "data", folder) + carla = read_from_file(datadir, "carla", delimiter=delimiter) + sranipal = read_from_file(datadir, "sranipal", delimiter=delimiter) + carla_stream = read_from_file(datadir, "carla_stream", delimiter=delimiter) + frameseq = read_from_file(datadir, "frame_seq", delimiter=delimiter) + # ensure all lengths are the same + max_len = min(len(carla), len(sranipal), len(carla_stream), len(frameseq)) + carla = carla[:max_len] + sranipal = sranipal[:max_len] + carla_stream = carla_stream[:max_len] + frameseq = frameseq[:max_len] + + # plot carla (x) vs sranipal (y) + plot_versus( + carla, + sranipal, + units="s", + name_x="carla", + name_y="sranipal", + dir_path=specific_output_path, + ) + # plot carla - sranipal on the y + plot_diff( + carla, + sranipal, + units="s", + name_A="carla", + name_B="sranipal", + trim=(5, 0), + dir_path=specific_output_path, + ) + # plot carla stream on the y + plot_alone(carla_stream, name="carla_stream", dir_path=specific_output_path) + # plot carla (x) vs carla_stream (y) + plot_versus( + carla, + carla_stream, + name_x="carla", + name_y="carla_stream", + trim=(5, 0), + dir_path=specific_output_path, + ) + # plot framseq on the y + plot_alone(frameseq, name="frame_seq", dir_path=specific_output_path) + # plot ue4 (x) vs frameseq (y) + plot_versus( + carla, + frameseq, + name_x="carla", + name_y="frame_seq", + trim=(5, 0), + dir_path=specific_output_path, + ) + # plot framerate of frameseq over time + frameseq_fps = np.diff(frameseq) / np.diff(carla) + plot_alone(frameseq_fps, name="frameseq_fps", dir_path=specific_output_path) + """Derivatives""" + # plot differences between sranipal points + framerates( + sranipal, name="sranipal", trim=(0, 10), dir_path=specific_output_path + ) + # plot differences between carla points + framerates(carla, name="carla", trim=(10, 10), dir_path=specific_output_path) + # plot differences between carla_stream points + framerates( + carla_stream, + name="carla_stream", + trim=(10, 10), + dir_path=specific_output_path, + ) + # plot differences between frameseq points + framerates( + frameseq, name="frame_seq", trim=(10, 10), dir_path=specific_output_path + ) + """Metadata""" + # plot framerates wrt carla_stream (time between tick and stream) + plot_alone( + 1 / np.diff(carla_stream), + name="fps_carla_stream", + dir_path=specific_output_path, + ) + # plot framerates wrt sranipal time (time between tick and stream) + plot_alone( + 1 / np.diff(sranipal), name="fps_sranipal", dir_path=specific_output_path + ) + # plot framerates wrt carla time (time between tick and stream) + plot_alone(1 / np.diff(carla), name="fps_carla", dir_path=specific_output_path) + + total_time = carla[-1] - carla[0] # same as sranipal time + num_sr_frames = frameseq[-1] - frameseq[0] + frameseq_framerate = num_sr_frames / total_time + print("Total test duration (s):", total_time) + print("Frameseq framerates:", frameseq_framerate) + diff --git a/Tools/Diagnostics/python/graph_sys_diagnostics.py b/Tools/Diagnostics/python/graph_sys_diagnostics.py index e33a22f..c30f3c4 100755 --- a/Tools/Diagnostics/python/graph_sys_diagnostics.py +++ b/Tools/Diagnostics/python/graph_sys_diagnostics.py @@ -1,211 +1,211 @@ -import argparse -import numpy as np -import os -import matplotlib.pyplot as plt -import matplotlib as mpl -import pandas -mpl.use('Agg') - -"""IMPORTANT""" -# NOTE: this script assumes it is run in DReyeVR/Diagnostics/ -assert("Diagnostics" in os.getcwd()) - - -def plot_many_versus(data_x, data_ys, units="", name_x="X", name_y="Y", - trim=(0, 0), points=True, lines=False, - colours=["r", "g", "b", "c", "m", "y", "k"], xbounds=None, - ybounds=None, dir_path="results", t_carla=(None, None)): - # trim the starts and end of data - trim_start, trim_end = trim - - max_len = min(len(data_x), len(data_ys[0])) - data_x = data_x[trim_start:max_len - trim_end] - for data_y in data_ys: - data_y = data_y[trim_start:max_len - trim_end] - - # create a figure that is 6in x 6in - fig = plt.figure() - - # the axis limits and grid lines - plt.grid(True) - - units_str = " (" + units + ")" if units != "" else "" - trim_str = " [" + str(trim_start) + ", " + str(trim_end) + "]" - - # label your graph, axes, and ticks on each axis - plt.xlabel(name_x + units_str, fontsize=16) - plt.ylabel(name_y + units_str, fontsize=16) - if ybounds: - plt.ylim(ybounds) - if xbounds: - plt.xlim(xbounds) - plt.xticks() - plt.yticks() - plt.tick_params(labelsize=15) - if(name_x == ""): - plt.title(name_y + trim_str, fontsize=18) - else: - plt.title(name_x + " versus " + name_y + trim_str, fontsize=18) - - # plot data - for i in range(len(data_ys)): - data_y = data_ys[i] - colour = colours[i % len(colours)] - if points: - plt.plot(data_x, data_y, colour + "o") - if lines: - plt.plot(data_x, data_y, color=colour, linewidth=1) - - # add lines for carla starting/ending - t_carla_start, t_carla_end = t_carla - - # plot time when carla starts - if(t_carla_start is not None): - y = np.arange(int(np.max(data_ys)) + 5) - x = np.ones_like(y) * t_carla_start - plt.plot(x, y, color='c', linewidth=1) - - # plot time when carla starts - if(t_carla_end is not None): - y = np.arange(np.max(data_ys) + 5) - x = np.ones_like(y) * t_carla_end - plt.plot(x, y, color='c', linewidth=1) - - # complete the layout, save figure, and show the figure for you to see - plt.tight_layout() - # make file and save to disk - if not os.path.exists(os.path.join(os.getcwd(), dir_path)): - os.makedirs(dir_path, exist_ok=True) - filename = name_x + "_vs_" + name_y + '.png' if name_x != "" else name_y + ".png" - fig.savefig(os.path.join(dir_path, filename)) - plt.close(fig) - print("Plotted", filename) - - -def read_from_file(datadir, filename): - print("Looking for", filename) - if not os.path.exists(os.path.join(os.getcwd(), datadir)): - print("ERROR: could not find", datadir, "in cwd") - os._exit(1) - filepath = os.path.join(os.getcwd(), datadir, filename) - with open(filepath, "r") as file: - # the command 'collectl -sCm -oT -P -i 0.5 --sep ","' prints - # and if closed via ctrl+C, outputs "Ouch!" at the end - # simple fix: skip first line (header) and last line (footer) - df = pandas.read_csv(file, skipfooter=1, engine='python') - print("Successfully found and parsed", filename) - return df - - -def convert_to_seconds(data_str): - arr = [] - for x in data_str: - (h, m, s) = x.split(':') - t = int(h) * (60*60) + int(m) * 60 + float(s) - arr.append(t) - return np.array(arr) - - -def get_cpu_data_from(df, bounds): - start, end = bounds - cpus = [] - for i in range(start, end, 1): - cpu_str = "[CPU:" + str(i) + "]Totl%" - cpus.append(df[cpu_str].to_numpy()) - return cpus - - -def main(sys_data_df, dir_path): - # get system time - sys_time = sys_data_df["Time"].to_numpy() - sys_time = convert_to_seconds(sys_time) - - # get cpu usages - cpu_usages = get_cpu_data_from(sys_data_df, (0, 7)) - - time = sys_time - sys_time[0] # zero out (relative time) - - # time when carla started/ended, the run_collectl.sh makes entire columns for these - t_start_str = sys_data_df["[CARLA]t_start"].to_numpy()[0] - t_end_str = sys_data_df["[CARLA]t_end"].to_numpy()[0] - - t_carla_start = convert_to_seconds([t_start_str])[0] - sys_time[0] - t_carla_end = convert_to_seconds([t_end_str])[0] - sys_time[0] - - t_carla = (t_carla_start, t_carla_end) - - average_cpu = np.mean(cpu_usages, axis=0) - - # plot carla fps - carla_fps = sys_data_df["[CARLA]Fps"].to_numpy() - carla_fps = carla_fps[~np.isnan(carla_fps)] # strip away the np.nan's - - # pad the carla fps data to start when the t_carla_end occurs - start_pads = len(time) - len(carla_fps) - len(time[time > t_carla_end]) - carla_fps = np.pad(carla_fps, (start_pads, 0), - 'constant', constant_values=0) - plot_many_versus(time, [carla_fps], name_x="time", - name_y="fps", dir_path=dir_path, - lines=True, points=False, - t_carla=t_carla) - - # plot individual core usage - plot_many_versus(time, cpu_usages, name_x="time", - name_y="cores", dir_path=dir_path, - lines=True, points=False, - t_carla=t_carla) - - # plot cpu average - plot_many_versus(time, [average_cpu], name_x="time", - name_y="avg_cpu", dir_path=dir_path, - lines=True, points=False, t_carla=t_carla) - - # plot memory usage - mem_usage = sys_data_df["[MEM]Used"].to_numpy() / 1000000 - #sys_data_df["[MEM]Tot"].to_numpy() - sys_data_df["[MEM]Free"].to_numpy() - plot_many_versus(time, [mem_usage], name_x="time", - name_y="mem_usage", dir_path=dir_path, - lines=True, points=False, t_carla=t_carla) - - # plot gpu usage - gpu_usage = sys_data_df["[NVIDIA]Gpu"].to_numpy() - plot_many_versus(time, [gpu_usage], name_x="time", - name_y="gpu_usage", dir_path=dir_path, - lines=True, points=False, t_carla=t_carla) - - # plot gpu memory - gpu_memory = sys_data_df["[NVIDIA]Mem"].to_numpy() - plot_many_versus(time, [gpu_memory], name_x="time", - name_y="gpu_memory", dir_path=dir_path, - lines=True, points=False, t_carla=t_carla) - print("Successfully plotted everything to", dir_path) - - -def get_from_data(data_folder, filename): - datadir = os.path.join(os.getcwd(), "data", data_folder) - - # output directory - dir_path = os.path.join(os.getcwd(), "results", data_folder) - - # read from csv - sys_data_df = read_from_file(datadir, filename) - return sys_data_df, dir_path - - -if __name__ == '__main__': - print("\nPlotting data:\n") - argparser = argparse.ArgumentParser(description=__doc__) - argparser.add_argument( - '-d', '--dir', - metavar='D', - default="collectl", # cwd - type=str, - help='data directory name for outputs') - args = argparser.parse_args() - data_folder = args.dir - output_path = os.path.join("results") - - sys_data_df, dir_path = get_from_data(data_folder=data_folder, - filename="combined.csv") - - main(sys_data_df, dir_path) +import argparse +import numpy as np +import os +import matplotlib.pyplot as plt +import matplotlib as mpl +import pandas +mpl.use('Agg') + +"""IMPORTANT""" +# NOTE: this script assumes it is run in DReyeVR/Diagnostics/ +assert("Diagnostics" in os.getcwd()) + + +def plot_many_versus(data_x, data_ys, units="", name_x="X", name_y="Y", + trim=(0, 0), points=True, lines=False, + colours=["r", "g", "b", "c", "m", "y", "k"], xbounds=None, + ybounds=None, dir_path="results", t_carla=(None, None)): + # trim the starts and end of data + trim_start, trim_end = trim + + max_len = min(len(data_x), len(data_ys[0])) + data_x = data_x[trim_start:max_len - trim_end] + for data_y in data_ys: + data_y = data_y[trim_start:max_len - trim_end] + + # create a figure that is 6in x 6in + fig = plt.figure() + + # the axis limits and grid lines + plt.grid(True) + + units_str = " (" + units + ")" if units != "" else "" + trim_str = " [" + str(trim_start) + ", " + str(trim_end) + "]" + + # label your graph, axes, and ticks on each axis + plt.xlabel(name_x + units_str, fontsize=16) + plt.ylabel(name_y + units_str, fontsize=16) + if ybounds: + plt.ylim(ybounds) + if xbounds: + plt.xlim(xbounds) + plt.xticks() + plt.yticks() + plt.tick_params(labelsize=15) + if(name_x == ""): + plt.title(name_y + trim_str, fontsize=18) + else: + plt.title(name_x + " versus " + name_y + trim_str, fontsize=18) + + # plot data + for i in range(len(data_ys)): + data_y = data_ys[i] + colour = colours[i % len(colours)] + if points: + plt.plot(data_x, data_y, colour + "o") + if lines: + plt.plot(data_x, data_y, color=colour, linewidth=1) + + # add lines for carla starting/ending + t_carla_start, t_carla_end = t_carla + + # plot time when carla starts + if(t_carla_start is not None): + y = np.arange(int(np.max(data_ys)) + 5) + x = np.ones_like(y) * t_carla_start + plt.plot(x, y, color='c', linewidth=1) + + # plot time when carla starts + if(t_carla_end is not None): + y = np.arange(np.max(data_ys) + 5) + x = np.ones_like(y) * t_carla_end + plt.plot(x, y, color='c', linewidth=1) + + # complete the layout, save figure, and show the figure for you to see + plt.tight_layout() + # make file and save to disk + if not os.path.exists(os.path.join(os.getcwd(), dir_path)): + os.makedirs(dir_path, exist_ok=True) + filename = name_x + "_vs_" + name_y + '.png' if name_x != "" else name_y + ".png" + fig.savefig(os.path.join(dir_path, filename)) + plt.close(fig) + print("Plotted", filename) + + +def read_from_file(datadir, filename): + print("Looking for", filename) + if not os.path.exists(os.path.join(os.getcwd(), datadir)): + print("ERROR: could not find", datadir, "in cwd") + os._exit(1) + filepath = os.path.join(os.getcwd(), datadir, filename) + with open(filepath, "r") as file: + # the command 'collectl -sCm -oT -P -i 0.5 --sep ","' prints + # and if closed via ctrl+C, outputs "Ouch!" at the end + # simple fix: skip first line (header) and last line (footer) + df = pandas.read_csv(file, skipfooter=1, engine='python') + print("Successfully found and parsed", filename) + return df + + +def convert_to_seconds(data_str): + arr = [] + for x in data_str: + (h, m, s) = x.split(':') + t = int(h) * (60*60) + int(m) * 60 + float(s) + arr.append(t) + return np.array(arr) + + +def get_cpu_data_from(df, bounds): + start, end = bounds + cpus = [] + for i in range(start, end, 1): + cpu_str = "[CPU:" + str(i) + "]Totl%" + cpus.append(df[cpu_str].to_numpy()) + return cpus + + +def main(sys_data_df, dir_path): + # get system time + sys_time = sys_data_df["Time"].to_numpy() + sys_time = convert_to_seconds(sys_time) + + # get cpu usages + cpu_usages = get_cpu_data_from(sys_data_df, (0, 7)) + + time = sys_time - sys_time[0] # zero out (relative time) + + # time when carla started/ended, the run_collectl.sh makes entire columns for these + t_start_str = sys_data_df["[CARLA]t_start"].to_numpy()[0] + t_end_str = sys_data_df["[CARLA]t_end"].to_numpy()[0] + + t_carla_start = convert_to_seconds([t_start_str])[0] - sys_time[0] + t_carla_end = convert_to_seconds([t_end_str])[0] - sys_time[0] + + t_carla = (t_carla_start, t_carla_end) + + average_cpu = np.mean(cpu_usages, axis=0) + + # plot carla fps + carla_fps = sys_data_df["[CARLA]Fps"].to_numpy() + carla_fps = carla_fps[~np.isnan(carla_fps)] # strip away the np.nan's + + # pad the carla fps data to start when the t_carla_end occurs + start_pads = len(time) - len(carla_fps) - len(time[time > t_carla_end]) + carla_fps = np.pad(carla_fps, (start_pads, 0), + 'constant', constant_values=0) + plot_many_versus(time, [carla_fps], name_x="time", + name_y="fps", dir_path=dir_path, + lines=True, points=False, + t_carla=t_carla) + + # plot individual core usage + plot_many_versus(time, cpu_usages, name_x="time", + name_y="cores", dir_path=dir_path, + lines=True, points=False, + t_carla=t_carla) + + # plot cpu average + plot_many_versus(time, [average_cpu], name_x="time", + name_y="avg_cpu", dir_path=dir_path, + lines=True, points=False, t_carla=t_carla) + + # plot memory usage + mem_usage = sys_data_df["[MEM]Used"].to_numpy() / 1000000 + #sys_data_df["[MEM]Tot"].to_numpy() - sys_data_df["[MEM]Free"].to_numpy() + plot_many_versus(time, [mem_usage], name_x="time", + name_y="mem_usage", dir_path=dir_path, + lines=True, points=False, t_carla=t_carla) + + # plot gpu usage + gpu_usage = sys_data_df["[NVIDIA]Gpu"].to_numpy() + plot_many_versus(time, [gpu_usage], name_x="time", + name_y="gpu_usage", dir_path=dir_path, + lines=True, points=False, t_carla=t_carla) + + # plot gpu memory + gpu_memory = sys_data_df["[NVIDIA]Mem"].to_numpy() + plot_many_versus(time, [gpu_memory], name_x="time", + name_y="gpu_memory", dir_path=dir_path, + lines=True, points=False, t_carla=t_carla) + print("Successfully plotted everything to", dir_path) + + +def get_from_data(data_folder, filename): + datadir = os.path.join(os.getcwd(), "data", data_folder) + + # output directory + dir_path = os.path.join(os.getcwd(), "results", data_folder) + + # read from csv + sys_data_df = read_from_file(datadir, filename) + return sys_data_df, dir_path + + +if __name__ == '__main__': + print("\nPlotting data:\n") + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + '-d', '--dir', + metavar='D', + default="collectl", # cwd + type=str, + help='data directory name for outputs') + args = argparser.parse_args() + data_folder = args.dir + output_path = os.path.join("results") + + sys_data_df, dir_path = get_from_data(data_folder=data_folder, + filename="combined.csv") + + main(sys_data_df, dir_path) diff --git a/Tools/Diagnostics/python/stat_carla.py b/Tools/Diagnostics/python/stat_carla.py index 1756b69..0c56f42 100755 --- a/Tools/Diagnostics/python/stat_carla.py +++ b/Tools/Diagnostics/python/stat_carla.py @@ -1,194 +1,194 @@ -#!/usr/bin/env python - -import argparse -import numpy as np -import csv -import time -import sys -import glob -import os -import matplotlib.pyplot as plt -import datetime - - -"""IMPORTANT""" -# NOTE: this script assumes it is run in Diagnostics/python/ -# So it does NOT need to be in carla's PythonAPI, but it DOES need -# the CARLA_DIR (-c, --carladir) environment variable to be set - - -def save_to_file(data, dir_path, filename, suffix=""): - assert os.path.exists(dir_path) - filename = f"{filename}{suffix}.csv" - filepath = os.path.join(os.getcwd(), dir_path, filename) - print(f"saving data to: {filepath}") - mode = "w" if os.path.exists(filepath) else "w+" - with open(filepath, mode) as f: - csv_writer = csv.writer(f) - csv_writer.writerow(data.keys()) - # writes ordered - csv_writer.writerows(zip(*[data[key] for key in data.keys()])) - # csv_writer.writerows(zip(*data.values())) # unordered - - -def plot( - x, - y, - title, - title_x="", - title_y="", - trim=(0, 0), - out_dir="graphs", - show_mean=True, - colour="r", - lines=True, - suffix="", -): - max_len = min(len(x), len(y)) - x = np.array(x[trim[0] : max_len - trim[1]]) - y = np.array(y[trim[0] : max_len - trim[1]]) - - fig = plt.figure() - plt.grid(True) - plt.xlabel(title_x, fontsize=16) - plt.ylabel(title_y, fontsize=16) - plt.xticks() - plt.yticks() - plt.tick_params(labelsize=15) - mean_str = f", mean: {np.mean(y):.3f}" if show_mean else "" - graph_title = f"{title}{mean_str}" - plt.title(graph_title, fontsize=18) - plt.plot(x, y, colour + "o") - if lines: - plt.plot(x, y, color=colour, linewidth=1) - plt.tight_layout() - os.makedirs(out_dir, exist_ok=True) - filename = (f"{title}{suffix}.jpg").replace(" ", "_") # no spaces! - filepath = os.path.join(os.getcwd(), out_dir, filename) - print(f"Saving graph to: {filepath}") - fig.savefig(filepath) - plt.close(fig) - - -def main(): - argparser = argparse.ArgumentParser(description=__doc__) - argparser.add_argument( - "-c", - "--carladir", - metavar="C", - default="", # cwd - type=str, - help="Directory for Carla", - ) - argparser.add_argument( - "--host", - metavar="H", - default="127.0.0.1", - help="IP of the host server (default: 127.0.0.1)", - ) - argparser.add_argument( - "-p", - "--port", - metavar="P", - default=2000, - type=int, - help="TCP port to listen to (default: 2000)", - ) - argparser.add_argument( - "-d", - "--dir", - metavar="D", - default="data", # cwd - type=str, - help="data directory for outputs", - ) - argparser.add_argument( - "-f", - "--file", - metavar="F", - default="carla_data", - type=str, - help="name of output file", - ) - argparser.add_argument( - "-i", - "--interval", - metavar="I", - default="0.1", # in seconds - type=float, - help="intervals (s) of which to take framerate", - ) - - args = argparser.parse_args() - carla_dir = args.carladir - output_dir = args.dir - py_delay = args.interval - filename = args.file - - os.makedirs(output_dir, exist_ok=True) - - """Import Carla given the Carla Directory""" - if carla_dir == "": - print("Need to pass in the CARLA environment directory!") - exit(1) - - egg_locn = os.path.join(carla_dir, "PythonAPI", "carla", "dist") - print(f"Trying to load python .egg from {egg_locn}") - python_egg = glob.glob(os.path.join(egg_locn, "carla-*.egg")) - try: - # sourcing python egg file - sys.path.append(python_egg[0]) - import carla # works if the python egg file is properly sourced - except Exception as e: - print("Error:", e) - exit(1) - print(f"Success! Continuing with script, pinging every {py_delay:.3f}s") - - client = carla.Client(args.host, args.port) - client.set_timeout(10.0) # should be running already - - world = client.get_world() - data = {} - data["[CARLA]Idx"] = [] - data["[CARLA]Fps"] = [] - - # to get FPS, we can get the world dt and compute the inv - i = 0 - try: - while True: - # seconds=X presents maximum delay to wait for server - delta_t = world.wait_for_tick(seconds=0.5).timestamp.delta_seconds - fps = 1 / delta_t - data["[CARLA]Idx"].append(i) - data["[CARLA]Fps"].append(fps) - # sleep for the interval - time.sleep(py_delay) - i += 1 - print(f"FPS: {fps:.3f}", end="\r") # no flush (slow & expensive) - except KeyboardInterrupt: - print("Stopped by user.") - except RuntimeError: - print("Simulator disconnected.") - finally: # simulator disconnected - ts = time.time() - timestamp = datetime.datetime.fromtimestamp(ts).strftime("%Y-%m-%d-%H-%M-%S") - suffix = f"_{timestamp}" - save_to_file(data, output_dir, filename=filename, suffix=suffix) - plot( - x=data["[CARLA]Idx"], - y=data["[CARLA]Fps"], - title="CARLA FPS", - title_x="", - title_y="fps", - out_dir=output_dir, - show_mean=True, - lines=True, - suffix=suffix, - ) - - -if __name__ == "__main__": - try: - main() - except KeyboardInterrupt: - pass +#!/usr/bin/env python + +import argparse +import numpy as np +import csv +import time +import sys +import glob +import os +import matplotlib.pyplot as plt +import datetime + + +"""IMPORTANT""" +# NOTE: this script assumes it is run in Diagnostics/python/ +# So it does NOT need to be in carla's PythonAPI, but it DOES need +# the CARLA_DIR (-c, --carladir) environment variable to be set + + +def save_to_file(data, dir_path, filename, suffix=""): + assert os.path.exists(dir_path) + filename = f"{filename}{suffix}.csv" + filepath = os.path.join(os.getcwd(), dir_path, filename) + print(f"saving data to: {filepath}") + mode = "w" if os.path.exists(filepath) else "w+" + with open(filepath, mode) as f: + csv_writer = csv.writer(f) + csv_writer.writerow(data.keys()) + # writes ordered + csv_writer.writerows(zip(*[data[key] for key in data.keys()])) + # csv_writer.writerows(zip(*data.values())) # unordered + + +def plot( + x, + y, + title, + title_x="", + title_y="", + trim=(0, 0), + out_dir="graphs", + show_mean=True, + colour="r", + lines=True, + suffix="", +): + max_len = min(len(x), len(y)) + x = np.array(x[trim[0] : max_len - trim[1]]) + y = np.array(y[trim[0] : max_len - trim[1]]) + + fig = plt.figure() + plt.grid(True) + plt.xlabel(title_x, fontsize=16) + plt.ylabel(title_y, fontsize=16) + plt.xticks() + plt.yticks() + plt.tick_params(labelsize=15) + mean_str = f", mean: {np.mean(y):.3f}" if show_mean else "" + graph_title = f"{title}{mean_str}" + plt.title(graph_title, fontsize=18) + plt.plot(x, y, colour + "o") + if lines: + plt.plot(x, y, color=colour, linewidth=1) + plt.tight_layout() + os.makedirs(out_dir, exist_ok=True) + filename = (f"{title}{suffix}.jpg").replace(" ", "_") # no spaces! + filepath = os.path.join(os.getcwd(), out_dir, filename) + print(f"Saving graph to: {filepath}") + fig.savefig(filepath) + plt.close(fig) + + +def main(): + argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument( + "-c", + "--carladir", + metavar="C", + default="", # cwd + type=str, + help="Directory for Carla", + ) + argparser.add_argument( + "--host", + metavar="H", + default="127.0.0.1", + help="IP of the host server (default: 127.0.0.1)", + ) + argparser.add_argument( + "-p", + "--port", + metavar="P", + default=2000, + type=int, + help="TCP port to listen to (default: 2000)", + ) + argparser.add_argument( + "-d", + "--dir", + metavar="D", + default="data", # cwd + type=str, + help="data directory for outputs", + ) + argparser.add_argument( + "-f", + "--file", + metavar="F", + default="carla_data", + type=str, + help="name of output file", + ) + argparser.add_argument( + "-i", + "--interval", + metavar="I", + default="0.1", # in seconds + type=float, + help="intervals (s) of which to take framerate", + ) + + args = argparser.parse_args() + carla_dir = args.carladir + output_dir = args.dir + py_delay = args.interval + filename = args.file + + os.makedirs(output_dir, exist_ok=True) + + """Import Carla given the Carla Directory""" + if carla_dir == "": + print("Need to pass in the CARLA environment directory!") + exit(1) + + egg_locn = os.path.join(carla_dir, "PythonAPI", "carla", "dist") + print(f"Trying to load python .egg from {egg_locn}") + python_egg = glob.glob(os.path.join(egg_locn, "carla-*.egg")) + try: + # sourcing python egg file + sys.path.append(python_egg[0]) + import carla # works if the python egg file is properly sourced + except Exception as e: + print("Error:", e) + exit(1) + print(f"Success! Continuing with script, pinging every {py_delay:.3f}s") + + client = carla.Client(args.host, args.port) + client.set_timeout(10.0) # should be running already + + world = client.get_world() + data = {} + data["[CARLA]Idx"] = [] + data["[CARLA]Fps"] = [] + + # to get FPS, we can get the world dt and compute the inv + i = 0 + try: + while True: + # seconds=X presents maximum delay to wait for server + delta_t = world.wait_for_tick(seconds=0.5).timestamp.delta_seconds + fps = 1 / delta_t + data["[CARLA]Idx"].append(i) + data["[CARLA]Fps"].append(fps) + # sleep for the interval + time.sleep(py_delay) + i += 1 + print(f"FPS: {fps:.3f}", end="\r") # no flush (slow & expensive) + except KeyboardInterrupt: + print("Stopped by user.") + except RuntimeError: + print("Simulator disconnected.") + finally: # simulator disconnected + ts = time.time() + timestamp = datetime.datetime.fromtimestamp(ts).strftime("%Y-%m-%d-%H-%M-%S") + suffix = f"_{timestamp}" + save_to_file(data, output_dir, filename=filename, suffix=suffix) + plot( + x=data["[CARLA]Idx"], + y=data["[CARLA]Fps"], + title="CARLA FPS", + title_x="", + title_y="fps", + out_dir=output_dir, + show_mean=True, + lines=True, + suffix=suffix, + ) + + +if __name__ == "__main__": + try: + main() + except KeyboardInterrupt: + pass diff --git a/Tools/LOD/get_original_LODs.sh b/Tools/LOD/get_original_LODs.sh index a46d8d0..a9f3dd1 100755 --- a/Tools/LOD/get_original_LODs.sh +++ b/Tools/LOD/get_original_LODs.sh @@ -1,36 +1,36 @@ -#!/bin/bash - -OUT=OriginalLODs - -mkdir -p ${OUT} - -PATH_TO_4WHEELED=Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled - -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Toyota_Prius/Vh_Car_ToyotaPrius_Rig.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/AudiA2_/SK_AudiA2.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/BmwGranTourer/SK_BMWGranTourer.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/BmwIsetta/SK_BMWIsetta.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/CarlaCola/SK_CarlaCola.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/DodgeCharger2020/SK_Charger2020.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/DodgeCharger2020/ChargerCop/SK_ChargerCop.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Chevrolet/SK_ChevroletImpala.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Citroen/SK_Citroen_C3.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Jeep/SK_JeepWranglerRubicon.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/LincolnMKZ2020/SK_lincolnv5.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Mercedes/SK_MercedesBenzCoupeC.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/MercedesCCC/SK_MercedesCCC.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/MIni/SK_MiniCooperS.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Mustang/SK_Mustang_OLD.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Nissan_Micra/SK_NissanMicra.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Nissan_Patrol/SK_NissanPatrolST.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Leon/SK_SeatLeon.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/AudiTT/SM_AudiTT_v1.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/DodgeCharge/SM_Charger_v2.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Chevrolet/SM_Chevrolet_v2.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Cybertruck/SM_Cybertruck_v2.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/AudiETron/SM_Etron.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/LincolnMKZ2017/SM_Lincoln_v2.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Mustang/SM_Mustang_v2.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Tesla/SM_TeslaM3_v2.uasset ${OUT} -cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Truck/SM_TestTruck.uasset ${OUT} +#!/bin/bash + +OUT=OriginalLODs + +mkdir -p ${OUT} + +PATH_TO_4WHEELED=Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled + +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Toyota_Prius/Vh_Car_ToyotaPrius_Rig.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/AudiA2_/SK_AudiA2.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/BmwGranTourer/SK_BMWGranTourer.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/BmwIsetta/SK_BMWIsetta.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/CarlaCola/SK_CarlaCola.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/DodgeCharger2020/SK_Charger2020.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/DodgeCharger2020/ChargerCop/SK_ChargerCop.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Chevrolet/SK_ChevroletImpala.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Citroen/SK_Citroen_C3.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Jeep/SK_JeepWranglerRubicon.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/LincolnMKZ2020/SK_lincolnv5.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Mercedes/SK_MercedesBenzCoupeC.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/MercedesCCC/SK_MercedesCCC.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/MIni/SK_MiniCooperS.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Mustang/SK_Mustang_OLD.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Nissan_Micra/SK_NissanMicra.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Nissan_Patrol/SK_NissanPatrolST.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Leon/SK_SeatLeon.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/AudiTT/SM_AudiTT_v1.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/DodgeCharge/SM_Charger_v2.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Chevrolet/SM_Chevrolet_v2.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Cybertruck/SM_Cybertruck_v2.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/AudiETron/SM_Etron.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/LincolnMKZ2017/SM_Lincoln_v2.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Mustang/SM_Mustang_v2.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Tesla/SM_TeslaM3_v2.uasset ${OUT} +cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/Truck/SM_TestTruck.uasset ${OUT} cp ${CARLA_ROOT}/${PATH_TO_4WHEELED}/VolkswagenT2/SM_Van_v2.uasset ${OUT} \ No newline at end of file diff --git a/Tools/LOD/install_LOD.sh b/Tools/LOD/install_LOD.sh index 0098d52..1239ac9 100755 --- a/Tools/LOD/install_LOD.sh +++ b/Tools/LOD/install_LOD.sh @@ -1,92 +1,92 @@ -#!/bin/bash - -DReyeVR_ROOT=$PWD -CARLA_ROOT=$1 -PLATFORM=$2 - -R='\033[0;31m' # Red -G='\033[0;32m' # Green -Y='\033[0;33m' # Yellow -B='\033[0;34m' # Blue -NC='\033[0m' # No Color - -if [ -z "$1" ]; then - echo -e "${R}Enter the location for Carla${NC}" - exit 1 -fi - -if [ -z "$2" ]; then - echo -e "${R}Enter the platform for downloading LODs: One of \"Windows\"/\"Linux\"/\"Original\"${NC}" - exit 1 -fi - -echo -e "\nInstalling custom LOD's for DReyeVR" - -if [ ! -f ${CARLA_ROOT}/CHANGELOG.md ] || [[ `head -n 1 ${CARLA_ROOT}/CHANGELOG.md` != "## CARLA 0.9.13" ]]; then - echo -e "${R}Could not verify a correct Carla 0.9.13 installation${NC}" - exit 1 -else - echo -e "${G}Found a Carla 0.9.13 installation at ${CARLA_ROOT}${NC}" -fi - -LINUX='https://docs.google.com/uc?export=download&id=1OqDOCAflENnXvbJCogBEmRhHQpEF1aKE' -WINDOWS='https://docs.google.com/uc?export=download&id=191tiK25MJ9C7-5Q1-sHt1mp4_EaefjqM' -ORIGINAL='https://docs.google.com/uc?export=download&id=1Vc4e43xZuXOJF_3-r3n3QU-yE5sjiAfw' - -if [ ${PLATFORM} == "Linux" ]; then - CONTENT=${LINUX} - FILENAME="LinuxLODs.zip" -elif [ ${PLATFORM} == "Windows" ]; then - CONTENT=${WINDOWS} - FILENAME="WindowsLODs.zip" -elif [ ${PLATFORM} == "Original" ]; then - CONTENT=${ORIGINAL} - FILENAME="OriginalLODs.zip" -else - echo -e "${R}Could not verify a correct platform (must one of \"Windows\"/\"Linux\"/\"Original\")${NC}" - exit 1 -fi -echo -e "${B}Downloading ${FILENAME} LODs package...${NC}" - -wget -r -nv ${CONTENT} -O ${FILENAME} - -OUT_DIR=${FILENAME::-4} # get rid of .zip - -unzip ${FILENAME} -d ${OUT_DIR} - -echo -e "${B}Copying files from ${OUT_DIR}...${NC}" - -mkdir -p $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DReyeVR/ -cp SM_Vehicle_LODSettings.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DReyeVR/ -# now copy all individual static meshes -# note you can get all the file paths easily in UE4 (with the folderless+filtered mode) right-click -> copy file paths -cp ${OUT_DIR}/Vh_Car_ToyotaPrius_Rig.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Toyota_Prius/ -cp ${OUT_DIR}/SK_AudiA2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiA2_/ -cp ${OUT_DIR}/SK_BMWGranTourer.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwGranTourer/ -cp ${OUT_DIR}/SK_BMWIsetta.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwIsetta/ -cp ${OUT_DIR}/SK_CarlaCola.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/CarlaCola/ -cp ${OUT_DIR}/SK_Charger2020.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/ -cp ${OUT_DIR}/SK_ChargerCop.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/ChargerCop/ -cp ${OUT_DIR}/SK_ChevroletImpala.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/ -cp ${OUT_DIR}/SK_Citroen_C3.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Citroen/ -cp ${OUT_DIR}/SK_JeepWranglerRubicon.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Jeep/ -cp ${OUT_DIR}/SK_lincolnv5.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2020/ -cp ${OUT_DIR}/SK_MercedesBenzCoupeC.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mercedes/ -cp ${OUT_DIR}/SK_MercedesCCC.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MercedesCCC/ -cp ${OUT_DIR}/SK_MiniCooperS.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MIni/ -cp ${OUT_DIR}/SK_Mustang_OLD.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/ -cp ${OUT_DIR}/SK_NissanMicra.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Micra/ -cp ${OUT_DIR}/SK_NissanPatrolST.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Patrol/ -cp ${OUT_DIR}/SK_SeatLeon.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Leon/ -cp ${OUT_DIR}/SM_AudiTT_v1.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiTT/ -cp ${OUT_DIR}/SM_Charger_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharge/ -cp ${OUT_DIR}/SM_Chevrolet_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/ -cp ${OUT_DIR}/SM_Cybertruck_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Cybertruck/ -cp ${OUT_DIR}/SM_Etron.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiETron/ -cp ${OUT_DIR}/SM_Lincoln_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2017/ -cp ${OUT_DIR}/SM_Mustang_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/ -cp ${OUT_DIR}/SM_TeslaM3_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/ -cp ${OUT_DIR}/SM_TestTruck.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Truck/ -cp ${OUT_DIR}/SM_Van_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/VolkswagenT2/ - +#!/bin/bash + +DReyeVR_ROOT=$PWD +CARLA_ROOT=$1 +PLATFORM=$2 + +R='\033[0;31m' # Red +G='\033[0;32m' # Green +Y='\033[0;33m' # Yellow +B='\033[0;34m' # Blue +NC='\033[0m' # No Color + +if [ -z "$1" ]; then + echo -e "${R}Enter the location for Carla${NC}" + exit 1 +fi + +if [ -z "$2" ]; then + echo -e "${R}Enter the platform for downloading LODs: One of \"Windows\"/\"Linux\"/\"Original\"${NC}" + exit 1 +fi + +echo -e "\nInstalling custom LOD's for DReyeVR" + +if [ ! -f ${CARLA_ROOT}/CHANGELOG.md ] || [[ `head -n 1 ${CARLA_ROOT}/CHANGELOG.md` != "## CARLA 0.9.13" ]]; then + echo -e "${R}Could not verify a correct Carla 0.9.13 installation${NC}" + exit 1 +else + echo -e "${G}Found a Carla 0.9.13 installation at ${CARLA_ROOT}${NC}" +fi + +LINUX='https://docs.google.com/uc?export=download&id=1OqDOCAflENnXvbJCogBEmRhHQpEF1aKE' +WINDOWS='https://docs.google.com/uc?export=download&id=191tiK25MJ9C7-5Q1-sHt1mp4_EaefjqM' +ORIGINAL='https://docs.google.com/uc?export=download&id=1Vc4e43xZuXOJF_3-r3n3QU-yE5sjiAfw' + +if [ ${PLATFORM} == "Linux" ]; then + CONTENT=${LINUX} + FILENAME="LinuxLODs.zip" +elif [ ${PLATFORM} == "Windows" ]; then + CONTENT=${WINDOWS} + FILENAME="WindowsLODs.zip" +elif [ ${PLATFORM} == "Original" ]; then + CONTENT=${ORIGINAL} + FILENAME="OriginalLODs.zip" +else + echo -e "${R}Could not verify a correct platform (must one of \"Windows\"/\"Linux\"/\"Original\")${NC}" + exit 1 +fi +echo -e "${B}Downloading ${FILENAME} LODs package...${NC}" + +wget -r -nv ${CONTENT} -O ${FILENAME} + +OUT_DIR=${FILENAME::-4} # get rid of .zip + +unzip ${FILENAME} -d ${OUT_DIR} + +echo -e "${B}Copying files from ${OUT_DIR}...${NC}" + +mkdir -p $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DReyeVR/ +cp SM_Vehicle_LODSettings.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DReyeVR/ +# now copy all individual static meshes +# note you can get all the file paths easily in UE4 (with the folderless+filtered mode) right-click -> copy file paths +cp ${OUT_DIR}/Vh_Car_ToyotaPrius_Rig.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Toyota_Prius/ +cp ${OUT_DIR}/SK_AudiA2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiA2_/ +cp ${OUT_DIR}/SK_BMWGranTourer.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwGranTourer/ +cp ${OUT_DIR}/SK_BMWIsetta.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/BmwIsetta/ +cp ${OUT_DIR}/SK_CarlaCola.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/CarlaCola/ +cp ${OUT_DIR}/SK_Charger2020.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/ +cp ${OUT_DIR}/SK_ChargerCop.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharger2020/ChargerCop/ +cp ${OUT_DIR}/SK_ChevroletImpala.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/ +cp ${OUT_DIR}/SK_Citroen_C3.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Citroen/ +cp ${OUT_DIR}/SK_JeepWranglerRubicon.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Jeep/ +cp ${OUT_DIR}/SK_lincolnv5.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2020/ +cp ${OUT_DIR}/SK_MercedesBenzCoupeC.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mercedes/ +cp ${OUT_DIR}/SK_MercedesCCC.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MercedesCCC/ +cp ${OUT_DIR}/SK_MiniCooperS.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/MIni/ +cp ${OUT_DIR}/SK_Mustang_OLD.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/ +cp ${OUT_DIR}/SK_NissanMicra.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Micra/ +cp ${OUT_DIR}/SK_NissanPatrolST.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Nissan_Patrol/ +cp ${OUT_DIR}/SK_SeatLeon.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Leon/ +cp ${OUT_DIR}/SM_AudiTT_v1.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiTT/ +cp ${OUT_DIR}/SM_Charger_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/DodgeCharge/ +cp ${OUT_DIR}/SM_Chevrolet_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Chevrolet/ +cp ${OUT_DIR}/SM_Cybertruck_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Cybertruck/ +cp ${OUT_DIR}/SM_Etron.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/AudiETron/ +cp ${OUT_DIR}/SM_Lincoln_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/LincolnMKZ2017/ +cp ${OUT_DIR}/SM_Mustang_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Mustang/ +cp ${OUT_DIR}/SM_TeslaM3_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/ +cp ${OUT_DIR}/SM_TestTruck.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Truck/ +cp ${OUT_DIR}/SM_Van_v2.uasset $CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/VolkswagenT2/ + echo -e "\n${G}Installation successful!${NC}" \ No newline at end of file diff --git a/Tools/VirtualMachine/FossaVM.sh b/Tools/VirtualMachine/FossaVM.sh index db8774e..7e18dbb 100755 --- a/Tools/VirtualMachine/FossaVM.sh +++ b/Tools/VirtualMachine/FossaVM.sh @@ -1,28 +1,28 @@ -#!/bin/sh -SPICE_UNIX=fossa.unix.sock -FOSSA_IMG=ubuntu20.img # filename here - -echo "STARTING QEMU VM WITH UNIX SOCKET: ${SPICE_UNIX}" -echo "Reconnect from any terminal with remote-viewer spice+unix://${SPICE_UNIX}" -echo "type \"quit\" to power off the VM when in (qemu) mode\n" - -# first start the SPICE server by waiting (concurrently) for the VM to start -(sleep 0.3 && remote-viewer spice+unix://${SPICE_UNIX}) & - -# start the VM as the foreground process -qemu-system-x86_64 \ - -drive file=${FOSSA_IMG},format=raw,if=virtio,cache=off \ - -name FossaVM \ - -m 16384 \ - -enable-kvm -cpu host \ - -smp cores=8 \ - -vga virtio \ - -spice unix,addr=${SPICE_UNIX},disable-ticketing \ - -device virtio-serial-pci \ - -device virtserialport,chardev=spicechannel0,name=com.redhat.spice.0 \ - -chardev spicevmc,id=spicechannel0,name=vdagent \ - -monitor stdio \ - -netdev tap,id=mynet0,ifname=tap0,script=no,downscript=no \ - -device e1000,netdev=mynet0,mac=52:55:00:d1:55:01 \ - -net nic -net user,smb="$CARLA_ROOT" - +#!/bin/sh +SPICE_UNIX=fossa.unix.sock +FOSSA_IMG=ubuntu20.img # filename here + +echo "STARTING QEMU VM WITH UNIX SOCKET: ${SPICE_UNIX}" +echo "Reconnect from any terminal with remote-viewer spice+unix://${SPICE_UNIX}" +echo "type \"quit\" to power off the VM when in (qemu) mode\n" + +# first start the SPICE server by waiting (concurrently) for the VM to start +(sleep 0.3 && remote-viewer spice+unix://${SPICE_UNIX}) & + +# start the VM as the foreground process +qemu-system-x86_64 \ + -drive file=${FOSSA_IMG},format=raw,if=virtio,cache=off \ + -name FossaVM \ + -m 16384 \ + -enable-kvm -cpu host \ + -smp cores=8 \ + -vga virtio \ + -spice unix,addr=${SPICE_UNIX},disable-ticketing \ + -device virtio-serial-pci \ + -device virtserialport,chardev=spicechannel0,name=com.redhat.spice.0 \ + -chardev spicevmc,id=spicechannel0,name=vdagent \ + -monitor stdio \ + -netdev tap,id=mynet0,ifname=tap0,script=no,downscript=no \ + -device e1000,netdev=mynet0,mac=52:55:00:d1:55:01 \ + -net nic -net user,smb="$CARLA_ROOT" + diff --git a/Tools/VirtualMachine/README.md b/Tools/VirtualMachine/README.md index 3ba4904..a467ed7 100644 --- a/Tools/VirtualMachine/README.md +++ b/Tools/VirtualMachine/README.md @@ -1,109 +1,109 @@ -# Using a Virtual Machine for ROS master - -In this guide we'll highlight the important features of a `kvm` accelerated `qemu` based virtual machine running `Ubuntu 20.04 LTS` for clean `ROS noetic` compatibility. - -### Reason? -Installing `ROS noetic` requires jumping through several flaming hoops if you want to install `ROS` on a different distribution than vanilla `Ubuntu 20.04 LTS`, for our case this becomes the easiest way to go. - -**However** if you are already daily-driving a Linux machine running `Ubuntu 20.04 LTS` then you can skip this portion all-together if you'd like and install the `ROS master` locally. - -### What is qemu? -From [qemu.org](https://www.qemu.org/): "QEMU is a (FAST!) generic and open source machine emulator and virtualizer". This highlights some of the main features being "Full-system emulation" and "Virtualization" that we'll use. Additionally there is lots of documentation and community support for [qemu on Ubuntu](https://help.ubuntu.com/community/KVM/Installation) and its derivatives - -### Creating the Virtual Machine -**Ideally have KVM support:** - -First it will be important to have `kvm` support on your machine to run instructions directly on the CPU rather than virtualizing them, to verify this check `kvm-ok` in any shell. - -**Installing Dependencies** -```properties -sudo apt-get install qemu-kvm qemu -# then reboot your system -``` -It is advisable to reboot the system after installation. - -**Creating the Virtual Machine** - -- Note that ideally the VM has at least 20G of disk space, make sure your local disk has at least this much free space. -- The `.iso` system file can be downloaded from [Canonical's website](https://ubuntu.com/download/desktop) - -```properties -# create a 20G virtual disk image file at ~/Ubuntu20.04/ -qemu-img create ubuntu.img 20G - -# download the Ubuntu 20.04.1 LTS iso from https://ubuntu.com/download/desktop -# and place the .iso in the same working directory - -# then boot the Virtual machine for the first time with -# Qemu parameters: -# -m: memory in MB passed to VM -# -smp cores=X: number of CPU cores passed to VM -# -cpu host: what kind of CPU is being emulated (use host to mirror CPU specs) -qemu-system-x86_64 -hda ubuntu.img -boot a -cdrom ./ubuntu-20.04.1-desktop-amd64.iso -enable-kvm -m 8192 -smp cores=8 -cpu host -``` -Then follow the typical Ubuntu installation guide through the GUI installer. - -After the first installation/boot, the system can be launched with default `qemu-system-x86_64`. Feel free to delete the `.iso` file at this point. -```properties -qemu-system-x86_64 -hda ubuntu20.img -name FossaVM -boot a -m 8192 -smp cores=8 -cpu host -enable-kvm -vga virtio -``` - -To run it with spice see below. - -### Running with Spice for copy+paste -[Spice](https://spice-space.org/) is an "open source solution for remote access to virtual machines in a seamless way" for easy usb device sharing, copy paste, and an [improved grpahical experience](https://www.linux-kvm.org/page/SPICE) for KVM based virtual machines. - -To do this, install the [spice-vdagent](https://gitlab.freedesktop.org/spice/linux/vd_agent) in the guest machine: -```properties -# in the guest machine -sudo apt install spice-vdagent -``` - -Then on the host machine, you'll need to use the [`remote-viewer`](http://manpages.ubuntu.com/manpages/bionic/man1/remote-viewer.1.html) to view the virtual machine's graphical interface. - -To add this to the VM startup script see our [`FossaVM.sh`](FossaVM.sh) script we added -```properties -# first start the SPICE server by waiting (concurrently) for the VM to start -(sleep 0.3 && remote-viewer spice+unix://${SPICE_UNIX}) & -``` -and -```properties --spice unix,addr=${SPICE_UNIX},disable-ticketing \ --device virtio-serial-pci \ --device virtserialport,chardev=spicechannel0,name=com.redhat.spice.0 \ --chardev spicevmc,id=spicechannel0,name=vdagent \ --monitor stdio \ -``` -Where `SPICE_UNIX` is a Unix socket (memory based socket, faster than TCP) defined in the script. Note that it is also possible to use a TCP host and port with `remote-viewer spice://${SPICE_ADDR}:${SPICE_PORT}` and `-spice port=${SPICE_PORT},addr=${SPICE_ADDR},disable-ticketing \`. - -### Setting up the Network backend -Finally, our last hurdle is that when we try to connect to the virtual machine from the network, it is unavailable because the default `qemu` network backend is [completely emulated](https://qemu.readthedocs.io/en/latest/system/net.html) and thus not assigned a proper IP address for bidirectional ssh from our physical machines to the VM. - -Additionally, "the standard way to connect QEMU to a real network" is to use a **TAP** network interface where "QEMU adds a virtual network device on your host (called `tapN`), and you can then configure it as if it was a real ethernet card" ([source](https://qemu.readthedocs.io/en/latest/system/net.html)). - -The simplest guide to follow to set this up is this [Setting up Qemu with a tap interface](https://gist.github.com/extremecoders-re/e8fd8a67a515fee0c873dcafc81d811c) gist. We have compiled a complete script to run through these commands in [`SetupTap.sh`](SetupTap.sh): - -**Important** things to keep in mind: -- The `SetupTap.sh` script assumes your ethernet network (to be passthrough) is called `enp5s0`. To edit this see line 6 - - Note that it is only supported to pass through an ethernet connection (ex. can't pass through wifi) which will leave the host without an ethernet card. It is advisable to have multiple available networks so that the host can automatically switch to its backup network card. -- After running `./SetupTap.sh` to create a `tap0` network and `br0` bridge, if you no longer need these you can clean up the network setup back to normal by passing in a `clean` parameter - -```properties -# will remove the tap0 and br0 network and revert the ethernet passthrough so it can be used again by the host -./SetupTap.sh clean -``` - -## Finally... -Once this is all set up it is simple to run the entire setup with the [`FossaVM.sh`](FossaVM.sh) and [`SetupTap.sh`](SetupTap.sh) scripts. -```properties -# start the TAP interface -./SetupTap.sh - -# start the Ubuntu VM -./FossaVM.sh - -... - -# after closing the VM to revert changes to your network -./SetupTap.sh clean -``` +# Using a Virtual Machine for ROS master + +In this guide we'll highlight the important features of a `kvm` accelerated `qemu` based virtual machine running `Ubuntu 20.04 LTS` for clean `ROS noetic` compatibility. + +### Reason? +Installing `ROS noetic` requires jumping through several flaming hoops if you want to install `ROS` on a different distribution than vanilla `Ubuntu 20.04 LTS`, for our case this becomes the easiest way to go. + +**However** if you are already daily-driving a Linux machine running `Ubuntu 20.04 LTS` then you can skip this portion all-together if you'd like and install the `ROS master` locally. + +### What is qemu? +From [qemu.org](https://www.qemu.org/): "QEMU is a (FAST!) generic and open source machine emulator and virtualizer". This highlights some of the main features being "Full-system emulation" and "Virtualization" that we'll use. Additionally there is lots of documentation and community support for [qemu on Ubuntu](https://help.ubuntu.com/community/KVM/Installation) and its derivatives + +### Creating the Virtual Machine +**Ideally have KVM support:** + +First it will be important to have `kvm` support on your machine to run instructions directly on the CPU rather than virtualizing them, to verify this check `kvm-ok` in any shell. + +**Installing Dependencies** +```properties +sudo apt-get install qemu-kvm qemu +# then reboot your system +``` +It is advisable to reboot the system after installation. + +**Creating the Virtual Machine** + +- Note that ideally the VM has at least 20G of disk space, make sure your local disk has at least this much free space. +- The `.iso` system file can be downloaded from [Canonical's website](https://ubuntu.com/download/desktop) + +```properties +# create a 20G virtual disk image file at ~/Ubuntu20.04/ +qemu-img create ubuntu.img 20G + +# download the Ubuntu 20.04.1 LTS iso from https://ubuntu.com/download/desktop +# and place the .iso in the same working directory + +# then boot the Virtual machine for the first time with +# Qemu parameters: +# -m: memory in MB passed to VM +# -smp cores=X: number of CPU cores passed to VM +# -cpu host: what kind of CPU is being emulated (use host to mirror CPU specs) +qemu-system-x86_64 -hda ubuntu.img -boot a -cdrom ./ubuntu-20.04.1-desktop-amd64.iso -enable-kvm -m 8192 -smp cores=8 -cpu host +``` +Then follow the typical Ubuntu installation guide through the GUI installer. + +After the first installation/boot, the system can be launched with default `qemu-system-x86_64`. Feel free to delete the `.iso` file at this point. +```properties +qemu-system-x86_64 -hda ubuntu20.img -name FossaVM -boot a -m 8192 -smp cores=8 -cpu host -enable-kvm -vga virtio +``` + +To run it with spice see below. + +### Running with Spice for copy+paste +[Spice](https://spice-space.org/) is an "open source solution for remote access to virtual machines in a seamless way" for easy usb device sharing, copy paste, and an [improved grpahical experience](https://www.linux-kvm.org/page/SPICE) for KVM based virtual machines. + +To do this, install the [spice-vdagent](https://gitlab.freedesktop.org/spice/linux/vd_agent) in the guest machine: +```properties +# in the guest machine +sudo apt install spice-vdagent +``` + +Then on the host machine, you'll need to use the [`remote-viewer`](http://manpages.ubuntu.com/manpages/bionic/man1/remote-viewer.1.html) to view the virtual machine's graphical interface. + +To add this to the VM startup script see our [`FossaVM.sh`](FossaVM.sh) script we added +```properties +# first start the SPICE server by waiting (concurrently) for the VM to start +(sleep 0.3 && remote-viewer spice+unix://${SPICE_UNIX}) & +``` +and +```properties +-spice unix,addr=${SPICE_UNIX},disable-ticketing \ +-device virtio-serial-pci \ +-device virtserialport,chardev=spicechannel0,name=com.redhat.spice.0 \ +-chardev spicevmc,id=spicechannel0,name=vdagent \ +-monitor stdio \ +``` +Where `SPICE_UNIX` is a Unix socket (memory based socket, faster than TCP) defined in the script. Note that it is also possible to use a TCP host and port with `remote-viewer spice://${SPICE_ADDR}:${SPICE_PORT}` and `-spice port=${SPICE_PORT},addr=${SPICE_ADDR},disable-ticketing \`. + +### Setting up the Network backend +Finally, our last hurdle is that when we try to connect to the virtual machine from the network, it is unavailable because the default `qemu` network backend is [completely emulated](https://qemu.readthedocs.io/en/latest/system/net.html) and thus not assigned a proper IP address for bidirectional ssh from our physical machines to the VM. + +Additionally, "the standard way to connect QEMU to a real network" is to use a **TAP** network interface where "QEMU adds a virtual network device on your host (called `tapN`), and you can then configure it as if it was a real ethernet card" ([source](https://qemu.readthedocs.io/en/latest/system/net.html)). + +The simplest guide to follow to set this up is this [Setting up Qemu with a tap interface](https://gist.github.com/extremecoders-re/e8fd8a67a515fee0c873dcafc81d811c) gist. We have compiled a complete script to run through these commands in [`SetupTap.sh`](SetupTap.sh): + +**Important** things to keep in mind: +- The `SetupTap.sh` script assumes your ethernet network (to be passthrough) is called `enp5s0`. To edit this see line 6 + - Note that it is only supported to pass through an ethernet connection (ex. can't pass through wifi) which will leave the host without an ethernet card. It is advisable to have multiple available networks so that the host can automatically switch to its backup network card. +- After running `./SetupTap.sh` to create a `tap0` network and `br0` bridge, if you no longer need these you can clean up the network setup back to normal by passing in a `clean` parameter + +```properties +# will remove the tap0 and br0 network and revert the ethernet passthrough so it can be used again by the host +./SetupTap.sh clean +``` + +## Finally... +Once this is all set up it is simple to run the entire setup with the [`FossaVM.sh`](FossaVM.sh) and [`SetupTap.sh`](SetupTap.sh) scripts. +```properties +# start the TAP interface +./SetupTap.sh + +# start the Ubuntu VM +./FossaVM.sh + +... + +# after closing the VM to revert changes to your network +./SetupTap.sh clean +``` diff --git a/Tools/VirtualMachine/SetupTap.sh b/Tools/VirtualMachine/SetupTap.sh index df0de16..3acca91 100755 --- a/Tools/VirtualMachine/SetupTap.sh +++ b/Tools/VirtualMachine/SetupTap.sh @@ -1,82 +1,82 @@ -#!/bin/bash - -# automated script from Tap setup found from: -# https://gist.github.com/extremecoders-re/e8fd8a67a515fee0c873dcafc81d811c - -ETH0=enp5s0 # my personal ethernet config -# note that you can only use Ethernet for connecting to bridge - -USER=`whoami` - -# exit when any command fails -# set -e - -if [[ $# -eq 0 ]]; # no arguments => setup tap -then - # create a bridge - sudo brctl addbr br0 - - # clear ip of CONNECTION - sudo ip addr flush dev $ETH0 - - # add CONNECTION to bridge - sudo brctl addif br0 $ETH0 - - # create tap interface - sudo tunctl -t tap0 -u $USER - - # add tap0 to bridge - sudo brctl addif br0 tap0 - - # make sure everything is up - sudo ifconfig $ETH0 up - sudo ifconfig tap0 up - sudo ifconfig br0 up - - # check if properly bridged - sudo brctl show - - # assign ip to br0 - sudo dhclient -v br0 - - # message output - echo "Successfully created tap0 network backend interface" - - exit 0 -elif [[ $1 == "cleanup" ]] || [[ $1 == "clean" ]]; -then - # cleanup - echo "CLEANING UP" - - # remove tap interface tap0 from bridge br0 - sudo brctl delif br0 tap0 - - # delete tap0 - sudo tunctl -d tap0 - - # remove eth0 from bridge - sudo brctl delif br0 $ETH0 - - # bring bridge down - sudo ifconfig br0 down - - # remove bridge - sudo brctl delbr br0 - - # bring CONNECTION up - sudo ifconfig $ETH0 up - - # check if an IP is assigned to CONNECTION, if not request one - sudo dhclient -v $ETH0 - - # message output - echo "Successfully removed tap0 interface" - - exit 0 -else - echo "Use clean or cleanup to to remove the tap interface, or nothing to just setup" - - # error exit - exit 1 -fi - +#!/bin/bash + +# automated script from Tap setup found from: +# https://gist.github.com/extremecoders-re/e8fd8a67a515fee0c873dcafc81d811c + +ETH0=enp5s0 # my personal ethernet config +# note that you can only use Ethernet for connecting to bridge + +USER=`whoami` + +# exit when any command fails +# set -e + +if [[ $# -eq 0 ]]; # no arguments => setup tap +then + # create a bridge + sudo brctl addbr br0 + + # clear ip of CONNECTION + sudo ip addr flush dev $ETH0 + + # add CONNECTION to bridge + sudo brctl addif br0 $ETH0 + + # create tap interface + sudo tunctl -t tap0 -u $USER + + # add tap0 to bridge + sudo brctl addif br0 tap0 + + # make sure everything is up + sudo ifconfig $ETH0 up + sudo ifconfig tap0 up + sudo ifconfig br0 up + + # check if properly bridged + sudo brctl show + + # assign ip to br0 + sudo dhclient -v br0 + + # message output + echo "Successfully created tap0 network backend interface" + + exit 0 +elif [[ $1 == "cleanup" ]] || [[ $1 == "clean" ]]; +then + # cleanup + echo "CLEANING UP" + + # remove tap interface tap0 from bridge br0 + sudo brctl delif br0 tap0 + + # delete tap0 + sudo tunctl -d tap0 + + # remove eth0 from bridge + sudo brctl delif br0 $ETH0 + + # bring bridge down + sudo ifconfig br0 down + + # remove bridge + sudo brctl delbr br0 + + # bring CONNECTION up + sudo ifconfig $ETH0 up + + # check if an IP is assigned to CONNECTION, if not request one + sudo dhclient -v $ETH0 + + # message output + echo "Successfully removed tap0 interface" + + exit 0 +else + echo "Use clean or cleanup to to remove the tap interface, or nothing to just setup" + + # error exit + exit 1 +fi + diff --git a/Util/BuildTools/BuildOSM2ODR.sh b/Util/BuildTools/BuildOSM2ODR.sh index 8eca769..acc9336 100755 --- a/Util/BuildTools/BuildOSM2ODR.sh +++ b/Util/BuildTools/BuildOSM2ODR.sh @@ -1,108 +1,108 @@ -#! /bin/bash -DOC_STRING="Build OSM2ODR." - -USAGE_STRING=$(cat <<- END -Usage: $0 [-h|--help] - -commands - - [--clean] Clean intermediate files. - [--rebuild] Clean and rebuild both configurations. -END -) - -REMOVE_INTERMEDIATE=false -BUILD_OSM2ODR=false -GIT_PULL=true -CURRENT_OSM2ODR_COMMIT=ee0c2b9241fef5365a6bc044ac82e6580b8ce936 -OSM2ODR_BRANCH=carla_osm2odr -OSM2ODR_REPO=https://github.com/carla-simulator/sumo.git - -OPTS=`getopt -o h --long help,rebuild,build,clean,carsim,no-pull -n 'parse-options' -- "$@"` - -eval set -- "$OPTS" - -while [[ $# -gt 0 ]]; do - case "$1" in - --rebuild ) - REMOVE_INTERMEDIATE=true; - BUILD_OSM2ODR=true; - shift ;; - --build ) - BUILD_OSM2ODR=true; - shift ;; - --no-pull ) - GIT_PULL=false - shift ;; - --clean ) - REMOVE_INTERMEDIATE=true; - shift ;; - -h | --help ) - echo "$DOC_STRING" - echo "$USAGE_STRING" - exit 1 - ;; - * ) - shift ;; - esac -done - -source $(dirname "$0")/Environment.sh - -function get_source_code_checksum { - local EXCLUDE='*__pycache__*' - find "${OSM2ODR_SOURCE_FOLDER}"/* \! -path "${EXCLUDE}" -print0 | sha1sum | awk '{print $1}' -} - -if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_OSM2ODR}; }; then - fatal_error "Nothing selected to be done." -fi - -# ============================================================================== -# -- Clean intermediate files -------------------------------------------------- -# ============================================================================== - -if ${REMOVE_INTERMEDIATE} ; then - - log "Cleaning intermediate files and folders." - - rm -Rf ${OSM2ODR_BUILD_FOLDER}* - -fi - -# ============================================================================== -# -- Build library ------------------------------------------------------------- -# ============================================================================== - -if ${BUILD_OSM2ODR} ; then - log "Building OSM2ODR." - # [ ! -d ${OSM2ODR_BUILD_FOLDER} ] && mkdir ${OSM2ODR_BUILD_FOLDER} - if ${GIT_PULL} ; then - if [ ! -d ${OSM2ODR_SOURCE_FOLDER} ] ; then - git clone -b ${OSM2ODR_BRANCH} ${OSM2ODR_REPO} ${OSM2ODR_SOURCE_FOLDER} - fi - cd ${OSM2ODR_SOURCE_FOLDER} - git fetch - git checkout ${CURRENT_OSM2ODR_COMMIT} - fi - - mkdir -p ${OSM2ODR_BUILD_FOLDER} - cd ${OSM2ODR_BUILD_FOLDER} - # define clang compiler - export CC=/usr/bin/clang - export CXX=/usr/bin/clang++ - - cmake ${OSM2ODR_SOURCE_FOLDER} \ - -G "Eclipse CDT4 - Ninja" \ - -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_CLIENT_FOLDER} \ - -DPROJ_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-install/include \ - -DPROJ_LIBRARY=${CARLA_BUILD_FOLDER}/proj-install/lib/libproj.a \ - -DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install/include \ - -DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install/lib/libxerces-c.a - - ninja osm2odr - ninja install - -fi - -log "Success!" +#! /bin/bash +DOC_STRING="Build OSM2ODR." + +USAGE_STRING=$(cat <<- END +Usage: $0 [-h|--help] + +commands + + [--clean] Clean intermediate files. + [--rebuild] Clean and rebuild both configurations. +END +) + +REMOVE_INTERMEDIATE=false +BUILD_OSM2ODR=false +GIT_PULL=true +CURRENT_OSM2ODR_COMMIT=ee0c2b9241fef5365a6bc044ac82e6580b8ce936 +OSM2ODR_BRANCH=carla_osm2odr +OSM2ODR_REPO=https://github.com/carla-simulator/sumo.git + +OPTS=`getopt -o h --long help,rebuild,build,clean,carsim,no-pull -n 'parse-options' -- "$@"` + +eval set -- "$OPTS" + +while [[ $# -gt 0 ]]; do + case "$1" in + --rebuild ) + REMOVE_INTERMEDIATE=true; + BUILD_OSM2ODR=true; + shift ;; + --build ) + BUILD_OSM2ODR=true; + shift ;; + --no-pull ) + GIT_PULL=false + shift ;; + --clean ) + REMOVE_INTERMEDIATE=true; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + shift ;; + esac +done + +source $(dirname "$0")/Environment.sh + +function get_source_code_checksum { + local EXCLUDE='*__pycache__*' + find "${OSM2ODR_SOURCE_FOLDER}"/* \! -path "${EXCLUDE}" -print0 | sha1sum | awk '{print $1}' +} + +if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_OSM2ODR}; }; then + fatal_error "Nothing selected to be done." +fi + +# ============================================================================== +# -- Clean intermediate files -------------------------------------------------- +# ============================================================================== + +if ${REMOVE_INTERMEDIATE} ; then + + log "Cleaning intermediate files and folders." + + rm -Rf ${OSM2ODR_BUILD_FOLDER}* + +fi + +# ============================================================================== +# -- Build library ------------------------------------------------------------- +# ============================================================================== + +if ${BUILD_OSM2ODR} ; then + log "Building OSM2ODR." + # [ ! -d ${OSM2ODR_BUILD_FOLDER} ] && mkdir ${OSM2ODR_BUILD_FOLDER} + if ${GIT_PULL} ; then + if [ ! -d ${OSM2ODR_SOURCE_FOLDER} ] ; then + git clone -b ${OSM2ODR_BRANCH} ${OSM2ODR_REPO} ${OSM2ODR_SOURCE_FOLDER} + fi + cd ${OSM2ODR_SOURCE_FOLDER} + git fetch + git checkout ${CURRENT_OSM2ODR_COMMIT} + fi + + mkdir -p ${OSM2ODR_BUILD_FOLDER} + cd ${OSM2ODR_BUILD_FOLDER} + # define clang compiler + export CC=/usr/bin/clang + export CXX=/usr/bin/clang++ + + cmake ${OSM2ODR_SOURCE_FOLDER} \ + -G "Eclipse CDT4 - Ninja" \ + -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_CLIENT_FOLDER} \ + -DPROJ_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-install/include \ + -DPROJ_LIBRARY=${CARLA_BUILD_FOLDER}/proj-install/lib/libproj.a \ + -DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install/include \ + -DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install/lib/libxerces-c.a + + ninja osm2odr + ninja install + +fi + +log "Success!" diff --git a/Util/BuildTools/BuildPythonAPI.bat b/Util/BuildTools/BuildPythonAPI.bat index 4375aa4..de8fc89 100644 --- a/Util/BuildTools/BuildPythonAPI.bat +++ b/Util/BuildTools/BuildPythonAPI.bat @@ -1,165 +1,165 @@ -@echo off -setlocal - -rem BAT script that creates the client python api of LibCarla (carla.org). -rem Run it through a cmd with the x64 Visual C++ Toolset enabled. - -set LOCAL_PATH=%~dp0 -set FILE_N=-[%~n0]: - -rem Print batch params (debug purpose) -echo %FILE_N% [Batch params]: %* - -rem ============================================================================ -rem -- Parse arguments --------------------------------------------------------- -rem ============================================================================ - -set DOC_STRING=Build and package CARLA Python API. -set "USAGE_STRING=Usage: %FILE_N% [-h^|--help] [--rebuild] [--clean]" - -set REMOVE_INTERMEDIATE=false -set BUILD_FOR_PYTHON2=false -set BUILD_FOR_PYTHON3=false - -:arg-parse -if not "%1"=="" ( - if "%1"=="--rebuild" ( - set REMOVE_INTERMEDIATE=true - rem We don't provide support for py2 right now - set BUILD_FOR_PYTHON2=false - set BUILD_FOR_PYTHON3=true - ) - - if "%1"=="--py2" ( - set BUILD_FOR_PYTHON2=true - ) - - if "%1"=="--py3" ( - set BUILD_FOR_PYTHON3=true - ) - - - if "%1"=="--clean" ( - set REMOVE_INTERMEDIATE=true - ) - - if "%1"=="-h" ( - echo %DOC_STRING% - echo %USAGE_STRING% - GOTO :eof - ) - - if "%1"=="--help" ( - echo %DOC_STRING% - echo %USAGE_STRING% - GOTO :eof - ) - - shift - goto :arg-parse -) - -set PYTHON_LIB_PATH=%ROOT_PATH:/=\%PythonAPI\carla\ - -if %REMOVE_INTERMEDIATE% == false ( - if %BUILD_FOR_PYTHON3% == false ( - if %BUILD_FOR_PYTHON2% == false ( - echo Nothing selected to be done. - goto :eof - ) - ) -) - -if %REMOVE_INTERMEDIATE% == true ( - rem Remove directories - for %%G in ( - "%PYTHON_LIB_PATH%build", - "%PYTHON_LIB_PATH%dist", - "%PYTHON_LIB_PATH%source\carla.egg-info" - ) do ( - if exist %%G ( - echo %FILE_N% Cleaning %%G - rmdir /s/q %%G - ) - ) - if %BUILD_FOR_PYTHON3% == false ( - if %BUILD_FOR_PYTHON2% == false ( - goto good_exit - ) - ) -) - -cd "%PYTHON_LIB_PATH%" -rem if exist "%PYTHON_LIB_PATH%dist" goto already_installed - -rem ============================================================================ -rem -- Check for py ------------------------------------------------------------ -rem ============================================================================ - -rem prefer invoking 'python' (for externally installed, eg conda) over 'py' (built in to Windows) -rem -set PYTHON_EXEC=python - -where %PYTHON_EXEC%>nul -if %errorlevel% neq 0 set PYTHON_EXEC=py -3 - -where %PYTHON_EXEC%>nul -if %errorlevel% neq 0 goto error_py - -rem Build for Python 2 -rem -if %BUILD_FOR_PYTHON2%==true ( - goto py2_not_supported -) - -rem Build for Python 3 -rem -if %BUILD_FOR_PYTHON3%==true ( - echo Building Python API for Python 3. - %PYTHON_EXEC% setup.py bdist_egg bdist_wheel - if %errorlevel% neq 0 goto error_build_wheel -) - -goto success - -rem ============================================================================ -rem -- Messages and Errors ----------------------------------------------------- -rem ============================================================================ - -:success - echo. - if %BUILD_FOR_PYTHON3%==true echo %FILE_N% Carla lib for python has been successfully installed in "%PYTHON_LIB_PATH%dist"! - goto good_exit - -:already_installed - echo. - echo %FILE_N% [ERROR] Already installed in "%PYTHON_LIB_PATH%dist" - goto good_exit - -:py2_not_supported - echo. - echo %FILE_N% [ERROR] Python 2 is not currently suported in Windows. - goto bad_exit - -:error_py - echo. - echo %FILE_N% [ERROR] An error ocurred while executing the py. - echo %FILE_N% [ERROR] Possible causes: - echo %FILE_N% [ERROR] - Make sure "py" is installed. - echo %FILE_N% [ERROR] - py = python launcher. This utility is bundled with Python installation but not installed by default. - echo %FILE_N% [ERROR] - Make sure it is available on your Windows "py". - goto bad_exit - -:error_build_wheel - echo. - echo %FILE_N% [ERROR] An error occurred while building the wheel file. - goto bad_exit - -:good_exit - endlocal - exit /b 0 - -:bad_exit - endlocal - exit /b %errorlevel% - +@echo off +setlocal + +rem BAT script that creates the client python api of LibCarla (carla.org). +rem Run it through a cmd with the x64 Visual C++ Toolset enabled. + +set LOCAL_PATH=%~dp0 +set FILE_N=-[%~n0]: + +rem Print batch params (debug purpose) +echo %FILE_N% [Batch params]: %* + +rem ============================================================================ +rem -- Parse arguments --------------------------------------------------------- +rem ============================================================================ + +set DOC_STRING=Build and package CARLA Python API. +set "USAGE_STRING=Usage: %FILE_N% [-h^|--help] [--rebuild] [--clean]" + +set REMOVE_INTERMEDIATE=false +set BUILD_FOR_PYTHON2=false +set BUILD_FOR_PYTHON3=false + +:arg-parse +if not "%1"=="" ( + if "%1"=="--rebuild" ( + set REMOVE_INTERMEDIATE=true + rem We don't provide support for py2 right now + set BUILD_FOR_PYTHON2=false + set BUILD_FOR_PYTHON3=true + ) + + if "%1"=="--py2" ( + set BUILD_FOR_PYTHON2=true + ) + + if "%1"=="--py3" ( + set BUILD_FOR_PYTHON3=true + ) + + + if "%1"=="--clean" ( + set REMOVE_INTERMEDIATE=true + ) + + if "%1"=="-h" ( + echo %DOC_STRING% + echo %USAGE_STRING% + GOTO :eof + ) + + if "%1"=="--help" ( + echo %DOC_STRING% + echo %USAGE_STRING% + GOTO :eof + ) + + shift + goto :arg-parse +) + +set PYTHON_LIB_PATH=%ROOT_PATH:/=\%PythonAPI\carla\ + +if %REMOVE_INTERMEDIATE% == false ( + if %BUILD_FOR_PYTHON3% == false ( + if %BUILD_FOR_PYTHON2% == false ( + echo Nothing selected to be done. + goto :eof + ) + ) +) + +if %REMOVE_INTERMEDIATE% == true ( + rem Remove directories + for %%G in ( + "%PYTHON_LIB_PATH%build", + "%PYTHON_LIB_PATH%dist", + "%PYTHON_LIB_PATH%source\carla.egg-info" + ) do ( + if exist %%G ( + echo %FILE_N% Cleaning %%G + rmdir /s/q %%G + ) + ) + if %BUILD_FOR_PYTHON3% == false ( + if %BUILD_FOR_PYTHON2% == false ( + goto good_exit + ) + ) +) + +cd "%PYTHON_LIB_PATH%" +rem if exist "%PYTHON_LIB_PATH%dist" goto already_installed + +rem ============================================================================ +rem -- Check for py ------------------------------------------------------------ +rem ============================================================================ + +rem prefer invoking 'python' (for externally installed, eg conda) over 'py' (built in to Windows) +rem +set PYTHON_EXEC=python + +where %PYTHON_EXEC%>nul +if %errorlevel% neq 0 set PYTHON_EXEC=py -3 + +where %PYTHON_EXEC%>nul +if %errorlevel% neq 0 goto error_py + +rem Build for Python 2 +rem +if %BUILD_FOR_PYTHON2%==true ( + goto py2_not_supported +) + +rem Build for Python 3 +rem +if %BUILD_FOR_PYTHON3%==true ( + echo Building Python API for Python 3. + %PYTHON_EXEC% setup.py bdist_egg bdist_wheel + if %errorlevel% neq 0 goto error_build_wheel +) + +goto success + +rem ============================================================================ +rem -- Messages and Errors ----------------------------------------------------- +rem ============================================================================ + +:success + echo. + if %BUILD_FOR_PYTHON3%==true echo %FILE_N% Carla lib for python has been successfully installed in "%PYTHON_LIB_PATH%dist"! + goto good_exit + +:already_installed + echo. + echo %FILE_N% [ERROR] Already installed in "%PYTHON_LIB_PATH%dist" + goto good_exit + +:py2_not_supported + echo. + echo %FILE_N% [ERROR] Python 2 is not currently suported in Windows. + goto bad_exit + +:error_py + echo. + echo %FILE_N% [ERROR] An error ocurred while executing the py. + echo %FILE_N% [ERROR] Possible causes: + echo %FILE_N% [ERROR] - Make sure "py" is installed. + echo %FILE_N% [ERROR] - py = python launcher. This utility is bundled with Python installation but not installed by default. + echo %FILE_N% [ERROR] - Make sure it is available on your Windows "py". + goto bad_exit + +:error_build_wheel + echo. + echo %FILE_N% [ERROR] An error occurred while building the wheel file. + goto bad_exit + +:good_exit + endlocal + exit /b 0 + +:bad_exit + endlocal + exit /b %errorlevel% + diff --git a/Util/BuildTools/BuildPythonAPI.sh b/Util/BuildTools/BuildPythonAPI.sh index 2e00d69..2517128 100755 --- a/Util/BuildTools/BuildPythonAPI.sh +++ b/Util/BuildTools/BuildPythonAPI.sh @@ -1,121 +1,121 @@ -#! /bin/bash - -# ============================================================================== -# -- Parse arguments ----------------------------------------------------------- -# ============================================================================== - -DOC_STRING="Build and package CARLA Python API." - -USAGE_STRING="Usage: $0 [-h|--help] [--rebuild] [--clean] [--python-version=VERSION] [--target-wheel-platform=PLATFORM]" - -REMOVE_INTERMEDIATE=false -BUILD_RSS_VARIANT=false -BUILD_PYTHONAPI=true - -OPTS=`getopt -o h --long help,config:,rebuild,clean,rss,carsim,python-version:,target-wheel-platform:,packages:,clean-intermediate,all,xml,target-archive:, -n 'parse-options' -- "$@"` - -eval set -- "$OPTS" - -PY_VERSION_LIST=3 -TARGET_WHEEL_PLATFORM= - -while [[ $# -gt 0 ]]; do - case "$1" in - --rebuild ) - REMOVE_INTERMEDIATE=true; - BUILD_PYTHONAPI=true; - shift ;; - --python-version ) - PY_VERSION_LIST="$2" - shift 2 ;; - --target-wheel-platform ) - TARGET_WHEEL_PLATFORM="$2" - shift 2 ;; - --rss ) - BUILD_RSS_VARIANT=true; - shift ;; - --clean ) - REMOVE_INTERMEDIATE=true; - BUILD_PYTHONAPI=false; - shift ;; - -h | --help ) - echo "$DOC_STRING" - echo "$USAGE_STRING" - exit 1 - ;; - * ) - shift ;; - esac -done - -source $(dirname "$0")/Environment.sh - -export CC=clang -export CXX=clang++ - -if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_PYTHONAPI} ; }; then - fatal_error "Nothing selected to be done." -fi - -# Convert comma-separated string to array of unique elements. -IFS="," read -r -a PY_VERSION_LIST <<< "${PY_VERSION_LIST}" - -pushd "${CARLA_PYTHONAPI_SOURCE_FOLDER}" >/dev/null - -# ============================================================================== -# -- Clean intermediate files -------------------------------------------------- -# ============================================================================== - -if ${REMOVE_INTERMEDIATE} ; then - - log "Cleaning intermediate files and folders." - - rm -Rf build dist source/carla.egg-info - - find source -name "*.so" -delete - find source -name "__pycache__" -type d -exec rm -r "{}" \; - -fi - -# ============================================================================== -# -- Build API ----------------------------------------------------------------- -# ============================================================================== - -if ${BUILD_RSS_VARIANT} ; then - export BUILD_RSS_VARIANT=${BUILD_RSS_VARIANT} -fi - -if ${BUILD_PYTHONAPI} ; then - # Add patchelf to the path. Auditwheel relies on patchelf to repair ELF files. - export PATH="${LIBCARLA_INSTALL_CLIENT_FOLDER}/bin:${PATH}" - - CODENAME=$(uname -s) - if [[ ! -z ${TARGET_WHEEL_PLATFORM} ]] && [[ ${CODENAME#*=} != "bionic" ]] ; then - log "A target platform has been specified but you are not using a compatible linux distribution. The wheel repair step will be skipped" - TARGET_WHEEL_PLATFORM= - fi - - for PY_VERSION in ${PY_VERSION_LIST[@]} ; do - log "Building Python API for Python ${PY_VERSION}." - - if [[ -z ${TARGET_WHEEL_PLATFORM} ]] ; then - /usr/bin/env python${PY_VERSION} setup.py bdist_egg bdist_wheel --dist-dir dist/.tmp - cp dist/.tmp/$(ls dist/.tmp | grep .whl) dist - else - /usr/bin/env python${PY_VERSION} setup.py bdist_egg bdist_wheel --dist-dir dist/.tmp --plat ${TARGET_WHEEL_PLATFORM} - /usr/bin/env python3 -m auditwheel repair --plat ${TARGET_WHEEL_PLATFORM} --wheel-dir dist dist/.tmp/$(ls dist/.tmp | grep .whl) - fi - - rm -rf dist/.tmp - - done - -fi - -# ============================================================================== -# -- ...and we are done -------------------------------------------------------- -# ============================================================================== - -popd >/dev/null - -log "Success!" +#! /bin/bash + +# ============================================================================== +# -- Parse arguments ----------------------------------------------------------- +# ============================================================================== + +DOC_STRING="Build and package CARLA Python API." + +USAGE_STRING="Usage: $0 [-h|--help] [--rebuild] [--clean] [--python-version=VERSION] [--target-wheel-platform=PLATFORM]" + +REMOVE_INTERMEDIATE=false +BUILD_RSS_VARIANT=false +BUILD_PYTHONAPI=true + +OPTS=`getopt -o h --long help,config:,rebuild,clean,rss,carsim,python-version:,target-wheel-platform:,packages:,clean-intermediate,all,xml,target-archive:, -n 'parse-options' -- "$@"` + +eval set -- "$OPTS" + +PY_VERSION_LIST=3 +TARGET_WHEEL_PLATFORM= + +while [[ $# -gt 0 ]]; do + case "$1" in + --rebuild ) + REMOVE_INTERMEDIATE=true; + BUILD_PYTHONAPI=true; + shift ;; + --python-version ) + PY_VERSION_LIST="$2" + shift 2 ;; + --target-wheel-platform ) + TARGET_WHEEL_PLATFORM="$2" + shift 2 ;; + --rss ) + BUILD_RSS_VARIANT=true; + shift ;; + --clean ) + REMOVE_INTERMEDIATE=true; + BUILD_PYTHONAPI=false; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + shift ;; + esac +done + +source $(dirname "$0")/Environment.sh + +export CC=clang +export CXX=clang++ + +if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_PYTHONAPI} ; }; then + fatal_error "Nothing selected to be done." +fi + +# Convert comma-separated string to array of unique elements. +IFS="," read -r -a PY_VERSION_LIST <<< "${PY_VERSION_LIST}" + +pushd "${CARLA_PYTHONAPI_SOURCE_FOLDER}" >/dev/null + +# ============================================================================== +# -- Clean intermediate files -------------------------------------------------- +# ============================================================================== + +if ${REMOVE_INTERMEDIATE} ; then + + log "Cleaning intermediate files and folders." + + rm -Rf build dist source/carla.egg-info + + find source -name "*.so" -delete + find source -name "__pycache__" -type d -exec rm -r "{}" \; + +fi + +# ============================================================================== +# -- Build API ----------------------------------------------------------------- +# ============================================================================== + +if ${BUILD_RSS_VARIANT} ; then + export BUILD_RSS_VARIANT=${BUILD_RSS_VARIANT} +fi + +if ${BUILD_PYTHONAPI} ; then + # Add patchelf to the path. Auditwheel relies on patchelf to repair ELF files. + export PATH="${LIBCARLA_INSTALL_CLIENT_FOLDER}/bin:${PATH}" + + CODENAME=$(uname -s) + if [[ ! -z ${TARGET_WHEEL_PLATFORM} ]] && [[ ${CODENAME#*=} != "bionic" ]] ; then + log "A target platform has been specified but you are not using a compatible linux distribution. The wheel repair step will be skipped" + TARGET_WHEEL_PLATFORM= + fi + + for PY_VERSION in ${PY_VERSION_LIST[@]} ; do + log "Building Python API for Python ${PY_VERSION}." + + if [[ -z ${TARGET_WHEEL_PLATFORM} ]] ; then + /usr/bin/env python${PY_VERSION} setup.py bdist_egg bdist_wheel --dist-dir dist/.tmp + cp dist/.tmp/$(ls dist/.tmp | grep .whl) dist + else + /usr/bin/env python${PY_VERSION} setup.py bdist_egg bdist_wheel --dist-dir dist/.tmp --plat ${TARGET_WHEEL_PLATFORM} + /usr/bin/env python3 -m auditwheel repair --plat ${TARGET_WHEEL_PLATFORM} --wheel-dir dist dist/.tmp/$(ls dist/.tmp | grep .whl) + fi + + rm -rf dist/.tmp + + done + +fi + +# ============================================================================== +# -- ...and we are done -------------------------------------------------------- +# ============================================================================== + +popd >/dev/null + +log "Success!" diff --git a/Util/BuildTools/Setup.bat b/Util/BuildTools/Setup.bat index cc19758..52e250b 100644 --- a/Util/BuildTools/Setup.bat +++ b/Util/BuildTools/Setup.bat @@ -1,377 +1,377 @@ -@echo off -setlocal - -rem BAT script that downloads and generates -rem rpclib, gtest and boost libraries for CARLA (carla.org). -rem Run it through a cmd with the x64 Visual C++ Toolset enabled. - -set LOCAL_PATH=%~dp0 -set FILE_N=-[%~n0]: - -rem Print batch params (debug purpose) -echo %FILE_N% [Batch params]: %* - -rem ============================================================================ -rem -- Check for compiler ------------------------------------------------------ -rem ============================================================================ - -where cl 1>nul -if %errorlevel% neq 0 goto error_cl - -rem TODO: check for x64 and not x86 or x64_x86 - -rem ============================================================================ -rem -- Parse arguments --------------------------------------------------------- -rem ============================================================================ - -set BOOST_VERSION=1.72.0 -set INSTALLERS_DIR=%ROOT_PATH:/=\%Util\InstallersWin\ -set VERSION_FILE=%ROOT_PATH:/=\%Util\ContentVersions.txt -set CONTENT_DIR=%ROOT_PATH:/=\%Unreal\CarlaUE4\Content\Carla\ -set CARLA_DEPENDENCIES_FOLDER=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\CarlaDependencies\ -set CARLA_BINARIES_FOLDER=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\Binaries\Win64 -set CARLA_PYTHON_DEPENDENCIES=%ROOT_PATH:/=\%PythonAPI\carla\dependencies\ -set USE_CHRONO=false - -:arg-parse -if not "%1"=="" ( - if "%1"=="-j" ( - set NUMBER_OF_ASYNC_JOBS=%2 - ) - if "%1"=="--boost-toolset" ( - set TOOLSET=%2 - ) - if "%1"=="--chrono" ( - set USE_CHRONO=true - ) - if "%1"=="-h" ( - goto help - ) - if "%1"=="--help" ( - goto help - ) - shift - goto :arg-parse -) - -rem If not defined, use Visual Studio 2019 as tool set -if "%TOOLSET%" == "" set TOOLSET=msvc-14.2 - -rem If is not set, set the number of parallel jobs to the number of CPU threads -if "%NUMBER_OF_ASYNC_JOBS%" == "" set NUMBER_OF_ASYNC_JOBS=%NUMBER_OF_PROCESSORS% - -rem ============================================================================ -rem -- Basic info and setup ---------------------------------------------------- -rem ============================================================================ - -set INSTALLATION_DIR=%INSTALLATION_DIR:/=\% - -echo %FILE_N% Asynchronous jobs: %NUMBER_OF_ASYNC_JOBS% -echo %FILE_N% Boost toolset: %TOOLSET% -echo %FILE_N% Install directory: "%INSTALLATION_DIR%" - -if not exist "%CONTENT_DIR%" ( - echo %FILE_N% Creating "%CONTENT_DIR%" folder... - mkdir "%CONTENT_DIR%" -) - -if not exist "%INSTALLATION_DIR%" ( - echo %FILE_N% Creating "%INSTALLATION_DIR%" folder... - mkdir "%INSTALLATION_DIR%" -) - -rem ============================================================================ -rem -- Download and install zlib ----------------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing zlib... -call "%INSTALLERS_DIR%install_zlib.bat"^ - --build-dir "%INSTALLATION_DIR%" - -if %errorlevel% neq 0 goto failed - -if not defined install_zlib ( - echo %FILE_N% Failed while installing zlib. - goto failed -) else ( - set ZLIB_INSTALL_DIR=%install_zlib% -) - -rem ============================================================================ -rem -- Download and install libpng --------------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing libpng... -call "%INSTALLERS_DIR%install_libpng.bat"^ - --build-dir "%INSTALLATION_DIR%"^ - --zlib-install-dir "%ZLIB_INSTALL_DIR%" - -if %errorlevel% neq 0 goto failed - -if not defined install_libpng ( - echo %FILE_N% Failed while installing libpng. - goto failed -) else ( - set LIBPNG_INSTALL_DIR=%install_libpng% -) - -rem ============================================================================ -rem -- Download and install rpclib --------------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing rpclib... -call "%INSTALLERS_DIR%install_rpclib.bat"^ - --build-dir "%INSTALLATION_DIR%" - -if %errorlevel% neq 0 goto failed - -if not defined install_rpclib ( - echo %FILE_N% Failed while installing rpclib. - goto failed -) - -rem ============================================================================ -rem -- Download and install Google Test ---------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing Google Test... -call "%INSTALLERS_DIR%install_gtest.bat"^ - --build-dir "%INSTALLATION_DIR%" - -if %errorlevel% neq 0 goto failed - -if not defined install_gtest ( - - echo %FILE_N% Failed while installing Google Test. - goto failed -) - -rem ============================================================================ -rem -- Download and install Recast & Detour ------------------------------------ -rem ============================================================================ - -echo %FILE_N% Installing "Recast & Detour"... -call "%INSTALLERS_DIR%install_recast.bat"^ - --build-dir "%INSTALLATION_DIR%" - -if %errorlevel% neq 0 goto failed - -if not defined install_recast ( - - echo %FILE_N% Failed while installing "Recast & Detour". - goto failed -) else ( - set RECAST_INSTALL_DIR=%install_recast:\=/% -) - -rem ============================================================================ -rem -- Download and install Boost ---------------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing Boost... -call "%INSTALLERS_DIR%install_boost.bat"^ - --build-dir "%INSTALLATION_DIR%"^ - --toolset %TOOLSET%^ - --version %BOOST_VERSION%^ - -j %NUMBER_OF_ASYNC_JOBS% - -if %errorlevel% neq 0 goto failed - -if not defined install_boost ( - echo %FILE_N% Failed while installing Boost. - goto failed -) - -copy /Y "%INSTALLATION_DIR%..\Util\BoostFiles\rational.hpp" "%INSTALLATION_DIR%boost-%BOOST_VERSION%-install\include\boost\rational.hpp" -copy /Y "%INSTALLATION_DIR%..\Util\BoostFiles\read.hpp" "%INSTALLATION_DIR%boost-%BOOST_VERSION%-install\include\boost\geometry\io\wkt\read.hpp" - -if not exist "%CARLA_PYTHON_DEPENDENCIES%" ( - mkdir "%CARLA_PYTHON_DEPENDENCIES%"\lib -) -rem ============================================================================ -rem -- Download and install Xercesc -------------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing Xercesc... -call "%INSTALLERS_DIR%install_xercesc.bat"^ - --build-dir "%INSTALLATION_DIR%" -copy %INSTALLATION_DIR%\xerces-c-3.2.3-install\lib\xerces-c_3.lib %CARLA_PYTHON_DEPENDENCIES%\lib - -rem ============================================================================ -rem -- Download and install Sqlite3 -------------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing Sqlite3 -call "%INSTALLERS_DIR%install_sqlite3.bat"^ - --build-dir "%INSTALLATION_DIR%" -copy %INSTALLATION_DIR%\sqlite3-install\lib\sqlite3.lib %CARLA_PYTHON_DEPENDENCIES%\lib - -rem ============================================================================ -rem -- Download and install PROJ -------------------------------------------- -rem ============================================================================ - -echo %FILE_N% Installing PROJ -call "%INSTALLERS_DIR%install_proj.bat"^ - --build-dir "%INSTALLATION_DIR%" -copy %INSTALLATION_DIR%\proj-install\lib\proj.lib %CARLA_PYTHON_DEPENDENCIES%\lib - -rem ============================================================================ -rem -- Download and install Chrono ---------------------------------------------- -rem ============================================================================ - -if %USE_CHRONO% == true ( - echo %FILE_N% Installing Chrono... - call "%INSTALLERS_DIR%install_chrono.bat"^ - --build-dir "%INSTALLATION_DIR%" - - if not exist "%CARLA_DEPENDENCIES_FOLDER%" ( - mkdir "%CARLA_DEPENDENCIES_FOLDER%" - ) - if not exist "%CARLA_DEPENDENCIES_FOLDER%include" ( - mkdir "%CARLA_DEPENDENCIES_FOLDER%include" - ) - if not exist "%CARLA_DEPENDENCIES_FOLDER%lib" ( - mkdir "%CARLA_DEPENDENCIES_FOLDER%lib" - ) - if not exist "%CARLA_DEPENDENCIES_FOLDER%dll" ( - mkdir "%CARLA_DEPENDENCIES_FOLDER%dll" - ) - echo "%INSTALLATION_DIR%chrono-install\include\*" "%CARLA_DEPENDENCIES_FOLDER%include\*" > NUL - xcopy /Y /S /I "%INSTALLATION_DIR%chrono-install\include\*" "%CARLA_DEPENDENCIES_FOLDER%include\*" > NUL - copy "%INSTALLATION_DIR%chrono-install\lib\*.lib" "%CARLA_DEPENDENCIES_FOLDER%lib\*.lib" > NUL - copy "%INSTALLATION_DIR%chrono-install\bin\*.dll" "%CARLA_DEPENDENCIES_FOLDER%dll\*.dll" > NUL - xcopy /Y /S /I "%INSTALLATION_DIR%eigen-install\include\*" "%CARLA_DEPENDENCIES_FOLDER%include\*" > NUL -) - -rem ============================================================================ -rem -- Assets download URL ----------------------------------------------------- -rem ============================================================================ - -FOR /F "usebackq tokens=1,2" %%i in ("%VERSION_FILE%") do ( - set ASSETS_VERSION=%%i - set HASH=%%j -) -set URL=http://carla-assets.s3.amazonaws.com/%HASH%.tar.gz - -rem ============================================================================ -rem -- Generate CMake ---------------------------------------------------------- -rem ============================================================================ - -for /f %%i in ('git describe --tags --dirty --always') do set carla_version=%%i -set CMAKE_INSTALLATION_DIR=%INSTALLATION_DIR:\=/% - -echo %FILE_N% Creating "CMakeLists.txt.in"... - -set CMAKE_CONFIG_FILE=%INSTALLATION_DIR%CMakeLists.txt.in - - >"%CMAKE_CONFIG_FILE%" echo # Automatically generated by Setup.bat ->>"%CMAKE_CONFIG_FILE%" echo set(CARLA_VERSION %carla_version%) ->>"%CMAKE_CONFIG_FILE%" echo. ->>"%CMAKE_CONFIG_FILE%" echo set(CMAKE_CXX_STANDARD 14) ->>"%CMAKE_CONFIG_FILE%" echo set(CMAKE_CXX_STANDARD_REQUIRED ON) ->>"%CMAKE_CONFIG_FILE%" echo. ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-D_WIN32_WINNT=0x0600) ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DHAVE_SNPRINTF) ->>"%CMAKE_CONFIG_FILE%" echo STRING (REGEX REPLACE "/RTC(su|[1su])" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") ->>"%CMAKE_CONFIG_FILE%" echo. ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_ERROR_CODE_HEADER_ONLY) ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DLIBCARLA_IMAGE_WITH_PNG_SUPPORT) ->>"%CMAKE_CONFIG_FILE%" echo. ->>"%CMAKE_CONFIG_FILE%" echo set(BOOST_INCLUDE_PATH "%CMAKE_INSTALLATION_DIR%boost-%BOOST_VERSION%-install/include") ->>"%CMAKE_CONFIG_FILE%" echo set(BOOST_LIB_PATH "%CMAKE_INSTALLATION_DIR%boost-%BOOST_VERSION%-install/lib") ->>"%CMAKE_CONFIG_FILE%" echo. ->>"%CMAKE_CONFIG_FILE%" echo set(RPCLIB_INCLUDE_PATH "%CMAKE_INSTALLATION_DIR%rpclib-install/include") ->>"%CMAKE_CONFIG_FILE%" echo set(RPCLIB_LIB_PATH "%CMAKE_INSTALLATION_DIR%rpclib-install/lib") ->>"%CMAKE_CONFIG_FILE%" echo. ->>"%CMAKE_CONFIG_FILE%" echo if (CMAKE_BUILD_TYPE STREQUAL "Server") ->>"%CMAKE_CONFIG_FILE%" echo # Prevent exceptions ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_TYPE_INDEX_FORCE_NO_RTTI_COMPATIBILITY) ->>"%CMAKE_CONFIG_FILE%" echo add_compile_options(/EHsc) ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DASIO_NO_EXCEPTIONS) ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_NO_EXCEPTIONS) ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DLIBCARLA_NO_EXCEPTIONS) ->>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DPUGIXML_NO_EXCEPTIONS) ->>"%CMAKE_CONFIG_FILE%" echo # Specific libraries for server ->>"%CMAKE_CONFIG_FILE%" echo set(GTEST_INCLUDE_PATH "%CMAKE_INSTALLATION_DIR%gtest-install/include") ->>"%CMAKE_CONFIG_FILE%" echo set(GTEST_LIB_PATH "%CMAKE_INSTALLATION_DIR%gtest-install/lib") ->>"%CMAKE_CONFIG_FILE%" echo elseif (CMAKE_BUILD_TYPE STREQUAL "Client") ->>"%CMAKE_CONFIG_FILE%" echo # Specific libraries for client ->>"%CMAKE_CONFIG_FILE%" echo set(ZLIB_INCLUDE_PATH "%ZLIB_INSTALL_DIR:\=/%/include") ->>"%CMAKE_CONFIG_FILE%" echo set(ZLIB_LIB_PATH "%ZLIB_INSTALL_DIR:\=/%/lib") ->>"%CMAKE_CONFIG_FILE%" echo set(LIBPNG_INCLUDE_PATH "%LIBPNG_INSTALL_DIR:\=/%/include") ->>"%CMAKE_CONFIG_FILE%" echo set(LIBPNG_LIB_PATH "%LIBPNG_INSTALL_DIR:\=/%/lib") ->>"%CMAKE_CONFIG_FILE%" echo set(RECAST_INCLUDE_PATH "%RECAST_INSTALL_DIR:\=/%/include") ->>"%CMAKE_CONFIG_FILE%" echo set(RECAST_LIB_PATH "%RECAST_INSTALL_DIR:\=/%/lib") ->>"%CMAKE_CONFIG_FILE%" echo endif () - -goto success - -rem ============================================================================ -rem -- Messages and Errors ----------------------------------------------------- -rem ============================================================================ - -:success - echo %FILE_N% - echo ########### - echo # SUCCESS # - echo ########### - echo. - echo IMPORTANT! - echo. - echo All the CARLA library dependences should be installed now. - echo (You can remove all "*-src" folders in %INSTALLATION_DIR% directory) - echo. - echo You only need the ASSET PACK with all the meshes and textures. - echo. - echo This script provides the assets for CARLA %ASSETS_VERSION% - echo You can download the assets from here: - echo. - echo %URL% - echo. - echo Unzip it in the "%CONTENT_DIR%" folder. - echo If you want another version, search it in %VERSION_FILE%. - echo. - goto good_exit - -:help - echo Download and compiles all the necessary libraries to build CARLA. - echo. - echo Commands: - echo -h, --help -^> Shows this dialog. - echo -j ^ -^> N is the integer number of async jobs while compiling (default=1). - echo --boost-toolset [T] -^> Toolset corresponding to your compiler ^(default=^*^): - echo Visual Studio 2013 -^> msvc-12.0 - echo Visual Studio 2015 -^> msvc-14.0 - echo Visual Studio 2017 -^> msvc-14.1 - echo Visual Studio 2019 -^> msvc-14.2 * - goto good_exit - -:error_cl - echo. - echo %FILE_N% [ERROR] Can't find Visual Studio compiler (cl.exe). - echo [ERROR] Possible causes: - echo [ERROR] - Make sure you use x64 (not x64_x86!) - echo [ERROR] - You are not using "Visual Studio x64 Native Tools Command Prompt". - goto failed - -:failed - echo. - echo %FILE_N% - echo Ok, and error ocurred, don't panic! - echo We have different platforms where you can find some help :) - echo. - echo - Make sure you have read the documentation: - echo http://carla.readthedocs.io/en/latest/how_to_build_on_windows/ - echo. - echo - If the problem persists, you can ask on our Github's "Building on Windows" issue: - echo https://github.com/carla-simulator/carla/issues/21 - echo. - echo - Or just use our Discord channel! - echo We'll be glad to help you there :) - echo https://discord.gg/42KJdRj - endlocal - exit /b %errorlevel% - -:good_exit - endlocal - exit /b 0 +@echo off +setlocal + +rem BAT script that downloads and generates +rem rpclib, gtest and boost libraries for CARLA (carla.org). +rem Run it through a cmd with the x64 Visual C++ Toolset enabled. + +set LOCAL_PATH=%~dp0 +set FILE_N=-[%~n0]: + +rem Print batch params (debug purpose) +echo %FILE_N% [Batch params]: %* + +rem ============================================================================ +rem -- Check for compiler ------------------------------------------------------ +rem ============================================================================ + +where cl 1>nul +if %errorlevel% neq 0 goto error_cl + +rem TODO: check for x64 and not x86 or x64_x86 + +rem ============================================================================ +rem -- Parse arguments --------------------------------------------------------- +rem ============================================================================ + +set BOOST_VERSION=1.72.0 +set INSTALLERS_DIR=%ROOT_PATH:/=\%Util\InstallersWin\ +set VERSION_FILE=%ROOT_PATH:/=\%Util\ContentVersions.txt +set CONTENT_DIR=%ROOT_PATH:/=\%Unreal\CarlaUE4\Content\Carla\ +set CARLA_DEPENDENCIES_FOLDER=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\CarlaDependencies\ +set CARLA_BINARIES_FOLDER=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\Binaries\Win64 +set CARLA_PYTHON_DEPENDENCIES=%ROOT_PATH:/=\%PythonAPI\carla\dependencies\ +set USE_CHRONO=false + +:arg-parse +if not "%1"=="" ( + if "%1"=="-j" ( + set NUMBER_OF_ASYNC_JOBS=%2 + ) + if "%1"=="--boost-toolset" ( + set TOOLSET=%2 + ) + if "%1"=="--chrono" ( + set USE_CHRONO=true + ) + if "%1"=="-h" ( + goto help + ) + if "%1"=="--help" ( + goto help + ) + shift + goto :arg-parse +) + +rem If not defined, use Visual Studio 2019 as tool set +if "%TOOLSET%" == "" set TOOLSET=msvc-14.2 + +rem If is not set, set the number of parallel jobs to the number of CPU threads +if "%NUMBER_OF_ASYNC_JOBS%" == "" set NUMBER_OF_ASYNC_JOBS=%NUMBER_OF_PROCESSORS% + +rem ============================================================================ +rem -- Basic info and setup ---------------------------------------------------- +rem ============================================================================ + +set INSTALLATION_DIR=%INSTALLATION_DIR:/=\% + +echo %FILE_N% Asynchronous jobs: %NUMBER_OF_ASYNC_JOBS% +echo %FILE_N% Boost toolset: %TOOLSET% +echo %FILE_N% Install directory: "%INSTALLATION_DIR%" + +if not exist "%CONTENT_DIR%" ( + echo %FILE_N% Creating "%CONTENT_DIR%" folder... + mkdir "%CONTENT_DIR%" +) + +if not exist "%INSTALLATION_DIR%" ( + echo %FILE_N% Creating "%INSTALLATION_DIR%" folder... + mkdir "%INSTALLATION_DIR%" +) + +rem ============================================================================ +rem -- Download and install zlib ----------------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing zlib... +call "%INSTALLERS_DIR%install_zlib.bat"^ + --build-dir "%INSTALLATION_DIR%" + +if %errorlevel% neq 0 goto failed + +if not defined install_zlib ( + echo %FILE_N% Failed while installing zlib. + goto failed +) else ( + set ZLIB_INSTALL_DIR=%install_zlib% +) + +rem ============================================================================ +rem -- Download and install libpng --------------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing libpng... +call "%INSTALLERS_DIR%install_libpng.bat"^ + --build-dir "%INSTALLATION_DIR%"^ + --zlib-install-dir "%ZLIB_INSTALL_DIR%" + +if %errorlevel% neq 0 goto failed + +if not defined install_libpng ( + echo %FILE_N% Failed while installing libpng. + goto failed +) else ( + set LIBPNG_INSTALL_DIR=%install_libpng% +) + +rem ============================================================================ +rem -- Download and install rpclib --------------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing rpclib... +call "%INSTALLERS_DIR%install_rpclib.bat"^ + --build-dir "%INSTALLATION_DIR%" + +if %errorlevel% neq 0 goto failed + +if not defined install_rpclib ( + echo %FILE_N% Failed while installing rpclib. + goto failed +) + +rem ============================================================================ +rem -- Download and install Google Test ---------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing Google Test... +call "%INSTALLERS_DIR%install_gtest.bat"^ + --build-dir "%INSTALLATION_DIR%" + +if %errorlevel% neq 0 goto failed + +if not defined install_gtest ( + + echo %FILE_N% Failed while installing Google Test. + goto failed +) + +rem ============================================================================ +rem -- Download and install Recast & Detour ------------------------------------ +rem ============================================================================ + +echo %FILE_N% Installing "Recast & Detour"... +call "%INSTALLERS_DIR%install_recast.bat"^ + --build-dir "%INSTALLATION_DIR%" + +if %errorlevel% neq 0 goto failed + +if not defined install_recast ( + + echo %FILE_N% Failed while installing "Recast & Detour". + goto failed +) else ( + set RECAST_INSTALL_DIR=%install_recast:\=/% +) + +rem ============================================================================ +rem -- Download and install Boost ---------------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing Boost... +call "%INSTALLERS_DIR%install_boost.bat"^ + --build-dir "%INSTALLATION_DIR%"^ + --toolset %TOOLSET%^ + --version %BOOST_VERSION%^ + -j %NUMBER_OF_ASYNC_JOBS% + +if %errorlevel% neq 0 goto failed + +if not defined install_boost ( + echo %FILE_N% Failed while installing Boost. + goto failed +) + +copy /Y "%INSTALLATION_DIR%..\Util\BoostFiles\rational.hpp" "%INSTALLATION_DIR%boost-%BOOST_VERSION%-install\include\boost\rational.hpp" +copy /Y "%INSTALLATION_DIR%..\Util\BoostFiles\read.hpp" "%INSTALLATION_DIR%boost-%BOOST_VERSION%-install\include\boost\geometry\io\wkt\read.hpp" + +if not exist "%CARLA_PYTHON_DEPENDENCIES%" ( + mkdir "%CARLA_PYTHON_DEPENDENCIES%"\lib +) +rem ============================================================================ +rem -- Download and install Xercesc -------------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing Xercesc... +call "%INSTALLERS_DIR%install_xercesc.bat"^ + --build-dir "%INSTALLATION_DIR%" +copy %INSTALLATION_DIR%\xerces-c-3.2.3-install\lib\xerces-c_3.lib %CARLA_PYTHON_DEPENDENCIES%\lib + +rem ============================================================================ +rem -- Download and install Sqlite3 -------------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing Sqlite3 +call "%INSTALLERS_DIR%install_sqlite3.bat"^ + --build-dir "%INSTALLATION_DIR%" +copy %INSTALLATION_DIR%\sqlite3-install\lib\sqlite3.lib %CARLA_PYTHON_DEPENDENCIES%\lib + +rem ============================================================================ +rem -- Download and install PROJ -------------------------------------------- +rem ============================================================================ + +echo %FILE_N% Installing PROJ +call "%INSTALLERS_DIR%install_proj.bat"^ + --build-dir "%INSTALLATION_DIR%" +copy %INSTALLATION_DIR%\proj-install\lib\proj.lib %CARLA_PYTHON_DEPENDENCIES%\lib + +rem ============================================================================ +rem -- Download and install Chrono ---------------------------------------------- +rem ============================================================================ + +if %USE_CHRONO% == true ( + echo %FILE_N% Installing Chrono... + call "%INSTALLERS_DIR%install_chrono.bat"^ + --build-dir "%INSTALLATION_DIR%" + + if not exist "%CARLA_DEPENDENCIES_FOLDER%" ( + mkdir "%CARLA_DEPENDENCIES_FOLDER%" + ) + if not exist "%CARLA_DEPENDENCIES_FOLDER%include" ( + mkdir "%CARLA_DEPENDENCIES_FOLDER%include" + ) + if not exist "%CARLA_DEPENDENCIES_FOLDER%lib" ( + mkdir "%CARLA_DEPENDENCIES_FOLDER%lib" + ) + if not exist "%CARLA_DEPENDENCIES_FOLDER%dll" ( + mkdir "%CARLA_DEPENDENCIES_FOLDER%dll" + ) + echo "%INSTALLATION_DIR%chrono-install\include\*" "%CARLA_DEPENDENCIES_FOLDER%include\*" > NUL + xcopy /Y /S /I "%INSTALLATION_DIR%chrono-install\include\*" "%CARLA_DEPENDENCIES_FOLDER%include\*" > NUL + copy "%INSTALLATION_DIR%chrono-install\lib\*.lib" "%CARLA_DEPENDENCIES_FOLDER%lib\*.lib" > NUL + copy "%INSTALLATION_DIR%chrono-install\bin\*.dll" "%CARLA_DEPENDENCIES_FOLDER%dll\*.dll" > NUL + xcopy /Y /S /I "%INSTALLATION_DIR%eigen-install\include\*" "%CARLA_DEPENDENCIES_FOLDER%include\*" > NUL +) + +rem ============================================================================ +rem -- Assets download URL ----------------------------------------------------- +rem ============================================================================ + +FOR /F "usebackq tokens=1,2" %%i in ("%VERSION_FILE%") do ( + set ASSETS_VERSION=%%i + set HASH=%%j +) +set URL=http://carla-assets.s3.amazonaws.com/%HASH%.tar.gz + +rem ============================================================================ +rem -- Generate CMake ---------------------------------------------------------- +rem ============================================================================ + +for /f %%i in ('git describe --tags --dirty --always') do set carla_version=%%i +set CMAKE_INSTALLATION_DIR=%INSTALLATION_DIR:\=/% + +echo %FILE_N% Creating "CMakeLists.txt.in"... + +set CMAKE_CONFIG_FILE=%INSTALLATION_DIR%CMakeLists.txt.in + + >"%CMAKE_CONFIG_FILE%" echo # Automatically generated by Setup.bat +>>"%CMAKE_CONFIG_FILE%" echo set(CARLA_VERSION %carla_version%) +>>"%CMAKE_CONFIG_FILE%" echo. +>>"%CMAKE_CONFIG_FILE%" echo set(CMAKE_CXX_STANDARD 14) +>>"%CMAKE_CONFIG_FILE%" echo set(CMAKE_CXX_STANDARD_REQUIRED ON) +>>"%CMAKE_CONFIG_FILE%" echo. +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-D_WIN32_WINNT=0x0600) +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DHAVE_SNPRINTF) +>>"%CMAKE_CONFIG_FILE%" echo STRING (REGEX REPLACE "/RTC(su|[1su])" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") +>>"%CMAKE_CONFIG_FILE%" echo. +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_ERROR_CODE_HEADER_ONLY) +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DLIBCARLA_IMAGE_WITH_PNG_SUPPORT) +>>"%CMAKE_CONFIG_FILE%" echo. +>>"%CMAKE_CONFIG_FILE%" echo set(BOOST_INCLUDE_PATH "%CMAKE_INSTALLATION_DIR%boost-%BOOST_VERSION%-install/include") +>>"%CMAKE_CONFIG_FILE%" echo set(BOOST_LIB_PATH "%CMAKE_INSTALLATION_DIR%boost-%BOOST_VERSION%-install/lib") +>>"%CMAKE_CONFIG_FILE%" echo. +>>"%CMAKE_CONFIG_FILE%" echo set(RPCLIB_INCLUDE_PATH "%CMAKE_INSTALLATION_DIR%rpclib-install/include") +>>"%CMAKE_CONFIG_FILE%" echo set(RPCLIB_LIB_PATH "%CMAKE_INSTALLATION_DIR%rpclib-install/lib") +>>"%CMAKE_CONFIG_FILE%" echo. +>>"%CMAKE_CONFIG_FILE%" echo if (CMAKE_BUILD_TYPE STREQUAL "Server") +>>"%CMAKE_CONFIG_FILE%" echo # Prevent exceptions +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_TYPE_INDEX_FORCE_NO_RTTI_COMPATIBILITY) +>>"%CMAKE_CONFIG_FILE%" echo add_compile_options(/EHsc) +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DASIO_NO_EXCEPTIONS) +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_NO_EXCEPTIONS) +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DLIBCARLA_NO_EXCEPTIONS) +>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DPUGIXML_NO_EXCEPTIONS) +>>"%CMAKE_CONFIG_FILE%" echo # Specific libraries for server +>>"%CMAKE_CONFIG_FILE%" echo set(GTEST_INCLUDE_PATH "%CMAKE_INSTALLATION_DIR%gtest-install/include") +>>"%CMAKE_CONFIG_FILE%" echo set(GTEST_LIB_PATH "%CMAKE_INSTALLATION_DIR%gtest-install/lib") +>>"%CMAKE_CONFIG_FILE%" echo elseif (CMAKE_BUILD_TYPE STREQUAL "Client") +>>"%CMAKE_CONFIG_FILE%" echo # Specific libraries for client +>>"%CMAKE_CONFIG_FILE%" echo set(ZLIB_INCLUDE_PATH "%ZLIB_INSTALL_DIR:\=/%/include") +>>"%CMAKE_CONFIG_FILE%" echo set(ZLIB_LIB_PATH "%ZLIB_INSTALL_DIR:\=/%/lib") +>>"%CMAKE_CONFIG_FILE%" echo set(LIBPNG_INCLUDE_PATH "%LIBPNG_INSTALL_DIR:\=/%/include") +>>"%CMAKE_CONFIG_FILE%" echo set(LIBPNG_LIB_PATH "%LIBPNG_INSTALL_DIR:\=/%/lib") +>>"%CMAKE_CONFIG_FILE%" echo set(RECAST_INCLUDE_PATH "%RECAST_INSTALL_DIR:\=/%/include") +>>"%CMAKE_CONFIG_FILE%" echo set(RECAST_LIB_PATH "%RECAST_INSTALL_DIR:\=/%/lib") +>>"%CMAKE_CONFIG_FILE%" echo endif () + +goto success + +rem ============================================================================ +rem -- Messages and Errors ----------------------------------------------------- +rem ============================================================================ + +:success + echo %FILE_N% + echo ########### + echo # SUCCESS # + echo ########### + echo. + echo IMPORTANT! + echo. + echo All the CARLA library dependences should be installed now. + echo (You can remove all "*-src" folders in %INSTALLATION_DIR% directory) + echo. + echo You only need the ASSET PACK with all the meshes and textures. + echo. + echo This script provides the assets for CARLA %ASSETS_VERSION% + echo You can download the assets from here: + echo. + echo %URL% + echo. + echo Unzip it in the "%CONTENT_DIR%" folder. + echo If you want another version, search it in %VERSION_FILE%. + echo. + goto good_exit + +:help + echo Download and compiles all the necessary libraries to build CARLA. + echo. + echo Commands: + echo -h, --help -^> Shows this dialog. + echo -j ^ -^> N is the integer number of async jobs while compiling (default=1). + echo --boost-toolset [T] -^> Toolset corresponding to your compiler ^(default=^*^): + echo Visual Studio 2013 -^> msvc-12.0 + echo Visual Studio 2015 -^> msvc-14.0 + echo Visual Studio 2017 -^> msvc-14.1 + echo Visual Studio 2019 -^> msvc-14.2 * + goto good_exit + +:error_cl + echo. + echo %FILE_N% [ERROR] Can't find Visual Studio compiler (cl.exe). + echo [ERROR] Possible causes: + echo [ERROR] - Make sure you use x64 (not x64_x86!) + echo [ERROR] - You are not using "Visual Studio x64 Native Tools Command Prompt". + goto failed + +:failed + echo. + echo %FILE_N% + echo Ok, and error ocurred, don't panic! + echo We have different platforms where you can find some help :) + echo. + echo - Make sure you have read the documentation: + echo http://carla.readthedocs.io/en/latest/how_to_build_on_windows/ + echo. + echo - If the problem persists, you can ask on our Github's "Building on Windows" issue: + echo https://github.com/carla-simulator/carla/issues/21 + echo. + echo - Or just use our Discord channel! + echo We'll be glad to help you there :) + echo https://discord.gg/42KJdRj + endlocal + exit /b %errorlevel% + +:good_exit + endlocal + exit /b 0 diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 0467453..4490b61 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -1,805 +1,805 @@ -#! /bin/bash - -# ============================================================================== -# -- Parse arguments ----------------------------------------------------------- -# ============================================================================== - -DOC_STRING="Download and install the required libraries for carla." - -USAGE_STRING="Usage: $0 [--python-version=VERSION]" - -OPTS=`getopt -o h --long help,chrono,python-version: -n 'parse-options' -- "$@"` - -eval set -- "$OPTS" - -PY_VERSION_LIST=3 -USE_CHRONO=false - -while [[ $# -gt 0 ]]; do - case "$1" in - --python-version ) - PY_VERSION_LIST="$2"; - shift 2 ;; - --chrono ) - USE_CHRONO=true; - shift ;; - -h | --help ) - echo "$DOC_STRING" - echo "$USAGE_STRING" - exit 1 - ;; - * ) - shift ;; - esac -done - -# ============================================================================== -# -- Set up environment -------------------------------------------------------- -# ============================================================================== - -command -v /usr/bin/clang++ >/dev/null 2>&1 || { - echo >&2 "clang is required, but it's not installed."; - exit 1; -} - -CXX_TAG=c8 -export CC=/usr/bin/clang -export CXX=/usr/bin/clang++ - -source $(dirname "$0")/Environment.sh - -# Convert comma-separated string to array of unique elements. -IFS="," read -r -a PY_VERSION_LIST <<< "${PY_VERSION_LIST}" - -mkdir -p ${CARLA_BUILD_FOLDER} -pushd ${CARLA_BUILD_FOLDER} >/dev/null - -# ============================================================================== -# -- Get and compile libc++ ---------------------------------------------------- -# ============================================================================== - -LLVM_BASENAME=llvm-8.0 - -LLVM_INCLUDE=${PWD}/${LLVM_BASENAME}-install/include/c++/v1 -LLVM_LIBPATH=${PWD}/${LLVM_BASENAME}-install/lib - -if [[ -d "${LLVM_BASENAME}-install" ]] ; then - log "${LLVM_BASENAME} already installed." -else - rm -Rf ${LLVM_BASENAME}-source ${LLVM_BASENAME}-build - - log "Retrieving libc++." - - git clone --depth=1 -b release_80 https://github.com/llvm-mirror/llvm.git ${LLVM_BASENAME}-source - git clone --depth=1 -b release_80 https://github.com/llvm-mirror/libcxx.git ${LLVM_BASENAME}-source/projects/libcxx - git clone --depth=1 -b release_80 https://github.com/llvm-mirror/libcxxabi.git ${LLVM_BASENAME}-source/projects/libcxxabi - - log "Compiling libc++." - - mkdir -p ${LLVM_BASENAME}-build - - pushd ${LLVM_BASENAME}-build >/dev/null - - cmake -G "Ninja" \ - -DLIBCXX_ENABLE_EXPERIMENTAL_LIBRARY=OFF \ - -DLIBCXX_INSTALL_EXPERIMENTAL_LIBRARY=OFF \ - -DLLVM_ENABLE_EH=OFF \ - -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX="../${LLVM_BASENAME}-install" \ - ../${LLVM_BASENAME}-source - - ninja cxx - - ninja install-libcxx - - ninja install-libcxxabi - - popd >/dev/null - - rm -Rf ${LLVM_BASENAME}-source ${LLVM_BASENAME}-build - -fi - -unset LLVM_BASENAME - -# ============================================================================== -# -- Get boost includes -------------------------------------------------------- -# ============================================================================== - -BOOST_VERSION=1.72.0 -BOOST_BASENAME="boost-${BOOST_VERSION}-${CXX_TAG}" - -BOOST_INCLUDE=${PWD}/${BOOST_BASENAME}-install/include -BOOST_LIBPATH=${PWD}/${BOOST_BASENAME}-install/lib - -for PY_VERSION in ${PY_VERSION_LIST[@]} ; do - - SHOULD_BUILD_BOOST=true - PYTHON_VERSION=$(/usr/bin/env python${PY_VERSION} -V 2>&1) - LIB_NAME=${PYTHON_VERSION:7:3} - LIB_NAME=${LIB_NAME//.} - if [[ -d "${BOOST_BASENAME}-install" ]] ; then - if [ -f "${BOOST_BASENAME}-install/lib/libboost_python${LIB_NAME}.a" ] ; then - SHOULD_BUILD_BOOST=false - log "${BOOST_BASENAME} already installed." - fi - fi - - if { ${SHOULD_BUILD_BOOST} ; } ; then - rm -Rf ${BOOST_BASENAME}-source - - BOOST_PACKAGE_BASENAME=boost_${BOOST_VERSION//./_} - - log "Retrieving boost." - wget "https://boostorg.jfrog.io/artifactory/main/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" || true - # try to use the backup boost we have in Jenkins - if [[ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ]] ; then - log "Using boost backup" - wget "https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" || true - fi - - log "Extracting boost for Python ${PY_VERSION}." - tar -xzf ${BOOST_PACKAGE_BASENAME}.tar.gz - mkdir -p ${BOOST_BASENAME}-install/include - mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-source - # Boost patch for exception handling - cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/rational.hpp" "${BOOST_BASENAME}-source/boost/rational.hpp" - cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/read.hpp" "${BOOST_BASENAME}-source/boost/geometry/io/wkt/read.hpp" - # --- - - pushd ${BOOST_BASENAME}-source >/dev/null - - BOOST_TOOLSET="clang" - BOOST_CFLAGS="-fPIC -std=c++14 -DBOOST_ERROR_CODE_HEADER_ONLY" - - py3="/usr/bin/env python${PY_VERSION}" - py3_root=`${py3} -c "import sys; print(sys.prefix)"` - pyv=`$py3 -c "import sys;x='{v[0]}.{v[1]}'.format(v=list(sys.version_info[:2]));sys.stdout.write(x)";` - ./bootstrap.sh \ - --with-toolset=clang \ - --prefix=../boost-install \ - --with-libraries=python,filesystem,system,program_options \ - --with-python=${py3} --with-python-root=${py3_root} - - if ${TRAVIS} ; then - echo "using python : ${pyv} : ${py3_root}/bin/python${PY_VERSION} ;" > ${HOME}/user-config.jam - else - echo "using python : ${pyv} : ${py3_root}/bin/python${PY_VERSION} ;" > project-config.jam - fi - - ./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j ${CARLA_BUILD_CONCURRENCY} stage release - ./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j ${CARLA_BUILD_CONCURRENCY} install - - popd >/dev/null - - rm -Rf ${BOOST_BASENAME}-source - rm ${BOOST_PACKAGE_BASENAME}.tar.gz - - # Boost patch for exception handling - cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/rational.hpp" "${BOOST_BASENAME}-install/include/boost/rational.hpp" - cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/read.hpp" "${BOOST_BASENAME}-install/include/boost/geometry/io/wkt/read.hpp" - # --- - - # Install boost dependencies - mkdir -p "${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/system" - mkdir -p "${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib" - cp -rf ${BOOST_BASENAME}-install/include/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/system - cp -rf ${BOOST_BASENAME}-install/lib/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib - - fi - -done - -unset BOOST_BASENAME - -# ============================================================================== -# -- Get rpclib and compile it with libc++ and libstdc++ ----------------------- -# ============================================================================== - -RPCLIB_PATCH=v2.2.1_c5 -RPCLIB_BASENAME=rpclib-${RPCLIB_PATCH}-${CXX_TAG} - -RPCLIB_LIBCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libcxx-install/include -RPCLIB_LIBCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libcxx-install/lib -RPCLIB_LIBSTDCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/include -RPCLIB_LIBSTDCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/lib - -if [[ -d "${RPCLIB_BASENAME}-libcxx-install" && -d "${RPCLIB_BASENAME}-libstdcxx-install" ]] ; then - log "${RPCLIB_BASENAME} already installed." -else - rm -Rf \ - ${RPCLIB_BASENAME}-source \ - ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build \ - ${RPCLIB_BASENAME}-libcxx-install ${RPCLIB_BASENAME}-libstdcxx-install - - log "Retrieving rpclib." - - git clone -b ${RPCLIB_PATCH} https://github.com/carla-simulator/rpclib.git ${RPCLIB_BASENAME}-source - - log "Building rpclib with libc++." - - # rpclib does not use any cmake 3.9 feature. - # As cmake 3.9 is not standard in Ubuntu 16.04, change cmake version to 3.5 - sed -i s/"3.9.0"/"3.5.0"/g ${RPCLIB_BASENAME}-source/CMakeLists.txt - - mkdir -p ${RPCLIB_BASENAME}-libcxx-build - - pushd ${RPCLIB_BASENAME}-libcxx-build >/dev/null - - cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} -DBOOST_NO_EXCEPTIONS -DASIO_NO_EXCEPTIONS" \ - -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libcxx-install" \ - ../${RPCLIB_BASENAME}-source - - ninja - - ninja install - - popd >/dev/null - - log "Building rpclib with libstdc++." - - mkdir -p ${RPCLIB_BASENAME}-libstdcxx-build - - pushd ${RPCLIB_BASENAME}-libstdcxx-build >/dev/null - - cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14" \ - -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libstdcxx-install" \ - ../${RPCLIB_BASENAME}-source - - ninja - - ninja install - - popd >/dev/null - - rm -Rf ${RPCLIB_BASENAME}-source ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build - -fi - -unset RPCLIB_BASENAME - -# ============================================================================== -# -- Get GTest and compile it with libc++ -------------------------------------- -# ============================================================================== - -GTEST_VERSION=1.8.1 -GTEST_BASENAME=gtest-${GTEST_VERSION}-${CXX_TAG} - -GTEST_LIBCXX_INCLUDE=${PWD}/${GTEST_BASENAME}-libcxx-install/include -GTEST_LIBCXX_LIBPATH=${PWD}/${GTEST_BASENAME}-libcxx-install/lib -GTEST_LIBSTDCXX_INCLUDE=${PWD}/${GTEST_BASENAME}-libstdcxx-install/include -GTEST_LIBSTDCXX_LIBPATH=${PWD}/${GTEST_BASENAME}-libstdcxx-install/lib - -if [[ -d "${GTEST_BASENAME}-libcxx-install" && -d "${GTEST_BASENAME}-libstdcxx-install" ]] ; then - log "${GTEST_BASENAME} already installed." -else - rm -Rf \ - ${GTEST_BASENAME}-source \ - ${GTEST_BASENAME}-libcxx-build ${GTEST_BASENAME}-libstdcxx-build \ - ${GTEST_BASENAME}-libcxx-install ${GTEST_BASENAME}-libstdcxx-install - - log "Retrieving Google Test." - - git clone --depth=1 -b release-${GTEST_VERSION} https://github.com/google/googletest.git ${GTEST_BASENAME}-source - - log "Building Google Test with libc++." - - mkdir -p ${GTEST_BASENAME}-libcxx-build - - pushd ${GTEST_BASENAME}-libcxx-build >/dev/null - - cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} -DBOOST_NO_EXCEPTIONS -fno-exceptions" \ - -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-libcxx-install" \ - ../${GTEST_BASENAME}-source - - ninja - - ninja install - - popd >/dev/null - - log "Building Google Test with libstdc++." - - mkdir -p ${GTEST_BASENAME}-libstdcxx-build - - pushd ${GTEST_BASENAME}-libstdcxx-build >/dev/null - - cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14" \ - -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-libstdcxx-install" \ - ../${GTEST_BASENAME}-source - - ninja - - ninja install - - popd >/dev/null - - rm -Rf ${GTEST_BASENAME}-source ${GTEST_BASENAME}-libcxx-build ${GTEST_BASENAME}-libstdcxx-build - -fi - -unset GTEST_BASENAME - -# ============================================================================== -# -- Get Recast&Detour and compile it with libc++ ------------------------------ -# ============================================================================== - -RECAST_HASH=0b13b0 -RECAST_COMMIT=0b13b0d288ac96fdc5347ee38299511c6e9400db -RECAST_BASENAME=recast-${RECAST_HASH}-${CXX_TAG} - -RECAST_INCLUDE=${PWD}/${RECAST_BASENAME}-install/include -RECAST_LIBPATH=${PWD}/${RECAST_BASENAME}-install/lib - -if [[ -d "${RECAST_BASENAME}-install" && - -f "${RECAST_BASENAME}-install/bin/RecastBuilder" ]] ; then - log "${RECAST_BASENAME} already installed." -else - rm -Rf \ - ${RECAST_BASENAME}-source \ - ${RECAST_BASENAME}-build \ - ${RECAST_BASENAME}-install - - log "Retrieving Recast & Detour" - - git clone https://github.com/carla-simulator/recastnavigation.git ${RECAST_BASENAME}-source - - pushd ${RECAST_BASENAME}-source >/dev/null - - git reset --hard ${RECAST_COMMIT} - - popd >/dev/null - - log "Building Recast & Detour with libc++." - - mkdir -p ${RECAST_BASENAME}-build - - pushd ${RECAST_BASENAME}-build >/dev/null - - cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC" \ - -DCMAKE_INSTALL_PREFIX="../${RECAST_BASENAME}-install" \ - -DRECASTNAVIGATION_DEMO=False \ - -DRECASTNAVIGATION_TEST=False \ - ../${RECAST_BASENAME}-source - - ninja - - ninja install - - popd >/dev/null - - rm -Rf ${RECAST_BASENAME}-source ${RECAST_BASENAME}-build - - # move headers inside 'recast' folder - mkdir -p "${PWD}/${RECAST_BASENAME}-install/include/recast" - mv "${PWD}/${RECAST_BASENAME}-install/include/"*h "${PWD}/${RECAST_BASENAME}-install/include/recast/" - -fi - -# make sure the RecastBuilder is corrctly copied -RECAST_INSTALL_DIR="${CARLA_BUILD_FOLDER}/../Util/DockerUtils/dist" -if [[ ! -f "${RECAST_INSTALL_DIR}/RecastBuilder" ]]; then - cp "${RECAST_BASENAME}-install/bin/RecastBuilder" "${RECAST_INSTALL_DIR}/" -fi - -unset RECAST_BASENAME - -# ============================================================================== -# -- Get and compile libpng 1.6.37 ------------------------------ -# ============================================================================== - -LIBPNG_VERSION=1.6.37 -LIBPNG_REPO=https://sourceforge.net/projects/libpng/files/libpng16/${LIBPNG_VERSION}/libpng-${LIBPNG_VERSION}.tar.xz -LIBPNG_BASENAME=libpng-${LIBPNG_VERSION} -LIBPNG_INSTALL=${LIBPNG_BASENAME}-install - -LIBPNG_INCLUDE=${PWD}/${LIBPNG_BASENAME}-install/include/ -LIBPNG_LIBPATH=${PWD}/${LIBPNG_BASENAME}-install/lib - -if [[ -d ${LIBPNG_INSTALL} ]] ; then - log "Libpng already installed." -else - log "Retrieving libpng." - wget ${LIBPNG_REPO} - - log "Extracting libpng." - tar -xf libpng-${LIBPNG_VERSION}.tar.xz - mv ${LIBPNG_BASENAME} ${LIBPNG_BASENAME}-source - - pushd ${LIBPNG_BASENAME}-source >/dev/null - - ./configure --prefix=${CARLA_BUILD_FOLDER}/${LIBPNG_INSTALL} - make install - - popd >/dev/null - - rm -Rf libpng-${LIBPNG_VERSION}.tar.xz - rm -Rf ${LIBPNG_BASENAME}-source -fi - -# ============================================================================== -# -- Get and compile libxerces 3.2.3 ------------------------------ -# ============================================================================== - -XERCESC_VERSION=3.2.3 -XERCESC_BASENAME=xerces-c-${XERCESC_VERSION} - -XERCESC_TEMP_FOLDER=${XERCESC_BASENAME} -XERCESC_REPO=https://archive.apache.org/dist/xerces/c/3/sources/xerces-c-${XERCESC_VERSION}.tar.gz - -XERCESC_SRC_DIR=${XERCESC_BASENAME}-source -XERCESC_INSTALL_DIR=${XERCESC_BASENAME}-install -XERCESC_LIB=${XERCESC_INSTALL_DIR}/lib/libxerces-c.a - -if [[ -d ${XERCESC_INSTALL_DIR} ]] ; then - log "Xerces-c already installed." -else - log "Retrieving xerces-c." - wget ${XERCESC_REPO} - - log "Extracting xerces-c." - tar -xzf ${XERCESC_BASENAME}.tar.gz - mv ${XERCESC_BASENAME} ${XERCESC_SRC_DIR} - mkdir -p ${XERCESC_INSTALL_DIR} - mkdir -p ${XERCESC_SRC_DIR}/build - - pushd ${XERCESC_SRC_DIR}/build >/dev/null - - cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC -w" \ - -DCMAKE_INSTALL_PREFIX="../../${XERCESC_INSTALL_DIR}" \ - -DCMAKE_BUILD_TYPE=Release \ - -DBUILD_SHARED_LIBS=OFF \ - -Dtranscoder=gnuiconv \ - -Dnetwork=OFF \ - .. - ninja - ninja install - - popd >/dev/null - - rm -Rf ${XERCESC_BASENAME}.tar.gz - rm -Rf ${XERCESC_SRC_DIR} -fi - -mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ -cp ${XERCESC_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ - -if ${USE_CHRONO} ; then - - # ============================================================================== - # -- Get Eigen headers (Chrono dependency) ------------------------------------- - # ============================================================================== - - EIGEN_VERSION=3.3.7 - EIGEN_REPO=https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.tar.gz - EIGEN_BASENAME=eigen-${EIGEN_VERSION} - - EIGEN_SRC_DIR=eigen-${EIGEN_VERSION}-src - EIGEN_INSTALL_DIR=eigen-${EIGEN_VERSION}-install - EIGEN_INCLUDE=${EIGEN_INSTALL_DIR}/include - - - if [[ -d ${EIGEN_INSTALL_DIR} ]] ; then - log "Eigen already installed." - else - log "Retrieving Eigen." - wget ${EIGEN_REPO} - - log "Extracting Eigen." - tar -xzf ${EIGEN_BASENAME}.tar.gz - mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR} - mkdir -p ${EIGEN_INCLUDE}/unsupported - mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE} - mv ${EIGEN_SRC_DIR}/unsupported/Eigen ${EIGEN_INCLUDE}/unsupported/Eigen - - rm -Rf ${EIGEN_BASENAME}.tar.gz - rm -Rf ${EIGEN_SRC_DIR} - fi - - mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ - cp -p -r ${EIGEN_INCLUDE}/* ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ - - # ============================================================================== - # -- Get Chrono and compile it with libc++ ------------------------------------- - # ============================================================================== - - CHRONO_TAG=6.0.0 - # CHRONO_TAG=develop - CHRONO_REPO=https://github.com/projectchrono/chrono.git - - CHRONO_SRC_DIR=chrono-source - CHRONO_INSTALL_DIR=chrono-install - - if [[ -d ${CHRONO_INSTALL_DIR} ]] ; then - log "chrono library already installed." - else - log "Retrieving chrono library." - git clone --depth 1 --branch ${CHRONO_TAG} ${CHRONO_REPO} ${CHRONO_SRC_DIR} - - mkdir -p ${CHRONO_SRC_DIR}/build - - pushd ${CHRONO_SRC_DIR}/build >/dev/null - - cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH} -Wno-unused-command-line-argument" \ - -DEIGEN3_INCLUDE_DIR="../../${EIGEN_INCLUDE}" \ - -DCMAKE_INSTALL_PREFIX="../../${CHRONO_INSTALL_DIR}" \ - -DCMAKE_BUILD_TYPE=Release \ - -DENABLE_MODULE_VEHICLE=ON \ - .. - ninja - ninja install - - popd >/dev/null - - rm -Rf ${CHRONO_SRC_DIR} - fi - - mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ - mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ - cp -p ${CHRONO_INSTALL_DIR}/lib/*.so ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ - cp -p -r ${CHRONO_INSTALL_DIR}/include/* ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ - -fi - -# ============================================================================== -# -- Get and compile Sqlite3 --------------------------------------------------- -# ============================================================================== - -SQLITE_VERSION=sqlite-autoconf-3340100 -SQLITE_REPO=https://www.sqlite.org/2021/${SQLITE_VERSION}.tar.gz - -SQLITE_TAR=${SQLITE_VERSION}.tar.gz -SQLITE_SOURCE_DIR=sqlite-src -SQLITE_INSTALL_DIR=sqlite-install - -SQLITE_INCLUDE_DIR=${PWD}/${SQLITE_INSTALL_DIR}/include -SQLITE_LIB=${PWD}/${SQLITE_INSTALL_DIR}/lib/libsqlite3.a -SQLITE_EXE=${PWD}/${SQLITE_INSTALL_DIR}/bin/sqlite3 - -if [[ -d ${SQLITE_INSTALL_DIR} ]] ; then - log "Sqlite already installed." -else - log "Retrieving Sqlite3" - wget ${SQLITE_REPO} - - log "Extracting Sqlite3" - tar -xzf ${SQLITE_TAR} - mv ${SQLITE_VERSION} ${SQLITE_SOURCE_DIR} - - mkdir ${SQLITE_INSTALL_DIR} - - pushd ${SQLITE_SOURCE_DIR} >/dev/null - - export CFLAGS="-fPIC" - ./configure --prefix=${PWD}/../sqlite-install/ - make - make install - - popd >/dev/null - - rm -Rf ${SQLITE_TAR} - rm -Rf ${SQLITE_SOURCE_DIR} -fi - -mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ -cp ${SQLITE_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ - -# ============================================================================== -# -- Get and compile PROJ ------------------------------------------------------ -# ============================================================================== - -PROJ_VERSION=proj-7.2.1 -PROJ_REPO=https://download.osgeo.org/proj/${PROJ_VERSION}.tar.gz - -PROJ_TAR=${PROJ_VERSION}.tar.gz -PROJ_SRC_DIR=proj-src -PROJ_INSTALL_DIR=proj-install -PROJ_INSTALL_DIR_FULL=${PWD}/${PROJ_INSTALL_DIR} -PROJ_LIB=${PROJ_INSTALL_DIR_FULL}/lib/libproj.a - -if [[ -d ${PROJ_INSTALL_DIR} ]] ; then - log "PROJ already installed." -else - log "Retrieving PROJ" - wget ${PROJ_REPO} - - log "Extracting PROJ" - tar -xzf ${PROJ_TAR} - mv ${PROJ_VERSION} ${PROJ_SRC_DIR} - - mkdir ${PROJ_SRC_DIR}/build - mkdir ${PROJ_INSTALL_DIR} - - pushd ${PROJ_SRC_DIR}/build >/dev/null - - cmake -G "Ninja" .. \ - -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC" \ - -DSQLITE3_INCLUDE_DIR=${SQLITE_INCLUDE_DIR} -DSQLITE3_LIBRARY=${SQLITE_LIB} \ - -DEXE_SQLITE3=${SQLITE_EXE} \ - -DENABLE_TIFF=OFF -DENABLE_CURL=OFF -DBUILD_SHARED_LIBS=OFF -DBUILD_PROJSYNC=OFF \ - -DCMAKE_BUILD_TYPE=Release -DBUILD_PROJINFO=OFF \ - -DBUILD_CCT=OFF -DBUILD_CS2CS=OFF -DBUILD_GEOD=OFF -DBUILD_GIE=OFF \ - -DBUILD_PROJ=OFF -DBUILD_TESTING=OFF \ - -DCMAKE_INSTALL_PREFIX=${PROJ_INSTALL_DIR_FULL} - ninja - ninja install - - popd >/dev/null - - rm -Rf ${PROJ_TAR} - rm -Rf ${PROJ_SRC_DIR} - -fi - -cp ${PROJ_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ - -# ============================================================================== -# -- Get and compile patchelf -------------------------------------------------- -# ============================================================================== - -PATCHELF_VERSION=0.12 -PATCHELF_REPO=https://github.com/NixOS/patchelf/archive/${PATCHELF_VERSION}.tar.gz - -PATCHELF_TAR=${PATCHELF_VERSION}.tar.gz -PATCHELF_SOURCE_DIR=patchelf-src -PATCHELF_INSTALL_DIR=patchelf-install - -PATCHELF_INCLUDE_DIR=${PWD}/${PATCHELF_INSTALL_DIR}/include -PATCHELF_EXE=${PWD}/${PATCHELF_INSTALL_DIR}/bin/patchelf - -if [[ -d ${PATCHELF_INSTALL_DIR} ]] ; then - log "Patchelf already installed." -else - log "Retrieving patchelf" - wget ${PATCHELF_REPO} - - log "Extracting patchelf" - tar -xzf ${PATCHELF_TAR} - mv patchelf-${PATCHELF_VERSION} ${PATCHELF_SOURCE_DIR} - - mkdir ${PATCHELF_INSTALL_DIR} - - pushd ${PATCHELF_SOURCE_DIR} >/dev/null - - ./bootstrap.sh - ./configure --prefix=${PWD}/../${PATCHELF_INSTALL_DIR} - make - make install - - popd >/dev/null - - rm -Rf ${PATCHELF_TAR} - rm -Rf ${PATCHELF_SOURCE_DIR} -fi - -mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/bin/ -cp ${PATCHELF_EXE} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/bin/ - -# ============================================================================== -# -- Generate Version.h -------------------------------------------------------- -# ============================================================================== - -CARLA_VERSION=$(get_git_repository_version) - -log "CARLA version ${CARLA_VERSION}." - -VERSION_H_FILE=${LIBCARLA_ROOT_FOLDER}/source/carla/Version.h -VERSION_H_FILE_GEN=${CARLA_BUILD_FOLDER}/Version.h - -sed -e "s|\${CARLA_VERSION}|${CARLA_VERSION}|g" ${VERSION_H_FILE}.in > ${VERSION_H_FILE_GEN} - -move_if_changed "${VERSION_H_FILE_GEN}" "${VERSION_H_FILE}" - -# ============================================================================== -# -- Generate CMake toolchains and config -------------------------------------- -# ============================================================================== - -log "Generating CMake configuration files." - -# -- LIBSTDCPP_TOOLCHAIN_FILE -------------------------------------------------- - -cat >${LIBSTDCPP_TOOLCHAIN_FILE}.gen <>${LIBCPP_TOOLCHAIN_FILE}.gen <${CMAKE_CONFIG_FILE}.gen <> ${CMAKE_CONFIG_FILE}.gen -else - echo "add_definitions(-DLIBCARLA_IMAGE_WITH_PNG_SUPPORT=true)" >> ${CMAKE_CONFIG_FILE}.gen -fi - -# -- Move files ---------------------------------------------------------------- - -move_if_changed "${LIBSTDCPP_TOOLCHAIN_FILE}.gen" "${LIBSTDCPP_TOOLCHAIN_FILE}" -move_if_changed "${LIBCPP_TOOLCHAIN_FILE}.gen" "${LIBCPP_TOOLCHAIN_FILE}" -move_if_changed "${CMAKE_CONFIG_FILE}.gen" "${CMAKE_CONFIG_FILE}" - -# ============================================================================== -# -- ...and we are done -------------------------------------------------------- -# ============================================================================== - -popd >/dev/null - -log "Success!" +#! /bin/bash + +# ============================================================================== +# -- Parse arguments ----------------------------------------------------------- +# ============================================================================== + +DOC_STRING="Download and install the required libraries for carla." + +USAGE_STRING="Usage: $0 [--python-version=VERSION]" + +OPTS=`getopt -o h --long help,chrono,python-version: -n 'parse-options' -- "$@"` + +eval set -- "$OPTS" + +PY_VERSION_LIST=3 +USE_CHRONO=false + +while [[ $# -gt 0 ]]; do + case "$1" in + --python-version ) + PY_VERSION_LIST="$2"; + shift 2 ;; + --chrono ) + USE_CHRONO=true; + shift ;; + -h | --help ) + echo "$DOC_STRING" + echo "$USAGE_STRING" + exit 1 + ;; + * ) + shift ;; + esac +done + +# ============================================================================== +# -- Set up environment -------------------------------------------------------- +# ============================================================================== + +command -v /usr/bin/clang++ >/dev/null 2>&1 || { + echo >&2 "clang is required, but it's not installed."; + exit 1; +} + +CXX_TAG=c8 +export CC=/usr/bin/clang +export CXX=/usr/bin/clang++ + +source $(dirname "$0")/Environment.sh + +# Convert comma-separated string to array of unique elements. +IFS="," read -r -a PY_VERSION_LIST <<< "${PY_VERSION_LIST}" + +mkdir -p ${CARLA_BUILD_FOLDER} +pushd ${CARLA_BUILD_FOLDER} >/dev/null + +# ============================================================================== +# -- Get and compile libc++ ---------------------------------------------------- +# ============================================================================== + +LLVM_BASENAME=llvm-8.0 + +LLVM_INCLUDE=${PWD}/${LLVM_BASENAME}-install/include/c++/v1 +LLVM_LIBPATH=${PWD}/${LLVM_BASENAME}-install/lib + +if [[ -d "${LLVM_BASENAME}-install" ]] ; then + log "${LLVM_BASENAME} already installed." +else + rm -Rf ${LLVM_BASENAME}-source ${LLVM_BASENAME}-build + + log "Retrieving libc++." + + git clone --depth=1 -b release_80 https://github.com/llvm-mirror/llvm.git ${LLVM_BASENAME}-source + git clone --depth=1 -b release_80 https://github.com/llvm-mirror/libcxx.git ${LLVM_BASENAME}-source/projects/libcxx + git clone --depth=1 -b release_80 https://github.com/llvm-mirror/libcxxabi.git ${LLVM_BASENAME}-source/projects/libcxxabi + + log "Compiling libc++." + + mkdir -p ${LLVM_BASENAME}-build + + pushd ${LLVM_BASENAME}-build >/dev/null + + cmake -G "Ninja" \ + -DLIBCXX_ENABLE_EXPERIMENTAL_LIBRARY=OFF \ + -DLIBCXX_INSTALL_EXPERIMENTAL_LIBRARY=OFF \ + -DLLVM_ENABLE_EH=OFF \ + -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX="../${LLVM_BASENAME}-install" \ + ../${LLVM_BASENAME}-source + + ninja cxx + + ninja install-libcxx + + ninja install-libcxxabi + + popd >/dev/null + + rm -Rf ${LLVM_BASENAME}-source ${LLVM_BASENAME}-build + +fi + +unset LLVM_BASENAME + +# ============================================================================== +# -- Get boost includes -------------------------------------------------------- +# ============================================================================== + +BOOST_VERSION=1.72.0 +BOOST_BASENAME="boost-${BOOST_VERSION}-${CXX_TAG}" + +BOOST_INCLUDE=${PWD}/${BOOST_BASENAME}-install/include +BOOST_LIBPATH=${PWD}/${BOOST_BASENAME}-install/lib + +for PY_VERSION in ${PY_VERSION_LIST[@]} ; do + + SHOULD_BUILD_BOOST=true + PYTHON_VERSION=$(/usr/bin/env python${PY_VERSION} -V 2>&1) + LIB_NAME=${PYTHON_VERSION:7:3} + LIB_NAME=${LIB_NAME//.} + if [[ -d "${BOOST_BASENAME}-install" ]] ; then + if [ -f "${BOOST_BASENAME}-install/lib/libboost_python${LIB_NAME}.a" ] ; then + SHOULD_BUILD_BOOST=false + log "${BOOST_BASENAME} already installed." + fi + fi + + if { ${SHOULD_BUILD_BOOST} ; } ; then + rm -Rf ${BOOST_BASENAME}-source + + BOOST_PACKAGE_BASENAME=boost_${BOOST_VERSION//./_} + + log "Retrieving boost." + wget "https://boostorg.jfrog.io/artifactory/main/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" || true + # try to use the backup boost we have in Jenkins + if [[ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ]] ; then + log "Using boost backup" + wget "https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" || true + fi + + log "Extracting boost for Python ${PY_VERSION}." + tar -xzf ${BOOST_PACKAGE_BASENAME}.tar.gz + mkdir -p ${BOOST_BASENAME}-install/include + mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-source + # Boost patch for exception handling + cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/rational.hpp" "${BOOST_BASENAME}-source/boost/rational.hpp" + cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/read.hpp" "${BOOST_BASENAME}-source/boost/geometry/io/wkt/read.hpp" + # --- + + pushd ${BOOST_BASENAME}-source >/dev/null + + BOOST_TOOLSET="clang" + BOOST_CFLAGS="-fPIC -std=c++14 -DBOOST_ERROR_CODE_HEADER_ONLY" + + py3="/usr/bin/env python${PY_VERSION}" + py3_root=`${py3} -c "import sys; print(sys.prefix)"` + pyv=`$py3 -c "import sys;x='{v[0]}.{v[1]}'.format(v=list(sys.version_info[:2]));sys.stdout.write(x)";` + ./bootstrap.sh \ + --with-toolset=clang \ + --prefix=../boost-install \ + --with-libraries=python,filesystem,system,program_options \ + --with-python=${py3} --with-python-root=${py3_root} + + if ${TRAVIS} ; then + echo "using python : ${pyv} : ${py3_root}/bin/python${PY_VERSION} ;" > ${HOME}/user-config.jam + else + echo "using python : ${pyv} : ${py3_root}/bin/python${PY_VERSION} ;" > project-config.jam + fi + + ./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j ${CARLA_BUILD_CONCURRENCY} stage release + ./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j ${CARLA_BUILD_CONCURRENCY} install + + popd >/dev/null + + rm -Rf ${BOOST_BASENAME}-source + rm ${BOOST_PACKAGE_BASENAME}.tar.gz + + # Boost patch for exception handling + cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/rational.hpp" "${BOOST_BASENAME}-install/include/boost/rational.hpp" + cp "${CARLA_BUILD_FOLDER}/../Util/BoostFiles/read.hpp" "${BOOST_BASENAME}-install/include/boost/geometry/io/wkt/read.hpp" + # --- + + # Install boost dependencies + mkdir -p "${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/system" + mkdir -p "${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib" + cp -rf ${BOOST_BASENAME}-install/include/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/system + cp -rf ${BOOST_BASENAME}-install/lib/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib + + fi + +done + +unset BOOST_BASENAME + +# ============================================================================== +# -- Get rpclib and compile it with libc++ and libstdc++ ----------------------- +# ============================================================================== + +RPCLIB_PATCH=v2.2.1_c5 +RPCLIB_BASENAME=rpclib-${RPCLIB_PATCH}-${CXX_TAG} + +RPCLIB_LIBCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libcxx-install/include +RPCLIB_LIBCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libcxx-install/lib +RPCLIB_LIBSTDCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/include +RPCLIB_LIBSTDCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/lib + +if [[ -d "${RPCLIB_BASENAME}-libcxx-install" && -d "${RPCLIB_BASENAME}-libstdcxx-install" ]] ; then + log "${RPCLIB_BASENAME} already installed." +else + rm -Rf \ + ${RPCLIB_BASENAME}-source \ + ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build \ + ${RPCLIB_BASENAME}-libcxx-install ${RPCLIB_BASENAME}-libstdcxx-install + + log "Retrieving rpclib." + + git clone -b ${RPCLIB_PATCH} https://github.com/carla-simulator/rpclib.git ${RPCLIB_BASENAME}-source + + log "Building rpclib with libc++." + + # rpclib does not use any cmake 3.9 feature. + # As cmake 3.9 is not standard in Ubuntu 16.04, change cmake version to 3.5 + sed -i s/"3.9.0"/"3.5.0"/g ${RPCLIB_BASENAME}-source/CMakeLists.txt + + mkdir -p ${RPCLIB_BASENAME}-libcxx-build + + pushd ${RPCLIB_BASENAME}-libcxx-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} -DBOOST_NO_EXCEPTIONS -DASIO_NO_EXCEPTIONS" \ + -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libcxx-install" \ + ../${RPCLIB_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + log "Building rpclib with libstdc++." + + mkdir -p ${RPCLIB_BASENAME}-libstdcxx-build + + pushd ${RPCLIB_BASENAME}-libstdcxx-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++14" \ + -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libstdcxx-install" \ + ../${RPCLIB_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + rm -Rf ${RPCLIB_BASENAME}-source ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build + +fi + +unset RPCLIB_BASENAME + +# ============================================================================== +# -- Get GTest and compile it with libc++ -------------------------------------- +# ============================================================================== + +GTEST_VERSION=1.8.1 +GTEST_BASENAME=gtest-${GTEST_VERSION}-${CXX_TAG} + +GTEST_LIBCXX_INCLUDE=${PWD}/${GTEST_BASENAME}-libcxx-install/include +GTEST_LIBCXX_LIBPATH=${PWD}/${GTEST_BASENAME}-libcxx-install/lib +GTEST_LIBSTDCXX_INCLUDE=${PWD}/${GTEST_BASENAME}-libstdcxx-install/include +GTEST_LIBSTDCXX_LIBPATH=${PWD}/${GTEST_BASENAME}-libstdcxx-install/lib + +if [[ -d "${GTEST_BASENAME}-libcxx-install" && -d "${GTEST_BASENAME}-libstdcxx-install" ]] ; then + log "${GTEST_BASENAME} already installed." +else + rm -Rf \ + ${GTEST_BASENAME}-source \ + ${GTEST_BASENAME}-libcxx-build ${GTEST_BASENAME}-libstdcxx-build \ + ${GTEST_BASENAME}-libcxx-install ${GTEST_BASENAME}-libstdcxx-install + + log "Retrieving Google Test." + + git clone --depth=1 -b release-${GTEST_VERSION} https://github.com/google/googletest.git ${GTEST_BASENAME}-source + + log "Building Google Test with libc++." + + mkdir -p ${GTEST_BASENAME}-libcxx-build + + pushd ${GTEST_BASENAME}-libcxx-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} -DBOOST_NO_EXCEPTIONS -fno-exceptions" \ + -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-libcxx-install" \ + ../${GTEST_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + log "Building Google Test with libstdc++." + + mkdir -p ${GTEST_BASENAME}-libstdcxx-build + + pushd ${GTEST_BASENAME}-libstdcxx-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-std=c++14" \ + -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-libstdcxx-install" \ + ../${GTEST_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + rm -Rf ${GTEST_BASENAME}-source ${GTEST_BASENAME}-libcxx-build ${GTEST_BASENAME}-libstdcxx-build + +fi + +unset GTEST_BASENAME + +# ============================================================================== +# -- Get Recast&Detour and compile it with libc++ ------------------------------ +# ============================================================================== + +RECAST_HASH=0b13b0 +RECAST_COMMIT=0b13b0d288ac96fdc5347ee38299511c6e9400db +RECAST_BASENAME=recast-${RECAST_HASH}-${CXX_TAG} + +RECAST_INCLUDE=${PWD}/${RECAST_BASENAME}-install/include +RECAST_LIBPATH=${PWD}/${RECAST_BASENAME}-install/lib + +if [[ -d "${RECAST_BASENAME}-install" && + -f "${RECAST_BASENAME}-install/bin/RecastBuilder" ]] ; then + log "${RECAST_BASENAME} already installed." +else + rm -Rf \ + ${RECAST_BASENAME}-source \ + ${RECAST_BASENAME}-build \ + ${RECAST_BASENAME}-install + + log "Retrieving Recast & Detour" + + git clone https://github.com/carla-simulator/recastnavigation.git ${RECAST_BASENAME}-source + + pushd ${RECAST_BASENAME}-source >/dev/null + + git reset --hard ${RECAST_COMMIT} + + popd >/dev/null + + log "Building Recast & Detour with libc++." + + mkdir -p ${RECAST_BASENAME}-build + + pushd ${RECAST_BASENAME}-build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC" \ + -DCMAKE_INSTALL_PREFIX="../${RECAST_BASENAME}-install" \ + -DRECASTNAVIGATION_DEMO=False \ + -DRECASTNAVIGATION_TEST=False \ + ../${RECAST_BASENAME}-source + + ninja + + ninja install + + popd >/dev/null + + rm -Rf ${RECAST_BASENAME}-source ${RECAST_BASENAME}-build + + # move headers inside 'recast' folder + mkdir -p "${PWD}/${RECAST_BASENAME}-install/include/recast" + mv "${PWD}/${RECAST_BASENAME}-install/include/"*h "${PWD}/${RECAST_BASENAME}-install/include/recast/" + +fi + +# make sure the RecastBuilder is corrctly copied +RECAST_INSTALL_DIR="${CARLA_BUILD_FOLDER}/../Util/DockerUtils/dist" +if [[ ! -f "${RECAST_INSTALL_DIR}/RecastBuilder" ]]; then + cp "${RECAST_BASENAME}-install/bin/RecastBuilder" "${RECAST_INSTALL_DIR}/" +fi + +unset RECAST_BASENAME + +# ============================================================================== +# -- Get and compile libpng 1.6.37 ------------------------------ +# ============================================================================== + +LIBPNG_VERSION=1.6.37 +LIBPNG_REPO=https://sourceforge.net/projects/libpng/files/libpng16/${LIBPNG_VERSION}/libpng-${LIBPNG_VERSION}.tar.xz +LIBPNG_BASENAME=libpng-${LIBPNG_VERSION} +LIBPNG_INSTALL=${LIBPNG_BASENAME}-install + +LIBPNG_INCLUDE=${PWD}/${LIBPNG_BASENAME}-install/include/ +LIBPNG_LIBPATH=${PWD}/${LIBPNG_BASENAME}-install/lib + +if [[ -d ${LIBPNG_INSTALL} ]] ; then + log "Libpng already installed." +else + log "Retrieving libpng." + wget ${LIBPNG_REPO} + + log "Extracting libpng." + tar -xf libpng-${LIBPNG_VERSION}.tar.xz + mv ${LIBPNG_BASENAME} ${LIBPNG_BASENAME}-source + + pushd ${LIBPNG_BASENAME}-source >/dev/null + + ./configure --prefix=${CARLA_BUILD_FOLDER}/${LIBPNG_INSTALL} + make install + + popd >/dev/null + + rm -Rf libpng-${LIBPNG_VERSION}.tar.xz + rm -Rf ${LIBPNG_BASENAME}-source +fi + +# ============================================================================== +# -- Get and compile libxerces 3.2.3 ------------------------------ +# ============================================================================== + +XERCESC_VERSION=3.2.3 +XERCESC_BASENAME=xerces-c-${XERCESC_VERSION} + +XERCESC_TEMP_FOLDER=${XERCESC_BASENAME} +XERCESC_REPO=https://archive.apache.org/dist/xerces/c/3/sources/xerces-c-${XERCESC_VERSION}.tar.gz + +XERCESC_SRC_DIR=${XERCESC_BASENAME}-source +XERCESC_INSTALL_DIR=${XERCESC_BASENAME}-install +XERCESC_LIB=${XERCESC_INSTALL_DIR}/lib/libxerces-c.a + +if [[ -d ${XERCESC_INSTALL_DIR} ]] ; then + log "Xerces-c already installed." +else + log "Retrieving xerces-c." + wget ${XERCESC_REPO} + + log "Extracting xerces-c." + tar -xzf ${XERCESC_BASENAME}.tar.gz + mv ${XERCESC_BASENAME} ${XERCESC_SRC_DIR} + mkdir -p ${XERCESC_INSTALL_DIR} + mkdir -p ${XERCESC_SRC_DIR}/build + + pushd ${XERCESC_SRC_DIR}/build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC -w" \ + -DCMAKE_INSTALL_PREFIX="../../${XERCESC_INSTALL_DIR}" \ + -DCMAKE_BUILD_TYPE=Release \ + -DBUILD_SHARED_LIBS=OFF \ + -Dtranscoder=gnuiconv \ + -Dnetwork=OFF \ + .. + ninja + ninja install + + popd >/dev/null + + rm -Rf ${XERCESC_BASENAME}.tar.gz + rm -Rf ${XERCESC_SRC_DIR} +fi + +mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ +cp ${XERCESC_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ + +if ${USE_CHRONO} ; then + + # ============================================================================== + # -- Get Eigen headers (Chrono dependency) ------------------------------------- + # ============================================================================== + + EIGEN_VERSION=3.3.7 + EIGEN_REPO=https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.tar.gz + EIGEN_BASENAME=eigen-${EIGEN_VERSION} + + EIGEN_SRC_DIR=eigen-${EIGEN_VERSION}-src + EIGEN_INSTALL_DIR=eigen-${EIGEN_VERSION}-install + EIGEN_INCLUDE=${EIGEN_INSTALL_DIR}/include + + + if [[ -d ${EIGEN_INSTALL_DIR} ]] ; then + log "Eigen already installed." + else + log "Retrieving Eigen." + wget ${EIGEN_REPO} + + log "Extracting Eigen." + tar -xzf ${EIGEN_BASENAME}.tar.gz + mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR} + mkdir -p ${EIGEN_INCLUDE}/unsupported + mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE} + mv ${EIGEN_SRC_DIR}/unsupported/Eigen ${EIGEN_INCLUDE}/unsupported/Eigen + + rm -Rf ${EIGEN_BASENAME}.tar.gz + rm -Rf ${EIGEN_SRC_DIR} + fi + + mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ + cp -p -r ${EIGEN_INCLUDE}/* ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ + + # ============================================================================== + # -- Get Chrono and compile it with libc++ ------------------------------------- + # ============================================================================== + + CHRONO_TAG=6.0.0 + # CHRONO_TAG=develop + CHRONO_REPO=https://github.com/projectchrono/chrono.git + + CHRONO_SRC_DIR=chrono-source + CHRONO_INSTALL_DIR=chrono-install + + if [[ -d ${CHRONO_INSTALL_DIR} ]] ; then + log "chrono library already installed." + else + log "Retrieving chrono library." + git clone --depth 1 --branch ${CHRONO_TAG} ${CHRONO_REPO} ${CHRONO_SRC_DIR} + + mkdir -p ${CHRONO_SRC_DIR}/build + + pushd ${CHRONO_SRC_DIR}/build >/dev/null + + cmake -G "Ninja" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH} -Wno-unused-command-line-argument" \ + -DEIGEN3_INCLUDE_DIR="../../${EIGEN_INCLUDE}" \ + -DCMAKE_INSTALL_PREFIX="../../${CHRONO_INSTALL_DIR}" \ + -DCMAKE_BUILD_TYPE=Release \ + -DENABLE_MODULE_VEHICLE=ON \ + .. + ninja + ninja install + + popd >/dev/null + + rm -Rf ${CHRONO_SRC_DIR} + fi + + mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ + mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ + cp -p ${CHRONO_INSTALL_DIR}/lib/*.so ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ + cp -p -r ${CHRONO_INSTALL_DIR}/include/* ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ + +fi + +# ============================================================================== +# -- Get and compile Sqlite3 --------------------------------------------------- +# ============================================================================== + +SQLITE_VERSION=sqlite-autoconf-3340100 +SQLITE_REPO=https://www.sqlite.org/2021/${SQLITE_VERSION}.tar.gz + +SQLITE_TAR=${SQLITE_VERSION}.tar.gz +SQLITE_SOURCE_DIR=sqlite-src +SQLITE_INSTALL_DIR=sqlite-install + +SQLITE_INCLUDE_DIR=${PWD}/${SQLITE_INSTALL_DIR}/include +SQLITE_LIB=${PWD}/${SQLITE_INSTALL_DIR}/lib/libsqlite3.a +SQLITE_EXE=${PWD}/${SQLITE_INSTALL_DIR}/bin/sqlite3 + +if [[ -d ${SQLITE_INSTALL_DIR} ]] ; then + log "Sqlite already installed." +else + log "Retrieving Sqlite3" + wget ${SQLITE_REPO} + + log "Extracting Sqlite3" + tar -xzf ${SQLITE_TAR} + mv ${SQLITE_VERSION} ${SQLITE_SOURCE_DIR} + + mkdir ${SQLITE_INSTALL_DIR} + + pushd ${SQLITE_SOURCE_DIR} >/dev/null + + export CFLAGS="-fPIC" + ./configure --prefix=${PWD}/../sqlite-install/ + make + make install + + popd >/dev/null + + rm -Rf ${SQLITE_TAR} + rm -Rf ${SQLITE_SOURCE_DIR} +fi + +mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ +cp ${SQLITE_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ + +# ============================================================================== +# -- Get and compile PROJ ------------------------------------------------------ +# ============================================================================== + +PROJ_VERSION=proj-7.2.1 +PROJ_REPO=https://download.osgeo.org/proj/${PROJ_VERSION}.tar.gz + +PROJ_TAR=${PROJ_VERSION}.tar.gz +PROJ_SRC_DIR=proj-src +PROJ_INSTALL_DIR=proj-install +PROJ_INSTALL_DIR_FULL=${PWD}/${PROJ_INSTALL_DIR} +PROJ_LIB=${PROJ_INSTALL_DIR_FULL}/lib/libproj.a + +if [[ -d ${PROJ_INSTALL_DIR} ]] ; then + log "PROJ already installed." +else + log "Retrieving PROJ" + wget ${PROJ_REPO} + + log "Extracting PROJ" + tar -xzf ${PROJ_TAR} + mv ${PROJ_VERSION} ${PROJ_SRC_DIR} + + mkdir ${PROJ_SRC_DIR}/build + mkdir ${PROJ_INSTALL_DIR} + + pushd ${PROJ_SRC_DIR}/build >/dev/null + + cmake -G "Ninja" .. \ + -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC" \ + -DSQLITE3_INCLUDE_DIR=${SQLITE_INCLUDE_DIR} -DSQLITE3_LIBRARY=${SQLITE_LIB} \ + -DEXE_SQLITE3=${SQLITE_EXE} \ + -DENABLE_TIFF=OFF -DENABLE_CURL=OFF -DBUILD_SHARED_LIBS=OFF -DBUILD_PROJSYNC=OFF \ + -DCMAKE_BUILD_TYPE=Release -DBUILD_PROJINFO=OFF \ + -DBUILD_CCT=OFF -DBUILD_CS2CS=OFF -DBUILD_GEOD=OFF -DBUILD_GIE=OFF \ + -DBUILD_PROJ=OFF -DBUILD_TESTING=OFF \ + -DCMAKE_INSTALL_PREFIX=${PROJ_INSTALL_DIR_FULL} + ninja + ninja install + + popd >/dev/null + + rm -Rf ${PROJ_TAR} + rm -Rf ${PROJ_SRC_DIR} + +fi + +cp ${PROJ_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ + +# ============================================================================== +# -- Get and compile patchelf -------------------------------------------------- +# ============================================================================== + +PATCHELF_VERSION=0.12 +PATCHELF_REPO=https://github.com/NixOS/patchelf/archive/${PATCHELF_VERSION}.tar.gz + +PATCHELF_TAR=${PATCHELF_VERSION}.tar.gz +PATCHELF_SOURCE_DIR=patchelf-src +PATCHELF_INSTALL_DIR=patchelf-install + +PATCHELF_INCLUDE_DIR=${PWD}/${PATCHELF_INSTALL_DIR}/include +PATCHELF_EXE=${PWD}/${PATCHELF_INSTALL_DIR}/bin/patchelf + +if [[ -d ${PATCHELF_INSTALL_DIR} ]] ; then + log "Patchelf already installed." +else + log "Retrieving patchelf" + wget ${PATCHELF_REPO} + + log "Extracting patchelf" + tar -xzf ${PATCHELF_TAR} + mv patchelf-${PATCHELF_VERSION} ${PATCHELF_SOURCE_DIR} + + mkdir ${PATCHELF_INSTALL_DIR} + + pushd ${PATCHELF_SOURCE_DIR} >/dev/null + + ./bootstrap.sh + ./configure --prefix=${PWD}/../${PATCHELF_INSTALL_DIR} + make + make install + + popd >/dev/null + + rm -Rf ${PATCHELF_TAR} + rm -Rf ${PATCHELF_SOURCE_DIR} +fi + +mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/bin/ +cp ${PATCHELF_EXE} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/bin/ + +# ============================================================================== +# -- Generate Version.h -------------------------------------------------------- +# ============================================================================== + +CARLA_VERSION=$(get_git_repository_version) + +log "CARLA version ${CARLA_VERSION}." + +VERSION_H_FILE=${LIBCARLA_ROOT_FOLDER}/source/carla/Version.h +VERSION_H_FILE_GEN=${CARLA_BUILD_FOLDER}/Version.h + +sed -e "s|\${CARLA_VERSION}|${CARLA_VERSION}|g" ${VERSION_H_FILE}.in > ${VERSION_H_FILE_GEN} + +move_if_changed "${VERSION_H_FILE_GEN}" "${VERSION_H_FILE}" + +# ============================================================================== +# -- Generate CMake toolchains and config -------------------------------------- +# ============================================================================== + +log "Generating CMake configuration files." + +# -- LIBSTDCPP_TOOLCHAIN_FILE -------------------------------------------------- + +cat >${LIBSTDCPP_TOOLCHAIN_FILE}.gen <>${LIBCPP_TOOLCHAIN_FILE}.gen <${CMAKE_CONFIG_FILE}.gen <> ${CMAKE_CONFIG_FILE}.gen +else + echo "add_definitions(-DLIBCARLA_IMAGE_WITH_PNG_SUPPORT=true)" >> ${CMAKE_CONFIG_FILE}.gen +fi + +# -- Move files ---------------------------------------------------------------- + +move_if_changed "${LIBSTDCPP_TOOLCHAIN_FILE}.gen" "${LIBSTDCPP_TOOLCHAIN_FILE}" +move_if_changed "${LIBCPP_TOOLCHAIN_FILE}.gen" "${LIBCPP_TOOLCHAIN_FILE}" +move_if_changed "${CMAKE_CONFIG_FILE}.gen" "${CMAKE_CONFIG_FILE}" + +# ============================================================================== +# -- ...and we are done -------------------------------------------------------- +# ============================================================================== + +popd >/dev/null + +log "Success!" diff --git a/Util/InstallersWin/install_xercesc.bat b/Util/InstallersWin/install_xercesc.bat index fb5cd51..115356b 100644 --- a/Util/InstallersWin/install_xercesc.bat +++ b/Util/InstallersWin/install_xercesc.bat @@ -1,196 +1,196 @@ -REM @echo off -setlocal - -rem BAT script that downloads and installs a ready to use -rem x64 xerces-c build for CARLA (carla.org). -rem Run it through a cmd with the x64 Visual C++ Toolset enabled. - -set LOCAL_PATH=%~dp0 -set FILE_N= -[%~n0]: - -rem Print batch params (debug purpose) -echo %FILE_N% [Batch params]: %* - -rem ============================================================================ -rem -- Parse arguments --------------------------------------------------------- -rem ============================================================================ - -:arg-parse -if not "%1"=="" ( - if "%1"=="--build-dir" ( - set BUILD_DIR=%~dpn2 - shift - ) - if "%1"=="-h" ( - goto help - ) - if "%1"=="--help" ( - goto help - ) - shift - goto :arg-parse -) - -rem If not set set the build dir to the current dir -if "%BUILD_DIR%" == "" set BUILD_DIR=%~dp0 -if not "%BUILD_DIR:~-1%"=="\" set BUILD_DIR=%BUILD_DIR%\ - -rem ============================================================================ -rem -- Local Variables --------------------------------------------------------- -rem ============================================================================ - -set XERCESC_BASENAME=xerces-c -set XERCESC_VERSION=3.2.3 - -rem xerces-c-x.x.x -set XERCESC_TEMP_FOLDER=%XERCESC_BASENAME%-%XERCESC_VERSION% -rem ../xerces-c-x.x.x -set XERCESC_TEMP_FOLDER_DIR=%BUILD_DIR%%XERCESC_TEMP_FOLDER% -rem xerces-c-x.x.x-src.zip -set XERCESC_TEMP_FILE=%XERCESC_TEMP_FOLDER%-src.zip -rem ../xerces-c-x.x.x-src.zip -set XERCESC_TEMP_FILE_DIR=%BUILD_DIR%%XERCESC_TEMP_FILE% - -set XERCESC_REPO=https://archive.apache.org/dist/xerces/c/3/sources/xerces-c-%XERCESC_VERSION%.zip - -rem ../xerces-c-x.x.x-source/ -set XERCESC_SRC_DIR=%BUILD_DIR%%XERCESC_BASENAME%-%XERCESC_VERSION%-source\ -rem ../xerces-c-x.x.x-install/ -set XERCESC_INSTALL_DIR=%BUILD_DIR%%XERCESC_BASENAME%-%XERCESC_VERSION%-install\ - -rem ============================================================================ -rem -- Get xerces -------------------------------------------------------------- -rem ============================================================================ - -if exist "%XERCESC_INSTALL_DIR%" ( - goto already_build -) - -if not exist "%XERCESC_SRC_DIR%" ( - if not exist "%XERCESC_TEMP_FILE_DIR%" ( - echo %FILE_N% Retrieving %XERCESC_BASENAME%. - powershell -Command "(New-Object System.Net.WebClient).DownloadFile('%XERCESC_REPO%', '%XERCESC_TEMP_FILE_DIR%')" - ) - if not exist "%XERCESC_TEMP_FILE_DIR%" ( - echo %FILE_N% Using %XERCESC_BASENAME% from backup. - goto error_download - powershell -Command "(New-Object System.Net.WebClient).DownloadFile('https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/xerces-c-%XERCESC_VERSION%-src.zip', '%XERCESC_TEMP_FILE_DIR%')" - ) - if %errorlevel% neq 0 goto error_download - rem Extract the downloaded library - echo %FILE_N% Extracting xerces from "%XERCESC_TEMP_FILE%". - powershell -Command "Expand-Archive '%XERCESC_TEMP_FILE_DIR%' -DestinationPath '%BUILD_DIR%'" - if %errorlevel% neq 0 goto error_extracting - - rem Remove unnecessary files and folders - echo %FILE_N% Removing "%XERCESC_TEMP_FILE%" - del "%XERCESC_TEMP_FILE_DIR%" - echo %FILE_N% Removing dir "%BUILD_DIR%manifest" - rmdir /s/q "%BUILD_DIR%manifest" - - echo %FILE_N% Renaming dir %XERCESC_TEMP_FOLDER_DIR% to %XERCESC_BASENAME%-%XERCESC_VERSION%-source - rename "%XERCESC_TEMP_FOLDER_DIR%" "%XERCESC_BASENAME%-%XERCESC_VERSION%-source" -) else ( - echo %FILE_N% Not downloading xerces because already exists the folder "%XERCESC_SRC_DIR%". -) - -rem ============================================================================ -rem -- Compile xerces ---------------------------------------------------------- -rem ============================================================================ - -if not exist "%XERCESC_SRC_DIR%build" ( - echo %FILE_N% Creating "%XERCESC_SRC_DIR%build" - mkdir "%XERCESC_SRC_DIR%build" -) - -cd "%XERCESC_SRC_DIR%build" - -if not exist "%XERCESC_INSTALL_DIR%lib" ( - echo %FILE_N% Creating "%XERCESC_INSTALL_DIR%lib" - mkdir "%XERCESC_INSTALL_DIR%lib" -) - -if not exist "%XERCESC_INSTALL_DIR%include" ( - echo %FILE_N% Creating "%XERCESC_INSTALL_DIR%include" - mkdir "%XERCESC_INSTALL_DIR%include" -) - -cmake .. -G "Visual Studio 16 2019" -A x64^ - -DCMAKE_INSTALL_PREFIX="%XERCESC_INSTALL_DIR:\=/%"^ - -DBUILD_SHARED_LIBS=OFF^ - -Dtranscoder=windows^ - "%BUILD_DIR%%XERCESC_BASENAME%-%XERCESC_VERSION%-source" -if %errorlevel% neq 0 goto error_cmake - -cmake --build . --config Release --target install - -goto success - -rem ============================================================================ -rem -- Messages and Errors ----------------------------------------------------- -rem ============================================================================ - -:help - echo %FILE_N% Download and install a xerces. - echo "Usage: %FILE_N% [-h^|--help] [--build-dir] [--zlib-install-dir]" - goto eof - -:success - echo. - echo %FILE_N% xerces has been successfully installed in "%XERCESC_INSTALL_DIR%"! - goto good_exit - -:already_build - echo %FILE_N% A xerces installation already exists. - echo %FILE_N% Delete "%XERCESC_INSTALL_DIR%" if you want to force a rebuild. - goto good_exit - -:error_download - echo. - echo %FILE_N% [DOWNLOAD ERROR] An error ocurred while downloading xerces. - echo %FILE_N% [DOWNLOAD ERROR] Possible causes: - echo %FILE_N% - Make sure that the following url is valid: - echo %FILE_N% "%XERCESC_REPO%" - echo %FILE_N% [DOWNLOAD ERROR] Workaround: - echo %FILE_N% - Download the xerces's source code and - echo %FILE_N% extract the content in - echo %FILE_N% "%XERCESC_SRC_DIR%" - echo %FILE_N% And re-run the setup script. - goto bad_exit - -:error_extracting - echo. - echo %FILE_N% [EXTRACTING ERROR] An error ocurred while extracting the zip. - echo %FILE_N% [EXTRACTING ERROR] Workaround: - echo %FILE_N% - Download the xerces's source code and - echo %FILE_N% extract the content manually in - echo %FILE_N% "%XERCESC_SRC_DIR%" - echo %FILE_N% And re-run the setup script. - goto bad_exit - -:error_compiling - echo. - echo %FILE_N% [COMPILING ERROR] An error ocurred while compiling with cl.exe. - echo %FILE_N% Possible causes: - echo %FILE_N% - Make sure you have Visual Studio installed. - echo %FILE_N% - Make sure you have the "x64 Visual C++ Toolset" in your path. - echo %FILE_N% For example, using the "Visual Studio x64 Native Tools Command Prompt", - echo %FILE_N% or the "vcvarsall.bat". - goto bad_exit - -:error_generating_lib - echo. - echo %FILE_N% [NMAKE ERROR] An error ocurred while compiling and installing using nmake. - goto bad_exit - -:good_exit - echo %FILE_N% Exiting... - rem A return value used for checking for errors - endlocal & set install_xerces=%XERCESC_INSTALL_DIR% - exit /b 0 - -:bad_exit - if exist "%XERCESC_INSTALL_DIR%" rd /s /q "%XERCESC_INSTALL_DIR%" - echo %FILE_N% Exiting with error... - endlocal - exit /b %errorlevel% +REM @echo off +setlocal + +rem BAT script that downloads and installs a ready to use +rem x64 xerces-c build for CARLA (carla.org). +rem Run it through a cmd with the x64 Visual C++ Toolset enabled. + +set LOCAL_PATH=%~dp0 +set FILE_N= -[%~n0]: + +rem Print batch params (debug purpose) +echo %FILE_N% [Batch params]: %* + +rem ============================================================================ +rem -- Parse arguments --------------------------------------------------------- +rem ============================================================================ + +:arg-parse +if not "%1"=="" ( + if "%1"=="--build-dir" ( + set BUILD_DIR=%~dpn2 + shift + ) + if "%1"=="-h" ( + goto help + ) + if "%1"=="--help" ( + goto help + ) + shift + goto :arg-parse +) + +rem If not set set the build dir to the current dir +if "%BUILD_DIR%" == "" set BUILD_DIR=%~dp0 +if not "%BUILD_DIR:~-1%"=="\" set BUILD_DIR=%BUILD_DIR%\ + +rem ============================================================================ +rem -- Local Variables --------------------------------------------------------- +rem ============================================================================ + +set XERCESC_BASENAME=xerces-c +set XERCESC_VERSION=3.2.3 + +rem xerces-c-x.x.x +set XERCESC_TEMP_FOLDER=%XERCESC_BASENAME%-%XERCESC_VERSION% +rem ../xerces-c-x.x.x +set XERCESC_TEMP_FOLDER_DIR=%BUILD_DIR%%XERCESC_TEMP_FOLDER% +rem xerces-c-x.x.x-src.zip +set XERCESC_TEMP_FILE=%XERCESC_TEMP_FOLDER%-src.zip +rem ../xerces-c-x.x.x-src.zip +set XERCESC_TEMP_FILE_DIR=%BUILD_DIR%%XERCESC_TEMP_FILE% + +set XERCESC_REPO=https://archive.apache.org/dist/xerces/c/3/sources/xerces-c-%XERCESC_VERSION%.zip + +rem ../xerces-c-x.x.x-source/ +set XERCESC_SRC_DIR=%BUILD_DIR%%XERCESC_BASENAME%-%XERCESC_VERSION%-source\ +rem ../xerces-c-x.x.x-install/ +set XERCESC_INSTALL_DIR=%BUILD_DIR%%XERCESC_BASENAME%-%XERCESC_VERSION%-install\ + +rem ============================================================================ +rem -- Get xerces -------------------------------------------------------------- +rem ============================================================================ + +if exist "%XERCESC_INSTALL_DIR%" ( + goto already_build +) + +if not exist "%XERCESC_SRC_DIR%" ( + if not exist "%XERCESC_TEMP_FILE_DIR%" ( + echo %FILE_N% Retrieving %XERCESC_BASENAME%. + powershell -Command "(New-Object System.Net.WebClient).DownloadFile('%XERCESC_REPO%', '%XERCESC_TEMP_FILE_DIR%')" + ) + if not exist "%XERCESC_TEMP_FILE_DIR%" ( + echo %FILE_N% Using %XERCESC_BASENAME% from backup. + goto error_download + powershell -Command "(New-Object System.Net.WebClient).DownloadFile('https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/xerces-c-%XERCESC_VERSION%-src.zip', '%XERCESC_TEMP_FILE_DIR%')" + ) + if %errorlevel% neq 0 goto error_download + rem Extract the downloaded library + echo %FILE_N% Extracting xerces from "%XERCESC_TEMP_FILE%". + powershell -Command "Expand-Archive '%XERCESC_TEMP_FILE_DIR%' -DestinationPath '%BUILD_DIR%'" + if %errorlevel% neq 0 goto error_extracting + + rem Remove unnecessary files and folders + echo %FILE_N% Removing "%XERCESC_TEMP_FILE%" + del "%XERCESC_TEMP_FILE_DIR%" + echo %FILE_N% Removing dir "%BUILD_DIR%manifest" + rmdir /s/q "%BUILD_DIR%manifest" + + echo %FILE_N% Renaming dir %XERCESC_TEMP_FOLDER_DIR% to %XERCESC_BASENAME%-%XERCESC_VERSION%-source + rename "%XERCESC_TEMP_FOLDER_DIR%" "%XERCESC_BASENAME%-%XERCESC_VERSION%-source" +) else ( + echo %FILE_N% Not downloading xerces because already exists the folder "%XERCESC_SRC_DIR%". +) + +rem ============================================================================ +rem -- Compile xerces ---------------------------------------------------------- +rem ============================================================================ + +if not exist "%XERCESC_SRC_DIR%build" ( + echo %FILE_N% Creating "%XERCESC_SRC_DIR%build" + mkdir "%XERCESC_SRC_DIR%build" +) + +cd "%XERCESC_SRC_DIR%build" + +if not exist "%XERCESC_INSTALL_DIR%lib" ( + echo %FILE_N% Creating "%XERCESC_INSTALL_DIR%lib" + mkdir "%XERCESC_INSTALL_DIR%lib" +) + +if not exist "%XERCESC_INSTALL_DIR%include" ( + echo %FILE_N% Creating "%XERCESC_INSTALL_DIR%include" + mkdir "%XERCESC_INSTALL_DIR%include" +) + +cmake .. -G "Visual Studio 16 2019" -A x64^ + -DCMAKE_INSTALL_PREFIX="%XERCESC_INSTALL_DIR:\=/%"^ + -DBUILD_SHARED_LIBS=OFF^ + -Dtranscoder=windows^ + "%BUILD_DIR%%XERCESC_BASENAME%-%XERCESC_VERSION%-source" +if %errorlevel% neq 0 goto error_cmake + +cmake --build . --config Release --target install + +goto success + +rem ============================================================================ +rem -- Messages and Errors ----------------------------------------------------- +rem ============================================================================ + +:help + echo %FILE_N% Download and install a xerces. + echo "Usage: %FILE_N% [-h^|--help] [--build-dir] [--zlib-install-dir]" + goto eof + +:success + echo. + echo %FILE_N% xerces has been successfully installed in "%XERCESC_INSTALL_DIR%"! + goto good_exit + +:already_build + echo %FILE_N% A xerces installation already exists. + echo %FILE_N% Delete "%XERCESC_INSTALL_DIR%" if you want to force a rebuild. + goto good_exit + +:error_download + echo. + echo %FILE_N% [DOWNLOAD ERROR] An error ocurred while downloading xerces. + echo %FILE_N% [DOWNLOAD ERROR] Possible causes: + echo %FILE_N% - Make sure that the following url is valid: + echo %FILE_N% "%XERCESC_REPO%" + echo %FILE_N% [DOWNLOAD ERROR] Workaround: + echo %FILE_N% - Download the xerces's source code and + echo %FILE_N% extract the content in + echo %FILE_N% "%XERCESC_SRC_DIR%" + echo %FILE_N% And re-run the setup script. + goto bad_exit + +:error_extracting + echo. + echo %FILE_N% [EXTRACTING ERROR] An error ocurred while extracting the zip. + echo %FILE_N% [EXTRACTING ERROR] Workaround: + echo %FILE_N% - Download the xerces's source code and + echo %FILE_N% extract the content manually in + echo %FILE_N% "%XERCESC_SRC_DIR%" + echo %FILE_N% And re-run the setup script. + goto bad_exit + +:error_compiling + echo. + echo %FILE_N% [COMPILING ERROR] An error ocurred while compiling with cl.exe. + echo %FILE_N% Possible causes: + echo %FILE_N% - Make sure you have Visual Studio installed. + echo %FILE_N% - Make sure you have the "x64 Visual C++ Toolset" in your path. + echo %FILE_N% For example, using the "Visual Studio x64 Native Tools Command Prompt", + echo %FILE_N% or the "vcvarsall.bat". + goto bad_exit + +:error_generating_lib + echo. + echo %FILE_N% [NMAKE ERROR] An error ocurred while compiling and installing using nmake. + goto bad_exit + +:good_exit + echo %FILE_N% Exiting... + rem A return value used for checking for errors + endlocal & set install_xerces=%XERCESC_INSTALL_DIR% + exit /b 0 + +:bad_exit + if exist "%XERCESC_INSTALL_DIR%" rd /s /q "%XERCESC_INSTALL_DIR%" + echo %FILE_N% Exiting with error... + endlocal + exit /b %errorlevel% diff --git a/Util/InstallersWin/install_zlib.bat b/Util/InstallersWin/install_zlib.bat index 1e4adbc..4b7c6de 100644 --- a/Util/InstallersWin/install_zlib.bat +++ b/Util/InstallersWin/install_zlib.bat @@ -1,178 +1,178 @@ -@echo off -setlocal - -rem BAT script that downloads and installs a ready to use -rem x64 zlib build for CARLA (carla.org). -rem Run it through a cmd with the x64 Visual C++ Toolset enabled. - -set MAKEFLAGS= -set LOCAL_PATH=%~dp0 -set FILE_N= -[%~n0]: - -rem Print batch params (debug purpose) -echo %FILE_N% [Batch params]: %* - -rem ============================================================================ -rem -- Parse arguments --------------------------------------------------------- -rem ============================================================================ - -:arg-parse -if not "%1"=="" ( - if "%1"=="--build-dir" ( - set BUILD_DIR=%~dpn2 - shift - ) - if "%1"=="--toolset" ( - set TOOLSET=%~2 - shift - ) - if "%1"=="-h" ( - goto help - ) - if "%1"=="--help" ( - goto help - ) - shift - goto :arg-parse -) - -rem If not set set the build dir to the current dir -if "%BUILD_DIR%" == "" set BUILD_DIR=%~dp0 -if not "%BUILD_DIR:~-1%"=="\" set BUILD_DIR=%BUILD_DIR%\ - -rem If not defined, use Visual Studio 2019 as tool set -if "%TOOLSET%" == "" set TOOLSET="" - -rem ============================================================================ -rem -- Local Variables --------------------------------------------------------- -rem ============================================================================ - -set ZLIB_BASENAME=zlib -set ZLIB_VERSION=1.2.11 - -set ZLIB_TEMP_FOLDER=%ZLIB_BASENAME%-%ZLIB_VERSION% -set ZLIB_TEMP_FILE=%ZLIB_TEMP_FOLDER%.zip -set ZLIB_TEMP_FILE_DIR=%BUILD_DIR%%ZLIB_TEMP_FILE% - -set ZLIB_REPO=https://github.com/madler/zlib/archive/refs/tags/v%ZLIB_VERSION%.zip - -set ZLIB_SRC_DIR=%BUILD_DIR%%ZLIB_BASENAME%-source\ -set ZLIB_INSTALL_DIR=%BUILD_DIR%%ZLIB_BASENAME%-install\ - -rem ============================================================================ -rem -- Get zlib --------------------------------------------------------------- -rem ============================================================================ - -if exist "%ZLIB_INSTALL_DIR%" ( - goto already_build -) - -if not exist "%ZLIB_SRC_DIR%" ( - if not exist "%ZLIB_TEMP_FILE_DIR%" ( - echo %FILE_N% Retrieving %ZLIB_BASENAME%. - powershell -Command "(New-Object System.Net.WebClient).DownloadFile('%ZLIB_REPO%', '%ZLIB_TEMP_FILE_DIR%')" - if %errorlevel% neq 0 goto error_download - ) - rem Extract the downloaded library - echo %FILE_N% Extracting zlib from "%ZLIB_TEMP_FILE%". - powershell -Command "Expand-Archive '%ZLIB_TEMP_FILE_DIR%' -DestinationPath '%BUILD_DIR%'" - if %errorlevel% neq 0 goto error_extracting - - rem Remove the no longer needed downloaded file - echo %FILE_N% Removing "%ZLIB_TEMP_FILE%" - del "%ZLIB_TEMP_FILE_DIR%" - rename "%BUILD_DIR%%ZLIB_TEMP_FOLDER%" "%ZLIB_BASENAME%-source" -) else ( - echo %FILE_N% Not downloading zlib because already exists the folder "%ZLIB_SRC_DIR%". -) - -if not exist "%ZLIB_SRC_DIR%build" ( - echo %FILE_N% Creating "%ZLIB_SRC_DIR%build" - mkdir "%ZLIB_SRC_DIR%build" -) - -cd "%ZLIB_SRC_DIR%build" - -rem -DCMAKE_BUILD_TYPE=Release^ -rem -DCMAKE_CONFIGURATION_TYPES=Release^ -cmake -G "NMake Makefiles"^ - -DCMAKE_INSTALL_PREFIX="%ZLIB_INSTALL_DIR:\=/%"^ - -DCMAKE_BUILD_TYPE=Release^ - "%ZLIB_SRC_DIR%" -if %errorlevel% neq 0 goto error_cmake - -rem https://stackoverflow.com/questions/601970/how-do-i-utilise-all-the-cores-for-nmake -set CL=/MP - -nmake install -if %errorlevel% neq 0 goto error_install - -goto success - -rem ============================================================================ -rem -- Messages and Errors ----------------------------------------------------- -rem ============================================================================ - -:help - echo %FILE_N% Download and install a zlib. - echo "Usage: %FILE_N% [-h^|--help] [--toolset] [--build-dir]" - goto eof - -:success - echo. - echo %FILE_N% zlib has been successfully installed in "%ZLIB_INSTALL_DIR%"! - goto good_exit - -:already_build - echo %FILE_N% A zlib installation already exists. - echo %FILE_N% Delete "%ZLIB_INSTALL_DIR%" if you want to force a rebuild. - goto good_exit - -:error_download - echo. - echo %FILE_N% [DOWNLOAD ERROR] An error ocurred while downloading zlib. - echo %FILE_N% [DOWNLOAD ERROR] Possible causes: - echo %FILE_N% - Make sure that the following url is valid: - echo %FILE_N% "%ZLIB_REPO%" - echo %FILE_N% [DOWNLOAD ERROR] Workaround: - echo %FILE_N% - Download the zlib's source code and - echo %FILE_N% extract the content in - echo %FILE_N% "%ZLIB_SRC_DIR%" - echo %FILE_N% And re-run the setup script. - goto bad_exit - -:error_extracting - echo. - echo %FILE_N% [EXTRACTING ERROR] An error ocurred while extracting the zip. - echo %FILE_N% [EXTRACTING ERROR] Workaround: - echo %FILE_N% - Download the libpng's source code and - echo %FILE_N% extract the content manually in - echo %FILE_N% "%ZLIB_SRC_DIR%" - echo %FILE_N% And re-run the setup script. - goto bad_exit - -:error_cmake - echo. - echo %FILE_N% [CMAKE ERROR] An error ocurred while executing cmake command. - echo %FILE_N% [CMAKE ERROR] Possible causes: - echo %FILE_N% - Make sure "CMake" is installed. - echo %FILE_N% - Make sure it is available on your Windows "path". - echo %FILE_N% - Make sure you have cmake 3.12.4 or higher installed. - goto bad_exit - -:error_install - echo. - echo %FILE_N% [NMAKE ERROR] An error ocurred while compiling and installing using nmake. - goto bad_exit - -:good_exit - echo %FILE_N% Exiting... - rem A return value used for checking for errors - endlocal & set install_zlib=%ZLIB_INSTALL_DIR% - exit /b 0 - -:bad_exit - if exist "%ZLIB_INSTALL_DIR%" rd /s /q "%ZLIB_INSTALL_DIR%" - echo %FILE_N% Exiting with error... - endlocal - exit /b %errorlevel% +@echo off +setlocal + +rem BAT script that downloads and installs a ready to use +rem x64 zlib build for CARLA (carla.org). +rem Run it through a cmd with the x64 Visual C++ Toolset enabled. + +set MAKEFLAGS= +set LOCAL_PATH=%~dp0 +set FILE_N= -[%~n0]: + +rem Print batch params (debug purpose) +echo %FILE_N% [Batch params]: %* + +rem ============================================================================ +rem -- Parse arguments --------------------------------------------------------- +rem ============================================================================ + +:arg-parse +if not "%1"=="" ( + if "%1"=="--build-dir" ( + set BUILD_DIR=%~dpn2 + shift + ) + if "%1"=="--toolset" ( + set TOOLSET=%~2 + shift + ) + if "%1"=="-h" ( + goto help + ) + if "%1"=="--help" ( + goto help + ) + shift + goto :arg-parse +) + +rem If not set set the build dir to the current dir +if "%BUILD_DIR%" == "" set BUILD_DIR=%~dp0 +if not "%BUILD_DIR:~-1%"=="\" set BUILD_DIR=%BUILD_DIR%\ + +rem If not defined, use Visual Studio 2019 as tool set +if "%TOOLSET%" == "" set TOOLSET="" + +rem ============================================================================ +rem -- Local Variables --------------------------------------------------------- +rem ============================================================================ + +set ZLIB_BASENAME=zlib +set ZLIB_VERSION=1.2.11 + +set ZLIB_TEMP_FOLDER=%ZLIB_BASENAME%-%ZLIB_VERSION% +set ZLIB_TEMP_FILE=%ZLIB_TEMP_FOLDER%.zip +set ZLIB_TEMP_FILE_DIR=%BUILD_DIR%%ZLIB_TEMP_FILE% + +set ZLIB_REPO=https://github.com/madler/zlib/archive/refs/tags/v%ZLIB_VERSION%.zip + +set ZLIB_SRC_DIR=%BUILD_DIR%%ZLIB_BASENAME%-source\ +set ZLIB_INSTALL_DIR=%BUILD_DIR%%ZLIB_BASENAME%-install\ + +rem ============================================================================ +rem -- Get zlib --------------------------------------------------------------- +rem ============================================================================ + +if exist "%ZLIB_INSTALL_DIR%" ( + goto already_build +) + +if not exist "%ZLIB_SRC_DIR%" ( + if not exist "%ZLIB_TEMP_FILE_DIR%" ( + echo %FILE_N% Retrieving %ZLIB_BASENAME%. + powershell -Command "(New-Object System.Net.WebClient).DownloadFile('%ZLIB_REPO%', '%ZLIB_TEMP_FILE_DIR%')" + if %errorlevel% neq 0 goto error_download + ) + rem Extract the downloaded library + echo %FILE_N% Extracting zlib from "%ZLIB_TEMP_FILE%". + powershell -Command "Expand-Archive '%ZLIB_TEMP_FILE_DIR%' -DestinationPath '%BUILD_DIR%'" + if %errorlevel% neq 0 goto error_extracting + + rem Remove the no longer needed downloaded file + echo %FILE_N% Removing "%ZLIB_TEMP_FILE%" + del "%ZLIB_TEMP_FILE_DIR%" + rename "%BUILD_DIR%%ZLIB_TEMP_FOLDER%" "%ZLIB_BASENAME%-source" +) else ( + echo %FILE_N% Not downloading zlib because already exists the folder "%ZLIB_SRC_DIR%". +) + +if not exist "%ZLIB_SRC_DIR%build" ( + echo %FILE_N% Creating "%ZLIB_SRC_DIR%build" + mkdir "%ZLIB_SRC_DIR%build" +) + +cd "%ZLIB_SRC_DIR%build" + +rem -DCMAKE_BUILD_TYPE=Release^ +rem -DCMAKE_CONFIGURATION_TYPES=Release^ +cmake -G "NMake Makefiles"^ + -DCMAKE_INSTALL_PREFIX="%ZLIB_INSTALL_DIR:\=/%"^ + -DCMAKE_BUILD_TYPE=Release^ + "%ZLIB_SRC_DIR%" +if %errorlevel% neq 0 goto error_cmake + +rem https://stackoverflow.com/questions/601970/how-do-i-utilise-all-the-cores-for-nmake +set CL=/MP + +nmake install +if %errorlevel% neq 0 goto error_install + +goto success + +rem ============================================================================ +rem -- Messages and Errors ----------------------------------------------------- +rem ============================================================================ + +:help + echo %FILE_N% Download and install a zlib. + echo "Usage: %FILE_N% [-h^|--help] [--toolset] [--build-dir]" + goto eof + +:success + echo. + echo %FILE_N% zlib has been successfully installed in "%ZLIB_INSTALL_DIR%"! + goto good_exit + +:already_build + echo %FILE_N% A zlib installation already exists. + echo %FILE_N% Delete "%ZLIB_INSTALL_DIR%" if you want to force a rebuild. + goto good_exit + +:error_download + echo. + echo %FILE_N% [DOWNLOAD ERROR] An error ocurred while downloading zlib. + echo %FILE_N% [DOWNLOAD ERROR] Possible causes: + echo %FILE_N% - Make sure that the following url is valid: + echo %FILE_N% "%ZLIB_REPO%" + echo %FILE_N% [DOWNLOAD ERROR] Workaround: + echo %FILE_N% - Download the zlib's source code and + echo %FILE_N% extract the content in + echo %FILE_N% "%ZLIB_SRC_DIR%" + echo %FILE_N% And re-run the setup script. + goto bad_exit + +:error_extracting + echo. + echo %FILE_N% [EXTRACTING ERROR] An error ocurred while extracting the zip. + echo %FILE_N% [EXTRACTING ERROR] Workaround: + echo %FILE_N% - Download the libpng's source code and + echo %FILE_N% extract the content manually in + echo %FILE_N% "%ZLIB_SRC_DIR%" + echo %FILE_N% And re-run the setup script. + goto bad_exit + +:error_cmake + echo. + echo %FILE_N% [CMAKE ERROR] An error ocurred while executing cmake command. + echo %FILE_N% [CMAKE ERROR] Possible causes: + echo %FILE_N% - Make sure "CMake" is installed. + echo %FILE_N% - Make sure it is available on your Windows "path". + echo %FILE_N% - Make sure you have cmake 3.12.4 or higher installed. + goto bad_exit + +:error_install + echo. + echo %FILE_N% [NMAKE ERROR] An error ocurred while compiling and installing using nmake. + goto bad_exit + +:good_exit + echo %FILE_N% Exiting... + rem A return value used for checking for errors + endlocal & set install_zlib=%ZLIB_INSTALL_DIR% + exit /b 0 + +:bad_exit + if exist "%ZLIB_INSTALL_DIR%" rd /s /q "%ZLIB_INSTALL_DIR%" + echo %FILE_N% Exiting with error... + endlocal + exit /b %errorlevel%